From 0715615b684e1a8b98a560ff2cd9ef03a1232783 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 14 Jan 2025 14:57:42 +0900 Subject: [PATCH] feat(lane_change): using frenet planner to generate lane change path when ego near terminal (#9767) * frenet planner Signed-off-by: Zulfaqar Azmi * minor refactoring Signed-off-by: Zulfaqar Azmi * adding parameter Signed-off-by: Zulfaqar Azmi * Add diff th param Signed-off-by: Zulfaqar Azmi * limit curvature for prepare segment Signed-off-by: Zulfaqar Azmi * minor refactoring Signed-off-by: Zulfaqar Azmi * print average curvature Signed-off-by: Zulfaqar Azmi * refactor Signed-off-by: Zulfaqar Azmi * filter the path directly Signed-off-by: Zulfaqar Azmi * fix some conflicts Signed-off-by: Zulfaqar Azmi * include curvature smoothing Signed-off-by: Zulfaqar Azmi * document Signed-off-by: Zulfaqar Azmi * fix image folder Signed-off-by: Zulfaqar Azmi * image size Signed-off-by: Zulfaqar Azmi * doxygen Signed-off-by: Zulfaqar Azmi * add debug for state Signed-off-by: Zulfaqar Azmi * use sign function instead Signed-off-by: Zulfaqar Azmi * rename argument Signed-off-by: Zulfaqar Azmi * readme Signed-off-by: Zulfaqar Azmi * fix failed test due to empty value Signed-off-by: Zulfaqar Azmi * add additional note Signed-off-by: Zulfaqar Azmi * fix conflict Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi --- .../README.md | 58 +++ .../config/lane_change.param.yaml | 7 + .../images/terminal_branched_frenet.png | Bin 0 -> 53664 bytes .../images/terminal_branched_path_shifter.png | Bin 0 -> 59599 bytes .../images/terminal_curved_frenet.png | Bin 0 -> 76194 bytes .../images/terminal_curved_path_shifter.png | Bin 0 -> 71940 bytes .../images/terminal_straight_frenet.png | Bin 0 -> 29125 bytes .../images/terminal_straight_path_shifter.png | Bin 0 -> 24433 bytes .../scene.hpp | 12 + .../structs/data.hpp | 1 + .../structs/debug.hpp | 15 + .../structs/parameters.hpp | 9 + .../structs/path.hpp | 37 +- .../utils/path.hpp | 62 ++- .../utils/utils.hpp | 46 +- .../package.xml | 1 + .../src/manager.cpp | 18 + .../src/scene.cpp | 100 +++- .../src/utils/markers.cpp | 119 +++-- .../src/utils/path.cpp | 471 +++++++++++++++++- .../src/utils/utils.cpp | 80 ++- .../src/frenet_planner/frenet_planner.cpp | 9 + 22 files changed, 991 insertions(+), 54 deletions(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_branched_frenet.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_branched_path_shifter.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_curved_frenet.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_curved_path_shifter.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_straight_frenet.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_straight_path_shifter.png diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md index b4f848e0809aa..ee371f8592833 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md @@ -787,6 +787,51 @@ Depending on the space configuration around the Ego vehicle, it is possible that Additionally if terminal path feature is enabled and path is computed, stop point placement can be configured to be at the edge of the current lane instead of at the `terminal_start` position, as indicated by the dashed red line in the image above. +## Generating Path Using Frenet Planner + +!!! warning + + Generating path using Frenet planner applies only when ego is near terminal start + +If the ego vehicle is far from the terminal, the lane change module defaults to using the [path shifter](https://autowarefoundation.github.io/autoware.universe/main/planning/behavior_path_planner/autoware_behavior_path_planner_common/docs/behavior_path_planner_path_generation_design/). This ensures that the lane change is completed while the target lane remains a neighbor of the current lane. However, this approach may result in high curvature paths near the terminal, potentially causing long vehicles to deviate from the lane. + +To address this, the lane change module provides an option to choose between the path shifter and the [Frenet planner](https://autowarefoundation.github.io/autoware.universe/main/planning/sampling_based_planner/autoware_frenet_planner/). The Frenet planner allows for some flexibility in the lane change endpoint, extending the lane changing end point slightly beyond the current lane's neighbors. + +The following table provides comparisons between the planners + +
+ + + + + + + + + + + + + + + + + +
With Path ShifterWith Frenet Planner
Path shifter result at straight laneletsFrenet planner result at straight lanelets
Path shifter result at branching laneletsFrenet planner result at branching lanelets
Path shifter result at curved laneletsFrenet planner result at curved lanelets
+
+ +!!! note + + The planner can be enabled or disabled using the `frenet.enable` flag. + +!!! note + + Since only a segment of the target lane is used as input to generate the lane change path, the end pose of the lane change segment may not smoothly connect to the target lane centerline. To address this, increase the value of `frenet.th_curvature_smoothing` to improve the smoothness. + +!!! note + + The yaw difference threshold (`frenet.th_yaw_diff`) limits the maximum curvature difference between the end of the prepare segment and the lane change segment. This threshold might prevent the generation of a lane change path when the lane curvature is high. In such cases, you can increase the frenet.th_yaw_diff value. However, note that if the prepare path was initially shifted by other modules, the resultant steering may not be continuous. + ## Aborting a Previously Approved Lane Change Once the lane change path is approved, there are several situations where we may need to abort the maneuver. The abort process is triggered when any of the following conditions is met @@ -1008,6 +1053,7 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi | `trajectory.max_longitudinal_acc` | [m/s2] | double | maximum longitudinal acceleration for lane change | 1.0 | | `trajectory.min_longitudinal_acc` | [m/s2] | double | maximum longitudinal deceleration for lane change | -1.0 | | `trajectory.lane_changing_decel_factor` | [-] | double | longitudinal deceleration factor during lane changing phase | 0.5 | +| `trajectory.th_prepare_curvature` | [-] | double | If the maximum curvature of the prepare segment exceeds the threshold, the prepare segment is invalid. | 0.03 | | `min_length_for_turn_signal_activation` | [m] | double | Turn signal will be activated if the ego vehicle approaches to this length from minimum lane change length | 10.0 | | `lateral_acceleration.velocity` | [m/s] | double | Reference velocity for lateral acceleration calculation (look up table) | [0.0, 4.0, 10.0] | | `lateral_acceleration.min_values` | [m/s2] | double | Min lateral acceleration values corresponding to velocity (look up table) | [0.4, 0.4, 0.4] | @@ -1057,6 +1103,18 @@ The following parameters are used to configure terminal lane change path feature | `terminal_path.disable_near_goal` | [-] | bool | Flag to disable terminal path feature if ego is near goal | true | | `terminal_path.stop_at_boundary` | [-] | bool | If true, ego will stop at current lane boundary instead of middle of lane | false | +### Generating Lane Changing Path using Frenet Planner + +!!! warning + + Only applicable when ego is near terminal start + +| Name | Unit | Type | Description | Default value | +| :------------------------------ | ----- | ------ | --------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | +| `frenet.enable` | [-] | bool | Flag to enable/disable frenet planner when ego is near terminal start. | true | +| `frenet.th_yaw_diff` | [deg] | double | If the yaw diff between of the prepare segment's end and lane changing segment's start exceed the threshold , the lane changing segment is invalid. | 10.0 | +| `frenet.th_curvature_smoothing` | [-] | double | Filters and appends target path points with curvature below the threshold to candidate path. | 0.1 | + ### Collision checks #### Target Objects diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml index 91b296f8bd40f..df9491576a4ee 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml @@ -29,6 +29,7 @@ lon_acc_sampling_num: 5 lat_acc_sampling_num: 3 lane_changing_decel_factor: 0.5 + th_prepare_curvature: 0.03 # [/] # delay lane change delay_lane_change: @@ -37,6 +38,12 @@ min_road_shoulder_width: 0.5 # [m] th_parked_vehicle_shift_ratio: 0.6 + # trajectory generation near terminal using frenet planner + frenet: + enable: true + th_yaw_diff: 10.0 # [deg] + th_curvature_smoothing: 0.1 # [/] + # safety check safety_check: allow_loose_check_for_cancel: true diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_branched_frenet.png b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_branched_frenet.png new file mode 100644 index 0000000000000000000000000000000000000000..51f3a2fc46500039d3a136d93a7918b2de82cc36 GIT binary patch literal 53664 zcmeFYWl&r}6E?c|;)}bx1WB;q4uRnA5JGSZ5`w#H@DLn=Yj9_=0158yE=ve*_mKB} z?^kvI-n#$psjXT$J2O2!Jx@Q~(A86b%FdVZM=8HkPtN-)l>hsiD=|h> z_5`xp^H3@&S$XwM+m-ib@B*GduIl0G8!B8+Nph09nY{g7pLIzU&<%2tX zlL1g<`0a29fnjEwv)k>5+5HH|hJ1qyKaYX6*yo8~!+sE5;1;dm;82W|WaZ7Bt}jy~ zeiA2NIYXd%UYktKZ=Q0}Q%}lnU2f_WmQEzPKV)p~z~R#1T3YMjnUG7E})iF?32 zFD(p?x@C&UIz_4T%zONtBA!(lzQ_Dex3qa0r(DORdt2rqR5)r+=3O#IH9CokzyzP? zs4vWvKlyA9z^oAzq@^E<6A7w-_QihxYaHi8Yt8u$ssPAB?DSu&!5J5S?#E2en?=p* z8j~3Z=YmW*n<+2RfA_tni~e2B8NdIt2+F*^H+vP;f+D{cWwY>b zkwzq^&+~i)lcB0to?xa0iSH~FgJ+B7rq-zp4DcpLtw#LN*dF4koiS-?-XXNb1?AG6 z(ien(5a7OhPy7*IR^&~q1Qvhs@HI3um`EF>J597U!hwNs=|n@2gv z`D>od?)3pzaKQ8C!AyB5(z#G3C#1&}x0pSWo@zWKTCNm?S624m0jFq3dKrtoKFHCv zs~Vj)W+zbTrXr&ZIYohaQxz&8g}igj63gm?jMtpsgXfL0^AH4U54$IQY4D_;6`dD! zu$xn=A=FdW8$09odp32*U|qfOd--&ug_E>gud|&%Y>XXa%piA8HA$G=XsS+}J%%ts ze&t6Bq*2Q&CBgK(pOR}7KCj+AceZA##j`Bt?xpp*LfY~1U}kmHSPXXDe)fuj>aLoV zF41Utb-VTS-QL|3z5&gQ1I>!|PhR*|O02)Nq@jCUwdt-8qxx<{PIUo9fH{HYT^&u=|@-MN*5kBF^iX(7Y4P*EA93bRkrNxPH#Tb(jLSZhf(|ZS?V$-J<`k1} zW{9!=mXd}R8`w-6iQj(}Ed^cmA{oAE{4~tfxN$k?L4N1)mEUrbCeP{VX0x7%{~}c$ zSy!CgDJI=P^n8OMUVtpSHt2Hxw(!Qo8`-gak-r)uDS!FyKJ$GJU}7EQ^o^@%Vd*o zyo0gjE@1R_+6FCx4UPcoZtY5@k zDpC^6k5{I+ml7AvmVgAqf6}qix*=+juz1sYpYf}*CSA0;8Zt07|w)t%}9ExxD2G#aukH%i)RikU* z6xO1|60PlD&M2rD707Y*Fa7*0up1*ca>8m|Ybo4{r+@zOxlDY`(n2BbTB^;l=-6WP zI2W;QSXr^3-hL}L7&XMj_&DIESC#t*winBrqzJ9WBC4h;a)+;cD77qzRxPc2e3;`* zG7AB_865LwDl?F{tF2ml`%r4R5fSy}D!aatH?`vRAeCaXJyW~i-BdYDEoppm+KuVB zz>f7cT;vU{1tD-Q>=)m%&yrgL@|05C3rI!yf=MqYsw^_+U2zl5^IMHi1^9+F?v|W5 zW@p?VU`p$1=si|B@Ejl~qku9U>{l-g;GBpVRaalfas?D?v=^Vy+UOjP+ELCJ-|&;@ zV}{2{mcf0*_lXT}C?i<>OFL!r9?oD@nroiIn_WfZ^YynZVGO+DZ0@%?zOyk`V_aJp z$OoZ2L-qsCYXVrc=@^XJZ81zH_ZGrbUysJ;l&g+45WFb#Be0*~1$K}cY^Gm{KM^{P ztsSPSmZ@p5K&^{OU)w)-%C!9&6To1M5u2|P5X!+kQec!-?)XCAnQKZ?L>jb=z6RqA znmfnw4#7jb1EU8)LPwvVZtc_y1FPvcVw-X2y{q$4qtO{%-j9D^um6vr^=R*JZVQaj z0-OBITDu7|?P5eK^3FLyj!%>J2CkOQ8L}(WRR|!d3M{TVLE%t+S90Wiw;A`>lIGK3 zl{}TuM0HeYgO;0bp}TDk*l}3l(?(Nq#LTKy)2#I%7_SGE7g@Wjo3y5AHfxg^{)K<; zjPd26B@)nAxda+nvEOkcOpo8#(!_h)U9K@BOH{WCIzC<@x=r!BalI6S37aiInNqZf zNfFoz9<*{IP}L~Uip5;*E|y3Um$b3cR2vO!xNj}0QMuD*>3ofNtq#MgQ45&BD~z#! z;8Q!tM8%yZ*7mvmacgSJglg!t5fgS(T{930nx`_aS3T zHI{nQXmB=`{_bE&9GS!QFLLvnd*56FgtEs^6Ou1N{iLZAT+r;lGuG4+)a-p%pq zDlcT%RekR0JoVn~c~{J<+qRzy0+AVqf7E<|LMb#SdVA9=Lb{Fmp3UshU*!)+zwaec z*N-cq4xi(T#*h2xb3bEUE#A6%?lYn3Ucd?x54g ze!~mY535f-4OhLe@XH?!9UX^mF{A6Uxz)Q373`JlpLo89sq6~27`4Xotd*{#UYV|+ z^Xhtwf&5QIEZ-ectsHA$Vde3Om~n0wgW2YUl21Q~e@s&~W0Nn|B5+-4n#u4*WlQY< zfiMX6<~~ny=DzeqF1)8V@teYH_r=C2@2#Oqyj85q=xrp^uO~2do$GC0C9f;_OYMAg zJ$#&-n@ce(L#I>b=Y_}&>O8+9p~MUiLX;dHz6+BW&H8=Xs`NW<_3rcH;>nKKQ=DJp zTSJhwm(W7;j zOkxifGrn0)$(TT`dvN>Zgf4!!t|rut<8;4{bD=y7&!KEVCVU*MABO5mTCef@$EheO zX)>jan8;DH8M_u{6PEFV%NMfDEX{h=fBE z9KNHiAkL04ubE`?xL_1E3o6ZKr)}L>y6qbLX{s0KT`@$LbEe#n`E7Hq`_8MMN{Fa~ z@L(QzIBx#yIQIOaFNe@L*4}G9U`WPmAadOdJh@#I9cu~Qp)j^{415m~y3B%5!Fil{ zVAU_11;zCsquphdW1|-@Hjba*_c8l@zimXyX&Rd$b{9$z#bN585UjW|QkY%|wd6eR zjBz-<_+Or3vKw4!~T`%_2zdf5=tD3Ujbq= zo;sZYT4KGPQ!Dso%JA9BY;MZ4HUh_5Anqwr49k&Ud=G{l4_6S3Q4pvfZVBV^>AMBr zUfWO(U*`I5&nRp;6!!OOX4Tq@%3g`UO5(8k*go!WZ)2uWoHCVZ7zMk;D4sPCDmG*Z zP-GWse>vv;dV=zCU+v*^W1h)=wQ>@9FleVh(*mQ`vHb%5BHs3Q7F2Acv*WPgM(pl< zlaw&?qwV1#Q|)R-y@@K+|2+(2!R0cB51R4dO1Jbnx}hgi`0^A54s=bf`*hDGb@0>9 zqq9VydUEW5`nFO(s2CeYf4k*za$?8ojq7ue)rLJdB{XxOyshM}?fYG)3iwLIq?6Ou z(H>;s0h~aH+eS5w#OC0Y{AZGzq4V3(t1w4On^n00rU`%yR}t$2gkP-;#c*Kdu;@Tj z>(sS}t?J0xVrh%25Ifd_d1_S<{nH5_fg2@b@4oEZgo;G}tiNYheO6lU)yG{gAs`gW z!{R|!TApI9duIxSO#_3seJ1y$c?o6HR8(+>ahGk~?&T}FzEd&#B4O!*uZq`|xyhhw zekD)8AYtJx>&42&C|WPTIdhk+S&5Nm*nl|WwYBr?UGWFK`#V$R%H(`&`$a<(dD@Hb$^qjM-|{>la?5hN%y--5GT6k(|I26bSY2W?As4cum~u%?VWOrV0g?89F05bg z;wXSgNlSveK*%4SV*Ul(d(w&jQZ3^W3`>Y3Bfr*u{lWeZ38BJlT zSo6*CrNk8bEzWNuMEqZwo@L6@03z{mRMYS3%kwI=H!pH0AHF6?^N0Rm%5=f@CTm`= zZ?DiT;d!tNeT`X3G0SNrE1Er!Sfs)&oFoT9gs~bMe%=;<`A|tfOe?D45Z2Bnn?+{D z*;77sD(jRr3Rl(M$^KhJS5_boP(!O9X`4HmTFd5qxvD%i&C$+O>F#xjXoG?PiE)S(WxpN z&yCbjTIgc`iYh7OObj>gPlh8nO1;|iX+-Ws7`E{q@f z)PT0J+58%WY(^}hCp4h^A0rzOM>aGn)83abt<7*iVhQ7Brom7XTX?*ieED{f@auYE zX2uagQnLg(L&Ua1&t-S4k3d5V7lxVMZ^tuV2z9zVb)qtjS!*?W2v_8qF5w?3DR~AB za6a=&6(l~qtbn${EII&0{l1Ma;`9!jUrg#i;*o{ILNKE}tLi?iDk=HeL70MD1M?>$ z2*Hk!KjDp~lluo`m7N{xd(f=o5-7OqK@MB3Qj^*s*nTnH2G;NNoO?y?v#W-myD_T5 z9yLZ0n;&x?viQ+XDLJdVo-sM#&V|e@&BKgq=Hkd?0LsN^tc*icAClb)S#(5`v-4rs zVZ?lEUcrU<7@E3>ttCo1Ap1SaA(UC7#sgV>busX z)JM}^vGEXbp!>c_%b6fWSfC;3qL1LZ0~;jIqyd3|^TFxTxDnFum7BDYv`w)HG}8Be zAaw;qGjJh(QW7{&K=oBWb?R@ZGx^-~_tOS@DcczJ*I7EnNzjcA+KrZB(1I0U zvq@|gNo)ij1lVdXL+(DEu5arY_Zv92MO^tlz7kH)kYY?lGWd!2j3#PA?4ioiQ;Lg0 z1=_-R@ExHRAUVyV8PsNTp`sQ}1D2mQg$dK|g!b+G7#&!V7^FpnZSZAUT9n}R1XR_h zgGv`|SXXo;sVB}X8Z4yd>Yau`3EhV8`|fH=Q{hzWPq(20;(_q*1t~4n7vvWWrVG^- zg1?i-YN6LA6`HmhXduNz4D6R3JlNbXjJiQU%t9<67BEe<_8(9M4J!`&x_L=cg!FtU z1lM!2=k`|6a6p1KU79sHIF{C`B0-^F13M%M0^vd>lGH3~Pm;`4^{>Sb>_+6Glh@{ha@OQ5-!Ew?6Vtzdr5d-pA5!s7;J&9N*u&&=K!A)NOe@M zP6upjQhb2UMwEWZ?Y=si7v?Z&nL0FcT^3hXqZb^Mt=P%Zsa%>rFJ}1hA}69jl02U` zkgGUMBu}u09So13?}7Hs`GszPgZ?-Nny_vL*2~)FZqFC;wMl`sn~gZLkptF&6`T4r zIr(4(mVycEpW4g41UYn=!wosK;;;FH{{vC5e2A?t4k+I3i@XAv@JQrGqG{=;KK+ zf^{`v@*x~Wo(Ea;s7-(Zi~P|FSS;H$V4=nZS=JWJf}<&%l*QTol`ER28;hX1sDZph^L} zpWC7FAwlnJo3D(9s}JIjm_;1~QxVxCm?y&Xz%6;Il}Tp!5Cv)s;XRw_q$(-h6r(4S zIenulwbw9xe)+0UQAzOJ<%~I}g(0%mqAfg{cD?6Y7NoR|tScFs4o<)Lk#^E$F$JRye4O2y)duHlVk;-rH;RoN6GDe#+88$hUqGs4}*3+YbIJJo_iwJZ&I9P2pdOIA(@ubcU0> zf#*=TF~-d52~np#rZ>HZa3MDwipzkK{PE%EU6BQ+Akffp( zcu6yXzCHkzm)(HkP0qCZjJXg<0ud1>sUoL9l6IXo!70}bAH}#ohYx$S^0B0vm!QTu z)cD0;=Y(<{E?(mm4kRRouLiyitzqr44EoX5onym1!i`?XI$*U5#6_=y^l=&wvObT4 z+@x?*2&y=gng=IXEnYBiOwC6D2seWX&!qHy_LLO($QJ{N`bAoyT!Clsh_bXFU;NxB zw`(F66$)9OrWNhHdmRj!V|RGx3fpiWR^j3>LSDUwLLHds+8JrKV!D{FZrIMJN@Lc|=W%UxG zriJ#*v(~JWETSedLvKub3;_HJj)!0I#3|84i^Z$*w_L;u#y6Ophv-;_m<9i|3YPGv z2CFjTL(mY|aQG3h13}4=C_<@$(__Od#TTA7zlQ2U>#lsuxcaHb%-TN=bxpDL`0KCX z#Bq-aWz-@#i(7<{2E-m{Fsm7ebD_cMNX+4;SkO$gte}_qVuVW}>9&>}7ZMUrbDm1B z?VkS8ty^&L8moU;xnYDV=NZ?dfC$>ZJr6B9a}hmM9!d@ON(i}7-DzYiUd+;LdmoSGmcx^=z5}{G{w~O-+Xv>p!Q?Fhlo(fs-gr0xkG0b?dFdAgB!- zdK9`m7`-{60*w{VMqUi+^fId8xC=X|$&+b>N0yMFIuU~O3r!7^w z#P?5v?}&h;fg4nb2eAP+#EUh^=yL7thSgBZ%@UTIN1GDH`-StDWL4Ebt8R(-uT(7W z&VTfJZ|fbP9NrIx7_F}hLSpKj2zEy@rSPr6GypJP2Vk=xu`9wUNG{?+nVA*gIC3=a z59uwuYpWgvnCB_6_e|rua?Mh*N{m%)M=H!VIy7bJqVqhv=#m1!yi3986}-@~pgR2M zXtF#uf~xz}p#oDt@GrRiRsw_48c3eY^GDj@HTMf#)8^UQ2b{MRyL5(tZA=fQ zkFEmk*WZ0YnZMyUwN7oigO?Ssu~@VJER ziW1kz)rh$JJntQ@Y?zZ1UvQ#~@f22X>tbv?8l?nkq7Bt-YW*n)E2^$ia()$17e^&T@rEvIF}TfGPFnoGced>&VcAUhRCfr zXdHaySP|2+CV&Y@_L+0H+FKsbB+#+r*PBqqZO(<$w&ycx$#G9`tS92vTDN5Pu8gkx z=IVc9R6XJKf4Fl!?x%bsg#e@3Fy&^TF7zMzfHTyez^^kJ;hoo4h?eJ`{=$s5OWhfy zUA9ph+$--3CK#3Co(oQb?*DyVsMxCg)&rjFnA7z{^DxVVUA{N z(_{|_{sI$@u@elTj+fVc=^$7| zM{G}>92lJ^08xLL^-hmL>zp+}-JNr3E|uG#>!QT%P9(On?vrNHG-w2fL?=FHD6V4;+|NqLLa1&W&ATMz`iC zpjxfZ9d?$o$$f>Dv`j!fod1{uoK zRYhQQ=&y_kjioIv2x6Z2sS^F^%(#wF=9o8tNS`jLqRa&Y<8Q-*G_6fjM>_r=@qm%o zn!0bsa}RGqh-T5!3=MnE&uEsY7FZ3$A`dDb0xR`98$5HYPrZ#OgHP|6?RsgP_)sb8YxzbWWv zCR$dE9vh_8(A_&Ab`QX+ZmvV-&#qjp)V9`mdJUstYvp%x6#kI!uFdyXgp<-d83DCO zUtHVkTYaoo#Ep$5H6EY4r%i&ny~#yQvI9@{spg9%c>lpZ-uDWWE7>Hr&G!5VRsA`N zU^PeL)l&7UL?>IX>TQ9Mj!ypE=xjv;`K>>%lh88GhN9FESEXUB1m*S)rab%NUIf(n zmrJW^W}VL~C|I6r>bq(W{V_Y9p(5m}e}CPcy;YIqkUtOx*fl~Sedv4KGT##Yn;*QHWvVcm?Z?$Z z;(W5ljvt=I>XlvY-#pW5462yzd8FNJa*G|AOEm~LpM+vD7aKkSaaURsw${aIy$vx7 z1N?9x!F9DgdIDVrYmN;ZP?}+-Uy0F-$*@=f+|;5Y^9iLvr;jKISo*xlXQsM4@@*f; zY$*#ruXQM%o+c|nu}!>|Eg}^%T#~(n0-QO9otNds$R$_VG#@B_ba#<7swhfztlFL| zHp9OVKNw$Cy+1(7t>vA$UuA!dJl!FI;aMhJbgT|NzPOZ?yMO|MJ6IYQ>xK<(I)V-q2z08$he`U1XKnQjscg3HKP z7y)}={2sK42t>naL!3ITgpW&fkq9hxU}{0q$YNg8s^fL1Px8{p4vT6edkWI$z$h~V9{+00+ivVCkikKBg z{bjGL`Q7)+?9d%u6twRR+U7hc?bhg01lXyRzw(pbY&_J^6pME?uqO>$AXYn-Xm(#i zSx=18pbKzclTa81|IXP+==c|}V@(>nm#qyk6QvNKw0;!$kxx5LGT1e_9y@kLjm~}4 zP=Ohu`7#1(!);814=Mm9N$av8goA9wcUUOZ%WOD9jsNi*A;42DF#h$Xo;P6{P2igD zFhGVNe;1@sNjt#rTj1d|GI4iiBjy5939_WYP!O8`ws<$3yB?A=r!6W`R60E$oIH){ z+?@Y7azbo8MLHs-uoO$8uxgVVewt&wV`KcVn}Jvu@>ygU<%X7^t;Dnh^hKfOBs{V> z`CCRaItDwifusQ8+MSafnWO?@AzFE~IBl{xYHQWW=Lzn=|4?`#0@#j0nzRwcb5u+t z^*g7?;vni`mBC051&?E!iSo1nnHs2AnO8&Gr9|IGU~y)SGCMuo5u5t85E@Q;(<+hw z0RM=T=Itgoe%|(xvW-+ueoAsQvU4220S{-BQ@j&8Bwn4D=j-Zr18vp_u`G@Es$7!m zTCxxQOT9IG6vK+6nOVi(eQe4vpXE8A0#edvPYbPA+n93SW1V@VnNSco1o3BUot^EF z9SuEk^ljV3u3r0IUMp9HP1kfu0})E04_j`ZdaymtlP}Ai zczS7c*!73!VKrPbsE+UA!_Knn2UlFqU&fMr>HV99pW9rnf+~+b(I*Z}@1HkuaR((s z1s``NuT=jI0R=&}&PY1uvfJrS1KRaY=v}e?Wj}5Te>a{fwMpi^z{icC=d(uwu=#3} z8wm~)>SRd7T#hjESoSr`z24Z^?t{v+6||C2k^CR#k|*WNjxzgwWV5mJFB_}}Bx#z1 zP-%?HN_k|%OdrzqcZ|5>;ZG{}R|@ErsAuCTLZvUGlWP>hFASA6GR}^G{dMR2V@t6^ z{Vv{bgX=MDoEt>+aKTsky^WO_VI zDP$Dy3ggkBxocOF^R^B=lq#3z8^0Mx_bIolGEy>ALpiODa&;BY4x7)G0NoW ziaU#J-eqwazN<@`3pu>51X(R_->cC_{XH(rTg(^=8>)`j_@v(t^`!abnUnafmUk{iF|xXu zrNs{rn98U^WIOc3&)BRU3x?AwiIJVfg zR2B2g!QzYwP-)-4s(16JloY!nDWpHK<8qGfoIvz=MP3Yj#%6o}YX2T0;fMg(@Jk0=b$LyAD#Z-jrt^CoQLjgE#-b;NQMy1Br%_u-!RAI#vzNzix15Lb zC2plsR?m9}MATu496EM_8Q3|~Cz$CC30iU{lQ!yNpQ|rE=WpYFP2X})?|_eM=7miG ztx+mYyEk;@$^3C!k4$zbn>RRy86EyLOAvKsco1OCX(k5!MJ`u0wap#2Nbzu{Z0M;) zBkLQz?6N;T&!xmrV^r%ebq%PTtj{0d4n2-gDq8bLl;m<7W(h`lvqmLl_$T2SubEdg z1)!j-oS8a1$oYLYXbN#$BWwD6qv&C1484mxSyOnpmU6N~QNuT@ZwgS^Ju!E1gX>c` zKW7T=vSN%I*4TA&up`}7IOX558u%^rw@d|%S8^USa5dyrmp2s;~tt@}{5g3BH zy2Dqg{5BO93#`isPQvvC#@6i0@3Zu%<_f!**r{y)CdmEjWdPBraks7m@m021_khcl zlldiWhwvkO-Ar0`_P_u(p_8vSDQ9MDs3B_*3cAa6hRW(<%M;}1_lc&LZdkkh-{Tc6 zs6)CwGzS-zMP2U=iZrFf5RDr3{rV}8#V$7RNz9|@HS;U~%9W}g<{C``&d8HJ=JL&N zi1TZV7kVE;UJL7{_2>gtYfaofaGWM>fHX!DLrPu5L4J3?9nF6j{)3|NT`JRxrkYLB z#)Gi!Mk}7xy=nqOuZy*hhD7}!$;fM!MahXbra#(ZrHh5^?_}is*#v+(N*pyY(=Hh~ z8=lO8VauwGG98otiu7S8cCwTtRdosR99)m<_m4D>2Z^6xKL$Qk>*`jlx__|3SnarA zi2m;Klj#+g?4|+#YF9`N3GiLMm4)6Og>0L)@@-aMw%;|v{onDTVnkmbDyb57hqp#u z209L#(=M|KN(Izp-wlw|!ds(UuDh47&PIabaO|`}u8s>@0Ag+rzPg5P8#I01!JTkG z19I6kKw>ocx7#m_xXsK~sf_MEYp(@%jO#P z&X2QrKW%2Ojr<5xYNS%IboSYyHE#V2U#XNGW)F~Gi8rV;h;3a14J?7#%pd`bJ)y<4wul&0B^ylq(pyPp}F#;XWMf0yVdaid+jiJW+}&b zHWYGry|HZ|ASN25DhGqdW~d4bDIox$!K}S4qH6V)HgpoO{ScMYv%rxZ!Cx>^W zvm++`^{St@8J`fz~Tg=+o7DT*gUIKmZ?UD&y!HusbW2vj^lE!(3@Yk}|{x z%hpcr&F^6&qh~!rVsd>~++WF{=$0H>aV%yzfEwWgnSC96A7MXIuJpn)m3FXcjYH00 zB^su*x_Qka@9||+6==W+N$4_LTfJu~acXi+fppKOxIenlOix94*@eB@qbwPuix2>( z`%)d;=6%WfxXkH`?r7K+auZ|Wef^h`5WNfnNgImW=$}HmUpQ{$N~Q{#Azf`f*9cZy zA{LIOCC*=8z~YGgZ3-A8-aL-5o>7)$#Zq0|^>uJ)+dso8L# zBuxMyar{ovS9@nG+atF(1Vuebb;ytep&lQ=I!vP*wmK$#^@A?*f~alh<6h$9s~4gq zlaG3uK?=vG!cB{Nu7@k|s6uW{SNw6Ynk zSYX00NLCf+diRD#Q%caQ{KS8P{+&pL?1Q5Y+0qR3KoFgZcHeEn4xhW>w4ZUNzV@iu zBO+a%pYhVA(JW;d&&W*f1${lA%mGhkm7jZ|?c&V9FrqZFX3ND8})WP5ko#;oKs2lA1os1uKD!73IVX%pY(YOT)P>jrS;t(;EHDYg%`%~0vHIO-SxDN9~_lPbJY4AfC+nF3sim-dL5E4jPuv~4%k$f(6JHQQ z&@9KYG(_eZcYB6*1b1drs`cjWd1V896=T#(@cFbihlbRfgY6gtxG>;|1t#DHWSrNI z8UyL1fIv#HgbxjAs}`te4%(9jD$M2jYsl}1D)`TKwo{$_oUxv^TAxrl{B}h=%*d&? zajn~&&j=sK9UnQ2J7MquMZ^+KYmExAAxPyz?gyFg)6Bgh+?gRfi+kL!vfrDC5mBB3HxIVQD?N{(lvZm1?Ohx-LP2K>WWXND8Ym_ z;rDa%>nh((s*S$%;p>HZ9W|B|*x9`o2&+@lfFrq^Ovf0SG3#Isc)+JK&PRT4;ZN9w z3QNP*wETgccRP)+X|k&ILw*yvT*Dru1Dy@#_VP|p&7ze^pzV5-#zNX9fvu|j|MTNOC!n@@oS<LwUbNhUj>np_qZ<>o8*$=uzz$M?WFZzW7$_Q7eA8)bO zyTe%43H`Q2CgQ{)*C%18YwH`6A_Gg-XUTNs zK1DB2e1B!4VCE!xFXyt+a;A-|K~K8vr@DZ+IwwmC*L_uOBF>!TaGB|VSeFQ;ZN`2+U}%R1(Vpt6PG zPy3FKoWCkw(1t@j`xM97Hc_rbyKGAQ*EO*==httKJ6!h(Ibudlon0_jpN@*I7h9=v zwsZ~#u=60J{Ms zSd0cqc;8QNAU}>$`4K6GXaTM+*Cwv~`<;UxfOMO2e)mS~L^B(ue8g7vs?4ddL@%oR zz2pQHOYWrDP8?iF8YyWAKJHiNoS^KER^h`G7KWsIWqpMzI*}s`sJ?Y#F*xsW>fsPWyagIX)TFyI9%L`7Wf@Q3}j-pimH ze0{= z?)TU(CIL`Qz}ra78KUNw`Lu|px0+yw`wO&z^FZi_Y~VZy>Y@zP{jkyC1tF{o(5l$= zk)8_UD% zdSf%d)iqt+pT(}cGlrM~cy&dz1JG@E@~dCh__DR1@rPuVd@ilzARnS7h-I8ltD&To zZ!`O*#)w}=Xtod8-fb3ZS{h+MnW3YUzM760iS=Kj)Uh( zJ~Qw zns}~XG`((#B>Rm{1MoxOCoBU!RduKhj-*FG-1Iv*winvI2p9^!l-goo4&RdDr z(t=Pn%PN{hTHx6hafOJ8BQACeU|G3D`9hN?&Qq=qsVAHIKlc1&nDl77Cm)^FF@5V2 z$AAzdPu6yRgQAqmA4);6+T&R=_7N?E8#%cvXvVpU88~z4Br8<%zP{!NozQ!`B?sHK z<)quEH#N|1AM_r2^Nvec@@cTOq$HM65s%~AG>FcdaHJNyoCi&4_`zD)`BJa(24mJ zIGv)p8D>ugz?<~0n`iJ=0geD*Em0v_!UjgASIK4ETwu50=47ODB6Q;4SoKRP#k@07 z8GxziSJv)_!9fpPm$f^E21?K$wln4yDUYt*zC&bb?0)Y@OhG)gGUoU%|GfJbM!Vhu zb$4{;EFtIllK|AYwYfhEazrZ+&_vbd1OrEC3aneW*7QfqD!T1sa^1E*dGAWwzijNB z{SJhgjCk&2zc?YF&v_6&9kO|azZ4N7s8Tz5H?l7tU;vF0it&AH*CeTu> z8XwLy@_#7%j@@eK0+9@_tdO2RIlF9I`Eq7cmJs)iulfag@<);pRZ^4ydO92h5M1?7NL^!h{IR{>iJ48P&b(y}MJFo*JQlzu z0a#>9b=;h|KB~NX*_GuJ>29u72F-FTUkhq()qO#5xwL|VmT`#W;f1JxBG?gKR*JEa zlZV&8hk$|w4==UP?t30%0?p8I?5U?HPelWmGq*OHE%Ob*wHauj_UxdK$mxUY$5|h1 z^RL?ccBx;`YDrV-^eG_W**cuCj4MZs=m<7wL6Yv`QrGS%<-3~dhEr~$nba!`1RQSt{DRTrbpw3Kl{U`8Lu{e(tvD0`$yyOPI@eR_Fs0)Dv z{zlblTiEK;p;$ja$tCc$%PKKsCtiP}$m%_UdCU&1g~8EMtd9=~KkgN+_Jz4zT`q~T zk#B{dTaF{hVu>xYh0{vwOQESb#`};L;9uWHIj;5pk^z7KTl9|P@rvsHHQF{V^uQdu zm%t(MM(yp6oRDaW1^t&41i5))<@X6wXciF?OY8B+a2&!E4{2T69r3-wPk0pPmwE+Lj+ko0>X^%I`A zY454Rr1D~~RO>SwMmxY?_WtS_8;f$cH`@GX?rYnxbhy*Wx(7xn*IKhXqP!GcggkK= z>`UeT_=< zT%SMf`cl-Ne*_68cZEcd=r&;H(gP8-anlXFZ`(&I3mn=pobrOGttqZLE8nBAD1vA$ zNemUGE+u*pP3|P$Ung9BbbMNDV`6bZzV{pv$*yF{cE})iz9AG)F1|FGNNF&U4sCiJ z!W^1x_;t--3zsq?PaW;6N~F1pt9>NVdoF)vj%F5eYJWuz#-;PeC!G(8&w*2wI zZ>r@LYTqj6Cddqb+>qh;-`u8$@-#0mHq-qa&vYgU66nH9O8@RzrB#3pWNL zjmbLM&)UygDQ&%c!Is*Zxfzy`o}8XsZ}~#+;)xpBC_VY}Y00mJKRQoOPu`WOsB()^ zU&=RK9FAy-21YlUIj;FUX;p9wSZYNR2i|A?okNP-`qS_Fy2j|Q2iB(E{xR~y&T$s~ zaCxs*Xjo|T?E%}p+QkpdD;;Ju*g#&xB668L#k3dn=&4nO04MUd5g`n!A-)piyh6y~G}h73sj zS-G2|^1UifrIB70h}S`F2Par_477PD>-=F-60kWBH0tA7FBqMTXANW zQ9kLL5xwbbv4_#=eG~Pb0$Y*A&SJAtM)!Q*WT?X19}RB|St}}Iwy~C+h!>KxaT|X; zbo(Io`7etJiBE*>X6p5yH3p6Wr0fl=vS=KPV%5)o9M@c(?fQbZHtZD8<9n`JOQZR?EyHyhQ>FUP0 zTsEF2!u{J|3R`weo0`Z6yG^Vw4cXm)N+H(OFEn36zrJ{7cq4fEhwFoULRl<#ow}K+ z;Dc>K_nK$qUw8(isw3lJc=WBUX?g=2a4nx?-AlZ0TW<%MVZ; zO&xowKKHB6p@Vtu&{`6XIE*j+J!u90G$I`$Nt>m3PW1u`BNwPpL^-0f%~$^yS8o{> z$MbXzLvRTY+}+)S6Ff)=5ZooWZjj&*+(~eUKnS|{;%=K@iv)LfcYlZ9|GB@sTwL%0 zcBZGhs?MpZ(>L8N$xV~IW(jb}g`FUWrAF>9lbdliU8Pf| zTrqRA+bi!MhU;D$$nzdm4oK(;HUydqg$Y6Q`a#~vmMA0Qfo#vj5N2N`7pEYn zZ%5k{j1`1l_#|r(!{pw={!Gna=)T}_S#^4l zhAb%LkmB$f1QK!2+@3^j`!%493fR!vj_|3yPi{wTx-lZtVtmVUWcQ+ULeH-OCVSSJ zvD(znLYjun*wLexY;U%7&o!KG1h$=sw$jkXNwxfQ*86-A=wrX{uS2VzrUX9<$A{8 ze-3dzfjRr--a;&6;Fm$^L$PN->21Chw1wV~SgbBdljs>1p187WI64WlqyKjFG_xrdJ5?! zmXqIJ%~#(eS1>T+$Q`AX*wvlVWtnH<|!OazR=Ti~n%-*ENpSdmpHt6?#xhH!J@m$8<$c z2LrTbxP=HauvnMP!Hyse_{hljDzW+x-!)EXNXRAp&qz|4R>ymBh?vkH*2ST7> z!qmlzla#jFi0+kwQ{LAiOL-fVC?34|S#3aSRw706Rp-R+wn}#P)@CGz?`=1m@5Sjy zFJ1JK5CL{eo;B&VrF$2~V;h6@D46 z^lgR^9BEY02KjbkXn}FC(6_p=hnA22y~^v`Ugry1Pg7h^A|}l@tgeL&^5?;=V*WYY zk+*ND0(u|j&|=;vyG zkfR*=pdKyVk1o^de}ryvOCymRFmf%~_V-ZX`qT*J<1FF z`DO(rE0cI5xiP1 zsEKwRPD(}1M}@hk>lti3b>qY3s`!nxl_(feib6L}T_3IkHjiDlXA!i^EW^GaWRa0T zs~sh7E(lG0Ho9zN^mhbT^~#(k?c#8|Qhr@{uri7*?ZZOt-xO@|smet!!UZmUYij!x+h(;dPMKuZhwc`uvQsa?L@_Zc<=>Kbc^Z**1|Fs7%)Ln9lUD6#vAL3zOU?GI^r4Mwa*7 z9v~wwh)fJg9w1$QzOa7S4bF89*mKQd?mAK@OXUeusQvUXnCqKMqZnvJhG!w$`w!LP-6y3_(uERsphgNT_VPo2rl;QB&v@`AJ%df~8J={`k>f zTDbV^h^WHVa!qWS%kP_#nuV=nvgk)Dpo4eK{P|2)F=Sh4I7OszoE2QsWc$=J9PioA z-D9s~Y*sEbbg5iv8pAl2@kMR3C^w+{BjwU+qBZtJX@}qY?$E6cb*;qS%3tt0hK2Pv zu67V~-P9?`qdo(~9<2mZ+(g$%`)EXruhkDUxGPh5A8@s9?v!4}~c{d}o?Xm#x=I*E4QNi9205_Kx zL`(op(;wQ7r#!1XU*67i_D>!=fYX~Vtgi_ZH8H>*6tRliH7EVOSAB5jE~>M|wuoM2HE|dEjzIIxu@3tEyM8W}7z|(#A|o4fNXNaEzS50v^P_7>6-oEJ|K+$9eHyXGz|4 zQJJws!>n@)e0;Wb{uS-WJ%AcF`^3R4Ea0x-`Cb2|r`U7rtwiu@-#EDxK2IAz z>}G{KXFb7YSjjSWw@~;uq4n)unX{Q5VdNB<$4q%BJZ#Ijs;a(wF&!F%kNnqLLP;+K zBr9BeV$LHzq7NRQxYej-i}pPpiEnydZXRk zoV>NX9mYQ=)k`cH$Yj{q4BoM{I6~hiy7Tn8QR}VE>@Z6s{k?PgaY0#G^sgHZ>V86=%9=re-HW%Dwp)Id&~f}9G1FW-{jn#*hiAXKH}h=NgbD_ zpJQQ{XkPlm`_H&6t^QWBy-XX5x z-@+dmQDoLHg>S-8(=@mVLe!kM`J_+_tgBt+G7<;ycfR=fr%$DgqdU@OYbUsCItT;_ zik9Hs2X;KI_x@w+QYpY?FGn$sUA>77_$sUeYBH2&2;;`=0tr&oaLIP;Vz$1Meo1<8 z;!V1jpRA-KM9>;TcBGlmgfu8>bo3;9l<~IH$w>>yHE+kP8zR@z?);;52WYpgo5cK6 zd>IEX&K~N`7C?NmVP4I!hk-^3A}C`MzekF!JupLp_LE9{8+HdPUS=DZGEMN>tPH^qfeaKme<@~_|f6*=J_F+R>?zo`tvfXle;uo^Ez3> zb>~d&F5znQ55?F^38#D5Agg|GjO%p}89{`qF-*mTUoC|R$fl$ic7*CPl>RK1Jl_ZL z)^YM9?F9ZfT)jsdd#=yeWcZm15GR^md0ZE?G1^g{s+ONe<^|@0u!iL)hW4kuc`<`D zD<}6zs4EO@&ov2smfYFMKbgzeKlz(V9FelCSeBPk2xH4|^}Uot;wDk0Uu4HkvZPFt zwi#G^YrP0tx2%xsz0v$?EC$zk-(V%T2=||!^r8i?E7SF>cpuXN+neO1)P^QYC4zA~ z?k~4inMDJe`_Ee^V29@Nt}gyYjY~`9U5rC!&cf-`L1ug_clUK+JCK3sXF52(ep4ni z#!uKCz9=x=w5(`K(EBV}#$r>IUONq%GFO`f@8k@eBISK{E)r8NfF4FXdY_tSq*fY> z?^#|XAsR}%ok~6)F87~aU2VSU<9R-zdUh5!Ru4!wFj@mfE+om@)mN?fG;eZGCYI(u zpy5R@?Lo|ibw1vU6g4aMmTGYwFxqNOP6!f}&!yz^lyl;_h>{Qf{`t@P?>57dHv!Mn z;<+tm0FwHA%5^7vOXpC)E#}#iQZfmg z!vB^Razy^Fid zl3I;97c8x^>7SFhN#o3xRVj2qFl+8X+rBg~JGsLN$Hia)y{fc1Qn7bt0jmOl_xhBf zJ70M_jZtatrYq&y9;!t>fnc*H`y)^}0xND^?X{gy|Dk`dv%e)9uH0C;%+Lr){3BSwb!KWI;m;*UqOCu;VZHf30Pq2j}uE zC&|GY?;uen+UkKkyU!$fDVQ^Hzq1SiKp}!ss#Khv0EVY zg*>tKDl&m%fehkHFI}QS8zRkJ6ks6#CRG+NE1woWKGDrB(>u&EGVN-;A3ru`A67>z zRpElUUJfBeHNDb%3+68lgFi21knlSVDd{6&mAcl`_BjoIE7@B;-vMDMtU5gG;hV6; zc`)WkO1b^pBRW*cd49Hm6m~B6#Ta?81~vbCD1?AgMRF5>u(D)GPWIQz7)2Sdb_L{= z=hLM`-)k)oJot>7*aoA__O z)Z7qcI~lJCYYsAKmbW15Fdo;Vn9Rm@5xt*G6{7f$@P^5e|&tFmu{pQ-{b!H>rH&vJz{9&S zB~z?cO)%EB%4RfH7_=b{aZH_FBbCAdwnb)4JCc2Y>}VhERA@#N2Uc|b6D!xEiR-HT zE<`DNna$j`*ih?4VCYzUm$0Io#cKc&R7wUSA9?mh+jX_%!;w0dOhh|1d@9b`&F*RW zWe?Tjl8GSMUWXdX&w{#yu@D{+n@YQ^*y$?AXb1!s0YUEU*7w{KxvKtslYS3}1;0|E zmLV1)0iL?PUY{&lY@uFCsD+*lMvy+7&jO-3pJ>T{_htN#NlHif(*bu{q$e#ubY{c~ zuOxp}8&7kP;Bpvw=5Qcis43z1)4m&#q7T^f={VK#9=Ntr;pAoBU|_!k=@&?toj#cZ z+1Y^dJ=KT1q;!`@;YxWLnNV7~ZCI6VX0XGtop#_Rr*O zj!lfM(~8>Eo58_Bj)qS&NgA!sHND=2i6&MCPNHq6RYayY(5$WoYmyS zZwkpWO5I}7AD(x{ML!~%OqGYg=RYgHtkQ+H?`cLW?;G=Q;L_3#cDoPkc!qN~ar$uS z7nN7uh3Ijin=QK?(Pe2_@qZ86$60vME^OL644$>9#nzN^vm09*2kb_yZL#BLjRjsY zTBx`Z^*-(qdVKiUq3di=9&Tt9K4|gnTVp%TJNwSUq;80jT{5~QfjU^LYtbdb!jY*< z=V8vq+o0qMmnq_9R(qQ#H6qtKJ725@Px%!mO>c#vp`oR(M`So&PpcYwON!~dU|}+D z-w$}>Y@=@cnuQkb>Z0}I-$qX778eRtNVbjcRvwXjokco~Z$k_hyYnvYyl-j`4+ZC? z#=le2ipQ=0lEiXoc^g1?fZ4*j$&1X4iQg;%t*FVI=9-+xBTL2b4~zW4Ba!Q+#2Ht7 z$5g~#DbQ)B=>iEe{@cfo^LRnS+>*zt@1;um4Mgj3I{8#QP8pC4 zg?(p>;|_Xs%6u%(aQdW{I+^!$2fB-VleE3gt5 z0!a_XY~h_{SHx`)H$fVN5*JSvNFao4=8?F_sSo{&-bU=bsd#-qt6uxj9ivJxbKjCf z`)yl1&ZBuPD;FBzFVd*hBrlY*yVhaFvo*qL1FqDogl=obZ0~2rq{(6GHC;9J$<*>u zY<9AlKhVGK`xyDM;ozFK8(-$^o~ndXy&;EkhrMC9@@yo7 z#e=s8QT8-oYrz!S$Kt8!aZk=NS$0kicyurxP(V+TnL1UBqQs+HS2^a>6jSuT^HzkU z?tC3)<+8QMm(Ic|=<8PJl8V4n0PH$0vY2qiW60zSFJ-fKpBo}xOZultuR*KPKxF)Z zITK!pR@Ee`Lj8nyOO=Iq|2teL8S7q*V6P}@W=66DS%q`Uzsq(Xw63fCH(w}v)0-i5 z9@G9)^bu9Bb(PHW<)h2{>mAsYExOYTCE^|Dbt%kBoWPWIH9{4^s{D!xYGqTX1rf}c zXcWX0lwDeaTC_@RWr4J;S|^au23(#b*cYqM-=XKVY0<$oY+HgJyhFxY-jRv#=14<< z2_91f#^3BxBM}mAz%owaBz331WU5wtIenQeXGoEnCpv~*I}{>(ma&j zsz+ElSxxYgXvfYXGhfi#+VsSDy-=gy ztbP6tK&R21t(Jxi{^0?VIlesED{_kdG^N+s^z~Go!5S1Fl9Q7LFq9{?mqR9 zeXkvPg4ebLnhEqaiCF2=BCqY;^7r|Q$EkarZtG3iQ09-G9J`$mDdwxny+sZD_k~Sj zEeQVB8P3}b@f)p^4ALjP_42(Yb8>`^2D4VBAUJ5-HmtT9Xj+h1WNa%VD9iQF&0NhK z>gHG$B$ZOhtYTyR3_^rmojAtFtp8-kn6Dpyrwj%*;2c&|Sia@cu>gu4<>uyiZ$vqN zc%ZHY3YAthwn}rVmH(*HVEG9~Oa`el%Rh*bz_y1rNUXNEP&Grfx?fWT&$P7F3kkmB zrHN~C(lW;NMx%)vKN~>r`}Xb7nK@(z@5TFY(h$KD9;J4LuatnwgOplNP5En@B#rrS zF?HhAuO*{FmtOLVrJ1;|g;d2=YCuLru$M4AxX;soX_^GP+83{v~Dndg@n3D%* z5J>7&iAS-#rkPS<=LdZlIj|44-g5qi6k)@q^%uQ&*AX|6v5R_*Lx#KWA;v&LDEoDt zu0YIR!u{Xi43SqKwQP7_UI>~+kWg>Uq4)Qn6HzRMCt}WRthQvLB`$MHF|;5HF<6hg z5&OLKB*I&;00=jj$CkQCK)%TS!yY`vrJx+_GJ-61f6_o5{|5<4=RpnaVQ0z3bIjPj zjvJzy)8lD8Tn7WDQUW6QwTC$MdD0?byBpTj@`vw;-)n0=@AY&>$-6p99>&LJlT98W zKOK8J!&zj++fD~hvem0axqzc|{?sqG{TOAL(QD$MtYLq?CEqf*5t}Iq z1~0QnmfUzCg?#e-0T3|^hkl%_QUGePSif`bC-G#z0 zwb;BoXlS<7zha%RPM1rS9Qb0rbjX%}AiqPwt$=8{GANF>io{v0DZSoo=}o?nGiYiJ zqaY!l?y?Eq_CcKF2B%HXh`j%^Su-=Biok^*XUV5aZ0hBXq!JVwYhf@mkgs3%JdHsukqy^*I|eXWfiN zP7~vFQOtj-2SiRj9m-6T`qzA3&rv)r=vr)4Vd4vL+AsNGkDA8s!x z;!Js!%Wo!IiLcDDk;G@6{e3G)Qbi%n)_>;94l_HPwPHa@ z9^^BETf3>%`Zw{s=Zb&7KG?$IcdDjWq<_QYNGt#yAaA6Awkcnq)iq4(faA5W`K(`R zQW5LY0KpKUFC;BIBSjc7b+z&G;}fb=&G`AAjvr1xAvx~EE>$0aLOIxRJVjtomwt}_ z>pM()c&8~wMgElJFfnzUwHC_$cZSX^6LUBU>iS42HUr75PMpDl8TvT+i6PXeEIOsb z=V6R?$bvuPiYLSWQMF(FdoLRGE2js*(w28lg#sJ9oPPOhLVi5ikSUbDw>cO_k_zN< znpy-hNk_ErgRDs#981EY%yF~7yN`Q_Wz!=vS_!LCt=ERWiE_G=nEvpU>7bt&fx~rw z9jHyK`+<|c5TKwIR0;2c1&);RiRWuheX$#O#3aUqDiF+qx>kPlx$f~TI$%tD{9z$7 zk9FMpnF+sE_hAf~ynuRYu-AnW*^&RGTE5lPp*a2!>$Abqm}=!nO(`|g67CQ2GE->!3I7UTf4Jz671p#gDpR=_H2 z*h4i4r66I)o{e$J`FNV?=Lqva$S@SGllep} zw@TYyvV+GnC)`3bL|fX5K3jZBf8LTsE=@MgTS%vtAFQC5fH)Xcj870(t^0|`U;I}s zd-RMpqQ~7Wu|DYhT=gyM()cybe#j_2bJik=1|3G8h>WxJ#TQks1e z1ig8t^H8%eC9F6!RNr*!fDA_g*x={It&!L%bN7jP43Obp93L9hhOr{+IBzuREYg<% zM5C55HpWvr0aN^XuFUppO^BvcXADsF6WG}$vqJ1*RTvSfks*|y3lVzegTb;)vSy^z zZe^TyufyTUm+5|Qa=k-N;%$tJcAPK13v@x6sgGp@pVd&bEVcjM14kfF*PL>Y!D`Md=l|`PqLVM6Nc?TGoz5bG z-qweSzei$XOrJ#fdoK@j-}mHx#aV|G(!7!Y2_Zp71@G)BSrOG-WhQVw+vET}ogO~7 zbs;QZMYgkludyasEjIrMTy|NQyk2!5+=2(r^{@gT&KR4n_L2p#YhE0|u5GztmiB>T z2h@01aF&DX>vJmSj|EP5w3WK#dD^O|GZk~HS%TR#DL@cP{8bB4f5kiK|c@Sq5sddBp^KkP`TE4ca9Hg?z8`)$rb;Z+2>X|jDZ*`}*NksufHaM?-} z0>^LKe)1YPh-oQ{2+4&R-&Bi6nm&2-_b6em%gB*KKZHZ$KZ6WWU>?<^G&;&Q_`Ad? z7zLR9^=bosERCOe)2(nm^LiOB+uNT<7ew@yR|X7`QWrTUfppoq%vdl6>(wsvnBvy0 z+_B5UWu(M!BFUt(9r40wavF?T38r2pIZn<$QrAzc&(sGy>e&>qD8Tn4&wm-M==-9{ zSmkE$9#3FPtuJ=)O|?OQg8}8hsI22P+a#;5aEDi>U5%o^`$4~UTccm5<0f2$7pzq2 zyGPf%8};PYE#%v%t~qM9-Qpp7nO^0}Vw|ae3@Ep=;oD7Lh{=)f;#lN&a9Al*~azmr}=9f`ja+ZSak10>=LWIO$N?1Lv12{<} z^+2}PGxWed$i@~(yI<55ciM?=A*LK$FgoR(u(n~8a9824Ut}rd)E?+WahFYRL(MvU z;)@LhsmI9yr!Q1=)1$TLBC|}X<&+=(7~bTG>~}R}w{B}?Qr&y=N!(gP$&8H*jOSok zsAZYbRfAt`2_IHPYAT8)5>d?_ok#df6j1~?c=^KgTLljpd##n6Y!g5KIAj0LMWx1% z2?+$YDiLFqspx`N^Z$HyyDzD2%ibu*DlwEXIPlbAr_T+j8c#I8tD8U&OexGvHtu1a z59VO_7+!OuOU-Rj(MT?9lM&EZ)s|>rPr~cc+lZAup7F4o1O&YfkxZYgQ_mC=MTf%>A^>*|)J#M@c2Wu@b+_Is1E$KokUueht z?CxQ2WU3ZtnTPb&IPs)iZ2G2G$r7&kBv?z`!x8_{sb%%@1;Tynj`C2y-|Bfx%(sh5 z{OMR;1=&w86<%crNNp`)!_yz&ihsrRxJm-RgyY{HgUr!MKhesY?^C~i)mDt-L&H`d z4?(z3fl)52AuPVC@51uV_Ip1sWAbpz31_VKBP%QbeII9VK|Bs+#L zq2$TMjH@X^_%-$gLXq?rxcQPd9jUWV@-1rib^Ptm*%vpsZfIllfEPnUSPMJ8H#0}@ z+p9yl3L%_dgSNP8L?b8vtudn5ngzI4r~jB;r5%A;e|6aicAx3U%ly00zc0_rP2SUa z=YI8%wRuM3Yy$HS>L}O-YTkvWSFG8U{JOGl?7Nro+OIjziv%xYY4X;&`N>0P%_7Q2 zme$AAYmXf7(aGYy1mIX9w8lGCI>gz^elC&w>cpzg3eX=NoRn-{TBbkTxPPy?Nk}eA zSP2+?yVkGJjjldoANMN@j1`gL;~Rgh^a6jIjl>$HU%-XN44vaLX>E&feK#Tt6=E;= z2&*&lfAEc}Y`ye=!6xR~nWa*NhO+=Yd>g8wccG4%GS?q2bm<7y>}4Xsdx>g2(<#(H z`oY!m#2)#<+%$2cP6lKQ7r2k+WkxT*%>!7uDg~BD#F@$WnizI)TOd_cF0@w80zxAS zTyfs7f!wuz%(HszF2BHlm{BSX2gSN&s(-_rl=P1n*O+s?onum`a>Sxuqfl+xylC_U z(C-m93da0JRFquDj84;wR+CGONsozV-p~vY^vK+10LSJp^UG9vuON-jG50z-LW0d@ zo}O<+5ih@;4#S^`(<1El*}l~CrL&|LgScmi!_xm|X$GTJD~kfMG%e$ND#yt=W`u*# zz?I5lCx?;Q+C-OgZ9dO0OFp?bYY+sC=3jp5S#B?t`H-2Uj0y+6*NpIKIHI+aVq7I> zxQ|N6GZ>Vt&#Q2(_7T zDnx!j7p8;}_$>XNU?(L|-)CChncx!_9x+2Uian2fx*SPevTO0ZI=DkdE+`=DDVho_ z5#sK2ehM{_Z0w_W1=Lk=GW8pUdh|GfZa^>E6lowN%mmjL4XEX=eNF_LFS5z0(;3d& zl=$A>2UB?%pQ#@e|BbqoO6gVu4knG6rnebsBlyP!NaBg{O00OULzIncL{e~gi9v8%a|G*ySA~j@b`_NwvXZsgE#of zdK-%Vm`X+YBv4cGo0Sk9|g z`?M^UUZy`M6^Ypx`)}X%Q}GvRZDWu6dpc|pUN80d&j39%kqg&>?>-=XN3Bf;go8fC ze|m=utEoco4G!}fTWh32rYrAY0n7-ym2JvfYmlv5(`$IGj?hn|_j@JlD_4i{xBWgH zh~&@PpG8McL3KtXS*U1e_5_=2> zGo`|J9pgv;G^oG?rYUFYTxL+pjB$0YpVrM?fLpm6*2%fcjlnex34U||ZDM`o;S4w_u<9mTV~V~I35kjs0wA`xR`-|o!3C!z8nB*ZcK3ECB#*^ohCsP>$-I|0?u#}CChltA`3 z+kR`pk)30bB>GJ4qDj^AU9d*VLixkCvSaG=%JS17o&Mj`^AR#<(5~;?S%W_7sRGsG z-#3-T9fmmvuqL0DY>Ni6-#gu%U5JQqJr_FfN7W7{+%agpD|5R?>LG;t&lDCf<8g8= zxV?H?v}AG7b{G&qOiI4d5D!SR=P4^V8Z8`Cix#d-pW_!f&E{8hupOw|cEEtUS#?gr zTpP)~zA*w)Zte^F6<^)`smjXd{Fw!Km5c1M3+vF$kO8V2VU?vYUxo8`!t%+9eiRK< z!G>s{P$9jPO0EVY|J^QvxHD*%@!Y+H@1Z0DmNRvmkg;)V+SX>7PG;)8J67s{VVLrL zX5Nm#{?S@k!|-P;KEvf<&?prD^IPcp5zXUly&tn{`qcQdN>|^;_<$VWR>kp*?hgvG z`)?tQ;m#8{4Q||gC*GU(;g$>!lFY_*hgu+L@SV?73gs}Uy4AeUJ^$986M=~jI zKW#UwXR`98wTMa+$0A^4i^X2QH?6qCaF?wgt!7UlDp((4e7bLI@R9C9BRRH#NI^k* z!QxlDdagc3mG-#VwVfjJ;_=|055TpLZD5^MiHfl85i-I^i>OzSwvBxsPR% z3zz!d|M4i@Q6$?L2C3=O36b#qyUVwQK`)B0nx?)`#{il)Yk9z}Rr9At%hbCHnZE3H zSO^dGUFc}r(@+R;{!GQ$SLtH1^<9=U3EAJx1a}erS|y@}pAo#`%~%k&8*_~1WlLvXL$apm|fh?B-c>AzT%4|B(8dk6GNo~C9?XY@A#g}(lOAe(Pw zaDrregJghgitB$k?C+tLWnj3{pKainNg_ZF&BMU5Qq`f`N%(f5unmNVOvk845gX(G zuDKSH&;)?SYz2g;DXrZz72p~ND${V~$~O#M)2of3?WuaHY3Jv*j=|t??0Ej2S1WMA zoFwl9d@t7Xyk0;9X!ObIllLi(gCW&#ywkJhvtF=Q`d~!cF+MQFgd?a!+rB01c6O@e zmqbp^8k>o)&&0JeftwVm2SsY0GV*vXI}pUzfa%PfG_Z!L1_9~@VAH`46VOf^Ut+#f zY*4BMDwHoEzQq3oS2K}rQbhAm+Gga~a`5c`n+bXt4uFyBw4$Jhi1$C`8G-)>g<36T zu%qSd>@akZzzXmO4^f!1K3V8YTXwxz_byt8w^UF?5~5Lf!Sc2XQ1lG3Nvy8tEF+Z8 zGLFpy{!y-D-YG|?;N^*4I@$NG`rVa4<_y5s>5nmr!-bi6DI)TNciw2tSjHX0s|kUC zAzba8ZQP1GGH?L>PXH?DcLiZ(wU9TTb5e2I>NCx*JF77|Satq`P(ly4-2Zi=b4I2= zN)fr_A?%V#>CE5uwl6e#mFaa&#{bW(Wnpgijt(KlKu`GYLxXl7c*{%Cz5u5UVm2dA z-g08Ux;FGP7jG_@GjD$+8p^UGvh(fYbotpRtBDEM?XvT1K&e*z^#3e11SkLJ8*e?1 zX<%p2SY>_2f9ph^vrg>q*br>~R;KT9ShyKfB<=)FsG{zub9|4^E z&(fsHg#luvngA|sO^Dvzt^peIpc}!=>q)&+$i!&bm52MseO+Ut*>lW_L;j!&Ku6iH zAm4&)1Q)P7-Ts<9HxI*Gw5UvdY%&d=QEGbWa^nBlA1a6)cp#9*dtjlU^I=hyAM`02 z(A%$Sg4d+H#l-v8cS}B?j8iq_VRU*O`@M*PN!>&gwO=!(1Ihr01Bp2h`Py;`H}@TOYm0JG7Uc~-owUr5552paG9qHwnads< z8!IsGj+?dS%z37Y_kJTCu}dx5aZ@M5xg#yx%o6MtQuam~ zuK1SKu086~;r0D0uQr3M9GW)E`+ExUTS~?_Ndh}fpgT!dz6odF9u+0fCiPx3iP-;6SF6~(06C?^men=eOh*m-xUbG=_S)}A z;^9Iq<?pjA^OO^PVbA#=tUCqng3-_# z_1||g^qv+?<#WhzeM$nHj%rT2@|JbVSKxI69ABDLE{7>Pr6&-QrOCfpcbv9u&G!+d zo>0Cvi<0=gQ&5Rz##qC>;)vQ}IKR4({&#D$2fdNB9=$oxg3QfqcE{l-6Er!`-hP`A z#*e@mD1`1MA?_N&Hb>$$$@&t6@G9rUxNL#M@%?{mc8mQMSuU0ky5UrV zOx+<8B{9V|<@iNF59Fg`WUHB*^@B^$TMp;ttZn!9h%HkOfDQR$H0NErHq-CS*?3tN z3fnvZPIqt4B=^5yM6*+TR%*foTucEF?nML>85$kVR&%zU;>Hgtonvz;6y^qT+EniC zS&quJDIL_I7-3*w3Zco2c?C=v~mE~6K%|H*WhD@D0AFWM_53>wqv+* zh@sB<@E}ajG7=}x@qODFnB%L3m(%2VR4j6|YkVcnejcHcUG%u>^%)W@$zF@PDx zXG=nYcXB_%PA0(j@2;|f9)6QGJEYszxD9oI+Zar z=iI|RW{R*+mqEb*e8Jf(y(@4TK&xxYWu`A_kvD4h4MQLwXL!pcA1-6*ljP_oe}RF z2$G?-|Fd$7L_dR8CzB(*@z3Uhz_QgwM591NBPOvOk+)vINnE;4b9)$G610OCWQ_=> zf5|UrKAZpw;+?n2m0W5f_jO)g2f=SW{9<(eo#Y@?gaO7J*YnPM`wFG8x*xdUq9X=?YegjH3#@1;ou14l(i#82S^G6#IxvWD8JD`lwHU+&NUa_jTkEGV8^f%O zi(D+sr=d2l8`)R*Qm$Kb{Lz|MJP%rJ#M>4ZKyL=+tue%foh+bz8+UI%YK~q4M<4z9 zJYFr(*G2o*c~N4Gz)|%-zYLuUWJ8sC@ucty$iSd~W6Yxq$)>@}Doy#%k&~?w<#52K z3Gpj0drO14u{(Dj?QgD8fX4woN4=!eIY})weI(Q%*?GSzdFVB7PPd~GY+ap0xy)@- z#F--r1%e?Qgc@i^0AvpRbBpU|zQKwp>GXmL=XeM)yg#J0lM(zc_5miy$$d3IHUbzxu(I6rm>LXUyIXPnlmc zoR2M0SED-WL0D&c^xzY|3FbdV+?3YA5 zvJHKiz2PuV$agzg9LbPKbF~v#s&!H~aFTWl*00pO{Ttit9)iBHA5QpH1h?ne|2Y`T zuitFNyXbIJi*j%m`*gb+>FUA5A!y1HKPRE-Y+(k0sIH9xVX%gx!bG`avKkANW6t z_+R>r?P~i0C|jUVp)NgRLF|vOHqwBf8uud|)ULR|ko*5p^|_{v=N z^8d5|MJi)Ze7_`Tv;JBI{mDxJ?Y3R{pzZm}*?vgYW_$m%-GoyniCi0BNL7T<%SwYX z_^rGY4GM%}ujY@KSEv8}BXxN_+^V|T-Obvrswgl&i8 zC+6`qqwNa8%HYBxZ1UQ_dQ)jb_u@R}ME}h)SYVE{5Tc%Cr2`!~)d^UIonZ$&c5H#q zO;)-V_y|)7uf_KGW@Jo)X`7j69!Z2IN+@T`+QKZ+X@8`|RweJ#S@i%>zMp zc>*h{if6@pWUm^vF+wWT9T@LW+&fj%Ej?LQzOzd2V zt!QV%?aHSu=d(?&01_z3^XhV$hq^quAa+jy4hxya8@Oy`iFYyBr8dW!t!$R z+Ux-aZ8rDH{S5`w?{-fs(DAGBgX{7gVaG%4by{Zb_VYu>)A3Sy>_qkYS~StbFx1P& z<@?w63qrs&=C+K(U*xMV+yJyg%9T)lXUUh|gINT|1~|%(xxeKvVT-6G+$6T)qc@xf zaZp*ALR$zOBvIIC^GkZBWJlleQ^9k1@}!o8--#Y<`c2=PuT;JRi6z!#Rxg>EBcWT{ z<&?YsWoAcrw&+)%cFtlLtQ0mbVk@O1IrP7L$HUAC^m89u0~p2qg!ZOZM}@$J(g@Mp zrXrjon1_~0XB+}ITE~@@&DJGAkAK+uN*-xXLbN$u?~kCq4~laGwlTt0?hXPml!C}c zN-QI}qR^c`JKw-)`eD5t&lGE?$}cru;Uf@gGf+7sCRH)8uQUnx#0uEhOM*BP3GDET z9aSy`VA0hvynH(mBnD{nv~BCi_Cu(#N1kAVR-1%YeNPS*bMJ zmcaQop|n$IX2Rwi#W;*S{hAq28${EqcVXr0i6n!o8@#$oQUda19~!j_Ny9aDlu!u$ zh3h{|4SzoeUiI9if$oT@j{6A>fz>Ql)>%Aj0YY)+pHjZx;CCQJUPGuEnb2t8Su+h? zYFFE2)hW?nxc9{c8t+~tfLhvOc0b;4;cliO*W~f}VA0Fr*R>bZ&GCJ^d!klfiy~nq zV@u|6yECMjLGKIwhYelf)-v53A*rA)Q-se<76;zdwKH&}2+@6jH2sg2hX+&3AL>q_ zdNGfz-Z*d!yWW(aoAQxU^)X}S@O>%me*2QeGqZNJYRysfGB!2;zV|ZKviYZBuH5Zg zv{ysk76*R+8l-R#Z8E}m^!mRDMHSQb6i*Zs^o2#x_E22V5dSrd)^iS=H4Ty)mr~IW zkd31yeoaUGI#s|B7YUv)7){WX4PWbF-SFu^I3>VL?#K?KRJpaG3=pyXwuG=4U zE_Ln&i{`=Qth%SoE{;c(OYPSr5?N1T48L}q9D8ct979f$rtr+)3}ZM9;HM7V;gEkl}wp z5v&%I4c`n#^jbylh5elx(Ja-1kiiGZCXZK6z%K7^T;w9bV@@dgv4l50QYw{PD~}~) zo{w7!x|hv)R%o{TA3~8|7Z_oQiGtuiQiz388lcEZ^_EVDexzFLim&Jh_9?6VUVE@Y z)N!>f&&WMG6?{cV_L;%suoAWioxhgoL78}~QQ@akM)BNxQFinDM&ah&JzS;!l5AB^ z#CE)4FA-LDSNn#&WB^sb{a}MjfIHSto4plJMSPIg0eudMWOQ^Knl1-Nge+}i3qOL{ z8HWm(W2Ltf{^4WC-F;(&Nc8hIQ9$r@QAH7X!Tem9askuHzn>FA|M(Cyn~-YqO@|x4 z%`5YH9(M^mtSwm!Bea{>Ww3kRjp{wr4tB&5RAM{}-O^AtrJSOqw#Ufahq(ZG>y!Bg z$_cDuwdrZ%Cb;sMbBl=ZB>Ol3+qv~od+q;Y>Mg*c+S>Qwp^-+qOAu+4?nWs=7`j`! zLAtwCN(6yXLKFDqKmlB-@JEdobKB^vkXq_i@$-TW#uc`=Zg_s59R3zf{iP{!a4D%sw&3V%bQU-JQ=h3n6?Z2HTnKt z7kHg0K|-DwqScF-C8ME_@jofVjfPwNwQxZbJB&mDc9%Oho5)QokrZ|vd02S2F1fO} zV+dn>!M*J=&l{OOBoRl1f{~l<;c_XSq5m;T&sna%mgc2U;_CBj`k{gNWyydO%~D^% z+`8^S4;2bu$%emcUkFl;vD)OM+dt%WUG#0+xPaaN&|gF)1e3ATlFbg32~9tX?l=n& zT9k~uyGGENnz`c=3ZLp~$oJ$|5rIeGT@(!mKfLGyX{qBnnQ1x%PEy%cLU-3Yd`p>> zr5qE?9f%0ptTKW79Pser>Yh8Ylm{f0p$yYB28Ugv^N!EN(U}Bcw0^OttMW4qLGzkE zsyXHLFxq=*=w~7nygzw1T}vk!B`Y3wF*enf(9B*PWA7|Le)N+2hV7HE2YMJy3xO4` zy}dnVRM%Eb?V2}t-~)W^&6PjRX1p1>WXzbIXPcZc4--$5R`aXdLN&wIcy>-)E*COf zxjJ&k@=9uP(|gpGpDzVwQHaDl2i;JT3QYAqbbC#iYsaSIi=v-kokc;}yIw^k^vpv@ z<3%AEvu%I?rec$sQ&qdAbBJ0xrSQ#0MN70z+aV5Kd?JXbDuXIr2j^YZwJU;w2>C2g zchdLuPO$uZvNG zo*|-)Qx3O3&w(jnU{uVL4ugFift=KPcIA#)OxDKJ-TvX^a446CLZ>;)ge3h@hvReL zatD}0fCv;WB}5GJZ#{Y-KI!${<4jLX!k3zz_OV39EpEqhl8^t_D6| zu0(OPkAV~Xc z%bV%qwoJgaCmGs%MhDMyMhW_RBx!Eu&bjW7;1r-n(80%d!~((A7pAW4-LI=_R*y!B zd{*0E-2Y3&+t1TDK2Wd|jwt(h5bG2>a8H?PB|EE^=4xxu&g@=!C)8K+y1V zXFu~6CWwtZ+DV;SIcct{X-u?QLXY>gxQV05)WEp(5gdo(k<()=P>4q)cIo0*I`31y`0{-xhYNAcC|S&KS)n!2h_f><5E+HC)x@$sp+h`8YZ$2U zY_bYpv5|NneMQ7IH8v+N2Gy4KR-8*8|CfQctv+tTCl!hXJ}(9v`#n~}qYh_{zOeOu zc%MEqmULCcHhXSRfE`8oM!HnmU;^6&24aqsUI15m4LQ-B15>d&2Hw%wPyB~anRl$6 zR9L1()nqp4y{@G}#B?uT0)xQS{*3k*9dGs5^n)L<@#nOLy-P-ZRPI#lbN1ugRSk`J zB|k&C6LY%2PGx4+0Z+hw$wc@qUUNrP^3L5yZy#hydQfMwt_Exd_}`62>HcXnhnf%^ zx&#nH4pYZou3<+FEf0$7RHcxPc+^evt{HZwD%KzNAlP5zG>5D6AuAdPCY~UAV?t0a zwpJc#w@_8tJI5LMJ?X7&lL(>{(EuS#7G%X}kn6Qu%H_~L#7@T-1fEzh9b)DTF2Y|* z1WB&V;(MR00{cu9?m7I~^$|==#KL^6dlwP;_FkCi@2+P2@{WMN3?3oVye%@Abj@_D zf-l7rHj~6io4qnggPKRp`Boa%AY2LA!4M=mwV*^g|1Kz-6huICXO4wSAd#bWHe&%rL`Td!`jI$`+b6nB&Mk4_=sDG)RjkNKi zyzaQaI&@l=HpUk7(mi;d`>JrMt&Gix0+7bdY>ET{p-OM+skWFJ7*JlKu`W(QX>X=s zM&~^~LWi*z$C4xwou`5GyHQVcMNI{|Wug*EMY)o)<>ETR=lY)k9H^$$fCe!Wj%{X7 zI^4)Efdr3*t!>%w#^UC2hc3s-7~)D9;^q!MUfr&9ot7g4+hgzwdtxZJmbEwbBflAm zHJ}N+nGe8tPgSjp*+5_Ok)e+Asl+*eaXr2G&IJMcSfqkeN2ZRn?^t2Oi)inMl6?|1 zY}yCm+gVeK>*uB*5?dt^!RXD4EKF8sqoTxOHYrToe|Mtz^Q0nXn_axENRh$N=gelY z{6XF};QZh_Z=BgtmQR6-Jl8eGuiABbd3|xQVyU2Pw|A;7=6T5HP(V6wkPV+utk>-1 zq(56+Fv;#3b_zn3hq{(#we3_%5 z9EJPLJ`QZm8OS(~41q$AOntGO+wQo&OE@#~^eeo31lF*v)Cw9$O>HXUMCm|DXe-F3 zSe)sp@$wd&q6Y0$-;_y`&t-J19a~ciw(hRRaf>C9nfSCOD{DSnD_IKN-hUjEceGAS z*%mxz74{GkLpeES@_oC$p?R^P_Nxa$O7eHD|I zT+C_uL{7vu3y>Ggk47-P0N^BtK39WyYmn$7q{;jaw8hFxch4hlGK>x6wBC+dJIULW z(4c2aSWE{zfyIXA4|>iUeHgsv_k9ud*9b4e1DzvWkY|eYh1O_K+d<#Ac+WzjDT%fa zZbM(j%_^BZg2~A#o@QuBs!E!bgOiht29zAPM~+#yNi_*W@@D3x>;8`iIKt?!XsM`Z z(1PWDKog3~vxhe7X+a-s!|C39p4Z6Phh|>ls%Ze0i#)#=yM(K{6|JKZ2FF67n6?#U#= z=a(o*KGj;LNL5Ng@=%KjOPL+N@1=4YDu&lZ)Dfj@&u?ADjDM17zz!pxmCQbp4!^%2CZXfGrXhSjrN-N=utDSzu$FXNY3JTl3_uBMadC<9=KpMvO}dV)!e$0-i>ph@TNpIGUyiF{22emPMJd7KyyNI0`s*2mNn2JkviY z&e+a+jq^4hLZ&tjm_w7Z#dNb3b$`+p5VHjaN=r?WHh)iiyEaDZuMs_@?l7f*OCa;~ z3x#0!Af(CnY~^R(+QsQnF9Rl{#F9@qRXGJX^s4Iso4&YDJ&cfgm%Qg#k+w@+@gNbK zl|}AF*<%!Ke#yv)#P22*aJ2*jW&ES@m2;ZKA?Eos;E%(G9nkn1)*CK$Jn)z1-ewLQRciXcg8WG-hHKlQo8qN8^V z#ZLOP*Wn}f2W~Z1dolUZ`zJIXQjMs6SKmi9R-hW8aUai-9(iu>l(>6DfM4jPE z69jwH8FsZy%*4AW6QfQKa)M~jetjwHhI&tfIR!jw>pHBR2Cu}V3FxsH<3+@Yp)@Aio#Xoe98cd(n=C;7mKR&s>WY!4PD2$@V#O!~&S{(7K=7Rxmt1~%_etF?~Zp!%3 zarg@8X9xsk)0ecAr&S}#l1JyH5Y*a3Q#Ea3pHPV!a+S&t93UHwBn$VJOjt?>8R+!< zC1j3e9v0c#&<4=cOt9Wk{N-K?k?A-^ZV}dR^OCYYl~JvRFo_zyQd|Da>PR0c2d2=D zvqfEqZE`L(B2r`wN#(j)qV3lX=hnN$Ad-jbwP*5|CO6C;_SMbWo)i7KZ(Pp{3GTP7 z*Jymuj|89CrfVYPYKD z(*NGHszd72t%2K6Z_nW?8hB4`emGUgq7)0i+qJ(#2|Qm-=b4|;Njt`1Vwl(Wjjp7I z+oq$SAjBz#2~m-3qVU%4t{3ho?vBoHQHSXoG2>cKVilzc>M8>GQjTYn4yZaM>`NWh zG36LU!jix5$EOLw%_2Y?nze`-yq%S&r|h}eU?YaYr3_w9s-og4Ic`;Zui7rz_E_Ay zU;-}62$OSd@D{Sc&Ih2X>X!FrM(0lSrX!!Ms;&R+>6-}__NUf@+JJ9v)zy8TTKsTC z{UT*#)EqF^qm&&9xLMc@+{`v{FT^$v^^5lJ^|hTcs*9E3z}T6HHv?Rj+C%WL@(Zae zJD%1n&gr&Od!B{As3KEt@R%UHxowQoSgsic1WVepfsizRXX@{8I_5|Eo!1j&oY(|Jtnd~&PLe+j`HS7 z^U>|NCy)(sYR;EeZ!LuO$(7$EN*DItKi}Dm4WLFiMrDq|b3d`xA6y=twG1!gUh>Y* zL{)c10izUJ7sl{IKN|1QBwrE?zpdM+!B`<`b}v5lj5tBO@>0lb9~*(IUbr9audY+;ae8jzIIdh1#f zL>%Q8WhUUL!}}mK_-F;i$NxkKWTT#4!7$_R?sw@f7=K-APL}}?$f6d?_;Vj?VipPg zPv_l*R)o|i&&#zKghTD!&zG?=Typ&&y)+iK%2!upXh`5|kM_FJGH`oJk7vf6uub_P zO{?bd&mSQ}p$sn`4zLgnu()@)FRzjqosxRg-ZTfHk1f1>SQe3*OzrU`-K3|$&kxU!I5Bv0JLhYZRKq1uL+ITPX_BS>IZFsHfuOd;ZiiUjT;C$#&K-aw}{A)vGUYZV& zg6@??Gce}xL9xh=gB~)x)s0oY#ir{gtu9-9LkTKU59O)%C_?)WLX3aq^-d5r!J@IaaPjT18gMj+RtC*5cSRQg*!aMAOo_5UOK*7qj2bhb&%;5cb(p zjmIQ*pTieyGtrZVu}#|Xp-^5Sp6I(B!9b#2wZ~~XX|4wy0jQxJ-z9TO>R+*Ed_#QK z9h{Um^)uFn&XV&Mu>-=S!HgO*BYKuLX|k+x)R1 zE_R3XLrK)|(OV5*6?sI=_puiU30uZpsUHmPnbeHTLwV@(pXMX{oHh(;h#G#PGn!G< z{cE)Q*8b%gJvr`L*jK8H+d^manKcf(-cApojV(6$kpQ;?jz!aa#zX`_SS7j2h_cA{ zyJZnD>vBN`WQn49reI)gZWqWByO$V-!xj%#?I7lSsIL5^O7;pgHFeWVig((68wTDL zK#F^^@JF$>_0y)jKVcP=mMf6;P6o7@&=!gRC_fY&QLCT&vUpEnh|!34bMj4W7lTd|6>Vurqre; zL6*?S$G>}Hd(qOD-e;WG5FW06-X3PaLJnL%L<28ZN-++Q8>C~mTbhyo^#V|_`y3CE z7=CC(18l!)A1VGEZ|(UK>(!po*0*Wi+D4q9N8!*4Y_%np&e7+I$0dgmVY+8RD<_Sb z`ZuuHcq(lC%AL7(i|eG7Ut6ww2X3ZC0d$>i#9VDu-a6L6S#j^7Ol)x)vuUg*KW>gh zQv!blHrW|nSNKpaVjEjj)anXAxT}Q5OOVjgWlU4W6Vhh=@UW zYLj-((FMNN*|e1Hi=b1JA(jKh9a;=u^ii`aV4=KiRiQacEwSv+>MQr>xf}n8e&T*J7&P zlka-v_Btu@kaw@HGTz>v&G``Mc9G%dpb$_Elr!Vrz0x89VF*}5_vPE`dxh3Q9EIHW zKw2)bljLx@Z-CRE#}kE4ZAnV*ZU5Qg*UZRD>JGpY2vAWO^Gb&``A9;ZW0ox9HrzOc z!{&}rNucm^$p92^00=1XP^g?B6x&*;J|*LOr_-&FfoSq~LfDW}9M87O-A>;@s>S8f_p z#)v8@1fQ&1gsGQ2(bV7ia90pYK@erGFfY^W)KQZRtB^cHmhin0zFqRZ#mgC(R}qeC zIDJFz;Ts)_sX_2`vDucQtL(SE%_8LmT^f^~tb_(Q)!f86Jab(Ho@9~iG4i6R+mGJ4 ztno8E@m`zv|64_NuadXjUhsbxxMTp(L@mYqxRIV7CPx@=>C^+f6A<0WQ`T@luJBH? z@UFSx_m3VZgc16-;Dyp7k31ZHvU!S}?7k@v$;kYK9$c*Li4^Si4^FqjZo19C#+rpy zA)SA`GQP<)D?Rm$5OKEI4DW+Z=*?vDsq(QVH3Hho~$ok$`_K-D}T z)9;Bm-8It{L-suv&6OO9oq$`FN*Z>5TMozFn6}SrxBJHIm2P!t3TMpg@8e(;+HK%&{T~#pv=7 z6<(3Su16hG!${Rc>-0O26Iij3J0R*lg617wC0oeJLTRe~a^iT#zH` zFhx|mgQViO5*cM%GG>#9ySFCodyL-dR)u}qzQ8*!d&~BJ&M=mPJjIwsad7;Sf#fHs zhC{=4b&8)xyRvxYPobkl6R6mTOo$tNUk`KzI8WOhTg98t!=t3qV=H%To9C%1eEN`e zmQx$ZSMcAf!~)3q2d2WNyPYvBd(tuz+6!ui*)5uXM2J=4E;iglc&etkEf~cGEBk+N z7{B4PeCblR;pR%9Rm^F@PBQFoXcS5yalSJBTnYqg<3B=56J#ry)0x= z#%r*Y?^xZST>S1%0#sGStFyHn$s;PC--e-r)KZ`fOlyzfz=93Rl85J0i#=ueuP?gR z5130gbFqsMLvd1Oh&bnMgizjrs+O}bjEi2e9g6!OxhSGOPNcSTZuZa)6Jx7@GG8Muk!E?CZ#_c%x^owHJr*FM_#)uWoLp zUHHE3y8M;Nz*U%5Ewkm}c~u8`al2O&Xx&~$ zsFiC&aT9n=t6p{{{wzB^n)}`l>)R$y%_k;P6aR}*TD&vGEf92*1QyUNvo+MhZt*OZ z`m}JKOA(X~T3vVu&pfd-o=5-vdq^KG?}!VbFYl4ztnEdv9n11@n)J$8teNi~=eCEMFu-jYJ1miuwMNGqgOLYlVx?beG}F zadymN`d7i{uVP9<X>;R6-3V3L5grQS$5FI(p2EPdQ~rv7mt_GYphBbn)-6taE8_WiE#EwLIV@ z2x-^>LK(epSC!U4`_h!=x?E4d;n^S(WLBGH#J9F^Z<9wVST-8kOrF=PT51*WX*o&e zP!UN30%4UEkRmoe*MQp!SnRdYJ~QQ)(ycK5hya_ElTK;7_+3fpt5{Dves#wcot<+% z>J;|y_FP^J`&wMat|oXXpyC{aA+sb+U2S0YDgXj$rtIluQJk1U0Y@a>cl<ewp;#ohv<_mtDS#I&LXm=YmH+(t(P#A!GepY3gQB20hq&h2yz$?5 z4@Ou)3bj8{=@o2)2)}04y=hfi=Z}RJMJ=^bn*n$i+^vUV!8_Z?yYC+SBrzUwG^Ft~CtiI-9okVVxg~ zy9aDv$({8i|wQZZ-*-l?S$^4epat(zsjzVZ#R7c})hHQ+&3 z=W5IHDL=U_Au+%};rd65hjBW1KcWYVl)DDgVzX>0jkCCqdDlWny^TwO-ho0bfXQSQ zz3(zn-1O%`Q?YPiNpjQc)dR(3Mc5*-}j@Wl*a4J&7R?qpIb4}cqsDEB8(Ph_2n zg`yu-?q>gmUo8flHp=%)RWx!n93EPT@8UAp1+}ZzF6&IfTgcO`x~jF)0Y^J!20oQ*~zViy*F>4GeKjCB& zk6~ob^|(n?q@UJ9ID05_a0&T8%OT`XF%%U?#%b$ga2q$-WgbVppO{%h98g^kZQq#n zW|PG|Xi7^Le10kbn`()O1j`sa^i@_W<{pIdBqKF>F(mwWbSGJXqKC z67rEme8~wli0{ngIr_=N6b34KEP@*cqf)*>>u~F5GBl21ro;@T80>*V@LH1jPpwI$ z?}gWGs3BXn&b@H#&5?zP5I_6^FUiS2SX{(A zM;JyU4@hzn(ws-E>>X!#Yed8X30O2sWBJ$=kFk3CtegXT|1nfX7;2sP6JNf4eYCCMqh*UN_|Mzc-_y*4W8i zCMZzyMEJ%oa=HIt8jnDqRK%{~-Bp*cQLQFofy^7b39<|)`-G89>7lB&*iDqqjZ}0? z&GlcDmD8&9*-B-0Vl$L3}K1rtVC z@yyrts!6EH+t0TtbCDl8NhCLmH+m~arpuDILrBBQcZ#jA%>nJ9x0xpK-kToHA~D=l z%l`4^(?wQ=rRd;^UG*FV5Jpn%8m2-N`>|_{(ScQI$d*JER~!}LE4I+`OOF84xIO-L@Vo1Ij_4H8FI`iiy*DW07h+BD7+q6oT#BY z%2boPU>7;qbV@7q$IsEtYVz|snwa0w&lL62*%eX%>TQQv`5>>ZdcA^P)lGTYEQvGG zx%s^utte~So_a{fMwG;4`psGL>_nO3<& z5h9~+i@fswDC0Fj_P^`C_*`jjxP=UvHeFnwnG=hK&MX*Yge=Ee))0RZbz@|n|KrmF z#jl3|vqUSgRM)Z<8dnb)p-sOvUiUx1%YM<4&CG#9o^h|Jr5bEm^6dUybtLPaE00At zqD3VNkxd#2eO>k@a$u8Pe8hYNnyJx^T=)vPta(-h;^6E%f}d-G|5dyWDXfyP^D+^I z-0jOP^>vTpLE5(y81FJHmbK2PG^03AT$5K0%1_%jpURXTkf#c1U-->dj>T?cnns(3 zbctaNk$ncd-%cXi{rc&CiNc8doHQB6FR}u|5N!!jpPsf`ZanHvf>+*DEwDl9)@h7U z8ns4~>F0Jx#^nQkPpI2GJ{=zym!{}R;{+FdB7TU>9ETwjv4y#@=xOozY*|U8f}N~h z_?S+S%iX3YfW4qD{<@eV11i%BwT7?{-p}n>TI(~6P1C)l#4zWij@!owQHi!J=_%~a zTRHk8OfLT~oayTggNzb|${y$ps4xQmQGM>O8xN1GO}SVHkj+CT(L;47Zr-5j&lnQ> z@@A1bksQ~uUzkhl3L{rF;WQNM{YBw{!1~NF<e(oXID=F7+Sjym%-tFMaT-SLTZH{= z2c}dc{Goi4jviEgp488@>I(Z=(Fe$H*raNdb#g*R^b;TutKDJCCYL%oND&vm3??cM zCalw8$1lz|TXP9|Xis`VLvar1M?4yf=A?UEH5Y^s$TM>LNsR)^l#Z9UAKW z!PRCVMx^?;HPzWv`@l@E{Q8?wsy}kIe@TDvY`x`VKMMqB0KDWs?*Xnlx-Nhv!DGvJ z2>q+1*o`Ohab_uD0ldN^#qgU_b0cD3&B%6}{wwR5v?B89t| zVaoZb=5?sAdfHbrW?e0z6 zo{Y^_{Ep}Y3)<`gaj@Zk4WBnM>v(?6wzee|50|PbmDXv&59gj>Eu~nQWNO%PE9+#h z`2Mb0&Wvm#3tP+KA9I|K#q|vC49kw6az+zZ$otX-fqZ${n)9svNlLjxFJZr1meM;b zl8>JdZ?Hj{YzNsrUu?7GT(TV?$KsZn@BFXSwI5ufTPN@wwq;Si3Do-<>)2tbt{_)a zuX^u_N6T{-m3J@vphHynO$uhJGavT-X3L7Rf+}L_xr?(mV4&#*x5kcNvP9Q}B=O69 zd12n4?Qol0#7D|@g6PB%~=u=FKSD+d0zjeTc-n>k;Fu=sT41u%N)w zFTgj*MZVE(QWM3@;WV&u8&A~E?Z@R04cpa7vCn{jl``D;sf!araClHoYSbYgtntJ_ zRPXcS^W?x5>VeA)r)S4eUmd;_ai5;;$OK|5Gu{3f8Y6M!C^Z0bfnaFo!;s4qYy~;wuI4%MLp=qxBo@k% zbn=kYp7j1|7W5L2RQqWx!`k@N;GvgA#@+YjsYgTJ=Rk*1UZ2>?Q|lA4OoYe1_jpRI zmwrJ6Iq8``Cum{tCO3>$XU)v$NZqFjI*9^C*aEHkuuhecA7v$VjA4B_#Ep_E$YcNe z(klN)JqeL17;g>L`Q5jWMsA0oicVo6|{c@A~FcYa3f2c2?0=e4FLeyHNb;1gQ@{F;#HUD6s zLzw(}{W(9zK%sKQvTse6uoFuFxQCuwE_CmvG}R1AGi18WwXgBoT)dCeY2tdm%(8Rj z$EXnsSEPvCIHn4ziS%)k7j^@rj_nnKhtI+^jcdtEB{)QHRiNuBW1lP&nxQLB(>Hcc zdjE2-F1Ni_-Gg7=e^4peLDyhj#eqYY767Wu$~nU%&PD_End~{iyYpX(o|MJ<_Bx|Y{_1EsH-pS-3cGD^? zd3^a%X{g7WD3hO1qvl$U4JsF;562DD#m}{jFHxz>Ykd0# z*s3cJDb!F{CfgU&!+f{MzesjY?n$QG;97{z_gCy6eHxgzE#;V4qTiKsh;pi_EvmeR z?(OcP0W6=Ydgb(C#;XtY&m3npVM*UpuOFyxd++q-@jghcp;>P?n_17%5dHYhc)6GO zK#PUv{hVK&ceR)Yy3bX9$_TdUp}dx}%wzUyChxDa4)Cbcf01M)c9T+e4zx^)-3Vl& zdhR}=Y+TKWRL3I!&yfZYl=4`!B3Z4#qjqIyOh!uH19A_fs!Dd=&+N)SQk_ppA%-np zC;?XaTDk6cZnNo6X4ENc;Sz5n!r zvDhHn{XNN9M9+?{gcS$ zL}?u*=BdfGd~G*QPR>G91CTvTKQd|%vD-i?My4GzC_?lmD{)Ls)7a)FoM`>eA}(S^Ueb|GfSa^@C$P(3P|QdO*`kJOEMc#Tc*hv(@m zZrziI8l!A8kq>xylqYRb?le1jOZYeO8)OqhQs!)uat5x%k_1mNh|#U(8ig^cb=(D* zj_TNtZ1PK*`bcc~eV5-EPe8d5ahnkxDRT)TS`yibd8CB=A}tJ?6c~@5KLvwMlWjNZXJITo?KqL7v27Jp!=KG;4+;6dxnWpK zz0RXhpIa`?3ejstxeK|%8Tb}qF@ZVotLtfS2t}&NMZS8UV4~CkN>m9R&~m@yBsFFYLxucVwtM zKE2_%uuxQ7G^-@ep!pxV3w$1)xqmnansq7HXPGYtxwbdALsaC@SwJdJ?b|55u$sazWK^$dsSFF|1-MUqv5!JiH?E zKS4{kHBZmYw7@V>m@srg`4C!~((Yh#v-Y`t`56R~ZBNlut0#pH0A;mth2_0?&`?pq zeSEbS(H?)?PpP~)->T1@XC3KB0|^de`ixeuu%CLVH}Md^rcb!AA4~RC1Ib!A4w80! zM=-ri3~7%-FQD6*?^xwEy);mNl{7d&#A@}ZL1PBr_Fo+$2Hk3O6IVCIgR@QEKqQ|t zZ=yV%x_0(m?f|6=d39gYG)@kboo762H{Y(v$WNIi>QoNIdTU9+-AUdYfM2)vx8yz! z8f)dky}J6?6|Z3wRcUi(45xm1L`WR310lf=Bzn50ArL~k7jn{C3K^y<13P~hF!Al` zn=QVASf(-di%LfQ_dL|_ooOVD#2C&m{N~wcf$naQ7!jey-)Z&^9mbPctnVt`l1LD8 zlfT+C!>NQBsk;0vWXR8kxchV5UGgWDi(>y(E3AKzKD33mDeMocphUNv@5m|s6yT%-&0ju~(pM3UKu$`cc{h;?ML+blkix5!%AV>iORj;J!6G>uW4a+{U z)A}!4s1cBHi?-3eBZTR&`-fn~4S{#NCdxN!9(KNzl7Wa**p#B29C13eFH!=XKVp37 z`3Le0xYlQyXE(1f&+mMmx?WGe-^9{21Ks&9sg$;kzVo{7!f|+%6ES!YQ>actcS+N@ znma5)15@s(p^d1ETuqESnzf*25H>u<3N>=jcmyj*mxwEw|5nQjdJjpM8V3odoje`J z?JDf*o(Y8czW!P2X{x>Lr2@$ilZ?5Z#%ma&5gsKt?pMmpfksNPXZy^dK?nq7MrKuU znu<9Bw8zJ<4|2i`#Iv(U5`n(!uR)9Zj#HqXx1!DJunbC>%q(ud zv@V_$xV|G+v&tz6bx;~uPt3``u1vtYoM(g#0{ML0L4p?+! zWf@n(tJz@~=u`NPFqhXMaf~wHrI1}`VhjJFor~sxVGJ2}a^JfRroOIjZ!a+}Zqfy@ z+%L3vix8{EI-ry~Y~z1~w#e+{sxLnyXdXQ|{KZk#87#L<0u3&6;h` zBFkC015$c1Jn$JIR7@Vt@V=hXqhKLAd9RqltTl)8$mS@%YW+mg*=^enKXGQ8o7dWE zzw?**HWP9A4KKce6o_NSRgDHTF>|!2u13d?ii?%`sQi!C|VvIr}|E1^2{i(Bh0u{{HT?YQZ0LvGW}9-pin~_B-N-=AukiM7L@L zdECAa>v#E=l_vMh$im7yt+4CMZQU~>>m87EFwG$Cl;&{ArMAuMvZ_9A07Y9Qx4qn0 zN%6abf64Iva}zDb<=EksS&!xw50Rs_DPwM{7@*1EvM>J9tw6*>P`G0?TAwhT%t`!^ zHQTaIux%XC-eo4SIvM?WDYB+pbhXWxGLt!Bn*e#vrDWP5sAx{osMgM|s z0RbbPm1U!FK>`NJ$f!hGv0psZ9*2k@$HBsFE?>0E3MzTJ)rTnQe48@&bA`0hubl+H zddJL3`^md7-e4p$LIgvqlSWqNCu=k^Aco;N*gPsO_3z?Jnu=3RYBuZSs^czDTH@su zpGOYGhpeHb_X<0yG!2!)SdpHMNb8W4jmKywUF1)r?g#u}G@4?x^2x5nI%b2wf86~aS70qLo}&oS-AZ-y zvkwmFIo{Z}p6^YLw=0|JEN}VMn&H^neek;8t|s&9esRZHcs6o*`4(l3Gf*_2`DD*-;|%T~%3?ga!Gr6Zpsm#gvfJpVWU(OS2^c{Hf<_Q| z^b(f%6MS2A(G_^`s!x_+OR@P0YpF8`u4#0g4xi@qgbE^VrnAh@y*~PW^hh(s^_CO( z+0(B)PDwEah(M1?l&_PGgV&{Y4l}Jq^dvzh^PXMg8QkAX<%{D#sRQbJdoN;xd(iUv ziLM!U+ttk46;y(jg>rxI|NRhi{o@|^9C4iEOBK9^=}*r=V#@*3cxf7)mgC=5J`*wB zRu*we~<*~<-)rU1PTE}7an2$}_UoMQ0(pO;;0)pY#;5@}TX>ZPX@YGtE-(KzT*;&MMdPps@!Q#^oP^43#c z#~G>pAn31s%#xDp{d0{j<^e>u?)4qcn>{a{@`kRYvq%mUlld&CJ@>~SoSdEtSWZLB z&fsL>e=9q(8o+l7{WIm^VcM+UxX#zU5yg^nTwPG}yaZ3X-Z>HZt}rCkij$`jQmBOF{hKIoSCBalejgkUqB(-c279p8q3 z$zs3TUdz2b@S{OTnJ9S?>Oyj2D*! zOALJ34Bh#5cHfXNe&|KX%DrtF{Vv{i8nuNNRsJ-Ea~VXMBb}vNr_p~(da!H~N*I#E zrpjcrdov~H9vjP6U!4Wm^b2q7FwOlnIKU5JTHQ-+#}^_LzOtAwVtH0#&L_*O!EZn? zfo;4hPaE>ZAEm5Ht$N#8E;CEkXkl)3@A{FN&nxqPh-@V=Y~fbr{mDl)+(yLwJ8Zej z=qTHx5e~k+ZX) z2sNIh^mEJ7Qdhj0p12<|^WLk+BDwdXPy(dE!aV=p5}UrTU3K@4KIa&jEi-2~@&yea z#wM66(XS4D-+8N{>bCsT2(?ZUcuDeOL6+aqGd{{Ffv>)VuoHx%P+VM=(xN_ngi5egr6SrMmFD;-b?6;e9D+FgTqk#v0R8Eu@wzz8*%BS1oe7*JqC zE6k=EnI7}}CV$?TB+8NoYG-yr>zH1d{NoH#6R;5qfrs^<-Rv^pF8{PhP(J7?Uj$9Ck`0vzM>W?7O z+}Bl%C+3o`6h6#B2P=1H;$C)I*A`Ga*R%10?<0y-NVG=%hk4T$=@Y|pU*3GU)oo<2 zdsoE|`XWGq{)ITsR}AwBV0upth>joB|Ki;;ibBXp=yxL{apeB(a@L}jz5Xkb2G-%JPh0aoKr;e(ov0y!2 zka;M!ZDz9p1X7tZ?b*cTBQNJ5@bO~n%xm&sEXkO#>Oz!PO~dW*{|mzdJp2;4fTmeZ z1OR|(vc#^E?soN^BYd5E+N;0T*!gg~3t!m+n7{=z;fv2d``?f48zcVlr=KtNA)Q_K zW;+doI&_sg&6|KA}10Lqo+NPWa^x~sI<)mbZgMO^p3SHv!cJ-$5>#UjoZ#sn@X z)V^Rd#j)tI&t|ik^=B=4a3-&Z?RNBi_xJZlfBjfk6V(6!%H>G?x@rnvhpZXJ1TLy4 z1VKFx#kGiKfvqF70RSwMWtFj(*wxoc_?oI8$ONv2%?&?8r-q=p5hy|k0&)=A005@R z61%#)T{Xq7zE>|_JicApVf(dI8MxL8Hxcuuc!rh)ogsmTwHvrp4VRE5 zXdHVCo%*;q<+0CW+UbU0v-`dlho8?`KDPjXwq=Q35oO=)nyR&FubVHw`g$~QEr~lz zqt24Q_=oM*izZfe$p|zzw0HqaO$~rNxcJ9#Xp&7>dm@wp0Bdlh{`yJ}Ujo+* zb0f|^Ypi*#xmx8#2arLAz;!KSVQpVj8-}!!Oeh0@l4OfrwcqWU>Ri)a5%a@Wl}F|QD4W2Qk5DF* z0l>9oiCqzGuQDET%{51X3xIS4u6hY&LKy(8A=8n1(_P11B76y40HpKk<%{_A`SXYn zxY$o96UqRfFUyhoh^OEcVZ!T>;eD^}-~V$7TmYmaaB(R@+5Y>eVi^D>%e2ba=~fy| zc^x-*+DqU9ARU2=(zF)JBIZq%MTlhpTvo=|6=AJ$j$`3V-~u2Wfs0lNWjj_d0XT=O zu`9w_;}Tu?61V_JN8o~Gri8MH`eT_DOaR7YI#NHzTH|R1E&$RIxFC-fr^+H6_6KN9 zrX%%ZtTi4cZ~>5xzy@;$1wc9i7f>22m^(rl(26d0MU*q$ z6;bzEqre3~IszBaves5GMKYik-8y6TWA#JbT4O}ntBnE|0O<%^0Lu+SSw!6{m_iwl zO{r5}o&K~}ME>|CZ~>5xzy**?OSj5|GT>ZF4_%P Y3kY*Xz9Xxr8vp;8S$x@Qq=RsK8%D5cvv0 zAUcqWyo`?b*ZoC97t6UU=8L1R@Ab<~+?FqkO8In|(p1^frW0K?xGB7pM&G`Qx?gh% zr{>KDM=i6=R|VGRh#!7(5#Ik~=M~=qlbFc1^YQ(_Z?7_?Tgv1xG&npck*QX>g1F+e zb+w8}Cmq@=n+*DOR2;$R;(FB8mZ5yy5_FfuN+W77E&qRGl1XGA0T2IwV|=OGJTv)})ayPsDd(n}fRt&CH0$;%&I2cN zoWeYjN4#gid-LyOIcc8Mav=rn?mR@@l&1I$n*y_MR3CXfxf%9rDbmfIm7iO!7PuiL z&tPwptbj=eD;q)i`29jZ{^tq&vHz5euQdvtAc?<_(yIqlj(-q@l^*r3?3dg>y+_;H zoH+A6&9AI1Nto8SNSFX7_1E->MGlmz%cBIYAGNuhv0s<|%dX6QU`~zLti>-5ENAqJB!}#HO>mMeT#b z_j3^YjO-kptV@Y7t9*%IVyP#?&&azX;$lrh|BSpd75hFRZy{DYlF^Rpy0`fER^L>^ z+414_YG>kakigzD0$Q5?%`C!2y~nja?|61~O4pXP%(^%4#Ds4sonrHk>1w}X#7-x~ z4z0}=9OnL(mRz(#h0L-Ij8HmxCffj%Cy;--yS{&3)BSTo1@ zQdK^0yUC<6#qxki{YS&l(k&=KN^Uu*V=Ic~jxgOe%n4~mUH5AkSmx4qrP;LR)7}X_ z4hRic9c1qMo$r{JT4ydk$&oprsva7oA1P9p=(*eWz7?rr=LX_65R~@huZojAW#lkj zzW$n!0#r&#=){oH2wDe3Zx$z3B{(|kb+j$*;Fg#fe_3P}QlC@k!ad0(4beG>|H}!! z0&h1f#V>o91xk*#vb>fvOr2oj%JkRYwzc(H@L z*?&oCHenA-rr!o_yr1izxq0B!FEcQuUYyBoiw~kE9M2wmF2BgOzOaM$QRW$7=>yIz zseUPOJLN4O>4w{3w{6rnR+#%aW1iffvdk7w9|}@%^z<8-gJ!jN1}d%))<8lifVj*_maT>gE^wS<1d0O|kLWs-it6V*XPe9pF~qmY zWXr?$z_hYF;zyW$!k9sN2)6aIH#aOy(I&FOVM(G^{9bsn*7sWt3ZRh5Up#XC z?zcUe*KHa0!#_->dkpAd=ch8shp^1+q6C;!Fmd)TV<}sI+8J5+)p6$Ez22I<_?=uk z9CL$v6~8xapUG`2Og17?7D>Y`;0F8O?rB1~s`Om`j{SDF={OqDGQU3j9d3T_ru0s{ zZTO~{`r0v`ajA7KXpzVCr)|CR_uR>)8|A{SgNhS^@rQ5a2bYQqINyyLb55w5oQ_Bz zNmMto)Aj9nMq9KK@GnlDmxYn>9V*O&po;<3jx$T_TW)9t8nzO`*0!x))i)^@DK|bQ zOD_`!zT05QpgqHS#=%iU+TKj-l`X()N_9c@13Kkc){}pJ(O+1IB0ym%ia#EbGV0ZS zHNMd3nmip9-(sgJW7$zi;Y7Ss@^h1@HgjninJ7*~UMrp_77v-8t?N*ykByj~TpNWe z0ou02;$AmKX6_c7g%@2i!}L=`JOyEal4 zCZGIV_oh9tAOe{;d~H`TG%=d9x5$5E0V8pQ$qJ@Gzs)C{y@(ZILG~zqQ?y-;*m};% zMn-Y;)z=oQu*>zmZF%4g8Z|BL3|i2AX%L6QWPJC4V?Sm@<$N$zxKNlS3T--5ltlapdFQ9U=Y>q~mSl_VwVo5E zmK_91iALm=M;FSJp?S~6k0xg-s-Imqzn&WY>iFrVCIx{;4!&5oIOaVmV1|W&)4xnI z`6cVKQgNaT{GlIEMH8)3ihzVz<3U>dF2aaS0F?xP^Ui&uC2m`6C{)mt)xBYXRkwdX zRajk7%)qI~1BJ_M>GygFMsN>alHzZtaBum03PphzT8%#fM*GLSFZVCUn)LTAU$%rG z%smWPijz4K^WBt(1)5*+mfS}TxIbD%D;31k(i9*3m2J|5J1v_nU7uOD32>`54$6k84`i5jhI)k=S&M3II4`SB=?%~3Ks z;xaQjqIPNuN_G<9tY`BYEFrR+UDDD_+(!X>s`Vt5^$z^Qqo6gP(+-o)ED_3L zA;;kgA_b8#dsQ#X!nL}1GCh$->mK&qx91#)t?SMaSgT1w4|SBANs$yqKap`NMqjqhn^^*Htz9*EqZgjm;5GiMSm)t-#a-u={E`qq_rP;Z=_{V zR*A$F5lG%_!y#3-S(j4#_9Cc5NZo@o_X8eO92}hVIp<1i!l)LZchzXTYrZ?As{FR) z7)2JaUo)L_3oTu4?{j_e>M;|%h5~U@$SINpBY(A6vM>klLPOJKI1j>$HZ~H6h)x}X zVsIJC7Y>eV3?-teBAvoicNb6K14gFLyxyC=Fjzu3AJm_51sx}hnAT=c9KDXU;KQC! z&k6c9<$Uj1lUlstpjbs{zQ#tA8y}>U1yoyCiGv@2K?nk z(#~hbN=I|-Xlo{i(qV~R)Xj56{_=b2a)$~se;%!+Voxh3#@~y8jo;I6CN{B>7PAz})lYB+Nnf5hhzX(|w*4nV`J=cWGK?6@_-pNuf5HmWL zueqlef1E6Dubf_1U)2RIp80u2LMMOet=gaQni!cLibNj>c~g7ls>)BIhixF3^E5Yx zTOfmwM6AQ^ydnNK_5)UIzu3xc_sYh?uuj+BUdBL@uPvn?%yupxF7rm$gTEVtc6Hrh zpZ;!LVFQZ60PzeLAZ#C)U?na~dz=yt_7#Xf+OkI8Q;-=hRXV3A4zX&q&rneWiG4=O zUUsVS8yuRUp#e z&b~q7fjC<90V87i9XbSR*zaJ3Cx@e|;#d*hf%?#A8kUY*6cAmbRgB z#`gg-;E6PFfay5i+PD^TO3yOx>c5D3M;oV;5Lf%y3Ja40cf}%YC;7!(ogV3j*49#-&#s#P?ZO_-X zN(q=!(EP;-79_^Dm|7|jYh@2Dp?c8?-zqKeXw=gqtY_j)AA8Sw+v?=^6iz99rw1f? zI130Ah0sdmQOO}per~2K6rD8UdH!Kius*TH)Kdwm*rUv}-|d+kG(75=9-$|w$c(Ar!MA&-jl20`;oiStf1v|MxR%Odp}NsM4R>ab&+ab% za#OCJ<_BOszCJ0VOdsNW<+7$QuL}gQTOUIF2Hv+;>OD0x-Rnml_@6y%ZDgkyL@#fV zKnp0UUX3pbB`nuV31bvNJ!SU=G^Ph$jc*=YRSO1;3~qZPKL>ma3`kdxES9`I(d?H; zi)%PWJbPG=ECrY*1H~&pzPw!~1J3d?N0i`S^YS9UK4eT(!O!(5taAN3;G&H{)HeRE zT0a3L{k@1Je~^N}@J9cP7UgolY<_9Q6NJRUz#z&>M)Ab?$8!xIeMn{O>nxz4?V++N zC)X|Qo1(k%N~{P)7#$l;spJR#(0+ct?g3`-VAA%jJy z<)H)AGAv!Y$%CmCN1go$kTW;(JFEfVT^Be|JVs!v5Ry)N-TcM+tl)-a7uS{$Ga-ww zk}V+D5fG?#N-FdRF{oG_0TerBcNKKn0dc^3BK^QpCP;u_wBCO4z1kbR2L>KYt`n`Zpu2*gD7jW?13tQMHNx4cla8{FAWIZap%& zT9|IxePk(?)<5~9qqQv+0*yXLmsD<<`xM_69=@X;&)RGKmf`U@@TSgjY zLFT)U5tcA;51y(jqY>fsbj#EA zwXkJ{6BCp)aysh`N1G>X=#W{Co(fj~q_M14L;EQ5k@^D9=##6n7c_--*i-HIqKomz zFQHxY;p{i_?}qMAytwP%WEh}B7t#$XFL=8J_Y7@2XinaG(Cr<~Okt90agdy>&%KCG zBF0z154BI$qY%UC=8-2-FfcIoF7-$b}wrK3G#ez{fh7@81lfMNcnUf@2@1YxkWExa;3VS@^$ zPTTQ$$$BQx$Pb`v zLFM|$Y4qU_?y%ZvUxspI<&R_xf*`C=H)2^;4leFI0u)VISrMoC3kLl%6%r6ub?uK( z6Tzqn7WI{16UBHI;bk+G2(l{=1yLnBWyz)QH6866eq%jVIc%$h$w!a`S^gG`YyI5% zR~r6c!Ng5XeL)7)H);v#65;)$rVK0Wlqz_T?K20=xvTd2ABZmvl|L4`esP;9H5+vU zff&?-m3tV`YoSqJ59r4!GSyJEDs^r_+J0VV4L4I?P30+fHf5E zX8_j2W9G$kc$bFs9P1-v0>KdDF`g0~wqU&E^zQwAj?)P7c;4tz1ou>Pf%1Gu2c0#LF5xpumZqR1 zO#huJ?$rvR_QXr6JCH`Uq(WsfTJh%pe0H%@k4)ZAO-Q#XBr$|Fgb&e))3%|npG~(o z{nkiT0MW4Q`Fcgls*%Z#wLdF8{l{tWS*Brs-3>0Huv3!E^C@t&^X!fSM<%hdeNqDi zGr!qakk|Y3uz4IED;8X%l)IaLZXK4xLZ5KNT&#ek#$@l`e1`!=+>^Lmd zer#&acuJqW#+Np!pu?KbBasDjC=urhTC+#<8k>f0`6g@Ap3P}4&|U#F&RuV3|sIm5Jbt}1?$g;jrNn9Fztg23syxCNvJaSx4exqu@(O8d{)ThN zUfk)0>T_k-+~0@%t=x7DB%})LLOj56*j~J^X8GeO{$bqZ4Qb_`pphEuKxCpod~t3O zVxhba`id&{bF6q3yd5%xx2!|5Z|5`(Dd&1$!mPjumVW}if~Cojl$76{`N)rH_IG~% z3IDZARjcu4z0T*WL;wXYjRf*ENT(PN( zcE@_oSSXmREhErvj1KdlSD62uTbkdXIYHKxhy*7C7wVRyqB1ylO(M?NQ&}jWX{yrW zq6JnQ$XXs8$gV+Z;qDxUqi7s4j4HVek(J6irMhJ3@`H4-rDF}TFwKE#&K4$C^}qe7 z7->AVQYR*yz!gCKf|=r^D0^0g`IM15YZ2XAMcA;>dki8IwEj=n2YkC&(`<=fI-DC9 z=07P6=}*!$&I!^P<-`UDf860rJn9;?vLL{QyKwJAFOmk+$s@9&Tix=Y;xR8~mz=8zDi*`Tq~G$Fs)U!je0VMR(S&A*eJEL#;gm7E ze0a4rUD)eT{5P#=h#8k;F993a-fH&T^q5m(HHlORJDXhe2?GH`ONfkPB2hIIk9m4* z3eQypySm)SJH7l{N`}=NT;_O$0*e-|RKeg>JXyM&k)B?3Iu0_(N)rypa!3)8;}B|n zr1rE?L#2vKzVO^^U<=O-Nhv-SQVCNsswgM^D?eByJ|7g@&TuRya+*SgNUmThw2LnK z8Qu5Bm&wtu5I>N0GFDSHKa+8Lp_?;@4O&Bv22zI%I?Bx1iZ6|O{zUbhZ7y^fQfS6B zZDh(X)KL;u;neSdtuLkng4GIyr>jEMBQq+Cb{>Tqr=Yzzw-MW9fzz?6c5Zic>Q$a==I2jsNw1qU2cfjc?v_b9uRR^RWL~ABi$eTkHVqT zs2^gI$*^^QcK*I5lX4}p#Btf`BE^$6FVdFzULQ+%NcJs9V|90`OcNJzJ#iMSHg@6z zf`r;c{sz34Uw*nft}^}Q(hb6-#-n+ZlAQdcy_;L@nXEh-ILwLyY-Ug$iu~g2{aBh& zS+tSuW*?%$215?55?Q1s6luBEBFRs>!d^#)-}iuxzd=%&pmVajyGidm6+${hrnv%w zrME?r>?+QoaCYpEE31rLL=1!r;Y6gNT5~Z$`3eSdX$n>Q1mVOFWC_Bmcnb9C85#JP zNJAcYk@WejvH~UDT<pavjA*iZHCjM_1|ytk?-NBR085mqTDBddV= zL4CS=&^P^4Z*Tz}2g*=w@^<0)UXu@H8}dLKfi1R{!hmpdol8nUjYTu#5*bew%zswr zddWZ@%)d1_^)Bwf5Hwii-n`4kfLX1ErO%Al&_0+Rj)8Z}kYMiEq$39Kr)M7hLxefS(Ob#|!) zm9qBRa;KYNCW~DouXhX!!aWvBQN(_-DnsUK~%$WLupUC)u3xInd`H$ z>^ME>f~i0Zv^B_l9(h}KGW&Io?&f*+&xRbM!!k4e67J$cBmIWfLvOIOGD>bBJt$e0 zVG^AorIQ3BC4zUDdst2xVaUtX%da#F`G36tH@s9s-T1xL-NdQocuNtMV6{D7a>kVR zjgD1aY&QS!DR8Np094o^f4s@O;(n@9#+@Mk&K3zP)RUmpEwzj0U`qWM%#_E8p676Y zPsPt%Qx;VusyfEiJ*DNPTk7!LeExU$r~0C&lTFZ5OB6rNqb=KuTA71dp+zNagwe08 zT$Ed{m{0hwE>m&4xKQnu!;dBvUO#88`n=4w<)hmK-dydpk-WQc1m#YlR?z3jPZa4^ z1>>f&{JKJzbdwFaf~bhpmJK9#_F1`9kVWRaoZU5DLg;>?DiIx@gN3Vv@KQOS@6ZJ) ztm50@=819ruWk7sg7Hk|snS^3)be=A;4-GB2#$9Z4RIeUDrEGA>{d#}i))VR$9YgS zDe zjYz?%dw%CmWY}z#m{xOm+A<=Z5E#KX3K>I^LM!0MM|nBc%q27=JHu$ET&vHV_6W1& zv@yu__+zScs{C*5lB1DT9kmS0;0=zt&iE9KEk1E3b#JQeF{f-ZK5!w`AHo`lMF+b} zaquVmEnztI>gLlZ%l8|N4d%C&2(9g&WvOlz8_EY;oHKvy;7CqWHKy=dd0K=zf$T8U zY39wdKW9UOTlkIQN7K9Sw2om5p9RClfr{HF#*m^vapZaGcss~?74{+}dNmXk(irGK z7)k+GBg>1(2-hJWx#R0j97JShH5#V9VE+mr=#sfsshGDOz5oRU2mlTl$LmKuM0s_T z7imoES%|^)5n;Tj(5wr7C-nC_vr4w1{vW~R_wV_P9j#Hw>gJ#vHP;SqGYR> zKab$ytFBiyR+yDGc@u%fzQY(~fu&?{>@SoB;u$wkEe#d~=Ywlha^J+rD>az@#FwRh zMns`fgf;UU>Zl)Gfpp?j3c3CMvmsm+#>T%m{gRQbC>-BfuBnysrc~OL_6p|*i~GdQ z4SEK`B->xz0lYS26{=#mJq4^ZQBwyayIPZ#M5|JdUY9}|sdHk^jw(|)JXT#(ldJS( z8+qu9o&M@@^}ogp#i=<$mXqVTi6?4nyAAAmIlnx?%?IWBEd`s2S6+@CWM#YbX5*bC>$tsA?iQ-dV9dJdKwO3KLwDvf;r!~+QlFEYk-ux02m2oV! zI&DWl=^~uMJIkJ+;K${8MFmx$>=Qi}*RC28*Z%OMT z(Y18!`H%?$Q1QUba{LVFtg$Vb3I@7i;=A}DFAG8LAHI7UN3<9o|A1zX93|!BiB48S zu)#=0MB&Mr+K9?>U97Pdu${ud3aoCP@`iAp=zMUDy0JyLMK~)KemH)9uQbf9=Y1^% z?I2vHfe8y0G&DcUmFMFoJ7oXpuroDJGkFb-D_>|@{I2?a!^W6Z{#(mR3k{c0q7&HhFq zZIU|aeAqQJ&O(9|P|cq{l6==3=_Gm-x;NUY?>I=)EiJ{xBEP%%z$}*>{_PuZb2^T6 zRo3;hEK)|%U;ryaS-)!n+_T56;El8dC@z1a5>aZ=gdX;7L%P8z61SmTLvW2t4d17!sq7i!OWXYD(TGlm7iX-r z*`0&l2rZ;6&Srq~go0%7_z|r}&na{VJ2#0}_rk26BM*wo$_O-sxpG9)z3D#}H^@dZ zOt3(mxbQKXWphk#+=}F90|0@M^E`FWwFPeIQ;h~7UNFAHEzJr&%DlG{)d>Y)0438~ z#D_qf)f%TSD66P07EH=htjPC=FKOKDeL1ED3mS#=#ibf zG9mUC%Dj>Id^q+hpIsHGTQJt@owN<*8x=V;>JAt5QgW|MoOEjrXgbG@V^jA_f250H zP~+z0|J`yP;ug^M#rZv_Y*o~Go(i5_LVPt)4y(EIhi>pHI`qmQr+JxolXb5S1&Ezj z8`5&u<^$2#7P-XcGWZ245SeHt>-4u+f##-pp-=o{(DHtS+H5rahR9U)XFRaE_Lhoa zqhp8ahcE3)3=vfF*g$QR(aq*~h6jMWf0=6^)qH64Y9wNbf-=-r` zG?m#C>oT!SW*q95 zs&nFzw@kqX>SaTQ@#0^JHrh6o7z3p@rhk2%5on#^y1(^c3AIKYs)uL^ zAm3>zr_b~!gI_!NS%56e>rs*EhK}S|-$)wRc-E!lR+&`IA zXDN*KsZ9@H{8?%mdijz^@tF$$DO@Q;X;ky~jYPztSOI>~YqT#BLzS=xG71n0k@=bt zuJgEoMq_GiGNbDdBP3yp!wz9ZTzWdQcH^ z{2XI+rT!ddNc@pytEN0}Mi`6Zu+HYHHD<7Nbt~a?@6)m`cHJ{ z{RsVw>U;Yq<#Xmu9~UBy`LRb35=Nb5>6;EL2OLl~iJgNV2h1MH4_`^p+|el|YbES} zCUVepDolnqPHvjxt`?8(nX^aQIy-JoI(oRBmUjdE6&uyalq$kYG)|j5v5*Lz4Jv8a zkb*gH7c-7In zJ}Vq}b1{0t{qPreLUp%@sgtJL@dMhhb--tG{-=V&0c{iu^Z%hF7}R)V*gP{*5sW@i z`{CT*I}!G2yPQ%>AXwt>G=71Sbf+GPn<;AhUf0KaZKpi02L!w-mMkiyyu8xEXHF&QXPqtGV!*E$?dK83MU9mJ8;%pXx?QGf}(s#=D zaBcSBI+|20kRUmN^%=*Yx}hL?3fD%26*fv#X~lU~uj^l->;vlXvaKq3T&7JxQrtX@!xmMTp6*{o z20tNjGq+j$d#(wWC2*ND@uDul>M8HkKs_GKOIjs9sGCo2rkqaQa_D!1%*2C2xxeKU zdST^OG(6K8^2G`+oUSub;>Baykx!*orgw4N$76OwK^u|eyYol*Bh`| zl>ancmUrj5ZpU4|Q*RXTr9cs#8^sQOUv#Sit#s8@aJ=nh>9O zCStzqq!UM)Db`+XA7WR6XM5K_n`j)So z6YBI-cr1>qR4AkOjkqrBqAggu|2+9bya|fLL>xa3 zPyyf=<_kwUz&;Hp(Z@dnkW8ZluK$ce|2d4dr8?Hlqk2GHIi`H8AbA9+%a=`ItO+a9 ze+h#a8eo?h7^>ws{~k5x_@eZ+mo-hl+Nh#lJZRK4*)`xQ5wnOWp0@;5w_InaBpiXm zYE?53%g~}g`@1>RMD~3x2go}+iY|s{)#k(KmR8NgiUH-staBQxd_EyygL>hZ(44-^ zUj?jJhD3K*l~iI#pigg1<-ga4%3m&NWc_Gt&u^9_rz^|+51h2snJjzqK4mdM$rz!^ zh0cuMZ@NxmdRVR9l-)z;iWK~B)+Lu7?nsuJ&s1It8w_urOrPtYv@BnH_}^SfJ{*Wi z^~d%3_}^}D!yWXURy19yR8=|3IaViFE>E^P?kE>>0%PeggdBqy^n3NW+QNmnIzrzo zY0w?n;IZsn9H~ikw|Gf)jY{3(#Y~G4aM3TBE5z+<6g$%ff4 z2VJa72A*6id2jt5;2gaLC$4xMi(T2Q<*YtbNe$dzO3HlK=|10^Il1J@8t~2oGcl3q zr=RSk++JOF+}XhbstS9{NGsPy9L&0>QnoaQH}S&h55@h$X#?)KXw;10 zdU{A-Uu8%=1f5)L(KeJ@itBeekXEfe>7={n^-mviM$xW2H*~KYseUmp$*xi7plH^_ zTT#!08)|mr)rKMN)!XGO;#9qile(nkp2>a8yG^0?s5&K$mBW;%tNX{}0RwEdtIZ*^ ze%$tR2k#o;D5>i{vsES9wh4ozR78D^tO4U0v%Zl!eI7&Bd;(N&o_j2*`@a&ck9{`6 zf`Q=2gUcXNEuz(^jw|%+Hi?`>OgnZgBmh49}?{*3NVO>FwdyizxKTg?dE77D^Du#qkHj5}h!H?HbLD50?7iPIS7Q_cm zr5dOuNu=a_PZ1aZw8}tRJB(l(EP~Y@5NadVe1XDb7e`97<|_jKfhSG#G@5jG@A5I9Da2cy zdBacHn_T`fKFmlxcDOq4@|HFPPkh7xG|}VS`oL)-=7Xa>$e-+g0j@kSujPrH;WFvj zfZH4o&b_=U=(xrlP9;Gl;lc#Bx*ZY(o=*v#oMy&pYFl{v;CGos`!mN85-Pc@vlBMC zZW26fS3OcqVAe&iO}hxIzHJS>wrYZgVGgLjb!ra3PGh3tO0?wA?|d@AT+hHs$6bq5 zZ$ajBWG!Tn3xraL+oaDq;J~lRWnX8n-Af#JH+)auc@6My;ec({z^kRvYHd!Ti-2%2 z21eq>N_PZiHH2~?iFRP}kGQqIYC^!{)DSoPZk&+vqRn#d>YyqJ*Q~`2X`mmMK3dlQ z;V(U#3^Cy~!^4D7dl<|6iBG0qqf!a_KcxrjgF_sOf5T_m@333_Hwiet^K@u;w|!@+ z=EO|7W^l@G34PgMdC4O6_)=|T^ul!?dH%c_02s0$Xsyf6x?!u^0|r-?IOcO?$Dz=V z`6sr|k;7+abMExbZc*EP?ghSzxKZ(RZfVd0Y3Rdc-PM$SM~MEYSx*$MWR$}kxS)D^ zg4`j%4l9|FVgQG_A2;xz@%TWfBj!4d;7~j${w;G9+%oF8=tYL>+dI66zN822htm`< zJb8q`>lMLxgm&KtQ6Qm+n|?+o1cHVWbRXWCX@f}pV6V#c4>4D>VazE1%wpTm~A0K|->UTuA@WnTtF4o+bL|vV# zYcIpB|79_^^z#T@+NCad<`x*viaq6yh!pm$4_!Dt0Z``EMB^jHiy{=;f)B0%3*uhn z&ToQ0e&AjMluY83-4;(;NK|NftgAlI~1)^~1KXJ+bO;Z3VhH9q5&=h3nP%E>dlWt zp{m8+YfF}s-3SK*lQ&&zb~Li!cq`1ShrQ+g^VeG^?+#Ix+HTPgC4%DZ$(&{{(`#M! zR;k7Pd3D9+QPKZQQz`W`C(n`(kB-6@y_Wl;&XP3$An;WtQQC0Bzi=1bK5RC#8yFaN z*Iko)L&JbjzV;O3Ci4oK&i3&GU2jQfMkSTX35obb7KHu2li1Ui>26h`44nsDmQ}UK zaA$SI_N7??8nRpnyunMW#$aNK%@j8k4L~sK@FjFM2}DV<$$^tLI2I?$Jk2Mk(lPLQ!CVnwr#ipz2Ct%JGA?MN&u_}2C=1KWNT(vSnk7~>wUR5{%re7k*^%zFmJJu+)m%%4^Rf07$7 zasco@`jXxIbRAvt{_ksl?ac1-N?D8;d$N_kc?|)NOQbogb9Y#7fv7^iP5WbFdJNdA z)-o<7`;sIBNndWH{cXk!x!xd{d=+uDIBOU$3XlI_=j9IkeYGEUxk{@5~aUPK`byYa?4%@iM;Vmp)!h^B3O6x3rY z8=I$#?RgbuHBfsDxEZ{O1ZlEKgfS40*C=-I`J=?A0Wa*(?ByDybF(Fp7u@ zldslKNWC8)Y@U8|b}@rE^z}~sU2*DOV&ciJZO<}_4=h%5y<~fed$@E#`8YR6d zcwZZJ_GH>5Yro}_LT$WQNJ~xDUQ1EBw7-2Yg#}18@Wf?mZv{w6NF<=)($K|DBL+eE zHyv(GrOn0lZTD}>GrEAVWnoML9OpjL2@Q%ozT`-#S24}%beNdI_f#PrtgSmN(~iG< zZrMpu+~1CW!MTlOt>`2?lWel#&XRt#t{+$a#Jms|6-1x=#-t#{kfQFiCBj9L{?hyM zVt}=ROX$X>aWCqP4LjzHhMDy5p_QElOdzYuyex54JD3d$#4I|+s5cb)kgdWk4*p;& z{V6jC$W<3MCE>c;^M!u%WE}c~S1aSxIt6%^bK)3*o^+#GieZwb;gY8EcZ-tOKUGF!q24J4n=Yior-I2H5ti7rYSO^F+o^%dL zqfIniRAMN`hEI=G8y3KlU;0#@X!YAH0C@AJkMw9yN0#oGHUptr@7?tH({|K6-Z?|Aio^ofSLIQmTl z;F9U|+_ZaH{7MLbvRecf6)|yeazdK8D+jadb+$llUK?`oTT3Z_^t?EY+)>Dola7%V+!%xC#X1i>q--&o_xkfHnh1af-@-7aL~T5 z^s$f-MKUvU_l8&X`PZ+)h%->$me%MULEXuiX#*3(ewL)8)sf*0!38rZJsC3dKv#r1 z%=dUAxak?r9E5wwMW=jgj3EwlF69@*ll7N1R;W)vbtQp#?(9qSMb1-CJw$FD=)<3Y z`m`t6S5zG;-s>J?fQ6w6U$!b&c7N3gi}(=1=fwSIB0gehgRd&1T663;mVdih5l`_r z`sE%}|w<7=>1Pjfz3!#AjJ3aK^OJdgNwN5=8}xFW-}N1w}dndiGjmNrH^Tp%&arUeN* zz04w5RTJ{na<75iL{Bz9`Iqdkzq1(*gxZy){q)(t+oUJ?Gqc+c5#^e-Wq_}*jMejw z9F@8}&KE6mw}elq3mE4~q{Oxzc83`YxKG77R{`XO1md#$+SG0!RQ0ImPAK(JDw?@Y|w zQa>xmv7d&A*bbKkhp@&7VK?lJS_E(zRGBAwAl9|(%HF#|vW1e>X}k)B6PJC@^j)s6 z$cgG;bC)OS5Zd_zj_2=;=&?hDWAL5b_VXE?C=p-M10F>8XLqk}Y6B|M@jasLMMLb$ zO<`gifvn>VRgbVNnZlRDy;pj(CD}Hf6;;B377;Fh$7;SC?e2AFr1bo9vOeG%MdrR8w? zcImHBq*DWo9raty(V@CTKai{523lFNCzqHg5Xc|*Ph8-=#;hxG(xzT4^JRig{}`WX z%AEKHQ4X4>b?H27ZFtdsk#H~@4M!#)jhHPA&Wfggfsda+AaIM!>Tb#<89*Gy?hG`| z&bN@fEPBPh+xYptyVUdl^#b@i1HJVVP-GP>DZWn7@*iq|&ySRu$?~QQ0IXo(@v>|5 zWT|abP{-L9+G54z+VPQ5rr9XMLF5Uv;R0+kWo{>=940_8gOj5;ea=H!zH&1BUPsQ!=f6{DZVhtgxlMp%sqos9#XPd z;>pw3PgkdfLK=c%^tAJme+l|pBH0dR&Xmp;0GFbS=4e*CD02TwTM0my@GNRb^hJCY zR>~LPo*qK!{>mOmAp0NSc(N<^w~Z&qeUp*quT^5cW^{R1#%V`-inBwOEv7<6=t0H^ z*%6u)!{r>nA$(ga9O+*JlBZ-DBgE6xW`N&BuaQ|0tUcNsExmo#HY(l`^mtU0$U*bD z*qU~7QM>V7gE58i;kdz)$o%i$IIS`y%8GGwh8)#k^G>05bT?9kp9)S$j)?1g;86LW z3@LFj12Hz%Hv810-s@1#2BVKHObwGtwZArN40MmKbK)9H4RkrOKP!;L`AbHQh_;@$ zKl+v_*9Dy)`>b&hmtxO1G<_Bu8goG>8r~-8JF#%$2posLF{m{xsnGtpK}JED=i(c` zx+`9EPGP3zgq)Xdq0NtJV6=*Y09YXGhnpt_hY_={a2U;~v+0mBiNyLh*c`L3cv522 z&m3}i_g}0?K5yq8njA_8N;@(l>wYqF8kJGwaT$$`@t(emu-OBNpmT4WMY2MD zj@*}-o1Qm1I0xAHiB_ypG=@TQf&Ssce|hE?O;o;qp|EyyYklx0d^4EKavE;fCu^1V zR&ey^Pae7A$gU%TXcT7hm%RMi0LuzxRf9Qsx8V*o{;9x|82{{6F{o@|3$wqAKj3*G z7-Hr07?Nm@o?Vnt>rFzyhe;p4ol&$;##ANLM=cAc?^UTaHQc&4rllFIVKi8ZYn`Zj zvtyEE53ai}Q<(e^F-@LdqR5vnSEo?&Lm|6J>BY9A1hR)3*{|Fl@l-yt^UmS-^i-Z> z>VCqahN68Dm|NtO6wHZ)I{l&XzkXbhOQy*rz5BENn{TYZ@NZ@!NHjWcr4Zpo@b@th zN{Mv>3d;p!qm8@o6DFVAJ2RUVB)>RAT=QK2J~x4_clVMx2g1wzU5@ajZr3qsxT+=_ zm2(;oaK}sNvYPLCXDW#^hcwpYCEGV#Ag(y@GhQc+>_zYRH26dLXy(UF#}j_i+N$J$ zt5kohh@w^Q8IA92MVaUie;duZv}0)(ub4XS)?a)b>xy*??j9pi7gqd#c>2nKsJicK z5F|%INZ95(NxUWWtu`_c0GCPQQBh^0B#@ss3Vo`sflneN-tyz?FIZHV@2Mfm z+@z)HKiJ~3@)pPsprtLi5+#8tlIz%izNiXys};j9VX9#oQG@lys_QA6*0xNO&}#N z@MNNa^!R3tD0P=5ipi{$M)gtbx;Tb{FDQIr@!>%tJSMSj$6cD%R|q5S~JAh7!oK;cWKp}tf|uyD>?i#Y!0 zBv_$(`F!MMrudyw*i`!dmO5g;2mup6 zVZQxwa_-(%Wgj8^nLzwH@3=l)`9HOWizl)r8Dlb=;y3f#ManGe9!}ou;l{YLu(f;F zm=*6EtdTUr^<{sRMGF#lO2nz?J@$Dm8i`Zx=|zx8G8{6lxkpDPA>A>j(5%$jS=a(b zt&>gY&Z>Sh8+*jnBIvRqlKbwO45M4l-o_wtg^P3O{21j6&KsB4os?EAi59_ZZm@EK zj?gW5Ca6K>R#gt#>@WolLdRfqpY8`vHpF2Zy6ULnz0<|>FpuWwHr8~6IDQ)snh{%F z?vaFHnF^&dg8tgrKt_es;NG|5J}ox<7#)LEX*M0iZQyZ|R;O}E5`pAQfefetuC-ou zV+KQDtAEf{hs!f!A+q_;gu8Cpp~{{ub=Sa%_FrJ$@h9=3jBN}vZ>oFa#(25uf<*W8 z)ra*P{SsO2KdT)<9xmSGS}@r#>EAs!ri_il=)X-|csawWv9dSmmR9nUA{1cO3b`-X z+-N*Y=AFh~BFi9v0*2Mz#m(v8>WmUPEXx*c;Obd zJS_XBZEIr>-lc!~yHUC}I~>2F6MmKP0>J2YPFMEImf@rU03FOiZxGEA{-#Cpfzk3K13YTv3`yb>0LVQbQir>HC+Q>CBK2JNtsJqer7sSYS z#VfzLg_^GKqhsJkGtPBc;23mzO6cvp^|4g9t~&so!xw=Z15dpqwjAVNzQ&YbI&2T7 z8ZmGU(X13$|8l@V*NrFq$X1L;rg6ocl4P^&Lay;=c$6IFh@BHEg0$>UFYq+^_kwQ5 zWmN{X8Jv_G0`ZHeWsBaZ>tik%{DIj`*3$R@uRFMusg=~jA&uA!f2*?Ql4h|%wYPU< ztuY+M9&+??lrdUlPkGv_YkuuFZ-t4=(-|-JOmlnKM91|b%0xgEQ$(Ms)^KEo0gWX~ z1KY@2a@WOH#@3=l{97>@lJ148{qj&&wTKiQ1{|hEwnU})Fl`>`!(!3>#Kn^NK~>(o z(3d(bw>)(}S$Q?o$)=e*V12nEAH~jG`IEfc>9!a$LD(HbhJOQ3EG#`9|1t|Sc*d-_ zo#5)Ey1stN%gNkfQT-zehdcm_F_ph(V2h!=LT7WL2c!P=wdJl=p`^$f{z-q_O*ky*Q-)WeHhM2UXyQr z%qUaPSsgolLCRMz-F4+u%?P&J_6uXE{jX>doSm35al_V~#;&;+h1DW4*NimPH2y9o zu|DVoVv0xS;=%IAu?-Sr2HKfr?n~NEmp{d;Ue6t1aItdqoo|2i+Urui9-j+S_QdF^ zP?S0;YG~P#X$;+VgUPlc)N50<&mL&Svwv_Q${4EH`u@U-9ebDlM-{9PgYGnG`eAhl!RB zdN|r+rfowmG~zNmuBG90_?<)EGB!zkf5fV8rQR|s`xI7qbTS~%zt(fqG;n%L+l0Sz z`=0&IiL{x+|zN({=5?b06S}CFpFAr~Vy_{+~i%f@ExY;^M8?Uj@_i!x~ zgDusI@8GZcjk75>aiNNGc$Vj&h=jo3SxWa0p+RofQAJ-TwD_-HjL2q~=6-8a2=!ZE zQ=_sUkgvPxq6TI%#PKsV*MfR221~`t-!4k^)yQKK^Dp#r=G_WH-KwNOyuGnEH^<2N zYW6lBp#sQtW8uvN0Ms$2apY4|Llb6;Sd7u0jTzH*NzKOKMF@c9UAyIPJoV4(TWJGf9fR<&9Z z-UIb4nBmt+-fWFo(Q^N1K86T2Xvvw2x$kdFI*1~nOoF9~&C(rWhr<2l2BZDuBo4s> znH<)pYJ$tvF!Eyk69L_xu}L=-mjF0f`l~5$dhLf?1nbo{dZAZ1P+yCcrwfpl{L3gL z5fUJ_o*#W-E+yNpAwtD5WM zM^k!eDGMu4TR)R1D;S!ZW)MZfl8yG6u%v!^isSg|05g^xWSMf8zH(4KCGkLrpV_=K64wQzh?`s&Hn( ztCLKPg3zz{ssqL}5`me5!~;^$$jX6O{5dgmg@>|RR)=HYV?%F>FuWtClWnzJ_+kF|AR>2`}~B*J%RY{q_rfY*gkXj;Ar5y8E*RA0klds(m0pt z6~X|MWEItq9214#3iyHTY=ba?^%)IpYG%poF|$~u*}SPms!;N15kq{mfvV(%p1#dv zO+|s`Bocwpb+*idig11WlSSa z{2J5{u*~>DUD5fXMqbD?>KB~qfL}1bJ6&dG@b~L!?V-Yes_y#+vZ!Ir+ZHC1dQfui1*V3>B-}k^L&P3!d28y zx-3cE&lNADMPeoeFqtaMGfeGV2@&4D%d+zfN?9J3#QHf|xNVVJ*Jn0GZOFZ?5zZw! z4j=UCTRR~cYWy76)6z;#p1vNN&fP8T8W+_MAu%*zkG-jtH383ut0Ya0Kc(J}SNDJY zGwiocJPXkW%mj=I9YV*lu+GrYQ{7H@r?UGDbI`g#M#Lat{X5h`yf-_EwOUVbd02Xr zE2KMh(sx2Vk}|QKjx)zHE+|3#YYg1WT*->0P(zQNoO z?ETN)*VYW$jkAr9rcXz@=V10VrZfS*4%O18@y17id-*4OQdM#h=ci5G2kAg*^MSFE z!{v<;@9P|4?hAXXOJh~}CL2WVyLHeR_V04pFrbd@Rfk_Pf}=67`J0bU9AphCP`!o_=#|&nDpUmo zF#i%el4W?`J1!V#7O3 zD!IVj0n6jQ?hE~m)7XQ%GmX4H5%XB@$CMUn=9u-j8J>dz_qPwQ$ElnytP%N)jkQSv zw&ambk_s*EM3TOG<9yvl^VSTTA|%x=Hu{OV4QeJo$_=P!v zx}9Pa_2-uV1h`eI%v{jotf7|DVfs@RtIsYd&A7MFMeJWyd2Wt6|3vGl?@RNPm9j#4 z>hi?pz!&#tBlp(QQSqEbECfjRnH!y&O!&dgQjM1z?89<RG6K#26U-CJdfVDR)hxL^O+;Sd&~p+cz-qqWuryS)df#s+n6Yii$ud8rtPhqlC|+3NRJsD8 zJR9G&B~Nma&~l4R!s|I+P28^|ix+ftKVO}Gsp)Kc20$yM@gwA1oRH~E$J^V<3FD@C z;O4E%Qk&oyNIzg`~5)-DE zioF=#C(eL9H*Nu7aIr`U?DWqOqmyx~F0i*7HWd^%>hv{sUG+Q! za09UAcwMulmE{vCH+VgfDfGC*Csels1HrCvqsIj&Cx&9__lp@Ym^fj!JRh1cA?f!p z`sw>}VZH0e1A$NamD`gVU7+!>|8;=3vVO+pjA7t7NxRy-fJo&}$cnw=d1SUhtBL3B zW~%}4%U@JyVZkvj@}=5)f0_gRcAS>J6;!c{;ZqOoMFkG+bPcWAVFn;7&T`Z;frP83 z6UC%6HgARLBz<15S8W7J&8VL7p2{IXfu@wCaMaV&vs~1%l4Rt!E~OQoW|XhD5DJ)O z(Mh^-`AGD+DMc`|vf3Ywplqv{eJkH{&7nq}PkTc#sx9=job`8(0XNFL@Tinp$CU?K zm(UsPpnXGbsohFC3BqIU?ZH}+ zCX4V-e@jo=g0`(Qzc~G&T1{IzXbYYvI62`RUbdr5hmogennAflbCm7E$~V3Q_-Lc` z#E@zH3+qoH3rPuAYe3gM=t_E{$x&{WMPOpbmC=4}yG`?O1F5`3uq_bCVyh zCw#b%JqL|)ENZnFzA_|ezSykVI{mg{TXh`^PQ3Z5iiI+2fgAgcIff?kkf5D0ZPt2f+3VT44fgK0@wK1%`-_zly&&cqv8n^0aGbivGRUxL9UtqB%-xExYT&^o z3#Kp2udLI*?N~8Di-A3|tPiEZcn2J#+WGUM{777$DF}oF?%Hmdr#ZbDzvdCLRrRn%uJRcm;)-J-)rC z7>Z;OYJBESNf}H;3b0H*+o6KjjI=8g3u0@3FQzc_?A*CirA0O?!`^yMY-NzD>q3e1 zL+q8s09-;mX073!qJW;2Q+l^r`xbvw&*IsZ6aOr~^pEQ4lv`SH#mRd&1v1uFH&^1B zrN!Sorn6?yBuz>GvT5Ls7Fd|MrW$Oho=lj?8OmygbnbGi;qV$UHuL8CC+)LuX$=0x z&^OyU$gWiV^)Ul;O`+*>m))k(xpHLyGka)l?L$XyM~3KoAa`(fz=GSiB^p!ir_f9= z4L@_luNy4jNf9IhQLB+Dn57_<_2aUvoPfk))GV9ggXDWMU&J43Ifk-0x9({1`s7-2 z8n4YUHc)(n$Q!Q1Zv?GKX^+^i!`I9vE|^eIl)h9Ur7pf^y4t3n&47kYexpT#t(gXbz7;d|NmJ zeq!FeuG%vYai~Yt6t`02QsHdeU-SR?IUZtP8U-Tc2(SZfe2S;Z1YIVNUz@f`I2wY4 zLU^I6@WI{3ZlvqW?v3SH?WuC;c&0t)C&sF2#O4*JlzFmWveC8HA0@G3I#EN)9R(lg z`AHdGlqG}J`>jg;9!Mhm)kf-H+UGQiXk<&B41Z$h5XcbA^^_H-|HLTF*C_t6qW^*~^U>+e5p9QKD=iAGd*(t;1-Cn^3ZA>5se1JEX>cY?S%`$Mn|2eS1EQ6h6 z*c38t{-t8tjMd+GfkIM-sO!2}91{`pMMAG_wigA)Qm_+TUCpk58Cz5v;@gDBq}9s; zF6?~xjlP|vzinN@$Rj!GVIWcTFQ5U-n^Ct_Y@@R7`FYpI{Y=YZ`9)SXP1q&2VW&~O zI4k6+MQzP0NJv8^nS(1Pghed^CR9THB8Z9D36{ZsIcZT1LtADlMwXV!Qoj1j71|El z3oQ5Sv%^Q^Ivj3Fc`zkRI?n45fvW<1a zpV*vcQ$G5?bHk@XFwZYaIZ9r_gK@gj8KWi92b!?Cq!mg1G6S2e*^Moe%1_!qX_rg#dgER0UigEL&v~`%%j_p#8X=3r5+wd&Z-}pFXY7%atS+?aJ7pG^HGGp_L9GJN4r9Wb>mzE( zjdFeN6$j6h=Pf(ZbI5Y-0O|D(k3x}ft(&>pqMBgdEj<$84%&4M-$E&}nHDQFYTh)~ zYad2pkHP}XlkoFGj2F1%2#>j8uP(l0_J8`#`V4t(2%!vBEE{x4ao`C zGDqR8saf?z{`jHIAYsepYj@#zRHO7>*ny*ET)8W{c4=!axXze-W_BquW65gE3LB}$ z+EnecDo+tqfJRay-CwB?nj2s)iusN!FWhimEii-y1Ty}W@Xnw7)f8Sjr$(e1v9Hn) zYf2}SkDd)pbl54R5pG4XxHN$|Onr?jFaOhNpfE$m*6KceSAJ-@(H9?a_5$hBMHD05gl3KPQ zKVcniy-Uph(*k_A3ZjWfUZ4u00tvH_3vavF;?4$TDRM82s^>1?U*geD;Z1gff5_p4 z(@b%2+&)|C8ysV8NuA!`mnZ~S>iT@$>8y63IXy!+`|OC0rit08 zCS*V=cZ<^6^~IOmz?cyZlIdkXQAZfz+^k`=6{MRdw7`|*TT?cFDEZp$dy!lYJcEze z=>EOR%G1-Mgljb2WwI<}e*-HK)ngVi7Rm4j{_Lg82H_z80;sEaf*x_xA`mJ7Cjd)9 zFni(vu5?Aqc(qIaLH=O@n|lFPPJj3PZEXCz9PFiHS`~n^lA)jZVE7rr(>4|QzThfT z7HbqUhZ$?MM3RWQ6AY1K3z5s8vJm+qf)%g;Q~f?UOjh3{O1cSqm_*Qn)?_quSQ#_F zqi%X!tijrWC~`uhK^;*LM5lzCnt-}A-%6p?{p_J0FNb%92}q5^d%L1X#@dmP&o4{@ z+L?BnqHBQLBEUGD2-{rwt6Vm>wQ7c)dO7%nQXRjm9Wlf|Duc?8VjyGyE=)mNaNHf4 zcyHNIyu%J)_FIP}E)@MGBN|n`U*AIqzyGYR?QUFM{d*?DQf*u2V43u@dLo_xiv@$8 z;F|g$zJqWLKL=4f`=@)cm1S$Hj5;zSRvVt)Vq<^78dW&X_70Qng*N$Y*a4w3pUm_x zzMs|lzv8lh>t^1}cwh;<=xDD3E|ZLMPBXc%!x6_f(O4o<_5}5GR>*?LmrAof7)%JN z@&*o7y$Y%vaC&{Ggpu`b1a{%dnO<3_>b4hgwyZ&*X}I3VeydYt;&?jDhpkZ)(qKh8 z({U3>69P0`Y6LqzbrfU;L4Tp8Pc}u7uX5{2YRV(|RG5#xNnh9*_LBed?C2;ATAde} zVmmJ?E;SS(T!4*+bc2b61SIG>9VLiF{@QWN2>%3Y#Uc$<(BPsK7nk@(Ff*0WBh!WE z-;m77MBoQN*~-zow9;owqbiA~AEFdLkDPa!5Ay=IB(wfijpPr=_W#K}8>LIsXu{4) z?3qMqL?Xd*EdQK?NWOhjC18jH!VcUEVE)c$4h_KlU`(0)eLUTyaPd=<^l$95E$-n#--%yTH>V2LxQAH{T{b+Aap%H937D3g8HGn?No2SaIn zw?=$udq}<9++M}5WX+eyVZ{=tjWNl2M9z#`Ua%V}z2MD87tsJI4~J8CZm^D=c&L)o z6yA=%Bwv^-q~(cNn+_l6U;dQkVyGS7%4_Rv0=Rwyod@(Ed&HWut09v06CPXlodBr$RS0VjSnzSp6th!0r|D|e77>l4T;8F zsOZH#qX5o3x7iUF|Bx4n_{-TUJp%#4F^H33PYyF3wDb!m$-H}pA>e^7f!6x z;Zz+vunYYN4Ry8nmpt7CEn3hv7aXxpu+X&J0zU=#M@DC{2s>O}7&%TF8x71l=*NbG z_pQbR4;C-l1nq6vW3>j<0R9W6!F0#pX^k7MA55~?J&tAXnwr-swB0dt#%5{#g?Uny zQjlQg(d<^i*fO~sVl-l?%sbY2XloEH2JvW$Spwt%SV(l$inGKI7zn^D0YdNsulGEg z3_%?fQU?38B3;S3J(0i!xB$<3FzG|lI>EOKG!eb}rI9c$o%#!7x#3?btStAoWxcHe zWRTf8Z0AJu2c3Tz0!9G<{1zsY51K|pS76qp&G&V+I=-6fr9OT?euIfH#BG-zGugk( zXcQ_t;sd%sN&GiR7pd(;-NJ*7B{RnwZ}DCj~Ru zN{<`wrD9ZN2f9pDr)%$ z>zSp?7PoL~HSS?>htYfV&sL2 zV-*>bUnqik7dy0~m_geVp09Xu*Q*yvsZj$%^Kn5k(0qL6H)sw#W-Kf?%|8QO_}_f< zlrUbDn5mXK8bkG!TN%+O`T_-CiH$y`dZNu#-7IPv@m=O4>YOpdaSxE$gCVP6bUM`I zGz2%{&^E=R0s4+7qzuqKwovfUf7IP&#DZwf*PychcntFAHY+1>?CZMn776^Xj>Bk& zW9=M`NhX;e@7s!|k1a_`Qhd4Kb0ylvT2`vAY}R>x>026-E)|-;^VM7DA8-urXD2kS zBpkoQjn~FVdetiUkx7Q`6PGZZ zwjEw3-b>}2@J#z!ex_2#rEnOg2K8*<6kZw3y2#Nz45ji7|8HH{+%gryXm`c%>M50W zreA-Iz8`#uuv5shxU-o7`{~7h(V^VI z=A20zGC8UGFuh}Gu7Sr>bnGKS4Y>#f53*r0%+ONgsDt#fNEVUiFi|+5=4pw^Gr2-v z;V-6FrnvTFK zKcX*G1z(6^&f-zbXwqLdx0p+4lS>>-&Z*80&f=GwG%B}O&}VaX;}7Ynb3_>H<0BRF zD@5Efw^MX?whHFF3aEHRzwjZZFH;746l8olTM|=J)Lcaa8uKx>hE$p7R(B~G6By$s z1}0tZq4J-m2dJ+fgx1U>3eLp4$Q=nG8Y@L=# zZbhJWzikUEINQ-WiHz(_@E=<++cZ_3 zg-buk5$)X5^V11)CjFom~0%&3^(_=tMi zDn7-UV|Bj?jJqsz+~YF|SMn|1i5l7(1E;<|uH+Efp^@_m|E~5iz#P95{G$M*V2%sT z0)6O!WBc-{wTd1~pp)rG)k=k2@GB;wu=f!m+4urz!H(@bWM4QQF2^NhuvFn>XPJMG z{>~YPd9~Oolx68Ub<$qY8mhEd*Fe8HSEjv$jKw=6gGZ;gT=`JPM_ash z#eXa^yd^IL_fnrIxrw$Vgst;>GDW(Z{Gc!dCh@dkd}iiJWO0N3|M6I+%W-=6VA7dw19!uTw?Up&j;=He-hZ?ze~<)Y(&e4Wq%ca*O^D9g!*OQFp)|h=V$D~ zS6O5H3$Gq+BhZHr!8ui*z9{&z&N)U%}#w0D;gn#d!|?Q{%$mf?6)hhn#%*5Jzm)79lQ6t6@j92 z!F{R3J!ck!i~?~M#wUXsbk9hK_nF(`+VNu4+OXXpk63V3E$N8cJ022Wzb?tJdO`FDFCx4x}2@y$Wx;CnRF&10y>{o3rH*nn$VD&n)OQS z!WwwvJmQczr8v@sll3ni1A`grxk@Y&;!fd9BM)R4iPe#KET27y<$M*%`RZc( z0B30~Cj^jmm}>;;o8t0L%ey|33bYV>wlskn*ey3q1#YQvS&3}vXxEI4N3xf<7NF&; z_xp}Cg+N?KaYNSKosW{e^p^%;u%a6sI++N%^y5$9X~?EE@D9Jl-Y*e~kgBm)VK$U~ zG#Z{Cic(h*&PV*b|K(hoMcZ!&%LDb<@CcN5-jB}5@=tSF#HH*;!;4;T1^=zd;9XBM zF2G2GvcM= z6D*x4O))_^SszL34vZ_A1-nUPF5OW*!MDr0Kc7}3;f_~4!p!bdf$?lG_D;2G>4iJ0 zI}4xZu|Sc#zLiz+iu88Uk@rzUkR9MZ0hnuv^98$gnq8HU;k6`{7s`}TUV{h{|GI5J z%*U*-=)9bFq8awIsX26fl?fQKGw|%UsT-{HWNi7RThqQjpEA8o{lPn1k2KrHlZ$j> z;ovV+Z55c=)Qd7E6V`M^McPl1YDBLVRCuMg=`Rfjvb>f0JpKX?f^b<(_iqq;XIMc7 zPu|&Lr8RvZtK1GVMOD8d%)9)+6z83RO6DdBOjRJ5DOPWJs8z>xeSq0cL%DG;ecYgU z`tuupF?>8HmWhf|-`6nx>^m(mb97040&P1~DDQ3I>RgQ$O2q+|@SxM4PR~G+wi3zs zECpy>a^2rZrc?u*ww!v&FLxSk%c$Pj+l?wBL6*#Z+U9vEKx+Lw3q~4JL`#Aq*D!nE z4rdYFQS3|`Ix)7DaoxHRGaYiu?12t!mTtedNb@LjE;q~_Q3fNN&lkv^3jQ;x z%#vSslSS3B@k-gNr|5b*pF zZQpA`SElu9HBlO8^vbF&9IdQ=2mlUvSu4ey4{+x(MXI_s&5x?3&Gc;*Tqpn5Jf@n~ z_SF*o6>5rn$#4`m_t)re1PCI4|958YsP+I|Kz% zPGSei7RCnv{OKtix3^o~iZs`oZt<%pYA5QcPd03fy8USj=V5!6s+>=!?vwQNujG!w zM<+R6jH`kUMHca1L)0mN$*lmBkGa>4paK4nrLL}RoUg_^X-M*|_ugG!+|inOK*ogV zvFPayUW*>R*^{>IsF41)XZ5k-C;@$FjOg?4n|hvwdyiM95nn#7qLW3G3>c2oJjmeF z;vuh@cGj_)-ZnwB?{=$Ipa0dQOK`8LEPG_Py|T&p6d$weyML8Ah%xFWAb)vfy0`%A zkMePS|D4P5*%kr@Q~dPxsI)9}NYFE2OPoZ9`hpsGy(Bhfbu)Tu?NzbL#p%3C)%2Z6 zmY9AdKt%XkM?JQf^!Ax7~d^B4k+Ta_lEJJ4Q(nz9w?*)zW;e=ZU zL4{a?+=9^S2c3DUo{Lgp2&TI&C9{@Ww2sT|7IJ-wDOjm6Aky#M(UMhQsDk%MZym4V zFAMeHSL0~H!NSuM{X^tdb+C4(4(pnWy*dn~{ErYW9;6-NK!DeExDo7x7xS@yP#d~L z+9?&*EAtxJ#)A+WKiDL&5BP6x&>e~{PSky>;rmD$?10n(&0=yu4~(=~@WXYtn6M7J zEZE!-zud%#ep)@W_Gtz^e%=9?h6SYSkQi~m=o0Ezq%at|38@?fnzEjwelu#e;&_(y+Lod<5& zCjvc%FZo9`EJt^^?;#u6w4h7$dZ^*OeVfvDs`%Inl;Hvmybs1p*AmOuKv3em+C}C= zs633^6^0KorqL77W_s-cr&6*U=1z}ZP1AJm@MKL+g>){AfC|<+5vM}=0e5IgqEBp3 z<9hXojMj)l-Dx=!{MLGpp*bCyC3k9fwj2zPzwTL=p9U5lG^NA*ACHYZ9E#^Otm(qv z-#lxt5VQv>d8EiHFaB_B%CB(88j?CgJ>w}AcZ;AJEK|6hY(HcS%8vHO|qjPTYbs|spTflfENRnBn;|o_WE5`kE4uD{AB65Hr*4V4aCzGHWJ3RvJ~O*hLS2 zR=HEGj7y!M{3$F(=3ix7BVcd;xHICx%O{?sB7mj8R# z#6~6(mZo97c)d;KeVO3h_8^YYuN)*O- zNmAktJkJ2&0mnC3RPVe!(H@M<&>Jkto__FRl-^gY1aQ)ecfbz8`>eU_6q`k~@Jtk2 z;0Y0F_mun9t(MUyHPOwSlxQXFZfI{8E8$Y7Jnx0Xe|v!`Iq;+HHy-T)lw}v;i9(Nm znedA}i}r`xv@q)fRtRR0sfUB}ihU2aUf>W}Wi{K(nW2RHkEWRSCq{c#k#-lm1D;yp zT;{hbWQ@;oGMbu^ymN&G;j+^x`qy4qWck&%_?^&rF8vC(f>#&^rI82Wk@Ivi zpOGJ4?MAiO0HCn@<$via*Hrk45aH3NHUo2Mss4g&#btf371(g)ny_^#z^a|Tb(~kh zrCv92UW~%QhHbT#vyF?}JIOKwQHeRlZ$1r{&v(HAazOfLBF8NQuCnL*N5SykE$gULx_!58yi3;R!->VF){f#2|=YMc9tKR;<$HMBY|E$#M z11g~TZNG*BQ+vx5lbt1c5!M>2^`*LV+k_K$@VWdUH~Y>SP zuY7R|)gCm5jmFteQxuiW84_gvuZP$=}gzEP9u#a|*B&;fxF@%cG0 zf=oP=Z^Kc+v4Etiw?{#2UNtAkc2#B14Uq zjrZc@W#m`;DO0U6JuU(Ej;1>C2c2%1@S`5N-sAq^k}vV;R`VGL!=C}47UE9~3{u|4 zV^iT*HqSX?=&EO`h*3JOfs5lGC?*q$NiJn`XQ57*Xkm$px&c1Z(Tl|rmXrO4*ZEau zgRA*o1MHSAbb9pm{kDP0)dGxvD-$oz$rF$e(Bkz-*exH;9jNWwLt9Qe=S=mzgnuZ7>2uvvwxl z4Aq`H^yvPawwIIzJzAhzw1Lb)+p0A#VW6C&A-=UDT`%LiY9e?}ehZ8c3cckd=MA1^ zO@a473Y6}GSiCpd6^~Y=K83A-I%vJ(tWk% zK_xFA-&9Xra87>p3=7k!07B=OvzmbaF9UUyF;>G2S({sXIkL`^3H83>FoJ^jynvLQ z)fG9da)Q=`5u!l@1;i)fN-Qc8Pu|8RC?$S3X3!OBH>z;7O`yhii}%2wdPqnmp>^u| zi|daAJ-L3aRx(HlVNSs7gin7I0CaPc(QxTptz$LwYFS1as&Ri->-vu61%#>?v$C1RD;XaeSOBgBxp&3 zYvVB_^2kewKPH!La#_g8!3Z+;^G&yWxZOs8^y1BVB|r3hPOZjEX0zw%v&HSp?60hR zbEXa!NbC{(O_abj7Fd__J7731`GY;B|TS&Qs?nmxaa(Io$ehG2}yc9U|>g zU2mu>@aINhS@WL*#Uc&}r2?%-9@$xw@%LAg^^9a^Z}JMWfXF7ILXE$oNb1d^JrD>Q zE_lJf0as+x`VfZK*QFn8>65Fl=YL`^{bF+|Ol}BM3jn(hFQ%cSS9$@+N9U79nr8R` z@R3`8R|E_?*6XMnT{d2_B%NRV1zzd~PUu|5vWy6cEKi?FnFhEnD{i+9G!+M=EN~_e zZ)<-Q!`M-ikb|EW;pd4oFwo*nT6&DbMbO4#VLx?>Zec{O<|dOL{y!~1UbpbHZ&fmP zQZIn`_|irBpv1S)R~DS`XL~cc?|Ln|{ZSGhRvuz}Q4&c<_{`Cr4h3AEm0}`54*p{P zaPzf5S*=vL4>(i=!mu~lWSjdj0BDD#2k7`d=K=N!MwlX`r^~IqJNC*@rGRkBq>)u3 z4vIgYZy<^Smba&?2}}s>Sblb>U2-lh6VktH{cZIqUQS{+k$JPmuj{@RiMLIXVn57XV|4Vu$tW95ZPI84}172Ef2F40Fi&3QXev znMK3jSODeOHi(vpgX57vpcAmXLpzOl&cLD={u||=RlgtMxYyN_i*6mrS~F$xsa=ND zBMn#+6%nvt2o3yLCuAa3e%iR6C(UGh?EVQ#92rhEaWDdId$|G_5bbA>iUK87b3l*R zoP#aJSeO{<(mlsGWR{#=7r+F;7wZl9l|}fKnosTI5lGbvUp^@_9n!PeN;5>}^qg&< zcxa3PBn4ll{iW|dXF9=$|1yAt4k2HZ;dy&_q|K?R_s!cyApZ9r5*T#;K7-|zn+{vj z)Bekz|Ek#=p!8lEd5>-50Lbzmig>sf2gLDbr{4=EpEJaMw>#&8&~wec1hWgZ&d%Zk zpOS2Rte$b%*d1v6e)1w_{kM}x>NAdg9sB$@j2y~>B(F(nPp&`$oYxOi8lvy~=B8H8 z%jSMK`;C52h>+H~NR2<21r+nrNxi&r3A_vNR&~^s0H_^S1P)uynW_U_E>vQwVjCdp zJY8pS2Nvd}*(?9K1v?Mh;=QrjGlp_9`m^%KJaDi`M{{&>Izjy-$~u3kaxj04o~!El z_gniG%`y)$TsJ&=&d8bZ81=gDpBRa%1D4tVT(f8`&eLtx@Nl3<*qjy+$H@7fsq+r( z@@oe8$!WbhD_nKY(|qc?r4r7{sTlI-QHIcYFxa&GhP{qAkilg1Wz9$tRznsZ?K|DG z*F2^%gTK6yisOsSDeWn@x3B^*#S@3;@a3IJ-m@uVB)WeDwkDmR-J>e-ee=i1q$MSD?PCb6O&N0AHad>jTR1 zoF2RFBrFT=R}q9)sAPyf!y1~eXHsTxhl~7=!WRjd5X2db_)CC0d9L|hCl*}k9*Vav z65>f^7?-C3yvg6)sf3gxfN`bg5neaDU+lgZD>xu+yww|Mh;IKrGmzS>+;S{-mM4a? zL?|eHg{kqcD9TF5C%ZPX-mv z_7sZ^Y!C+lllDE0ET0!&)G#N@n_@K=66ZqPL+;*9GPE5phAeu*FNj4U zu_lJFZIgMl<$4(@#(9TW|IYKp%FHBA2!HzH#RMFU$8Ffi(SCW%0@C2w8M;=j1LcZ7 zp;Ruy<|Om-J=vys4YTLzbO|tmuly~~(PjC5S2!>JDpEV3n>`kk&icZv_nnaRGvz20 zoENPfM+R?yCRsYzi;~pAjMDXsML3v#uZeT736g9!87`2LMP=CF<7(v)`}ioLHwMyI zQF*Z$VxKtD80dPVFH4oks8t{R1_!O2I7wsqT{0zG3ERIm31zHm@+0GJtZE@kvRZSL zIxQHDv+RnU|JkS`xi~jg}W*0y6RE#q$XkvRnq9!*MsTAOP*xJ|j{HBgC`y zySh(zn%eL*h@HTlQm;hpiN(m~G{GZP>ddWayp%qa>g&J-c@`KPt$#`$!?$ktyj=Em z8*3=gC}Q6EC>!q+?@SC`$3bs_BsKhOaa-a{uS{m&HaZfilcT@F|M1 zP&jTrGr1`fiBWoy2`Qw3q2iyv6KeoV*ypr}VU!o*G6`?u*i*hR*-^*KjV{<2rx0Gh z9u--WM-8XTPGsUvdrnY=8afx74;X4>kbKG{gJu75e-oO;5&AEcX5a39AtAJW2Tr-1 zxH0A!5IR=20NU8IO$_)#LZ;s&MKa@+^iq^x2T-vHXTBBa+wuIjW#y&4IA_bs`5Ed| z$pL0oZjsnDO}cgB=KAyb2b-R`7L&<8ny{FDzgVG_VH9?>WP#8amCAoIRsHG%>7L3) zY|Q_LyEGMVuiYDaT~o98-zuL=OoCCUtL?z+WONl%qm^$cW3~5?@9X(jEK<|?>;yaT ztWh;Vb?PrREv5`9a^;y*NSC_L`!q$D7(H*5IZm;=ET#)KfbX86{-7IZtUvyHG=RY@ zP@i`FC+dafily?(i|Hgrr5f}Ap>5Cq$J19vRrP&ct0+n{bw(p}2A&D{8WEd*K9YRdku6QbUMQNP*Jw>ro+j{Ov$Yj%OJ@~- zlet7!%TwhPz1)16B4or|zHc_v3YG6H$-fKZD+5bF>e4vZId^_jtp=T7#@lBIp`kQ% zCC!z4&!!viMRpylcmjK_$e*u!Wqtaej|rk>>Zp%IhfjL$QO|7yIcEuleVaN@Xk|}{ zcSoWk{Y9E_j{vWL{=;*-R}&v}BAm|O9c|B*k_)jNqivYR=J52SE~L2$&*2iU{LX*5nCWrOj1{4fYPrEBea|aW zXtKq@yQ*Z@B@^Wf=nL2^V^xq6WzwM=Z<`N$&aB`W)AT!)?JfrCUYIjU*VN_g%8OLK z_nRpWE<5V~jDy&bND=2wo=ImAISH>JcgCDamswp7BQ^n(0zY)z?X%R-@1(y;11ge6 zt4X4im@N!pwM8AS4cT;&>Qb=u^|J$*>qj~auccr&_O#z)9PnEBnJc$QPKTZFn8<3;Q z#qAd$0=9*ps)Cq^MaiQxF&fVEZ2u#o)8$EDo$?LV(S2@hkv=`=D0lnSV14_|$l82@ zSM%d(yjKu?h1`)LYlA_PZRw=rbUmns610=ueXIyvlJL&1ZsL!i6q}RrPIZ#5^Y7jF zx^W&3*&kr9lsB(Oy7)IkUvEHNZ5Yeg@8l<2DG^!bI56<}}{tFo??adIs0=rNZrT0+_XugXxYs!L^6i4NjZvN{+}gK zsmAJ_SLjsCkQpp?+2$k>>z8p_g$LNPg?dolus+|gn2)!zbs1^ub*pY#UD^GB@POf- z(V3rTqjpfw;rJuQPpszLxnTXyScZ{ZsCgcdw?9W_u~qoOjA@eAqoM;nlYuC&4>f#BZT9Y<@~ke#}*R? z34{xA$AvE{u$Eq4T1Kf1_8&*Y_&8LZ4uZ04W!POy|RDeZ1vQKUt0k?U%A z5~AF~@M(z&(=Ty5*8gk$1#TnWJ^nqks-(|SRbA1id?Znw^X-Wr8Lh-_S2L@ zrdrB?_#1D`WSF{{FAAZh1c(MHf$L^lf2T_mX%ngkHBU>k)WWQbYNiIQNj=dO1y9~v znXx5Ws~uFR&)IaQ3TMellA~#Evh^1P>(EFNrEpM47rw9S_(DTq%v%wC!bKVKqh`^( zL+=ZZR~ti6r~b<@tbP(qJ%1Hc6&{VGKZpsIA^W6 zKduoiRRjUEZo^1^j>aEf&(;Q;*|=vQeK7PaX8$VHsfCb`Q6}H7oU&HGF5z#`)3b5h z&Y8dw=wb3<&E_i8;5eDK@nYVN?udZSxyT~dsOb#m*?x7?vuWlQkA|GMLRAmq3>$}W z{c_p=th|5*hY4o1i>6B1Z^tNbVo-RAp(LGSD0-0?cms|Rr8HL; zN6kCix15jOdYvW4yF46|63*WydEJf7;qSa(jmtTpQW_KsaC9eOFD# zw5HkZ;$GO(uOmipmExY38`#A;ycoWqM}``D>THpSaAkFRGEQbW$p2~V;&gEBX;n!Y zgxsA@Il;K9v8BoH6XxV^;cYE0363=Gd_$S5&nyRxv0-a7vVI-!XXw}4p5sU(zt73) z2+!H$QAyldNXEK$-bIa6inl#H`a6qrgtvOpa~5`mJho=p^{o;uSS(RfdvgqUO`Y8j zS8>LSRUh`d^U~2$mYbA3o1J2hPG_nQPaoY+^^va-Pj=f?(+JYUc^|SSUh&nOu^ufv zgy0;xcj_002-b}al;C@%S>f|_h#T_*XMfbmrEGL`nv1mrth~`_mrN^-qc670>6*~% zl;r-K1FF$PyQ~|12_gSb;z};I`B97R%eSYu#og=<@8I}S=#DbM z&i2-nbbYrKFO(YPNYZYj7lVtN+r{v-DYI{)v#y%{xMcBB{^=$g#^_Ia+f|DP7dN~- zwwBJEX-~LFa|5)wT_fTnQdY!=h-lefKOB=!86BN$#q+ll&aP*lvWFSvg_=}~-_iZEv)vb)8-Y^qS*C1FA*d5rJ1wRDoo>nhg?!eZ z`}%R<@be1PoMfN&bVueq_-R_~1={>&$k131dzZ`^)NUzfZX$rb!pBKJl}xkC(2ik* zyGwu+Pyk0aK5T1yZ+3-Jj#gxx}uC#3j&tfN{k)BZG9_&rq7 zd7iICo>*Rg)zwfo!y6*t>OD&HO4X8i9j)?{?2)>~qz~%)vqmHvZZcd*gbS zwwKC?HKc806Ed=Pe+il57+w^S3@s-(&)VTir9;{3BFEXoSx(*4J~r0&@OEm8xA9tF zU??Q_+?!G61~gNm_3`?F+Ytqqk&VlFivoUI4( zBZh`U>04gS`<5=R2q%4Bhr=$nz#Da$rdA2Dw48}U14I4PnF})ew&n9-j@R5M);lBU z4QbLEY_FBdUv2alF11<8<*Dla@Fp$k1Rof)SEHd}xJ6jdG1KL5)wiSvEF^%y1>SFghW7XVlTNWtku!C>OT!bI18*3Zd zTK|+e)L7X|oa_Hn0+!0ME;K%!tF6>WsNVIQ=3$upaVJ#U0Kd(&YIyH(c}A$~>9!iO zRVUeDC<_Fg%(#J8Qv~@6*~awxO+110$-|$}X9)^uUC8*WR(w#}PPf2o>s?gs#io|| zTP7Q!tPWF|l)JSp7tj5dKC)3C%dd_tzDL|nKH_s=AMkyO?`s=h6a=y%QB;)bDxMRoO#o5)wSD8F5Be&8oT?6W0LbzZAvc%7dI}T3A z!1)a#$_#JqNKRz(a5^cGyNX>u%vjmETBi&hX|MGqCWFX8f*-2KtPZ^H%0{p;$0)OZ zCgr?#;#%(-w~HCU`5*<}5e9Q4pLmvo!vn9c(l}884zpL=bUZ!(YuhtMmMd=CQYzixRTK1mttV_pDxj* z%%|t+@oHdr$HeCBej6^0khdimMn8qy86TKJ?5{|a+(vS2Bs*7=l$zp`8K{}N`xa`3 zioZ)byHg8B6aj+})Rc*CzI*<+CH>2OSuH8iTUgK3QjBHUmN_HI`H&EaR|BNv9T}Xv z%muua^>e!jz@J`*9>751#fG_jTNqE1jZk;8fft?_c{oX zPuG&uPrqOBJ#>=?Ecj9t*zTNs(D!TO;XX$fLq=qt9`W;XBq@D2tHkOzVXm8(6&RUA zcXk+#pyA<8KamfTBNMA{*@Y8AVxfUOK8$>6wUQcR+h_LHo6GVk_+0(-xA0clw+Zw) zCFQk=ZyM1>T69Y@cDR<@Zj*T&mWh`59OJkVP(Gs4T-D40hd8*iVuJ}Syg%=yzu8zQ z%twV6SS$r}onKE2G2gcBjj*Prgktktm4NUs~x)`q6cAutQCm5x`K%b0N= z(6K+c2VQFi44UfMRQz4OW|g65AOeEh2%IwCa(lI!JP~n*g03{imGmI_Qqvse(1~A;3Slof--{nW%j}P)*hcW zb(Ew>XH7a3=E5^~&qv&*8V4V1nlcAOv=x<~Fllt;x5&1@=)fK^24SGCFA^B2K6Y^P zgO5{M3Bls*iHove*0{lbLaM$3-Umj{ouN3mh%EZ*g|F(b~OpeOT_w1+-y{e z&Rw|V@#fxxwDY=|azrKU$)Sz5B|%5ByEx&c8=T)9&B_n!nzRp}xiCB|>0d#xST5tl z+1-{(t)qx6(PK@%DcoyXzg(5mXq&t1 z5j-fm!C(26Vrx$otg$35?+5&$gI$6>g5`Cc)p@AxEwwg(N^d^gXM(%YEGnJ|OyEd@ z`!u-ifM_c_~qc|TgKW~v`Si2Q;Rp;iI^m;om47onWln+Ib z&tUS-*>iWlLRBVQB0~=~xBK00?Mli@X2#(8Qc)Z11`qQ@CtM9g#zI;Q`6ac-%%Fmy2 zH=<44g2pD?<1KZszW4B_7%V+WC0xE+(Js5WLDup z=>C(Sp&VP{KYG^R4~nr4K7%v^BQfd@}@9 zq@g@4V~;Y6;HNd>!0;Pk!Fl!6uB8_h29}iDS9vdEImpZ50t;W&YG5-mLwOqz9nar} zh(T)Y)1y=aG0g_ohKlKPsc}IJ-nMs9fh*e5wt@pb9s6*f3^UTs?(lhXwCtb-sD`|b zThh<6P?iFUxZZdtm3c=x(hAoB#ZqyW5*jWrmPG!D$Jko>#tDhlqp$Q2jA_PFFF zB9Fh@u^WZ8>+>8BGB+^wojkP4d*emFjhw<%MK0RVzzPwW4)T{pf0a8CK_w$*M`H3j zDNGO#nk~aHG(>N`G8+3r>>ED!gn_{oP3Yz*ntY55 zEDm$Xt3vl|YtZ%>lTGjlTdf0!%LTQ_G}I_(MyCYo`h+y5j%Qh0J!r8HAl0FBw4Cuc zniklWcydDeA}FZ*;}Had4Vv{s;hPoSsv>o>kH7)b_g+r`H91(Z`cBTHOpOq9?)~~ zK=Ix=C9NbLx0R=HwTjJLDmHeJ#Vs>=!`L6oTh-GNoBF2X(n()W!IAm=!}Z%A>A3}& znFf(&>(vg%8T*1K_FEM{NPq$5h7q;1V`6@T4V%D6?$JIwK( z(d>(f>5_nt%f1y<`0-!GCI#fya&&ba0I0NSO*I#7H5U~G@qk6DtrSBnhw+KGyJ3W5aD?g?liLB(2Fzin(~;k3uco#YEzk@};cFvM!}MLZyU^iuxr=la zrLadhqPxr}CH4|BA+abc-Ap6JNY;Cl50snviv1Z#`wfiy__ALy?7r*|zFBz&{{#1a8Pir!Fkl!D{$ ze3vv&|Dv74v=D$GK2(vIOfjs=9dMU{N`uK8+ zM@^Fyb zKpdn7+uoVo-Cu8I9OC71%0oMs;>N&aN){4(Lf(SBM{i%L`-y{KWi7wNWjS?d8*7lF zc(0$&^UYpzp8D&F=Y}7>b0*+*!>>oAf6C&MVN2Y51rFTnov5gm_+;*1k3SE&uD2Xq zu2Bh>jVZ-~F&d+=(tS~!%9ohL5{qIx)0{cY^-?u3yN)5Fy9-nu=9Kv^pZ)3RD0~0W>+`KyL zheG368(dtk-!T5Ek(&7OF1+iFNS41oNQxT!wyrD<%zr6aj5w!Q(}cXJn8r_#s@!Yx zaCJ^8e;xVac*8IGeh=j#4B|kaL@>0i!pG@cL%qe9(-FLfTac+!JuPcnH7;STWp{qC?`sdME* z2?*N8#xP>42~Wg~L90;}`aWNkY7xhuxmS00VkF}R=x7WSZVAa`I)j(Hs}73?yjn+w z3YxCh$u>8WELNR{k(OHx7NxpIwp=_7z6SKJpr$rZtNfyF?xU>7w^*)V-25r$rwH+X z$o4*CPZSR5qWO*Ja6Y;;*)c!M#1FZr`iR$fG2JUIcbr83&5(lmn6LI*^JbP#?cp_yk8c~NW5#T9^ZQ@d>N0R`Z z0l;a3y7me^omao@uV#pqMVp}$s$^mQG``9!M=ZyHDry4Bf?#RoOc>7e!%4^46iAaH z<{PUr@T;5FjMI~Tf0`lk=&uyz81uQC9KURT_AWLzkfz?_4Sv{KXDQcp@FrtNwCswu zQ{@|R29S4@V{WozE?zRHSNNB@^4P;ko{l+;Npr(D7ioHnbUFe3;SadHI)lXw91Lf6 z8p`yjgh|s5ye*dK@SYi5D^{#zxot6z6EOwEKDB9UrZubhTVzWyQ^jfx3&rV=x$~d?hwyN5%G|Flrd14!-0db;&(+>bW8N>m5ThQtuZ^FXFqB3j z+`MU{xb7H0D6+h^vz*$rKbbwTO94JF-l^nd@L~wA>q|*dch$P~6JXnL=m@^Cl9ew( zbISz7BqDd+f?##rD?jvi`Rvq+{{g{rkazk*zffHlQoLur$$5ntlNj8n+gbbCW=^}-v?9~e>dd9@Y2KQo=4x=t!F`fquXEbtq}7Ulfd*shuC~V z-B6+*8a}smkX1zb>O!*3=9IFx@Ul_0ip#~es^>=gS3A|V#0+%LfXq(pr|9$v) zdBYB92@q4iZSjR_X?b+*&!VE#BZS#so&f;&dV6r{x-B`_^etdZn9e@N&|B9Sze%1E z#86&h$z+!sidvZT_P3KIU^a08CfX z1ORHuzGcjSxNQwd#K+$lKYmxt-&noZrF~v4L^`0zQQ( zCwoHO-e^+EoV~Q37TUv7Iig3-H=ej_KxfdhwXxbZSI_f+2wbI${;5l?2EnF>79ygn z+MLVfG9wK+^HswcM!H%=r~Y-DfMDqx>B3ZFu?W<$Rhrk6;He=E9P%Swh1sr?2Ba{X zzl{(QVg}RrdcI32J2qzICGG!$Bmyvs@!x&|Lje9UoBMWPKcRqEk*5MhzA~ihibM;zmIWSi)TZJCZTixy8q*)e0_jshYhbLq~`_Oum>mTqSES%ls<*jHECfzpajS$%c>Y<<4T?54b{%-mD+i_KC#IRCy6`?T)9%QUg zPx`6&oZxRKDLR~}kv48C&%I73=o#|K0mkGEy>@xRBoHigSQ9yiCjo0ENz1nm&>IbR zdju(&m#YCEt7AADV4)hG?txd9ULDLNGAH{jpm0KF zJ~~4U76aUPS?$gmK)`F&crZ}n)@nOi|epPe!gLTxIk!MNp<8~aBehvFgWv%>)d4R>oi7(dKp zk`b{v5AU%yG3%s1Cbfg2r0ugggkC1h7`R5EJGg*+nHYHXV9k(KGF7*-22IwsF+O=$ zBE#2}pFx6evX?V9AxepBWMt?=f3&m=XgdfizkI0inBf&yOolXJ`y-*X&8H5<72>S1@69sr5; zuKP3|hwYFn%OX2{$0R2!&1JyHsSA{+0xmOa;WY;@ON4~OGMT9Nv&CsZCxo|dX@ycu z;+&ViL)J65;K{>-o!ZL1;pe}8yk5+=vN2kxx}8r&th_2)zB-*bSA4iXeT`UkW&7J0 zJ51O^sJ2qa8|BD-;JlZnIN-ZvDPU)S6_hcwmS!m*Wq*XBM!Lj1&RKYcqtVV^2X?LX4+N04ztdkG@ZCN)m@@r%ZkGX48Y&&F ztDCPGL+k4{i7J-X;frG$!A~~ycH^sb{qg=`H7BNEkcIo!J-d9e*)_~_&xaW?2d!uz zYqRZUv9tRNWCJv8lH{=}JnvY@6BW?d%3sxWgcKBD2l(h>gPjTrjs(mu21Gz!IEG@x z6zJ*vZG`v~P=jxoV}2}kP61*AtLATPWVb%F$CiY$r)F%q~)P>#`moS->&`c62^p7&NHh z#-Mu?TN9n!GmtpPa+*G_Lkx>;zn#b?0(HSs?PA5neN6fzs1nEg*4!TxtvuZ*V}xLVjFnmp zga*9}8(sdH5ShlQ1pz=^Skv^@Tag)?LguIFcopaZb0`SxfVfENW725!m1FSKx4knv z5*yQS0t)i@)Jd3ybFud-9*hLVbgK);8}m)&9YQ5_F*U`^)s2GoABm>G_G0;Qm4cyW z%+|(G1)ZJm`@xD++ZC`II_@3ZnIKUCv@kI=z4Ui0|gug07dPK9A{1 zL84fFc$Hni03yUb?+$VK$e8blQGArD!uU>0+j)gUoW~==RdG4)Y~FH6l1%bg$Cwb> zc}3M4g2nLGp#jz35KC+z3rZtMdg7jIGwj@S1NP3w+CL84coew(T=aPe>y!NQtTv?X z@%!D>Nx+L&C4||r-{7@Tg1_l1%dQw~3An0p6BVuO?CMxrMkExk%nv7m{K_scLZ4k7 za_$^bSnhOX@Mx1Iexw^PJMqK-yRVF5kW)nF=EUCJ-2vrdsl-gWvIRk8{WszQ>Hi5C z-^elcj*|C|8i{t(H1z9LKLASKd1X7X?C6pIeuaMv8p!V0xI$1#fM~sOqWM(AJdror z{5Mi*-1aHi&A2w2SwNuiTm~zt_^iWk?|#2?%cbx`?+Ld|Q*U2eE;GG*?X`vH!-?1R zR{h09Zg%}Lw+@AoyXK2*5Gw*I+lfN*tORdJ93IrcG48Q5@$Js2nbIe=K=g_K1iAisAqL$kq_H@e z8tKy7##HrCgRMsxDXRiueJ&K` z=6Fzq590P6kV7BKwAu_;#hHuazkS~g9JvBWNV&3+BkJMn}|fJxM4OO(TS zr8x!H@u4V??TtVCN6Z3TX#_%=h4sD(xBR~GN`{c?>yY5sW;Kz?OgvaXeGMIIuT8ch z0#yu9?Zjke;&4T)pldt(vBpa~*CS0NZ!0UsS1lENRnT&k66Jkiq%#-(P{7(kvyz^N zo~VXd2?p~#@m>CTkn?Xw`2%mcRp$`@RtZHGPbcP>6}^HfdSzxuhm`xhvK!Xy8%(b$ zk$jE z?2kAr>2G5{$oFN&jl2G9z6PPwfWCaEQ1$;PnTOQm6rRRHeYohu*~&c}!oIEeJj|!9&bslRdR&m@xkGO#*G9*EOU26pL6(g5 zb}KeR{i_yRS}Huo@ob{av(EzuY&bN*Ysv|Mu~SeOV#%4}o$?*3br0 zE{GJCwci-`d(L<=_V&Wxj<$rkv%nz(H*3nYo2$i&6APbE&TVCwsi5#fk~UQBA8+B% zS9tnS3%u%rk2ow8xk+RuAT1VjlnQVhCXw%V_(8xh^}&FSO=pp+TLR_b_U?|lQM$CL zXS^)0YJLIzA1Uf@V*BJyzUs}&r=IHlQ9pq{LJUh?ND$S;DIz#E70l9qv3Dgb|RlYAAlSVl+GYb{%G1k>CSFSNG zX34GKe=~N#FdTX^5LV!lM5OlpdN$mly?1i9Av4yh3@Mn2dc|1=Smoa)QDi5gAoJdw z- zL>%tzB(?QC6^G^ea=DgSVFzj9G~xgKaHjV;d^jmw@^{L9Ys@!sex)J2oj*!@g1$lr zW(tTKLRF9KbvS4#TM}OOJ4EqyXcT(mP+~JtSSZWOnr_!EtbZd3{F6N^F(jf8$Nx63 z+h!74m+q>q^{3zdw!hW9We*5CoHyG+hnTiz1L7yAu9%}&7KiOqp>>s&ANHc3y6Tf^*Q<<#2?mSgHenLl{Xm8-u(($B^_Fk-m?8|^{gB5S4PeM^$EQpcKpot8vR3y z_4?zx@*ik@Zo%f4QyiwiVb|{tz*!}I=JYvo6v*-qtc=m>TSa+kySV@MPPz0s%X+}@ ze^ve)xmO+bY%r)?p}rro9$e`&NPBkX+<%7ezUs@WV3IQQT!5sNnK6yhV^u2lB!xvc zK99hc9M@FXRUSgfH`xB@Q}TA81h6+_u6tt zc=YolrKL&uCh1+y>jjJVXBks|PLipm4t zRpYW%`M%R0bW3K6#}|0~F>b2g+f3mK!1xCiKS3X6@oky{vpO9JE?S?bVE(U?r{HDs zFmU%J8u3T04r1H4=%g@sY_fOfaTugA2}J4e{TV#d(^W7xplJ&c#oz(|?reyU+5sZ? z)7)hu`3yqQZu$A|JW=l-GD_nwj!Tl=AxTMZww4Sz(ie}po>ht4|Ln!@Ej z-Gi^5kZ~3(tvl$dNAIyle;E1dJGd*yhAL1tZt$}hRp8V@|NFPm#c^w&eBPG_?_JpM z`mm_I94>70C9nj80!GkVPAzM7$ec04fB!sY)np2y6%orjrfZ!$@yG0|)uuxJv$*`$ zns3N~Pt0o2urOjUr4RGKf-|1gT$Yx&61->FYR&DGpY!5xyA$1|p_;zi9#pD*QIY2J z%0Mv2#Fj-_s0(-X`DG997lebKBaxCptb#N+$%z8C1hd}UYckIaNm}jjb!u48j8hYv zKU`J&ni$gFuU{gZ=6Ju&p1XOLH+`8<`()_5ZazdU zghM#=x7WB+@N<{ASGic-$IXTV zWGi@~74`t;2)kjCdmXQlNcD)EyjDtOX8#hR=S7qQwb>;_cP_M=WJ|`AqtSLVpUh)R zmn*|AG;AW`?dN?|ESIo98Jm-Bl~t*Hdu&m(h(#>8GB|ks^Sx4^XbAAWr{ChXBlR=kZaTt^~1qwup8+;E*cm@;1^s#m#r zab}D0uHpzi6ASML7G99Vv?l-DtA_8s3#qO1qSr`8_5pn%0uECKbnNc05 zqS;D9*}GrBhIYPK{-%VEgS)=O-Kr>Dl$ee+7*0uvl7<~nBNHMi%`#fpr{@(fHsZI< zPF22Tn%tupx6e5BESG0cu@~3czp6sb?UhI*7(#AAlG$t`$(9^e5@M8xeD09k%88iM zSvk})=HtKm)-Xl1o3}Vt(qYnj>=0S^KmO{G2p2(X4MRd~K&vpNEBY5MrB@PeQe8T3 z2x5MAx*CYrCfNDEZZ@fJN08wX_K1#*ypX=ejEFl|tXEtYav_ z0xS_9OSGLP&@Y^=MVwL$_7Mv>c#g_wUNe2VeR4BF@N!nghtxW8U&0os6k_E1yj^}y z1{{ddi8adJNUX`FDv|iVodAHNYO8YT(ofv(oWtt-zZG*7%&iuSO z4c9^UuJ&mM=nW{GqwR+6RHr~O( zB;_B@j8nuyB#08okZI2X)8cLEem+w||7w{4pZ&Uk^J)oR#R6kmVfMTu9UW0x!mxPS zrgtWW8%6nqS0p>6>mn?&M6+&?UCW*L;$(W8(pV;a9n>2bUgm%fH}uq4c8rD3FNZNT ziHgECMO9$G6%7H4Hs@&?6$M_L@PUEVJq0UHWxQ5Q=^WMO0&LI4t{B}^d9Q3|*FcSG z`gC#*+_8BB7V#y1xqo+MwLHgOKfJV5U&mu_*zLB`?vYY<%}XWdt_*^fa{e%jO%eR7 z+*sL;V+VeS^$t7~>VXrB4MZh{s5Hu78HpWA2NXB_$1mRG#e|>~^c6zA8{R2M@H-GF zBIXPDnu5F!@;ean@I%0sinqV+K+Lj=h;sq&%cd9YmpmH(={?iMQuDFa?1jZ9tz#|; z9))ABGgr%?=t!!n=$n&Ka~p)dOi!pb?ne&V?+ag#Fvi1+4;~<9vxkjg=bH1{tR3=K z%2GDZBy%_lsHzHCV^W5*f5XBRAk0KU$Nz># z;hw@y{H=>Hg)0Q7E*(wh2Li*&LHv*`!X!SZ9Ao3$qo5Quk64MB%~5i0$m7LN3>W+T zty`MyGU5GLYn_E*DPN=7B}}5Fm&T=sh#{+6LQ-i&%|3sk0aMq=>gIU*Gfef>aQx89 z<79^HH-Y;35gX?J(!Q`r{)hFkfOL(;!VskV3>#|xg6#Ql^o&y9-7ls&p1Y>ew!)`l^oZG8O>dYiOSgwXmuP3|9KFQnh>oJPbGSjU{I5Ee3EZ@*V_%XII zS9HXW%f4HIOALQ!v7xeibn0PeRd8Wu?s&hdt$6Vqw?hj~o=hC$`}*B{kjQ>M|Ht=C z#&_2-GR(Je$r-5nCB12x0SgXah0X#dV&}!*^`aEuQT<*#f{x2B+@f?7Do8*BLH}Ev zs~raHUPDNO)tu-0z`;>60qN1kF|~HyeYTu?YBop>n9rnr3jOm1S>oNb=`qzgFqm@b z3a$SS+c}#164oHyy89BY!0uqn)3lrL%N9~WXwhR-8n6}0NLLFCc{g#_1Scw9ak^?k z7aQRfErydNjt!9NN}hi2WiC40A<}$9Jet@hpbR{le_q+SET>1v%;9{V3E^4OT^9df zUOP74`;Gmb7$ykK>5so^zPs+!Gcuay2d`NyWgF(wOn34y^^X2()6uTaMUJ{XHLQmI zoeRG_omAs_=9;pdDicwS1+yuqb{5b(T1b;55;@vhL2Tt4v=A+)Lwp&%|FB^_{JjIS zc>BCeK`+R)Ktx5eKPP1P9&Mt-^7or?JOwQEyXUb;1$dCltYO1XaubA4VK>tTpzQO1 zg5l;4BczQmQSnL(*_GwJFlYCznsBpOz5a9{e>o6SiucVAfAAhR@^YinkxuI(eX_i} zXn;Jjz{PN;*{SBUGJbbWa2N>dz+JR)<;0wFbPoeX>RjGN)WnvFb1jbFI-LqrJ3}9_aS1tSQu+z_xlk zH@;6@x=U490!#8n?w-Yg6SxKk!VCEP3{L?EM{y*uEJxLzyY>^vg`qRDaxYAYFRP%k zF>=A4>ty=nrqJdc`F_`2n6_^MaGgnXI(%T`rD#8GJdv?uH0ql>KNGFWJnm>6$aBRH zk{13%tfdjVf%&U&6X<;$TRp!x-PRiId!Ef2M4*Mv%1Ld8DCld{Ir3(qW;HdTfQQNa z5R#Y~(17<Dl;$yveg-OImA( zA^O#kO!QQSSXe(giYsGQz@fB~a2Q*l@?4%`pDksu_?oh65r*_PW+rCRAMz|EXm{nP zIV;YM;0ArT*uQJAz?LsS}?DMZch3m9ij8t@b% z8oJXYU%(Ly3$`ifz9Ba4(nHc^>VSK#i4$*Zb&VA|&6v1acN^~SkWOD2tZi)kKsf&W zZDtZR=jT+A(h1qUnnYDFo*jaYb4x2mrnfliAnv(6Rs|HI-b_Cj+F@s7XT?6$2N=B0V>lSxE*isLUh zv`W}9Xeb`h1%r&@!SyU)_Cyg1KjJ80)kS|`F_LY-y2~d~9~(lY3l&ug{u1Uso?Mvc zJ+jqqQXS9RQ9nlnNi?OUrUl-|TCISs!`)kY_T+CsBxn7nOl3~!#VOhkSh~K|1%9~;PgA&f5g0I6fr*Df zC8p~urY~sh&IAq8>fqT({S4X+d)_2~3ePah79;(@*`!M-H*+{L`8?gv({#RMdJV*X z)@!)fd)Q6Of0tFJ)Q}G74R%H3CYNw&v2`2**l5sfey4#0Bz58cRe$Z;ve zZ%eDFU*4ot^ew~IH=YCjPna&5Fo$9+h?lB`CoF~2cVL?fJ`1*>Wx zUcw`#NIUA=E`<@M5klIMUbZQ%BMvFWR7}}3>fc~!gE!>z%by;O-}cMRKW?4tWI0nM z84-vtnV-NO9GXelMIBW|n!J!#QYi5}mH)@`cv9{k9l<<(L~x(E<6qWMib?F?yoz6c zBV=xMfKRtoUs~VyNHERTMLSbZ zHIi$rP zB28}My{gym4m&;J3beJ{UFP-*HSeAefPhs%2mX$bLYR8(BOY;s~?*g`1Rv|(GgAI=(p-!ejPWLyjL79sg=5!obK+x#CSSWhX!HK z=MAj5g|Mib3pRbYPZhS26O9h{2Hi9(--^%eNXHf{*E;3E&_~`+ICzAtyA8kztii#~ zB4}f|X`G$_=}#hj+;hH%b@~6@4erm&)ns$`t=EQ2OP+V3nFWl(y3vnsKin4(K06b_ zTe@|l-xHQ1JJ^v>x7ER)dYs6uIa>xR=Z2nS21 zUmH#|>9Dg_u<4gaFMD_9ND7%q;Z9PS&S*z$u;mRU)1!4EXRh}SO2WJmE?%i?pQJSE1pwsiUtTXa`z&=s!pTW1$GVAphI~TEcN)j+G^s&3YjaH}IFP0sviq z+mCxt+_Qf0J-ZfySRGlUT-6*tu^~6t<@mR?^Z94@KsA`7E#aS>#9_xA@$s4`DCLcM zWYM1QBw97vI0hM0_$<7+lm82QhT`+%YP*^oXv^K$>fdj)M>UjIb};ZU%;`JzMO+L= z5Af~?YwX}MRyo=XIX;@G0Cja!PJ3D%ccjxIQ|ro)b4O_R8|u9)N%weIQBmPT#@fxC z^ior}qoT{-~hM`T;XL<PQ*)0@hJZcWsFVT#0NDo;^#yE&FACs(16X zVk2i4^}BPbvB~CE=B#MJmf+=x(Giu6MYVyWz7p?;9#&SBm5qe~0Rhe4005xh1i9y> zb3ZioNU6Q{b#h7r$+4lr%M-sS>=u(G#`?`(+tz`g6YAbme@9)am@9ciDQ|UJ2fw@f zvA(5C(w+h1Uij17BY&RgUQ8%To2@|4=wNHHjQM`>S$sWf`=%&QJdrM`VL^+ZfN0Wi zwAbd>wo$k{7i?LRCwKd~Ijg+DL2vI`cU;SoCo6c<;{wfoj{y-k?|b$5N0LSJyQ&Gh zDTz(NM8qRW3Tdb+we^+}`@LB*>e1@{(_al?MOpK(Xz4eBKW()-O?D5D$Edu8%!@Fb z$A_j^EYbDRo&1+ocOXfzZSx_1=?SEfk%ux5*Rh4#8$(&~jTOQ-?DB6G2#fDvQ8u|K zwd9|v%(-LE9!Rl40vA7N=ZD>tL&d-qbB^^30I>5t)9ZHD?Pxbk7k!O8J)eVmFRm#3 zjh2Iu?k(HpPugZY9QlhZOvCS4WA&!k8c_wp@Wbw`VlJh3Qw7GxA}>Jk4t>+OB7RmL zO?iAW9Yj+9d5)AL{3=oWRMKW~HPuDxa>h%V8V zk8O@hFXoF$=gZn3&|IfRwzOBu{Ys{4g`vMn8Q>`q6-^Aku`{_I6=b9!sG*DrPY5fO z@8+*wTMwMR7~Ts8T$P7=y=XLsHSsgDq)S3K#bfWz{4=lEZuUv4%ApH>3;+Dg$^Q0> zN!&L;_>Zfnpb-lt;~=4RX{omIC#R&?$Cd0_5gU^#_1}yge$rrcd^&r5JxF%4#H3;- zg}H|9#c_wgSq|M&;6*RTapt9g4#B;M%XI;Bo~BMS5!**gv&LIYiI;i+8J9^vv)&Hm z457V)XVjr2(5qiDupE>A4*-;dHWu;;j;>p`gG~qS7un3X5`VbFy~q`Bb=qo;*j4ls z5*7~q!y@MFnrqAvDb~(SZN?RIk-&CqnEB*p4xid|sm32Ge1OZyIl)uOpdNa4FSwUz9c1&=f~{I{TL8?e&zw**L&pGXrNB1hSfE@OI-sn2}|mFh2Own%{tDTxu< z9Fd!_@h!L>c1!Wam_=$H7T17vHG+i93uCVlA4CcfO*BuM(4bCH#}fkT*QP-m`35s4 z+@#r8bW3DN>S^X#)O@Mcz>yh~_tZhNg_+S?@Q16}#$=IfQj;9$h9v!BEaDybKIsL9r!rjF4xkX=_NdJHo`)DaNGZO^wA17lKYELG^UA1k!MLDGRAel-%z%*_?qB~|UXJ0|f&`*fd20XBl_!4~2C7iQB ztP=Thf2KnZX5SzAPZweLLn&28ubl+KSeTR2LYR|ob|t68RJp=xzRHx?%9=?} zx8>Q34)LQ&+M1@4L_ zKCTimRwc{p$xKCZQfoVz*{InBKfMXY9_&c&PcT@y-AcZ)l+tBxK;Uh)s z;sePZ7H!lIrK#QGCmmclu3RNz4e%OmR(3bWb|a5R;h>dd7ZU`KD?`dfo_M+U9Wx9p ztf1IQ`rI^yNkJ9HPX((x4LA)PO3@Jm-JJl7&$EYiAxD}ow|-VyUVX$0OqZu9fx?+; z>fke!ouc3Jx^_dl=i>=5REfh(j_(qDYT9Q1RAl?lX-F6rhE z)7ZbBrn`aM+_;dx@)X-OJ0iz;w&Lhj^zkZBoq@%i9qyV52?2!jK!3+W4C=-i)i5-{0r|K7 zmKpbbHF>8ZA8N@CPQ2B{hQGxPyS<)kz2Eq(4*Sso!>kMhnhskrDued@ltaBP3c_p0&7yQ>39`MLjIlJl~J(2n;Rtv~9~Lsom!K z7s})I`M{L)yi}_p6V8*ybtCJ7B`QJ!w5aJ3TJt-n#4Zggjz@&T0X}qO`K~;U+8{?qs5^3E7!h7FB&@0zuXJ(&eZkzk?m`Sj zeonid8b`sG;|N02RG-0_^P34Und%gr+5Smf~Dz~X1N#NVZuy*#>?tsyZR17CdZD0 z#%cPS42@%&L6+e;H~}M{$C1p|-1!}-xqo;sp84wD{LEC@9FEaR^}N(3`#8s18pyFn z{#+EaE{wKEn^W%R)%f5qXpEGBE_+d=uA9RF9|%l#C<_Nww4|i5%8FrsW8uv3u;;)% zd%j7xK?wReMUPdF3_nE5d9pLuG9v^W`Jze%*Rs_S^HB$7{tp=d$P4SssxT(S##&jR zKmuWkOG`8-^X1}C2?x^)%+*NCNeUC32Qt-jX5AN};5_OoD-w?|MZ4OBk)))keWSre z86RZVIaVP1$5i95lY0~IR!OrrP1!!=X#k&81yy}~WPU!>5eg>llEUKkmf7R>K0^A!DVvsXAQNs>)}=>LiP{(CD@N7VIlR(zh(=1D?xk#-<^=3?6*uiPo#o+ zyDl*%fqf7G1r`7UUc?@~;?O}VXZrX)6{F(o=6u~DOf29CweKrOlrcfQmREUT8Z(29 zmF3qqfUg;wO}+kBdVP&K`|q$eIB^7q-}sEU!VDT#zK%YQ1OTG`fmX1#s#v9Pq}=?> zmMRI*=_?qCKUqPz&G`)Y)AY3IWlT;KfCfR!&?WWJiNT~lbEIDC6JkPO?2`hQlZfQT z0VLP2{Ke+_D`dD{Jd2Yb&0iU5OVJ+|Qbiy`baPIO}+dzT0yDi=E5ie;0k5 z4O)>jMA5IVdC!UNdUsfqS4oD z-#=Af5wxG8mDEeEln6tV~DcIv=7W*6nNtOF|Wz54Oeb%HUTE$5%fQ z7VB<9o`4;Vr;^n~K5QmzPm=SPc)M?U@yrgbN;)^0bnacFIjU2L6MVFhv2 z8bCQVv;!-<5Zn!GR-sPy=So~kF*`HCZ5$5mlovle3SHd@51IbHfEqpX_LZjw&__YN zf9}72Z`-`Hp5QKM)=V_?tUYv$FdQ!FeN;nHPSfKOY!r3t0zX>x&}%m5@JPn~&6Ixz zwwb16Lkcc8=SuioAxP6m(uQcVG<1eajdkGtjq&;sjitxxT`g6f5gYCDF9M;&m$nVRUHs5p24ZkM6cR4aLO zNC6!hC9ALnrqr}DW2gkF&=c&OsoUu8ANc9^C182pG+;Xma>l)ShfmNoPXL*rb@_ZT zuZ(cVdeKT4&X|OYSh3VMGKY5m{f;& zihg~0Bk`*UR)CHT!D^{nC4W~rL-iqm4qVA<=_dA<43%&_3q{Wgl%Ev15B8kf7cY&(97QLCmqgJ*MRwwwb=DFA zfa1Qol7ilzRCpeEW?3M7D{R6mXe#SmQ6nIW6V5(#G@uxg{eA3l})Y2kHWNJ;eyH0A98%KizK-mnC*?z{?0$`8fTT zqvVckXb4mUjd=e9D}iVzoYPfi;xQp$>$OA<7|x*u+otRA5^wvY#&th=>cqPPo&4(i zKeomr!TMneKU1Hxt#Q?5*QJ%id%c1Nfbx|Z zn7@r|P$?Bab{&N5L`ZffQl8rW&J&9RU9(1Mx{o*M(@CyqCGy(YzO4jHoqnPR$h82= zSJwEOzdhs*5fO%@fY2j-(kjE$c#09BNZx1+?KUg$9`bAL%94;O*ir&2=aRcK@*Pdg z-PxAS-7O9lYThV9;iPEDxhSwh1M(OyxX8I?fZnFo4<;leheXa;^YdXl9w#kX?Wga! zRtrebC!oQ<0-!=bYr*65OM@aiWo&jP!SkYZ=;X!z`*r70mBdR*hA%hAJQKq@H~T&! zc|=L`F8n){e4W0Sj)oGFaU$B7Arlj@&kAUQ4hN8eSODlH&q?WMce-dPPi)2NP4%Lz zTkd%J^ai7JlCM|JZTa=Tx(_rzfUfeJU{-?4r{)WEvV-5dxzIN*|>nkbJoEk^o{9{+iTTpwloFcCo zYvu$0g#^uaiQx-)gX1Lcadz?jcUGP%)r|{f7X2N%L#c=qNQfRK2rrd9r~wf4UX26( zI6+t^g*n|gJvt1k1xfLb)ZP8hH0Tq3vB%Pj&Pm^$lNLobL{8`~2t|05AF6`mw=e)(R!tH!5U zGw=}?&_t@sOhy-hwYy3&O2X(W{LA=_{|F$da4D zHg(3%%tj#R9Jr&|aj6d_6Hn2p#%w1N;`gr!0pMFe_^>kV@MG^()XwEmao1ARPRO|F zhDaiO*1&ADShFlEH+$Coid_G9GQw8LS~}v2rpW4F2-e;&CqQP9=MfK}KP0i_`gKFi zuf}miem+H~E-w{2u}$Aac5cZ!$Pe;}T7yHfmwx$tkI9}H_SmaoH*{)dOI!!PNS1!9 zN5JEThs`8-Z8e5?Kpgn$>dc+_rPGvd1T@@H?PmgLP;10cN)ejo;bR8W@)x zdb-!>U48UrmFSV|DvK*g{@k9r_q)o6K%lX3u5;=*8`uKd&RcJuSyqDha@#JpQA(Pr z%jG1+>UWjC`|}my`3?thGb5uysKV7fGY3?RRGym3mA(cE9h_^_BG8KWC zzi}8J-*jgGdH%+eok)x_4aVO}M4yMh;nvBl`)ZA(8GX0Co+b*cib8}SFNU5Qoz8ro zyLy~*859KkF5@!&ImS@y7GT$6bCNU{3LT`TF_tG6zYTFy|-Nm3Qz<0n6Iab!oZDkz0_Y57}H#kO@M{!b3w)8q}27@c^(-Nx1`Q5jQ> zS&}K0&WL_ohN|r$A~MFiw_34UwvV4aIc?p|O#Ugt942%bqOHabd2z1Bj=0zFPwkK< znap?hos1W@g_^(1@X{O|{;&_ukhQa;kk8YxJpfk#7WO>&BV34M`wSQbT;TN zy|z03gXG?Q$WZ$@|G6yX6`H=sunm#TxBTj{-p4L;1VvFrE(DE&hhA@dFU_RaxZJw; z`1a9}s6fXs*nnzc>ogeSV`)UlX|IiS;7{oZZaP~2@a(%^n83{nuuvx_j1#egGMit; z7;_?ppJwJ((5A&$$qnOc=M*9t0%du=3?h<*{J803qXVq9PAMT~LapCO1Hn8Wd5T&@ z&L)7J9r{9PZgN^?(%Uf6f71I;>5$qpHK#KCj{UCgf|Gmz zWlx(0clcl+f0OGn?eX-9ZcH`?<0olGO&8{LGpdsKy(S{|9`QQ?UR5 literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_curved_frenet.png b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_curved_frenet.png new file mode 100644 index 0000000000000000000000000000000000000000..f834a64867e6c0a62b37609f4c5eceb01361a9a8 GIT binary patch literal 76194 zcmYg&bzD^4_w^kbWN0L2Xk$P`dWMn?5fmgOq(y0lZWuvAWWWHF5D7t~k?s_f5RjB^ zkd$tC?|{$u{qfuJ5nANV|FHJe;WhbIt8Rgc_TGrD7?)dbJRl`>P-I zE#DdOi-h!6>J$75kA@S+q)qX8@dy|h1^HWs6B=dRyU&iU7avy zC;Gd;-)PWf^`*I#QL9$Jo8_{EP1*su|D1St>L(6u;X1F zy5+=ZkQPB_x7W2^b2iV;_vP8(NphT>TlM2wF>hXdQ)!y<_9RYyOt4$4Fq5aj zU-0$@^iVJi{PDf+EyWlYFXty+mgjM*Z|;m zKW%xEcbngu_L^#EVempgS^l8XX@&1WldOr{!(Y937AvPuy$*)7Zbq)L{++t9fnWXTzn0e0hIYHURCv#4ng42GmCv zh739nj?HxRNrq1xp33CC_U_FQpNV^#w6+!F%Ex-Cs_y>%F6dv?-ACn~q=s=F$+v=V zpAwe&C1Z*R7z!WV{KlbUdxR}5`du0YjXzv28=a88$LbLvom3T(&*Z~4O?JJGWO=3R z(A$2NGM{qBIG3kMNyqXEjSr-?K-#8BeHwa3o?Iw3_pRd~-onH9 zlmb7Jx-Um$uH%oEU+tUSMepw?QkS6>tK3ZwYMj=`4LUy_QPaik^6?hA)vJPUP*5P~ z3x=heLnznBnrdtx7J4mEMEH*T@xhl?VZB`rIosRbbvj)WnGW|M80ofZ6BphE$A~0N zYxN(}rygp(aw1U=%RZCK@3gQRXep!!NS3HEm8N^b)z6>(R*hg+4%;c=q0zBgdH+ea z|6VH3n2rN4o7h1A^0BT|z|1X%BoDTQW9$Zhn+s>wh*n6tciKdd0o1lCe_i?f8EJQO zw5{n92$*E;)R?aIZz0DGkHe27z*XD^_fzXdb9ZS*U$(=2rjRA9x9mh~+bGsMu}b#* zZ+8qR=yC^_TcX=EdSo5dz6{u$DxG)_eRx;bJ7}9W9`P%dGWQ31eA^XXnMa=EJp=CA z{+jJXi-*aPs4?m&=EP)DXheXSbp}qsiTlYab1Z+|&R}p`ntqiplW|+4$EI`MQH{wK zx`lMF+Y72SVRP%UZEr2;92>fCd8$;Gh5VU#doG0eR^ka+1`TN!B=w{`Dsa|Fv!w!d zzC!I>EShWKbge`noz`%q>FB2S&M|grry#LTV0fv_7ig-W(X}tstq=_0T3o^|$)wTP zXpgi#{tM=1Wj}wA-G-Sh87}6jb>7~SJZP@aCAJD*Dt%3YS5RUkF?;{bmB;R1?Q7yV zf9NG95CiWsUi4#k`1r(7sicg`Ni7*UTpXDy^X=JatrowqHc1DSIZEv(-lXBy^3{G` zuio9Y*E2F~rM>AQ&VZ!*jD#x za05N(=JIFK^J_8kp%kK{pL5lS82k?)r^inNurJ^7S-9D=d__!mrvw2QPtM4f?*fnZ zWCnp&2fI*OMcCH|WGj9zT4L-a5OkfgCPd(Oy9Z&0&@G*h$XgHS$`(*iT&W}z<0F;^oy z={aYyD{sG)Mq*nV5o%piMKMv{-d#eU?@xg_?_kjIHRgw@iwo`ETCUf4+9ift6?;W& zI{a_!L_2)y<|=hOPg5y9%H2LC z&f=wpu&x`GTlf?%1h8qP!w+^x-ly`|j5zN9#>SLJv3z>6$_+3NG_6%1f2cKvxve#R zyDO4QSN}KX`RbLSOqA;)y7S`=`|D>Tb!Q(99mKyBf7tKIayi%xU0au(xU0FziuoQ> zaDJ8q#R3||#;92-kFr*jYje538c0aR<9u@`>*_%W6(II6OB&3~OZ z>{$Bj3H#uk)!(C|IS1X+5jV_6(z67O{r@bZ(588FrW(m`IRXKXPyPjqalM~?13sGn zko#WDapzift*xl4crjI7@HHHu#Jk$-I20ENq#HHCpLl9c__A!K9RZlV%X^{@@Ghg4 z!H61FKu9ENx~z6$Z#ivutZHzmg?g61!`<#_k%mO(XtxMUk&w{)4{;4b_ob`WO*QJW zgySnpzdn3XQozqPbcDWf0S_g=bju+tbpluW8i}NnW-+5()ZrS}DoDttItr z`AdyD{b%QgHjy_Hk2!OSCYF{<|mMAGSvddD=lJ|u-?WohWJVDOTU*Nv`r@6Sjd z^w#5JZTg?}Y;U`=ufM((9U7wQY+U~)Txo)IwjXW^%*+J;YrU%ixJ?egy#BK__l;;#D@gava+ z)%+RQ9WPr5U3lj${;)37v389J&UQVjDvGVk$bkfPj=;vSlKk5M$r8R-8PBtpXX)v! z&q5-c-?9-#;fZ#g1AHBjEA#4 zhvh!3asMh{IWv`Ubfm`f{=qK0_Pk?X*=O`=i`5rLb*4`$s8dw;d+-&6pL(4#vw-CN z{nmQjCoG0>%HS)`)^x4NQ&rRA{Iwl{xe8dPfmT?iUpx==kOoH}dP!_4a@t0jc*t?wx2zt{EO3y~G>D z$ZKG&ZXM!+#62zSn&F6v*I|vo+*a4^g^`29J2)!!Z3dC#$-3~Ff-7c1fwOL{g4KOt zZk>JO=Y1m2lG!;hV?5{MK98w$ofwcBezD5*U-veQQ!~vr402r`XO3i(AOh9`4sV(u zIB0n41=FBi`mr5Yp7WfcRTJNsrCk`7D*q+N*)GT`={@wfnzMcA_h-L!b8C0j_zc-z zVc+Ua{i=8Tbe~`h9L)=6>bL4O8&R)npnwX~9tY1>ImfC_f!^m@$PQb8c;?;oYmYUX zQ{;)qq!W}#vu&53RS$xx^S7o9^eIvdY>RDizq?RP<8yV0uGc-xt_EvdkmJjhCWvLjd6 z?MiQVi=yk+)cml~L>KG|nC@ns@cPd`^gGg%8ga!0Fz!ffP5AS0Y=&nGS^V)hRMv>6 z1Xm??OAK&j&R)j~z{=lK?w@OCn+`5AflQvAX`TmLet$Q?+?W2~!=Y-BTwxekNcUWSss^{*HStTa4pvIhYYsN?$DAE*)io^* zAFAkD3v2n^cQc~=1U#ukPwSt@S{!27s~g2HDK=Pglk)n9$@O zmj zGC)c*$+5VqY)|(A<#I@O`SQGgl$4ZvkgSi6-~AxwJ{t)|m9IZ_>2RCR>FlOmp(#l2 zk(tR37>_79T-3Enkx3)PyX1K18k`Gkm`2;P)dD>7HJcdJiw;wKz?sqPpk zbC_^nuu`k^FV0Zl`ufy1JSUpbfoio$*#2UF+{G!7=C4T}>pN6Zl)g<#ZKZ&RWLN{3 zM|{XP@`^W_I}=`cxJ%(jf~A)n6%sv2*8AZt!SKd zY0+$*YVn6@VRl2q4Kn5^=vn%~U9TiX(e;LSj!Za~ei7=AAqu5n*(Mjp{9pzjlbnr& zw?5+xl{D0%%bi^Ip~k}got${m_jm0K$+lRwWA75*Sw@Gvv7M9ZlWTt7tY$#PyHhF< zdhmhB+s7opU-Nm%SDw_4JU&5}aVjMh_~hX)h{;YrQCl+YHYSwPE7tp(tmq6(L%V** z;%VBD8@<5cnw78HqY4hPz$%J?V%`<+j={ypnTx2-vCK?kY9FnSjXiRgEA_{DXLK4g z#dqO1P(-u+j2j9$_?Cxuk z4Om4<*7dc|k<)`9kYaQI0Ds?I>f)k}clqce;KFJmBq-9lUVY4>_q48m&^FO^!f$m1 z<-hWN!6m0}aSY7<$~x(-j^5gjbyh2KZ}uDmxNyOjx-sZ9r?ewJ^aQ5GJ7VKwp}I4Q zwL%I0x?#3_2gz4S5C7PF*@g#2<4#@IZQBIbMQK>A1!O@|F&(svbQc-c?EyK4>z*N=t^{o@gr$C)6L==AHq-ROWBSZa$uJQef zg$>ya&&NO~#_+BfSuBbp#bAEsJlil3P~ z{$BNpUd>dH?3h+*2Cjfmt4HQFV(lExIQ&15(-YblYPA?;V`fT5cj7@bbp4qPwY>4x z+DhI!q#t&AX*0<{ecs{x?|NnzE1fOsu-r0Fmi#6grPaXRsL z$YvAUN%^V^ffRuY4WUs@kKG!Pp%yL?!mi18*>lTmVYxq)SGbpDh*;8q{D$uhaY*ZdRXIh|Nd!lt|;9tJM|5dovg7x)&XUlBDU&NqtH~PuPg0) z%s8l%S3Ktcm0l?b5{KYmYyF|z;p7J#B=wQ4Go5-F!QU!2k(E7Yf*T$VZZ6hb$_IZX zS7x4~r7E63Pv(r90Dw;sM<^2dchR4Ga^j2wFBD8r=H?&_T**q;S=Q&R zyu93*7jN6U-B>E~nuJwBQM$h4eBGdXPn$-bir~wgRoyCxprg)dSV;BO%kl7Y8(a@5hnT&oOpf)-wATg~C?t z)c&-5%6Y!ih)MG^wnu=R(P7XYVT{u23y`I_Tw=FQ2K^Tc*t#ShWZ=+y!8HYgDizdXE^*^v5(^e%3%ge&kq@(i?V^xV-ST~<7C^GYJZk2C-uKB%kf zYb(FeI6!x%b9R!ISGyr!^iP)vk5{rH$bk4%j!*Ay2!(&+R8^WGet9o6{E7Qlz4#BI z8P?sxP_}&Efz>%IuhZ7G*$+lIO|R}3F0Z6XA-Xi8!FRlgf7~>(PIOoc=Vgv)lOmj4 zmU4r`zA`#^K6-PLBz3jjhYE{NL3b4dET>+rIizx|tw@d%FB=+r7T-6lT89u{pdMfoVt@56=mT2(Hbn~BMTg_Q&+(%t$ z(HDSAE@xS*q-Y6KtqZ~~?d4CJY6cMK)HM9tqqnVPZCG8HR;8vs=_NG>5UKp?Uz2uL zba@fNC2j>g{e(}EFOq*^cd^5SI@C@7{o&`&&r$)ZmkR9db8ps(qgcIJ)4n?^%PT_a z1#g1fXHY?@i8^PrqQBiTQWD(U=lha5e+YeP4C~KJPF|weqiRykxK^n3dXwRwAr}ob z*z{_9P~~jo2QfdgvrWp=3JEJ3L|Mx5?~iBwKz>$4kYW&Zv#BQWwJQPyvY9ulJnUWv zDZXI65u>ITE40{-+lozWezvK_RG8yJmVMQrtMaR_&Iz_+X!T0jnn z1&-ZshkhX?NBK(~8LrK=y1XN1Mfc@<`emWMem!5D^K0JMefZ@;(rTha#U$kQX!+hM!1o2bly?U0O@< z2jiVXx-v>#ziDSkc5mYeM0vw-f^x-x2L$ZXzsl0AFAkV<|9wN@hc|mOqw#X*;411H zSCPVj?sEH)@9)Bsx=PIBE?-`lhX5JY=57`&g!&;IB=3>XD;h~ zj?P9B0A|2XV8QYGFW%zj1=Dmz#xF)gTAa^!4pA-AZJ`ThY(A{Elv1= zi+qUAToT^jjU=*H-&(r+ofN)@d;FCZUPHN@b8_shDWxC${BPrlfcLS#g+~|NGp(Ln ze|bIXmh|mVOpHVs04#rvD6o_(u~+C}L~9d8WR+qQEvJn?;!_xT;caenMidhY>0+pF zG?KnR|1t~P`+D>-`RdNk&424Y1UntPoj>J!g{|Usi$vz~5FFY(oWaho zsPQ!3Cw-eg=KN(ysfou9(XfMsu$vmK-Ou+!ZF-@4siPlM@zZ*}fBitr9s=kP2~#&_ z>}9nXTZe}~o}x}{el&p}xn8@w8gGv}NW7!kANNdzMwLjq0T^FTgd--YH zMCGjaobs9A!Ea4gtchB22E^E4?N|YHE>!x^X>b8fh(pa}qL(y1toja*UaR41dz)|e zXg3`+rL|^rL_$A0q6JDQQxW{FSe%j(%+u7Vu#tE?AOj&sM_`rlY;mSF<0i~we!lQ^ zypmpjioKKqBSw#BI*WB_|71kdL0&&lz`ikpUL(E@lG?lN`Scpu#yr}h) z-8uT}qD*3}yt5ABvjKuFQzgCSs zs}NShf0$>ye2@r=uHmK&-HDBgfvwuBX+Ex4u7LF$YAt0WfywwR4!by&5wND2UkQ2i zY4mUkLB^VqA&|RNfJFKx)N$N(>85E%Kau07C5(O}He^HW*8%CA$RtIQNl>}yo1Alt zshD?l#zH1(AfEoZJzC`56tH2{T=O{FEO3ft<^PIs3Ax;INJG^c_p8(2Pe9Abx2R9}@NOwk;}yy`7%`vX$}7 ztG&hDhB=0aj(Sd$kp>W+NO+S-jKqa(dA|N8X7z#=L?lKn!srZ_0?UsBe}d^I zz;4M|P3AzB;v9P8nt~-O@>30^_j%iC=4G$B{JFSfJ6&w01*>*&F86tX!G8;~rTS8w zwZkl38v7Q+hMF+ohXT>C?QMMrHR&1JOP9rIJx7;|^)M--sMYk!CjShGlIHjA z5uHPqNQbUx>`9~94&;_G3Zn)=)yAyfy|0!&PpsZE%db?ND;agGelNCuyHzxLKF})d zy=(tj;(=@SzhdxR^TYuu<-LmDRzG}awBoUrE}2S2>f-x}toxC~XI+EPRLoRcZ5>iywZyy(FaUERhI z*D;sf5KBX&{GeR_kGi&IH`FwrBS=&j!n?J43p6N%G0tDpfT51sFu6bct~*4fSC~@J zj6z$NG)lPNZ_?zTG!lO_{;h(h$FMFqDl}1-DQ40;9o;6l6U3rE>EOyL0PF7DoQI8# zJ4IDp_9r?M*cDc7O$ss}rgC)2c>Ye+mJBG(*uN6ybuD+G(Rr6hJ^aylm0L6z=T>wF ztPauS_-_yuY&kkQ4Fm40WuM+$@%s5=QQ^sTLm|Cl&|OKE4B)DH`>e8nfMw1LCWtW^ zJMh>qJDUsm24j z36ry+XL{<`{mHca-12GO1L4KcMcBS7~mas697p z=h-~-zA$Il5x-C&puybrIAy6loA@aT_c&RSg$IaIio`vm7fimUpmtv|MMhy@#jpFR zvNt1t7PrmF6p;o6Dzddvg`QPd@?F78kiQNdT7;$+-17^9gc6^hamwo)Myj6u^)RqQ zSA2L)Gx-ZJ+0p(wS1n6HY`84aNM#iJCZ`gcS;n!KGI&Vnk1ksn$b zg1^Ndz!PGhn_P>UuKAW<9wjho#YX&+D9yWIF?+)I+dCIg@Ts$=nz)yzYSJv0MlUTv zje4ms9hp4qUNaavF4Ct9kO)2M8Vgpw>ODgCgj(VR9HB6+aV<_Gi?nliI$<%N(W|0< zbxhjvY0>_iqd&In^z>-Zh&<|x0yUdg!Q!tKNn!OZIIoTMweY&4OIw8adPHPeRqx5t zIbJ+1JUAUMCD?Eg3p<`v%qPN)-#(s8i^>}Ewj%2r znXejhAMx*H(l2z=CF&hCC9(qrJ-e?o^U++)k&}~+oOJr`Y*lW16nws}U#5mYWzkl? z&V;5jIebWUIhMo3Kf9@}ZKJ6nwSnY{FpV0*nIzK4@Ow*1f$*B@)wdVG5B;-`G?sd* zOhY0#S)g`lL$5-W{nN7N-^|gxuZG``XdL?TgHJr?grbvplJ{fapdwWSw15Y|W0@Ln zvOf=~TaAA=cQ81YZ|%+Lv)sR35!6+;O_bVu15>#7Y+jQisK2o(WDlyX5bP&R_?-rj z@r(}o>v=PWwihhf=2M8-EGi2JaqK~y{$AI}Z(cr=0|GXay5Vj3FYL>LD9~}TV*TQlpg{G*`Hkm|(Aa@LZ)0I+|@q&;SI z*dYQySh2Hrlz(lx(w7^ys+$hV&#(6%7wnGgf&5u54Q|&A5vh9qxAXI)jGRDi5S?IH zhfxb{{we&v|B0hO+4gPi$CJ%&BpJ{l3WxQaDcLW3yK(nWLe!`tpPO8bY4GRRv0)2y z@fEH+BnLFljn=W0AiMa=o2J1#?GhR_P@Dp`v-d~#PJIk>WzS`obkOpTt3+@X-2BPA zI!_`Xd0Bki=d2NvZzV}U&1@YH$XMf5IbtDSZ!Ta4K`_qNQM1q{lrd|Oek;2k3b{}Gh*;ffHu6j7d{$4b( zJVc_x&2C|jt>e%2r`PbVGx3=yH(<(Z@y)Wkr}wRTc_`YyvcIHB3YgahdCEwgciq&! zF4#U9$_SKsqM%mEo`vg{3FegOG6 zyo^w~N)k8U5IC_E1f3eVY^rxumv<+j?aSQtzq1SX`XqPTCypyYzwE{bA~=wZ8j7bO zuUpTy6bnD#}Rx$ds~b}e;M<(JzkG6+a={ z-`8ktivK9lH55;Ew6N24lo}|A(`cIAx(et!FW8!v9XW>9UFn?W_WH?^L$*B-@=MiH z-R?Ssm_JSjj`MF1kA`h`K=jn0XEFxsnhce_%7gWh4`CsM7rN&9ufD<4$w&9XlRrXQ z2X;lDJm>`gqh3v(SaF+o2q_(zjXmdj(!Lxoog(5_KK!AdZ{PfA*xpv|xhYxz2}54_ z{?Ud?{mc9##Sw)bUeSp#b3F_Ka2gvtfc3*PM@6Gq8{gi#Q-tD8AC-0-Aw0h3a;Yru z(fWZw!fS^|&v)CA=#xK=?3eEePFg(!%}#;0_c&sB&s?6oC(3(NGthhBs{V|($)zCE z{)a~KY3C#dS-gb=;(%rNoTr8rZ~t2VI6_aiEisu%&Oon7{X!28b`DmL;#Fbc8~vOG z5u4Yd#Q9hs9JzgFG{SGXqr{)Jo{b2Xns}&Blal#2XB>3%nXmtsSjtZ_e!i$+ zA?KV#FcDqRl;dR%W+w>?;YwQNPQBWA`uW;Qn!DIg7{01IbQz zkRRp6;{tixyM=SDcS1Jvh>rHuhAxRVW_QWdxd7j^DKZ`fUZsCVzB^DoK3Fgp{kJ%p z2r$V;jzZGxe@e(2RR- z)O>3@-OmL1)1Jppoit>k9~L=-TL%+v!vlrTds+>I^ARPE`-aA& z@fjc07Zz0oRcw<3?9@?%#h(|K?x^(MMX0Ygj`N$|i!p82t$@yj54(0Q$7(goax9fP z?GMCnzBe771K|u`DVr$tuqR~G(wf@IDL*D{Ml{-Q+v07wr2%eE788j_VJi8r1O%nM zF)JBO1RE~QZl$Xi8CBRrFn!=XAw%Da8j**l%{E zMYlDm(V2#jgT)e63jLFXXKiThWqc{)EJ*PNI8`+5UGZjSV^X7`m?Li;s2U6S`=vNV zyK8VU9hAGt$S>gN?)N!oDMI*6Uq&OyO*bS^&T!(3Db0@-APS-W1*c>aG#QST!PZBn zkGAU0d745(?MKSp_bw+%){+Bj=pN+}+X8vK2*s2~xtbM!Lj@J?+PI59blVBZ4^m{K zbtXzyMPH^x)9BbEq<#*fcvr{v+TsV7cO%)}tymA?N2(@-;{y&>ftuEru&O@c zIVuG=E2g}39lH@07aH}GbvXo>p8w#7A9>IyKN~|5o;s>k4|?+VZa>_Dls~AMTCu~g z)HnskgJrV80sR|o&j_BsA>4Sfx3FulWneA8A@s`n$q+sTfMD@);KidT%^+Bq{Kfg; z$0o*Hdd>bv0o5-Sy(i^UVz_qiSXmM^l;&Sx-fV)Jo?-BTH|eWM_!Q?OR-8p|-H0`G zDH-TRw?HZ)V}HEsD*Y@sSkViOpd+2eDr0!ps$|odKuky&kUwr*@`I^gC!$8fpNHR7 z{krNBAzu$RHySFOcjDLWrGryR?~uzB_Y&1;n;4q4D(`tUEs}y z68aNuSOeC}skVMwsgJ!*cHhk{c0%lbfK=`EKTdSVaEho~a6-t&2ebhuSDIpm7%L;bwDUrDSq#AHtnRNj@ zz01R1Iy7gA*Ysrj2n}5dt_k`#^vGq3aN3!58Vajx%kM zBtm23$vv7BI1-%5e*Uh!;B?I^;dssmKc6b#gfuiQ5=@=|Nb3izNSQZ2M&c12(CqU& z4=-|Q3Ck_;oHCc#zUHTxFyVXmr?$q>OJF&9LeaYZL)m6nqjVMTw53|$uV}O`7&p8* zCr>!>&TFy8UTi;1_};%x$|BEsggpK_lGLOKaTPHwuJp#QKkbKs_1+7=QRzsBwg0&q zq&4+UwK?3*3M>niBmH7WScozjAPyO-sK*RGzc%gUQI6;y z!}L`B( z2mu=!9AQBt2=2T|UiMx^_ZZ>J)%I!DYt}J~GJGv4DH+r1{(IH>a%g%@-RU`4-fJoZ zWspLHi_waTY5mj<94R|_L|fO$mEVvGfRA_8i-op3|C>FqM%e4RjzD@xgd%Zx%OSPdej7NRp4Fs4}RR?hM*PCh) zXjFt1VugZ%Q2b-v1|oOz72~rf;oSsYXZ;1Nk>Q%YvbVbn=64u$edxJCDitT^MWHPI z;M6ZVLZzOAmsh^_SeJcpkwMpyU;zXzhn)};7j^jiL@)rb{{ld!5t@90;c}oa{L&&$ zhT`p&le`>c9j|ir?f&dx|L|VzyI{X76=#Y{+9V-RTck-5^RE1|>`1@|Tqc8)CJqDD zWMcRl={<=}0(juCm@)GqCa53QKxTdeJ4Yuuq6If30I~S-?lG%^tl32c;w(VpTiu$} zuuGf4ZD^Px=POI54C`so0dg3vF>+Be+(MFH;?Ify4Fk{`VWs^^(rr#5u24mu8*%Q zpix4aL~tpP8>0g&%P2ZBniTB~&3wq9H!o^CA08zVGyngYh7lqB4T594yjha^rJ3Ir zM9nszpxW$I>1vcVK(A=h z2*p`N7#%TVT66~kD`&pKt0?t#7+O2zWgE_7rlwThK>K80o1|K|+{26Xd!h$|ukFL8 z0UbwhuI@O-spPY0^hv}foPr2GcFD$#8=B!A)TC&w_b-il%FYi1z&y6DTE(d&IzXdSsHLzqYJpfIt8<|Vc z-tl10Z!p%UJ4DbM|F-6k*#Q_Mg#YY=f5I9jEo8IukpWp*><u6MI&@YmcbyBcYXbSm(XE6W?C88FPAU3@jYTQ#g>ey?t)N4^%!jddycdtcA`I zr;z^@8XrLnH+LW&=xB&C}eqk`lpnT0|x@9X^672F_<`o~%Hno6>Z%&3-4zH9h~AmCu4< z0Q-tV2|fCG=V&cBm5kQB6J3zdB|-#GIEaOW4uZYd{f=?CXTg*pFLDxti0I4GBZ7bU zatcs@lG5+8wrBHHsxZ&L;=yQD4%vsH`zRT1UVe#SQW}A@zWbyPkKHw}EL{y80VgX( zR_Y}wP>H`8@gsR=7||eFp?Qix5n}ieRngI3AZ$iJ7j74WbJ2T{f6@4he3J#2-*L>l zv(xR)n?#d06-g0dp4Mx|HE8}0c~Ezrteys{?@ZPUncXKD(VhlldadWCH$ML%L|G&I z?w1^YboR$=GqFd}As_4|F4QG2xnema8lU2z#nJRLWrOA(4^KQHe8ic=-6n-&a;S5G zIpk$*#Ac{J*!x$0X_lyu(gckx?@rsF+`>5_EIi~W$=uNj5nTvzHZstXIbCKge~zx4 zIX2{1p5UUM-n zJt_pfU!sp(Osxy&ug4`ej;@f;KY2<;8u}_xwOm^EIcE(K{A$x*IG;hv7oH@E1G>xe z^JA^0Mf%5ftDLNg-$ItZ7(*qZ`(Xe$=-I+O3Bpc6U}ary$V+DtUg-b6<#*B3u2qj$ zS%|g!!ZcqFNO|b~fGF@7YCeA(GvB0WF+~!|CXT15+qTYiryO+E$4~o@L|jl={SO@# zIHvQ8M#fku-f?7O0Y*mKNf64B6LA>AvbRv;IHn7 z;aW$+6p+@XVQ=;XsmvUIk(~ThZg3Uy|8BPhMV6({ZV~Q19g?H|CYn4H0(-0-%GA&5 zU_bTquqMM$n`a3>GJ7|+irHP29J+w+0i%%_D_>9D7wX7U<-B9SzA8qnQfB z!OCY~2`0#OmJrWd%SRP8cofG=byG=HY%ee~V1*ayhppEHq^u9}uLatiX+EY+&1@*N zC1#K){SLwb|9@}1Il8Fphxp2*YGGkRn(%-G{LOa0AUQL&*FGztuM0-qy!p(Ywty{H zo~kXETV}?4C_Dqwnx}dCD)&V>ZK0AyxmAoN6qVfOcL_zoB93|hQBMB~VDf`*ec{cV z$_)f?*I6`RNkuo~K!9dH?%AI<1XD&)q@|8%kv&mBmSEOz%^^R9A`o9 z<5lk@e}~JSAz6IxH_RzJOkIRX;*HD?YR$@kk#`u2yCT#tf|awR2tls+?Z#w5z90WK zMA^*}0)WI(=0s{YTdu_^F{2*_=Ti-;zu^B3Dj_%`2LZC3tFKMIza^<){DPe=VV4|r zMYGZ2_8|K71TV6GOc_NL2i_6k>P^CnaIZIGyCe7g9sA0m&sZ8W4uAjh8CS0SL~huM ztoWZl{^Xy$X!srilktHN16S^jsN+Yz$}1yBHO5D>L@hiw!jH8!b8=v_I{k$6OzNDI<*5C|{ra&P0w{iZI8a-y~rP^ME_KReU2@7tsGgD#EuM;>v)2T*4ULSq1V}YN_W6 z)sm*J;AK2O2Lf`^ym>|ra#WjMO%I#wbCuXRG>Bw`t?n9vITsg*HSf1@jsgb6aAt+( z6=!};QWTj%a~a0M&0_3CMpAVPiD`v|@=Wb_m^}}d8R(!qd^6mFNs9oPW;W&PV`e@B zLEgo9l96A`xQJWj?qm3`YQIK`p0~`KM=5gRf<&Sm|7qsOa$2>7@HFuNTuG0`>$tX% zOlRLb+x`7HoE&77J-43aPSArr#xRg8nO?v`^Q1&yzQI9sqYiMuS;LfHY% z-D=`)-kbA9y=Rqm<$3Yys{AvQAO|r%g|6c^c-PAtq#xidbKdr6S0I6DNXgcz)IQ4p zw$A8c>)zbea4)0wKjz?Medz{AM>zYC0eatPXi^vx3&LMr<+`%0!7e!Ymtzv_^y4o{ zpY{#fW`kU4Esxg{q@_3){K!TR;LoMOO)kG;P6Dkb!uv8Q-w*h}U>6>45gY}?DN&_! zRHaRKnsYhns*WKQ37E86sjDByTDUBQYpHJxU!!Z1Rk_qanoSjcP3~)?zLXdZM=L+h zdS&*kr*3Y0U_;mE7dwlm(9DeEc!Zs$EEgBR*_3M!;P@_g#=s-!@HT|{0QYbLas;tXg>t7RVt zP%MMQ9?EnB<}umK?6Va58jqSo`58NKPumT&t+=S2Q38JE_>pa)4)t|$RDFm{rt7g< zU_GC*(IflkRT0xtI{+Vu;Tf6i`aHzUM}%;IiZs|3FEaiB79X<6S5R3aKm$=8=-}cD zSwgJYH3Q95MEq1jRd|Acw^Z855oaLL_G2H)GNc<&ikN(a?~6ga5Wk z@k_pfrVQWudJc%DoT>f^nIIv%IZ5)zTN$D(@1u$eT&_DM=x$D-M1_~?=Z#a%`QcNT zddf$Fwo>`!Qt73KO}Cw#f0y};<#-3Ja?}0m&MsZ!!yO@UAIXYdo1dK)8OL=+ev2o- zJ_8!OPYZTS*8H3;uHaFC{tK8f8PMx_vQ%vWyASl)U~lE+X`R8Akmvr{$pkJu-4T`R zVu2*6CBthtadya&=Ramk{G@j()$V=@`^9c(B42|et6>Qq%y^MTveqQ1Xz}Z3)pceOXE}YBBmPdpUudeCs~wr z^r848I#VCAgQ$xLseA!NVs`N;zKK$mg_pA?t%5flUU_L(vAR3>KL*cn37Wi$!Ow(> zF`|p-J#ff&O1f!WBo%xZ{NDp8keE{<_|6tmcWsm>pqq6Xla}I*zlfLwcITbwIyu94 zO{F8CKJ}Wue@tWr?8C}@&UQcc!%k@XYM%Iz?Yy-7U69k_bv|mJWJyE z!e;~7H0V)-suBJG5aIk5@gqaP<;-AazzGB5bUQS|?`O%Nx3$ZaTm{;txKXK#dpA-> zl-bC`>)-nea)-6lJnT#HIUMW3q`#74U5}g6u$eMr%PaPi zC4k3$uv0&x?)C$x|KIuIly;Bw|6}XTqoMx(`0-)v%UH6{*dhS=8om<$pvZ4fG`6LB5|n^8WM}D$f?N);+#q0@`{Nll*EIU};J{KW&T>?} zR#eWNYarsu;Cm3%k>&x~hRmQ3;){G;ZlOtFDcXQ(BN0HQZQ)S9!D z^M+2EaGYV@v&SKhyRtwpu2?CzhFU$+SD|&Qw4b`wYqvfw%)&E{0ak#~ka8%bxt+w@ z$w)rK$Z#7}2yTC-LP}vU!?RwAE>KvbRB3wGR{}E7LO_Q61|&A&QAP}rf?OIj@2T!l zRQ28yLt=tdO-#aGTR0y0)zEOvE&=;>s}u@)31}%s`Pysmm+Jjv75`}NP(2R-;iF%+xfRv#0Cv6<+&xvH}#i1 z2^@;Wp~w&!Mb<^~!gi?DdX6|Oq_8QdksqJ`ocizV7daU6YkDKYCb>)D`6xbcJi^0# zC$Lgzu<n&9(n6;kUR<8&DtAT+1Hj3Px?48ScKRoPKX!$5%2 zhQG7zF88l>A;$82d8V7QfA2zoai^3iT_+%oSO_S83Nsq02lGHa3j8`;gS##!=4!3@ z(bR>|T&7t7hyCD$gsK9Hi(BL-C`#?nAVGqIf7=+eIL`P}XJ7zcT#*e_l0IQP z{S(Wu<6kGE1A@#qDZgBI*gSc-`Xgkfdi7d&V8*9R1=kQBC5QlTB%iw8=bQQo_U)hT zTkrS@Xr-x@Ri~zF3BJ%4{A1_!6szr3tbI3Qq_DVnxX|vYyLOtB&0O+ro6fSD2>am# zx|?qW^aa#zRx8EvPy{2t_0G93b9cF9eaoypSlHMow25$#caX>Pew;k?4^(uyG-Bpb z@^Z?X>S}@zRh<3B1F;Qak2#r4W6#4}VM(djgbnA1Lc@D8y>G9{I&Us)6v`ghO3B$F z&&A!4Tw-L{5^jkRHaLg$DilDe%}DG@iPcz!3otL$#q&-?epbf=mWg?rZLg!wAbl># zlJrm*su=-@@#4b6A`bnsYNEH>iY5a$g~!Z3KO3_UYg}h?B!A6Xa;VggOlW3}I2qr(AGPdRfde~P-R&b6xgn7RE*-}<**!X^WHutBB zGW2Ls^Cb7?UfIJPB$GNiTZlrF&wFKdRnFouS7s3BTEEwZm`&_1(FfwGeT||g?}QtS z7=J#Nf$yjF*`7lll`hKY*KK%Dm^^)1T+dZm}85 zR~19^Gtn4vBLC{>w$ndRhX5*@IZsc67`@MqtgLcyFL#q~?lBa~fbG|4s2PyA(DG$Z zG*{|f_(B{mptY925E#L^#4W^ud_I7LYJU1Ggz9%oh(vn-Nnalbc_r{l&4s5R6aoqx)k|LNWQ85-w6fa5O(htOV+F4hsqP z{++wPSOj#gn|tNxsp`18_X^7Sy8If*vKy9*4L_fq@luOD8XOwG9_gB+{I>a4&|)|< z;=4kH@H2)NhinqkoQh%S9Cv7V`BR9BJSp!;^6ZCMVshQ1o5GN|krS(SiKOOtqq0Sm z8e!zF>wlB>YuSV!J=9G}NoneQXyH8M?tVhcx9CY2p(e^T2i-If8jNFLPE0_nf|BcdxjTVWoR%(YAAd7OY>cD9}AVhR0Y) z*p9Naf(uG6u!l7RDZM|3O~wolE;*nGrzUPSHNGrs(TVFdE2cukj5+i#*YM=igVo`4 z3kgz7AbN$#XO(cNd~1MT8zD2ewiAjfM>l>H)n1(lDWV?a{IL8RXT7=*9w#0I+kf@S zhy<(gM5-glI<+XNwb4yJ6!SI7e)!)tZd7k3Zp}tClqTh0L?wqs=!#Q}R=g3?dP)Y< z3%br>htKChL1IQ7qyi0sK|e+7I@76%@$fC0N5e0Qv z5MVOp!YC<6ZftrEV~j$3NSZ4cG~X34UD1hT#gGV0{wHx4DfB3spN&Es^*R0y46JU{ zUk8(&{|xiT$V?a}A8~4!O_jX@0U5p4IXpPo0eNj~HPd*byKfOt1;#`;2~ zuAnNb5`xmo9pyed(Q`HO?w@)xgWG#trb z@>9h@>(Z8BOAHHrHr$XLW4)H(?v7vJ~aGMG6iV}MAsEh zKV7i7{w_Tj&0my))9cj8nM))}i!}ePAY=SQN>d~@{Hh0Yp8m(}$HCpNSUbtr=a4G3kY5e(W~ipYL%c(_5g9CNKL#9ors->c1~IGY z)$U@`(PNURnbhFwyjxi>#Na8Q$3!3X^v5J6xQtMOO=d)U0L?G1tA}56yuU++9bgk* zA~%RY^It|K?hhV2ZckMTK0@Y(zqw}$usb3}B7?7C6`5gU$_FK9@H}1UiAKO~IM|Vr znoY#!2qc6em68m`M24+Lqr*sHnM`dZ6Kn`J909l5uIoQ?iOpj(`aFLOmsbwO$R$0x zFMj*mz!xBY-3A+$>qv>X;|l_JSqhZAnkuV<_PArL5f}fD5q_x32ddOw#_A|4)2a_q zN;s!$_hG|3^5PW~y3>T?R7i<9 z@?tET@>hpy_N<1B=Bb7j3S-VQ#*xIMb8df@LqTSB?#kxTI6b-K=v+VIj~Eohile0J zhuuGU@BXHQT;l8$VO!fHVf(tc>(ZIX+b&4b>o_(iz~_dxHaW%5FxMPa12}T}KKEvE zOz_+=MffLz)sq|@ufPxi%xguQtjHy6?k3atFnLQcbk3Lp;+hO=`kfy$ruy8^OAi24 zo@4V7{&v#R-*2Z1)%1~X4t@_J3I{gR(jL!~4dda7|E+Ze@QH@XUgbzq?BfpcuwoJe z-vd&=Oum;i2>uXNNY4?PKliB}K1leBC%$dc%!5(bV$z=^(ptH?{As|zJq;^enjPMO_)Bc~?I#V!a;TvSihDP&F1a%@TxFagW6)c*9-CL1UR0@< zC<}7O1DD03`QQDKMK=~bG9-lopgyMO#?)0{xXHwqIx?FNRzaA-#?ms36 z+m2hFvF;>=jWSx_qXKSHe*VTA> z!dk9DhCS?3zwl-{O%jLeB>}DiS-{0>H}gbTPy`#S1(3n`93P$nLa1v_2xSsEoZ-G2RzRXk7p=T>&I&M zef>ri1A+t5j0X9+Y&iDd2^ee&jmct$me#leZ#fMuoY|aE&9ZeS2yhbR>qk!GJ6g@N zv3Z~QK%2vNV6M&={*5sdGaBI{74<@p_gWKQi9saQuCubnJBTc^AtPh*OeP@Tb9BT} zl@6{8UO(1LUC3ag6+BT2tveFHf4^CSTx?M+8g7m&#>Ed8g`jheKHK7jq%#_DQ?-Xj zGGkN-X&RG?A7DVv`iiA*t)}M~^e$VC%`-ON(IqORBk+`uX$qWgjETc*^0-wRAae7U zm6z#}U{Ks&G6)kkPy52$dhjX_gy0&0`i%&pZhWLv{>-ueECN$#&&ER7dOEQ6d_Skp zv-!r#)qY69l`+8PNU+}@yyY@np1|=^m1>4?vLo>feTpldh38R#M|M#nt^qj0Cv#0q z1csm+J@24%dI1nFfc7;;HDyn~x;I5M2(^AP5`hG>n;L5UB5X2WquEB?{Hfx> zJ?Z}*SMnWLfHWu|ykNUX2U7^#C%Fdvs(-mDo<6B;=@?FUKpb0!6&^MGgWm@I3s@!# zuSh{yz#YD9EeS$MXK9JKWZ)R0mnDv}!v=KG{f`R0{=tKL;P+$IrC>FFSuOM1^VoGx;hKgOP*IXuJ|GuNTtw#Sc9LCUo$~6CcOKefNNy zB#ukRRgOyZD7cNJaurWB2q?P`FU8&Z1E*WRDTUSgB~Q&9u+gZSQLi{ykX~F2 zfJsgO=HCSWq)Q_LM@DkerPkx76z(xeTuqt?Z|%ZaoAhR*Lo}Nh^@@^nN&7yV`U8I4 zPXf&9j(Bu7Jev3iy7AGAUI+PKFVLzt*h&TW*^rJjh`rXv?R)KM>r6rDM(0z~Q;-I@ zGD8`J;Jldz9aaSEWFY(u#wC%kafeLIdB86P<9~X38!#)xhKYs8-2Alj6OD#`ZO5Va ziCcfnSf{t>L&#uX05j6kh!#%rTXYwXP3t%w8?GR|w@Ki|%4%IL1Pr^zCgY=2bRNV$_jAH)?^u|E43bmwz z4VaMGasd3xB~fjkE-MZBLq4o3-1U+ty-|0=h=zJPrsavxO|a-a`X**y&DY(3hsQ)8 z;`Ej9@^H?@#8d3Pt?h7i3T`^5IfSz^!fX@jt6`gj4CGg_r^I&BHM9cEA0N>Coh9TziCPMiA>p#w1gh0bb ze`KTrgm_a+|0BcwxU579JS*a|4RB#28-h*IM#HZcCV-vqAlB3xbSDls?sKF1c4r!r0R_ zC1rfRG#KKr>dG>SKrgj&994-eo`+B7)XB+OVz`XjDTS5Rab;Jmr1((aB3+T6_t4NF zb{(t1HJ9jp@;CF+d>TjfS?o($WWGb>>qc)^<_e`zV?GDvY1g@PUu<~SKP{c#Fg^N~ zl@U;}av<>VqmYfGa7}`UBC4N5TGERQ))*-X0KM<^|NQSaNLsjz3FFG4%=E(~oX%&B zECdp@)3GIyV2_n3E}Dm1vrLW^^$~0Sl%$t5yg_uin(MO0J9;KeI)ki1l|7n2usht= zrxH-cmokuz`ExXgOZUva(yHprl3?Sfl+zT~Uw>`TX!(IOyo8#+cv(k}H#7g2yg$xT|Z5_x0 z5J=aEuq+||lpNwDkm5n(jR%n{;df&WGp~(SK!)T6Ut&^%34BlnWJN(80EHo@1EqG) z*pYt)#Gq7a-nV7p$Sl*fj{9f7n|?Vz@5KfULhN&;$F+xM4!V|?s-_-a6@9|v8yras z4T9X;WUiU$F;t@GxhdZek6E-emA?CRcySaQyn6*UFsMUEm*^+j_8ET|@8c-6Z8(OZ zHD4OS`{*|b3<6f_J`IZ&ClUu1aU|OLfMD`O(eT6^Fh-CE-lR&J{Azh<&?H?Dn*R|yMY}>sfg_zVQ@D&>dtSz?CRs0Y2GQ#Pmbde&K?_O< z4pZ#;pHFEDHwo7^LYbAbw*oc?r#{#eizp1C3}JNA#9IoR~p*c$6hR z=QTR#B_WLE+#d*w`9n=jPeQ~Mo9Beje{d3WxXzUI5%(sqI?nD~unBTST`jR&N-Q~d z{M7b=M5KFjAS3IpFhST!EHP$6$`_8TqjSJcq{8z~ z)pEWtaCML0AY0HT71k!Tk$4~`kBJ)bvRIYHUtRH6k0IF8!W+W&1Y7Zx1-4Q&a?SuG zCc5GnJIUcI1as8oX%LwkH)TdcA&eS~A_e<0+fL6PfTcQJFgHh9IHZ(4f`=u_9;#W; z_oR?rr(Katx-m>o50BT#Q8R!M7}}2QSXQKgd$3j+jwox6ShESkip_%n#ptcFxG2u; zn0nC1=3G=nx!~BN*%W4^<7q^WEV$rg2PACplNYx)>>GnzLU{=Z!0*F#`J17bj#4rB z#c`)CXL^SCD6sK1XN1+rqnH`tA+Jt)gB+{fG#`qaLY}fn$Pm#05SeU;+8m7V`JM!0 zZyUsb_eb2u>*^>*{VvGsoXC`r2j5QcuVW^pYjPAf3`*}O020SKLuUByC#?p0^P(^i z*nVJom(h(t>x||@=cEJMyv_)bx7ly4fz1+Y9(zYJNr&f4@;T z88#an_6Ww6ag910l*U_=Umb*kQ93?XVvSv#j6T1D;&6JmhLSC-@AbN0zBF0lKpO6C zTd}g980~hU0ANo1IRd*_X{}T?JZH>WXi;yC)#j`A{`3&4***YQl19A`qZx}VA?B1~ z9gD`5xdY7&J0Imeb0-*`LnG6uq47=x+27Y~#DwgK$%7=3!aDErh!hmovhXchWDD`I ze0Y)w7HI@NLpGp>aWP;eGPP~m+A4ShRIbIPt)jt+kyZIYKD*w(ZTH}=-H)^yz5D5Nq z$+DrTM8aF1%ONE!Tqh&wO!Zl)NsqNQfk0tX}9}PpM{K()p^~z1t zu4J&nh{~@$r8o&m|ksxA%0YvXaC{uhsfluT9@$|bP%=@OaV`(!oL^)x&THOU+dd+Mya4OesZkiBaUJZCT*BM@ZUM%dz#ww^ z8If80Wq*IsaT4;-${L@%B0%N}r$d>cm9oV zB0?!|&5_L~mk+;h3deBiw2QxY7|yX_M`C>9fdpH(8UZAJyQsfczGkTK#Xrw(qu4!y zup#pmfQBtk*EbKfS zf!_9w5$QD|n?dYhiO&~sviqz*)MjE<8)G6Gwr*|<`Kf3bUUReB^}-ZkjC=SVeT!4! zq|nEOZ&8$xrH_kTZ~=k$H}*cXRpWcmg=zz1{2CBDm%ZPwO#qR#kP=jlys3JwqjN?| z*JH%9()P5#rrV^(-?)PZCvY@3)vLqwj9c^pCoFa1{5UUiJodH2ABp*jIE|sg7|?c1 zUZsk0QL6Rg`nAU7RQ|C~>pkA87ss%9P=-1%8piS7WQ1ydbCm@IF%MEsiUncqu@CQZ z*!_mE{X^CiPhZ2)XtlLpv$v9ml8*QKq-bMDqv(?)%wA}nobZ;PC_7yCD_HD))F=c; zR`v?%J-u=pyi4HAzBC5YMv6UM!X2Q$b1;I|t_OIacb4JG07s41#uKz-bKbakz|lIP znpdrDUGUCoH{-Y;FaH4yReFs9H zckymPVm*Pzy^Cz2B^U<3m_^}!{*VpY)(%Bc^yjg-_9tGnYMN#E^(Cl5Rm+ExJvmvF zi7z=%lRkZR`Q+1bG=ZjUDoq9C9v5AmL0hN8V_2o9m`bm0E<7Emz2WBJH0 z-N{V{q^T-0B%j>mOecOPj6F4?yb+vr5eHP0Qbk*b9BUmY=jA~!18oJm^(Z;k0tROv z01PiSyvuk2T-ZSf_g@uQ8Oq5{?XXbz^ntiQGQwyBZmpm}a55p;q$|WOO=^g;H13v2 zfI#f3O*g~r+_3Ib6liQdbCErX1n9uBxhnl{PQCJ85eEQINyFB&jsAZSp!BCAt@C3} zBH5=q8;-=9fjrL>OB%(a>U4pO3JSOoZ#9ad^^{BiU=&-SsBJUrL_pxEt#^pn8h>2Q z+PEr-5_e)6iB@wX4u9Z0mCO~UL&bz(9>uID(qIedJ!MWKxq+>`i_Oq0IF~Rj0)pQGlGsQzXTKRGA|-dKHiR4j4VOPq832Vr)&WxMnWH@P-saru zKxup#dj!6?^Obm+$dP;gJ=5enKU57`Ky1%x(U&Y_*Jn_N2RmH-y}=m&jZlL8s^4|y zMgLb-%yCu`f-{HQRw2E;uj za?X%JN^~PzM!qZx85YBTLWSJZ-2GncEADQ~dr)FQ4ZmjoceOdA?52YT6GS{c?de!} zjvm+qU=H?w=t)U~d1NhYP5EfdXN6(euv4E)UyM98j9d4s4b1U9!Kc|wFpjs=t?N{w z2QaJ|LeHo%M*^!K$4z;tiT0%7^rW01^bq;I!C1S=flg~Eq$%lH^_AmGyWx2fag|Wq zvz%THY@XeaxRr?>Vd*K)mj3DK(wqOBepe{XG5#~yr1De5MX{$5-hwF6@p~FT`&0Pk zj#g!oyMUq?oh(;fAt4meUXs9CuS+W&3j}SxI@)}k*@AE0{IF+12WS5|cJDi90I~9< zQagbyBt~ns8f+%ACOElihvwfVh(4ZqVNIu&X1IJ)*a$@*VL~PKGUH=>CAuzp9-wBtXxo0YihTd4Ms>gw1 zNh7b5-LtnI_{w3B5zZF~aR*8sy&I8MSo=wyCH9yG4g)Jm;cr_h7m#mWD`N62136|U;SYy| zlvA!zKmLd0pZyCRC3uIXN7Bs(S8^NLl=~IVEV*%pOjjO7atO*Xg{ER?+uJK4UJpxn zP;DR0T=8)v4C@9T=jRrha75!k%f+bpsB0EcK0E1BaA7rbj3MK3V0@l5vONU?H_i1> z(B(loICu`Jb!yI~eU_6i0yhOLxO^{9m{qrz>IFLx?@t^^tS(%pK;+r5y7OsX&l^sB z!LC0AEcnNn1)D{jT5u5o+U^^k290(*#*6+3mz6->Vi9K@OJ>TAj0}qzlUe4B9aUxy z7L=AkY2UsL{wHf@DmnhmnmGs!&w%>n5kYk7j-@VzDPkWFeh_y`jAz%82=}s`=!<>+ zlu4OC>AJ9VAal5cJQ~DT)7r>09b*2f+HZx^&HsJ>%)+M^iJOL4zQ?ymmV7a!6*=nb zsrbbZ=Wa~&n;ZrK6*U?}mw}{{(}~|OEOwNajzs5x46sm?pPBceROt>o1XnPc7k9Y* zLDI>9_ezG%vm=wFtJR!C=B1G{$y_ZWBir3CMvIW5rs1OdkpzcsHNe~lsthLoS``O4 z6$Nv9ML(V|jDp}IpHj5HOJ&<`myPZG7+oGiOF{fG9#ofZE>ggUUl^!x4dqy1s7dHz6c^-mRuRs+D_E8S8e zX+vy<)ts?sV{@I3Z7hfyn&1H(CAoA!Can1ut3*EEoB;EOT;A&PW?b)gTyIcm{JW0Q z?VZ8uNPa~W$UqKYTn^s&-KBrn-v|6YK-L||L#%d}PoN=zyjPt1mCRm;&y_#11B#tp ztHHL@c$Qh{f-jF|kY4yTn_Z?ed(9h5+!F+RFxq1pwwrG8dtK|%5kkfw(IR}Kil$#lD zQB8TZ+>jpW7IqqFupQe4*<-}XF4gd4mu zhU}hF`QYlF{+r`S+YM_;#Yx4{Wst%>Iw!&jhiEaL8Q(pLY%Dx8g zWhEEbkZGV4a3lMg5qjcv`&G49o0a9#A zW7x75FxFb(R)aKR0wYw$BVCt-CU)k1-#l8lj%bLdsNHqveUI4p#N7!@GAr-pcrB51 zXo$E5CD*Ntp^L>|wnCVk_xtH-Fgx(qg?J+%zzsAn^(i&xuLX?)3EjZ%o=LW6m z4j_h?e9XVKlK~#;b5*mK`j&qksKTAF$r#Ay-o1pfYtYa@GS<6Ko?I$98dYppXfcEr zgG=^$jZ*g!IlD+h#8d@MU9vdi`q>=a4q*-t8|8d=yX~Rzq!t zHrmaPNXa2)mL|9zi)$}x1)mI%wd#%N9}8m*@3|xNWplyH0;S`RkTS-ukO55?wvgWN z->$c>x~6C8l<{LcruCdjWtGWafg}rB#I~K{^XEkKxsCB3oC#~;q5V#g9weEmQ{pVI zp4e_|{Hb(xJjgdG8F6?5C{|mq&}PlfL+(y){oeOt0E9pZ3J~uKFopH<@yNz-Yo%k(6^zIR@T6c3suTuNT_gdCO0WeW&Cpv8KtvXXykmvYIWj(pA+h!&Nu{dvcL z{a1dS6?1Duqo(V8hVQ2*mUUG@og41Mh6s_&+K`QJ-B7$>c6!?*?b&6V3z&8$6YlE8 zBj5gI3FfS?ddxwoSVq~h|4Gq$A?5yOmN7sAw85b`+|-7{(8zl73oHfVS-eV*7zHKg zuSql68%~;@bT1OkD)*$2zUnIg+2n| zNeuH?Vu(LLiJ7-)6U(l7u?6-F<@S$)cDR>4cjxn%=&oXlUxCj^jW2v4hGYaBJz6?y zkplK0a}-bzFx?@aC}Szgrtdo9Bo(NA9w-Kbz~II_67yNkFwJ)QG=F}jZ$$U6bam!#g!8{s--fK8#@JZOYiB z`QvlPMXnkhCsP4TvDLL~DHu}6beQP38b}hHX7+5uHJeXaz3~&gkf*_W<34(zgD}9J z1lHc6MS%L45h1x{;C|jE@Rir;yDjZya%1Z4X_J#?=B9(6sdobA-_hCrT@-*=feHy! zGyKIrKN>bhWURW0qv5<_r9l+o%5>7+6AZ|O;LxSI$$ywm5$lY)Kk}WF_zQmYZ`T9bxdQ zN!DyR08!s`paunE1XYROGmvR8(_7(SdqvSV+v+kl9o;yyZe>H*zE^FQ&1J%mnPUn* z3%jBE^!SvRNSmgYcOHT}&j#{l&U78dY&huty-kNWLet;<3TqTSZpeOw&S@x}+Lb7! zR=9KH-hAv0wnc8-KUoy@r6UgjEdb=CEZmr3IQ{t5e#9Vm=$wuCH&${xq6VY=%ROgw zjtJ652J4fO&HhR1$f-}1!Yxa%Q4Ye?b`~N}r}mA585x=WcADw5>|U;bGGLHKwCY8s zMJ9aqe4Zejo1}N6Q9UB=&8kwNo~Mt((Dc!_yA zNbvs&SmFLO+5LW`?bR^KU=2fIX&Uw@c^K3*->7Z&u__Y>2t>LOj+m)qj z|Hp-6DkUw&bBU3fSY`jJVrkBDC(a;qz2BwU>@VNpD$Z-b7KKhhGEW3#&T=RknoU~} z9$!D?5e5xakV3_pFB+s;q*xnxOob>akrqB1>sJg~Ws+Y;D4h4N3w8muQimgDZ+qHE z7>RwRNIbuyQ(D;*y!@|@0JGyl+C109yOKqqYu7UdozrP=A*?Ou@N=q z(N7Rt4ZLg4yUpk=BF~=W@eElU9O<>xgsw;a~a9gb?{$8`Ih#xtc!i|_bHgfsWbcbK>Im5`9 z!p}3gId`o2x%tUGsZL>~Z@?8g1VdENf|5dI2^B&Npwu-`pUAxb1#le zRRK59LKD;>%}_kw?|t#VUVt#pzxZ5w4W9GalP`|-IX$5VQd4j%Xhpr5NFUSsG4`qy!Tp4fD}~QHb4G#!_bk_= zRCfKckOh5?>X*TK-AY~YGn%3PL!r9c%Z?2i<*67W?WD4-miQqm+p!nNp1;Ahbn_Wd zdEpA`0Y+KDH#QV}CF4g&y(_8M2dE7_N8>Q-Q`zZt1_rLQfGc}wgDCSxtb1oSKfRe= zm_pEA-%k}3LP4Vw5Ef562GkWZ=?8d!d}!p_CMq=hon3wMkGw^FyO3vCOf-hQHUDAO z8t1hZ1H3VhfVTJf;>EW0oCbyG_^w*>+d~k?QMJz;e+nazj1*MD@;9DHb>`T7GcIV0 zU&E>x2g{~nf%t7&%S|2!mlZYrAmm{u&29fX%j;A(@%IsQfmEUSPlSGeq8_1&Rzw`G zX$bl`AfW7$2Gy*wZd|baga7Qqe{k_>bb%86&%7c7HrYj5_?8Rb{Q}RoD0X-wd)+^jHw5x4Ctci`zO1Kb%@?pP{m*QyS6r8zIPeJD6#J86qROV7>fIeE6ivS z&?9K&Dz0XJbyZV<5&h^_t(qy5I>>gH(o-7xGj2v>qj6HVo2FwF8@{C8bbt7!de5fS z`P4GgPaC8THtoPMZgQARl=&LLzAYC^4Q#WLC4DteiWc-Nx$RzYRXH7Oc=oT-V~@>fPqG>Ih1& zodac_$G}$GE~2Cs1(I61{h8_x>f}RmG_m-1eR&K8wlhC#YZc_zkM(z7og8M)=qs)Z zaLKt6|M>&=p8Khu9~l|3?g}Pi4WsebIeTBqjUg=Y8!LKlpUtwDW49!BetgHb>-aJ1ztFFA+Y-(Q zoFW|q@0NqGad9;So`{?<)*W#N6g58`e%3!%7lh|NXW* zs`5^#wAK2Pe2!0+u0dPJ%Ky+H`gQ*{zv6XqHt;BxPymS`L`jN8Rg^`K$<7)W=K8U+bD zJ`VV9e(Unq#8tVJjmhsbY6EvIk2vmLP#_cOvE06I>qn*}7m0j!Fm1o=h z_|l$+j@Ei`UPua1as1XZ2?+)44J7f0?kN90Ul1&a2U%If%O5hn1UDFUP$jfe%`n>+ zbO-Vt9Q{T=g$`j6vEg%NPmWZ!kFJ#6^SdM+B~r`3OFdb;G!qeW0sRf#xM5s3{`Q*A zt=Cl|AMMKg#QR^|->xH^eVtVx+&N-^ahI zqfwzJaSChn-YBN_p89rqdivd_0@vgC+uC=u@tN0;Ca33*G}m4Q9$30gEq_^?QQUS# zC~mvZz&7~{{vf}3kOunylZy0T7E69fNwL5>XQAHwEst(mzcmy0rmTj-+fQ8d+^s3Y zLwtwqVPn;*O@K3{1}FS3@dE4SjDI82b8URLZ7N*iDv~VrJs)GN_4Yoq-=9PF?~_$P z%oH7M$iMKM``RHr?8kR29;RTSh)TvP+Ntkf*1D+k%2=oyYvD+Pd-eX`a@XSzxa-#! z4#YVSLBb-y=#XDfl$O^{{QW$;Q-|jiy;f{@Sz}KG0)DTl?iO8{YpUDWc=2tSN$nVq$31eBD`2HjC%hTJ|-UY98{b~}>cT%xf8u5@z1WAz}fGMIL`tpRE>)9@^lZ(rA zC~I95xYxg{OZ*N(5u3U9I&JGmv(h*+!eL}v~Q z6iZIW^$eo#D+pQ`xB|LWlhcxMrmNL4rnhd*Q-`5ER%?)Qu5=c!Q=5H6i7A3|^LHbj z)^KMA{xz0h;b^$_Wp2G=EY)PhtT_X%Cm+!LZ4I9RMFwtA{d!9B+>tUk$iMO1derKH z>)|0kcL=!M8Emb)NEF)|sjHnEnP%>Twe7BFPHO!0qzt}c8tZE{nx$U>DYEr-MLi%B z>Flhmtp*1LZBKegxUTJ9`u@%cW&4QX>mwz4lC&{jwv)zK`5673T6pTZ*!PL*;Hm+2 z04}Y0bW_J6FH8`XmOFWPzkj@Df#VPTQ&ruDe7`9=9PsH{emTle#sZYC2Q)o6p`dLw+-LPX})QZ0`a z8E!W5P!P8qgso==Zd=+u@TOBZ#vQEHO&&8s@Px?>p`R+t&>nuPJMpiUJ7KvS26Cb` z;1>cJ@?KQm4#He#f2eF1v9E=%>8~F1+|lN282k}PcQSj>Jw4*+vq}d5jz65c0;o-s-%j#)I>%+D

iK0m$l#qKC>x3)aT?pbIc5iM&y;$h)o5D3u+?!s&pL&NV~-7~AlQzDp& z@vQ!jqM{$(<2N5a1Ud9Jm46(I%$tkC3VZmOIQ7$bBY*OvNS2=$UPf`e>)UN(|M(oY zoCjmb@rcg3;cHT1;XB;*S{~5JfH_06`*)sXJQ|fQDVc1VtlQ@VQDs-2i-zoHrslWN zhgW0CyRYvcT%0aV{rP1GQR?VfujzbZb)`1+x|ZT$Bzeml-st5?Xx~Satuy5Zv-B=d zt*ShCueGyL5l1_QyR_7>{zW0heX~eZ%Ot{Oy4&JdjxWMw`&fF$)O%|B54}3Wfo6rw z?qScH9VM3YejCMo$>!C;{o_YS;2fDXo1SL(s_vDtwnY@EB9YQDPhGlaGA~spfClim z9)0h<#b<}0AJ5j!ij`|Pkm&>7>&H#uzGS>~40dNU zyH6f_NjpK5M7bJeG6T6DS_IODuY9A^giX>>+#a!h*|E5JTl0#Si-O~@&mJ8_$AlML zs#P*36iI-HzgyHdI0K$E4~}M&m{QwK*80s-9UqO`UL{q=9oO`+agHlUoPVv|AWj30 z?=H1uEBSngFc1!HHjSzbus!$<-ud9k`S{Nt`tu9{ncUN+k9!Vzt9=)F0KX{OU$J1L!RrNjZTP^PSiw8PP# zmQI6UH{5(@!x}exeGX*s5L3C@TIE>KgojU}N;LIr&mf!VcY z!+ZA5H|yEvEfw(uWX0*OuowoFGxj`}Aiuv(4SsAWUwqXAd5 zx3`}ctVMNhd-l5V0s573qC%&w2b_=@qxT7ChGyAm#ky6f5j!3?J3?0Px7hgqW>81N zgkBAjhrrBW@%Wd8iw2RWbd~Qv3td=1!e^;5LsU3e9LPOenwua&bvr0Rebox{_2{Bl z6e7XZMdFK#p&$N6B$E4s$jO??Ban*!p+bNts38u7AiTvfLd{|GZcoZH_hd3SYjlL~ zTft|^uO@{LhkwRGgl*`yuRiKhHzN4sM3p`iaQ<-(m16CD!yFUH0D>1r{elV-qM`4R z&*&M&$b>1Qh>Ysp;iYBHHmr-f!9RE3R4RqOUqREx>C>c{+HhW-|T>zeR@Ek3Es)6gmaL_n3fa4`Bf&ZMZFMAPmD&YA(B8tt$yto3S3Tm z4D^G>s(l9N#rkKe2x4$4El>(gbcs)YjKACI5CM|_2o(2YC$7pvWs#0GtG#6!;*$zb5r!cXpAbQoc&PVez# zUtSmdF4v?kFWWCKjT%KmcorOLF>g3lrdQlccPDHLi3g#cOi&vBTFc&ZKFBW;y2^?R zt$MEpGp3BPqvE=jsN2#X=FVEO3+0;B{Uo{#4z^s{;|k*of-BQVC2ZUaqdTzB##Q@Q z7+0M4uvpYE7xzhe2%m2Q&f&I#?*h&OvXK;L8-;|sx7wBpM-DdD7MDE+_ZB!$NUfqS zBR`~coM3y#idui>EHIgS&nrL%uc+DNf6dt7q?|BlQRd`#(zT?M!sYH@{pYY>_4ZE3 zW&v3jW=YX(X|VaxZ9WC!xPQ-u^gdr43qcgi3ur{N%QbLeW~p-7Qt>h z7}#1&Tk!R``#dUMu=jfeMonYmK*xQe@OB)}Ds>_UEa6;O$0Lccm5XK<>|LwSL-#s# zGxW>Chtz9?h{NW>DF%Nd@_*DIo3lpthhSdWQbv8)<_|^snULf8Z}nltrQTOVY>LnI zeL~ZiWbe}~`gF_mi~Toxa9f=>U^l)a1U(%YUnJf)$a>f+2%XV2Rt}dWDZ2(;z?wL+ zMfuWoeyc~cuvDXI4M$Q`b)^@uCSL0CaxiM~iK^HfJ)^465a=A3YtP|i71KZ_^l;F_f+%cnW zPCxX+flVDhTD!&Ft@-zc>sYIPFU*9jMixFzb+P7_G~siHEKOs(*E`ZAyYn)@q=W8} zEPl{(P;lpG*r{>hn5>gdGRIa|n~%^mu9zsxCo;BxPGpyYt(*Sjb%()TySF{)k7TNL z#xq-BZvWs;7tGiF(VWYnYgA^oF`VZoxVJdDzX!GguF$VI#m&`?qoZiGBJaAd-n2|; z;QwU4s-gQ3yt>(~&?k2jRg@SS04vZe`e9mUu>W?&K5REut#duRZQhjaWI|8%Bag5& zZB{WIj;N+4R95%yn3_=*V%7;e3xF6xQms>Vty35Mt8E(zH(*I%Jq+!y8IVKXBP&W2 z7tM&C<0WUV4Pc`oct1@}U)|i)9bAQCNO$M2D@a%wt4Bm5RLkt4`Apce2pE z-W`FA09QEVOR<+;zervn0w&7mSyrTB9^M+g+*Q#`F3Is1hB@d(tXm3e$NjQS_R??s zU>LXypHtA$cO^@+vmtMglat3bKU$OUOw%A(iFRo+j?i(f-_e`e@nks?*(HCH6@JoR zPGVEmr^cv6nMfHR&^PiNgw7hv(Pw-6V?Ua=zyHI`VBa(p6-e=F#*H}O6Q9$NQ?&8S$4CBpZ zV7$J}YS`2z$J{sgsLVbw*Rk`>aGl-wW!8AJ54>^a5E2?2lH*3NZpC3*&{oBx zG%Om7abcIBuH%kNkSn==Q4Wl?O%w3GfE9X88@D1!F*5jlH|W{C%hG-^v+Hv)@#PAU z%DzWda9OXhd*P69|81zx!9ceF*b8AGI&QO*gUol2B0M5O6`m}x&bwy)F)fBIfomGH zx7sbz7;)A4qm5*yPwR`_!K!k{W(cR zT{G}ru;X{<=gB8eUZW15D5jt4u^zYQ3Fh%`4uvW>Ym?}I{m!U6UgrD15zWVp(<|<3 zm;sz5SQ)q*n{DjeC_Cs}vKS~nGFcT8dPs<8=WgcdNSiy{CJb8d_CHb2vGPA9G8*r@ zJ)Ot+?(t4i_3ZK4eo9>IaG(f0M1xeFw{_Q6q`j!-Ht$qxk>tQB5n)b3a!UQrv&DuJ zYLnj3v#Ii4Ug#=igO%97I*NF2O(3LJDb-e2&ks%G@!>sR5MK>j4`jYr%nE^o{dV8b z-C$hI1U&9x+%*QWMZe;nZrjA?^rq}Sn3+I`=-5KuD&q5_O3pXwqIlf#nX`m#17ieo!$E{2d#2okP7vT z?lBAdKS~m8*waPL45@wS`>DOU*1jGf;JIb`ayH#DdbFYoS1jl3%mxn+&rDN~8=Dh_dckpB;c93rtJQlu-1%{Q1dveeX;NK+(eFejBzY`?AGV z${#(9g`3ZCastj6An2#NIRQ6Jt!~e7@`FT3kGHiA)?eqGjrvOb^|xOAE{VgN zeg8R8>4Ra4`r8}eZ~j{_Mk{MAyV<+Rhrg1$l7VSFB{x%>4|7*cHPS8L)Ha{) z-B&l6)>(zl6O6YeI^VJyH!1KXn!er%K}ZFoZPNuFH&6{){cXD+>m6e5!+f;NINl(= zx!W~hHH`Al(tZW^aCyQG*Rmdz@=Q$Lf^US3ZxUA)7W}TRB+iHyc$5O# z+Nhzj(80wLFtQlO;uZcG0xvs9=OacuwqoJ^e(zz=H0`Yx4)q7xfIJx7FM=SVNURGV z??A~MX!+qj>fPL0O0_{Yt-hR!$piHL|y?Chd5c$_~>EJ^ca(VC}w zw;5q5E4Uo=$T}&lY(xZI;=X4BSFSX6CJ&ZhNl=3Lz@1U%{lw%X;;?}am)3U=t54Fb zKbC2KM(sdZt23iHeNMS2En>S9RB6Nefam{aNBi6Enf$uF;C!*svOAzdTUPdgqdGMn z*i0b-!I>6AIN9g>*_Ooyo`_+{D+6Z%&E% zdV1EyB@#IT-PSEr)LoCNBZ%$O%2Qdp)zSmZ%|ZOW~)OZS`|oM^CMrADomgBEmjnskRh9r3(Rs>)@b}!{7@-m!7GYzNDif=?(#SN zuDYLzAG-qC0w{z<<3Hz%^tnaSs!8B792NPzsS;8S0yc6Ur=XzthqSFuB&Aws|IFm% zWPcz0-!mgzQ6AAUpF&?=gb4Cg$J#ZUgKr<7fI0zO6okp^qk%sPw2B_KQDME3%)?#2 z{s=sEuHU)P|OpGzdT{m-o+u~MJi9e2T5j)Hyis`HjG|p(acE*2^~3UP#M~Ks z2hO(Ad&Sp1EO=WsdG*`IU)~K{ff|x|bo0GB<5=e&P^O<@60yZ)Xr9-T$C&Gr9uEDc zG+8EImY+*7ghx&T&r)^e`tAvZpFXwndeU^{MVkppZ))80diyhTAnFd`!#$k9+Yzk z>+Pi<)YyNPro_HESrGq_Y<6(tI3@XPq@h{VQl7D%M}a0zm&nn?&p&LYG39uybnlT2 zBG(z?eqvE_-=bG`+d4D!CAJwQT9C7eCReb2uze9X zfkaURA)2@wENe{t%Xa%LyksmH;Dy+|uTe}{Q3C+~4bA$JRK)dJj)pNjZ^I8h~whw6^(X>Uf0oPd2NvXcxq)XJ-D8th>0{fsR+OnMghX< z$QchZwzn$)S+fUE?@DJWYbm+{z`p%qe|3GI3iEPo<*+sI@`HN~z2VDyI%zs^(=OI- z3EjPM(1YUGN_G$HA+Z|jWAmH4XXPiUmB;69XMc1ZrX&$HP**(&R+P@lfm6n!TW&e;D+jL| zWxkv{Bu;5U2l1jTaB{{|okLMGlwDePJ0pnp$YDfeb?ITq99II=e#(2FSYE6;C(pw) z-joZE7+2E$Qib5~h-$jPzwxe%W`M+6x&;J=C#6~a`1Gy&%Vy@gtTh0dcxdh}lsljO zO9Ndazrr(Wq*`IK!A~YDj{&bwsJ|Db3RLu?yVD|b?=)mxkJReyopTNS;04K~KTd0A z#HY~l+Sv*%V#q>3+ff)QS{;9seDcLbMOCvZcun)1J`kfWrHtSIW6E&Q<#{;jP6`L4 z(W7qFzjSX*DBf*5shSo1LFnHbKwfvT9Y?n|CLD7q-2kYXP;)B&#<_!@1yiq-tDX7P zuUqVwv4J;!GksDFko6OxKELq&3#9V{srv6WjGYy|Ez7#ut20T&RZcE0CeAC5hM7(E zJIxnDpkXJd{0Zo^naRGMMG6XnJ387a*!Hf=RxIKbks7W?g)aZ&qP&sI^OO=mhnnQh z6`iYCLL3iszFL|bC!#dX@;c1T%L&w$acS0^O4=27^2_Q2IJ<$T0nAYHH@x6jhRTwW zSHcasx`kSrlddv2sj?0(fds%n{74M)3zUTtlJl%}`%LJ`-;;RWu>jUvyS<;#h`Y0s zjV`v85Hqw;z#XovQq9KUR4p;Pw<=g-;U3C}e3M=Nd|#IAO9H8siS{glL&I4t|U*s4#NDoA!Ipbxr|rQD{7e@=&0W!*#`Z?*?infcyjH9`y0 zkG=+yj`r7r{`Y1C;LWlB-mJ1)qJmpATgmZA}lKVKAzu)5x~#g=W6i(FZ|L!lk+bqkYn`Ls%%UazlC55zXZN{L>1&V61=4)tTG%8sv4nD z#U)-2#vp6Uj%Z?Cnv|#`OKN;uHdTWzJtyxppgHWK$Hn7k&tolT&t92P#b%239_@c%v=;45_ zqtSD1Eg36pDD^P2{<_pH4$QmK^l0+vUAj^aQs7MwgyQSy*G~;bK|sB2e9JmK^MaZQ2J z=*g?iT_|a~Ri0fIjq#zS6UE;H^?xd4dhkFT0Ttk2PVcZmcFfU%mv9G1A5F|VT}@7j z)>VkQ2in)2BpkMEBwSiAkyeL{|DL>M$jD2i=@;!1$WMY$IBB?uXt}{q@*%(+JqiW4 zS?Ajg%CY2A*`aYdU!BTK!Xhrf>Z=ds?-SUmc0jVI1^;JjGzq6VSU|WtE+!5D4+SZ^ zhin4e+yCzoi9gQeAAL6z!A@Ne&^Lq2>k;^u?K%A~H z`Dw|x-BI%0gOQCJrr4@Dt^HGKSn|$Q{DO>&#Yz0-31NHAYx_!iT7$zy1 z>%dKqIzpvODj&W!PUcg~-avxATC-*m^R`Fyl}=QVjP;RLPWXFdPn;m$=#SaSBrDzG zEJ7rCq*zUpQju#|dZIrOrT>Qw7nHlTHfoCBVwAG-@(KP@eVYKXPiO~;(MWjAjC&13 zK*zNI)=12n(oLLRdP^z;*#0(%amW}j|6$Fl^Sgo)`AX#?b%Ts%O}7;-REQV(bF(g= zrW+8CU=l!Lp7rt`d#Il#PFI$(^Wp2;W%t8xSM%G+D0vX_II){3lBnDY(6Kuy>O!O* zT?9Vd`pUXbf|e-2x$k-Tenr^`ZaujE2T8r^wsgD_4cvCU=L{FFY9!r|4=M5sT%#Yo z>g2pdw0vRoQ*N-DD3Jf*%RC@zI}S;OP-V-wocLc?o`p=%Ul)RvN=lFy!lWENSzFIt zt<7U}*4(i<6#sqXt9I{|;(%_H#>!xrQb~AlMR+BUO=RK_0wHK34Y1x2cGG0vzjc#j z2`MmeXf+RyYJXAp_45O}l~y}5W|=veQmh8Sr?Y{_g#EaK?)Na5q;=z!l0Zmr-8J@0 zP=j8Ytxzzq1}SEwI3E1o;I#vPRV>Ytnr`fk1a0bI!ap9`4@cB-;+v)=Wk zX+Gae6>NvV%aO#2T_W^P3F~kDQBQ=47337X8>h8%ziy8vw|-@(#^&;(EM(5~OM1@Aq|WZfm4)7Vkfmpzf^^Qmdt$ z5$BXdQb{}t?rL0ENjjk~Q7@F{O{PYUM8@_a{Kb4gBIK2Tro;PF#?FBt`152z2A>lP zrRlLy)_HSX2Czd!|5Q+cIaeg2H7X(A63}V9up-$3&+CAOwaF%dMN-ao=i8J%k zkA~+{c5^8C&(WW`fI`7#iPA&w9+fikq+BV|U_uZ05Hn2`cL(Km8yPXGuo2{p-Iq4;^& z2iT+}AF0Daj$r;|bwSM=QfoEx4Sc~)Zw%4v?|uNtPcC}9@As>R@I%M4pzO+uoDzz* zIA9>kf9ZOtsHf;2kJB7;ru9_|8RDx(vVEl03G1OC3^`VE-TKNEF@gLm5>l{F6F#MC zvZ*1B!C-02+Vsue$9(!|ZtUes56g>*lBYg3u1Cx(~o&NrzDvkldu zVi~Ju0zk)mF2I)27j5!y1gQ6~L!LQ@hLsR=&Taa`8WMHT1TS>+y(xt8*+X^jveqyJ zUPM>6fVBjOHW`$3{6{ZsI)YzF99W8&`NO2BBY{YxWvA=G6L@qzjQXx9P0^h*D23uC z&laY+gZqu~Qo1_Tmc;9V5`mjvli8It&q?*-mwMFgxORcjkdFV!R=O85di&FFtI zt>z0Bz+%FsdZi#0c%YvhpCYug{TW^Z3jQr{gB*r6``4T@IFHz^`GbU-*{|)OF0Cm@ z5i@UeZ-fk{D3;#m|3zAUG~n~79JCy^N~K*&Yv{9ou2%SB^oDFsb+iu5P7eS6Q_MZI zP=PKjss@UCPs7xuH4QvvTV_!lEA&`wD_jLK5Jx&76$1Z9sU6FUZ4`%uH=O~jwvWda z@RICrw>fc4b=ThbY#Y6jz7af@^p6Nh@+_zg!a{ej>a(TfblvtLdX`8@DL+M?8R9|E z8!Uvp|BKo+;y`AZ5&H>zp%n_G>KW5`*f?;jsXx-cA~h`^ntUulE&V75@sj^<4^*$r z@Q2hVsHK?tK6^=$);sxt`{BRG)`f{TW5u^O{B-{z1EtU7ULLZa)OP*9w+ z@P*@hChj+{v+OX$oKztNl660~z%t)NY3A#p@IdHu5YAw+gtb%h24J-yjI1AE1C9TC z^g7_$j5V`>YyUsOW>K+*{Aw3``g(JFvHE%vbl)<x8A`UDS2ckar!y zS-lA_NXD9^sDlD)@IK=V=7J&KcStWf>Yc7Ei!ERv?wEnNo6f*hLi@$Bcl_xcK+mLh zMj()Rz5ZbxvwC>|NNKo?ymo>JbNDcS?;76=AhlVrRWu4sjrH*kYSC!?SRvkVY3 z2@m9oV$}sz1y@`7f+_fP^$j@PbJ(PT_$S8()@`;JH0;nZtA@ciDFm@u$2WcU{J@Ez z;?hU4TW#TmEA!~(c^cp|O&$R|_##9I2@XzGy=WRaz&yPKJwMVc)g`XM$hv~REX*Z% zC4u6Zy06xNq&awfOv@`G5iuczhYEa{?hr!?S#?vLH0Qf?CkdtKtq!(Cs$Me$2?(-S zxo!AzsV0$zIaR_022P%#t%g%(;F-qkl7!O{z=n^U^k}%O^ zK6(BpD%hEOxwdbIbdzGN-Q0Qo+6um5(cb48gr(#Q9m`#rB2(ErO(+0ACs55D;k~o> zUSu9prxM$(CJ}aZCh@9XwkeZf-?ih@>N$FvqeviW!NLZ$#CTzo@N(mT7G|VU`a3S- zC)sisn%Zy?kYu8%r1|9_av|mminV*ROL}gA1c00+&0j2NSEK`Rpq9%0g+^~A>^wes6L145A zDNgl%8bgIqXn$l~y?=?fQ3W1^L~63cpb086A(wyt?*#0}*BnO<489>K)3agF9YohX^-1 zus6&Kry1DZ9#C(oUytSKIQj4YV&gd1#w9tL)YGHEU5u+pBH{Nlf>g5tlpH<@8REXn z2K-4CK`Y_n@&1^Z8)jy~-aA(U08VjHbAeSBe)iYsPBm)-g4xTPM~2UWV{ajy+3oc> zpo8A7e0Lss3{URQd>I4EIyI2%U#%9~v3^K+atQrGzX&t)mzF?0N4*$+z@gbizW9R& za#r-s*tmQ`VkQT;981tY`Kc$FknaHyg1vn7?+t zFClGmER?W|`m}YN0Re|GnZDRfHN(KlUD|vCR!--ivmQTPH@PLb0sD%12oN}F`iXBb ztQ!-RU6)-5YeV3F@1u1lP|@)b9fu^UwNoB3*L?~!QuT!?CBMg?&|+g7S&LKLK}4Qm z6=kf+GAksNv-6@-H1tTVnWQ_9Q#s6U!RE8fb2?f1GMoc{mcr4q#rH~j^5&{{A-!RC zr`T@E$+z~#T+7FiwSS%yrG%{XzVZ6Kn>bcy&6hpA8sNoX+SkF?td2@35TXIMwxEgd zbrqGCZbEzydpT=hndfQ(xpoz~-EgR+!M zqT)a?ulG#BsPy(js*E-22!LDBOGTy8b8s5hPRR|Pvof_FR%$S7?pqAP7Uhc%X@_Qw z#G&`R`C-UD(-J%{1Hp^Io;LutS$(>%(6w`@ULu?)sd`haSbad@>lit<_m1<&+dF;* z#-let0`alK2W8dT{8jWQoB#Iug_l*xQ|R^C_j{ZfK-^0wTS|YS4}<>HUCVrxE( zI-d)0&~->%!zj$P;R+WJzFx;b;{J>5;uoOl?B2{BxOx!YaN1S@V1ZD(kOJ@X%*VyI zF}o`wC4deg;Q;cZ<-eINJ4ZJHqJg)GcqjJRVdQUr}S;-MUe4xpQ&CnHGT z=c^(}`%Nq@P1l%FUCR$XZJUp0=AM>6i`35)riFCxUIW5`jx;jHSG8n0Jb8?g@puw; z6`W!j2n+4&V?+AUKypoRAwQrz*!32WAi%-q42K?6=n(Y_d0r$fP@zuNpNJdf!1p`g`5 zQr02^>O|P0>4vACeS)<>f!yU(qQi~Q2D|(KugdL8V;CXI|Lo?-<#^|oPWQ&}SopFaeU~lgb zM4sMEV&|itFi2knpk?P8-3eag?yzN~9U*a-p&E^f+j#QZUq2L@Z_qC|ZdyfK@@K7T zUlLo49FX6Y3Kg6qO(LYMP#X>{VuE>M0LzO@xYS{`NCLT2+eHUxEWsNDPAR}JH;|)! z@V|xsQ$Q-G1ym>n9F!f+TS5V?n?YX5J6HzO)P4^oLO%edi(6Gz0Z%?k?t@tiE>`;f z1{fo~n8Ug+4St@`l$CT-=hg@V$pFU+%7e>!9{^WYQu$cz5EHw>b=!0JUT63IPqZ(FQ# zBGjw=L%!(zT>E#?`6fjQ0ycX>m`0<&YaK@{-mRGDmMyreY2a%z@DWzQdEE#YMhA}Z zm8SQp@r{YmLJpflfnoUtc|PdS8gQYZhQ9Q<4NyxO-0X|oJKkv)nCmSd);Xu9GJK|QXBV`CarEr0pl4KaqKFPL6xj8^Ut(C!9<)%=Kt2Bx^hSsTobM zADthJy03wvI6V;;(pt?-qFBL9sA1UeNs25URuW?Q>#W@|lJ(|L+@1%HU}Jd1+RU44 z@8%xa@5_Ajm+g5l1RZ6*KC!K8nYSF};9$JBuGUS0$v0a=QdINjctu$mbJ3;+C?>Zm zM#!0mEC*@H>tg)NVi6o`n#Mb6*G|{-hXCLPkC2dhM$wB`81ZRWPr^A*S5l^5ToNkgbVR7=jEnHQCjRHIZGJ) zW)uE~evLrurc%yGh_?2P#r(b=8@>D~RWHux%4O50UNjIwK0339DeF z8Kheocxesst#`=P(b$qHQL}08t0?kYxU6mKNdhyJpAEK`C8wC!l%Wt1K@td&U{DzC z5Ighci=?P5t>r96q59uiQ&kN&oNS51^Mi{Ii40*MKy2y98`^@6jXK~$d=f5pQa?}4 zOhF`I`3*^`T|tD}t}1x=2ApgZwe^;o;b0Tn+{&SNM1DvXeG;i9h$)Cyh`hI)*c%Pg zs47)KK=wD#D1>H0^d`M5|NA?76ymu)R}fIQQ11v3PWee1{{$?pA=+fQ1SQ&u?uFMA zxAC~NA73k79MKfTXX}pKtC|-gOq%Gyx~6bn>nAnvbNW%8w3>;+A*<+P&SC$r7GTrT z#O7AUB^*1uik4A>z3VJAYssuWJ{z*TkcUSAVq-(b3D-@+OJ_DS4UQa@e3sU=)+B{w0*KObr@ASF9 z&5=!bG`MKhM8GOamK#^T_L&e z-bHDIh&c1?D}*cXDSk+x=1O|@Gvnh1b2s53g^_7ym1Q#qu6l%)ew<(B8<~_SI;{bP$PRsXA=@rpcpX-@bUlt{fSQ@5 z;iaqIpYub+U6;^D?YE}+Am#;SjFrc0A6s?m!)$dMgO9=B`Y(1ijpgzDr#f!?UuQ1} zx{dEnXGqSh!xR?A^*{c(c~QZ~uOg*PQ<&PGWB07Rt@=(RRqx+Ni1I<0M|wil)Uilq z7|@<)MvKZ5L4sTqA?74lHLB5p_h?Gm-E>jkiWBBP-IA!BGaSWfJJge9>G2= zrBLX~7n$f|8i2c$q_ncxqH3&DvuPQ%^$Wy`P0N`a64Rvj*3I zp$uq*bdLFjIKWWK4_e`kX=3Q!lg&@xtlqToM@D_AXw0>5Y(_C6Rh+Iimla6J?~#0g z>O*f}s-v~Gj4JALI$9Vx-BR(B{NF|uR~Uk{7d!6k*N+&Djazf{9k7PDhiPP^hh>2O z0mL$VG)?iJI>)+szYlzvP)f@}!lU!FbWyZr%4VYBR5ZL2aWQzAt1zpaau211zKaeG zWha)I?Y*;bKr@tv1<^bj&^NC6R^uVX&&7PVROb`w?<7Y{Mn->apIlU)XK6FxUr>9; zxw&zD037!A*IafekyWKG6wyd!<^p+nSEYOnIZUj@m!q9n!a<|Y{iel2DM$@L8oyA( z(!4AV%F^yw4&)laBpFN{DxqL#57PS!aT|HN1bj+Hy$EZ*vB{S&XowF@XJeAk@E9Jv zJ|membfifZnI__9t+}D}vd?+>_qE%wmHD}kf)*NKXtZV0-6VURo}^rJy_^<{lM;UeA;Q zqDd{6`5MCIDp#+GH&ORP0hy7E{WpuzF+o=NxT-4?jSRQwFX=Sh<3u=v3BlDt0?7C{J26z12Nh-#L|AM?B(>!!-=zXzZD)0#g5kc^7dg+n7w1S|o@>QP+K zu@hCu4R#{(Mx$!Ms;Isj*L;U(4A(#n`&ED0Pwd5C_RArd-hK*i=)klL6>^dB;a8F! zy~&(PwyKh1|KH#ZE}0RARxP#`+ms{fd90b%o@L6}HG-hQmyWRR=#204hXt7)xMTd% zQ;O#6W-tp{`Haol{e$xe=xoKd=7@sS6$(WNS-;=f?S(@e)4^WcgPV*f^>Fm8 zZ$~}~$A{_%;5lG8tNQj9*fcU0dXV6uD{5=YC;U;`(mh`UE~{c0qSwhI{Z9KIMvigE z23=E`nVTPAgPMd$|B;1LduM8~-=~|4GZhd*(0gcsmYkfH+D(1(kH{?>;RD%#;DPuR zrJ5h5+}Gk3y%@c2L>H3ZI(YiC{63|P_i*^OsAwdsIP-|-1#Wny-%Wkspo=qYnTJH5 zfD0Xw96#FT(W5lMh_Sw$HY>GL_tYsE^bc|;)u~aBQm1*u*6E)PO^rS~qm$4uT`VP& zRdg9@)R1P-U+TnrB$(*FYwHjGNf>OTTxv0;kav;qk`)(I1pfFoT`wm`kG&bLhd{eJ zHDy8ry<;`L_!79je9tZG!f8?;$J@lkTi zlRxPc6$jF=h-`&d+cLg|Tuf$Ag6(#J!`%Dff4-y}Vs2`h(DL)=Jwn9z;pTjgDM9{Z z7dI*MKb@wcuFOJ`TH3mr_8OMv0$w7x4j8F{@^NRfXtd2p8;5|BDby{~kK=E8bIc}q zq(Y(wZf%mwmkRq$%OgAcfR3$!W@neAE2-HaLUZHjI2{OchYf9g%q z5+8W}WKlwl1uSVvdySJ}_w~f9m{WWVqk(ohx-(nbQU_hwAl$e!kwp7ST zo96N6V@2wf#&;>o?B8cZBu?52CpA|6lg$VrqRk%U480*9{$JV}$P-A!)BzEDIXm0b z)U-ykWbqH)Z7__4!%Xn*(I;8K=c4rb75Yxs4c0I-`!^FI)FJrVt;@K6@0o8V0V z9gkWeAj_P_SBQm%O(--olTLBV{q9yUBl{^Yeu+;IC**;nv)P-`!-VGW)xM2B{mzqY+PV9^*)fcho-g%4+F8QCv`p{1 zMpE6?LqqL5-owHD0fA2%!a{9Q_eAMEMkUk!r74&{$5RNv6EMOUCt7 zIC_Ii0*EU%l)q5^iB^sNond@RK}STux_?-eLYe% za}yauE?a*LPcS4JwYc&u-SKF@{rE(%eL?CkrL}?f&9Qe@`dqQB341U$lt$V^#LsMM$_;p<~=7qa)?MDj3dNX}Fy3xmJ zI0J`%DNMwPwriP^#f9jeQ7zy!+=g)$p+7BkJcaqMq)U>Ttiyo2IzLdYATYtzsrr|w zp;2M`VAP&p$|YC^;`=>iXJF-z!&u{|i&I4=Sqy9tf2t><3?#8=bthB?V#Wct#3s%7 zHVV2_epMR$kcd}V`_cIbF%Ksi-e^UFzgD5nw%}~is4-z(VUCeH{ zQCNM%pPy$v+UIP~*<>q&9Fj}&8rvMkz>QoDkzi4qi1C5F)kyUHbjAO^dH?mC=vi3NXK^pR}ixGH4r4mu`TwSl@P&mD8cts z8OsY^2=}25=5nxQgf8`Rt{j$4d?kQhZd>wK|7It6({Jx(RXxB17?mxy9P^9PAoUSyZ3F%r!!6W3}%-28s=+1be1 zvwGF-e~oYksex{}DN`>2O78R+ocMfNvw3*)kB+CIex0}ySvh6iejn1zyl%+C^KenD zR)NMmp(i6@h&itONvllbhg1nap6Crt*A|O)HB`A}iKvWHciH9K&m`JN*iY2M3#9~N$EQaoi7-pn`>1SY_YX$xQxN5O2zp5e|hgk6#PV^^+q(zw5;_6HKMxGapRC z9dcV0hW3iGwuXSDxiV>y4WA6UN6A#IK}Wa$!1%=xCFBt5#q68Nfbln5Tw62cnWV#6 zjSGL&dF>rzeWghmD>3LpwBq8gi&r(sAT*i!q)--2j8iGw^-;DQgLrh1R?45xcOasS zN5^RTeK_LfAPv-a^VC@&8X7dp&GOTB`wq~dSPIBGO^Ns>_r@Nm{i!4z9MFOK68l$% z83{BRvWiAUuI4%^7qnYUGkt=|dAHsGKGFnGTwagjj13%HDL z%D$y#+(8OtNx*sQQFDs0l<1lJv?8scHqDTOkH}J8S9e_&1|+yG7O<6ve2WK&+&J&CJr@E;i|IK0d(!6O4nvv zLu;X}{%fD}yVl0==qe_eu2WOmEo)u_eH7{0k1Cof_y#ok`5W}C+>)=$eRNF@NJ82) zw$_ohajDOE9ae0ttkKI@d|$2+q|ePb@X$^eJ1NY}?Nv8a&k%kN#=fgT>ieVUDp4T+ zzrwEmW&YZTufo5t+FCM%cD;a{yty?6k{f~(?FMk}J$G~Qj(zOI$hUnr9MyGdQL_eg zKluzMj6LhiuGQcf(CORdJ50pZ;Rg_Mi%%Q^a!TwMar4ICa+KCW=X8{CEfxa04YjeqkrY{Z$QStCRzHzC#>19R$8QBd2quOo;Qsfm3zpy zVrYmE@IuN0;F5kTl@Cfr9&3YA(#PkOM%gy6j?GXG4L#gcAgjsxj)zn-Ofi0>d@{w87<75W5mZ^4lDa7DGNMNmtbb) zvdxSRYmWn(3%p^Q0@`t}D=E(YkC8JzM%$zMB$A48g10Rpc8XHNC2CvkJC&=pk@NFL zZlhxEqvH0Ri=3aQXCnYmQtov5K;pa(#=u3wgkuMajb*fXv@1J?C;A(<{Z{rp=9(oQwN$cMLYLPF8mM1Q&24jH-^y^SwSv<(^9XC|!M_TSqw z7pQv`vP#|c*<7S?8XE<;A~dl-K67IeQ*e;S_>Mx@?=hJmXTR^?&Wu}O1xq;8g-ans z;6{J-eUJyv2JMT#7f#zc{mtIlIkpvgJ~tjgg;ctHyUp|u{`^;H%*eak2QycZAqAw= zK*&RF3-M(jAa$Z&iku-EMkyFoF#Jx-+l(h{7%ePpYMBB)ZEks1tOXjlju8R^J)}E- z9YZB*^UD$N3V?>m^iq045G!kQc?#OpfT}Hud`S^Ew=!pOZW5Z-%604&8lcbyxt~}D zKK+Tg|3HBlwk{(~VZ5*7ymI*2BVhU$P^?1IRbQ)**#G%?lagCc29WE$AI&;lzteNy zW}Utw=SsN6#-AY0d=hrqY|OCXvV5GY`zVBNZ*7?}D{i2vR!p~LGd_nY8KjtdPT}aGlm*5%H%G`DX~>+?>&t0pX%mZr2U?>~Dqf#oFG=@5{NTmPk%{umv#TqTFzkbY&Um$R<+79;@JARFEmd3)kH!E9f8a+7@Zy_C@( zh61Ah%gRWp^CwJD-7E5GT4T<-6q!JeEPH!*WXkHA zg>! zf;-e^sFB;()F10T-CcSN^7|M;AQqo6{rg1v+F6w*fopZ#-8(*;ia zqDtV{A{@U%&G!!EbJ&CDUk9(Gw}#cGuMiyU@8g*5{4z3`WBjWnCBu?MGJPZmAn##e+_nx4Tvgi;`^Ew)&%xK+0YHlW5ZxJ25A z`HBP#iA1@@IwcbvHu@RMRb}|GF8z)m=IZ=UZh~L8J#eK;2vkd<-2VB*7B684&FR|S zdi5PKbbaB-_Iuj<=EBRp^@OK|gq*L2ugDEMCucj+vh?Nj5F<+_%p<{oLhGYrqK*C~ zb|!uIw+O+0vrs6hhhWF^I@8)Tf2-pop`C$mDDSv?GaLn}0D!P0Fzv5LItLcWd) ztTf(W3^)-&ol^}m&02kffFWfyM<6>F8JQg%1J|CDKZntJ;(gv2kTDtfB z*4W!&==~|iup%TvYLN=TIe>vFaZ2Y};aMGn48{YjBCCtXzw(W}-_T#GB@J?BEWbj_ z{Dnb0$c9gFt*dv|ea8-Fw7$2qzDZK9^>9~UI@N*PCFvha(o&b>RH`M4p_62tB$J1< zhVks7z#(f|+$_VI)sO6^oY*~uof6#wvMe2Z>EeItE`g?MXKwnwcD?r8XUx;kHkUd$ zISIaA*}XEx67vsW8obWXv=w^q^G{zs zQ~~D9Fz2BI#?9kg^$F>zX-)t*#k-L`zD+TcCq z{8Rk1snuuolBa|z^R`N7^^F=XjjtZw&}1_pq8stES9Z%@f_TJ;(I^ZSQHV^)Rq$Ew zep8sM*t5KQ{SXCk>p|QTKW?~2PVNsf9kZq3YTOZFFEcO z5Rq6BmeiBYj@Lflfk3Fj`P*2Z%-7pT!)@s7>VF@~TmEi)b3d+1{f)kyR_PLKd0`s$ zK|Zf1fe^OmR+np&iriv@k~rzY&f|7`VI53)Jd?;a&uvsuLUiYJoJe(Sjx8vhI zd@d(l(F~2DRw?Ez9nK`)A3G*x=haL3d9Dt*qh#6Y4%=!);VHuxT$1Zri4`t(*Tuoi zL+FGJ_#~5v_nAI1)KmUCrx+ALa|yKLGsw6?6EVv4E-PpAoD3TpQDq66dc++%Z#iLF zJ1vezKwO1XFn#<;7=bG2xzc}Y?jOncp?80?7H&|O!b%0rcO20QAEf4#5hl~dH#0%@ zLAq=StzP#PI=^7o9!Le#2sSoqF0|Mp6>e1R+^maI9b`z zL=Bpr@a*(j#Ok$*uklM*o$~7u@^q};1;I`>X*0@4y<=mLc*tXTTWCC%BFE;ki+2j# z_W4b7)k>>}!#Ch|r6Zi|E_2S8K$VL~0Gvj}WZ)Kkcp5uPTl)`~7i;eBo?~;r5w3Pz@l?g?+sqxX88TjQ zRe5E2LHseZJp5k1dMuB+vcZ)Ikapa{4uXU68QYZKa+V%uXN+DRy?vD;=vK_}B_3kd zC9dF@jG?-pD}6lp)NChiGHTTjK$#|W)_L#P>b<^EUsa8RZF7ZTdq6ld#nC#cSgzA| z?y?$=JDW7hr*NNE_5EQcC$HnqX7Z8aum|FF#mq(Bf2)TpnG_Yjtn)28t)fGoZ5lP2 z29H2lx?~57-%N-BK&doBCS_XneOq_V3Q@%7%{Lo=CQ!;{4;cd9DunN@+`n6Gxg)H% z`W{0)&JkS zv*P&*qi;pD&5*)9s1m9vxfi`U3U^Rb?qlg&jE`K#yFb1e!-pH zRsa|7Z>}CWE9U6pz zusXMKmnLX{|NI2*kRkoLfCt1F(hohi7g^1wFILTMFDuC%LUjc>K%KbMnjA8 zMm*0IW1!c0x!T6tf$+QbT?=E0soG6VXf0a@%g0Mf(Ud(DUV-3lzn)g~=#{MQeL zkKxmAXOW8gQQ=gZ&0SOT;|wR6ZuD^ujkh3ki`_=AZR=SiVn8c6H!p@P=Xupeya|dA zYpX*p(xAFG>u%S>4gWqjSB-PiQ=!DB}|KGu86|yW=G{<5Fw)A>68kKf+&;0K=?T4uuoJnn6AzuF~Z5gndhXnRjS?XP8CG zxH(ERB4`0_QJpp~SyeI_g6M@L*x<0r3F*%B-pyF&VJ&qOP8TG=1XY)OTjGDL)oXfP zuRqlU4xE+Kmv;lJugB_ks>_9}?CfH`hB-E>C8{KpWjljGa4aa?^;+I@$`wn+VAB## z>Iw~4wH^$>42gt=oqB4yycwR>uD{Hc?i_a;-djT!eBF}_*X3Mox#ID?yMERCwt`H- zGP!g0l3x}=lx5G4IeY7V`b-3L%MpZlx>z6cR;c!sVTHgJ8c&syaV`q64p({Y(XgI> zs?u-!^LjJ;$|YXZ+b}ALE-u}JROKDCNtthCX+#v13tKp1qK%lF>tDje`C%H_IdE*E zYfPzAs6b@SVslaXS1vtVQuwwjMfb?(m=ShtVN=DPC6D9qzzxD;PwAkIH>o4>V=m zDS{{#^iaI>{MzsMOKv|D*Wi2G6h;Y<+TN?0krim~H6dIXc~1+B!-?6IP7h}Y1CsB& zfDVFDSoL&(!eIbgk+bM~?~BDYp{y>E(b@&Km3>cJ?dsdO!itkPF4Mpb^4 zxxJ{W@s=0HAp5&D21W16c8EZTnF&F3k@B&eEO5wW^4TZ01ar6F?_eGTM28i=M?$={ z9prH=aL3EU-go;h$Jb|@+>O2p89z>1L|iB#wA?un$u{*L9Xn&*5sLUV*L*7lB8ViF zokUjAs0jE$EA=VwI59%U%?R)?j>Z${-7tLlZ?J>Csf@ZA)-0VmM3FG_taQ}ow!7M& zQ@hCF&V||8vG4uVPCl`4jVv#{$qx+7WFEa((F^;4CPG90ASM({Xnmd`1`Cg>RNNN} zr?oB2$1f@19bYs35GLQ_IS zH04F!nO={scv~*C{(E zr`Kz+>i+1}`O0;5U$vdcgTqnzwy|Vw1-+)Zj2^|PY~KeTYvW>yEtr4Of5b>J&KPh| zww&GJWNuN4S2Z%LET&8PME)ae5sNA{eI)QU)6B{8lLx(Otisr0y)Jr@ z?)sB7?_Z)D7E6IGbZ`l{T#+6jX$?JXeWZ2lD`5D5+6T0eiR5#?5N>}?(7bPvwaep$ zup7o^W6t(|VG1FN9IeXz%pAau8ca$R))X4P{m489d4@R!XR5uh2ifzyeAC-ux(AW% zy1nKW+l6z9mAWA=*Gcmrjr9;16JWcZQm9K$lMXQzNzXqM_@pao|9or3THx5&Qob5>Hd zGJuwR&*Zyqs+W_wbI4@)iPzBJDYI-nBrk6?PsDcGDBoY_D0jV?J~2YC%`p-HWO1Rf ztC~cMIxQtC#Kd#Zj{79vKEOj6Tzx*{ZS-l`7c=FE$#u00BF{GxpVhIIJ32Zdwli$} zBeINKIeDA?6=-F_n?l{y&zLxDo;JK={W@dlmE6ws%m?V*+&E<61ODT!;iE)P5PE|n(4T*u1%!4^?+fsmFM|_@{nEgngaMtb3XvodkbsdjT8OxqrOgf23 zBr%9eA;yH9V7~d;>|H;ah-lBWsFyCKRB9Y^K1|~%6+y(b1cXVQx_HktbTSc9&RphS zdsmB?oKJtXf%B{=e(RKg zaOGdWT8-&l4Ue%WV=fnl>F;ZXydPsPCoKd9{M$pr=PjfP$+k@`e8WRy_@sD}3->U8 zfC91_k>p2zB!*iZQzwH&TV0xB-Hr^L7!YJc-=bfUOBZ9yjWQW!P+^krPM`huii6%^ z9^ASM@`jSZe_{|P_`3<(1SORP<%$x38c%EoN9y)en)w_;K05$4q|EV( z)+=R6wd^~QWvy~wf;hBZtSkbAnkaPStOQ9w?UtAZ@%x9D#hhnn0H~GA2W!jrIi3f? z3^7ahZP>2bQ9Hk)_GQ=WARu)v;xk?V$Q~V+coCOb>R0vS*II3`!V>s_<#C>=YjV`- zw|v1eq?%Q}fPcE3SY>#eB$#? zdfj_0wuk7^qw@bA6D6V_WBu?Rm4QEOLO!uD|GRf8lA?-A#IE^@#p;$kDUU~b;3EbL zCzpJ?p2?hy{i(k)`IaXa)Q#;oGe%aWy24a;-~x_VMGg5w!^bb9vjPIzU(OorT6-sB zy@L#W)+k7My@EbT`+rJ!Y2DX|3tple`WhJ>F5i^7rfUNc&#>E6D=a$dYFQ* zH*<8k0#SO4>SYk_>e{u5RW`a)mJO$h54bkD9n$(<4mR9PQwt3L_dAypmVS$qxEN|+ z#7}@j^$#h|uDIn^lyC-5yqOQ?1DvLLOz#Luh0INAoY}jTGA3o3l-br-g*barr#6K* zG1hCpl7s`{iCSVeL1lW3&Gqhm-l;FiRj=a(fg&@EfJubrcE8~E$gNtCS+GkrE! zddoYht$)OL|LgapEEdskzRW%LRIPV1W1uGCmKKNK7P=k2w4@$93e2^Bq(eVigs*s+ z#*_+C(ovd2J|1x8+7NAUS`uD;R)*dr$bY`qfV_DgEc3b>vm)hp&PHhHuINVd^|;41 zXz~n>AKO{yZ2)mN#T5x$v9xnLzO}W7NeroBm>Q?td+Y5dqKX<}7S<;;E39e+{kDi( zsj##rxb4X2v-LiftR=;t-guR{)Y^>>82)POa+GG_XkN*K$2r=NMn zrmQ});ErxjVm`lzN=k5#3I5GGLKE~lwOwg+35P1IV6u~TL-gC9Z-$n#voEL4;<-9ML@Rs5sFEeTIo&tzNK@uHbL zZc#Od%&LDb6zy6&9Z#Ra^s2{Z)QAL;?;bJ)$*rK=zE|%pFqV6cyfE}NLR=y3(LTJTiN4PfcC|yApQ$dFZx^kN#t&<*-I^ZlEKOzKMUrlXtQ*9<3CPd zj79eSNx4E=ck{R0t$pV|(+hLe*aO&c6!X6EG@1CDq1wB3@|?S_5D!tgXsig8DaJs!ZF zLowUr#xT$?X2zj6IzZfa!&c?`l8FC>M_D{T1h~gTnm5KQ^-BRDEhYtW-4U1nlvgp^ zH`A`;8TECx;l-ivGA`=#FLX9*d%}=Af5mE*!YvS8|Afon7`jR|sNPE1Y4E*_?4t1D ztSup8`UG+}%&MWs)3)I$KvyIie`mn^qE6i1{H`tp&zq5jjSy4Ug(Sc|w2_sd>@Rbj zzZH#O5lNN$@^g#eU5_(aQFahfUeRw5vI?8BYWbQ(e`I? z$~eDdIS@6ls`W&-_1=1W3I5PwgKWF5to6Te!Q4%~KJ}@erp%arLMJLnZYO0c%S_E^ z?lLNk1xOfR&%@13oiH&;);b=p1a|?I^1Ywnx@#fxb`8u?zeUaXgg~?UV>HZhK5gN* z{bn$}Z)ceu_^FSNKUwN|B_#G^FK1d>R(=Olt;rLf5NAdYJG#n%WvnZ0S}!|#%^?V) zuK?%^O~x=Qx3}vt5vQ@98>#cz`;{|G$=k~iNo6EO;6Faoi+b%2N!~qyXc%Jh4z`Os zM+2&#Od(*!Rqa`i+c(Y)LCv}%WJ7s2(ae-d#LL#1?)_=IB!$v+Sw4i1pRe#4NWWYs z40sS{jW>C_5^f_HiTj>~db0!smRPFUPQ1~r;&_HrI@w8nj5u*Mi0rrEannPYHPq?Q z4VGqmxYuqCf~#H_m1E8%KZ>1ZoX)8*0=--2G@fA`)P0zraKI?tn_+x-1S(%;Wm7UI z?Mp(wTX%^!3HKCal!$!bNE07sh-=mD240cQ{i+XJPC-5|lsQ!<0U4dxE1+4kFG;1C zb29Wm`e)^D^`7WpGhOb)yyMMNJYxb*HN3w9oYIVSpuDGh%yJLG;E$CV=%bo6Hl(Em z8z=(qFOZkWSf7xWuOWw%ICT**YV=(=MPys5n0&&OT5DB?_Zk&7U#pnk{PODi3X1J{ zpgMxdRDqkLeR#bY)@^9yZ#wUQv^dsAVKMwZ=u$=}E*0)Izgqhzu-4N;zxAgf)!UK+ z%j29$0Oxb=a~m7h_9Ab^*(`nl)H)<5o!mHp28QG+moxG~LuwHJ>R;!ve;$l&v!wTSt&waaIi$L+c7 zYZ~xmKd5yVRGAUfSS1l5u?9Y2c0B2lte*Nl`M%r^Yj@ULo(|9^%gX&#P%Z^|Z5>e( z6E8upOHiIVch@?Ri!ez0&T08v*CnGy%U^?@BFSFOMo4+*$GzJx`(?e3k9XR{>LXPm zN}4`6>?f%*@Uq}1bGCi>4X7%$t!5`hSO3YB0^GREK9hj#MV|%lO5p}NX&lg@PN;=F z5-|t~8=zX|YbN?i6I4rup%)Bv)6#TgK_OOj74^ka3U_#`h&{@7R49UC4cfMkk}YjC zrK>&H!ogl-cF{E#1Ln0@@O#Y?V;f%FHX4&1;dz^O3eD^H0;<3Dvdg> zF7*H?xhk)~_~$gYt+Y8fPsTQ_SkZ2?#r6QPild%$z-{V}5Fl3R8~?zeEhdlmZJL<8 zjk{U9%o@Y8eD6=_=bdhq$?BSK!MMYv0zX)uv{tBv6bQt5dC=)J%F5$PBTjJG81MpM zhS-%Nne=#L;KFBaziE1p#%$L+zzynIWmmPH#p>Q6X8luf2DM-YzkG)npero^oYs8ywPPa&pS?g7}EWHfhrj!8h9xm;W=Hw(9@w zMba>M+2H7aGYKGg^Yb77FB4yH!}$Qr2C*}O79-9tUv;5ienIyG_2P1}rXv~_b#1wz zq(t99u^R(SN!5YYkdCo<83WT8-&3(KT|E>fX(btIg{LK@Ro##Xmy%d$Tr-teBVf;* zgi&?{(TY?l)!0|&H`jVRow=PpgUeYQBD6T+%(|h5ETNu`%3r=LT_u-WfCWa0?-{sn zG*oT52A2&05-+=99ySz!g0tpV^IDNF8?{#zrWvT^RS}}~B{p*2b{K$(2WyaN{7$c* z7%R#T{E?rgP~X})IEWbs^R;C-IIH7(^U4Zt>6Qf0)XUJYnm1|4Y(gUf4z6cw3EKdS zfh*#Ej{7tmMoydCV4_x3@3!_6tbE=Uf`XR;P-0;Q)axO0xIE|}Ak`c2ryDowv2BhF z7T?)SE&c&?m(B3=b%kIOAjp>P97s}Q`Gy#jEHZp-R&`0^H_f5RqjTw{^o>j{|N_$6y#e; z@t=`d95Kot^tq9p`&CIB6U|QKeSA#jXzE~+KeSq#j6}j}ThJ1%Y>7-aQ+i-IljuZO zH(8Xgj*HBWNHO;G)$87r)3YO^VkZBM4%ak1vPGRvBkZ{2tTiF>)yUDo4n>NvA)XTza`G?0zr=iALi|HF70?Fp=74X$b{x~yso(tKwbjv0s z)&-M(rrWmi1r0}#kLk6WEHWqkp1yL`N{_zRU4ckz!_gf=|CU^RhR7Zb0|W3dBcm0M zj>2DDxQM*3{6pusK%dl!GlU8&uClMyoYjD$YYlbDBA(^a2^%8uHkZKoz10lg@2ll1 zCfl|PhO;{BK`K_I3_vwZtid1W8a)c0A7kv%W4AO(vUPH~TC~b&`VVTGt2x40*zm9m zgwH6+is}$iU(7z-tTIGll6j-1NLt>Y>b=9VCJO&1*A5Z?**5>UAR?1lZMwBT+ix@5 zxzcI$(LvwC3k2am&&}!A%+uG-XT6GQrbpj!rqxemEL0p6+sQO%sgoSm#Scbl;9_SK zXcJUtswsqJf8B4)4Xp-o!@W1g!g`-okntr;W)CMsnIrV{k)bF0!6;v)ByMyYr6(@p z1IHkGfS=IY@$Zq;Gs)E(FNcd5lZ$ffdI7ect(bZ_Uv0kn-Eu_#Q0l+s$M!~vSxw8g zABC-{#-QcnCkqytbS5ACbI>7~?8|@HAsIj(X06m+%=+aMyy$AD#Y~gTSlfCCsq9Z5 zyCQswUh|CqfJLBj`QKBS0@gm2@Z7GwSluDLhaPaQ*4FZnX1#5e$v0cqoaj2s21YE; z7rNrWqO%Z5-sUPUz6c&S)Xnb8vXz~Sq_QI-(y#VLFn;ZFA+^+s@lkzE{N5I#-|%Ip zmaz}ODBkpuH5|VKL{sB!>Dr9`FSwvl?pGBcG@5h^SgqQ)Dg*7-c@wMCgoGQ@^bsdz zY2Q()fXCdlmpE%nQnq8qw`$T56Nif<9x%7Nu{WKd#bVXG+U+0rzdSLMwv7mI0jWgkCp@ zm(ung9AxYiaEkL?jmniYgFGc7U@wsE)KQBS*Mndgh`}$~##Y`8rPgdhYi}8_>9c_WTjM8h@?;H`GMvy@OO|H3y*d zmVTebaD+k zdr*t=%I&lfko_U_)<1PXsT5OoKT$N6JWQmO8Eu^1c3N|D_wD81zaty&q~}^uU0tvf z`|N{LDg8fx8}q)2F|Bp){vL?4+9cFL2!?5d|H}_xE|Op(NyaQ_rnS%aj&Xa+jyvv* z^cYf@kdUIDWx1MTBRKLiZ+ku`eJC>;yL^`kOrhGR9;bJD!w6Piofr%B(#970R zMm$4jA|FI2{~RlIDwBa>lpEutx}$sWM~xL0Q)LX_>DaI@6{E7-qo2(*;e0yt{?f7+ zQcVE1l%3|6p&aDWK;h~xun%PJ#eDN-wP>R`bztrR?>9!sL|6uA10B)gO&jidNNejS zmo^Rle?djJ`_L-Rt7VY)sWhzS({USdUANt1RT@tYD4wj7 z1dZz&BndViVfUR-JVnY-G5ktOtPl|&zCCmO49IsitJS6|Iz72! zsEKE5h88$sD=-&xuqrt8}C`lh)z1wPm0Z6Ted`0O2+E8S?U~DsEFN;vuhn4 zZ{T2`DjL&k1Omm~Kvh$rddmni8vPI$Qk`yqCW`dF(8@#`&lnlJrh21?O7x_!YuJ=) zMF?nLQ;!qXO7p)t0GmlHoKEn1Hdjd-6kfVv8- z2t2O1r*3zO<@ZrUX>oxb2Qfo^(!XTzc-p2jafdt{}P;~SwHod>4V{C!wCJC ztiUbEC^Z{Ca=YT%A7NYHX0)Ri7+UB@@9f4&N4<1WOAhPB_C zFxd{7s6GIog!2>v@!@_`wQ{zqu;Uw(WO<$>sx&!l#ZN$wh`GXHqvqJ$D;Sn#a^nTG z{>d+7^kza>d5cuS1VYH!rz^#kTZ&9E99eV(4L_8E1}#WK zi*mHkW$KLKlPm1{UWtt8euG!4hsaURw&7J@2HN#Y_nD3gPU_*%&nSFBdnO1yyK%OT zpEx@G(zc#A=x1vjKS>~_j*Lt+2uiEe(kRb%*q$eyZ3i%upQSul1R00rF@_blC=vu5 z7>ONiv?1#RVPzyK_Od%36FC9`79$viGCmv?1)Zm$pjnWLV7tNx|4} z!7wt@={Xvn_&bi=C)^H9!D$e!e2PPt1bfjV>0?A<=qWdl*Y{~{PoX7uRD$lN*09^{ z!fG(qi_q>&Xz}(E5tA8+dt>oB6q+%`Y~!f^jL3g19{6ZoBX#Y}UvjV~e=UquzFd~i z6JFqvfyroKc)YCaD@W0L<9J4cKL1rMM2jzm7uTLY<@1^M&Lx6*)CUvXV0@mRa5zIT z67hrtsp(i5*`DHhZbbO4X^+)yj zw?;2cH?WqmN0;|%Sb`{joOJrR&Wj6(cDlHu^dS-bX3m;gz<=7(eZ|I34l9b3C zPK(`_PsRS_r#Ofd*}J*jSfkGQJ4Ka|s#ym4`Kq`x5xCZ$EjMI_9f$lWmQGo`E76C%hOAQ}&Mt)Tt+f;U7f z9l&ha*kWR}b>Ptx6O9+luGSo6+{2j&Q9C@D9>Td@S9f<=Jz>PuO$y8&72gyhgXin4uPeGK~@$s6fHP(gTGVG$3s?2G^7bO z(*|PrS|z<34?N#ki5LZttXZZyFTV-LROMw8`gaf%7Q;-k)1=5GMvBw=<8$m{Z=8y z1koRz_2k&mctflR;LT#&<*>I!`_Km%wrCJZ0YhJ!h=PvZ!wSh{tvq~}N|^iMd8cX% ze~bZV^>WOKq~Lussk%?Ox;KpMB9--`20+r)`Bw6|S7vW{X6v@(6k6FT2A15o7q8N) z3eL({*_+t!O|w2T z-bX}P7O~Q)_%1r@%(vVpg_*ZcxUeDc0aw;!kLOFUq#x>=B_Rg&tsshA#PkBw49Hbu zFqokCm;j*x9{d@V3g-P?c4U=g;CrW@A1V-~<`8^DWk;ogPV{sB9HGz)k&+u{!{S8z zj3f`YK$f!c zUwxHl?vF%oYqigQ=GQ+aT3?4;4XO1A9(G%hl|GY-Rl0O2AH zMQxhl=N zs!G~$;Xv4CA1>*8pcO%*!DW1YTJs7@rKr)9>KERhS!oq~4Oc^Aba{P%=wFsCgib7l;OO+* z2YVQFeh|!woIK#!!QBkHB-WKvuNC8a-iE@IA(H%qm?$8R%pj5$%@%di;VX|M=%^L+ z8#T!H#BgbSI;`#QU`yuS>ge#T9h>X3x5O>U+E!P-Ro)2KE9V{0!m8_S>oWrB9nE-IiHOFXYT)FtxArLZb$++Yd@wyOsFTe3J8|IPG3$<+ zym|$FW&4P&Cx-+~2|F*Sc%-gdJ5-52__Se#O4-m#nLnyUCKh#>ljb3*xYQW854hTQ zh|CMt@A37CE!B=A=G4A>@BC;xLBy}7`njlU5dGJ1L4R5O1k07iHR3nT=;C|Sg1%!4 zao=m(k2*fb)fLwD1GCN3$J80OHQJk}u(r!Q-mTmTTY7Y#$iws#Ul;ndK% zTNXShp0{MHDCPdNHMjiJ4ti3j`3Cc!mn)OpRc|BXAw*+yn&b_`r1|L!PbL|k2>rXF ztrp89KevyVvGij7HW}xw%@$U+b|S)B^gUx86B21p!3}Zjp=FHR}u1 zzgnc%Q&ucC#_?f6=lFu5&c>G(35->omS(kZLD3;d%i!7`^!enEVkGl<6U)TVc%%IA zEug`2NEzs$ptoPpd{_kW1RQ{m3FT-yMM$qyP31bor z>v(tK+TRnG)=2WCnHWqm#~fLZYNaw6nQd$>W7nf9`@G}J$#GMC4;LG3t=fNmWnO+P zst5IMkfJv3bT|%zLyuLbnb{!s24id<2j84D42cG|0jaqZ$?<;qo7m`T%ipO;1A)aF~WhS%9U+{SWh@F9?!| zH~ChCs`uOxNi{+5^r>z;Mj(ep`GYH}ueU1V22~6!^>hxGOyyBm+9(iTrx63 zLY+&N1L_K?Mv7j-86121_mQpM!Y`c*XxKJ3e>H-Le@*$Ry}=ldu_nWe8#8UtA$5Z} z#Nhu?yOvJ~-s-_Nd|O%Z$Rh4qhDlXl`!P>2p{t_tJ&+**wzi=F;KodiMkCBGJNs)G zxMS#^?AcuvH*b_@W*w|q2?pwfc^6wRMl0WY@rF`1LB8dl%#aw|azi4$2 zwQYRSSnE5898tOcE7+}Jy}ky$u!X%Wvlx>$IrP2CXNnmWGBC0G$tUkubE8nrDa*1R zguQk@V`}L}3bBk&YjZxEI5>4L)FzieLN*jXViu&`I%b~*Pn@TU?Qz7Q`_9MdqoF3r z#NQ=CvYfo@uOZ6>mGqcjbb@inVS}|MM#6oHG8OUfXHLCv{E7@7*h63M{)EKNEBsJW z><*S{|8;ZPV$*(p`tTxWczoZ&!`c6Ms#t%mRnwfVY3;JgH#_0g-XYra$lwqK|Df)Y&E3?& zk?2VfD8$h*eZV((>MG3@Z~3Ydfkk3z5dlz5#3@yJ6$r!wVgX1aISGFGaKJ{#TAPjy zXa0I~w%rS9he3x8l~a31q%K&8kWAGe^xg{w9hb~6h>RZ`wTF208e4V<=bv3U#bQYtypn{$$^f-yVsz8ThLgv{e zefmme>?8c|+k;n$I-ai6sjb|CoO|Ap_d7vt1?s}sj80s@f@_6dBN8j}y$}GiG;?tQ z>(0za0>MD-X={wlfui%6%=yGPfGFx!_y%O6VEcq6m8w%R*wx1P5L)|acSPu2*>N;X zm6?=zs1fu2x_`#t?9l+P&Vd)JrzI3BiMVf>o{w5}KbT(RJw>;r07BNwQ$f83^N+|w z0co%ZP`vh>-~m2hUM;t-#?J^*rxus)*o8;zfH1QIxJYwj1Sd(=VK6_<$&51!g-2`< zk%)~SJaGo#L=JvUWUSNH)zDFgJQ=;_Ypp(SMl-61F(~_*ELb7@Ym#K}Tf=A^-8dLX zXP3YRBUcLpVw@j}@m)@=3Pz^0TI|8*DrDGFsM#79$+hvO$#PPuZy~xzH&_U~e)>_!6Q=*hRT^&N4)Ar|lK2nc}8+!W?yPoL-4~zu7 zEWcTuE%O*3TFERefq%dK*V=%1b6ByqZDX-xpP>hp&WBR!siq#a(2U}F8R#uOFd5$e zMp}^SgjiTde4Dic-xIb-b7m~>e-4xXy<#1sUIzMsXRjs-gdQ;{bgXcrIv3W%utbo@ z%K*VNNvPoZkMsCt@djhRw%W78BGYDwHm0k976Zn2)%a>3g2EjHe49cn8vahi#(&-scZ z#tJKvn*bz)QVXqF6$UM_(B16>)q8M5qP)XJ*LROR2`UgcNG#OxvXksfDiU@AFjw}L zudpzDqnkHZStJJWSSBrZx1N7}zC7sWp7xVhpZ2=CiRa;j-W(U%o$KxIROl{cFU_6W z0T7`V&)PLo#+gpW`P(3PC6Cqn_C$e6_~?fMVO;$|AFQ%qOzA-~Zd^7ou!cccp7H-A zo&^Pz{Izy|;gUj(7hOv8uuu6jZ0Ns54gyY$pgBBjd#N1s>SmWx?)FU32=!lKQhI~J z)hu`oPU4EvoXU?Bp;(@>zJ+#0Dda&|CZSTJ=oIzRE&QOG`K8LkE{d)YOHClpaQ2#@ zs#k)@1LAkJiDgnXG>i}Oym$|zP|!W+cG^Ks9%QNLJ&LZ{AoZFApV{`aeK+K=2}rMT z7KJ7Z0uLNFr~qQKqE4mi96(+@EqT)aX3+N4!zCm?Ka}g(jTKcR%y#A^bq3stdoW+q{S~0q^=!9p74Ui$>OJ8BW>Ff5~EMY(N4Xc0#FvmID7pEe8^5$?gK!@RO zWDr8xv2Zg=+F?u79R96QcT68Z^5;eVlWUCmW1thlJeIB*n<&Qrm&ZNGy@)^1iIgg9 zWxwFx6Dj_ggFu&Wo$LS9*kq^ekq}Y8yqF@S9kb%>%S%5lmGYS9!_lg zpDHvf?e^8v%PzewL`P2aV$}cWzVod~H_4GHkr*cG7`Sp|?gKasEmZEz$=IpN1V5mD z2~h4^;MK(Nwd^|MQHChq~+HKc-L#Ey`nU%2P5)MHsR)WN9H} z$-Ye`%g|($5fhRuV<%*Z6fu}&5QDNzwrmg4SR=-svTyU=nV$FazVqLmyPbQ^_ndow z_nvbv0mNwWF3O!hPZeu+)mwKBNxcR3`T?%l2bGDRK9#m`q#3*z;W-pI*Lg7Wai=_g zoApbBoBbh6Ukg^A@)P{ z97mr^1R)e&fNLFSWnjs=T0v08tH(JE)BS9Dp=S27@}7X88E~@m;pp)5D!eyc!Z<`9 z%<(MSL9SpeMiPOEV#POs1E`|-<~-mAQxcqmx?j=Cisv!$CbHrHj?zPGPS7}|%j=_??y_e7j^98I62F{YZcN0OhLB6&3`d}=}v8=DJ z{F-ed0FWXp)(Sr5{>8J6X6Z64 zO6bb$&&zfCEZy+k zR(>TA5+fC#dJUN%Fz~7Dr?1S|9q+uRTC5pZL1yj&00p4a0ZYy0BCD6}rZpUA0J#3< z&{0T1-?Mm~6*AzWx}^k)I^6DNKF*JGaNQi|E7awI*IBS;g-CiMK@-4`s)gc%`{=k= z)%3-_fjp!Ifq4?hMH))TEGVqZ^Efz)W5Y2UZH%mB{ z(i(#}s8DGG#|5_XAc0g%qF^e43Rp+FIzJpI!lt40pQj>dS~U22q`K$9z|;lT!je$L zW9BVM#}Fu@8rn1eg$oa|A3v9PnGde;k@1x9$aULyMNo*n?)#JHq#Xj9lP4y!GMxwpvUP$hWFUNrpfs_5`0qEyayxrUf!} zSbQ*l*+pPGGfK8!7>?q~M7?igOT*lz-f%B6!OT#Z_- z*M@)~fq|D6=#HVG>IRvSZ%a~T;P|2QC&g!LaiGGItOduN2XPAaFc4>cUG4XS*>zx& zG=Wu>vKe*qob>Of-Il%QyL_~K)$i7*rf(tBymkTDsbR2~aCG1O$VYU#!oSiwJ(N9t z8$<(O;*#{GfvK|U+D)APiaCRn0V133cJAtUUfSON;C+=Ww}ya06Gaf-bKSPw@YJEk z)+@(c!K{pXCv%CXqf?uc_;}mz`$BK<#MM3UZ+no*=fz3<%2Rl3O_LkqoZF?4&vviV ztFCepR^H69A*iYWAXt|SzN>f_R~(a%2f|>$$0ClP8FH;tdMt-uSzg}Zqwnl!_n>Gq zc+=A44N2FZ4?f&pwZ#&RRwNKGPe+12j4#^`_+@Bt^1&%Jcj4Sx7ikD`$7{MN!Qwn^ z;ojqY)t&N;oD0i;1;j?~Bff~s(40ZC8<=M|K*7O?3(t1>`Hmdj2{7COq-$ zU;d{tsQa!ZEa3KNe>T;t0o(3*!J@AZXOw?QzNk~|hUiS!oI!8pUX|(pEclB}7(dwf z;31!GhVil1F`mVfZY;8H1OJrwRJTiV{KJ!zCL36JI)(EyMUadD2J~NjuKUos*tP3>?l)TDG?_>to#Iype?@0#E}r`XHMX)wS-m7on*w`r9)kc& zje(D4KQHv~Gpi}3BzX}8VhdRZywcpIvV}x2Hc3(d+jw@hB3wX(^e&|!hWMkLDduXrw|7$TfaECTO)zGZ&16Dpp;Dorg)jUqX0pl|>!oBu6R-#}_C8c@cgza{* zm{qhu=7B%TxcXLtiCPebPK31vHoF8)K&v)PvPq=9t)CdQwQREJU0phuy_@{{P1>qd z(tTk9SZk`!{k#jN!~7p+YFkO)Hkfn#+a8*<7@(GQ!To8KffJ@mK8rly@Da6`jH8hL zF}n}M-}zRZ`_vM{W4_#0TBR<5RXT_v(>)th6O2#xq}% zrBY{_%dZ$(f3$q<6C0vhh^6XMv}LG3rpxC;f^b}Vgu5lj=lT^n5eZHUjBRd=+bIXC zxXQ{A9UXqy&u?_~@rJRw|JJ1MQv4uuiKWJ`V}LdcH2VK?t~_?ThgUhczhbc>)@fBk(uQZ zJ7WK|SD3~Z{)++Q=kUNfyfBk(VqyS(Q&<|qI9a{+#P&@!X3|Lum=0X^-AE#?mS|9h z)E?-Q*{cF=GneNk%-;SAhpi^sNZDPR*oHXB!ty7dnOwGT;60KX*4bWn%`Cad!})vW z_O7i1y-`JoJ^SUIKfq7!a&!0=dN%raf`Y>NfQ}vux(&6IqOtRRSaZ4e__p|X3sUa3 zTKZnOQR?l%vgayoD;MT}`z>{+7dS5QB1X7sJWk5>_nJ2ZK&IIBmOdgOi!m_Bh&n&z?ql zwsFtpdzEA(vuaJuo*R;n@_^+85n$T%%l10&HtjmyYl%HekzF6Q$we?oI}YTA6JSyY z?RCx_e!!z5MPL1DHdL@fqxg9_$Bi$%e0DM}PsGB!REo2BRANdZ(*<$7i4u>PPxWH_ z{g-e0Ej3_VZ1zHVXR$D$yUI$0lDO`^Xvs*cjnSBNS!I=&@-?x%Ct`VCI7v=^NNC5W zy%~o%`7%VpYKcyBj6Nq)(XmEV{Q4oBB=)gRXWz((kOh>J;C51jbO>WuesAe6c;Mjr zXehzH#G;qn3$AQ%7;tsGd6i)(LpOqgb&}{tK_VKnX-J%W%nh75q|{7 z6+CUvQvX&h#oSD+&Uttq%GWOAkS7vgjMAesWhGl5`;+_2r`m8LxPw9BO9$K`Uj7lT zc3nW*Wp5E&{)$!tjv6c;_VoE~Rnz1BkdQc_oV-I+!}`N6m6$Iz$8yyd1s=5Q`?ua5 zPCh$<`=G6+nP0j=;sbY?nVS{rn`-mSt=eR>9W|G~sTbQ;toj(7II&xi@K|yf;%c4M zY#Z-UTs}Uj_EUFi=vz#Wc2b74t6s<5dUUp;oYYz-5ge zj^ps%QR(&sV$8F60y$z_Fc)AFs+Nh`$@v8Ay*iiF?;9#AdtxQTQ+ zgNpprV8HBHsC-oBeC}{ai+TZ4XrKF;oF=J$yv#ob>Xiet6Fo+2wjYVLJrSv?0Tr(q zj`t+Is&Kr!2OTUvZRmC8Xul9Idf>5a)^me{i@XI?#ak};c`?OXck%O*NtJ4;lFrsl zCB1WU6^qRJ2QFLwSzrj)1wcazy1y^Pl(%QK&;N8h?|mTr!h5WD)y8URtfYkR>Q^hD zjXBE~u^-FngPzow-AnZc=N2<(j#67bRY+wv8yy_wJv72~Mt+BAO-`=LqWPDZ9MPe zd5wPAys=5GU%v0_^h#}B$|1F`NLxI{50Cz9XcBO${idh~@E;ssOe#KKz?0z@X5d~< zUU^nf=(+g~f5j%{!&>1QZHrg6$A#qK^lN?5*HERxOJ`f2yqpl_H={C7vtHKvsP7+V z`1u6&@Ncx>^z2Ugz-d}B<_psr>G|tM+gAWg%}F2_q%Q*mXcD8GwU-Z9=d4s_X zE?^{Z$-FjaI2(r#{?bF%SEADFixy(PRCDOK>rdp8^Yogg>jry&3qp6V2MI;0E|b`d4#TN!3{8n z4)=OLO7-_^r_VEgv}NZzQX5WJSxs(`Xj?Smaktc7bbC1mFLfeP{j2BIIHV}#J-__& z_Jl+!2AkyXwh_1|^2!Y7WP`;=-Hm=RjRTg9hT_jtqn6^k5it33Wo8%GX} zFV1Bjwtenz)sPUU1#~s&VivR{5@a_vnNo~Ar{aBTCLS-|oP;->6SrTD^O{i2WzJP( zrW$r{Q>iWUGn8y7!eegp36Z}^N8C@TO;kmC7|OYhCo51|{D&%AT%Ii3N!}DD@}g+E zCds|Zg;CtQjg9vNW;AaW6kuU@4xY$`!qb-R#-7cRE|lOkW5$}6@V|>)Y^PWI{N}vO zYGC;VTh|HiR7hU#P{ciUPpu242wCcCK+7xf4)wRi|}k$^6CPvb80FVfP|=9=-KZnP&DLnUruX>DSZWXdO@ zEHw;zRGXSO(h=YR6FRAH!~qee7V%McE|zhGO9J-DcLCr`+i*e%2JKIwo9sf{Q!9Ux z&LDZGz;6(~!_LiwcfSm)mkCKh2$HfD4Ak25X)oc_i&sXx!ZP|sa<>k91llV!w}_q_c|e`9m1g<6Q10{Q)r9?qc^J z+D@P1Q`&DW3PDl-$gw+Mbb==`5(ZvphQTuYjE#-GWI61dy3exn%C6KGbtLumt$htW zV8S;uWH#Ca=^8n!$k*iLxv*K*9{ArusnyUdNup}^uY)&>pa?~Zy-S0F>+Azk)5Xl4 zBU~E0OsBpVne2oJuZ8JF=Tj8*(Z3sVT~ofLy;}cMKrdnXyDqQjPADTu0b}(XyV!)N z{?eTXE`iZ~U-YuXjh0waDW_4Z3IIjBp6%q$wC}EshqN1i)6$zC-GnvbyERnE~a;j&Xi(fyItLa6d2`2YE7J_rhK z%-|Mz_GK@@g7F;!7k;REJ=i9L^da-NStG2k7SP=Gmeo_R*38ovSlCPM3fL6hm4ewS$3jqGO|Zm zm65&jeNOuPzTba-Uj4%>=Xt-M=f1D&y080w#Odp4&_G$B5D0`u6QzcRKu8e~2r=Us za`2OLH+w1}5H5(OnzE69=FiFHB%a-1-aWpahjPXI0>yPj#llQO+(?7&sxLUZ%5U*f z8f%h zwSxUB>gtN#6~E)J`2BFcS{NtBpVaY6j$2GzESnCiZ_M$inFr}Bw=a*M-p`t5VBM8A zKrr^NG^emXE>5jFJkGQB!2QC4QIY*%zxzR{qTyiA;ndpbuNP!s83qR3ml0ttXTDkQ zs}Mo3nlC*A?1iwm^~$eW>=IKV`LmBJMfBYH-yeML^bZK0JPZbJujs!S!`?~>so7e! z|GD~$$m8VsO_|WkTbr4_^9MTJ<{~H4YJa~{uCMOoyj~7w|2g(6Lp4hWwjTw1)9~BN z3LceuOL?RE1o6u7A)acncQ#{sFTg@($b#N`zg^T+S&>dr2eUG0AH_t$Y>`zqT=AaemOGZDQlY?y1{Q)WSktocR5 zjyIf__vlWR>By&;o28OwCL2TddN=0gY;)RIzbrIgfvNp6+U__BItMmgJ<)4pu5AR; zRPGAv%&X!};6i?}ivI~r7zfM;mG$x8z1xGZRme9~5; zcql)*X!+pWb@uzze9s>QuU=YmZ)Dh6){7+U zB+)iaV$P!zV;nm^cg#n#3%T3jnp%UwEstKb1z7m$NN8()->E`?9l{|t8y+mb{ggYc zoSyLG+MS_1I^l|BoJNR%8inifdMiI>CTc%j7Pk2x6&-N>QCTi}Bm!{Dwx@?}YoS%O4k^d=| zkGZtg-~T?SdpVU(yXa~OOTzMT?~A8H_i{s+(KVLA-|eT<5=B}mxhB#g&6rH=wO-!K z%~Vw;{F21vH#8@!EV*Q{H-ZHO=lP!Oj5sWAYM`H4FY@caY>Y9inRWZlXK;3eufdYS zwu?`?4-^Wgbvcwa*)V4An+47^$cCT|Z9`5pNCLNSLhK z*fV)uM%bj(eQKOS46${FMy@uerQ3lEVZ}X_4OM)@E}uMS>*v=w2bI$_^IOET)ha%Z z!8435FuX72H>`1c{5OMk5ZOViUq=Q$@fZyWWru8iD_c7!Y1|f)y~*#=`Eld+DzxP^ z=3=gnBfY%mFAt~PppUO*MeAkBQZ9Z>+VGfHxcftR%ZFN^n%rqy@Qc7S-KNo@*X+@i zqlL!(8zK)|sXnnvyUz*#>Gb>PZ}Pgk#8vLF%Zxdis8z%|UDCzPHRff>sR1S31CsGFsL^!M|jg%N7+x1^`)}VA+=m(a(iM&bLr1g zNxmiUHtEKVZB#TYM2P)lR`Iym)I#>igAj0RY0ELL9H-}7Sn`0I;kr+d7dWHv1y_!G z|DJM>*DKSZ3MDM6nEl#XR1|ER5m#~wGYY@Gml+Ai_1-4^&$yh7V9MVIIOu@%)qJ|h zK({vjDR(&G&*5FNllBmf?8{HAO-&pZMdMf^G7BPM+i8g(J!}WeWsgd`FB0O#=kBI8 z<6lhf-!f3xpQw04)P(kBfLMQJ^4A<`#WYH6mCAKpDwH-@QT{vi@0o7JuD z)nfPM*a7th{!W>DD?AV`@h8pip1gUu{}3nqs`ra~1_i`zGbjCy87&Ev5cvEJ-zk;d zenXy(pJy4DdtM=U)c7vxkvQF9*CM2g#GkzBj;{B@g2BYsx){#-ljpmKM-yy>WJkC+ z(9Yj+-wnzX8I!-9sW>t`;5on09p?_P%O<^<%Gs3nU#K`loY#N+S%ZQo!tJ-?P3dQv zFNq-0_OnMJ9J@p=M2;?O=_K?NrQ|b!V(LZdVCS0=&51Jd_>Ks94{Sc*E-c zg|d-G$to=FUewa+lqJuCuFv09Za2gTeP)lbKTF8`{;hR$IXlhYEhL>)20!~g8;I+g z`ks&o{_sXXs=IH$H2M(DGaG4d%MnJLQ|6{hrhm0Y@pgKR0?{UddfSZo;GmhzaAWB_ zwX)%4^po0%M!v66WP;zzYc`&QQiEiCb<U=hvLo_dMB{0j%RygS0-f(0Ra9LM~L)O7~y!&H*# zmvVF*$%&3H^X(J97LqtdcT~^_of^>)L8FJ+8k87)~n!K-P%gaPZ0#+n~j2B@d zU6uXV@O>QUFEI`)i4n=Jvwvb$p~ec)Z#T$L81fe~VS-%6EIgVquKRT7XjF6tA8F

((%ZrwfGx>S zIIj<>cl}+;9+(qGtTb5H|Iw9W*N$w%oYAbtMvYC$-t)p$f%Zq^!9Obl91}?llS@ky z^LO7*4G@_rbr54oxkyx)u(vg(@qmGlD@0^rk75WI6uPc4{rvOFgHrRe4rZpQNEMk^ zIIg=*r)%mODwSc=BLX}&tV&D_#K$QHk(hxh-nTarz}lQHf$e2>7g&p;T}m*wJz8U< zycjb0uHRl9Wv7h z%A=5G=^O|-=i{%V3y-vT>ZRzKXpnZADqUiaWNX~}eM>!E$mlBKQA^~uAXgz=BSkeK z9xpf~8q;VyJXE1=C3t#@6Dl*M;ki=nW~;v8E|xSVri@i8e!Ry*l5*%_LjK{35PQNV zZ+;m-rg6Ck=S>*NK(^9eNwiiXFt%YHGH2;tibffl1Caxft-cRgmBXlyt9e!m7fE z&+y_s=8!;8{Z_#c()s$EH-SlOtG{Lkl0qJ8uUXPAy|F6?%0x!*HM@qd4H3lJocFb5 zqv)3C*9B#t*wbjuNP}Xgr0zQw$*!|uK1wAG^FtvuFWRxCLf_aZSRhx@uOXK&b1^=P zZvUz-xI&(p6%*c*yOfuw$`*Nc+k=>bktz8R1jdMaf4-yk%RU)Q$phZjw%9YDEuZ21 zOxnPG`DrDUkBI@PaEewycA;SBi>mu)G@_Y`se^-X2%En2gFexGizPW~0ujFnFvGMH#uTd2rz)4jGBAWJElE#<_CS+_)%fq}FXsu4R6bZ)y!} z);uV9V(b416(m(B%I!#NRj)ICcNl*k*LbixP3t$nFk~t;u$SI9bGbh7!n;5>M`=ar z7{Chb8<;7Xmd5R_vPz}I>wnpIzF*3z9DT1bO2YQqc*+kSUCtFqGkZ1O}o;o@$(M0+DI4>lDj2)Bo%nWq8T8$XN6xKsRKsiU@r8Btm=BJo*)`?;~f#qX)tqkKS`o?+btk;#(A*K5sfvdt9fqPav)9o88 zx@!%$T**#6S2t^f?Q<;mL%0^%jR~Tdc~hQLkhYVD_!Q3%-jc!U-F`DW=<|BW2%b|K zFYT&xHCAt_!j1}arFAzCNC@NgJ(~YY# zj2#hvE-asTe^wP^Nel%UkB;Mc8?ks01#5I!ojt$vhbX#Yt$y{|-2Ee)v160*&n3#{ z@>d7pWHI*9xgd3{1vIVzZFHI{Syf>;)64KI9Tj6^5TSAbzejhY2-4<<+{Iah22JOy zcYFe-CB~1+*q?q?_w!h2zReFgobj9V)YsxE^9Z6T%HJnvjBr_YbX%4wD92i~QZ9;o z!;;}26B!gjQfDteroOe?g3JBM^qXB36MDGid6XG!npa+2GV^Qe&PH_qL~;xEficXc zCg7O7VQ-EM5(X5~k1TCf&J<&qT9}|VBK5dYji7umxT*`Vl0>1)`%|2QF&V1;ouxWW zuG@QW3aQo>lR%N`Rio-_!t z_cRMacNO~k2H-r4Twjz7n`S#`Jtjg)G@iOmA2NUcJj=KBJ>IGX2-JIW?250R6;%5i z(RGK?+kHRU;(NK;Rn!K!Z4y}$c* zBRHTCS88{moCkiRu%+X2OEjw%#H|HKG>SYT=C2$S*%}`;Hu`XmQn2Ke%E%%-V=>Wf z8B6ZGT)?^LvDx0dK||JOjJi%f{V-XJC-8Mn!Fa$Hz2?Q$%3fxgH|{RWOAf;V$Q4%( z2q-VGBK(GRC2aPLWZh5`LLt~Mu|b2ln@_23@;?6dt&!3U_diu=1K4ye!|~|2umnx# zPlGM|LmmFf5oaUgs3HXFQi|^G z$xJurT%-FF1B=iXFXy|wP=sPUN^)8?8PdXe_9jn!%YNOjex3b+PvMrb zoFyp_SDJoVDO=1dO$0#4YM%}bmt`z1$(at^ep$d_3|jGdV7B=A2&31^{5vNx9Z&Oj z+4VEcuEvpN4@Y+0B!6;paL+NV6+3t4uOfQDX)F%UJ)UNm?dY>Dp|MdL{HKUgUW+3* zxy-$^+XrZz$pDt+fV7Ejh^rK*U&K!Q5?G7H{qS6ImuB+|RpM)8O|ku3F< zjZnLGl^Tw3Ejr^D^1((j(n8%J+n|4Rz*8hc#glgI+Ds+p%%|{+S5`eQQG|sZPl(2T zw`=#NQQ?2|A-yt1R|vj+fivvtb%IAD3raAJmB7$}P0u^`c-vA1IQ#{hC2+;g}hsRfcHXqGR2F2~WKVNy7c>ejJM*KH z*Mq5`>%1suuks^d+r_LMPi@^k z`Kh?R5hZ+b&SyTHRRaX+K%FP(jKQtm65>5^4g~-rab0{%| zK|h2Zm|U-|Kh`=_|W>S4`Oe}UwI`c6xg^(MRv3Hz%aTlp}Dh{+oML2ZH+_{(8ckeEDoQLjB zS)7dC$mm{Zb&ZAv18ec)d8_x3Cf9`ffK6{J{tJHE#0 z8#4~wW&D2kQfU~juv_)|+)Jy5l}aBjO1we{(I+~^S=!fvP$MC#_%>K61?rvHw{ow( z0UOnhvpmMF3&*ZMZxm-)$l?#62L8=zgYPK|^YU^3w~U}m%6eRy_%`$&2}a@ zk=Lg#ECpXcZ}B}$r>waA5Xdc3YE>J+S+LWy*FAtDj>sLDFl|b}Eoy2tr1SLJm!a+q zv$;?ZgnO7}m_)>A>VG28CtVSCk?S*Y3saL+jtfa#y^NjV4!MmAaZ#$+svM#fZ6sq- zSevKn_5N;b04oJcmCqMx&%G)i)N!?skGB!ZbMM+cpG@f#Lex?S z5ecsLd03Q}%lb%)E7ci`;njQdYId_XdspGMbxm5L8#8(<+88!_=D?d#g^Pm%?2v=V z=?;nMEA>l>h^Mw>9qt~4cuzCp+KI}zJm%!9G2Bj{Yg`}0b*l4J<>>ofFX>}2BULt6 zr3Rcx-t7m=`J-jn0tz82Ps4~&pJXz%W<9jq9|2+B#61dD{D6jLTbZ?czkI$E9Yx&y z*2f1BwIhM3hkNgh@^AW*6lgWC#hUJ((0@Pf|SkFk9v)8Jiq7%7k6j>Qm^0U-{i!q_2b`KK#zVs_6fa z;@$l>_N^tc9$YXA-(}IrIVJNBHn~*@MG|G36M+_sgfkySpM$KE*rY@!#Zc(p;2Yo+e*}O!#$iATl?dkw8WeR-K~~4$%N`>y}mIF^fzQSzC3CN zRXVEp&I?fNjJ~|;1&W>ap&!!k`7u9RTKa~Nt5S3q5_9)W43v^Vh#Iz*vwhJCoOns_ z3}CS@h%pCEI_f4^tvsy6+-T5ft=xE`8RGaFM^6RqIveec*pFdRomSx?ia*Fn)rqvr z%jy<)9=(LJth$;~C==7FP}Iyua?=(e328kp#nV4A02j2rMAcrz77e@YvJ9ET z{D5zL5#sl=-G6-QK~SjAtlA`i##cgb{DpX5>SaaR53esJDE_>HFZFUZynqJgvp>s? z+RMPl3poDR)LvA5zkomJMxxePU?k_0|BE73GFa0rcyRB!4p-3QFY*Y#$1D>&H zCp!yS+5HFQ53d)}2(jytJ^3Yc)AKo`4*E#@;U#=ct>+WCI>js88IAcx{?6Zh*~LX2 zeLj081|Fuoy6663W^@Ca@MDbs`*%N%Lw36A);1p(LAM|J%D8jSSNYh599;lrh3uy zW~WO(CZG86@3H=na=UUk70k^Taa{YyA&~TYp!@N~-%+g|-#X7X5?WpG{liAG?G2Ob z?FDk1+(lN0lcjo|g1~3^O6ZQdJ-j1!i||dxhNz;n^wvYVK`-G^*&bYhC)26Pj=xa% zfY`%A-iyktpa^3sI9!HNIkchfxgjJ|tmmz*QQ{d@F#no9xZs6;#YWt1w+s!P6oaB? z2vZZFND`8eG#0X$OER^jGoxYldTQG3yT527M9efrJz2&XKz)?SRcr`KB@90y9upY< zDh*v?N(3awVHlfb1%cqteo7<}zkNVyhY{we@_9@e`Q2@~$(88W9nlW;HY%1mOr%ar z{ZnaIR*O_~u%uQ!24~~3pzKIwqn!CH!bmcl;du6SWgZD+s!VDEfE6zSUtlG(0tlr7 z4qUSq2Jq5wQrkMH8B;?AA`*Kg{sDK=X%(K*M2yj@B#0+d!Dv&#g{vZiz(P419&94E zzM~VH4B-#+=i!=6eK9!?4DNoAKnJubnNX@%TI0pPUDXA zn_ml?;cQ)=Y!fwp=X>RYnIP}O)2~B!;hLfd^Kzt|{__r3A@*(y*@<Z!B(5nKXPSU$3-dmG+r!y}b91wgiH&u-|7v1GZzh8X2u8Io9WE~?N=Fh zLKAlLeVnD59KN8Wk$xZhz?Eb6O06&3S2DjPH~MVX?zarmq%H#eJ5N3A9Lv@h`{<*> zPlNm1_qn$CH$+OjSsb!>eHa;Nh5h_>{{0I~0*QF{STLeYUFp}{eEBZWAU+q(Xg}DV#pZ?cBah5wS4WdJuJ1%NBn_odLXl}+W;YMtt#ujw z6-TuJ$Jb_rBvOmW)Du;cAMa3HqQtbs%V9YFLFMC3#a-_=%g?Unh{a-Y4$n$mik%8< z=bLokI*7Qo(|F*qqx63EuK!}8V~x`S#ogtlj<;}Q!PxH-c+AkqLBF05yJ~mFQd?vs zp{NnYV@-NnK9_9!u-*B?yj4AYX46QujUTfP8bX$gZRpGK#Ut+2!8&lZ0EsN2OL zUQo9G;w5BF`NB9IZR4zBSpeIzn%4|T&&!G7XwcL0*qw^@JNYX90|I$hM^gNDvTtBk z36(f90B0GKiu?vio+qPMysV%+6Ufi2DNdU+XVZ>93! zmC)js-(Ud9ouGV#eUl#kWexaT32$4fIAXy?j~{MqC%DG{A3YMiI`HmEefHww0zr=~ z{y7#}TYNb(LUJWv=(9&;DCEbeIoI0X*1cMUfytj=jiEw~_vr#$IScWuI>1guls~Yo z{c=LYNEY`r{Md^!gRVNmTzK);iAjF2GPh#@5G@vGVBdT9@B z4GoG^SkKta5iJaOe1$j9nQsAwe!B>NI)AY%RsBT(>2~y;bN8m^><7cr-g?+qEhwR? zyiG+zKXGTg5c8l_42dySCOq7rn%QCAw12myY}_!G+l@Iq5|&WH(VkQ?1FA^~#CL<} z+Xp%P(=pKGaMx~sUSOlE&Ba?B`-wlf{2>jD!g+b=<69!LmC;p$Y-t1OasX7^9B8$B z#|QxG=RV#Mm{E*>AfSQ7*qNymvi-!k5Q=P1gW-^6X-kr@QWZ=>jD;m58N}V17jni% zxu=WMZ4OI25{dJivF}WyWtB=Sb`$vYo~@mtCl{iC@demuN7=!=nwCUjW!x*_y4-P< z@hIWm)lnh#2#g2H=KC=Bsa$C}a4`e=Kk_uqsDyJMEmX)I=>6&NbP<8oYf1Qi@J8bU zaCWz4e{N$>v}QmFBeJ8057QdTqJU4PT!Lb?ZR>O9>|N_i^5zeB>h-4rt*MdM5`m}( zHJO3mDWI53kio)O(Ld7!Km4``kAg{7kk6i3Ymo#d#lpv1kTApoJWt%MIOe)`3=s8B zQv){IOv84&{+nKGmkcON9w_st@8L{8yv)qYKb$U;`Zzw&-%T0~+o^pr^TAMq<01y$ zwlM5F<1G5AjUS3zJ*}zVI#MAZO`3N|=#ajfflsyV0f_3BaJ)-`cjryU-_1@-Txe>^ zx?U!57p461JsSlC|6;zb;_4n>f7^{AaTy0rH>poo8H3v2D_j78u49Vw{LvfYUZjfo z7@nwH(#CVc)EGwSv1bF|6#e&}d*m=B8F|IIcN(l*1LQV&b)TYV+zo zzBb{;Fd}F%Mup&a9?II780bI#S0?p~=0G0MA^C^+sc&frGDYxcnp#+Hn9J)I)>Uwz zqusSNUJ9{aG5|k$@CsJ|_&rm4Be61EAeEg!5K-_p2H7asi2Jn0Uk(QbD_jh&ZVEP% z@fu^45I=yLj(^mIb5fy^$F0jC`W*+w6KyTu2;y zg%dRM%P|kQaV8a~0b{g;&gkos{UgEg?YUDOS4U6p{OBC|$&LN-sr#{7l@GM?9vF$m zQDw`HY}LH21;RL|TG3BTK@qKiZ4x;J@$w(s#BDz}fI{QSae z$jcu8+{@Iwh!!2qz8Wxjr|)vG{{_D_SO33L2chZrssBzmJe+esF<^elRP+D(R7o2; z`Mp-byYBVb*_Kvx-=0<>TD^`&U>TCFyCDSYlNmVgNq+9b&QV8#a7N%UN+8B*b z(fqlv8C+lH`n3Z;SSm;bh~{W(_}-dmp(C;A1@6hiHs#xlZ3M{J$$f5R0buEd`|^@~ zRKeRD;WDCh9cVm1GEv_*AI`yiogy-M(>VrQ!tTx#z`e0n= zwMbRoC~j_i1%Y(p3ZUxduMV%^Sp~o)=#+>_7n0fK~#+7RX%0%&{0KX{Be)ijn z=S0J9*>25S!&L#iVTY$v1@00&7OP?|PqqDdw^d;% z9Ly5P*#uV+o3w|gC+2!u^XmRH8igJY-gzEC10knDN(nb6L`B_SdL{)1OFE!)6yL|Z zmnEwFIGW4pIt#xaMm4BlV0K-do{%gGhpH+c2!()JpyToqVh&DbTW(P)#@!kXGjVgB z`>R&@UiGGth$AuoplqEOYF&yY4mg{naG+_3DtmlOt?k9BFUk6mq+H~3lS`{hmE{MCi+7dKLfV|`JNqfi|%}L#8@|pNBYW{18yH zsP>`$GSE+>ifP!3f;mfvh)BZK=goD1$teKl-8zvfhGMR}6_^LSjHhCo$(4vq=Wt0!luU@T)Cq-eVyYVzx8Azul6&A)$66)3h=EKYck4SlmdB)1SVSK@a$ zVgF%%`@*mkkZT>~55ee`l7JD9X1L(;=^Bsz&x8}pGj}B->hoyFXBZ z0MzrQe&FkUelL_36c5fCNG-w6Q~T5K1sJ`c=0JaQ59(t=pK6t3I~H<>mAdH3AP&)6 zoCv%r)(4Ef6j%F@in-&?QzH)sn9z=rnG;`uaR7v{$RoJ=Z2^^2kiVOy&R_@m;`$3= zA@7*{AI3`pjHg1*MSI$z`ej8b{v3szy92Ux;pI%2fXGL;%r<1K_fU^#e8^ z+;ZK9%&?+kZxZ(z1IqaU?Qbk|n;+Eb39j!Q>o>r7q2OMW9lKN)1ADt;#sNctz6Xg1 zJzA;V-gUNPME2C2G(s^9o9lR0(q5zi3sE=>;Jw+JPv>V;dO_sWVL_j{lBVkw-B%YH z^DOE zH?L})OE^_K@eLrUeBkPp=G*4-EX9bh1?*hQ%bwZV?}NH;TyMe0>U@1bQ3O%Ngiy1h zbp{R$Kou#_)jPtF?_L~ZztU%$sx%ehsQ+(!5sh2gjeE}oJ7e4D!9T>4q(7}Y2o=mT zrvuuqSMkfTmi`Ndrt(#Df6b7@`;*c^jyJE$uJS{<#^6!j4n*i$@%-Va{&-7^T%wTh?C9^a$#F7F3yY;9 ziZSZ%AjSjOK4YG!C>;J?aIUfnMvp{%FplTB!aee5D-ADkh?+omk`w>K;Mly!Ylqb) z26(Rd=Lp)(uQWpCa56~QV_TFc1iWs%vxXDXKhOHb&G-Hrm2TJjB)i|`C4b7d&?~h0 zG}fA286&=+Hz>4dHuMu4FOX(2dSF`{Lt&R3!%JRKZc z3M%c=WEOOs){QrRJD`22kRSjcI%zrK=Q>YNJ{97ZGIi`_1o?94_u#l;Wu7Wy*#P)UCft5 zvAJiS50Gt1Gr3r2!6(_f<+Qh`cVhAmy5a(u`&<< zY@CNpU3I7!m{SB?J-ekYjCTb1pejyz45e7ql7~y>u_)-bF#kJ+z7eJ*uiCjubJc{& zNqHAuld>`o@{GIW)s>lk0!U3cqs4XotcXj?qc@VLO5WaMP3GCYRamz9t?azs7tlnD z{j}QV9e>J0DWW13iE#C`BNeEbMYC(0V&7c}N_ZPs{8}}D&y}E$IYaxwc zMeEpq>muP>OY#gG@Z5~pv7?UGx$zK1Mt$D4RM8gD|TGjWv*1f4}jE{V2B}X z8n=rn5^k0_oNjRkm0S)anhGhk>S}9a!%>%C8AT61ywaS82S3VK83(YA@R>z`>%bF( z(Qwj|Y)}1EewA2I^{_qFoc}lTr;GrYWr~{prlVQ9vGEt3L23ND zg#na}9j)V4OaYLP=N?y~h8P~`l5dAmkKS7usX||~(M*GJTK`Rj2j*7;j2OuPA{P9M z0(x^LqAgDJnaOn;B!nwP&yO0=L%$>*^?~~56YU0g8&7or#3LdOPx~#|&6?p--Dfb3 zVAHLc<6z^WTWBPNPv!@`7VdupLw{F^D3TS>*IWtw7oaiBfGBuV$;WDKRLJ3PU3Ss1 zy0gnzm2!5!3at(tGXa@`Y)aVgMaG%x%#RtcT>TdiDs-UhipOdnmOjzj**daR#n{%u zOi`krHW6XSGsrYF_H!jF687x7(jR{xI8ia;+Qo-l9aUr_i34i%iAvpX+y9;L1x+O) z2-?#x2P`Tm_x>KuvwZGU9pW>5_@`Ut3U&ndAOLd!_x033Ix5*c%9e#ZE4kKAq_diD!^S+E6)?^JQ+v52x zt+2$524#pYJnFUcX!qjr^fVvdKRKB%WZN;zNDNqFz+ws$1l2vl)LxL4%C$G^L(T)Z zdc{ZgU7FT2Zr6w;!epsqKpEjbOMh`>Dgff7=ZB+`zncl zdfi@MTz8ZXYKdZqx(|au2BVG2xY7nKQT^uX{f+|he`Qw16iyC|MRD&o-2tV4p z_{iX#zJ2AqHZQV(-id_!Nmx)L{Xw8^0E%HOpYrb6;V}aUeM>k$-`MIRSc2-mCC=$X z!roUfIHERW8sqO)j=|7A=8EPcEND|F$+MdXh(DZ6j66r6bhmS=smqO*x1i5B8s^yG zK@KciI8=c8Y^jV$$~7$l8~&j;Z0Yr&;_#M<7d#_I6l`d5f*;BA(` zBR4Q66O*iTW>n9OJHzk8*pp6%`p$y4tqC0kV&mVOZeLG=fQClyyfnk8Zc9~w{`y~wZ@czaqz*e5Dv@-;T^3x19ZA9{0T z^o3F%>EUzo=dk3Nzb&(`8&nn*$mZ7PJo`@2o4MzP?{u5cu`rJNT94bFb}c1J)Y75)nWNHZYh3n>P@eQMb2MW<=F~X#qg!d%N0d6+O+l-s6fZdJ) zyN5M|y6~aiQ)i8Ll>w&tv_dA7-+~>hhVC+*KIB^zDXa-h8Go$T6%_1J9RY)&qXOS- zzE+(_+YKx~SAnW0ms#-#oG&v-*D$yz=$Nl0#{{YqfArT@hwq-KJ0qY+uVSTIS8b(K zX!NY$?^_H42@EUYfXv9SEE@Fn{o7Y{UckRp$jk{OB4cEIrnxmA%blWkd-2nJgDU3f z>stYI;_`fNxehdG1G!>xq&%6|Qd8?&pcN7um>iA632tkxaBmuD8O1dz3 z&qXmH_UFWdkrhw0mO3{c0QO}G)LAa{!6SH^TGY9Fb%oJpAcRKbQ{`l+#mu3 z=5piB^cmo%zIt84L5*}|rbZx&Z0m@PA2B336{PRfT#t#3{fO`)B7>mXCY4k%B{6jG z!96nK0d15)iOHkR%XN(!b{y)>{1`OJcI+J*WtcW7DB|N7@#i!Ej#=72bZ z+_I3b33yCyPq=jR46!Z3oh4!Y;cbdShExyS<)1X1A@H_L!#2eW&KeEF zpG(M?(2>FYI^9NQ*BmaBw2D07eEMl97e-7DlhB)NIb)U<)OtpdP#-y1;7On}B6#`@ ziO8vAR#z}`3=S121+e^th<>5T`};7@)+HpqW9>XvFQ0yJyW?$uzcIlyeykfCnaGEj z`!f}>@q7YujUCP0qtKJF59r>;Ej`BpT!;k6D)%@%U1@hH7XXVgxb0v-$^US@)#MU4 z?km%N7%{l1V86+dIZ+7G0KyKgl^9b%k#{Ru#Fiys>Tznt8itH*;gj|3Ee3($(o0jiG?p0* z;`}YeU$BLqRe{oWv1OGOn~bg~r{sieeD!yxzRDb=^E#lkuTzL)a7@9kQI{o`lKbfN zwuVG2{>{;x@b&ND-t_qpcD=g|i;Kk>(m9sFRM)evMBVP}WY6C9_d7p+mF}v-b3GnU z+ie*M-H3cA!fe@iJ7xbc9C4EFOTjGULafB z{Wk|MUq1{+Tfjwxk{44agh|zf#fi|@ZWI45BHWW(x!l!j@n|l#FuozlsSGM1pNZkZ z6_mf)`OMw<+nq`zc=gS2fIB>P`Pb|VPTgO>?%(b0O$iK`dRrz4=5YRmaxnD2dR7O; z$b!(w;hV)*$jeV_-XW5YJ4&E?#*Z{_qahi(I|MGsg3Db%wBygN{y4WGqlfUW+4pF5 zRg9%Cv?H!N3z|kvw^aEF!%fZA#Sh;lKOhm;h%ez#OS$+8L)Vxw{o~jzYpQX3!EZIB z+U!#2S*`C&l~2zy7>MM9G=$v0bMY|&J$KpBcubSS9~-;>6ezb$jh0}ZN`|&*50>zm z&Y2|~X@#os>f$^++$-k+=;OXh4uKM53abM6(r1^o|L2j)Th+f(Q$rem#?ya6Mim2k zhcofQmLAhjNW@h~WOE2M4mr>odJNB!H-fu7C3JplNh`!NxA)h^I{yh4z;#Bi~ z4zy1M2p8r&LyhT6NZ2CYTj%?hY$6`GZO^P2a6hweVJJ{9%>uV)qooar$ofK2aG&`O zEV#6QPx*9F6(~qbGp~{8EK_-oUs&6hq~DUmUaLv{tH_#?L{3E@S+%fO73|y zWOb$gObo1V2#BPEENzAz7t*`!U{lp>u=<5!k(aoisfz=%?l=Ypu@=tSQh~OLw3{HKOJs?Az8%|;cY9DT>@*OFs` z_cm}7V;#-^C2_6;2)qfb%H?0Jma<F^-x6T3GKnEjqcywfG;G`0|-l~}F zTS;yx12LjoaX=O;3FhT<;~ibES~IHe5ndYh*9Na}&L@FFu$Xtjz%i!b{M)Jl<+3Xj zxsdEM(OA#0k5$Qh8e>!zc4j9LlV^lz71v-#OH{Fw*4sQdDjSN3MaYy3zA#F({()d% zpmALwAzVrMGQQUODeFOBUPx!3=E99kiQ0Joomj6wJR=(vj?!*J@2t>Ubz zP+h}ETD%z?NvzjK2-f618YFk^Y%6FV_=vcmh_&eso>=CcUQo<`*418cZH*DB_h`SqAWcf0XIr>cZeT8~g7t zwmH7-f!qhThQmWv|5uT4KVu>!g~yB(*!CDA_46RW!rn#uJjHVVz0D(xM=-@B9%K4x zky`nzXf+?2LKG`~ZREJuxf}z~0YBeq)1}T8x@OsMc4cw(OiHmvoMVw$8lfU~Bp1z* zdGNlXf0qRfN^M_lCfofIAP*;l8j$#>+Aqt1W0U5pu88kT1v}qo46NhiUrPMsHz>=2 z06o31anViYP$u+*{pd`m$6S3$hCDwWY{>>8n{hU%0;3C6XBoO#$YJuQp{FOyib4VR z$Arn-kP#hwZWGJTL|^HC&4v3jn zVYus`7b+h`0t5XtUBu#G9E*OFSe)ZES$ymf%RrvdOsjYV6e(K*cb&LQa2_tG7sup( zT0M$m0+H#+%b*UF10pqdcaemfn}wDHLv$MHENUnQ>4#PSn=yNhr3PZZmSSLVmpx!k zm{d=-4+YmQVu{!PZ2`uF?tG{U3$Xyl$L(%e3wMBm*E^>|0%p2C+{?($agUH;X-kvymL z64?0~Bl_U_&*J>sXjlSp<=20T-}$;C%5CFrXz&FpA-OueVpB|bbg%!2$wo;O4;m#9 zf0&ipy&oK2aSNCj@V#*|_`@*uSnl7f3dsR>BiKZKyo|}%hpdyuljz{pyzmihL*PD? z!XZ(4se}VuZG$AQpX_GC$r#jW{?bxw7&jy$5_aeXjblrN6_WObS*=mb9+LXB)RRMOCQk0wux z48wEX7zNksQY|u7`tZk^dw^W+@@&-vDc%AFFL}=HNV8noc&IlRB?inkzAY%zClzjZ zv)H}q7)CEOWuz+!WTLV4%5}rK4ws zf@{-vE~7xU4n2y3N&oqsbV!R_aYk(iat4Sq01E#Uo__I5&F}3mg(>0DFfh(RVr)2p zp`6|wxqzlOAO#s~wxO;jq0Ouxsr2>zupjDwn7ZzGs-wSuZLXb*YjagxBV=Z;%WWAq zA(WY!nU(DAnzs<5xNc=cl#!9W%E+dWtd#5#vYvDG`#sO|kALcQ&iS768Sl^g^FHU6 zZ+I}q_o;ec-&$1@A((!;K-x4M1H)Np6%~8*iK&Z>@v}x;+RfD@BCG(*Pv0NhAL7dR zSec*C@<$oE%hf4jBb7)znDjYnBDp6WO@czF_PPYU5eOrDidIJx3cptzwkffhtLO+VkL0gf)vO9c5iha- zIDj(`yeAT`St@kGn!{`B*MxG~(^+&&56fN=Vg7XiR1huN9Bn8g$c1UDn379QAo+R4 zP7BK)G61vjI>sRc!3p-q z$EZ61CuHV&-0>p0@vSGqRLqzzzh~<6XF^v`T$kD|y80FCUf`HYL42p@%hANTgzWM- zrjt1wn||g}z2HKt;Qqr};UF*Yu|CoL01JewG!8#~9%f<=xQOGU(~l9S6V|axNwK-n z%fD!prAegG0ZdV81RwNUS1Aex;h&b!mL`DhLllx-&Jm!fje-50aNn+smdPV{)CP1a zF`Vv|ak64J(w83jJ~%b@JkC{#YQzd$!J&m4B%m8XFX>(pM;pK3N-Bh#p>>-UiCw^0 z3ZMuv4(EONpLmnS$8y|610+ZfZcPkqSzsry&Bn=6&aOLfUG&U2z@UgMg~}}A&3(sc z$y~U=0|zoMC%!*}AD>yi%WsQ;B8x_f9u5qg!Dt7!#*|7D6#B&p25$lz7gNGZc<0^$ zTD2lTrYA*{nyM&!JtzTK%XN@3w6)(wk+jDGQ}22a6zgBRC`)LKgq^58^yB4P%vsz& z+Ty;sW5inQZ;3}Qm5E(VKgYK@{)|-fNzr9XK%*0k0J55_#cyy-XlHR?8|tD zE(Jn!F@EZLsGYC;I8VOAOPu%a_S8_!NY%tEvENm~aRf9DcJ2!5?dswuz89}dZ@!)@ zJb3WzZ#_gyh7wk}KS>3cBPuRZ+1kBy#UaixXrfS4OB3(R~KDTSie+ceQG@^1n51NhFMHM9BN!GO?DPdgh@*e zxyHe2Gwlid2wiEq$NyQf0{FtHvsciBM|G>kE{b>@`Z)NeAWGB6574%xg4RtEH5W1P z14;qHTc$I;mJdtNdG*I;y|!r7w01CW`#qzk-&Bo|{lnkaExEqj@IMsp|A4m6LfBbW zy=XkojJr(-%;rN>Sc^bbB5brA{{n{qN_xACC|paeMm;&X68@#jDo#G0P3D zCc+>+0}V;qP>5`@!0nV&JkSgN74&zQ7UDoE{_Od(g~H))cQzWw!(IxsNCqarw1-*o z!u*+D(_{A$2xmI7s0eQn;x1VbAP`TVi76annW`mN2g`}WkFNLlr55Jo>n19k*Zng$ z+4DF7#$yCW!ca~V*O;cRX`P8+B6k`)xTZD#kym?I_H^kHVJ+5eiFac^Dr^rpneV<4 z!oYadoaHg^ANZed3AQ?$P0Mz{HtA30GJMcp5H&E6zoeM(QK(GPCjp0#urqAyxwg6% z>8k_nMH?l+l!3F?qQ>Zd)_z&(=11Teta3g01(;nFF{xbHndo!BlVEOYGi1RZKj08} z1q3FQSLLg_-TIH=8%*aJr7+%IpT3GaI#&r}D(3bKLxDwS3q2iy1Ewf|oGeO`(x<;OUDeG8hz&|?bZ25qdDxym=gm$`}8z=!sy6_0TImP^ zxYQQ-h}@RDsKq(!I9JyNLDVnjcq|T)r-{BBmisxVGo?sTustYIhq!9Cvr#yF>lMNF zo*r*49Aax}3>Ubx#j564n_0?EJhWayN+ zW)TYN>BIE{-Ias05u{0oBx!6z8#)jQDn`g4VClDO0_YieRLK{PjY|RqQ9nlB2nOvT zAvK?K^rb(Q62Ny~(~7j-gCk=LT(u3=FD{h68PV1rhEqb>oplMo+rXhgyl^dw!LR~u zBt+d}%6H8I+bbhT!5I%rs|tW5z;b+lEbrsd%qz*WJzu79c}CXRWp<3&R>WXo1Csa> zJss@A$PyZNa|HY^BiID4Wu#SlO&1#x^q9H`QC0cFa@`NhVQ7^U>4ht}oT!bx0^*wv zR!=kmhQ$-(ToKqS&lZd*25rL>&c71CCrH6u$wEfKZ0HWWpxjs++d@6ijnia|g|Bfn zXTYKuFF;v?Yg}-6@8ZsT_RMc$7#5!=SPVG@mbI~A4Z?4Wpw}gMO&5NkahG2* z(d=lf(jp4F;WsF!SVU^!NGRw7H{~xG2lG-ip$9Gllg=&tf=3$$92Vp#SPvvOlAhE} ziyt(Y;WT?GAJkGYR~pF`O9Ak|1EGX676@S=O;~PM5e!6K0lsNL=$F2=O(iI)6->=R zuW`#$zu>10!CyDCkDi(t19=y5~#{#h;KPb|H4#_|=l*3bF6~l?4 zT3*t?Kk|J!ofJoms-o-fo*iZ`r$W}S9)^r|D;l1z~tH~AeYtuj_=SZ^o5 z@a_n;WE;76z$;Pzypo5LyX~i-#LRY>{_v5-2qKDxJ`{3`?q*>9%fBQVp=USz)e+7~ zP8nUqBpMML`!yk~MJrOf=hFXL{>{!5Hy32WWkYIGt3Uf&IMPrhP1F-adpH5+x+AO{ zFx-M3xMWg#M>Gl6a1ZRa}N#mjt&9T*#jQ3s7?iO zOl4w6TLFybE`jq%q!o zAVf(1?YauDRV#bDO-KtE{#$?Z>17h46>QP9+7XSGgbv0#j3!X4YqxcwVvKd5kean0 zb&eNM9sNvcS}8sx;r6MCu+S~7s7qhRK(Kf}l0Qgmql4}1s{iYgt-2m}Td1T$8bcj! zQ#jsgG=lrJ0q#N+6Z`U_#^O$=kbE?@}5lfQT$8OUKEee|q3Nw8N!$qS2yMqih}cUN4k z8B$CtE)UFwU|VsU8+FttPeUk=_CzJaE2$>z8M8w-|GKbFy9;69(Ttl%B|_TTzC@#a zz(&pKf?3;xG3V^6lw)5La3B(#65SQ!-{P^1c&XVkS9@F)9(twac z&RlrUer&7m90pc`fB)Hy0P)Ie0UD)CKVuCBKBCJdedrzw9=Ny>J;SVBFFS)z8On@+ zi39vOmr)xo?QnmM{YhWzD~>7zs`9alm@gtKi(d1Q54FvX8sM-XxxXpBr~xplLW6-gQ#GJ*!cMpD;B0=f2b@FqjED{Dlf&>-vMfkQh4O#= zEGZE-Vdgw$%m~>>TSp((++<~)yy|XqE~vWK71c$#-OeXC@K}W{J&r%9dWA+zkX!x{^ zBK}_}i4DW+Rw6K_0{Ab06P{hF%3s8!P5`pdfS&r1ffPnTO3zf06Ezuo;<|eIMR*oO&UflIQG7+@gn~GJ}<0cG*2Qcax*~ zFDhU1pM8E}f7Y2->l45|3;zJYyeAz@B?;HkfCcpRZCnezXUkw5y8NwgvEzTUl1Y%N z4t8_7BQBZj2qMx+)BWjh2^KsLlc{U%;P~>zC=DNQa3cng>2SNi5d@>I-!w4La&&YH z3=@YBwJWN*Q4ky3^#v|Wt$u_Pb9X16$hk!e%hOtxzm#man^+nF>wGWK}}q7wUmLu z9TglxU@zbz#z@&0rX(!{&{Zs{AS#o+t}$>9;88g~q`h=}0!+>b%R;tfcI+z+^1NGJ zr&bK(3_$FznYtw7@i1pO>dT`7v6ac&=Me6;AUbc#Q9?x!Zem*3I`WeB#_HW)pqXi6 zm?yq&-Xn~UV&FHh`gy`RmzvRrDj1mCPJz#M!3z^X)a>VD&M&`aAMmWivZN0VslZUp z#EF)78)=@~k0-%=7Y!jbXzL6SJ1L|6OE=X(*w*+z#4Tr?n|nJ_`*k5&pxdikFe>F! z3wKFFef?voi6QVkx3gn@Q@ZFPra{hx!eDin*Fej;uRO@()srKJXAi(@jpK>|!7&3$XejMRyV#(lK&@Dm*kB%lkDu)r;$hL^~D`#r@QF#AbG3<4$1 zM2wxPjg4oQ7y&x~@Q${=HrCA3<_1S+CXPisnI)=JVya6Qq_)pvF>39D<5K2Z!rOCi zhIx=iwzQAnk^Ja|=TC$JnRaA|Q-iI~#V#enXd9Rl;7)tJIqWk7Xu<-HRD1eOfWk;GB4nrzE2g%XRgtfvjxEcEMB$Z|JUIR1SEhc%!r2GlW%N zX*P1avCzf+`|_}~ET8#W|FwAgvqVrTHYADj8K}C9Kol{OQQW+Xf=a`~ ze!V%GT4B9pCWk@eBh9(0&Cej)MqD!l^GbEG35K2Vf;vzO%LYRj(%$~1=f>y=ARhqF4u%&P~*c}VJmp|bpBWSn<$LK)ucg}*+`T0Wx;*Cvi zZdRl=-QXwg1YBmcU=*t$*msD+dCV{X?f1Y%@3)UEQBs6bt*@h!)AIJe_v_h^0E2CQ z@DW}+&Ry|rc`J(9ds`KO`O`!r{HD=(_sy-}k&Ix9Z?^FBL=TCPGDvaNOMvMq&E%iI z8B>NM*J%m0v>~Xk)@_vc_U7DBsbXIrSg9z{NC@>qpq#S(Z%ws5nOzj=i2FW$l+3gy z=DW@5hl2V{`4S5Jcu~ima)>DFJ^q8YK5FvJHDJU3dExDBHlPinE97ah&%)vPF{Yj^ zfA{CVUb2XbuM$Lk5Ykb&UZb!v`vWPg!>zurFdzGY-dNqQ zy$mP|;03iKTu4$TW+~qmGC@?*Q^BZ9XFio!IcYi(gk@wDr~~(I9O#;yh5ziW7=BJ4H8tiMD&mU$K-|zG zq+M#_i)Q91dN2(Dk~e{x0@gBP&kc@Tx|X=88iHl+1jw5yh{ZHTRPbCH92x>(>zOLq24+ZoUT>V`B^G;lc&TULEMIbPlA48Yc2cef%@p(8|%HY!y8d z{Qy=u+jjWf@X&vc8nW0Cr#be-Z64(B9(%T89jtxzd`5pRr+G>nKeE{66$OwiXc{ia;sBOFMogFLOv1^L?xp0_(CXj%HAw(DFpEXHzT5r zCLYfgub^K#1M59sdTd5!GE2rE<#W)0N(%qIIFOGxE;rG+*By>=VeZ&w)M*oEb2i)j<_sGT7G}b3j8pNz|JYLSZ_mdy@bfK?$^825Mux{v|cn(YuL8R@*?q>BAuaMY| z4i-#U=+i<~_HH2}FT9JEoFIL8|C;tZYH;hb+DYO}o`59AK(qpZA!m)kwUmI;1Az8X zw6%qj>&c!WRZo5aOo-vUUrU_HY~+h)XlwF=T)vPO=Wv>`RqwOH3#k5+&<#(AqlZ`# za*eGCj`SdR<818hIrr9InQ|)GyYQk!?;Oe%vCl=m_=X-R62IhYas%Myw-OWEZ*;YD zIzbITe|wNDh9M|lf}64ltx+=9_J2H91mDd?DU4APY?f=f16? z$-?}VtDC!^>LLHj@R|u=`1wn0nwaTQTl70BJ@p4imFb7Ilbagzu0*cu+u6&iC-QWy z6AWG7{ao<{CLS3fpsx$PzXpk{pnUHb@SqM6g%?)f?D?KQ z;RI5T+5T*Gmd

=nOTijE!73mtXYwyI~?F3OA@AhY2Qq=|N~ux0Rv?mc%dZ+}meD zv4lHTERUVX|FI^5g7Y6?3+@HZYzeU83z`UfCCpiJ%XYK?b(6939T*ZZBWYu9j@sSv zCNNQC*fN{wK*_bKxeBA7=VJ&8FH66ZC5&Y2l2jbGuaz!3WEXV#&A|GCHyfLdd*ndz z0LkbTTg|#UkR*PoHZvOdB?TY3hR8#{A*Q^-;L?{s<8zuKAEg>h%VU1g0qf2I*~0GD zH&*b+O$5Ww-;yBAx;7_MngnBh;fk|a`pWelKI!1%XkYikP*QLBywDki-St-k5`U#K z8t8Km*L!^LeFVI&^cmtVGymIVWL|?i1OhhM`~%LWSw1{yNoQc91YPd?kY@mW_M}Qj zFsck^Lp)U!Hm_OZ+PP|vs*sT0&g!{#iMdFX*&G!05zG6AMRYHk=)dCkwU*uX4c=*> z-}Z^~X*0AFE%f@nI;aQ@4*owUs2fIr>GThOm-jmsKy+Wka*YS| zdb_RI)yhpUiFOcSUs{skS=(WgQ7_t>E}{DF)g)Q<8)qU|s{ei?YwMLn4gznRn$qF<&w_*LvWk=_bc zyZUdnb)*!4!QKnJXj9%h7{fHu3kt$e01h_bgWl)qZ}rjFEdwJU$iit)+l3f?`)?|F+2ghsHy>izc$T>nq0$ z&3Hl*SQbnHxSIL+7B~B1J`Ha$u!_#(G`F~}F^@PsTO%n0P_qnk0J!m;u{D-%q~0CO z>g@<8@~}ROd{QKh&v7l*peF$kGf3MiTf!IL1oQlA)o1-sVv)V4(9am^iRW}WzGg^3 zQ*|;8yxq4&Up2YmD0stlYSY?J_8&43KiP@vQa!cRB2Hn54s?mm)3yeHI1uis1*2%e z?u_T?HY*GSjP_p>gm*;0{_ZtBUpfLyE;0wi(@z2T=T54S789| z!W;F%yBky)-ERB+$&G{QH&m}V67AmObZ_iL|LqMRaU#FBhP&I1(eP;ixwP^(KqDDa ztY1~(16jY}x6=B8(Lrh83k9j%(gk;EJsG|Fcd<=WYCZ0|kd*1oa`}eTM$1?F`vnf& zF~V6)+W8A(>e>sZsNnI+KYJWzL56M$fm_lPS*037mERI!Po1pJE`LH>Cq?p?y2&4M z_W~yA0W5(f=Z3;#Qiz-#1s^@PNZo?q*`0;zRd1Wnm#1aymxGLGY5+TADGaGjC%ADt z43uZNeFgHE)TdWL3E{2_ZK}kP2G^X!&2}|w?SmLw?RV(dtPJgl>wEm;v%20{XSaP2 zcG9Od1@<+osGf~#{R;;C{|v@27cd+J(q^nkXpB8+0<3f(9F4nnzT6=Y5mM(JuYO6V zj1h!SD_;NC&e`Ke9iH~{3A+CIQ28+BFLLqY8=nIf5?dn08aZI108;Xk3|VtM26MjLwd~nZUAQ z=+>?K;)bf?hlPk@WNd9bk->P%$p8cK%11{Kho7Y3dl8NuGzIkvV2!=iFx0gq0){6( z@|;L$T09F|N8F#cRe>2t`I6x^Z=`&y1MTkoT`J8)lwdwXt`DWcMPkhoPRGoG{u>jt zIs^c9{fS9#NPV0!@@O?4mLJ4~`I4jyws4hYO{~RlX1G+G4;)a-agT4iI3MI|!$Pa% z%`TgQ*&vWNouPO+D`M(+`H~FKwHi4B|E(z}YC|;FXLNKr&`WZMs+R2sI~D|V(P{!r z-5e41^J$kmz3}$i+Bk{!&r*5{=wIoKkh|4^pnLY#MHU6J8cpw?bjH4y{LVb5zTtfN z-%)|;u@r6nm-Thz`MkEZJbgLQZ^^h86*C^9PuC&ZyO+-2nN+4|k6q;LRG5Je9&(VY z?g=DB2#LDwLww)7EUOCib`E`MU3543+}#3xXZnAm-}*N?D9s=qLJE_A&|$fZ>)ott zi!%FYsWW}9M;=x{Lqpj+EYebd5OQi(+JL`9fh?~fP6x)i>-I$vZ+@HuBJK=5EZ5Z0F#2kQ+9ZyMnYp%+BvwA)0Vp@oW zlF1FoP7KuTfdB1(nqbNWuK&EVP#)8kMxE~NZZjThqC67;2F{9ukp&Ih4nweUx7%1j z)Gz3vpXjGO6uy*@BhH6qmZ)3MQagqMf~ned%-;0?^o#St3n)(Mv%-@99Tkofc-{Gk z`d-OGh-LcHFLWM9Xp!H+qkArAF+FuGDskt>C-RPisQdqShh`*cX zNCT;>4um&1Q~?_RoBwSe2KM-0(7G}4&uj%tdPt5X6S`7L4!CdvZI8^%1t~~vR@>iQ zH3i-1cy+YPvqYFsGH)l2innLF!SgsqV!D9Z9VppBj-k)Ix{?xg9e>3<8eq%xeB0{~W^ zb+C_hlWpyt-H-nyKJE5Dnf-EG8u>ThFfxr_FzV{%EeC#~Gm;0o*5vm?s=8hOFT625 z>8oD(tAKu7;F)EAnt=^ENl$%p2oNrp&j?15-2@#cP)kZTB$l1g4v_(iXjy4fieJC2 zQ0daGTSJod!d&$&m0m@VEJc$>mUiMlGfbj9U2O~w|G+I7_5&?k-TR}#41j8{gVEB{ zcvB9-@1K6Qyppf^?LrFLnG>ecLS*t~pG-fBmd_f5ygIVTyZbk68^;KF;|5E(|)V3uGl)grLBEuC{3MY9s$~|T8cT=gxsnkc}zwyMclfu@$^HU zhzPQ~$pUG2YhEEJj6kmAht{OAy3IV)SmFEJSZJJGCW-OCAqa-`zSm9FzsG-_ zgp_>1@nDD9=c#oDF=6lySAt7^PbVe-%3w~^hPqCBPTtChQR4y@oNoe(cs9?Q1b;Km z*4GtV530F@#6+vzt)1@?X(@^CW~t>wiG?+j z+N_qZn=|tU&8~d&KBxI@c;_@DFUE3pGd=eFnLkv;*NQf5Ift_`$(CH5b)DvcQ&9@M ze9JVubKB3FKuu1X!3p+zJ$7&e#`V?)m_)TE1(nkolG7&tk1;;bvPDfQ3W%Mno=2~FD*v}B`FgkK9aZ-oLuI~~Hr z5UtFGd}~gl9Ze-QAy4w$*~a{;&p}a9Crxub9};5wx}0c^1MJX66O70CC_kgGn;Qd7 z0?VK8X$_o#6vaTTH<`9=B|KBk8&aKmNOJ!Feocz;537WpVOAuj)>M|*? z>lG%^-_>U8h6dGX=GQ%I+`Yy;32D)eUSMK}pa0h+)l8y2&BMm|IGcs#I@V-?L>+_* zEAnC-Ii5@l%toE1y2tOUY%~mv$zG=4fFR71{e>^_BE~;fCWO)pLEOzN;W-02vW%|Nb2^I_5s+Pl-5KQi-mR#K4Y^#fCiq zcqxsC5qot;kmsof`m#)^X;m@UL4}QH<&pP)s7!#F9SNp2LGiejxz{5wd{&{NHj76e z|8*9#FB%}WPYs()v?K}fzbp_;9LerJ&_ z+-{)Z)=VtsRFW8BO`rjA9aMA^fVR8V*n;+a?&kP&cXy#BQa_wyQ>$w^Fi_)GbH>H- zM+SySy$p3N&lVdUGRe+xrYFCZ6f0#grkyF^%&yivRt^2D88t-ZWCj=M`UNtA@yNe+ zxn?Q#KT8nAX-@cYn~TcNeC`m{ff51axh?lCGeQ@fGmwcnl~rAqAKg-lCXwM2Q59Wl zeGmIM?RGP}Ypa_$olHJp7fjryH7{niJ=>rGT)gLen3i(%a0Dj}>(II_9KlAIWU_e0 zI9TD4d;U_|OODgHHkSoTwPe`CSAY03uLz`F@!J>qDEgmZWReKeKq0x1XEn4%o)+%a zyPXo{wx5p9t=vRV^qUs!y{>08^ju7RoZd+jZy7Dc7M;;E%8Hbmn?Rp`tQ=jTYedWX z>pR@YlHi!~Ib-;w8|`Yevald-u(td4+E{h;)#(p%iqilxi**KtN~D5cc}bv^~fbXU>#I zBT!<60w0v0SpK?EFz~NSHYeC#mHvso2exLJpNJ+gVq{&IYx6aqi;U__d31Y}|GGx1 z75V+J!Cw(FVL1lPmssb|M_XSc7QYFi|8T{*voxdSEg;p9hU9O~?+h9Y^eR}-ND=Iw0KaaaePtn!9%}ht6D*~Nsjr}Cwm!zT%hd&@ z&7T|mWYG$ipL)2aAOA!Ubv$lZ{{62JSvVvk=r{{U+7*R$&^+jOK!;}5xy#QImy1!E zR6HG0@3c@+DP@2)t)dP6du%NgdVt3WmGq3rDi2{{eiwpFVFO}!l3;bIr7G=;3xZ0EQK!5B{1@1wXQ;<{^f2+tQ2S^KmSce zVZe>FDZdVAv$_ENJxPRCsM_Rx9DZ2@+GI>n;Qu4&7^|+BC@!7I$3Yt_Ff^ioTYO^8 z4KFx|WaQQQI`JtA+ujs92YkhUlj;)lDHZRJIE4`pKn2+{{XE?sfHXu;?1vJe93x*= ziWHzS!cE8t%)61PYp+|sfq!g|v%APHv`wKdxz-tXki2G`E!_W;hA#?7`dy0fp@Wlv zoW3m%W!2*&IL&wjf* z6UhU*uO6Pq7;$EBFb8HZAKaH8bh?MUbtw6kK_JcNdUjdG66mpDzb*XH$VzW9Afet3 zd7UH_VgS@xpr76T?%y(4{_8Pil|S~;hTvIFVZF1D#|O{s83yqFFr~Ivk4!PT%_6j! zr7)8(gIR|Uej6#$$kL-`&BA?GzwXR+3Vb%ab3xA&+uTe79IOdCk#6ucOr-XK zG7^%}&zW_@niEkSYH;g65FD*f4z=G%hV$Z|Yr8H4C^^)op!mJ%>dfSro{uk$4+JyG4ZI0dMN50w4P zV)(73?$fTpe?z=9@RE9_k&)277ta9B0-v?%Oh5RVO@t_Dc@0!VNtrhW&;<~f$k6WzPPzRt#i zZ>1bUV#b7i2RxwsB3};_cDr$acAkcG7Voo#YDDtak3*xMi zI?U?Yc8wgSNum`_TRk7iSgnoiF&Rve=&D>p(<8YFx8Ne7OVT3I|GEJwI3J4w;hY=R zyW7c{FUmDTAsXH@(;P-bjU29e8#s}#E_UImD60Dx2eN>NGY4h9*P~w8|n$ zp|cd7kJ5)eq75(U&AUy+v811hD_7QgjI-BgqHWRgC!4%KERW!S9lW(0My6M~H)KSO zy5h*SWo<=`gmoqdbW=%{UWJ&JlQONII6lwo?l)3P7T*D#D$q9m1*lXQ=rWsHHuj=5 zTtWDNK!UtE%L&m4Uakwi}}bPm?Ii;2FkocvGIlCP1TJ)e8~+p?O1~f?c*RlRs1misgt7)e&zuy z1S|ky2urzEv-KOo%)Bx>6h>Ocjto@gC?B_%mw2qK^MCmnE_l%h2&2?x&NwMxV&iv# z77-HS@?>TriA5dob`WshLx8}NBIsdZnQsVEyNiok)vrPxFddytS*7V3C;^o4P6c3}@~M3YthsDwcNEmIb+lWpU*{Yt$s6 z@jR|}7d*9M?|;63e+2fzbGF}-XKn+}FxK^v&$z&2^CRC2GoLfm$>Khx|7pZh=Y`m1 zhvYwzlCGp8BO}|NIN0sA3cM#4axnT=@dtbM!+O4&Cx5<6_y6I3ec&l1-TiZj1?67H z6+biD(H9^8I;-8edBr(_D#rTSS0zp_lk9%lDj#otJ=nz#P08p8CV33gmFKwX(5U(|bV^5;fKcu!uZ--o025)`EA z_#wOBhc&aG@Z%efC#BV*e2uga>cA}tv%s{HnJ1J2@iSljUbnELTNkVOSPE6D=A7)_ z{?l%ng^CJ`e7^!+V*4GL9Pr~*lG+}Ni=LkR63=A>1EPzzqcoPC*90axjJkRxM`1Ai z-MPpwISM5Hzu|)cF%G1Fu_7l8t77OEQ`Uo7WqZ__k;zU4Zt51=>ywiB@|k~f<)3OM zK3DmzS=|uGBYom!pWwfV^ND)FNMd8*N+fs-0{mw@5d8OVFP)^6vLZz~XmUkCVZx*3 z{71A@btZpcCUew~5R~UJLFIVoxUp|Oq)%anr&1GD5|*W>x}R?}bD6)F*W8(cwy)$T zQATpJCL9pbv~Xc(D?+Z@8ToV|ndick0RSHAAvtUW9`q6F{~DIzOLL3NMr`h{Ejp|t z+QF@(dO}tG{*L>T&Ca;ZHU{@1?@cO$AU#x#0f~YiFml$;bTbh!#~VkL>(WGwp&TC8 zLJ1Prd6#aY-1a~U$ZbKxzmKerMF@JUGo|(@GFd0ufpmo{_m+RQa1)DCed)kswPkKY zk!^iV3&rVyq23#jxCy1WrYj*ZkO8Y9T&hv06X^ng0ZPk*ziM6 zbl#wqb#J*YW8n}kn-UGac|ySZp&nuqtuwXYPs5;j%d5*HyGX7Rc|K|9z!N_Z~| z%F5=FgmNnT&K>{tpS*UHnpgTOgjeIrl<}G&A!ej5!zezPU0fv`1{qy*Lf zzv@e{$57b-ZDi=%&Q!DPV2eW3neddhNqNaEm4=Gtt!~b?gS>Fvr))zqWaZ+=Y66H& zQc5hP6efkmPCuALXIgzli4-o4QOLS*tl|WEH63w`eL<1?$1({jN2OR6ws)VYf)tnH z&;nDF;r_qew35Zyk#1rVb4Oba-QP|Q&DR!zA!?)@sTN82I)t2h>W) zG&Y>y>R%`VI+)X_EE7ju18}~70cw9D4bi@pta1y8 zDtk7VDr{{_L2t%Zj2xoEgA83NMnV_$=p+(tH%0&GrwV)uUebr;E*D{2Gp{E&*r;%b zhUT~m(6RN_-Iq5!(9_nQ_osu2gVu_kRl-V)-2LG{>B(j|o0D%&+J6!2`(7uG7ubcw zezYB-XD}TAcXv@aHBXVbMfp<>w%E7cN7@U$TyGN;!hZWR>VC+1vbU_iRh_Kj_qNc5 z@a=`#Hey?aO4RM7j78L@f#%+xjxw0Pudf_Z&wAk$?}vrq!40P_XtIlTWT6 zuf!ZL!AV1kD`w9WcHT6@NlA&7vnKEh6|y3)P}!RWs9^jTA{ikmpWjSy zKCAirwa*g|phm`Feh!P$75%^CU%z!s9{Pxt8a>z792V=qcChx9|1_?Ec+HTiPZ-|@ zbt)MJ4yf!a3`@{B^m)(Kzy+rT?Ghs-(UEUX|18afec(m*q%h9r5Ef$`+>Z5k%eFtd z>`!#w84t42t(-&0DTbBfWwXy*2pzr04j4KBVZkjEM`^IdS<4?K=93ZPi7f1C9IxXw z5;&0D*VkUJUv?OLe}C5vT>0pKh->-XDt&dXEic4}F04@^#HMq(4aTsd6zX{PQ3w}^ z-ddtI6c7tqp4RKrOu;k1B@Ti`jk~V$X$5RO?Y&*mnid^DnLK6gV_18eT>VQZPOmst z=p9d;oEI-86#oYo`8C3!U&CiBI8Bi%!h}Fr5PnP#x+M&7C;ZZLnEg(~tKGx+` zN${7@o3fkkV~O6Yy3!+Qzwv!Qtnp^aj@ttSNe1FUJ(wRijMU0ITp0v9N*{uxkY;~U z;z&b&#Dly3=Tn|u#Rbi{4aD()21pbLD+Q0sNyll}Lgn=+3!gl$iZ`;&SUTeKGd7d7 z^QR)CsMLDXP9g*@ROSw%rDSAcsrbe-X^4GTD|tQBjs%$fa3X$$4Jhe?EE`>t1t{ue zmAB^JgovJO19S6C2xfn(mf1|EV>|Y>FlI1eC2Yzr2Ae? zaec0PbPl}iKx%dGVc`?7XK-*1H=MHHd+l(J>M~3yMpt;>X`eEstCsVPb{YkGclC$% zgFB$T)G9r8yiIB|_k`bSH;yL}+-Z8{a`QFBm(uksJ==%(;)FBR(eYkIC7*KpYU^qt z{OrPbeSNt@79)YP;Wz?3A!qpwl$++9_HR3-~lRw!cL2VIDI3T*IX zRK!j7_&mgFeUy25f6akExPIW#;tx;4JmpRs)=Wz-EXRr@cj*^@`kiSujGohb$sRE~ zsmX<6M78N{MS6%qdWYoRCVW{?|f9%3q1rAYaZR%HSX;^(>C0;6rUoi>pA%UGYm2JfoQhxM|cXu@h4{ zf+edtFj8YK92F_IuWpty@MZ=dqxnmH6x_$@xf!?XMJUY8BOYa#t!m7-_e_47I%Y~H)KgG6bfvtCj# zCJf&V2hu4Zqh-^sL@g>Cv{Xdg-o&y(l2OI_Ge`P z!L}_LXlV^(6UbJKj=htyU*eG5U;Q9N9hDq#b}muVpMnqb=tqz1uoIf~dAJmCmG*%fJQK289q@r&^T_0jQkrrsnQsiZ}UpKIyL;r_4Z@U_`ACPRQgxubF6 zSp%Pdcitp)72SHxHd)oWf@`4xQE5?+d;duYBt!G|Y3G1sT>-O155}=UCa}}7&-;SI z{??>EqYm~j*0+s@RuFZ+R#y4`t|$I^%*j1Vt$*Jk+ZQ*XdBt;tq6V;<#8|6fRDvcM zSHgt_XaPa{ivcvQk08}ppV~OpjccLX=l^!u*X}}8&Ybqsfw&P^dGGaT=w`i6Rg`J5 z*fJ$;uD=Vl!HF|1t;y|_8-V|LKn5=20yxH#14Q~)a6o#@JtZCfBzd`YbIR2sc-J+- z!S^_?AB&zDWl<%4%gDHPDO6u|Pl0WuZm(`qson@Ie-B?PDrx-=b01e7zJ_HW)m$Nql(8$WgqTqi{Dt= zc$s*Q7HI^Rc)t`ri46Px01&N&7wngM~%cF<9&;!M5-Q=9v9f98`}Y0K7$t;LO3)BDr8`nnUG z$O|Dy=KIg9MfG6L3(iV;E+3 zLl&QZXZfs3r2#7|D~oO1uXCR@asLp7o3U2jZ@WxQx*oxI^8OqjqoJrwoj7^uN*Y_# zl~xK!X)S-}Y3{9=U{@cRdS62dL4m7E`|;p!GZn){%yzC@8x17oO+CG!B3-_F?$Xg{ zJAZD^ykOKBgR+n{nbpY;@hf(u!O!^~x8?((w6!?R1My!=w&PDktN4f_O%%dejL42N~OSd3({a(nrnp zugCFXnENrR`wh6LO#z~gQT1$O`^oVxPGvtT8qxmkql)RB+kg*(gdYAW`n`xj(>|5# z@DkM|MEy;&DzO8vcr$Y~rZ%ctzG{M@;@p`ZA@?**W!)f#eq(_-7u5dvhA|EffaRzBs%G$ugE5f+dYc-TA9< za-WhO;q_Ptq27Lw&^P|Dw58F({58+?1-o1iaOvr-x00UeQXFhxrq$ocK=NP7ZDLKN|9MZI32Q$4%QuCc69SKb+$W>E~&f!RbfoM)SrkWyxChpeximrX4v{((gT1N!_MvDW)W`yhD7; ztz`KRr3Taz8q}%r{QS7$X>Y`P+jwR-iLk4Z)!&*5Pr7lj=i7o;N9wAuDN_$@Jp~Ebl1l=dOivPBS`@I zz~`T1z}=p`fzQEMzT<77ShD_C`1Q*d84|D0Z6zxw3pph7&zt0OP-<%s&CKgJWpLn( zYj&1WV#4SolJlrpRk?D_I`GHOAq5%L#L(p!Vd{Q59`M^ZZTc4)BA$mFs-DR-8ki#| z@&D5#xHlN5Z{uY}esl#Mktb~9e5R4}0pw(6Wo_=y;l+dliJwA$V>UALKYwr6O12S( zfykMH;&>!HYk!YNt?p1Ycw^%rmB%c^t#n>S)Jw zl&31Js%C8CxBmFP`<(gO2_hs&^>Rl%_}4Y%V?@&Gm*k3clyXj+uVR$n8_TB6DWAh9 zZw^)EW}m))Uz@@R%g2$_`|nBBZ}-oQD=AQFFjgNXlM{Gr1E$BUeR+9QNPTU1Q^%Q>@T89)FLSE~!fkDBV})kXXTAQ1rf-a{ z^LxUL+PJZ8Hnwd$jcwbuZL6^w8z)B7w6SfQ_x=6vz31y$XRWjM%$|8>=9w8C0aNAR zI=o1U63>V63Y68g;kA34r+@XEBGlN!*AWTZl~nnmz{UjccU%FUfNv`FAyHU_0|5_b zSXVdODO`TLEdJiddTUXm$lsuxJbf_>czjWj;%B$)oq=v*gP?NG*5pCPS4Zaun2%!@ zgJCHH!3~}E$WsqzRj|0PpIdA=N?vB^?ZHt0@ek>7ZY!79qIE0 zTycFo9nTv191(8#zkPy(9sSR?S9%9JQx;d~SxNg$e0 z@ZIV^8^ycGD1<6L6)(3{5OCt*WatXl*Zl@Apw%90$`P`>4cqOz2TQ-H2h8Cx^n2B} z$AJL@9gaHiy`lHMtXU+ft9Nq-zyhx()E+w%7auhKE_u~u@WBs71%2K2c_C>0?(Vnh zIU!w|{B$uJ5M1&~)IZ?&dc9L?=1s;STz&<0+?c9BT0T3oPij7m-mp(#Frd*t0Pd; z)9P~p<;Pk5>FfQ|PS#3c8HrGj$!Q0isG}qsHc6FHp(6>PZM%N~Z7cX738jh$sFF$r z!C2pBMUbIkw({!6=TH21E!45#KIQK zi--3#gVdK$@P2~@faA#G$WcYU=%j6w*tpo8;YP`;xn~y`2k_bQk?YDK#hr;4#J5Yq zS4xKZ?|b!R#i54Tl)ZOHRM-1d`U7h(h_+?8IVnsi1cOvWzWB{UXip!@oL2#T&w6Vc zz0ktQOv{47fU;=6ZI~1c9wzWd80hh*1mr3vH&g^b5z*@p_I>Pc9%?d$u4h-(|zwLUuSXO^!J3bVuuIBxAnv}LMqC|#vE7ijW5=t&LGg>VLJ?(2o$o* z`kyuaSS0ERPg^3$EQggwZ*+Z3d9q-9M+p*vv1N1fIMe{j$oq+L=ojyPxti!aUC7p zw)VEftsPMTPuoZht*zmLZy}7kX&DA1Y1Nw78^=gjryiRF1CY@FnYaHUHed~g9sTAM zsBHTD`;>y>(A$|sqyHht$8|=Zkb>6sKd(gB*ZeaB^#0zYQXJ9!c~XK z><$_dU$lQ&{kG6`{}CHu_EJPncF?(TpQZGp*E+JPxtrD;)_0q_tJP1Svd5&}&(9e)`88Sl-N6Yr{JfQfsG#k& zPn+cg3nT%E>EBnkF_*gsJ$Y&0I*qn`EH?Tr;`!s|q^<>53Iwj0D4``B?VoWs^7=9p z(7+Ps)Vg^CP!gsINB;AVgg}qCp!YNWRLGxSHbf4u67Cm^oJw=(X?E??y zc>dz{HiQ&le9ChM%!mOJq?azTxnp!$tPQ^!!#;Npi45scM=Z%hmy`UTD2_jLBXPz= zcRM=Znqs$ugkzBs4v2Dq_G*jWZx^8GfXgavjB7E7V(RTri_4zfJ-*AKnakU5vy+Rn znFk1ZZz>^FWGPs3ahXzT8I3aX$J`v>XtdYlBbga0Nhbz{i;EQZMibs=v2?$50#Ncl zieyyzsw61kKrt$BZTi;7bt?y-iv$mIck@$Q@CL1J1ON2Qn^rFi_d~zl+4@isO0XoU z(Au2$$th2Xn~gn%?r_Ux@9aA>VN%qJMxODwq%yrb4vob>$v<~pAI&;PC;IOA%eYou z(q{c`6{8bCqA2}DXGn7KGo72)ws4AGp>Aj-P)&mJoSaW7cT9*lArkz<1BhMBZUi)M zF9h+&c{laQh%%=ElP)`g2H3^$!y;LBdxD>Bcvw`3^ z-fk5pi*mP8`ej7YvZ}VEZ0<98qt}mD+D2OGZ`u|iD_YnmWt=bRbex7x!6uz+?WE1g=XnHBVgRr;ZpQpg*b9R$hb*LnQ{y|x)L<%a_m=a5aC9NHS(w|@&XU6L$5o85C)gsO;$*K;yYYWEKibI(rGsfv=|w2Cuzb#cyq~$jV(rMC~&<*Q+I7!kv$k z`@bj52=bC}L3quPl0)RuqyT@_gmYb&z7=hH8ME?i%0%_2F?!IIB7q8wb+HpV6C1aW z&ve~3xa}g1PYuTpc_~h=1}CbnRnBSpU>YcD(AFL`_vlC>PvVe`^i~UbBEQKbDu!E& zn`QQh$tBOQ=<8;Xh|v*Gr^ZJM2M33QA4?R+_iPGc;;jXhL`?Xy*!KH#Fn9@l^i2N& zfnA7Ra#|CfHXZx5^EJ2T-L|4K_dvz6kh`*m-~IkHYNU``8yFCiWp(yuo6SN>HQ*4^ zjSuZQ`%qx+-*(Szv{t`0)pCzp6nJHppKxWoM0o95b3*RY{7Dbl_2TR9hzrSCks7Bl zQc~5EA7i^t9aN1TS>bt+44)texk43MCA(4%#R&RF=%Mi z%_3B}JTQ6)p~B0zJqhCvr#fTLd03%B(=Uget4>*{9CS(Trr$qw@y-UaDY?4MBvdUs z!;yo5Opnv`1O@#ht-zx0rj(yu@<5W&iA{>Bs?~%2>df}8!*?qKaBy(CNnaYWn@UCD z4XTN4LXnh=7*t4FESzR1-u)4o(h4a0pl;tj49Fv1ZbyB%0mIh|F{0yoPi?z~>Zbip zM$O)7?hg*dQA@j!o>$t93u8c4aY+)P#(Z9m*6;Y0kTH$& zr}*O1Ij}BeWR$3zTEmKt#ip)mCe`_Ha66N2Jrvr%6(l-*T*s9|9~y8G7lz7|_WQCFqJk?O z_kY@Ndq2uQKnIf=l0Zm1JvL+RiGeQ%q!F}`$jR@PHEZHvD`t#GH5AROpix=lg1Mf+ zvXum-55B0VV8mc$FiJ%)j~zI#on4swz4CC_t!YtGi#g!-aK`x?pw;@cGUdy&=Hd?B zr)w}dvGET$TIXg<<&IR5W4$`0@)N;}TUJ~3JD=gO(_#)SjJSzSGYR&3=AMf3?{Pf* z={o1`&p_ktBrI+1O;`Aufw6GnO&Ee^@@rvX{)g&p&U}7`NJC3yUZPPd{{}0E*viBo z{Z%P9t^@e!OjsJhWZ{%#)0*rCBbMZBL+5}k>$Iy(K8Ww(&;IULPKe$d-W zmf?l%+)EKNoygef}KzCp%77svVjqrj7mF3#D3%jT1b1Z#@yilXwt-e=EE)S*xija>f8n>?W!5(=}3 z6uI#a*CFEuy$E=}yqap8o&IowZpRbH#*I+q;Ph;7!lNYx&mZgYteo{%Pw~*p^Sx2> zadx^yCuNDIBw>Xu<@p5xPgV;Qc+aOpn};p36$b%5-(fAKiEU_O$~|v~oi?81Be<@% z{CjT)U1DS7cDO#AWND7I+VT}YdkjEM1Rp1KpLv<)m?bn|Rl834{%1}Kxjdk`c`6cv zRWahMs|E`NDek>J&FUd=tV-Qg>x*0dCvZQ{|!3s^h;Xp`T}`qScvaP zrxe#XkzSq0FM}zhKK-uil!Xy3Ru>AGS>c0Z^fJh;!9I^yFwfcs%zdc-G&)U78@v5& zp1fPPe+Y7=bESr=qTgo;mx4~cV#}KUiiwh&pdiTqsicyc{6<1i{r|ZDH-lMoQkm6y z{-q*(xMZg36&kVeao0lyADI>To=A`9D?^OFI~LC`9=%~^I+iLWy}kLfA48i(m7VFX zn`2EY^7?0&JJT~RXEvJ?yQ`1$+-sBLb+TZ#KOOeT9t9-C^ z_-k{PHXBp0h@L2c0fI?qcs#=uk_8kS_-4fX5^m%YqUwm@t-k~h(@kzuZb!Y0NB#5H z+!8PIeAB8S*V`w^%)_7Wx&)&sTX0aQB7NfR^}loK`ICPtT*VZ; zX@BFpBChZLz)d&1e)#8t&+n5wz1o^?XW{3=d%C)Me0)lla<3X`ZEd}@G&gXxgbl3h zIpe!mgn)p!u#t1ZE`Ww79u(5gfy#0FU1*Rt83FI{(QCddMpT9d-0FFCT0~W$%=LL)Ah50K95fv zl3+vJ`Lvs_?dP`<%0FB}GMQY)w8=mLqPfvePgx}tp^v};6ctHed>$|A55MdWw$k(71XnJdr1eN8V$aX^ zGhO2A-|k-d8XrjrfApnTAoWJ{Zu?7QAY&xAeAgH7h_!g=O@ZcVy(S8{ZpQC&kB_p= z{w{xRY8P{v|3uSwH)AoefG4kbl~FIC_!r?;XwxVh%NcdwFF1YdDSpBec^DaS3v7j(d)f zVzT^Z9}jLsq0dGU~&MyaM`D)`8JY|QTf9^OGK#$)p%BjT09wS}&00RC(~2Kbvd*2m^K8@^xyHkK(yaW< zNEq{IDtJFb@xeaI->cvB4#Jx49S{;IE8;;f>!?d|J6*x)+=>a?{`*v;$Ihpi)aZ;* zF_JY_9+RMGI{$W|`59{9zsQQe(wbm5eToAJ_+_8f_qgS7xyv4220$kzzp_S;>n7hO z`(9BM?L7k}+s;e)mqU@6xR@u9W_!jTXS-*@HfAVdaO)|8<~3v~jhMLjhM$H#wKqEG;{dD@7FSe6sweW#dw+dIOBe+<*`>75CVasB_i2Bh;^5LB2X8j-U~6lA_FyrR zP)Uiw6{|;&A&6yc?=fs3Y>+{TdMPioxx%&Z)3M1a4Q$C#apYvyQz-porI07!1D$a6 zux0CmZGqy|`JGdtp~wD2mOEz>lZ*z8QY8gJk={>Y$gAB<-CtVK_h&>7Qm;z)ru!L6 zRo^lMOs2p_Le|etYE#=`Av1AGSrifCFfkZMU5}Al!N=dKZwo&8`?injA6u&dGjZF= z3tkjq%nt0b#}CRh(C+8otCf`to2w`5l~DjMqvLt=yF~4<%hUJ#`Eq@`MEiA$J+TkZ zqH*(MY7@Q7^XzS1v3AMbra4*6jh$I;Cf==xw5={gQ>cG^xMGkuy6tl);AI|T)gD>c z2?<$DrAFXFog2K+fD1vXvGhp04M~PvoD1Fj@SxW9-jy{;0fX0%UR~uV!sp7J(rHyg zQ4`w6!@4~8Nkd;@sytN{lhmvT*ZAi>d*saWJgK=ToG?qip~tC&tNh`9TSB^<&RnUf z#pzd(@bS290p}Su9H*Q;DEj*E$0Gk(;t~tR8Dxyp)e3v)Vp1R;WM|f6kjsE;jtcol zy{F0gV}U|hCjvQGpBFUZ$)BgmyWH-EHl!a<;&Yt>0q!BVoy@ieq3n0!F=<-m*^!bk zj4p$`fMEQ*Vru_!9ecQS(44NSkq*nLsjCT}qt*QPnpU^Ws)(0va-@g;pYwi66ojx- z0aX;h2vuHz=1zHfa<|e=+`)^LxZ9% z;OWkyjkW%dRoqV@PuhTPipyqLm6TXB)mSa7)I;U6<6(Tn z@1}`)av^2Nb>VFH#-Y_y4k9PG_A7!^3NsA7xUA@dZhE?-X8pgEen?kvez|XHiLLyX z*NY1i?Gq`avgQTB%?!#*M`wIHZfC_bf=2u-tyDl=T<+Ns>hF5B^}vx1hpQ z)WvZm$}s9n{PeyN>Tew2tF6Ltq16op5#UYKG(YD=K;X3+ER{Rn3`S)|r~5-(dJ1?8 z`(Fa=#v)|#Mac(kNnz;ECgH$q;9IxLO*w;4;kYS)i0*j8R zzsPt|mpSTUjk+sQf40zur8GNT{}!c$EdjPBWoF(bEP_CjG_K^?MY|X`zIwm;5a-$E zM4UqFFlI~6x%S425@OM0G?WvWmu=H8wiP(+mICc$nkFdES6upNJR*gZ)=Z$1cV@1E@`eqq@&;B!fDL9$b&g{9b@9`6OapD4R{Ux@xmir&~t5Q1J3Ty3S zoSSdVj0LQvh@OeKi%*h%=u%F*G_&V09y`0FAooe0)QIu&$vD-;a($; zMRcJtTFevHi^m_fd!Bz~mPNISQbmhFbz-~A6=g#erIj90FO?W!E)AbDtE`fK+SIA* zpQI6Kgh@9mIwlElHQ@27qfztM@LO|hVEvG5tFy99;UH8}caGcX&}T0G-DhXgL0GO$ z3L9G3=}n8OHd}!@j1a(UoDQ3*%MnvS@8gp{UV1mSqH6V3g-+4pcPSJe!mLnq zvZWfi$jn-V<0PY@a~-=$&NJfE(9!WCuSnrBkAz!lrzgzxeWVmx*q{bsx}z}ks#}q1 zv;W^}BBMe+Bt>ciLh67|&`*W5z6HmDf8|gk4Jm^z6?Fyl4pmG()|RP>_J+8W=G38i z6UeaQKoKu9JSY`aei1CFOqXwV$O(ASBstT}90D?2%3&!^K;n1rkJVlKr-0S7i-|?W zMhGb!g1o5AaSTS5ph0{DGDO+U&bagMQgYi+WSPQa+;DqjW>Gc{4i*l!!5Mj-<2-y4 zd17h^4e&h9t|&3mP!Uyw{GihI7AR+9drUf-8okS%;bqO`MX9V(Y(j!E2g^cZ>1zvv zml&@Sif)1y&)R(&q6hjf@T1-OK?t>BX5Cq&$*zGS5mAmlxN0yMp^+su8!W z>>p}Tr(R2SA-f%uG7jAH9(gg08@e|y@J?M~pt~3Jpr0@>TC3>fV#LG?Tx3?Zs|Stu zT}~?88$5oPHnvb?m?q@x0Ou~VJnB0}io&?pVkQW1lquyddtRtU@In1b2!>!&SAYD}kmHFuEn71q%39CIaso1N(o0&@V z!ITunE7wwf(s4~OApkg&iHrr`MG7&WF@PcU6x@ZCY3+IG}JVvG^JRPF@RJDV^C;&TNF*)cs}#RX2Tce{Qcpu zc?5WPk*|N)62k{f8A8$tsnB7`!bG-{r+;LUpowaFa^q#m1KS1YM@h{r=88$~JfS9A znWm`YZyduQ^lrZdR+d=d+S7(;v#R@)F>wJ!dwJy-L_KdrL835@?XcD0%2X7;R;h69 zg-4{aH$%8%Di?YEpI=VgF~07B0%QrXp4E^@4KB69k#r)V+mVg$ zi_sz(YK)0k`NxMC52k88SwQ|jwOV)*D0c-ExZ|bPxWf(*F(E5@ae!^E1_mOOc>hVU ziZn{XXbAW{D(s%v{u-=wBl69;QJ@Yjjkyig4@xSHLVFG7eG^zcfeQ_|FgAFo|G_L^ zNtsk6STiRmBo5Ci`k%|g+Nvo6jCi%9$?9_|WM4x`oefCIKa+OwJG?UV-sqySyK*Bj1;9chPgVK( z)(U?kv=7~M%k0LtKPf+ZK%ItC#$v*dRCM5}yLfL5CncB7R#7@5&gn3fH^>!?ybMruMdMxhYxhWKf zM`8p9-Ti;L*(%%+nD_ZqDzEhSH#Ozwox-l*2YmFI9kt+u<>iB!j0{c1XJ&(5AD!=> zCUjq+f_DfjP^D2~Bsv^s>kJKhq#(E(JptpBd*8+7cGqRQ*3kRp)q{~N5^L)8z{cQ( z=fZ5kJBN{qRz_boDT&k8Sau|X5*ZyB=#wBMwwCiZy9?XMX;E8!u#kdqyEl&axN{Cv z$S=)M!^ECv$)}*s7CzCr^z0fVLLO{?lo@`Ev=L@t@B9$t-`hkk)H?(T@_7cgq-Rk# z5TW^HwTkkT@#R(@O%87_<6HTmm|FS?6M;>y)Fk%-(#axAT3sliHI6Ji`8 zSpVh_As1WUevm%>8A}UPDotbEea}=TGfubNRgw-;Q?;f>*PezfE3#^$k1kJzT{q#T zpqA)%{cX;+wZN27ij7x5{jC8~y3rH3I5r>{>h?rj2tsncKk}Fqs2|V9Ely(6?6R+k zEJg0Iirui`LTaly62G`AS&VL5jVJiwtULuG{;CrBD{e8JdZQ1EIx<>Exq|e6FFssI z42m9Wn>L#iHvH??da zfoq*lP$chlSRYVvf{6;&%(^lqEH|HY+~&|>ahh}Ns-VLPh}bIZl#<KGF#V4DD9+GDvefNk(Ml)E%#LMYm=IKhCXT+ThAtbmK(#G0B zN<#!-Vb)p`Nt=(XGAvL{W@=bB6I0p^b80>>k1>uLl?Gi~RiQaCEd)fmq@<0`^}~_Y z^X6%A?A5}nvU5-*j27%#5Uhgx;}%WAK$LQB12H*8OG^tIMKZR?C@Q854E{bzsw8cS z#Jn3@<#P*csE|}51*GTVJ-lpJUCbek?&9@o+zD>$og<>%#=y3%=)#}71T$q?ii6mf zOq+jc1^g(^4~u2p%NFml*H;s(?F8+m$~Ij1k+KAtbD*F=E)WpS;x@5*7lwfDoB0wnXdjM|P0?)TfM&l?_{61odBx~jkms!N4$4Kug0Oyy7H5^b^1318`1 zD%$AD|7@h8zFJz4b?kO+J*=r%|M#MafBnuVjmZ2dqFhdh{HB-%NF^!m@0UWX+F?{s z@#Q4!aeu6#nn^3{pCFA07Mh;M0Ler~p*AK?{XmGA_QK5n)H>Jz?Jyde zPr!-`C&nJA9LXe3o6X%4e0SB67q8i>@GQ-pDt?6bk5M0D`W+{p8}nxK%MMRxKFJG( zq%`~nT_hXygP_$6tE=!QDz{M4N5r8d5H#`Qj|!){?q|x14DYCZQK$RVeQFwItI)TZ zicD$()|DGpp{$(8Ww|IZ-}JJqY2?V1Mp}y$Y~5|cXs|B53!!8 zpsNUM&B*+RtT_GlA)k9U+sZG7MbP0b>*|HshcB{H6I8m>p?;AgpE^fIokfeQPf^m! zP<;9C?g|5~V~ZB#^*qs79X;6BJ0Rh-ZjZQ;ilE}J98;lT?i?dc?Y_ss_I)`j<)t`I zQvvP7#S|$asLub|sp;8O!~DT`%g&HKOg~7R)v~nkPu9TiyQVBpL=6-?VtNI9YzHY7 zoT-y=APQ`f`iEC_%m|ZAv>1;km$lOz)R(HNbb&c?77k^8fHW0)i-I0rN5-BNARnys zlPzt8F}@0phE}8y-7@~X!mpjdn_h!*Od~z3AZ*pQqk|ek7=YU3y!6(W&E>ek$q4sq*$DS_2iiL)OT&=GM7tGZM&E-Hn%{yk*+w2RYNp395}?&qP;39b z=%Nf?>JUgIYgAoUVLTPF9efZ(H=y6`k$s}Z@@}Wn%$IJUl={F)Qz_b*e9ue^8aFk9 zt$%e#hKUZ;&XQLNET{t#A6Zb&I}1%((#qL4%%3o{d!kz;>tqrJ%v7TnsVdLr zz0WzCaklpx{?$uGr%0M(LXR&}_Px}KRL?-^uc=FHc!s0I0Xk~)cdZ$<(}h(=YB0XT zg|UMD;;@qI0RIXkQbRWuHa-#g;?7J#^}@b@z?Bu;DPMavJr-%66q1zjji{mSUEs72 zg>DAJ)dmSHbPg7K>J;Pc$pdYhgG{bF%%7yd;wUs&@hiTJaXIhhQOd8Zk%?mJv+p4H z>$YC??)3+AeT65R&6ncL7@<--u?29^kQeO1>wf(_1H(2*^?eWMD~`V+Ql#PO>8C#m zeF_sUf&`4WVWLiGD${<}nIERt4iBPqzP_gWECF~H{U5eyi{`GK+>V`%5c{w)q7#$b zr^PqxFzK9wPyJXg9DDD_I&wrUz7(YUlsF`?-&Y=8hkC6%=p-B$OzG0hY~10<{uyB} zt>!!1)a8G%JzUIA0mfe5bkQ-7`PeWMqV1%yr6mjvd8=8*{uAR@8j9@lqEnvi^63|{ zvfSGWr3&M^0tk~Na<5oPfc=c@Y|hO8YD0A{-Z6OSD} zb98iLQF=)U!R_RuT~&H@vdHT6aD*T|r@I+>$`z{+&)AR_mZhk2=YN2({6xIvarX1| z&%sS6S~cRTc&Qx|yP64x)b?iIC`}}sI#C#{i*{2nAd9woT?8@l{%j%kkt=tO;vdx& zp$AOH5G3%ARQ&x98J$l7S2~)-QvprIBK!;>tj7?#f31_w(M^XLKM&1u~BEPlCoZ*SNCZ3??9$=$IMg5^FnGG;3Loo1BDz)X)8pzR*gXZvW@0 zJb_a6q3{>;kAaketpM+rLr1*~&iVp_n^xNR!m*`c_7tga5-cgDO*pQ4WOHjmKma6^ zsOoQl7{o|~VA89RUR<*sZk4U3u0E%wBT1?+&xV=v0xKDbO`?+OagnJ{SFD1IDlOo2 zL?iHi*9;`mcQrHoKiRCBEo>Z`GVOh+Me zS6=C{W{I}ZH1$nx%jLn;G}RkFd;QqRPt!5vlU_~J@h%@erQi$QFt9+n^ulc7W>c8j zBofV$9}_c+x+oa`)YXBXd{M>#mo5LTTmr-~!kTe`J~5W$u@^zk>rK*}Mbe~y`e`ch zl&JGNm{gO{!KlN^himk>&24fze*EFx_}n5PTz@A9v*2NLDr8^l6gK8Joj@q&4;*gO=S?XIV$O;5S`?@%#)E}fnM>j@mH?-8gToYigA2c#&F zG{gU|%;7lOMy?kbTvJE^&a16<`bR|>d@B26F0tk|192twYbtVNWMJTOl;v0V5p$N5 z&kYqgBZcXS)rs%bt3Rcs%|7}K#%|vjy+tj>jg)DLYm8&2|9J@i)>xDpV|re(2^e)5 z^`DTEM!6ozCXcf81wFK&)^8xURWuy^FkMz=YD)ybD}9uYyvqNg@gKyAXw@k1gGPIn zL<@Bu(_L$E!>vuPz|po31!mj&_*7N?s!@4fUnyd`;SUkvQE%u!mQ0fiXu_Ayz1HpY zmLOv2m_deSa$B57g&{-Ih^i9AqDKm@3JhF`ZW$l`?9lxh&LnPjPz9guqA*+(14S{H5}l&nv>rAdG_Wo78;CS*{VA`x#**@?Y- zi660j-}zn7a7I1osPWrUo3I@U&As~EZPKOor~-H1cBQ|2Uu5Ed^AL4 za~j@pN3o;Lt4PW3ZywJhF#+R}^|~~&&reUPM1{BJn&NZlCZEosMQ;9fft`5rK(Q?B zVMM;$&J6^9Qe_zBTP1{$8ByTi4-dHoslY^VrAe z(!Wj=(ZvqtzoUx@?~#`UJX8I{mQMU6P~%$cmmAl_f-avVtsM1arkSy&lw4lBq?^1S zw1ORu_@jFM0)5EA-{nuAmV!pTOjq@@QQZIoyt=;lw1UTYI{`|GwV3Fmf(u!jjyw0g z+4AwS9epR?g&mov`DP#h%Fy=%TSYT$$gXXk7JS6fbTK%!0no%>D#DUe`KY7VF z%NhS38D-nqe(qu4kuWQ88xyM-e~T6HYG!@1aGOBn6HJiPiV7QnlZ(9{#|mig-f5{s z`N^B5N>gQJ-s7d<@W*slq+~Hde1h}So3y@wS7_cj-t+WhK(a~3%vF8w%@;7aN|G`| zJrnp#-Yb~ZMTb%z%uy#j`)`l8C#$2+U1$+F`av9rEg`39Xm>IHg*u~?*Xv_i^XV^{;=JxD zl8_)^kKab-i4MzBB%gMWdYN~7y6tM>YcjjAzJ&jkiu|2?s-$~Q=`{*Rgb5|i0+~Mk zgE5yoC%0Wke6lAL|0H`Z+Le4|qReua&nBqFiU^C6LbC74VY$(dZo5GcSxQaw^_=j~ zN}T6`Q8L<%3XJ1(YDPN)O%w-ae23Vi78!j`7e`IKUCVNQRp~T9xJ_t%Iw6_2CfTSTOxS!^0diSSv!C|;t?{|Ld!^^>4eS%i>4^|ZXFd{Y2 zZ04-Laeq{IrCIKCqDrt|l_dQEN}{t!=db=;dVqeiAbNEpT=f?;$&zMx*ywlCYvrup zjar9x)Xj+T;~ZPYY-yw=Tx$qf$o?9N%-3rp2vk0u8y~+8RXSy(Nk7!CPSmx=b-N#< zqb;+684c}~APJ20JwI<6nTXOYe(myF=b9=6+WHy`JRCL@W#tJR^!k8$GQ@8c)!Cw2 zA7Ppmylk(XBGJt7@nt%!2L24U>Dsg9Uj*_gxqV)7x#s~N4|Z!a6$Sq39=7Z9BNI;L zx2P#uY)JMSU4CQwDhc%8n zt(@d|jxO+@>9$3|bJjEGOEW&}jt(ii|8giTX-uQ*(F2iYH9Cequ74_gj7$1wwVIOU zLH6W!`X@!nMc396@cnuhXl-$Ky!(SgKRWW;_3NmlrPN=DSn@K{^CsDmfWEk544Yk*t1&jk08=4ktcQPKi2o{q0Dyva-W*z<@~)`D$b$)$*w!peBW8XI^2jQ!p44(9 zFkvV$u*8Bi2h06=Mc>q-apsTvw$EUqd>^zj^z76#oxZfs8=FsFqV-Sv-j@;C?sY#z z&H_U4hAzAR$Ww0voPA?Di;RX{-^%T;bQA?9B?*0F-|^h9M$($Q-QFS8x2cIbKT+~~ zFG=*fT(brJj%{*#yf6Y2?Hw&w1wO`K1M(lwc=}fXbzB=?1XliJSEam->=K##>7fPO zh16e7a|TRFSwqOnay9F}#-0+FO;8xi@pRx7@p7XqYaDLFu7VyczMdFQ`d3j(a` zh>A;}%uD=$utmn#5JyHq>W!r}1$nL+gZJ}*Lug6;qUOFF%i`#OJG#DcfbVpClK>Ac|i%Y(b^{xLMt_5I>U{6JJ%PX9c6Ty5>?bJ?iim?`Bn zk>DdIevfClRzowTKIl;3-s-{Cb~^-`a5tyEZwe1<*759*c5ADVyKvT}+GL`TkU zg*h1;0@3?R03=^%)A?=oOkB)^y6+I*JyuyaSz1fqdYU+4#^rvG zzfKmyra@I1r4A^$AKIgb?e4)C7-KHa6u>9@Ux85WfaO1?p+omG8DQ)-x_rFAR~64z z6m8@o9rU~U6&Z644UK<2W%mZWz>L=Ali6mnsZ+rotJd<$uWuPUP#Flmh)VoH1G#mE zzj8Z2BNz>tiuzUe)s#1PG{#-qX5$U{@pvQcgePX&w`vQK3{*;yms<$~Fbn+7SRg`f3C;?}~W8y*I0O zD8y*sa}L5e?Emdbxb73^NIi__P_Q?)N;UoiGyZg^onZ*g#P>dph>4GTq|1Fxv8l>j z`_Pw%y^;3Yxi47Q4wc2`P8@tiqaO6AOQT-IK%?@<&Hm+{VIF zq5Qu}>c2JAFqtCfu!>$kDKwH`_6GATXp$J)Vu0Au5R}Q7Y;5ZrY^U><4faL4@dw#| zF=Q(cPEy?MZ$=cnb`udOlPEN0jZ+0=)#nQi7HRg*B`h`mK3SeC>LshG)*&g>!ViTsTYGq;uz~4D)_bzom8X zue34><%r5>2t&Q5s0UNBjF(OT3A#uyPbK|@I`pn9k&bI!`C3KRNU?~q1hBrV97A3B z7qJ!MGNv0UYUw{OoLVPWUfLt9R=FU7K!nzwQ*_8~09LagKh4U1v-9i$wvpnQacbMv9~9JG$==z`J9U}VK1-={7S3r|Eq%#x6wb}Cs_Kmdobp=yIZu23=qunCpgGS9`Im*- z!P#hj&snW4iVQPZL=psE-;r~#lBSGrEveoJExM&1lE}{JEg_)5i?@cp1%Xm{Pc53tEPC=Cx&rpU7j1_L~>kWw^dyx(9 zV~fKL_p9nxy3W*`|7{$t#8tP=Dlls1$tlsQUo=G2QF)QP1cB<=N_S@%#_pboJ zb>zzcA|URZuKrAc$dIAeaKXXykyh=t!*+&v6O(KbQx1?C-rwbwOl#~;ecMx>Ri}z3 z))?LJX=EAUMvB2;acKGCJTG?T2hk4tpGLgD1^nF!vdz2Y+EzGVsK3wZ^^Hoyu3`8H!g^8hr?BG z9#VVwXSs3Z=;cN`Q%!Wt`bHUXXJ=nTLG%TTNp8Zd$og>G47;p}pH<(*aO$A|5w=sP z(b9mm+AaHzQiu~%EfCJ{i_tU!!g7|Cdd7YQLf?~Tva6r~nK~=l^7F>eH|)GFS{w0B zQb*m&-Hs7$Z0%vVcx|>#M{n!K@&gbjw?`dW~LAFFXUUd4p=eK{vUC01ySqVd7%4?t893^Arboanu;i;s$>$w zma985t7XV?70quk0G-}PUR!x5+cwHhkv3JCC7q=-6^DcxBI71U(SsE@ra1orG3{^+cU7jibG?*8q4$% zI5iPw`%abHQ820fY@^SPoXgAi-WKIE6%czh_alhOa~2JGFnsD2nbmk$o~JCK3eYh$ zU{R4QA;-MVqc%aX_Cein{~_K&+NmDSZ0Ma(b5CR6Z7Om>fcv~&wA7q$s8!1qzN8nE zgu1~=tyCDzMp?oa`Hs^`k3_Nm)WoAq4G8fDo9`dntQ_2*FJ%~q zzc_Q>|0Y_-fLec_iBtbdP|lx2HDt*oJHrw-SN5LMWV?Z#^Ogx0q$40^e2|(6L&4f} z5Y~^I{Cp7AmuuH~i^C@SnN{X1Aweyx2p z{Jf*=J3U1L`VGE*{I4#^%gaNF(U>EA54cSqg)d#q$h=Fcf5y0xeG`27-NE?g-z6FA zmx6Ea9@{5?Z17=+0~zX2^XHGMWp_Vg1ilq%3AP?z<4eLTQPJ~Vnw_m5j2{BoVh|`H zPo`sU3plQk_WtR!vsnBOAgy&l3zlWUNxek8q#!Y&5=>F{RDEB|%~4}DO|>SsereHl z@tq?OID>OB6YSHv;*pxQ!cd7$g%=m%D>OR-oLn96znYOSxs+GXpMFbmyV!QJ1C8?X z0Mf(lzL%fh5DxPG0n(phCI z^^Q(H`wd84&&-`|Z8;>`cCP!f;cX?Y-_cmKwA`KrUHr8rV&)IFAc0YjVV@MY-xF9& zCwrSTqQ13V4;!TwziJlzN%;M2 zc$aGpgM6DSH}gfCzmJC64d&mkXV`)cXXK~*^54>Y?G|*r1y2t&YP3J8QJOAjkWdKOYhARB$p`ejLgh zX7?Y%7dCspp(RVe4h^3br+6}jzH-RO=YpQ^n(T?D>^!_uGblCXO@Y(;zOpv*pXwXF zoGza{Q2Lnme3{|Kt_**_iJ)~C{*d}cA1HJx84GWUYzGBe7l{&LaeONQ=lsiUwL^8T zuZ%}O@}!QjTN-KlMwH&{eHMUP^>MsWaU<6i*$ui$6G!6{5K^@A1<7usFTY zm2+Q?VsK*2vpr!Tya3I(saPNJVNCP5=q4;XL)qiv$z&#Hz*m{x91B8q70OyaBmcZ% z&3g}|XNrq0+@AQ>`1}eRZ_(-kCnEf$`iD2&na-3b4b5taS6Qm`sSQ!4$?_L#aEgfu zhzeb@LlC)+j81~>(i=T9!{orAnR)K>zt>N_=YgNLd5YBD=^~+J@ejREbFHdtPYH}F zCl%HGmcc})p>{2 zK(YDb7b)4#25V9?-oPCq5E*fG{+(sO3tMBZ0wEw&FW_Ip>gW>Lnq%{0TV%))(YZ0lq6*=RS%%eIAX z<;NdqZ#wRZ4Y#l((4B9dQCly+h8HwZej^K3ZcpnQsodP|{#NKw8hWq;m5*rLH*Vaw z%FSU+7l4 zfNMIsL%mR1cWYy0-0+5AwTtjkm6Fn=p_)2HTh-2qpYKq%)^$y*=eGWH-+2|6?{IlcnLDHrtf9daM=zIv_yi& zrS!Y^2Cp89Jj!o;RiNCxy@iI{x=lRuoshOj@U?Vx4QXczIHl&*AbM;~ z@%p-NKP9$Tj<`9T9+7nncX%F;2)wu${(+jJJG*=hGh^ub7@fY^6=d4_bz4BV)tPi+ zeI1rtbt(6%}eR@`u zW?ZGB;p)&8^R{k1zG^c0mgVc7(&4d->U&mfapxd>L+^e0t!BlbO_440&&GRTh;J{X zK_k(9tGfkfr7Z-*cBi`RGxwP{P;+>8LQ|MH>uO7DJ*#oMY1@*eN9hhvhjC5ufwsu* zXIMZZVVA2NN1r2M?=Q;CXs%?Xa~w^0^c%l4ZJSCkk`Z;>R+e;}CcL;DILq@W?-%@q zFpKc!`(LZ865Mb>PxJ}z6Jw;?vLVd|&5G){5c#6yMGQ)kfF9L1@n??X-QHL)hoTx_ zQorYo7+~t)pLlAa?#hfi-l;`-4K|xrr!&Fl&5+7JcS2dI9u?djy0;Is%rl?)J+5Y5Ajb&x3@Bu5BxSlM`oqj$XstO0KT+uLWj@|75<6d`VC%Oidb}q z`!3>Wl;YWbjpCVN)-#IDqWp2c{i)6=-HYa_eDve3OS+(QcuWRgPo>|ZORMK`i28t| zTpIZ)l#vL@mEr3I-udGx*#xEwvCz}tfcxf5Pdcw>_{`2b&6BmibvJ(9XLsU`t~Qod zz{SbP@a-@0+%k4$7iTpwPS?Ev&CfY9PvURFAO8+Nv_3!cr$3xx1^Il(Zh0HvpK!&o z?t5_3m}IbljV{u{8@E=_X5mc}up^R%d53?+N^C4Ee;_(K<0CCezH^ z`$yx}>6UCcyiWPQ-^3dGtfu#!InQNBu{m|B(x41cpMkqJm+txeF8bFSwpXM+!eb$UxoT@D4if z-^=lf^0fX)KMHu!l)WVPO=m}gZR7H7PCHkO(d5USF0SpK&+Hr9Oh;XL_+0!=YY=66 zHvvlOaP>qbw5;gr_Hm$)3j3zs4Os<{|2bKEVMU~}aKGGxNKS0G9V9IbT9hi-@$q)` zgeb7!MYx=ehpfnJqFmOHpvft?nC-yChf$ha@&B$nq-s#P(O#22;pZsgOp$i}at(t> zWiH*jdD}kW$<$LmgC%QIe4d!Gb;gQ^PHOCHl8T;m;{3I^8H>%FpEyf!5Dqb>x;AqY z*weoXcV}-Dq%cYbA(REUQnUS%OIYv}fxBtw{mX@e^YtJtntVt{)>`YAXsA{IJ7SE} z7w_mB-$%5?0(Fg=v=w>gElO;GJ7~;#?@$O7i?xDjb@Teu!aoyjyy>lY;tc*lHD}^! zmLc5p6+_uL#=m#eS+@)?f3dT+5?mZE$euTK--vdWu?L%KMfPD6rwVqOIj1MvZ6Si( z*l3R{3$#8}Dmg|J&_zF$*J3L~=3O8YC#P=MTL;}Mwpsx8=tBiAAr z5N2g}=Knxbw5NDgLI)`+iIuvN7g1IPK}}(l?=8(fWpOKwk!QH=|ARe; z@$9#5bx*+j0iT~sWEwcR^3}oRZwW1(u5iGj+3eL6|JZ0r(p0bp-a5zY`1#zAIy{AfEK>jpnwakK?5u!Aj$5qi_1V@+!(b`R|5b1-8j0T@mJIG z%Q^y!=#0(x1NZ&Tl1%TqXxWFdaj!A+g4G&@o2 z(+LF(e~Nt&&MVlZ;;e3h*W5LKeT{8OTsDOjv0hG|$JY3LW+tORsVt8z-ZLdAbTFth zhuElNB}UPT*~8%dYN>!wIaa;K;SC}yDu52(Miqec)Jj9fY~lg$kQ$YzWpjwHYJp@;^hjJCf$ig5=9$hc93B|~ z6aHgBA#-OE8$H0-D20k>5ykKBdi`R!sbT1EgKHM;EvZcDv+2Coi=Vx7`1=~fw0lx6 zF2n|`F%J1wQhQapoa8N-a&@II0RRP>6#hd2O}d1C3s7!fztWCcw)CRf_3TZ+xKiRb zsH?gwddG2}Fk(ME&+GEtD3=$)7}fYgwTrA@Le13ySt(yC3DQUH)PF34&c1WSYEvKqn4|h`jLb zv9UUH2l3?PJNn7`#^9kS6_#mop-j8hpJ$zL^yAgP&r8RZvaU8;NCEz2tuJUN`VPlY zNp&DJ8l7CUn0i(@mlL8Zf8c$PkN!)UXtX|Wn*;dZC*xLo9_8YM?A+>96Q^x~2rj)R z{El^JCD!3toH&wYVYVo{A?gh5Al#}4Ch|HLdJ*G38tp5$WSS0f@*I}jHfQ^|hRSQ# zhe3tm?Q^;QAHW>R?LMOJ_6FT9mNgg*Y zd=dzo>g-%R#M(ksIE%@8rt6{7e7p~a|g=XBcwgfv?x*yZXhsGAvopTzxWfnL;`;Uhj0SsWJa*@1PH|<5tGJj zHoZLN@}Su3nw3lL9ubH+CUFWSkHFh#co{@fUTg&HhI!U0UK-C0GD0gNVYiqSiQDGW zKYqTp1IxU@LE5KbyKs@o^45Y;Ctj51-K%^oDCfB145&RcN43zJVHU_z38(pzRxsgO zN3M4_n;cgg?1l>eqbb4U_9W(vtuAk=A_uP+v9?A&H>)eUC2U1vj zxG#lTeKU03bkLV@l%x%#R33ZrgLh%WjyxLArabymg=BB0X<>7QZ&j>#@}Jz zF3RMAB)b^d__>DCF{yPKsxlXQQ3bHDWp;j9Kv5&gI&e)MeEqGCS(I|6Fy0hYQRvAH zFtpeo{<#+-O+fyV=iM=h@#n#JIxg~aGNlbHILUv9n<2qW;9DAVEwNHB%Wy|agne9u zT{7k`f3f>2_%^ey$7tWei`+o2Hc5Foy=`gQb9nu#TthZJZ#-J0$|&&a!w)=zjc?o&|eSAF6=&fSI*xaHCZ` zYW=hDsW;hl?KKKUKx!sh4+}v}dUM0roxQqjUg4qh`0wbCHY7$HF=w$w5}R@NesN_aQMp?rHRhyNz}Pw`sfr^Y3{R%$%%(uHrvR ze@Jx?9KK>j`E(>K<=*6cYCX1Yu{{w=c3V)NUG;+!38tk5jvm=(F zztw|r;>P5pHhMAk|E|2f*)MmKULsLYv*s#V;1Y4!7SP-!wbNAsy>Ff#P_TA|0pVy| zLWlK5@y6cbMVhT>ECMk88O!BssHk#%vbFZ$V)bQ6x_E#3P` z_!kU;?O!&^0arB0zc9Q^V-~1XMeV93B(pO@J2^VgI8EovtTK|ok3v=J;- zOzqDSdu!gejb_79XUJ)qqUzB zN}ZgV+8xG;-~6>Sd~@dCyVA}jTR%01&z~-Yx~;>jj`CC~`mUyKY-9R5;d|a%L_8iY zz07`9w!Y3Y`u9`SJ54P{B z0xB%h7SvB1N?Tc>&R+>zA8cby9s8WWh^vorRHmFtf=Qf7nf&QH9Ak}SWZh#sf=*_g z`LMY1NDFXfq1@PbY%MXkJ%Y$~ER1FB->N_W zxe&f&$`1H3=H^O2$wt2CqS{~h$!|OfqMtJ*eg=+C77`xM0r3ifam&Cp zUQGCiFGf8&{PzT$OvN0nPQsJNw9lB!EHXS!_Pe?^IddprLTxW~mDaPlWpx*tae*(X z5lKun)zwQ!stH_8P8a5tiaA^Fii?Wu?qJ-n=MISJ>bym4W^wx4F5z+ zO6ZreIkJLOhP*z1mf+y;hOu<{+AAnra}y<@Q(N((T?1P_dZywNdlBBUrZ zzsh|i+j`{o)fNX+imC`gY;xYgiMs(MihQKRxqfOhgHK>xySxva?m4WE~`~vbInLOElhQ!gznI69O)u?@!$l^ z8W}`**dB7@C0oxv$1{z|9px5LOC0jD%5va*cuI2m%FWh%FjhjYb%+llZo*CRTl$J| zxw*C#`#S#AnYJi0|E9Jna%-O|R_Qmh$d>#pgS(|}8G|jn=U=-cLv?I9(kghmK z;Lw{ciONsHh|+!jV>D$*JMnJ@3f1)|2i}!e6rs=?A(hZu2O#YksDGF4(B{?$nt482 z>}VOFm2y3K$JsK;(zSHynfxH20xs*WJZOGEqjE+5@Xw03$p7f12vKx7AWTXuR4@i= zDh*;kb0T)}D#BQ0^ZYX3;N<$2=GtbSoIKO$y=o`Bk&6rV2nVZtX)SxC48Zhk@+i~Y z^$aXXx}qpGdiu)t$gGUE%Uy51iGQ&(4is8#HZS*tHd?XoESu>rOm3BQbW!W@Hu2#o z4R&fb`(LD74~W_N$uu$ zPhSvj4fwh-TS(f`Ivr9%o2m+?C-(-ayM4q^*Ssvq0bGLhe-qKc8e&i6uxhvzd8M%< ztX{X|ti)&*zna>b!gmqhNX8Ug(y4|y^_LUCbL+OpoOmP$hw0M%L?Ah4(&_ceY{8ZL zo`>j&h5Mp$!y`2!DruJVFMO4>BOX>5=KVqm9}VrT{i=WNNA?e;jd!rD(-8XsX*oF) zU9Mm&3>TBzijOOiu_GgdDW_nY&$K;l@!`UY6#^Yo@1 zs(kzl5Ab@ho?%)`>^}5lh@S_^n-ti6APOf5u*?e0J}SLb2*L0=%L{TT#sZO_G({3# z(Sc#i!Q!%Ul2D|$o}zg&y3jBA@EPSI9+7`W=nfJt_n7&7m&@vEVO`@)foRSO8zMOO@YNpa4Tp~btqdN~TGK$3f(EgDt?LArErAs637s&}X zSG&OUtdQfe9otY?FrhSWQaz1;_Zm}ROm;|hTaQ-fb4VSPh|8jC8*f2F#)Jf z{0fl7PBuG%jzKMm6a!ull!RfL+_1`&0kF>3c1=_iYY=5?`jvP!b4iDA=Yp=A0aLIEe|0gn*)aB z5z6pCo*q=FA<4$<=DZ8RL3WD^g(MY6-DvQU;eBm{Kk+6-{cSwmD?-TJabP0?95xrJ z&fI@^GvT)%w2y2qT|Jg?nzhY^oNpy+OdEgxxN8?faqW=~9K%5RBu*y}H*u5mXKt~c zy|vBm+W~$_#m!Suo%v1po9PwL3OZ)53SA*7LHiv4w4t8}W(Yjd;>LpFw$|?^I9OrU zS*lph&Y-4T6$hKm_Qe@J17GzcI|mr?WDV(mOgO+Bw;w3W&1V^Z=Hrxg=STU{I%WT1 zLxCFMPA}1R?E{jxNpv8u`G%KJ+5r(UaT??RpXPSM?ja0dL(8b|ILZV$vAM#u>6QkM z+xR(M*5Q2#7kcG{xr^4EK}$kQmCmt+Al+sD>b7B69G%OErA`wklSFv-vZXZ6{^a2~ zzZBfM5SVnGtiZ2YvW;a3+KuXm3K7y-DV*_M>(cpfZ1ocv1s~8DiA_eM&jwdmg;2N# z%Re_YJyRgZ*DM5sWI`IPLQcZd@PZwTnnCq;n75!{d?S9mM5`b>M1SMd4eMp}P81ez z7AIEJc$g{_?13sIFw+_I4XCSr5l<9m(z8}CL;33J-y*#7ov)g*GND@XL$WdS2{TO- zS7^q!U3?pGdp9o3vEuuifpi_58Pl6(S{z~)6%**Dt7n}Eu z1xK1~D#(#1UdHs{+s6E8O}5c`R3F#epp3|-8|0eRH$B#ETqiq|bbz;Tilc(U6@>jT zZ3*PH>|~ZItieFh%_#wnJMT1?tyU{NFaSRoFZ)lfuB&y6^!KF7zu|fmp2{t6p%8Q? zA_icDDb(lG+>FkGy^nIi&Ki@@DDT|olb_bWw$9Yn+LSt}7LS-f{NJ5&T<`&*9txX6 zKrz(GM2nzc4tC<=6f8-+-l;(8Xq!fU!gdsCdW!(hObjx90RuT@*yY}6-oF>rEHxWeIhf{wfMyk8rE*X&n_Et|v#mYo?$4o3d)HwHj4Zp%kTQV>-)w7PGGqs z4N^CWY+17W3bbl~m|?j;hFXjMZ|B!jy75VRyfcQt&Ksz0gjkNhv36toN2nHxA6^8g z{a_<4cFb(V?W5O`c`&+1ftw4sKd*Ez(%)?Q!L=Gjkskg~*h@l)%81f#`2! ze+YpR1;YIMID#HFQ-Z{>15d5OFgxBqh&*AGHSFv-E099Fn&V2$wA3!@>^-l)$Q~vN z0VbZ<%t(VNpkxFP3n9^a4P1i5y5Y6^=97mvLOh9mg=y3WxMx0fFV&l zTs}q*%2DN}_NE$!(Xhcrwg-CQivsngTX;kZZKw$LpqNXNXO{4|qd1Lh(aR(WA^55d+8sNV6;_+#*p4y*Xm$n4!aqrfC)6DndoW?7-Ft@{>c zqg6h2l0Fi=HuF)616=6pPKcn?xdwsl%GJ5j1xwSCHfEH@rx{&%B3#2X4y_L(AqMq) z-(>=nFT<7LP_wr&b9Jvn{a&Ke%OFCl5ywDAm*1x1H1;*`URaJUYGL?UlcgK@(Iup`qOz@;C57eNP*!r+wvCl`oN~!o?dd^uD zsASnlhqr^thNHH~B33NIFj`RQdF`33<(6_%hZZ%dK$b=?|Q4U1QJJJ&1 zcG;YrGeKrsI44xHd8DMzv>hFO%&56bZclD)NB3*UkLF_jiE#cxHxUy)!No(4h(Cny zm&h8t1=N)We*xq*DCv!&gbADnH`Vt7VjTlx5`}f4jnFAb*&UYE~+`C7o z>z^?E<8G3P$t-%<92FRff}~iHD+VUcWz7O0DH@2ViLP+_1?G5X z{G@r``g~R&IPWTiQC_;4#g+29gzxmbs|qLbe|c zXZD}Hd|K04kbMJj;g$pVqiq|)f|zob`- zMKOhXRl=zAmNA>J5he(~C!dR@2nE!<*0Y9?U|i&3>~Y}P)5#EtolMnm!W=hbzG(9T z3ttLp%Ok{LyX1(^6}CKdGkJcB>RKRS}hsFG4wn30I zrGpDz?GExqLT}!UF<;cuUL0P6&kR?bE-wuy7PEW0tJJd-~EKFrCD` zjGZOukiXG?r#pfsTkFE*QGFxOM|g+46rU&3dZCJpA07vWT~!qaS(2@ZShNyRFqFfp z(jU0FcV(QS(_q<83XbU^2-t-XOzZhRYr+P&LqbJ~0uoh%!jxSX9x<3o#?+bzljqzr zgM9o{vWzAxD}y646O0ZfSu$<#7t6=ZKtsxY5eqN?ko{hgLh@#{(W6EHUE*H0BM2uu zTg(jOE2Ps>3di*@zdAfG)62`dEzUo`{ywMrTofeXMw7i4EroY5wq)njVHoutHUS6Y z``q08O{=_h`Tf_Y(U~uIcP-xA;0A|vt3BwN@9t{zJbiX-+_bbbD>wH@N{B*|u%{Ro447U5VI`Lr^m}eD&Ubnc`Tprs!2|yvLmln42PysY{+DYh-t5~1zvp$} zCfy7zo{y>eA}1kutAQ56AkhM;XL*B`>9w4z34wb`>KGElKZuoW?WU){X^u82-v5eQ z71YqsXma0o=FKNir1IE2`-rQ;A-d7~C$!@ca@nOomM|JIvK>=WfRO4+g}?wlaOg%9WWK*pBnDfb%ujTUHt z7X*Z+1}HUV-i|P1{c2AAZ&|LigceV8yr$8)y(AR^BxuepGLN-5CAaYkvP-~m##nYy zI*WMcg>IFM1JNbi|5&-eFbuZ+*8=0CGe)S%*!yPcie?Rxp8Q{``96X~{Zs*x*>q6! z)ns`G|4+Uw;euEKOpTx^3@A#VqY5$>TEd-shp}^|cI(k67b?1}^fFPOVGv z?#f`}>3kdAVQt~Ysd=(K7ruIM9LUg1t@)a(z<_C8vvZPr^2jVyXU-=u$b<=CUk=0stIx_*-I1xL`ti|fF|B+xi^m6xVgP-{l0gz8}=vjMP7CB zlL#uB)`UXS`&#S4PS~dJ6@hEs#4jbx+|X0ld!wo@Zhx&k={wi}kTNlwuC4d-`JrE2 zd*1RJ)htA*CJ5D?P0S4{gyhV0&&OQf+Db?bOa_J|GnME3w>EZM|3v^E2l62*80Y4g zk(Hl6FE&?9C~J4PPW0e!g89O(K{1$?9EFZf9E=ngJ{${#^tnV7lD%5vbY&QXEEiHh zRS?BrF7`bx&aj~>IYpF`2*nf;m_~xHC@vOONm_a9F({%<2!206^wqXjiJ7qg#kmns z-%;H|nSOJDh*)YapeneRNR%uQf~2FQ0PbjYI~GVwk-NKirQ+GQ_zZ!%_Me{$Jbl1Z zpUcM!2Yt8wy7(U!qq8i^En8F`66li~rniTlAyc~jQlxaXZ@5p|%N*K>~rrr~7u zLmPChbUG1KfQKHpX6Y6YLPsOvIw|*|ZxfDs1Q(~rKqhWt7gs@A`_((F_mS{aSH=um z5(x-$3P|}*M=$XXLtT>KfHzW&C!#pvIx^7ZLa(L9t+XIC6om{Rt(PT7erR{7G7@d# z@ku*;dSoG>H^d~RLB>jFus{DpR%skHwP2jz581i(FRQ}rWWEAytEH+~`^fxtmZ71c zwSlnUI0Tyfg&&^^h9^R#%gsw@Ax}E;%CxE4#s+#CS`_bdR@E^f5XgV1PacGm%1;p$ z0qDK!|Mjtq4etQ_3Z0Cene9N>`}lzfgY1r75xe7ds~t?2%~uAat~qFQFhFi%{^=!A zLP9Db*eo02@_hI`ynR^Tm9YAAO=~x98XYc{ z8K=?N^i+L*5O)GSY-F$-&Iyrq{iEl zTi-1P$6XMg`w6M2BG`XTQzA5U@Ki@fdk5%2wd2nOaOFc#7rWUnFRz+3r&ZZDdTYb1 zIacVufl5awDJn_1MDb<@4-&OZ>#uZ64uSMYfPw~vqCQFIFLRpaB^ zgm5u2_b~yoGrpUP1sX-@(_^ET8H?O=zBF+ag-VD@ewH>~ZH@%ex6zp{+-e%y5&=Pu zd-gM=xu>}|*5ZgFHDnSJ5<1y{Orq+%rKO^xaz9zQTRon`#@9*jq@RlP6zu~j>2LSC z5{Of@FXdMlnV{hBSseZ_yp}7xwgeYOkqt@y+2vqt93g;tURz4yxE39xSu^F%d$(e) z)urS9Bg<^LfWwD0@d6TA%{HmD1`{0K;XJ5UZbDR;TVbU5I*ZD@Vbq0z6)us1*RkV3 zp$OVhkgn`A^kr>TVlEHOPh_c z?+a!XJMe0Qmk}Leo87wV^Bq6+{`SFj3~&DhCPFe-r0*IU-Z5p#>z6hQ z0fu_+CFDh9$TS(IZ5R66OZid<@CTbR*aMvvT9r|1YQE3gy85tBiJR%Rvg7zz|GF(XxBT$L^AmH5(T`G-;JqYBG{cK?u+K#r0 zXJzGxpw7#P-^K8HxwuLK8yZq3g=p^>@6Y#W#NsX7ArwDEp?V}S82X%o*MSz6u9 z0YqbD>fiu12nPl*nO`aMr3+M6w5KXa*jj-NFuV?y0q|bq3Ec!{XVjiQ!%^s7-ck@q zH9o+{;@L^Bd^||AI6*EC(6KG<|CA9R<)J7ruRqGgr;vO#!kle?;wSR}Pnm@#8?a^! zfL#riE~N*uc;HkK9D+Y7*>pI2xfG zCtX{=LI<{BfPEzpz5_s0%-TwC@Ni*oZHYX^iixvIzO%^kDj-&y0bEc~NjuKIv#W#U z9o5e3DlyR@Y1988Fw+$Q$CY0}T4IU1#5Fl3WpOLf@hXtT8!-DySFFvxfQTxj=ME~p z+9xOSmq)T#{)eISE1)HkqG=F0r8Irq_G!1}zfM5@02-8yYoe6>S4s4%n+TXJ)5^6T zoo3O)2g8%OhF39UQ&JP9m-m7Z4U_Rl-FL;#dS&6+?C>|^s;ma$=8T$tyD zMja7}Yb9;bxFIuX2g}BqQ0WfUh>$@fOMo&NDaN)8ljlOckSQ%CWrt+*&sxg7rLgr4 z{+9R{alcn)P^MK?VOHARG(kb3gD`-X#Rj>?Rv8^1{lkOiQd2`L!160rEMMLgnU1ap zj2-{IL;2a0qcqnwZA!WpIdn%ov=i|A{(~R_fWq(d7h}6wjO<_JqH>p~6onUENkexNOeKz>TFn_B37m&(1w` zfO~i(^S-6d-_jsR+UGwsi~(qfS*!V~@rT7(nGKrD02pO+k7V3ROMbV4$;3a~8z=AR3x`5Ug zvtFPlW|vuS<*FV`E8$sM5C3Mmn=FmS?+K26QVm(!PD^swUdR4$B?5S722fMpVX1V~sTkm4FWA1fnbYH6G4y#7pe8FuQ}19z!f4FRxP0IYz6 zEO9Ll?Dw){^PgRm0rLz$%p4CVIPsgB%fnVLBnBKgat0>0ty0%-pM0Y(BO35oj?Mb^GL1$|Ap1-PdF z3`ME1$n^Z7D11|VzFYhy)uHvWoHR2ol;i#X2pdVqv)B$D%rEwsvKFlD+)P^Q-AbyeKOX=b4Z!a^!)&~1$0QxafYFfkWL9K1J1wnzLf>xAw1wMqcw z+OIZ6=rTB-|9vZxfCC9EjKhl^9uD_pBySlj^)FAs?L#D04GQ}5lkQce$j+o9*6N7@ z8e9S<2nW)Wt*@J?0dR<o_GNtU@sg4O##|E!+8{BKC zOJl05zp{$KoDH)n=xl1&3my+Rq1BawfcLEpE&>RrHa`B*u6G3&<7>S}RW-;kK)YRe zrx<`PB*5Q^3#J90w&RD#Q}SCduL0_+*G$ukEno(~7nS-62!U0&7#K55;v4+;oFG_a ztA>=~Rb4;e;YJ{61jNQ%C3Mi>8q8qL$=?G3GZ>we%j0UHB(C3fCxNtd4R;;ZZXba3 zEI?E#b{dKNT{RgBh?kXS5PawUXp>z-3>^b`x&>6%2&x+dPg4uH7W;^R{xVw!$S2Ki z4Tp@>z!}sAi%j0M0PTeB{ta6~&sf`692zR^R@^5pp`)>U>~uGb+kUZna&;OhVWxD1 zr!})gUsW_KCo9bekG~3pc7PmDj^m-fQWCG@zJS^Jz6)_Ai#{JC&UH`2NZH}k{5_7| z7pd)t)tB3Ozs0Q@zzte`<%#zESTPAcMli!lAhpvj+KK0~Ib1|&K*So5qJgmSywYx6 zMVbP#TD#tvJDDLySNBeD25m>p5z79mSOUcXPPpU**nNtA>SK=)8X7Vk00C>WEw$EU9bM5L?kAbUy?!QmMP^4S3ZqDur0}c#x?O6jx{l7Y zKYB)tY1kH6Sq!Qtwpj4y`WglB3(&ZYNeJYLB+M}C0MUEG)RQ=z^-|B$L_7S>GDBl{ z?9>Q|@x6Kr-fB5hV`=nkVIQ|8i0NValgQbqs-lKZ1psHW7yu_qglm16h>LEv)Doc{ zNAB`QFl_jm)mPBkc#zv&vYnoPAl}B5uZ7Egrr>psUWr8vDoc_+f)Sq=zQ3C1g9|JB z>g|g%zzz8}zzYnr9Q?Y&!$81~Q$QqWSyXIv`gh7I^xXRqbbGpkx+c`|;=JM7y0scD z>DGe3cxAc4SZ;kI){+siYe})fG#Q|C9|64BJ{^E@Hfv83y_tAYezkTzLTd@S9@IVG zPA9IUokiVBILEKY%0OT0?Ce0&##Du*8$aIik%3tt-Vz(ZKXr{69RmXmfcmR|$(Jy* zK~}T$bBuFFYxpp@AoIBsv@9O20fz>UGiI~Pzy4HpY37C!rX6LB9U~q5MI1wH5k-e zbzSv7^SyJX4vdgG!gU<|oHT+weYrrfmbKc_my7MQkm24yRJ)frZaH8=tYaA4VAG}F zgp~MvC0yXA_3XDD(|$d`NT&G8kfZF1fW9gLMQ+qDGZ!FJz~Sn`~Lo3YeqP(0W~=fY3o9Nl_rA6xPT*e%Rj? z>Wh0HGJ8$|QRxC|9%WP8?tNEBNKEyNk@bu}@!VP~yQ9Xf=OM)R78GbYk+L?{_(Kmu z<5MB!t1tIK_30n;%H|D@|7~$@?j^M&;o?pnWrG2PAa`7KYnIlNPw4@s_~|0ktKGY) z`g6YbYFE5&(y~_6WMo@+)bNp}n@&+fDR*mz;2)s8;9F}msV`&@5picms)OKqnWe6B=z z8|6%$b$f}*>UYg;8I_B(n-mbAEr6&7v&=2i=t6^)zWWh?kVrHaId^@Yz4L4x{~9;! z2v?6t{G`-0S)#zuxO`>rwrXkvVuFyc2zPLiT>C}FiErgU{PodGj*gp_jyw_}35j5> z&yGd{SCqu`N9SK2^fycLu`&0FK1P43fE_ehSCzr~py_t8!IuN2~OXT4Q>}*NM+= z%Q|2lUtR90kM`^KFaOUjB!G$)fmf{}peU-Y0Cur}V6ke}dyl1;WoPn&N-8$DTn|HI z+q3z5KZMS!e05T8-c*p$CqArRlMojd_wGb8sEBR+1oU0M{GM-BKR?fWnQ8a;&T?R0 z2Z53R_4Z^pU>SSjz(qcJumyK7zkE0YG{R!EVawt6juQn|MNbOW`#ZY0lwIhA%3J`+ z0D(t(X_ZA9s4nKQdHVraT<@{^={FZx4Xu?vY^V&XVl*<^`9WbZ@!RWT1!sVBI)ai? zK$|XpI0KZ}3XCBjFj*fBRlQ=*-*dZb9xu%gefweIPGIQ{1Z!Wqot_KQ=XL9$GqApN zSz>xus!tMB^*eim;ur|t_?tt$5pWsmjkB+xLG7yoT6O{!ui*Z-;6$rkwlc<`cBk8+ z+wb?Bmal!=56W3UaH%Da=Xeh&)FuY4f9iY{;)rOtdOzUixmC+Ry>r3FdoYz>K&dD1 zG;pz?i%V60UERLx%N3N2HdPryEr~L5FrMl+eSLS?uZm|Y)vGJgl$4lCwr+`VNxAYh z3lf4odw>m}>7d5ss`x|3moL}++UdV?7O({YOo;PRdlDs+L$8+>L)3bl^t&pO^&8}h uiHWI_$w%H+KKf?E{*0gLu6&>5&;N{UwSpphXR&lK0D-5gpUXO@geCyO3xtXQ literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_straight_frenet.png b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_straight_frenet.png new file mode 100644 index 0000000000000000000000000000000000000000..9a36642b2d5451830d70974a84715c7f2d16f9f1 GIT binary patch literal 29125 zcmeFY_qG9Cwa;&)1 z;xuOXT2;GTQ{RM9J2q2MMB#Pa(SpaT(R#8t{P!GagLr5PpU~MAi!5Pe4 zlgGi>p>(q`uWzPMtKH2vT6sRq*E*#AujYySTe{(mX`e`OjM?Gi{t|3*qqiY@jkO<&W6 zQ`fT0f>$M0yF>)l&+LsTYI%eidwzJ-Sm`=_(0Yg?BqBPHc77833B9qMoB5ki*Ap8}=rs8gX^dh|nMDZ4bn4C{ML+t2 z1I-K8=%C{CelJUQo6oXxW>!cwt>?1DErVFR|Bxy+=3Kp2Sa{>n)mw8uQpvv)6F`^p zZ4&5z_t=++&*`m*S!dXX{tWBYJoDWdmoZebqcp@8NAB-V6{cz4BX;U;&`LkNFZbbF zkBlrCJAvy~|8T={r+gbvuE1cxjaLBXav!MegTh}VaY994h|q`T(sHLFl%gz8bn1B$ z-=hpgf<>SW@9HsqOpH-lap;_ZxlT=#0^${^8n<4ko?=&eh)s8UiVkM5jio z%PGk6^btq=WUPwJ=AG@=Vs0hGmNG7y9a)u{Ws;s@iy=PBdRHeZ3w#9r#k2YT`Hy6O z?PO6g+u;r3fmm#bL>ywrBibzE#E9*#D*wZ}5fwQty!VKyP0_R+-ODm|%iSTik2z*m zR#yGXtZ?EKRaaCo$M-%6`K(>kI!KgHE*U(|44zO!e+C$foOnED2{k#HUPnt-fn-ut z{&*uzP5iRt>mBl@prk%JIJb60*Z~nyYurQ>zM=U(wzt^gg_*U`ulLP8Ke-+0tqdqH zeAS*N@m@}=Y!|5c1fU5;QoRJOeE(ELWgdesa$=Mgb^F65YmslBgQC??bc6ANp*21Mvajl8g2WF_q!eq0d+o{**7_sG?%T3V3zLin^a+{k zl~ATj6q67ycWVl=0v9^H$K`(O&zhg>uf`u!|{3e$;0{`tO2^xqv4z& zjY6~-Yje4cKmmaqR-@%B0kOJ;gjFNopo*vldfgIlleg{?svxQPWBL{D2{kw~|A}u5 z^PVbT>U2)<+KBqjIIS9)m6FnL*drN+;OMXZ0jx$PrHhUi3CQM1RsE~od(mpta zU6N;GkJ)Gq`_K04!=6@@xV!^!9osS7zaCc}K3%S>OA+exePC863*Nn#PczE#iam^dwUK<bG2Opvx&OcUtuENz)uGF}M>mAtFPoXy5r$pnNrx~2rQ%f(dsN$qiL96|72AVE}ypP-OAvBH-4$D@0>*feJ1#y<04j>?=~H6>SCI5 z+g0a6AX8N8B_b3z<-0&st^`4FG zKJCcle4t-GV-i*vk`Z)>6(JXdO{BZrpD7g?PWk^hxXg#7%;dbC3$d>vv{<=G0ox*f zRuD67Fu##sUeYm?g4h+g%QKfUswf!W48@>*a_Hnc8Xb;`QW|+t14uA```X#$`tsOw z47E+W|Hm%3qh@G=0HpNDJ-1m;iDWI~o}j%ledsAmsO@b3RpM+PGJ zt53up8m=i-R#s{1$8fEF2LcTjvvi%NjX~@?fH9+!$a;Fs`yQ-o3>u41a_-aT>QK(4y_cMIKGq9G{lz)M(Yr+sjr&H~drdtMcr zT7uTtktp`0BnF^BPI-#GGYP4RN8ZmRN&K<)aw-muq5zV#h=m>j5NxB6L%H_@@P$cR)mg@ zQ4gwm6K6L=b(OBjPZd5>uD#|1%QNZ-j8*I$3T#y-jADxt$dMT{$6=)@x?rDgpFn-QELOOTu`amtQo+}v+&i@HuJ z#yF1eR{{f^t_Q#}RIF#qt(VHrq)M{I|Jn;bhah$eXhTf$8mr7pmUDl>i*IyDUFl$< z$I#=$e3w_%PgV%^oc}S{a_&1PHZf*Zvc1)CeV6>&J#O*|y^2<95datGxuX))mP|E_ zhoa+o4OenahLp)fU;D6!CELyXxnHI-T|zzmk7j|fwPrF$4_vZKwESdR^rE-iAGf6a z;%YzJx_D&go}Wu3)8XIHXM89aFb#{p}N?3M}WaN^VbGrK9Je?qHGJQz)&Kc^2)qNOJAxey9X>5?$@i#hp%A+Og#P0gFvy@n*fdNOL7tmcIWoc6G+b zWc?aIa1jqWWQ)Cr7k!H~zQ7FCB8^zTM&j6&;oX$KV0-jz(jtDdL37?F$k0z!$4`wc zVR7zLJp@iS(#K(m2~ASZ&n{Mf)AKeC^i~qYfGJ%G*@T%?X#P@9)*`0dctQCr9*e!{ zjb z*`jC!pf94kcPemnbHC)mkxSsY%~w0<|5DLA%gfpD6E*YtB#sgfB_~qTeQBUrWou?b zllG8`J!;V)%cE0n()VM9b{Kb0KetvjaU*Mw(OPN7jQs%KLAAmc>6S`4hbTE1LuL1^ zDTJ(5N1KZCz;_giUBsj`EXrFr_XV8A==dYQXunO1rlA4wfV}AMu{Il`%~^$M7{G7y zo-l@B!fKOREH!L6uu3sk4sG)7K}r$2lJp;I`Yd-dRHcqH)GttXrht$g&2KicxkHTh zilmh2=;(`2z3sr<+_2o?(Iwo6X%cF2Pr}UR+=B`&SAnkRN{uHMlUdDw$ZaKp2*sD_ z)^dh_^yNnW1kquN-m4l{%s}fO&G0L)-R3MLxWtm`7CJEIq_@5gvJ5G47v1V*cQGg+ zbJ4|;(U$J^?`>iy+{Q(z<9?h=LVZ|Dv_i6&6PcC zZHFYez-xyN?RA{^P@sMKbXDf=BD=7cf;49%V=R3w{vo@2hw$K(W27C@$ALM+W>7PzID4Av(~Ix zHiT~H04zcS9IG^lU}lB?pXDchWOsg%CLr%))mfDb_*^o8p1Y21mRp!FS5)pju!zB{JeW!wR;ut=AWbUlFIV&}v)8Jy(Mj_LhN;V^X*N zSU_YIZ|aSN6m9Af=Da84ka;451HW5rKSjNLc@?NeI4(oElkxD7jG1vL)b{)WIYsHs z(r1Z&8D%x_#xBZQo-lZDpY3R!Z>X|LQ&>`Nq6+ucC?u&!s)E;wp01q>XYf;!nQ{T} zUyO6~5fK74z1zUREutrP;L~#~6Qbm&R1tSQ{#i47FNZ8UQAw-CndvB{>neyGLq*g? zmcpb@VIh&+16@uxYnt_4(+lU3oU`ftp*dgPRUaiBTc$kz>r6B3(L%nv+M_ja7QD{^ z8fr!s$+Tf3;Y2g5<|A_eS`7wN)(PvJRyF1)q8aHnz+f${RZ5Xw*nTVLp`Rx+Q|%|%K`KA>EGXP0{yFOR;`JAY$uiGI7|L`vsB|d0H8-29d4{+;thYx;S}YvLGOGR`-1+H zxCv|tg{{;>m1be=cGsRW5sxIQm-STNzA$J#7jRtOG~pnaGY+;+2ecX`bv<@zLuWm) zuvld7B&&CD21=$xg=eN?-gSTA5S$T|iuY1-VkAXXOGwu{>r)fFn~7M=FXdY zp_nK(W@O^+X6A^X{mh}dUP$}lCPZfCgU+aSGYduZp!t-}Gc^a%5(CaWUZ6h<{)ejQ z3G#EH+HafcoxN41oEIl`K}PJlETo#*!9T0C06Sc2mvhGQ&9@{?>>umBM)xI9$Dad~ zAwo14&Lv@vd^n8!h7W6dkiD|mLtH%ksrhd1D(~|#6VdD621@BMuaHs0QNNVh@LV%# zWT!G>J($pBg5S-ooC&)`G?u8dl9K$5NKz)$5dpA@W^+)wiBc9F+x+N3F*TNgt@;lg zyC2;AT#gsJu+6sN>`{m>bV1VQLgXSqe2cM{0Faw#fj%5nbH`U%5s#4c1e&QKhw~6& z>Bj>Bn~KF(Xpw>Wb#RUbefb+h29my=U+gKFD-OW&fqyGiT&A>9|FIaCAQu zHCq9J=!KdtZ{1;~2PdR|7vlZNA|;pBeSu$Od(O3&PHej87a_y;Hez8TQya4D`zN|@ z$XH0@g|7dtqu#MnL%5M;-EVg|5IPI0)Q@bO#f|DOgpFY2z%YV#h*8qCU92CrjbQF% zfmQ43>jvS5Q_3Oqb3Y-MUt|c%7yEEqbLCS@NH6@#`E}M8RV)~$nT})2I1^Q6i!l6X z9=wwbod>Gk?gl}Tgyx^=*Jv~qWcRu*Jx9PRqM0?#;LIJ6K^vc_zs+X=Pw(Quv-cE5R9 zo_JrreR>;A-eqYd=tVrT_-T(d-JEK!8jY_-xZs7ntch&#RM8I~+;2HzaD%Zab#@V9 zr0F;>kwXJmt7@mnJj0~xN5czRw+jL{{oB=-Bpypv__XSETGP%}8 z9~Jjtl%2CB)p2GVeA+5iIycVghJh0lc$I{4w-_KbkRk#5#I9sF#3Lo*6;{)E6|^Q2 zlFcnRGd-b8hLFKI-zkiaR`ikXA(D8GLKET(*$NQ9n@aY*yULMOLaAj`X@PBU1m1@Z zi?rA#gj&#sLe6gn`QX0+>$~aDH5UvU%kY5Pqj1{20>cxgGt|IC^D1i#m+aHd8)_-v z?Pq%iS{IVz(RUn|hJo9gv={KQ`MX<~pPpv zYt7#v^S8e+K^>3J$7-w0&kwW?Ha{O}sB_jTLRo|I`&ivIO z&E#u&?OI_^8}!OSdqIUZSmBg=$ZdFm=y4JZe-+eX?d$kbznh(k zh~S>#B&mV*`vvkWcJM_sI3&7ZI&&0*9!k@Z2wsEH524?j)pXrq0L%LcPz0x;Y_t)9 zj|I%Pa2eX&($lV?G_HrwZ;}xE1`VGCe&PzU`()5C>1ey|++F&G?P73Pa&UAE;`_Mc zcssYf#^7`I=Oq+@60O``kxC6|h-dN1!Es=zD>Sw4M{zJHFwuX;%E=5!@G|5xSJ0n^ z@p)G9%RMC|etQe<72e>_y%w~trh&<{9p@;6M)`l=n7sBtm}y(uA`atlm=KMY8@h9( zh4~>=>DqaLTgnM4B;51c_~VYBd}8_a*Zhf>HTTg=$~|()ix)S^N#~s;;Pbt^X-50L zPzlSxtuFaHD$t|S_{TlJ-OlEWpy5N1JcQakTYY@jZ|5c;D;Km2HVMp5%bcug3qn{x zY=C4Bg!cZ8tEqT@gKOuwvRD3jFOg*MDMr~3)*l(V-=6o2gMv5QRZS(qAn_;CNfDQ2 zAE4R_>$kfE9D@Z57^gO_J4iI1 zDVlX0R=`p2FJCk1<;oqvB=;!$4D{`*?9rEC8A(aEb5K^U&v)j`9)2vc|~=;i#w zHHIAAHPIb#LzUa%ku)PBe&~LK6#Hv2)RZ*ad{FVY-ZR&bTdywY-sQ1< zq+0jGs{-1y(RP}>fpZMs$2)RCiAS*;+TA)a+Ks6r#_qe$8u#FPY^0#OSBb(~I0O>C zs~E1k6PKk+r!S~h`kPIIGNc0c!1hB#==}jCSYD!_SK+KSEFg| z+{MQ6>Gm9|yzjv-?d7uC15ZP`(~GqpXjYB(?W|f*3RlohL&wE(-sZfVFvM+==Og9D z_`v(eKdq-{L#5aM{9SbtbFrT1c67h4hP zK>*Ic>C+#o@gGA^2U*R3k+v{^z|Hd%d9BkkLkJA|HuXKV&D=!vVW=GMbpDY$$Cv;> zA~s|msFclgwToRelrlr9zL0^sc12dASUoHMH;4Ve^im=!Pq^{KyVLU>QAvELxs;jfM>yA~vY*taCL+U|o9_6yiQXMt zUP-i|z;q}RR}*Et?KGCD2$U1l1|yPFTzr4XQHaqJbVSGn3Wz3wsCi#aXO~T0?o@!! z$Z6peJ_)qDuTQPXOjq>+-Ju1BFF3C+OS!}+b{7YumeTzbnN8uyrzWEP2q$bdb}X4DmbO!1?+@-Y7fIqD#lTh5zlOsSy_8 z*QM{5SBK!{QdLn%i!k52R>W5`>-n1Z8+Gm9g{Z_s4z6!lK8|C6VW?4v0IdwEnumt_%K(<)up)a5$8S5`#s0J&>lJ4`@6Y|rB)w5*w%|J z&*S~TLeze03YzW2%Ti%Jzq-yUKoY3qlC`utcYEZ|)*!yp z;k!3p-To`%Jt82s2$3QO=kDLA?@(U%fnBKWj2xhe8nwjbaJ^1=C=TS%>R z1AH0F!}#X7XeN;4hrrH0S-+;jOfsu?Q9S6~jSnB}KT8z9qmlF$dfMT7dU(E^*(V+f z;ZbKNx|JMT&Z?OQ*$28s1Om6=GrQiH82T}u)-Ks>fN8chJ`t&YqpGQMqwJCa`!HK) z7!cuxx|1Cf49)9fHNhA0M=vRuX!p*lhSkeJn_az0$K*+3JVLAZ4P^Y=F~TY%%hWiX z-|>$Yl~S2r_ENq*&{Q=QSwG2Ya-+ddN=n0#?z*Z2pD)Vi>$&HnW4}hkxTih&&k+ta zTgaq!*}(s8PrI3I7yF7_Q90eVtopW+$2DK7)8SUYkb_S*?-Y|E55T{LX~{lU-A%bI z$AQ;FrW3ewn=_%EIqJkuMXLOk!6lXP;BMCWZ`@zKF72jybP5@ym6+cBJ<@2CG&Am_Kv&`SczJEfyz+O57LG}{tR zKyhwWYD;rS%%gU>`!_}=RoxqP155$3i?6>3M(&U^A*ESW8M+as4YRxuTP9&Y7MRjf z1KENv@G}7bQAnyGnPZ<#DAW#5yjd{Z{1{R&u>P=8;|4A;RG5nJ;mo&g6PIUjm`Y%f zyN@DUhih%5Ew0LS-0O*3VmbFzg>M^W<$R;q%c{`U!OQ-6eGsS3iesMiCJFHXXiBz* z48J|rMXENaYs{CMF#^Dq?(*d~V8`k;;Q&Wft%R)>hN2ah97pHwwvpE_#dzn4qgtKJ zBWKKKZXD$eDw2WHJVYt!{sp3&HYGidKGV?V_G^E$vNI+Bp~p~-F8BguVOeUR+wVU4 zwja_hBjK=R@R0o&ZF;+mI2zjb9+>T=Q%eG$s>p8>Y2ieCjuEdOZmDtPVzwy4w1xDw za~XvpIv-1_21VU8q&1!2J|3Lj^~tE6{incFx(eu)X*B`+TO!l8TO zg?TRCxziVnmFH*gN#ER2s@!)_7o0Y@`f~ZG8o5A6E;6*m@aCy-U$a%LWxJ2hz}dTD zc~X0k0M{CklVU9;AvUiQhi7U^O-k;Q=2e5)>9Yo{W+bLtQx8K}3JhV7iO!(B!fT9< z=k$6^Vmb}KKS^Vr50Tq`&U>egsN;0%=ead#n6Kdi42(Fg}JOLd-+t+!pUY6W3!Ak)lIBqh;~ug%k@COubBdS(@bP{$t0)GwXvSQ!@7tvm zN%o*Nuc~p5pAU!lXAP}rprCH_h~9YQJ{n1x*Jp+f!FoB8c-;DNhX~RPGK)Fq+!vyI z_Ubt4T$9e#`Q?kLiS{n3DdECt*ILKWKJ?39l6uqcoL?)G15L1)NPCy z%6N%x3s-a*vTq{P3fYF@?r@!*H3&J&@-^RKY3m)LHbVQO1zI}`P<(eOeO6*c3t~!jRaA@{CO`0)GiM|IvS`S zI)LSDP?ykHGMDG#fj#bT;>CsiapYI&GD|0$bqR4FKB=vqb9cjkG2b2AJ|<*okt^6b zQiRl{4qIWE0#;7*Mc&^npaz=l=yXY*yZd~z~n$cvgKQ*qsf*SE@x1{W3$_1L)$j(euWCp`9X zlS*Bm8Zd3NrFhnuuShBnk5gPrigD zsbd3xjFGKC{zSja&db1^uJ+cDBhKJ^LD?!3ts%;!1l$WpP;i3nnnZv1(Us91sJdX1rqmQbwCu(cb@V*;OCH*mh0zMu$$$;|Ao^Z<(l1%h4P+WJo zF{#zZE&-Obnsq$ie28vep$`mmNYrnvuN1?@A+en1ALNUgDZafU^oPy&t0*8s(5tYV zGSLF^zfN-XaO{H3&WGKNbb95~98EXhlfd5-YR|MVrtPrLkH}m4>mGS%Xxs8^OLKhZ zJOZyUyFE`!@Ak_O>6kMV;3(X8mfJh$2=vEQh|6*`W6jfjDEWkGS52)^2j zhc^y)_m~EqO}7{f3@&0N)UEIY15E?qzj{;1Q$IV7{2f=whp%oFGRZb zeFlt3&Tx*7!S41K9NDwezMHARR_GVKGzksDJvd6jbZ1a&+kv-rz+r-+S|-LTs0JO( z8q~x(9_CM^dFFtAdPEJOg7`uD>?H$-!vpQsjTx_F3}(K5VLM}^h2u6PvLXt^Mr&iN zXv6nzezfFzQ|FSJh7JT^5n2yPitu&Q9(*#p0ToJj*$oUt>YmV$mI&C0r|>grGU zdwOOYDnXx-OE z3sxgQ6?i;Y`UjkOyO4JZ>3+Zo36F0exy=Xn7Ifz3wD#!+-#eQ~!0>${0x}11sFVZ{ z)u*nDLgw?zT@t9|&uBzih)5$5NqXnvj+&`&Hf{HV;_yKj)pb=SXtU|OU)+BecwV3m_ADUMt z)}P>}oA4QH?kN9;-elE$Gcz+go)w;`OI^0VotK$vilaKY}q3aE)XuuB_v&F@~Vusr}d#oBkzYK0lE{XW0y6K425Ie zpu|qHq}*T+pDybWRodL5puic3# z&tmYedR33u;o=bK2AHFP8RmTe+C4uHQp2lQW*jQHUKy(cL{jC#$6PxK;v0<>Lq|`1 zG(#T!`-%aOYYEQ6GbQgT0H5w{IHYT$Z1jl0t5F{UHhCawXyiQ=b7O0zvnuBuQ&a2i z#j#yu^hydjU#)R-vXV--$y02YOjhe0`e>bW$w$I=6XLNY9&)zQ?00^Y^KuwYz7E6w zo0|mOtp8N6OSYlDteOuV|2u(-Tu6x};R#`t4-M zMkC2ZG*$)f>_5(z^CCp+&JLn$zQq2-~Hvs$ols4*;*_bsE zI>oQOd+c|2nBy1alF`Y%#Ytfy$5PEx%lyuovQ65lzdS|OROE%XrSF+E#f@u^MO{1n z!K>!&w^_JTOsr1=uEK>Lwr+lxCL`E+Q!?l(N$r>0P27JxQ(+4=Zusy5rBId^jLG&Q@0JDgFePEuTMT| z*v3}@EP6=q^?)Asaf3HO7%c_@?cJW%>f3I+M|C-dN3-akOYFre4%o<8h~NHc1Od8= zv(;FZDI9V6({8SekSG;~KN^0rQi!3TNJdWER&-9%I_;1N@<-@o{oP6oQ0efC%kr?F zj_Ke>D~Z2|$dKBe|MkAEd;ENeJ=qwJjI>S_80Lzx*e4UT4i7ocf6Q~iN3iGoKeHlQ z%zEJwHl)YdwT^5F1W9M}A$w9=e@iB?a4E}@)JW072N`j!nT(-`CAPr}u<3c?7(eYDB!A9OCv6+H&v{v?JE_K;sco8kX zrEk7wMOsw16@9Ec`HFRUt?1|)Wm6b>`mDtY5+qdL{yq6$v;4nax!&p^wUjp%=&ncp z13dAW*?Q33i~QijVrQDgo2&|Ji2+IXQ-*{qyo{P`*8!pl;jM)Q4eY&AJ%szipY1wR6tpgdKlD!TlMNePg)MSMg+PzeSMlgNvXZe{ zPmRc8OFg|Tk5SjVA5wGzep8xK_Ffq?0(FDbm$TRbH_5+O&X`FTg|CVJb{tb&v=9wP zJd3oc7=|tHq3M&GuKSx&FF~Hu`bEVo)2F@D^L-dC{uue~ zacS42ZvGupej^1gqAuzadV^~s_v3Q3t99=-skkn- z%7ic7yWXYq@ZHwdY<|&Bvg^eGdo+PF@G^q{xwag@@Dk&l0A%-)WARIgXiM zPMY^i++IiQyrtbgMlCXrXyuNU=)C_jQQQk;Lt6}~K(oXiv|{@|=Wu$45U_`gv6|tv zNg{rxZqTkWq-HM?sWSD4e~5@%(PCV(Zb}K3a#LUbD0b)sNxS~hAhed8xh`Gw#tu1C zn)F7iX7&RC?&ir-PLLYdj?f6k|gEe{O=YLaGmOFWU?QW== z*COkydHL@5vODPQH@Am2`pMk2Y^BkZxI=nNL|?;6n_ZCRG+59FijWwu*#i~FyzV{T zw`gwvEK`8blaC5xfT! zBJ}AGXXrRUe^eh-|IhCk(OfPi`n?N1rVy+dOsTAzW)MilVPNj}y42gUj|M_W@!M#Y z%3|<~x{pR_2Z6;B5+2o>LnTpkQfMWY0sN&l=NTXUI3!^E9N|S6_e=Ul@Rab|b*bh9 zVbVB-=E`|_+@5^k!PK9>#=awmxNB99hjK_FWLdi$Qdu!Ap5By)7q$!cIH z)d!knmf%A)a{;m%$_JXn+h-oV4$(;U8;5gRJ1F`9 zrA{cJqd2^&VB^57|8K*^$yr?u5*Y z3d+PV;T#JdVTd)`_2TPcC+%Pn$cMBDVFh>l!%hU1_*Jg0XfT_sf-LngTNE*BQPq=R z@79NLixCoLHYgrp6;J1H5&6R3de@DOlgHO>R%Yzv>g6*CR;dl(7|EKC!EJIg<8^Y^ z>9(K#owj9@w2RwAd7GwbEb;4aHfatOuPST0lZ8#hqhC{PQ5)svjVG--<@s2iUD89C zIC-=@7QD)zyvq|KEXs+~s(u6>6zSxVBF?SF#eYn^*q^u}hiOIb?QO$+lKIWSBnVwH zXgDylVU;veni0PT^1oJ~w$I+G)q~KfG~}ytI!8-SifBT5M79`Ts}N5izSf+Y3mL$Q zj)MX+GV7s5Ny4i2!Rl`bUAm?m_pjOqe0Rjt-b+qyQeXMS!x9u?6CGBKyGlk^~T*jzBe2k8r*c8UDjp`C&g}4IC5x^)@50vg>f@t_TL0&WL^nOy%F>O z@`G(n4i*K>%PVjN69QV71Ol`3ocRiXC_IbU*`h26W>r1kKPG9ANzz@>@46`y3Uo(R zXG2y!X4AM&bfA8b7#?601175YI+(SSTYtj}cY?9EF)T?qX}Lh2czD2GajKjW2VH3g zhO;Q#IcV=4N}D>iJF;6J-+DNag2L|Cm-Nfd5BH-2<@j*ktT9zqeoIEhGaD+rp^^)F zt-G`AzUtQu^f~mc!Re;iC1?-NC=;2wK+p1Uo|{vpFtR8~dH15t#AYE_c-2C^#YOJY zRXWz?g7OE6E*A|)E)|i62t^$issHoq_J2z1`r2cpc{(DJfH1N*0#5Bh(^LCF6F&gu zrqdj%SWZPsB^YgyEPx*+yf(8&i%UTpcQk^H3p46xm;6QvN-v|n@SlC3Ek|PrKjyA9 zsrda}AO~n$Mw7x zQOD~gyn-K>#>LGEEe?6!QEb8R!3Kfgt;Vog1fS7WWt#nu$7Bj4mImqOx0nUtgKN=% zA-OUVfFEbh1(1=&e3d7cwr7~v*DhBi&hGty)>an}xIp zxL(z#{v+gPpkXT7^8__9OdfSJ1+0bCZ=iwqMJ7$g z)0ZDQzI0?VKq8CW6~zq;7Ic52d?Ag(32&LvaGr}bR-`{Fl+(pJ z^Uc6@Mgb1IyATIVTfezV+Yx8tQrlu5xD=pS3Ze4jqN8R%Klza6SBi7k$d1>1w0k6O zzf|NT^dCXc5OLdggbXl2v2A!US!mwyv)G33n~5votz@-1CJHUM`yMU_ZYa{w!OLhW z@7t1-{R}p*(;w8$l}0JT*Zh#fb7z!f1RU$*!oA~`&lW|HWu!S7V=YtPFuBN5fGwtu z9_HSW4)aeB#@{fi#BSX#vF0P`lvVPs^(n>I=sUU#R#@O9AgD9o$n+geb^Nfk{^gP;{x%7Dos-zKEfz2z*n8zn9F>?tyJVHQP%MGl-*YK3RW@#UK{bTx>3lTo zV@rE<@0%Zg>VMmmiPg)_J4PQw+u!tI+(hFyzKCyE@}VE%YRgX*%Sh^}{OChJv@-rK zbF03h#eU{hQt!5U5^r)J!K=|+M($pQX|#0^UM`&$mVlHNwoRrlN-NuIoA5fbwVOpX z>@Osrtt%?)b*=erKvb3~NKSqYmO^`qi@5!t7TG*XN_goNzDs0xlGi^h1CIl2D2hnz zrK8@zAq}H53-mxK<;ZUR^lptHU5C>|0dgv0tvFd)&?BxHbyjG@XN9kuvQx zSe84(lBk8I>?1b#l3RsOYn8;^EsdpCMR|Ilo_*@vYR}=*&5G!VpqR94CCRe;hqS(W zcIvUACMWj(@yPc{_7-SndiZj}J&IWiO)_sRQk!Hp7G(Q*=Ja2-a#yd$5%Rp;YM3>1 zzF9$ITTW)fgd2Uf2BJr$l$rf>y#aAqh};IhUAp=}DQUl6yd1aLdgAoS+G0<@$0tb2 z^@a83IlLp^>cyiR!T-1bKL=N;Wa1gJaRPO+lX4sXz2y3404-E@qm-` zt2I!NUA51$(?(V+t0mKhGI+p!sj!8QPgzBcq;8rJZ6QhJ0#3@qEX_#z>L?;6idwol zlH6AoHOEYJVrGG&tf&7Zh8RDR@44q~i(t`kDNiZ8|1^D*X7Ud|Z_fMoHDEuVEM{pJ?c z#*oCT-*19N6E_1sVFlZ;e6{tD5VN4@>a}{6^qeOvMs1rZ)${!_*5J1Yu~$EQyrl^V zV`X`nv+(i)_gKH-_5+=B^Rc`wy3`2K^qjNYh6w^SM@jik_!oV@kHrzI6=5EInwh~} zT_u9|fSPfC=Z+PjV6L=szcw7S*4N>bOAz=pZB1qwuQ}+GZ7%Zoz3Wl;NFXHZJT|7t2!$+MH9;*XnG{MfmYZx~0a>@s zoxlvNE;S3*B$7lzAbOJdZx_m<6~yH#iLCgSdQ8=a7SR??)Oz5ol*<7N9)F9MPAg53 z0B3vr{9tlhN9K~^jS3n>E_|Rei^!l})z2X)+hxdnyz}dhl)#~IH0g@98ZIjWX|uaTHT9EwmoHeO+W2}qpa~6$H#Ap zA6v_x(=C<=xXNsnx;$zNF89RCQP9(wC%yBi{KI1zya)6)i8MI*hE~^yr@*VELZ9fY zpY^%~9nBmAHJX&B#MP`(M7hM4SKAf8=uF{`)0_{Dj3O#i#7Z}YhZxP|Q>=onaGVk) z8};N>=4Bwt@W4q7p`!dbiD2~$bI+iJvMxqng}(4rHb2(lI7MT@vbW0R{|RR*4&nX$ zE$|K8o@ak>`Nm)2y(MoKF6ecVs@++EAmMLJsC*4ydFuTFdbPu~3Jl?y4mRN`BUHZC z%1VxpG%^W%4|x;Y4CfrA)$IfR>?E}EezJJxNHY-jtIv`%+t~`gp5sqJKW^HEgsQT! z*}zZn)5BcBC5%_VP0nvAle`$LiEo1jic-E9aG+qOiwMSp~$k4lIv8$6l>xh zQ26DPNdNEU9LHQ9eTr`{{JIHV#G(!DTu3p6C2frn7mM=+-%UUW2EoX`(wg>N55F;F z?HK#yPTG;K6JR#J@0~{bq0O#yyh||7@mrggr>yZ?FU5BUWgW&kTdAY6pb>gaWtMm5 zqvjSY>+?QO2KK|Lb48#a?c%fe$h0T9v?rWxgUkm<4+gtg)0HX}hSqP~jyvKv4QXCf zO57BN!KLtr0EYL?uspxSdqe*3R9;4MTI9W-g6i;;8B>*CZzn`}3Jf>WbuTF)g!7wS zTL2w<_;1R1Pa2GT(_nijfkwpgZDkZ}0n2&cY%@-<5cmHy_0?ffeb2*4NK2;(xO7Q( zEFefoDBYdXqI4)qmxwGSUDDkp-7Fy`uyl7W&3hL=zvunl=h=Vuo|ro`=S-eCXf{Kn zsmck|pUsz(C;Q`l703U-IGm`N`>vRtjtQ>Xr%6W)BLdL8H%Y)BS<_y+TE_!I^K&iO zYNo8nNNVP2RW`FkVQzAQD(Bl(h(cxG9TkU7JD#2zLP@tolr^c4z9cHT0f=u|{iL7R zMCS)>Y*CD;XQGC}hS^{7T(_C6&%&V}uNG*MG#XIA&HUF1 zhxi-d(y0;wNCd)V6y55F4deB$2b+Jx>?Mv;sLqd0s7g{pskmGs|8+2}XB~|*;f;Yk zy`lQY8-pYs0~rbQ@}BT|395DLvkwu^*_&$pxOM%y896)T4-ljxh+*UfQ+;Xwq_mXq z=R5Efg=`H~gv8&9rF*nnzFjVUfm=G_`K6Vh(-bUx$~I+ap<0!wNxia~fLh1Z8Rz(A z9XsA>1V(B6`h#Bz+l>u&r8zh_(3>caSb-L~3E?tK-x(nZoV)$;q^}%q(K{e0NNSE^wRyAVC8aY}8TM@Oj|a!5<^#Z%&&gx|L-oNw>V zm48{dnNZcfsq4}(zftqm#x<0MM`1k%2)YjJj|4GP<~CM+VSw|Azf|urIvUZ%+Th?_ zJd;hdr2V<}kMo&(D}x9YC)t%P?o2i>gTk#pCnE+T8}l_nfofwRjEqdcA}x5DOkN7d z-`>CJ?efCQSZWge&;Wb+O9+6w!peSDXZHPN*C|{;mEzW{p}3^}cc!nyy?Ul(238oV zndH$xR+#*dh6u*y?&hz4mvGxNOutGc*g)bNCU8uz@6BSq9L7C;MJEgddaXap3*q7K z@AS;kGi{&Wq}(fo%owu{9LdZQi3!XyEy6h5$8M$K62e22@Bx4d%&KHtOLBf<=K?@7 zJj*#^RgTDS^0Qp&YrlTAfgJY!8ge@(o)`o-Ct7K`cy%JEPD&8dZMookQcNPgsK_`A z0;w5)BR53;H)EVMis$s zl2=JNKf#40Q+-p?T;z0{iF<65Brg)2Lx1!q=#e|Fp_|QgUwxA1j$vgL=G$?WUubUL z8M& zwAHZ-&fr-X3m6|I(5!-|3z_>3GozX+QRkM$R!eA?AB+=YtU`d}{l`yi;Z8;lWw~#Z zWwJe|^^7?|Xm>P=;b+uedw*J%O6Dta>!JackKI(kmugw*YBgeP7-^*rt@gPvS$>56 znF|SWi6R$yAsnBT@jf~(a`0g6AbjG_uh!_orRIA?OkfzNEvJ(27gY zkY>ry!FP3rpIe?!jVU0)0!a^5nCu`BWkvq{G(;Rk-W)iZ1k_NG8(_@&3xEdv^#@T@ zL04mWTWHCNzeiJFra&3-Qi~|;a{xDDlrF?_BG7#fXncCi)p@`i8XSzk?y2?wKn#|i z{fvblbFO8q8s_UjGf9Ql%#}SrKLT6JhYAhv(rJmuD-`lG?GrTn2^Bw?ghvv%^G3g| zP6**kAK7s@qYen+L&!D|=wl`@h+PhQ2C8N_0GhnrL)ob@N#YO%ady(Mw&e-4^xSKZ znt0zcB1E?;{D*G1j^z?&cQDvsF*0|4rrH;7<|1;GK;SqTXp9_?3;-T( znu>NpQqSn;`Cc`nk6Va< zxZR3odmGO8NyK60_KzE{rssGid)*-ZNQa|#jw{+uP4Nqt-TtdLtD9lNY-2_LK3Eor zAXFtOqFKBVqaV08kV@?Rd+g3B-tKPXhXX#ea~q!DsU2Gw{bI{p@S_@0aVaE3BMu=* z*cfQPEI+4UX1240*b=(5%lyQTO7!$KTrg*hGhvKlo-P%q>L|BoBpgo&lG0}mGqx}t}T~~3~Dhb)iR$>yee=x@>91!0Hl1TA3n05mo!qk28=#hfp z$yKm@a*4d?cs^=u=oZ>Wcu;#)VCHnLtfV9;rC&U)#n z=r=et_vpJ(dD*U#a$G(TW~DGAS=Z@ojPgBx;7>Kz0gmKTfsd267NCi@@8ln|VfRa# z>e9KeBSyOD@~w5AuW3H*7AfZl553@vZapJh@Ht}oNg;|S=`V+8T(=TyAW)Zb4-Y*U zn}T(T$1n8Oz@$Jb30WJeN7_({UbMiuySnKhyyFg6^ld09W^t6;1 z&iT!Mob%|5E3!N2J~K!a_WI`3a)=)s6t#w2Hf;0M-Ovq%X2zWjC8fDjnn0~&U}QSw#LJ%`T3nap;sT;Ss!q>m{qsopq`4SH?%&u^b;Aoev7 zZYC{$axtlTU_y~BpwgySmEk~2*@3D(aRiTj1jeR#VtG2arYCDZFEs9`@9MTjZbY{Z zcLb;Q2ym3Zd{|nKV0h(O{zMO(Q>r2%>Z8|Lpqm=Gs4$DC?z|$Du8-bluLJ*7pa_D|4*H?=P2H*AEXHU8BqGCH$v) z9(in^X_s*%zpk}kA}guG#JE_IyN4`=0+X()Px*hk--=Q_yh_XxJMDH=V$7YH6aTF& zTC$wBa7)n?+|mt&2_s2g`YEpHE!54?Sh7^0+_)K5!^`hR-TPH{=WpX>%B;lj zwR>xDyeifDQLPbZuYPxTq0^zUbWL0zet5lbXATo~uh`uf#X~lL(wPO(%}TO=jPm^LjlZhIZx5d&BD#+7C@@$^;Tye5 z0LyX#mYtfHI0-^j%A=^8`^My~1#9Fy)*8@+v@L(8V1Jer#~Z~SOfLSRTIpkegWm45 zx#1S&MvucY>x=Q8maeY+!72XfnVz)!ZW`y4VP6ExpfD|fFpzJ4Tc>9Q6Vbi&Svxv7 zyqd`ZoQw{-A6}Wy)!iyO&bct4L#a%CtvP8Lwn?x4HeAH^+(Bqs&ObONt~8uGwtP6S z_B@CxtTTsxyx9xKixi};=R`wumI_#{v*3LoYO8meF^PVJ5 zX=&JBYtEk>?}t_bCIU5mjG`&|<9J6{`|oCP1L3;Zd2xM;RPv14;&8l!#y}a7zSip{ zZP%Wtpmratd-O{h$6N9#$N7!{COqE97ZwFw=S2(M#uC?bcgHg{-{teTaKBu0rY`w6 z-4X%3q3CztQ?%=9(+_AiY8Kz}2O}6EiyGmN= zE?>Ltuk1Gq9&RqBovfw##a6D6eNw_d+Y$5)fzBTj_+3M;FO6GIm@L83j~*Ec$OWhoegtdK6ZXs+d``(%tSeCFM@l(lur>pI+ z?s7pFl}s%ig?X?(G-ITfL}Z>jbC?2d@XBT<6m*rAxJD=!PO9(~t5b?-j6P`7i<*-f z+&Ls#YL%Xa{wZZgpxnK~?MbR|d-y?%?#P1O2de<|Ct}^tyh~QLhvJV@;;Fk*v{|Zt z?$qvC0$k3B^Tt)c<=fmmMSdajRvi-ZTrEs#D zX3MAXUj@0_QSlGIY^2fJHr6j<)21rEziFp;j}Vu1<3#o4O+LpQMj|c=fQGXkWt&J!Q+LD2NW?34 zJ_&VgBLL+0@^z_18&hd(@~oTjYki^q4?ISbCkaEpKyD$x>h5^W1fySjahEzfQXQ3Y zo9t=6Ngg~*J+QZPDS?nLG|lS*HK#?KSJSO&#e@S%DqX@K&dI$eowArF-@@u%r>}h| zwk&Q+ebBM98GysQ*GI#)*fr>eiSEuJ%+J%Yr+=PPU@9X!iwM-G z|7CX{)YQt*lm_-{kE>_Hs!{LH)?Z)Falpq(9H9K}3lpsrpUR%Gddz*`8J;-`um8kk z2jY(WEY;gDCg;0nSWmkPY({UF^V`?Y=gXhij|04|(22>dX=PJcZ!PYS!7MkN);`ck zXo`;t$hIUvvT}M12Ih0WP>CS3KM{-8_}j(9q2wySoXqEOmm@e`Y5BC(d!=+_lC+INU@%VFRobg^C=&nv}Xw}C1)Aq#n@(XIG zC#?fAW-ny;alZ^at|h>ht%LW&UFIj7(W1F=znnY&ICqY~HQdpvIwhc8$`ulKbDWvV zpd-u@oa`H4DdnN&w6{r<&-1ukUCLaVnjRzu_!b-T(yImff%UU((zMmbyc<20DLuW* z|D-3!Yv9bqS*?w;K(Z6LEsZ(5u)k}@H-!bIb@5q2QqycvBKn`XWqA|tHEqyV!pMyM zYIMqKrhTQR`*HsAVElc?-mzMMD|%V{RH8E~6?ZWEdxTOnkt)-XFIYQ=&$wTi%#d(n zqeL;`Qf&Eah>$6uMiw`Jk!5Q%5_1X3A|nmb$g#nb19Z21i=S%OO=N{(Siq*WTF{xf z#6{zOpRzk!9}Y;@`trAg`Sc|lWE^EC8&v_FY8&=Jz2A%^U189&}U_d~BNx({8 z?8WC+6K}4A>)h3&@3igxcghBZ16z8Ug-xk5;NK7CVhq1rMuL2-0*T7LH`EfA+>A3^ zs6x(pzL|N;ugBBBfOWg{su81s?jq{*0!>%AI|;SFAu$fd-pO9}DIK{&|BgC)#&k~j-+Qe4z8zi@M6bJl&6d_fLK7)kj=vo6@Cbk2X}FO39T&fAv3T43Ve}Pv{^wu5_`mFARF;=g zpB|A1)h|j6@Nus*NR@1G^YFH5r(URxhSe0g#^%6#lAzc(nM)c`=7fM##gx~zOR)!J zDF>0Khm+zE5|eJ+&|V*4{R@BFsDU(M2<;z z(vCCkOQb|^Ri@7M-YWqp#IcTtspHAam6QP5YOuFC=;BclYs$=^ksNu(2z+XUQu?xG zdrta5r&Bn-%&wBGfi^}fxSwC!Kt-Rgdn(oY>r^h3ko?i$6W)0%g3zy+AX3BTTU1DF z;UjEW^E&Tqtl_{F$Jkke~lcZ$`d|X@L9aGZ|etW%aeu zGd`=_B-Z~P%v|Z@vqGmEt$>9#wI8C_pw@DC5^Moa{ym^;fj;JvE zClDaXI(Mt5YjOOhPObtUu_-HsHM@i+zR%vQ4@*3*qw!4}rjzLf!%IEgHW*V>yVamAtJPD!_CS|`!%LD(^*p+o*D@dFp(3y(+L9#|(nKjlqK zkvCLv%zq~L1?n3*?Cow*X0!bbiaF$Z^_?6xce2c7Y!KX=ryfvzS=F(Pp5l%gZ;FeZ$3v+ z-*xodu|TQBd$rSUjAo!&^Xq0fj3y&JBD~cmH&*so9e7-f>N-6=iF{C37qcH6Zi2pK zOYMgSB<6Bek^1Oxt8*GvlV>zN+fF?pdC!+kQxn_!XBV(!xdiEXGIlq2@18Nfn(M;& zEy5ql|F%hSj6Upb#t6OC_mha>v+$(h)GWTU&6z0?R&|1SU);~R2iKb0@DzYJA%o^P zLnhReZDM=@x4XJOgQHi(e5iI#W%j}51xN9yAywZ|6;yaScc_YAJ0;18j4%4AyMqDQ z%wRA2)ghQoaDNqH^C83_5@6MtC$6dXz(m{w;$gnAk%l`LgLlRzu27_m8CUy*+1~j5 zTlVAzbS<&Fyr`!3(3t0r({92vt>;ewlRJdSOn>3Agy;PHY4t}J7uNBPB7+V(y1EwV zU9&d+dn&5g+{We<(bDErHqM#8%~kpsn~>2F)D7}JBQApIu@arjm8moa`{25R{$y9^ z>rPD9d;VIN%b?d-=O2Be0qrWt^!L0s+_fil=Y6TBu|C=Ta;kqPf3iE-fs{5{o*dN0 z;{sLNspZGh8epA9BcxHs=#Rgl01%~afIt!z~(58u6fv?hHXmt$QK{ge*2eo2pVOpSAzq$A^&TU(oeRJ)Lm1Pi?x*ihN($@W zkE_5W+-Ix7D3puwa+%3*MrH4m$2Nq%yUF-Xg+Eqem zTJLc1TJDre2>gYq#ScO84zt7aQ+w7uL6H&4%A-^BT^gWafA1@FgH~5g!Gne*)rA}E zCR4EC`4NrS1s`CnSRw3SZa1-;TF`rQfFdY>;GT)Q9ELVhD-(1l-?@I~~sg zR!QsS;f9dk5{`PGkm!}*D246HC}6idh2Gcgx)gN+Hi4MWrss=i)9qyY7xaJ<`6`I% z)%0jTw$*}9BqfWu6X~oaH?kKq=VLD zUWDtTkkXw^^Kr3eP{!a^|44mU=D$1 z!YyLKy}Iweh?eG7F&3^aJH(F82kKgS);JB?*PgnSl~+as%9fc$$dn3=saQ*y=WXw) z5V}fpS6|H1T+Ip@^q9u~W}*Ie`s40`pD^H}p&w)M`*3JW?RkP`QuubcvkB3&4{{*yOiPZVNRW`2lc1(5n~kR|gds zR}!Z-_tcp#PiTD8;Cr)js_vpJY(rowzo1~42gICg*!kTtl^^~HMI-^Ybj0H ztkESYtqz@za>jaQ*!+_QW^TUPBZE@(eHU||+i8>ITjLhMreeEhmpn5Bw6`$4VA z4qXj4OK12orpKpSSX4Oav~fNFk8ip^0ZzlYGA$S!U2flA<%q}I)$W@D_9Ea%1ib8B zT#FTLdvky>7iB0kG%jakIQo5rbMC0`JNy}?IJEYOnBL^k?eDzW;@C#`zP0te6}9M% z>#%av7IQsp$CsCz) zK*Ftl`&J}O;|n4t1jKH&RjSF;O_bjCqF4#FZ+YQmGc1NcUYECs64h)l)v_ z!VLI?aP0Ms0>0&Q0@rr(pf)AewvkTRAjTKVUa(_y*5&)FBV$O@!Oi2-9LiMkrAAJ0 z|4Gl2v1fazQ*NS|v45Yh+W{#cMInv|{rkgfTDuIu;RXYnMuM2mo=zDQUITgG~zQWqUvL|=Yt7B5L3aS#r=4j z8xd@ZlznhTglK5wi+4-5C4{gS?|pD;4yFZh0M!8zGW*Y_F;*V{h+fPC zItg^uA%)Z^XcoX2#WMe9>lMpEwMhR4*`aajnvggkIiAD{XawX&Ai{GY zMckKCy7eShWo7+1#6LqrJ(_|e20IK5HnXxCY*X(rppnioZJd!5(wp>eA<4*48kN7Re9tYw)7tVpO_ zcU-P^%1@TW4E#oT!7>_~BTc7&6&U`*EI|w;^S6x5u_n(?GJw5-CqJQ=ZPW`-N=EO~ zKN0~8kGxNn&zO^mz}8;x9C4Y$!}GD)!C8GGs`wv@0n&tO@Y4T++`(Fafc|=eXd{rt zAp6nn1CWTppYza24^q2vdq&+}(G)3a=U#HxRa#`70*|6ofjyG1 zZpSHwt~oqGF5|63!Nd7FhC=GmiNtxtK!!CQs}-N zZ*8qVGLrYH!3#u)awwa+OWsP{Np-o~piT?41tl{kr7Glm;)X#x{z7&N1NRV=im9SwO$@ST~MAU{<+RP%0( z2Df9fDecQlw9^$5(t59M#L`NA;}8*g7-84)<9oyLgHKey4H?l7U+39&v5Fq zf-B()BeBDGL&KV!upuDgjvw~Ec9+GW^{yC5N@*3gFm^`M`mORP)ics+!^`2~7zc{~aAzyz=J(!(o~)sOI}9rC7aeK_B>dd+@#(w>X`MKG1_eWKBb%yMrqBWb&VpFs1-1 z4t8tzdwEGmxmzo1G2`t755BImqvjl6PH*qAD~@O*^tS@xOpkKvSAwi;*RLlphTn2z z#5!r;Qi0Sw&p#GV$D6K3dPPfSXYea(%Fx+;4U1H?{qY8sI3h&jwE(JKq!kV^DQ=HU zzlI`LrP>6BMFGk0X((7LZUr)M+f0uM9zQ8ux$tkht8`A0qX#&4fO@A$Q#$0;6Rd6V zqbUnxnSu;LQ@NRqpT#Blef95j+SKia$}FIbm+EM7%8vJwxi~#~q3wwguQ08FMO8m7 z7e&o+EfqOt;>sPpa0NZZP6{dVJj0NKsO>Fgr)21K8T}3aIUcpoFPQnSCY~3wtkn}Xu}41DMK(4J z#abyD_%D-`S)^V~^q9Qb_VOFoVb9H{8FvO&^0w!lbzrS*++>;@09D;2u4%S}-usy> z-#Z!EfC#PRKV(^;Oz>M z?N_diP2e~@+F3PK(|6-^xlayXfSmu ze$&@?U`C`1mVdN(iOJ3zu)%a19n#CH^NJ4+$0ElO$({W+K*0Uc^DI^;qlazCm(1GYd1lCCfhih zvLg2Ma#pFMO<)$u`PNnqW+NWNGV*H8~Bt(6-gDujPXx2a0D9LN#@)w8;2_FzhlatfjOPTJ6c-SCI`J7oKYHU z{uP>Ar0~2jZ}Ij`1WmSrccLGqR~kanhR7FI*i{o}zAZ$7jA6u~Bz+@2ZW=s^F`P^Q zx1~Yx#uB?>si|_h`VcSU-v*mG@W6*&MQAmUAO+sno>|#Vqq0obxl7DQvHX_xk~$d= zib+Tjzg06jtr{ka6Y*5qi)o0%p#vpw$qC*-$fWHDP<6S+;o8+W{hTSkSaCY$@LF3Ny#KDvRB7kX!ixH0em{kj z3Wo5;u#-NCYB8lgEgcV$VU>%E0Q!x+YflSp7u*)dBCuru23gB##^i5^hX{ZdH75{g z;%hv#u2Opmv>%|(StHrGwWN%KNGOgE7&ScyU#OM-yZ9wW8WHbE`mw>Z4djd>o|qsY zg=Z2KEYC4*l^7!uA(Q={s?fDf0L=^mE(jEeP+h9B<1wI}lBwj{%>Ow-;RRJ+8k3FiX^niRBEQG3St2Toz z{0kXSwt&aN1*_FUnJe;5+lJq_NzEgGZCgvLBeehLWdhBUgrKa#WrgwA-bC0n!dlkP zUj2h`td7`EVE|iK9J{9e?gQ|znr{K}Lm_Db7C=AKOLeFLvPD6fOK3-#QYA^S@CTp< z0gZ~ISZ9Jvvj1uEk-SVn2cPtXR73h!GeqJa*#Fle9wMg5rcl=*x%6Ic+*#xHA0>H! zgFRL3n!bH{x!eEY7N-%0f}bDsZK5)Lo2`yJqXvg-=v#B|xyGG|QRQFv3$zGEjs&blKQEMxVI1@B*;6sNcqio3fPEAH+^g1bA#ix+n&P@uR6cMa|i!QCx5Z+hR)bJqLu z`~l}fWPU3%Yi93jwp@EA;YtdUD2N1zFfcGE(o*6oFfi{dq2CWaz(L{7aAiBl$O4T}WsDq~ z3Ad!Bjf_#`jF?k_D2SIYmg2H{>5|LVXk^G}ZwU%_~gV*olx zB@&_Cch^J_bZQ0fS{J`C6XFkLpOJouyP=RK|2tYW3_unp6Xi|CyK3k!PqE^EfBf4+ ziR<0eBD%ODfb`uWh5!;&J;oK%@n1iX3VmfD5BrJVeln1C2BQ~f{g2|R(WTVDEJZ$9X=kJic-cAW^}f>a zW;g&b=|{Di-0f$#HRY6+J?C)_GLLKu%fIuB(-*M@zDupeZykN#v`8iHRxN6_A>ZL4 zG&E1Sj{}`*uV{*V!10Z#?00X$MdG`$;CCSC)2~{|A9K!Fp^!@zJA;9YLO!3eH1Kzh zC4ckGebQ?}=N|!m^Y=%OB(NQ*K1cJVssH?^b7E5Ib~8O~^A~_iYd}ah=dx(P8zV;K^S8v;eO7;wKb% z8-nvEGL~6->VqTvQ2!T~cG!s!JeM(zs$$d*nUbBiFljg52fD3Z8n^Vp=!>U*MfOm| ziquaFg2nKP77ki(vQj%WJA95F)5tM0ky!n`9(N&o4w{xZ1eh_ZmEHFu^MFKAa!3_dd$YzttuU*7DeW zjJcoPy*jF-4~g?<5`RrY%DdWzaoUD32?fb>iNm*P;>LdP z6yi8Xk%{9FbUPh)7e7MwwJ4xN7gX{ZSqT15CDOOIhK0aA3K)OL$=TSI1r$&lwRW29 zCHUOA5fr43mUeK?Nj7Lsls};hTVV+P%)1=8VT0l#9P_61uX20Kt8Q1?yxRv@ntCtp zi38AUjY;2SCV+sSU6=sY-@Qw}zTFm=OjR^xdh1YO%*{L_we^j(x7+xp4mzW+X<3@P z-XGYFxeQaMp9v%B1N*z6W1961cr~j6;l>wnh|Eo3=-tgj(2aL%XeZjTZ4kfj@ik`2 z?jAHiJ8qhYY7-hw=KTZb71pvK$=H#55hiZ#(K}91(JOjGl@01wsDa>iYk^&CLX}xf zI5TP@hSBJ;>>hi%`K>)Da`pki?;m9M>Q&oO1&|5()tsDKbFErt74wrywc%qdjOD1g zbDOcf|GucJNJE^n_YvV=uu~<}PiKvc(K}=OF!%n>5KxA03|!n`L8ks^!$W_wNN=6M zkvsq5)*klxe>R2VGT#5%Y5c4g{CBM0ZWDa$hSyZH4O`(|y{f2I=!S{Hm+6MiBvt-W zRUK;azR1u{{F=NHOnh%C6gUz>Mi{tpk8CPWZoU@7D9)u48jLCWfi+{hs04kpP>WX< zD!VK4IQ(aGu6Lyg)lmX65#+&QRQjvWF26IXM{!_8bJe$lk#;?Ur>Wmm|Fehhckd*3LK!YUeT-%@p$?&bt6{wBiQp-(i=6M)^JOT>PwnCoM5#|qoS-HAe6 z`@}QEsaz3&C2h)`bU`JQ>PQXd;sgPUK@C}`%MstwBP_&?(xj1R-@gMK#NYjEFUa^; zS)~d50YYQh>3?<04js9Nvx~D6DV~j|2ZTTVA)bd$YKF!(PiZ~2RR`9JSdzIgPi(gr zp4uCELUmjID~8aLbUXZwi#|DPZaIKTmoGXJ~wZU^ik&2{UB1Pgp0@=?Z_ z(dUGHn__~O6p!G=k))Q?cvU4S=3g-x+x>M|mOrd8y(bFtTdc2HYuQCAKK4U=8HUM- zqQ7ZTg(8L8<~h7U8YXz*a@J$u$7-G9s3teULS)BM8#Rrm9ol-ojz(=2T548j`OXk+ zPcsplBUrs%G{3qGy?xIpm1+sXDu+2;z>-xGScDF391akw1{E% zLSZl7U=^`T@s0Cl`+aFPF zH6`je3V>5fY{f9%Yv$O4HO}v5(!k=s+VQJSrJ@5aRfa;}j}LExvusulvG>?SP}$g>HC}+p@~$b|Yq7 z?wlvsDk-7pN!2Ph{@6;D7jJ@Q)rkU(MW&`l?)efT7R*@1XtLs0Y5$}~IdH|AC}NB* zz>o;sKREcz%^mww!vg%iyjqMjFAhD;B|?ct+>b+?EUl9Zd(wkRfhq*Bh>U__6lS9Y z=jrKr*B+ao5YOgo{4uCCmqKjy6N4^MejAwFc88rO@iS4*LT96J!5hLtrhNnq9!>e4 zX1BxH-_k_V>;Fa&tVd7>-HVclkw1u#FcN8WCseG4=tDwoW1>ZXjb=g%yZqs;UI7;0 zmZ(KpSDnAQ!;xW;CByf*bt@7@YZfg0`L3EC4;_>JZx0D<$O7YNFL%W4Xoa8pTz!e= z2V8x9G|p^8=0a@UKqjT$`9Ur2x;GRaDcW!ZsB3Ja>Jc$awC6G+9NITu5TbFI;5c( zv{U%-ZBFNKObzvNGfJ-2DCIxrCjq&sVUOf#8>ayNpBKTI#wvG zOTGWko^JRG4cS({G*XM%8?ej{vLNS8(j)_N6Ul5md-E@<59E5(6wp`9Q%&o$OYiXE z0gLOUziRq{N`>JyBj3`a2q^%8y-~6hL|t5rD^WoJT?<1KZK32M1PSAwtqBWqaSpzA zl2NI+2$hH^?&PQ@tC^_LqQDCY<}Tb&Rv~~feNa?U5FJ@TCxitnm@&jWy|F#u?B1e0 zO(SjyYX&)kLNVDC-;?1^Hd=AX!grLn>6UW~lSk9vb{WTwW}n0qH-&X#UY>(M!rL>| zL!8V=G#5S82<|!LgTdJyQxHCEft&!g2t6S^M%RbG@H%R~Tk2H$nSq(#p!;!{KE&fa z3X0~R@?x{+OBDqJI|_|zI8DWT8?$8ntj;EbOSmsLg_XX=|60FI0%(-K372V_Zu;V| zUK%7WGBG&cJ>0P0Z)AfyjrBF~A&!{RApK`~5X>j|a(w}T3F1&&V+#p;vVbhPk1B9b zkdQ8a&Bc?Wa3De(hXqJT7x_$C#;SeYpmiuacy}}{bj~5iecUY8IJkKNYt$!5d~_y=Wz^c*N3;>&--Ser6$%3)Tse-RS&JPL zJVZeq<#(Y*>^csn5<#JzI$IAyF_>zS_wD_vMowGGILwBUnwq#Wv=uG|AcO`Lb@hN- zAHKvw|4ZVzD`VrEQ3t?ueG<2d>wgRu&EI$y_HEQS6mx|Hue0oBWl9vO7(0M-RJY(^#*;d?TV-t>DfcBR zjp~?@(e2!tPE!z}^vXY$??)`*KN?E5R6W+J^YEqVp~zB50GZn9NjqnKUIV?G&J&G0 z-#1B%3c8eU6@e#D5^WJ0QcWG|8?)WjLYKjHMdIMdq3(BQ2N*s)o$p&$xCps#ipKT#>Rdk&E8c%K$NY+kr2vDj?FSJ zJE!;f($2%Es4`igA>oL>MH!c?n%EAU1W}Mfd_0r9_hpPD7N>L_+Jb49gx1=YqE{18NR*U8gz-M-JM_6VFDl&Atb23 zYg#*Z-%O%X8_;5XzJw72!er%^nOSinGeeYx^P)Mj-1Ct@Y0KT%9ny?7N#C@97Sa;W@JPvDA}x|tS0j5G@_}6XN~Ye7Lu_80BVRj}RqA$s_x1I6fTRPP^i)ORug|#LoL_i4 z66^S{WC}v;D74uR)M$%=e+i6WbfnMt*qlq=%BgF;BIOsp5ng{?JjaSDa~g=s!8Ju)b#C>mw=%Dr zh1YZ-mF%tDAsy_(VqzPgcwv z4W&wZ9cmG1Ta%6REL?pPx`roBkg;4EM%K2LYQ+aWZ7NR4=Oahgq)p zx_v9e3G=N=XN3IEjFIIOTD zZy!yvxU!@`n26F0Ys-rm_$d$MILJ(w)8o$jI_+Q<|0^x67*i=bL&O_3+%)1PmjWhE zDtKy&O|&OTaQ^mVvzt2IK#<1=8_Yyrw{mA^C&w%fg%Xk<8k$zXOoEoe?oZ@ z)kePKY@77BTx7SIvJFhmqr0jLjx)W?d^WIlw(+cRW|@*(;v^2&ec$!CgRm^F=4Iz; zIg#M%>MSdhDPom;$eG#s3Wo*SGD~ML>90SZb0p7JyM~sm)&xBwrg1YWmiIk> zGe@%p?&*_==CTmZ&0VCycgV?lQw!fs#)b#yTMTzA76c^~*wtog1&<3CWC)8oH69 zKYxA%2EIi^MATB#mXYw}ElpOh_3d$ziMX_D#F(#-{t@skspyG_c%>zw#oY$3(@`)! zNU%3A4&(;gIaYMKgXVWX-Eb{LZIT8Tdu%YA0I~1C@`X!C(-!VODHNmPqmDAf=rK$T zWBQPfRH)#mo``!{z`WM8C)5&IZ=Ir~Z1BTqMLXwyG{frt+5g@%dDh^DU6Hn=G_vVz z4W&#=nRiDhJ-u10x;4J2!-1PVS+T7RN-Q>MLM7noIt!J+NZ?X4pPQhAF#UWvV5hms z3h;S1Q0=eVH;V8S3$unrOydyRj+lb3(ZhS zsvnehmZ8lyH@%zwwRc`FnvNl=)<_>^Z@l4h)V}SjuP@=jb(X78GIOQr@*K9nYxk(; zxPIeAHzdb14Ez#J?QyKSd`IFBK@18i)+Q=I-vmbV{lLN*T77)aRQc=s=B1O>(c!+8 zHSGFIc*2zcog;n3@UY}-vUM{HG@JdviniOqJ$ka~MKDZcP;Twfo(Z560OuFk|7;Jq zz-CLpo}roU%rR{$`xPsH9;ika@(Cs23^V$x0~M_)t6V}~sg=bkL1R5PXSkv7gOFU$ zIy^H;UW>oQ93&^YLSacykaMU;E^iVY%5`vXxlOFH^Nf>c>4&PQsbj^bcw0Yb5zTKc zR1Y67`-iUPXpP3@-?ZM(U1&ogx(Q^Lzl@0ZQ(l??^NQ-|>X0KxA%%=Q0bZt;ZhU`y zXpJ~AJ4ZFofdplke-KvHZJN!4lxeIYhVHMMS8dAl6fEsX@#lB+B+18fRtDfviq6C6 z8Rs+@cjiyMBYaL+|D%SDzu_h9Bx(E$6N1+t1VLfuS#>w!MW^DeGLY9La|+m<=*ZUTbLO~ zH1uNwR{|AvZWj-a1D<=Gw3(J=shnxeOICgdvS^cF;lWsgwE;}D6SKZ4tCx+Y`33)L zj2vH6Zryq2t(NijQGR&EH|RBt#4BxaVQ%)n>u7S;UP#vjUDAEw6)z@MGZvcdc)>oq zlnOa5JYGceS06%b+MiSv9nZ4$v2d{`CfNtC>_6??H^i{byeDkG^(20|$r(Tn`%}!Y zdt(10M9s`~W&Z*;-#=`rUt=ZIU@{))2M`H(ra@41NZN2*W$EwAD}}`S9q(hoPYC>T z^OtGx4NB@7U&zvoz#CUSkPt}I$`q&DbE5IilvB3fH50JB9O`2MENQ#feK^_PS05f@ z4KkDHvVPiD+uEWSdUz0)CTpOhEF)7)WwuU?pc(QGPS$Gn>qA;IX&_+rfqeH$b7=r8 z>GJRT+8oW>oNXw|O@DBh_3kRZ-XR??G$M=95_^4PM_cQNtKCb#KLI~mhhkVF7yK#J z?N#*mWImdoMUM?TIK|)Y?7Di|Uqs_^ZwEXKw;M`II}&%?A)(dUonX8?__xYY7+!W-_G7kA{7IdhvWt%pvZrM8^-^*Pr7vlH{mz&QI;k5KI3~%V0yeG;L zy*2NwTbc-`uzn@h9(m^4vKR{ZivfJml|9Pcjc~o#|uSYh-YTgLhnT_ z%5Qci>ttr*$A_J3G%5?bqpqB?!TR$@NfC0~Ew$I2(x(g>2gsil=a)zsg z-o~H`j2G3ErIr(Fu(BkYimj>)MO^WE7l#LQQOxf2`4}G&Fmbz1tjtBvrCU(+PRFkH zXlA#DMQ#1H2m~4Ypz-KxlWCb`wPc6=Z3(^k9u9d823m7ZyySezkAsFXbJ7l@;ue9N@kQ-^9qV{&YN@BAw4-Zd_b%s(i1!4mIYScAo&vkMUTzJGJJ+ zGH{rd3fWDahd`zW-NB(ijocVo_vysBWn z+ZX5j`;n*bdur9);?hQT*?ssXr{@NRAn73@&~R zjknZbF5Ry7=28K#NQlYe!rb#J`&~Fg&Yg3bGICARd&~)%W@e-H||H7;AhE zaE8`IC??FWawobWKgHF+^>>8$BuK0y(z2 z$+g}Pg7owjOUnad2yc3^6i07iw5+y{>R8^PG0@IHK~j>0T7e5{F1hSW0B3?nJPzwb zf;|Xv&FZsHxAsC^Yl24>cBi`&lDHO@2S(7%d)i_TyHVA*LEfcRUr9>~q84WEuO0Uv z)V0sqK97?{My4n(E#0lKrH4YwR#y|6+VeV=1entGTrMFJ`#E63qZ<5b%eQxF9b(a{ zX-r%y*vaHw7PrJ*Uuk>8p?IYQgRl0eEH{{o0<|rchg=S^nt%K$AxMlLkksNo^+Wf zR@S0bs?6?<{T@JVf1M=(0h4n9Gq`U1kM!m+BAw%C+Yyw@rH#AIxJM;d#s(;=8jw~IIAMg!~p_rY(P+o+w z-}NDUtMfWX#hy_*T*qyaq7wu-yW%{rbC|IN8V+}w@5jc%-adaig79Z) zhIPN#7UPG(J0M8FjC2~m=$lgmC~}^03qr zu`c@t&deSkuw8CYqcpO_$-8RwN;Mg`P9Uh~8Lx+mER2y-jwl&iWqX8*-~phk?7gG1 z&$VNwpNR?+VexoDNw)uj$0N^g#aRb_@7rRY3Pv$<$E*4H z#MEM#O4Xm%AO4Tb*~U=UX`QS-x#k<%hbwiB+-|D-+vhTb+&$wfrvoflGlyZ5STTAn+ zuq1Whbg^?|8s%y6)yI>=Q&l;B{PiXyXKU@m6)M9n5YlMt?F+5fLujMD_otL}KF{49 zSeIL5(O%>GO_lbG(wsc|&s`+X1LizHVV(+GU4f?ws`i(9c+bP|Pcw#g`2_`gg|L1o z+KxBaKcjsksVSMUbiL!{o_oQ2+{?h{fSiDU-{a;czf8X+xGz%n4m3>Sczg%=KDj#= z_e0**m392-8_BrPE9pU95FqU-($F`Gnz$o!K&UBti<&7mranJE)_G5N0ciVPU0s4m zP{&^t1b|j~N!`!R7*qhxdrc4NZ=K}r*|k@tfAFFMZ4O&>Jx-oTg)Dd^`jHCF@0N<% zi<0QuK5d7ZB=#fqw~evMXM4UfhK8PrTK+2a|1QgDyWO9+-5aRx4Xn^t5V6bj4I7K1 zvVaj7-0Zx^6S3b@3M@F_Js)4BXIKO}86?&)*hZzn-4oa%56Hy9^#;BOf zO;ksVsAA?`=2`XclIF&Q6y_T?y@;)?iVU*$1G21tNcOZgp1qT-sM}y3 zg67GRRCYD5YJyO=Q{}132;jc=@Bt~&^QXEFQ>^asX6}_gZKI=*nO2MbAPFF!xk|uGw zlPXhbP~%Ag2-((F(85qvTUngL?J*@5S9ByNE_k#8{?vTBBCAZVK|=#qXT74mu%>1r zOQho9gfa=r08Pu;9p6&H-%nn+(+<=Af_jJM8p>csLNQvW9@ad!A9Y9HGPXM2KVl-J zH}ek&?s^f2yATX>u#SFKuKHb*=rBk|jB+(`8oh;9@vD&~MQX6H@iVSiF+MoSpuP?f z41oquzAIbVXIE3pVV(ykJy_xcw+D~u6{i6R(mzf4*jJeQ2yB0N->P6nGiE^pEa&-9 zZ0LIBroYfiNJzg4RS6cmZG1K*N{PvSnKa-ehr^`hNSESS5W)b`(vEED`LeIJ!D8Mz zZo3H1?wHUM?(Fo^&@=tYZ;6#JO{uZDxT8&gVort@(a9v(Hqz9qc~~Y^7z}a=rDr@* zRWPDu9HKVW)w8l8bRVsot8<4;&MZkdikt?|*Soq*&Mr#|*i5stNO@ius}#RGh!PtF zvWzt8;*>SFq8DIAmkZ866CaSsI2M$9b11`fnOm~N^>d(z0(qM&Js3tnk&KuRFesE$ z9Q6=m8VO4y)WTc`YJEX#E2uoWs%3pnbIW}$65N%Q;|G%Fh?kllERKlRWpp9?-cV>x z)<)}D*!)d*Aa;fl97NqUa*2UM@ji(v`RelADh+jSr&$Ka!!Ku^GX?~U67#C^zH2dv zYRe-WYCSW`d%l&TWUs5cmeXQA*eu{88X(6&QPxToQ&q(k_Pi%YCFWCv+BXQeAwX&Y zI%VXZ&&096kR@n1+6?ja=JV^z%|&~*b91rUp(I0$Vz)&(KAzOne9o`mJSkcny%Rsn zE-88k;?zu6JS$G*XOH2bEU-Dtnv3`46 zfdqDAd)Se;M|-TT&bFkJ1xY4PmJv%95lLo#&}$3_gvbCyO-{Tz}t{Z{1uX&W=g? zZm{#Qmr(Ic?>o>!6C#jXJ^>m`_d7}}PU!*bou7Eo7I7w}e$;IG+}aqjGljF{RTm`0 zWCvJM^CdP@p z6lSI(z1D&E)NG!as)!xd`|Fi&5=C9&R-$0S@-E1;W9iUdKUpwCWP3nw@Vk&o&f+?; ze#dZ$ZoJS(G%w!R6K)BETC3>tzmycH+F6swAurpdUxJo~erT)s zv7xHij`hOghgyHvRp8lhNzGeiG5MoCQ6mH70;~*8W}_QdI(sG#;8rNglY}P=It5*Y z{-$?xJP27VJRF2Ne}hLPV}u76R}~FNE7Pw{l_XvpDM?bNDR3ZS-WSg2r0i=lC9+?d zm902RkdnK6=38O#sA;26MJ-kf^$-ZO9j>IR1*xe*lC`9eO*YjgZA|~@>OR|4q&l-O zEz7|=W4gq?yQ^N&i#hi9SBQb0T9k5v`}uD4Ed{;zs^4YCPjv3Qz)r)XG)@hD4ZXfS zuC?L3KotX_E7GE6LcAdgM}gQUsmz?FqXfK!cLLKD9{6jgc5{=n?maCR zO&^2uTJZ`kovHygB}23HCwj4GN0Yzgj}CSM5(DAg?KdwTfy&^SE+`M2SL*&93W<3k zG#_JFZ(w=aooKmvqItTqf{gXwBrh5g8=GhU%wfg7&+=X7W4i$q$l@hk1L0DCh-D7%UGJ9kB_37iIu$8H_ z1gUHZqIOeV6!jUnJG;E}?gc5#V`DU7p%8@W-Efr#&+YgiN>S}`J$Fehr7&>VM+)a5&*!d`Arwg>|@8B!OgUJ;y&hlt_17rD@{Z_80fpD zd8?wG7F%#xHOgi~9+4Ypg*Qyo%N6vl+=xbw-2ARhvU;?}F`&dYF`q@5PJ97+2##1b zDc2WsIRdk~6hRj=A+BLq?_Kp3Xqx?`Bzg7e{iUB?rS)O-u80nrLfa(rju#w@E9Zus z^lV=@Rd`y6d@1O&4B02wzmt)O)OU_<2WOksZOIG zI!s6clY%$%5~QoO@C-yzU2=lM&a%GgmA?IRbL4=~b&|V^Ci6P&Ne->lI#;*Z;_Pn77X5a9z@R{3&YVM zf1=u*F)l)qF4EsL``G6tXyElUH5G}N0)x0rPsZH#(d19CX?Kro-+rr>xc5MB!5{Xq z&)+`Q7Ik=Ka<6bxXOHzasXh zS|~sp?!qHgoJ`D^rl$r_V6)cvgWY`jZn9Rg$)(ttW7PcD2T8jZ&5%-9b;W_nJBt&A z58vvC23R=oxh0lP`fsSt>|OXrB+%)DQ+3!rJ_&1Kup^~V%;9h~`7LgZ$xN+uGsh#v z#f&gGo>za&&brD|r84X8cSUjOQWwOU+4m1TLB=G*(J5X(3uLKoCltj9bu5?^RV4G=to3hML` zw`|TAo6WH8Urq0rfFvu=C}Ai-JNm*uG`;+1hJ~g4ya(5T5e~!>W>^COQP^gJKV?My zc~X#YABxKc^DBVqCL}0v!iiMbhm_iJ!_N>#v(+Wz+cx)f)goQir#NR5WNMp!ErZO@ zBkWaAdN$zv&%!c>{^`Iutk4YhrMA|_k#C?pQJZ0LOU#0kjSl%Q(NymRIB|Z^XCdk2 zvM4R}OVfLKPjByPZ{vKC-CF=A1F9^2f2K|h^>M=O%mToA!hTLiRv zCg|lvonrLx{x04V9z46{jLyf}JsomrOBTSNhGo*hOfkz;fRxQrP76SM4WV>!|66Bl z#I007msS}QMsB2@#dxm2#Yb0H<;;14uY|&|+k0P&_4Iw z(w9KbWH=leBf*GCTgZy~LbQn+%~@URv4fGkrOfpZFMFVIn^W-?k#xRw-OkHq1esOJ zt}y{z#iZg8qF=G29MZ%co%E6wCE&ftYxsk#&9W9K=A__hy2U=4P?Z5=v$~BCVHtx+-=3Lj^}?>*)zM7uxcXpNXTIQ(?+`qq6V`h!1#!tC#UK+4eTIChl; zaJsy#lz)p)n&Mvkxq({rP`JF}8u9FbL$|es0#HJ5wn2?h*(xlh>46^*v;6dw<$#BW zN0BC7%b_RQ3Z~{ZwsavR47GXRwINfM%Nxr#r{A)uqT-RG$yO*UJkR+Dz^1 zKM?R!TbhH2LYt|NQ}Z$q5N-JME86?kCuCIjYSFzpV;VPo(d&R>IHhj^==^CG(A0Xa zL5@%wUWfgbqk{E||Mp;`335p3`7E6hT+jw4^1bC!%NZFrwT$#Ax_QeOOxNXdtj{H8 zFqz+k1rK+Z(mq3lZ364n#7sO;_W&){5RMmiT zIa3@TG29DC=XGj!K?+Ua5J;n0Gh6YI1O#`sN;wFk%_$tB?8dnCHnX?c-0ZZwV!=XR zbj^QC6*JJAo{jO58AY1XVN>`e233BgqvdEn%S((c`ZQ7%P^4nfy75dsIn*WnejqlK zv0FK%m%`W2tfac0u$&W`+fv_drR4@uGhZEeKP~_(LbC|1JWqnAznnK2)RskfH_SU$ z`d&H}W|LhFy{JOd8r$O)rD15XX0O0K7Pjk91+u0-peR_Am4KUW zK9e93Cifw2e*;Kv#UhyeM@lc62M$?E6c9go^eOWq(*I0m8J-BB}f_K{H-gVSbQhLwUJX91RH6YJ%r zv5VVng4~)O8ZnfR`8-YYU(kna#K=tj0TQlwVi^|-yl*GrfB{9_ET>K|_b8dji-tA` zPP)X&axxz41H&&fMVTOVDsh@4L-7(%Th$FeLdXQFPwj;2-EhlSSA$2+w^unT^Ye>h z&xBrapd91CUDLR5r{MCuLqT~)O`bsVyc!!%;&xV0k>yFFV|{NfJ0nBoP?0-}nC9z( z!0SVyTRWt?#piz7`>xHeO z;kQho&5ty6gFDPGql(U(qU^6=q({rc#`|K*o6#&}s3zs4V(XUsp2Jb$BQ&ExFxO-NQ|S2Rc&R- z`$;eeT758axm~e9+=@QPWZ@Hz7(NncQlGV4@^vYHk-$b z8hkBq4xeJd&nHDZ{?$p4HU3d&W}?Po)`2afl9GstFV3>u;oHX)OCjisVui{KHW&-c zHkZ#0=PSz46J2Jy==Mj18Xqh;D$e3u0(T1EK#9h?7Bv46^Eq(O!w?{G4@U*OI`n#V z=+3j?5xTS~lZ>mWtg8o#4^&Bi^p6<&L;2;mi?n5qiv^U@boOQ@qSsCd!E+ALV4}W!R%2eg9A6r(BN`; z*q%?s=Nb1SPNeu-U$P687!`YUwcUAUkP)7Uvk^+=nef*^pr-?b3R*3fQv`puKNjvM zJj?lI&mv;!DAdw02d!TddIG@8dh_H-j#LaFqGQ7ZIl!Q4=A7$Toy-wnP`4-9{#@caj%2?yRK6^7eL*{0WmueyytyAJ0_5K#x54{IGUI!PY zHGR`j%Q+9^;D$37hUPCgpbH=4$(MK6AK$9%cx4+sS%nrQQI_YJi}FijHE%y{ETnk} zT}@Q1JM##{38GT zHwFOn*bN zl4N%sGz=v!TZqToJl`#|d0wC1*yyW@dAkb>d+eYK`#sXYiqR%BGnt$L)dd{p=?vEV z5yv6Yzu8TR+*h>fL+96oCB&R@4ZUpOp|$=zU~};43n{cnPXiq<_@Qu2w?w8X9qnm9 z%jEZ`l%mtc!G3vJ&~N>}Jo?M-nL%Nj;N6na91?S@$Is0?J-1^m5VUBvwu(zp1l4z%oZ`b(=M@LY zG<2I2TMqzuU#6qoS0G!?!RZRVG*|h+`f5th*G(Pp-0glaf)5R55|^s3D)@IBa%Pu1J4^FyhBV*un*(-^ggbJ{S*t=Bm+TV_Mo|jD~?o=wZ zzp3ax58Auf^YDe9eftqZiAbb4ostSVltf$xn&0S&DhV3n!6jR6daVU-5ABhx_L-9` z_CaZe?Xw(TZ;e<%GOb*T<3?cdU?jo34J@r>!r(iE&gw(l5I`E9Ox#$MJ)*9<#^Ah= zxA1#U$M*XmO$!^F-z~y@eMq=c$S$=$j;wGIb@ocF7L3tZVt5)Xf`C7z;W>7E@*gJ> z49A4$%5r8QdJT1f9Zx-#PNz(n;MU`P3$C?HonfNe+i2ld(bNs`oVC)v&>vwzvy#Pd#NtjjZ!7)P3Rk;}_m=P{HkglFlC?a7=st%BFae*ij^oEKW zB_h({Po-U31n#==sDg)%NHWbFB|f4ZYx(vREcZQ4^BTD*;Q1>PH-8prXMM2MFwp3P z7H9X5_xE~&_9#WjdqtC_CgxWt5dPknm0*L`R*t0TbE39Jyy^$8EzD+q@4{)!sj29t z@}Hckv(rUB$xObSr>uC2NX!i1Y zdwM-keWY-9=RBt0h-H0bRZOX!%*Y!d7?T2uVh4G!pni)2$z>GzXc z#&Y~lwaKW3qilKdjP6O_&YH7=fnH67y2PB!r9nIx?Xx;Is2zf( zU3Lm~_TS44D34AyczxPg*1*l;n1Uw}oaz}^Ha~5-8}E1gZT~Wsa-B49sGQ#WFw0Lu z=dPejSo+Y@aRuN!1uS^3QY)lP^!+KYLzfKD76}$9^t4dlm1v>$5j=GJt{k zPDlRxP5-`Dk)7Tgs!jq@X#0JG;kqU`b1<{n6?a2>@;hV^YvmhuNc&53>y;IU)!{AM^E^pM?(5Z@VQB_HX3WM6mpc3w z4YmGe#oVP9+Xd=jC6^x(grA+CFNE(3UnbrCG+#FjpB?Oa+5yn?34d+Qn*dru)Vygs z^AodgziEFNMq8WN_$bT_y;UE~(fQtoQDsJ6VHHO-)y{o1*g5v~rNh5C=jD)F)9)$Y zoExmYdsv8jDzLgZ5AnYaUGqC5Z#!QJO}|Ocge*a)%?}Zt958RztvGChkG*Dwp7CMw z&4fsZUxKjTrb7=o-1-VGu1$kIb|lK{380$EQcy$_^2~z>J&Ak6+s-};$M*<_C?^gM zTfCl2RTIQ(RQOFHIE)>QulY#!OGSIpS*Km9CFk1}l5||eoC^DtxC?o>Ej~V^DCox_27>|Y3ZB|ZLHOl5~kLYUW?00!o=zI7^6z$qP4r% zLu5`zX-DeB1)TLlYIcIxeec_hoVJS!zuW#6OkNxqn9jVtSs}OB6;=8s*0nno-{`Pk-dX$M(F(#wHTv8ZVzHQy}NnO@?GiQJ_qF zG!IoJ1Cl7gI>7_V$4)8pp2S*yew4uU{A`j3c7y&*dwBw(nZ@#66Z)O!44<_G*023K zp7RNT%0<&jE?()xEYbib9%LApszEv-%QsqPMk9N(U$i*04_;Hg=AUxZ%nha{*rlN} zoq6#R!t6XB$T1yZ8SXV5-h^63C&w&hWuOr^7Sh=spnSU(@|D}8f|0|>;^?H@9iQ!6-51MD+yQvYCXu;yC= zf24~ke7d-2G9l0Y({)+K3Wf3}8AG}}DH#JJ?B`K%`}#el1(|^ zJ*Ww;MS77&S-Gv6Imx7b)2Zn=T+R7wlv(@!v;Mk&5=bE3zw19N+5-`9=h;B%(Cm)Wj)j ztMDp&;Roey^{Kfzoewa@o$)7Xt?p+0Oyxz%xV#cVCkA1X*OXw!ynrxEo@}3d6V?2@ z%s9Do>Z$8qVEzu~!WJp6x6@iuEn*Vu*@)a(&S^uh8PsFZ=E|KwY1fozMXxGzN<2)&{(wLWkYUfZ^x{Lu3UvloS%tS*f~|Yp^Jf_ zoUcH-)7{#Q;ZYeC%%IkXZ}&^_OIlf*Lw2f+cq3LhZSH@;FiPeWL?OMiQ@qN#(hi$c zjm;@c3HH9V+X<&TKb=oU#zooLEe8lLwFdlpE~~u1&))q)Xo)Mg@CUZBL9Jb7zkqG% zw?f)Q*Fr`l6Uzu4K2cc(V{z8V@By{Nk^8tHOB}|oC?h%9+fB+jak*Qf^Rct&tjqg~ z21ko;!{_{3KRvb*_YV>$hcPdQkK@)F_ob6-4O=Y=PQ%NjPw%TF9$98B1{FN`G=}G~ zoI6}Tos~n2n@&y6j;?mH9QyH3Tv!D0-L4=2AIAdoZ;ZV1C=n)w|4s1+uA!;nbPJE6 zM7hR}_-S;Ste9wV`>0~{Rp@%sjJfIB-|ao}O@g(n3qNl~$|gsO_g4RHNar5(5;bK~ zO?R;!G%2R6>ufb&xIUfj_uO+ryLrv$htDVX=H8k-&(2Ws5gbuQW=&aUO&}hZB}9=% z(sGOyofyOWz!WPZy=SbwU<1v1^Jtm7o03lc{${@QdftAGNTtj=6x9@VWoz?I$3rV3 z07!zdQ+m8MFq^n&oXw1sCv#?bQCedvQq}8yJt$rOf*CaC~Rvh$sc95U+9^Vm^p z8W7cx+RS-=0y;uMsOKWw7^ggEHdJDnJMW;E?=Ehm2Di=1i|6J|$uG_P;lGJgyoP&vSP`$SA!64x{Z(N%`wZwVvb{#^R|RoOY(H(esWJ1obx zfTt(jn39%Xv{HUG;hCIXF;15eXV*IVq?(s4STeILgF-d^ee~4em}^;|gi51btB&bC zXEB~?8V^*v=A-YAc)q{;)%7PEUN_}xvXY9|N|f9{-=c~n$jmRu~cg8kQ%lpb_XQa-% za)~auyuvabEmjpV-QA~Jmi~vnINIW=-nX)pLQbE&BA#7OA-W<409M1-M*!P5n%wz5 zxJ)A<-X@ExJ9_n_IvMbh*G9}did}ugIS9-y%q8Ml_@9{FvG)pP!+UogF$0T$b9{$It!U?Vuyl(!ztzG|Zb*V{~-tOKLWO!+n z6`fgmOLe&t+pE0XGNUAk$tkR%vmxF^;N?+u7Vh%Ak2>FEH=z5E2ba!s9YH};9n8u?QUkoqY8H90Ryc&@oiYNN$ z?r#Xx4tfpHFCCl%UB<+Ybn5Fuc1Y>FomAxv_fq`w;+-tcBUkg{mw$KZl+i9E4 z^_jut)s18WZP$=!Ntx{(76i5w5jX0^RFsh%c)p`>m{Tw{nP3(dL=II(*P#s~#UI)* z=0>9#qm+9-k18F@>ASQ(H4=_9_{L}-XQzIh`#+VuSl`1YbKf<)lEn8VuJ;V)HdN}? z^WNnsPwIU7an2Jhx(+vauje*y7M}aq_Z{7|vI;XV$T(ch(SxWm2=|O`okd3xfg=m~pg7%G}z@ zRO`~Tzj^LUeBL+p0Y-^ed8euh78V7WYUeE3B_&A4gtGGPhU{}qrD4;O*13=S+aJV6 zlQ0f?wY5oxMurhK&2xxxnxwd3omWQgMf2^}Q923qW}@P0l%X_qN*cV%vL`v|+{#r) zFO)u>pGOBMkI76;IJ@QkxP>_Rd0~^S5MJ6sij)(5Uy`^@D#ZO??>;gt6L}WKqS)zD zT~`KYl^s&i8GD!8o;t8+9bjd%t+KHEa+q?d)hG!@AsMz1CZG57q?y!BW)Ae(2M6b>Uej{jfK8XK_4Q zD4c8A(^lM2UwMG0RG`9_i(el%!SaXc2kt5ZPmMEq=})imN^qw&P*NsBhPY*1At9yQ zc!(J%spp!C&-<=F@<)??ey4o1$&l{E$#n%C#bFEMop^ohS2rKO_hjEt1sUHGw`Vwa zi`db=WeoqoUWT`>XgMli2d1R^X~MAD!e}*rrpOpMPC4}?I4>|UC+&kw=%;al#b8G>(qtN-Hy5V zTHY%?g|qfPw=C77=3-G5n8qELrH4;Hp^iTCL2pM(vUfjY-l#}7_sfX0-IuZN(L03O z*G5y}H&i~7Kl~VnxPN2AJ#OX)Psgs#LH1uNYOotb((~n2N^L*a4Cv?}+kUjWPbyG# z)N^2mlH#IzEON%vQTAtfJy>aAZt@}-e-vXy&Z@O4Y@I818a>{#-Hbs=N@4QKXZ#iY zTisZ^r~Mcumy&)r>a+T+sGC_}?%gGz^td`t?c$9Ng{CL0M*$mwUmlhBu@VB2qIGRj zUT0Q0<-0{Y5CK*aJz2q|{L zdDFZ3lhKb`eAl{4TfAm!N3lIS_4d&sssHshqzf)wd&p4(X3(f2C;=Pam@8SA5~N2r ziI{L#8(ooEMIa>atZGn_N{px&QL#w0;jT}C?V1Wl9zhV7DD$%NTJ!U-Pqt^q_z0O7 zY-|;nDrxQlKm#*7C13@w9%YfLb$-ys-a^nRMdg+^N^xDydpg^DM{S&kgt$7SAXd{sgTm(E2N&B zV}G;FHHuI6s(WXe{cHbny;AuDO~-x36=~CFuS}0I4`)*o&jxlV)5VL)1_+Wl@kTn$m9Kg#SGZ4+l!zc!@sm27-1P6w( zg7SAaQCS=QrIz^eGt0~7o5@yuMLIgJ1J+N85;k*=`>zmYyf_=)rWWBEULpnEm$$yy z46cm)@U$G}^8vV41ONr+#X_$0-%xMVMgFUm`jtTZu^Qv|eUmrxbU<|IJ+^#R60za- zrK&IwH`HZ(RhV}8)8mU3YAm8zCUb+QAQQ$Gq)R-U7o%A!f1X1Q~*D* z157@6%c1M-1j5JI0Nig5gVr2B^WkskM5*%S^Dp`%UrPUcdu6_vQo!qXrj#tp-O^$h z;95W)wTw|BVsQL*A#o@>Wh!yVFgh?0`k?Fh`YK?oYh7)4MB~m?QUK1T;A^kzWvlT< zXvkV^LpnM_H^agRHvPU_*Ml(mYOA{6sd3%qVbvuvmDInZ>tZ5gs56UKkYL8*Dg5T! z2j56CCAuuB!=#AbNTp7)DZrFFs2sJ|F_>6+qBwWAL5?59_RwAT(&;XmSNFgf+ly z24>m{1({HhgdQ?a)(RdI07;A>tN^rDtXr8=cf;GDcc4x{u+{b^lhPGlpa{a)!gEMa z{W|^!NL;`|DpRgQhYA4lO)LpOkIbkNRE1stN4+D@2mq>2psoOT4-$h^*`co8*aA|a zPxqR#VqG5G90C1n(6C-X(12EZU_S*2JCeBuDOx`k2T_gzB;I))BR&C3lp#|mehsp= z{RBJzAg*8d@$f+NquathP$vc)L_uQ^dy7?E{jUEpEd=BspW4i7yC$M2gqmdZs%g^zQqMgA>~>^w^ObO9N+iXvU1;;&TF&0 zO?Mpe$sLcKKHYQaJF7{99M@(H+U*`p_^MKSMyO!%n77=?hX$N|5I^WA4_dmDh%g%W zyyb5VxXJFJ8)+m@?=IDZu5q-+HU2mNUWc@)U% zU%bc~pob(=7!ItohC^gR57TN)IV%W~+E9VnwSm{sOvqMC>2Dpa`Yi=59}afgSQ2I4 zgg$}PaSv>v@@IF7+TQZ&0A)+AN+ccUe>YE}Ssk_dSV`QU{yH6&xW@#oqZJlBBXjuy z+$0;>OTU6aTw7x)pNClCd#8y|NC5p~lcKKhy8`65vp))Fc(nu`xHU|_pD0H{;@S6C z+dsfzqdDM$OC;gB^NB;x19B^}z~>1KXd&YZuYf0mpG95$^1F0?42oNP`J;%CWP{xI za3zD>)%XQNia)Y4>lvsvLZEt$`kzdV4h6Lu81)97u(Lm%c=1bChnTAlt91Xo!LJ@c zi0vKrtOR7Y0{_F;-+sZe_HU>ZGl=q4MRKHhmb#af%>DgWR>Vz6#+VGGfDslA&F2mr zN};wE@bnh|D4rpcDL+DX-hg7G!kffgOg#$ZHIRq=m^Alm4Do&llu8JJWEUbmKT?k7 zg5vj~I0ukFXMQ8-IY5fuLx|r)V~w6;Crs>yULMHv{U6WF$nBcA6b@o=k^hZvMc%0q zhaqzZ8J~HHd(QThOcl=6fN(9Mo?{dw-@?%3&e}>lZLVLFU?w?f>FB)r&As-b!?3 z(QX2TG+qf{kg279+l<+3>JKd6V(-tG+=*_DfeZs^(RG|_Cr1<){hk$^nH1<~wtIB@ z%=3o%6^>WyhXWI~@m_~(YErKf$?;gaAp-$FAwG2iIw%+b?W+zCh9+6e`_09PBw&AM zI#Y(8Zuu$&h)JKsDgMs5BJD`wb|!!4W$lUd#l|PDNHT!_Us?h5Nw;W^kkg_u_jr6M zfNUFA2$KGNp!tHIhg`z5SD`OKHv)D-2cde&e`mlDEG`8cmU6 zhgLQ3TAG&!tgcjr1xeh)e?8k6{iG+?)y4Koc)`u8X~_ zbKgl@hKL*n5L;?Y)Fm3CowT%4aAQ}#5&;iW`%h>6KW;q&Gi?j2?J;OW85E)K`4S*U zft!Y!I+`$u*e5e5>t}`yGZ5q%&|UCiYwo|8jR41=T?z1;Q+g7D!jZ8K0~-6icz8sO zC-KBWa>W6QVjcLm`@dC0?(8B_OUGrRypMygW=I#L{%}@3Tu?tSiK{ku<#RzMt^e1rt8cFKhQVkRa%W2B&h$Cn}=% zu^^tZmvxwd9#XT@R{zlYJ?(L&c^rJ@LR+TZyz^I3uUf8#ie%uIYcxYZL%0(f9x1!F z9Q;;=^x7M8AP8&SMC;%V$_em=NfD&=^t};ni+!}#UzknXXFEr+)z|N=+NPm11h$z@ zoOzGzuMwvGC_@~Fg>Q$KsNj0!1bpotHgb$=3(QFh4hiAY8dcck`sDvgVv#j^6=1Ae zjgUF5cITC4YvwRCyDi=~PG8?jhK zFdN#WBg)NAj1HagidYY>q^}$I*TUCqg)^NRXk_}rN{nyg_M~kZk-tC3YJR;ncN3DZ z5yqo;L#s#$u0`^xlDgouV{KBA^vHeimu~=|j}h<(+A2Ow8}3kR&5E_OdI-#ol+;I& zI&9|zaUX|mE@#~sf*2{@#gZhBdQD6AvSyfuI9AYi?TztRwMV6e_eMK{^fnvF3qJc= zgD~tkyo&o{Ithi#kfIkV&WaEME2zZC9(h76Dr<-BFyo3MOZnhAnnCsyBn7QJR1WE7 zautvkUKdu*{VwvBsGpetf`JNVGAC_c!5XEqLC@jw|JqvKtJ}KXged=H8i#u1SbU{i zMy+%n*98hj+NIG#LP#t~4tDbo`I8 zRO1_J#`sEzVnvvglW_!uh{m!Y#A}PJf$a_?{E(Pt#H#FMND6Ichv$mCl9Hk0!hd}R zqyT+kAcXRDhoUAGpi5!fH}_Nczs(ZM+Hs--2v;eaB_Rc|phb>vKZ%*dYtPuQ(};mP z6?6~C#{8%Se~ta$cvbDeKfK4lOP~)ds=PYVeveJa+HD1gG>V@zI-IhCgo+tZlhFWu uM literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp index a8b7a670c881b..c11839f0356c6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp @@ -140,6 +140,18 @@ class NormalLaneChange : public LaneChangeBase bool get_lane_change_paths(LaneChangePaths & candidate_paths) const; + bool get_path_using_frenet( + const std::vector & prepare_metrics, + const lane_change::TargetObjects & target_objects, + const std::vector> & sorted_lane_ids, + LaneChangePaths & candidate_paths) const; + + bool get_path_using_path_shifter( + const std::vector & prepare_metrics, + const lane_change::TargetObjects & target_objects, + const std::vector> & sorted_lane_ids, + LaneChangePaths & candidate_paths) const; + bool check_candidate_path_safety( const LaneChangePath & candidate_path, const lane_change::TargetObjects & target_objects) const; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp index 9e6b9d229d2f2..c844b6b218d10 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp @@ -269,6 +269,7 @@ struct CommonData LanesPolygonPtr lanes_polygon_ptr; TransientData transient_data; PathWithLaneId current_lanes_path; + PathWithLaneId target_lanes_path; ModuleType lc_type; Direction direction; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp index 589f2f20ba258..eb07d2f0d3704 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp @@ -39,6 +39,20 @@ struct MetricsDebug double max_lane_changing_length; }; +struct FrenetStateDebug +{ + LaneChangePhaseMetrics prep_metric; + frenet_planner::SamplingParameter sampling_parameter; + double max_lane_changing_length; + + FrenetStateDebug( + LaneChangePhaseMetrics prep_metric, frenet_planner::SamplingParameter sampling_param, + const double max_len) + : prep_metric(prep_metric), sampling_parameter(sampling_param), max_lane_changing_length(max_len) + { + } +}; + struct Debug { std::string module_type; @@ -52,6 +66,7 @@ struct Debug lanelet::ConstLanelets target_lanes; lanelet::ConstLanelets target_backward_lanes; std::vector lane_change_metrics; + std::vector frenet_states; double collision_check_object_debug_lifetime{0.0}; double distance_to_end_of_current_lane{std::numeric_limits::max()}; double distance_to_lane_change_finished{std::numeric_limits::max()}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp index b25dbc99189e8..f0adcb1d69b42 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp @@ -113,6 +113,13 @@ struct SafetyParameters CollisionCheckParameters collision_check{}; }; +struct FrenetPlannerParameters +{ + bool enable{true}; + double th_yaw_diff_deg{10.0}; + double th_curvature_smoothing{0.1}; +}; + struct TrajectoryParameters { double max_prepare_duration{4.0}; @@ -124,6 +131,7 @@ struct TrajectoryParameters double th_lane_changing_length_diff{0.5}; double min_lane_changing_velocity{5.6}; double lane_changing_decel_factor{0.5}; + double th_prepare_curvature{0.03}; int lon_acc_sampling_num{10}; int lat_acc_sampling_num{10}; LateralAccelerationMap lat_acc_map{}; @@ -151,6 +159,7 @@ struct Parameters CancelParameters cancel{}; DelayParameters delay{}; TerminalPathParameters terminal_path{}; + FrenetPlannerParameters frenet{}; // lane change parameters double backward_lane_length{200.0}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/path.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/path.hpp index 0fa0a9d977a26..0fa2c6cc8dfbc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/path.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/path.hpp @@ -19,19 +19,53 @@ #include "autoware/behavior_path_planner_common/turn_signal_decider.hpp" #include "autoware/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" +#include + #include +#include #include namespace autoware::behavior_path_planner::lane_change { +enum class PathType { ConstantJerk = 0, FrenetPlanner }; + using autoware::behavior_path_planner::TurnSignalInfo; using tier4_planning_msgs::msg::PathWithLaneId; +struct TrajectoryGroup +{ + PathWithLaneId prepare; + PathWithLaneId target_lane_ref_path; + std::vector target_lane_ref_path_dist; + LaneChangePhaseMetrics prepare_metric; + frenet_planner::Trajectory lane_changing; + frenet_planner::FrenetState initial_state; + double max_lane_changing_length{0.0}; + + TrajectoryGroup() = default; + TrajectoryGroup( + PathWithLaneId prepare, PathWithLaneId target_lane_ref_path, + std::vector target_lane_ref_path_dist, LaneChangePhaseMetrics prepare_metric, + frenet_planner::Trajectory lane_changing, frenet_planner::FrenetState initial_state, + const double max_lane_changing_length) + : prepare(std::move(prepare)), + target_lane_ref_path(std::move(target_lane_ref_path)), + target_lane_ref_path_dist(std::move(target_lane_ref_path_dist)), + prepare_metric(prepare_metric), + lane_changing(std::move(lane_changing)), + initial_state(initial_state), + max_lane_changing_length(max_lane_changing_length) + { + } +}; + struct Path { + Info info; PathWithLaneId path; ShiftedPath shifted_path; - Info info; + TrajectoryGroup frenet_path; + PathType type = PathType::ConstantJerk; }; struct Status @@ -39,7 +73,6 @@ struct Status Path lane_change_path; bool is_safe{false}; bool is_valid_path{false}; - double start_distance{0.0}; }; } // namespace autoware::behavior_path_planner::lane_change diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp index 77ba8fe68a653..42586e7b1df92 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp @@ -11,7 +11,6 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. - #ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ #define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ @@ -26,6 +25,7 @@ namespace autoware::behavior_path_planner::utils::lane_change { using behavior_path_planner::LaneChangePath; using behavior_path_planner::lane_change::CommonDataPtr; +using behavior_path_planner::lane_change::TrajectoryGroup; /** * @brief Generates a prepare segment for a lane change maneuver. @@ -98,5 +98,65 @@ LaneChangePath construct_candidate_path( const LaneChangeInfo & lane_change_info, const PathWithLaneId & prepare_segment, const PathWithLaneId & target_lane_reference_path, const std::vector> & sorted_lane_ids); + +/** + * @brief Generates candidate trajectories in the Frenet frame for a lane change maneuver. + * + * This function computes a set of candidate trajectories for the ego vehicle in the Frenet frame, + * based on the provided metrics, target lane reference path, and preparation segments. It ensures + * that the generated trajectories adhere to specified constraints, such as lane boundaries and + * velocity limits, while optimizing for smoothness and curvature. + * + * @param common_data_ptr Shared pointer to CommonData containing route, lane, and transient + * information. + * @param prev_module_path The previous module's path used as a base for preparation segments. + * @param prep_metric Metrics for the preparation phase, including path length and velocity. + * + * @return std::vector A vector of trajectory groups representing + * valid lane change candidates, each containing the prepare segment, target reference path, and + * Frenet trajectory. + */ +std::vector generate_frenet_candidates( + const CommonDataPtr & common_data_ptr, const PathWithLaneId & prev_module_path, + const std::vector & prep_metrics); + +/** + * @brief Constructs a lane change path candidate based on a Frenet trajectory group. + * + * This function generates a candidate lane change path by converting a Frenet trajectory group + * into a shifted path and combining it with a prepare segment. It validates the path's feasibility + * by ensuring yaw differences are within allowable thresholds and calculates lane change + * information, such as acceleration, velocity, and duration. + * + * @param trajectory_group A Frenet trajectory group containing the prepared path and Frenet + * trajectory data. + * @param common_data_ptr Shared pointer to CommonData providing parameters and constraints for lane + * changes. + * @param sorted_lane_ids A vector of sorted lane IDs used to update the lane IDs in the path. + * + * @return std::optional The constructed candidate lane change path if valid, or + * std::nullopt if the path is not feasible. + * + * @throws std::logic_error If the yaw difference exceeds the threshold, or other critical errors + * occur. + */ +std::optional get_candidate_path( + const TrajectoryGroup & trajectory_group, const CommonDataPtr & common_data_ptr, + const std::vector> & sorted_lane_ids); + +/** + * @brief Appends the target lane reference path to the candidate lane change path. + * + * This function extends the lane change candidate path by appending points from the + * target lane reference path beyond the lane change end position. The appending process + * is constrained by a curvature threshold to ensure smooth transitions and avoid sharp turns. + * + * @param frenet_candidate The candidate lane change path to which the target reference path is + * appended. This includes the lane change path and associated Frenet trajectory data. + * @param th_curvature_smoothing A threshold for the allowable curvature during the extension + * process. Points with curvature exceeding this threshold are excluded. + */ +void append_target_ref_to_candidate(LaneChangePath & frenet_candidate, const double th_curvature); } // namespace autoware::behavior_path_planner::utils::lane_change + #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp index 69362994dbbac..422c392cac462 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp @@ -24,6 +24,8 @@ #include #include +#include +#include #include #include @@ -56,6 +58,7 @@ using behavior_path_planner::lane_change::LCParamPtr; using behavior_path_planner::lane_change::ModuleType; using behavior_path_planner::lane_change::PathSafetyStatus; using behavior_path_planner::lane_change::TargetLaneLeadingObjects; +using behavior_path_planner::lane_change::TrajectoryGroup; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; @@ -69,9 +72,27 @@ bool is_mandatory_lane_change(const ModuleType lc_type); void set_prepare_velocity( PathWithLaneId & prepare_segment, const double current_velocity, const double prepare_velocity); -std::vector replaceWithSortedIds( - const std::vector & original_lane_ids, - const std::vector> & sorted_lane_ids); +/** + * @brief Replaces the current lane IDs with a sorted set of IDs based on a predefined mapping. + * + * This function checks if the current lane IDs match the previously processed lane IDs. + * If they do, it returns the previously sorted IDs for efficiency. Otherwise, it matches + * the current lane IDs to the appropriate sorted IDs from the provided mapping and updates + * the cached values. + * + * @param current_lane_ids The current lane IDs to be replaced or verified. + * @param sorted_lane_ids A vector of sorted lane ID groups, each representing a predefined + * order of IDs for specific conditions. + * @param prev_lane_ids Reference to the previously processed lane IDs for caching purposes. + * @param prev_sorted_lane_ids Reference to the previously sorted lane IDs for caching purposes. + * + * @return std::vector The sorted lane IDs if a match is found, or the original + * `current_lane_ids` if no match exists. + */ +std::vector replace_with_sorted_ids( + const std::vector & current_lane_ids, + const std::vector> & sorted_lane_ids, std::vector & prev_lane_ids, + std::vector & prev_sorted_lane_ids); std::vector> get_sorted_lane_ids(const CommonDataPtr & common_data_ptr); @@ -432,5 +453,24 @@ std::vector> convert_to_predicted_paths( * @return true if the pose is within the target or target neighbor polygons, false otherwise. */ bool is_valid_start_point(const lane_change::CommonDataPtr & common_data_ptr, const Pose & pose); + +/** + * @brief Converts a lane change frenet candidate into a predicted path for the ego vehicle. + * + * This function generates a predicted path based on the provided Frenet candidate, + * simulating the vehicle's trajectory during the preparation and lane-changing phases. + * It interpolates poses and velocities over the duration of the prediction, considering + * the ego vehicle's initial conditions and the candidate's trajectory data. + * + * @param common_data_ptr Shared pointer to CommonData containing parameters and ego vehicle state. + * @param frenet_candidate A Frenet trajectory group representing the lane change candidate. + * @param deceleration_sampling_num Unused parameter for deceleration sampling count. + * + * @return std::vector The predicted path as a series of stamped poses + * with associated velocities over the prediction time. + */ +std::vector convert_to_predicted_path( + const CommonDataPtr & common_data_ptr, const lane_change::TrajectoryGroup & frenet_candidate, + [[maybe_unused]] const size_t deceleration_sampling_num); } // namespace autoware::behavior_path_planner::utils::lane_change #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml index fad98ecf8f8e1..cf7600556080e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml @@ -23,6 +23,7 @@ autoware_behavior_path_planner autoware_behavior_path_planner_common + autoware_frenet_planner autoware_motion_utils autoware_rtc_interface autoware_universe_utils diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp index ec000b8fee97c..06a9d505f90ad 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp @@ -63,6 +63,8 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s getOrDeclareParameter(*node, parameter("trajectory.min_lane_changing_velocity")); p.trajectory.lane_changing_decel_factor = getOrDeclareParameter(*node, parameter("trajectory.lane_changing_decel_factor")); + p.trajectory.th_prepare_curvature = + getOrDeclareParameter(*node, parameter("trajectory.th_prepare_curvature")); p.trajectory.lon_acc_sampling_num = getOrDeclareParameter(*node, parameter("trajectory.lon_acc_sampling_num")); p.trajectory.lat_acc_sampling_num = @@ -213,6 +215,12 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s p.delay.th_parked_vehicle_shift_ratio = getOrDeclareParameter( *node, parameter("delay_lane_change.th_parked_vehicle_shift_ratio")); + // trajectory generation near terminal using frenet planner + p.frenet.enable = getOrDeclareParameter(*node, parameter("frenet.enable")); + p.frenet.th_yaw_diff_deg = getOrDeclareParameter(*node, parameter("frenet.th_yaw_diff")); + p.frenet.th_curvature_smoothing = + getOrDeclareParameter(*node, parameter("frenet.th_curvature_smoothing")); + // lane change cancel p.cancel.enable_on_prepare_phase = getOrDeclareParameter(*node, parameter("cancel.enable_on_prepare_phase")); @@ -338,6 +346,8 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectortrajectory.max_longitudinal_acc); updateParam( parameters, ns + "lane_changing_decel_factor", p->trajectory.lane_changing_decel_factor); + updateParam( + parameters, ns + "th_prepare_curvature", p->trajectory.th_prepare_curvature); int longitudinal_acc_sampling_num = 0; updateParam(parameters, ns + "lon_acc_sampling_num", longitudinal_acc_sampling_num); if (longitudinal_acc_sampling_num > 0) { @@ -356,6 +366,14 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectortrajectory.th_lane_changing_length_diff); } + { + const std::string ns = "lane_change.frenet."; + updateParam(parameters, ns + "enable", p->frenet.enable); + updateParam(parameters, ns + "th_yaw_diff", p->frenet.th_yaw_diff_deg); + updateParam( + parameters, ns + "th_curvature_smoothing", p->frenet.th_curvature_smoothing); + } + { const std::string ns = "lane_change.safety_check.lane_expansion."; updateParam(parameters, ns + "left_offset", p->safety.lane_expansion_left_offset); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 88f58debb886a..7748795851865 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -28,7 +28,10 @@ #include #include #include +#include #include +#include +#include #include #include #include @@ -36,8 +39,11 @@ #include #include +#include + #include #include +#include #include #include @@ -104,6 +110,9 @@ void NormalLaneChange::update_lanes(const bool is_approved) common_data_ptr_->current_lanes_path = route_handler_ptr->getCenterLinePath(current_lanes, 0.0, std::numeric_limits::max()); + common_data_ptr_->target_lanes_path = + route_handler_ptr->getCenterLinePath(target_lanes, 0.0, std::numeric_limits::max()); + common_data_ptr_->lanes_ptr->target_neighbor = utils::lane_change::get_target_neighbor_lanes( *route_handler_ptr, current_lanes, common_data_ptr_->lc_type); @@ -232,8 +241,6 @@ void NormalLaneChange::updateLaneChangeStatus() // Update status status_.is_valid_path = found_valid_path; status_.is_safe = found_safe_path; - - status_.start_distance = common_data_ptr_->transient_data.target_lanes_ego_arc.length; status_.lane_change_path.path.header = getRouteHeader(); } @@ -1124,15 +1131,92 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) } const auto & current_lanes = get_current_lanes(); - const auto & target_lanes = get_target_lanes(); - const auto sorted_lane_ids = utils::lane_change::get_sorted_lane_ids(common_data_ptr_); const auto target_objects = get_target_objects(filtered_objects_, current_lanes); const auto prepare_phase_metrics = get_prepare_metrics(); + const auto sorted_lane_ids = utils::lane_change::get_sorted_lane_ids(common_data_ptr_); + if ( + common_data_ptr_->lc_param_ptr->frenet.enable && + common_data_ptr_->transient_data.is_ego_near_current_terminal_start) { + return get_path_using_frenet( + prepare_phase_metrics, target_objects, sorted_lane_ids, candidate_paths); + } + + return get_path_using_path_shifter( + prepare_phase_metrics, target_objects, sorted_lane_ids, candidate_paths); +} + +bool NormalLaneChange::get_path_using_frenet( + const std::vector & prepare_metrics, + const lane_change::TargetObjects & target_objects, + const std::vector> & sorted_lane_ids, + LaneChangePaths & candidate_paths) const +{ + stop_watch_.tic("frenet_candidates"); + constexpr auto found_safe_path = true; + const auto frenet_candidates = utils::lane_change::generate_frenet_candidates( + common_data_ptr_, prev_module_output_.path, prepare_metrics); + RCLCPP_DEBUG( + logger_, "Generated %lu candidate paths in %2.2f[us]", frenet_candidates.size(), + stop_watch_.toc("frenet_candidates")); + + candidate_paths.reserve(frenet_candidates.size()); + lane_change_debug_.frenet_states.clear(); + lane_change_debug_.frenet_states.reserve(frenet_candidates.size()); + for (const auto & frenet_candidate : frenet_candidates) { + lane_change_debug_.frenet_states.emplace_back( + frenet_candidate.prepare_metric, frenet_candidate.lane_changing.sampling_parameter, + frenet_candidate.max_lane_changing_length); + + std::optional candidate_path_opt; + try { + candidate_path_opt = + utils::lane_change::get_candidate_path(frenet_candidate, common_data_ptr_, sorted_lane_ids); + } catch (const std::exception & e) { + RCLCPP_DEBUG(logger_, "%s", e.what()); + } + + if (!candidate_path_opt) { + continue; + } + + try { + if (check_candidate_path_safety(*candidate_path_opt, target_objects)) { + RCLCPP_DEBUG( + logger_, "Found safe path after %lu candidate(s). Total time: %2.2f[us]", + frenet_candidates.size(), stop_watch_.toc("frenet_candidates")); + utils::lane_change::append_target_ref_to_candidate( + *candidate_path_opt, common_data_ptr_->lc_param_ptr->frenet.th_curvature_smoothing); + candidate_paths.push_back(*candidate_path_opt); + return found_safe_path; + } + } catch (const std::exception & e) { + RCLCPP_DEBUG(logger_, "%s", e.what()); + } + + // appending all paths affect performance + if (candidate_paths.empty()) { + candidate_paths.push_back(*candidate_path_opt); + } + } + + RCLCPP_DEBUG( + logger_, "No safe path after %lu candidate(s). Total time: %2.2f[us]", frenet_candidates.size(), + stop_watch_.toc("frenet_candidates")); + return !found_safe_path; +} + +bool NormalLaneChange::get_path_using_path_shifter( + const std::vector & prepare_metrics, + const lane_change::TargetObjects & target_objects, + const std::vector> & sorted_lane_ids, + LaneChangePaths & candidate_paths) const +{ + const auto & target_lanes = get_target_lanes(); candidate_paths.reserve( - prepare_phase_metrics.size() * lane_change_parameters_->trajectory.lat_acc_sampling_num); + prepare_metrics.size() * lane_change_parameters_->trajectory.lat_acc_sampling_num); const bool only_tl = getStopTime() >= lane_change_parameters_->th_stop_time; const auto dist_to_next_regulatory_element = @@ -1151,7 +1235,7 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) return lc_diff > lane_change_parameters_->trajectory.th_lane_changing_length_diff; }; - for (const auto & prep_metric : prepare_phase_metrics) { + for (const auto & prep_metric : prepare_metrics) { const auto debug_print = [&](const std::string & s) { RCLCPP_DEBUG( logger_, "%s | prep_time: %.5f | lon_acc: %.5f | prep_len: %.5f", s.c_str(), @@ -1195,7 +1279,7 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) prepare_segment, common_data_ptr_->get_ego_speed(), prep_metric.velocity); for (const auto & lc_metric : lane_changing_metrics) { - debug_metrics.lc_metrics.push_back({lc_metric, -1}); + debug_metrics.lc_metrics.emplace_back(lc_metric, -1); const auto debug_print_lat = [&](const std::string & s) { RCLCPP_DEBUG( @@ -1218,7 +1302,7 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) } candidate_paths.push_back(candidate_path); - debug_metrics.lc_metrics.back().second = candidate_paths.size() - 1; + debug_metrics.lc_metrics.back().second = static_cast(candidate_paths.size()) - 1; try { if (check_candidate_path_safety(candidate_path, target_objects)) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp index ef899cceea0d4..bf0af0d133dc7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp @@ -73,6 +73,34 @@ MarkerArray showAllValidLaneChangePath( marker.points.push_back(point.point.pose.position); } + const auto & info = lc_path.info; + auto text_marker = createDefaultMarker( + "map", current_time, ns_with_idx, ++id, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, + createMarkerScale(0.1, 0.1, 0.8), colors::yellow()); + const auto prep_idx = points.size() / 4; + text_marker.pose = points.at(prep_idx).point.pose; + text_marker.pose.position.z += 2.0; + text_marker.text = fmt::format( + "vel: {vel:.3f}[m/s] | lon_acc: {lon_acc:.3f}[m/s2] | t: {time:.3f}[s] | L: {length:.3f}[m]", + fmt::arg("vel", info.velocity.prepare), + fmt::arg("lon_acc", info.longitudinal_acceleration.prepare), + fmt::arg("time", info.duration.prepare), fmt::arg("length", info.length.prepare)); + marker_array.markers.push_back(text_marker); + + const auto lc_idx = points.size() / 2; + text_marker.id = ++id; + text_marker.pose = points.at(lc_idx).point.pose; + text_marker.text = fmt::format( + "type: {type} | vel: {vel:.3f}[m/s] | lon_acc: {lon_acc:.3f}[m/s2] | lat_acc: " + "{lat_acc:.3f}[m/s2] | t: " + "{time:.3f}[s] | L: {length:.3f}[m]", + fmt::arg("type", magic_enum::enum_name(lc_path.type)), + fmt::arg("vel", info.velocity.lane_changing), + fmt::arg("lon_acc", info.longitudinal_acceleration.lane_changing), + fmt::arg("lat_acc", info.lateral_acceleration), fmt::arg("time", info.duration.lane_changing), + fmt::arg("length", info.length.lane_changing)); + marker_array.markers.push_back(text_marker); + marker_array.markers.push_back(marker); } return marker_array; @@ -171,43 +199,78 @@ MarkerArray ShowLaneChangeMetricsInfo( const Debug & debug_data, const geometry_msgs::msg::Pose & pose) { MarkerArray marker_array; - if (debug_data.lane_change_metrics.empty()) { - return marker_array; - } auto text_marker = createDefaultMarker( "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "sampling_metrics", 0, Marker::TEXT_VIEW_FACING, createMarkerScale(0.6, 0.6, 0.6), colors::yellow()); text_marker.pose = autoware::universe_utils::calcOffsetPose(pose, 10.0, 15.0, 0.0); - text_marker.text = - fmt::format("{:<12}", "") + fmt::format("{:^18}|", "lat_accel[m/s2]") + - fmt::format("{:^18}|", "lon_accel[m/s2]") + fmt::format("{:^17}|", "velocity[m/s]") + - fmt::format("{:^15}|", "duration[s]") + fmt::format("{:^15}|", "length[m]") + - fmt::format("{:^20}|", "max_length_th[m]") + fmt::format("{:^15}\n", "path_index"); - for (const auto & metrics : debug_data.lane_change_metrics) { - text_marker.text += fmt::format("{:-<190}\n", ""); - const auto & p_m = metrics.prep_metric; - text_marker.text += - fmt::format("{:<17}", "prep_metrics:") + fmt::format("{:^10.3f}", p_m.lat_accel) + - fmt::format("{:^21.3f}", p_m.actual_lon_accel) + fmt::format("{:^12.3f}", p_m.velocity) + - fmt::format("{:^15.3f}", p_m.duration) + fmt::format("{:^15.3f}", p_m.length) + - fmt::format("{:^17.3f}", metrics.max_prepare_length) + fmt::format("{:^15}\n", "-"); - text_marker.text += fmt::format("{:<20}\n", "lc_metrics:"); - for (const auto & lc_m : metrics.lc_metrics) { - const auto & metric = lc_m.first; - const auto path_index = lc_m.second < 0 ? "-" : std::to_string(lc_m.second); - text_marker.text += fmt::format("{:<15}", "") + fmt::format("{:^10.3f}", metric.lat_accel) + - fmt::format("{:^21.3f}", metric.actual_lon_accel) + - fmt::format("{:^12.3f}", metric.velocity) + - fmt::format("{:^15.3f}", metric.duration) + - fmt::format("{:^15.3f}", metric.length) + - fmt::format("{:^17.3f}", metrics.max_lane_changing_length) + - fmt::format("{:^15}\n", path_index); + if (!debug_data.lane_change_metrics.empty()) { + text_marker.text = + fmt::format("{:<12}", "") + fmt::format("{:^18}|", "lat_accel[m/s2]") + + fmt::format("{:^18}|", "lon_accel[m/s2]") + fmt::format("{:^17}|", "velocity[m/s]") + + fmt::format("{:^15}|", "duration[s]") + fmt::format("{:^15}|", "length[m]") + + fmt::format("{:^20}|", "max_length_th[m]") + fmt::format("{:^15}\n", "path_index"); + for (const auto & metrics : debug_data.lane_change_metrics) { + text_marker.text += fmt::format("{:-<190}\n", ""); + const auto & p_m = metrics.prep_metric; + text_marker.text += + fmt::format("{:<17}", "prep_metrics:") + fmt::format("{:^10.3f}", p_m.lat_accel) + + fmt::format("{:^21.3f}", p_m.actual_lon_accel) + fmt::format("{:^12.3f}", p_m.velocity) + + fmt::format("{:^15.3f}", p_m.duration) + fmt::format("{:^15.3f}", p_m.length) + + fmt::format("{:^17.3f}", metrics.max_prepare_length) + fmt::format("{:^15}\n", "-"); + text_marker.text += fmt::format("{:<20}\n", "lc_metrics:"); + for (const auto & lc_m : metrics.lc_metrics) { + const auto & metric = lc_m.first; + const auto path_index = lc_m.second < 0 ? "-" : std::to_string(lc_m.second); + text_marker.text += fmt::format("{:<15}", "") + fmt::format("{:^10.3f}", metric.lat_accel) + + fmt::format("{:^21.3f}", metric.actual_lon_accel) + + fmt::format("{:^12.3f}", metric.velocity) + + fmt::format("{:^15.3f}", metric.duration) + + fmt::format("{:^15.3f}", metric.length) + + fmt::format("{:^17.3f}", metrics.max_lane_changing_length) + + fmt::format("{:^15}\n", path_index); + } } + marker_array.markers.push_back(text_marker); + } + + if (!debug_data.frenet_states.empty()) { + text_marker.text = fmt::format("{:<12}", "") + fmt::format("{:^18}|", "lon_accel[m/s2]") + + fmt::format("{:^17}|", "lon_vel[m/s]") + + fmt::format("{:^15}|", "duration[s]") + fmt::format("{:^15}|", "length[m]") + + fmt::format("{:^17}|", "lat_accel[m/s2]") + + fmt::format("{:^15}|", "lat_vel[m/s2]") + fmt::format("{:^15}|", "s[m]") + + fmt::format("{:^15}|", "d[m]") + fmt::format("{:^20}\n", "max_length_th[m]"); + for (const auto & metrics : debug_data.frenet_states) { + text_marker.text += fmt::format("{:-<250}\n", ""); + const auto & p_m = metrics.prep_metric; + const auto max_len = metrics.max_lane_changing_length; + text_marker.text += + fmt::format("{:<17}", "prep_metrics:") + fmt::format("{:^13.3f}", p_m.actual_lon_accel) + + fmt::format("{:^15.3f}", p_m.velocity) + fmt::format("{:^15.3f}", p_m.duration) + + fmt::format("{:^12.3f}", p_m.length) + + fmt::format("{:^13}", "") + // Empty string for lat_accel + fmt::format("{:^13}", "") + // Empty string for lat_vel + fmt::format("{:^15}", "") + // Empty string for s + fmt::format("{:^15}", "") + // Empty string for d // Empty string for d + fmt::format("{:^20.3f}\n", max_len); // Empty string for max_length_t + const auto & lc_m = metrics.sampling_parameter.target_state; // Assuming lc_metric exists + const auto duration = metrics.sampling_parameter.target_duration; + text_marker.text += + fmt::format("{:<17}", "frenet_state:") + + fmt::format("{:^15.3f}", lc_m.longitudinal_acceleration) + + fmt::format("{:^13.3f}", lc_m.longitudinal_velocity) + fmt::format("{:^17.3f}", duration) + + fmt::format("{:^10.3f}", lc_m.position.s) + + fmt::format("{:^19.3f}", lc_m.lateral_acceleration) + + fmt::format("{:^10.3f}", lc_m.lateral_velocity) + + fmt::format("{:^18.3f}", lc_m.position.s) + fmt::format("{:^15.3f}", lc_m.position.d) + + fmt::format("{:^16.3f}\n", max_len); // Empty string for max_length_t + } + + marker_array.markers.push_back(text_marker); } - marker_array.markers.push_back(text_marker); return marker_array; } diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/path.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/path.cpp index 44ee1624f0f51..df45da3f08fa1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/path.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/path.cpp @@ -15,17 +15,22 @@ #include "autoware/behavior_path_lane_change_module/utils/path.hpp" #include "autoware/behavior_path_lane_change_module/structs/data.hpp" +#include "autoware/behavior_path_lane_change_module/utils/calculation.hpp" #include "autoware/behavior_path_lane_change_module/utils/utils.hpp" #include "autoware/behavior_path_planner_common/utils/path_utils.hpp" #include "autoware/behavior_path_planner_common/utils/utils.hpp" #include #include +#include #include +#include #include #include #include +#include + #include #include #include @@ -42,8 +47,22 @@ using autoware::behavior_path_planner::lane_change::LCParamPtr; using autoware::behavior_path_planner::LaneChangePhaseMetrics; using autoware::behavior_path_planner::ShiftLine; +using autoware::behavior_path_planner::lane_change::TrajectoryGroup; +using autoware::frenet_planner::FrenetState; +using autoware::frenet_planner::SamplingParameters; +using autoware::route_handler::Direction; +using autoware::sampler_common::FrenetPoint; +using autoware::sampler_common::transform::Spline2D; +using autoware::universe_utils::LineString2d; +using autoware::universe_utils::Point2d; using geometry_msgs::msg::Pose; +template +T sign(const Direction direction) +{ + return static_cast(direction == Direction::LEFT ? 1.0 : -1.0); +} + double calc_resample_interval( const double lane_changing_length, const double lane_changing_velocity) { @@ -53,7 +72,7 @@ double calc_resample_interval( lane_changing_length / min_resampling_points, lane_changing_velocity * resampling_dt); } -PathWithLaneId get_reference_path_from_target_Lane( +PathWithLaneId get_reference_path_from_target_lane( const CommonDataPtr & common_data_ptr, const Pose & lane_changing_start_pose, const double lane_changing_length, const double resample_interval) { @@ -146,11 +165,197 @@ std::optional exceed_yaw_threshold( } return std::nullopt; } + +Spline2D init_reference_spline(const std::vector & target_lanes_ref_path) +{ + std::vector xs; + std::vector ys; + xs.reserve(target_lanes_ref_path.size()); + ys.reserve(target_lanes_ref_path.size()); + for (const auto & p : target_lanes_ref_path) { + xs.push_back(p.point.pose.position.x); + ys.push_back(p.point.pose.position.y); + } + + return {xs, ys}; +} + +FrenetState init_frenet_state( + const FrenetPoint & start_position, const LaneChangePhaseMetrics & prepare_metrics) +{ + FrenetState initial_state; + initial_state.position = start_position; + initial_state.longitudinal_velocity = prepare_metrics.velocity; + initial_state.lateral_velocity = + 0.0; // TODO(Maxime): this can be sampled if we want but it would impact the LC duration + initial_state.longitudinal_acceleration = prepare_metrics.sampled_lon_accel; + initial_state.lateral_acceleration = prepare_metrics.lat_accel; + return initial_state; +} + +std::optional init_sampling_parameters( + const CommonDataPtr & common_data_ptr, const LaneChangePhaseMetrics & prepare_metrics, + const FrenetState & initial_state, const Spline2D & ref_spline, const Pose & lc_start_pose) +{ + const auto & trajectory = common_data_ptr->lc_param_ptr->trajectory; + const auto min_lc_vel = trajectory.min_lane_changing_velocity; + const auto [min_lateral_acc, max_lateral_acc] = + trajectory.lat_acc_map.find(std::max(min_lc_vel, prepare_metrics.velocity)); + const auto duration = autoware::motion_utils::calc_shift_time_from_jerk( + std::abs(initial_state.position.d), trajectory.lateral_jerk, max_lateral_acc); + const auto final_velocity = + std::max(min_lc_vel, prepare_metrics.velocity + prepare_metrics.sampled_lon_accel * duration); + const auto lc_length = duration * (prepare_metrics.velocity + final_velocity) * 0.5; + const auto target_s = initial_state.position.s + lc_length; + const auto initial_yaw = tf2::getYaw(lc_start_pose.orientation); + const auto target_lat_vel = + (1.0 - ref_spline.curvature(target_s + 1e-3) * initial_state.position.d) * + std::tan(initial_yaw - ref_spline.yaw(target_s)); + + if (std::isnan(target_lat_vel)) { + return std::nullopt; + } + + SamplingParameters sampling_parameters; + const auto & safety = common_data_ptr->lc_param_ptr->safety; + sampling_parameters.resolution = safety.collision_check.prediction_time_resolution; + sampling_parameters.parameters.emplace_back(); + sampling_parameters.parameters.back().target_duration = duration; + sampling_parameters.parameters.back().target_state.position = {target_s, 0.0}; + // TODO(Maxime): not sure if we should use curvature at initial or target s + sampling_parameters.parameters.back().target_state.lateral_velocity = + sign(common_data_ptr->direction) * target_lat_vel; + sampling_parameters.parameters.back().target_state.lateral_acceleration = 0.0; + sampling_parameters.parameters.back().target_state.longitudinal_velocity = final_velocity; + sampling_parameters.parameters.back().target_state.longitudinal_acceleration = + prepare_metrics.sampled_lon_accel; + return sampling_parameters; +} + +std::vector calc_curvatures( + const std::vector & points, const Pose & current_pose) +{ + const auto nearest_segment_idx = + autoware::motion_utils::findNearestSegmentIndex(points, current_pose.position); + + // Ignore all path points behind ego vehicle. + if (points.size() <= nearest_segment_idx + 2) { + return {}; + } + + std::vector curvatures; + curvatures.reserve(points.size() - nearest_segment_idx + 2); + for (const auto & [p1, p2, p3] : ranges::views::zip( + points | ranges::views::drop(nearest_segment_idx), + points | ranges::views::drop(nearest_segment_idx + 1), + points | ranges::views::drop(nearest_segment_idx + 2))) { + const auto point1 = autoware::universe_utils::getPoint(p1); + const auto point2 = autoware::universe_utils::getPoint(p2); + const auto point3 = autoware::universe_utils::getPoint(p3); + + curvatures.push_back(autoware::universe_utils::calcCurvature(point1, point2, point3)); + } + + return curvatures; +} + +double calc_average_curvature(const std::vector & curvatures) +{ + const auto filter_zeros = [](const auto & k) { return k != 0.0; }; + auto filtered_k = curvatures | ranges::views::filter(filter_zeros); + if (filtered_k.empty()) { + return 0.0; + } + const auto sums_of_curvatures = [](float sum, const double k) { return sum + std::abs(k); }; + const auto sum_of_k = ranges::accumulate(filtered_k, 0.0, sums_of_curvatures); + const auto count_k = static_cast(ranges::distance(filtered_k)); + return sum_of_k / count_k; +} + +LineString2d get_linestring_bound(const lanelet::ConstLanelets & lanes, const Direction direction) +{ + LineString2d line_string; + const auto & get_bound = [&](const lanelet::ConstLanelet & lane) { + return (direction == Direction::LEFT) ? lane.leftBound2d() : lane.rightBound2d(); + }; + + const auto reserve_size = ranges::accumulate( + lanes, 0UL, + [&](auto sum, const lanelet::ConstLanelet & lane) { return sum + get_bound(lane).size(); }); + line_string.reserve(reserve_size); + for (const auto & lane : lanes) { + ranges::for_each(get_bound(lane), [&line_string](const auto & point) { + boost::geometry::append(line_string, Point2d(point.x(), point.y())); + }); + } + return line_string; +} + +Point2d shift_point(const Point2d & p1, const Point2d & p2, const double offset) +{ + // Calculate the perpendicular vector + double dx = p2.x() - p1.x(); + double dy = p2.y() - p1.y(); + double length = std::sqrt(dx * dx + dy * dy); + + // Normalize and find the perpendicular direction + double nx = -dy / length; + double ny = dx / length; + + return {p1.x() + nx * offset, p1.y() + ny * offset}; +} + +bool check_out_of_bound_paths( + const CommonDataPtr & common_data_ptr, const std::vector & lane_changing_poses, + const LineString2d & lane_boundary, const Direction direction) +{ + const auto distance = (0.5 * common_data_ptr->bpp_param_ptr->vehicle_width + 0.1); + const auto offset = sign(direction) * distance; // invert direction + if (lane_changing_poses.size() <= 2) { + return true; // Remove candidates with insufficient poses + } + + LineString2d path_ls; + path_ls.reserve(lane_changing_poses.size()); + + const auto segments = lane_changing_poses | ranges::views::sliding(2); + ranges::for_each(segments | ranges::views::drop(1), [&](const auto & segment) { + const auto & p1 = segment[0].position; + const auto & p2 = segment[1].position; + boost::geometry::append(path_ls, shift_point({p2.x, p2.y}, {p1.x, p1.y}, offset)); + }); + + return boost::geometry::disjoint(path_ls, lane_boundary); // Remove if disjoint +} + +double calc_limit(const CommonDataPtr & common_data_ptr, const Pose & lc_end_pose) +{ + const auto dist_to_target_end = std::invoke([&]() { + if (common_data_ptr->lanes_ptr->target_lane_in_goal_section) { + return autoware::motion_utils::calcSignedArcLength( + common_data_ptr->target_lanes_path.points, lc_end_pose.position, + common_data_ptr->route_handler_ptr->getGoalPose().position); + } + return autoware::motion_utils::calcSignedArcLength( + common_data_ptr->target_lanes_path.points, lc_end_pose.position, + common_data_ptr->target_lanes_path.points.back().point.pose.position); + }); + + // v2 = u2 + 2ad + // u = sqrt(2ad) + return std::clamp( + std::sqrt( + std::abs(2.0 * common_data_ptr->bpp_param_ptr->min_acc * std::max(dist_to_target_end, 0.0))), + common_data_ptr->lc_param_ptr->trajectory.min_lane_changing_velocity, + common_data_ptr->bpp_param_ptr->max_vel); +} + }; // namespace namespace autoware::behavior_path_planner::utils::lane_change { using behavior_path_planner::lane_change::CommonDataPtr; +using behavior_path_planner::lane_change::PathType; bool get_prepare_segment( const CommonDataPtr & common_data_ptr, const PathWithLaneId & prev_module_path, @@ -187,7 +392,17 @@ bool get_prepare_segment( throw std::logic_error("lane change start is behind target lanelet!"); } - return true; + const auto curvatures = calc_curvatures(prepare_segment.points, common_data_ptr->get_ego_pose()); + + // curvatures may be empty if ego is near the terminal start of the path. + if (curvatures.empty()) { + return true; + } + + const auto average_curvature = calc_average_curvature(curvatures); + + RCLCPP_DEBUG(get_logger(), "average curvature: %.3f", average_curvature); + return average_curvature <= common_data_ptr->lc_param_ptr->trajectory.th_prepare_curvature; } LaneChangePath get_candidate_path( @@ -205,7 +420,7 @@ LaneChangePath get_candidate_path( } const auto & lc_start_pose = prep_segment.points.back().point.pose; - const auto target_lane_reference_path = get_reference_path_from_target_Lane( + const auto target_lane_reference_path = get_reference_path_from_target_lane( common_data_ptr, lc_start_pose, lc_metric.length, resample_interval); if (target_lane_reference_path.points.empty()) { @@ -259,10 +474,14 @@ LaneChangePath construct_candidate_path( throw std::logic_error("Lane change end idx not found on target path."); } + std::vector prev_ids; + std::vector prev_sorted_ids; for (size_t i = 0; i < shifted_path.path.points.size(); ++i) { auto & point = shifted_path.path.points.at(i); if (i < *lc_end_idx_opt) { - point.lane_ids = replaceWithSortedIds(point.lane_ids, sorted_lane_ids); + const auto & current_ids = point.lane_ids; + point.lane_ids = + replace_with_sorted_ids(current_ids, sorted_lane_ids, prev_ids, prev_sorted_ids); point.point.longitudinal_velocity_mps = std::min( point.point.longitudinal_velocity_mps, static_cast(terminal_lane_changing_velocity)); continue; @@ -286,7 +505,251 @@ LaneChangePath construct_candidate_path( candidate_path.path = utils::combinePath(prepare_segment, shifted_path.path); candidate_path.shifted_path = shifted_path; candidate_path.info = lane_change_info; + candidate_path.type = PathType::ConstantJerk; return candidate_path; } + +std::vector generate_frenet_candidates( + const CommonDataPtr & common_data_ptr, const PathWithLaneId & prev_module_path, + const std::vector & prep_metrics) +{ + std::vector trajectory_groups; + universe_utils::StopWatch sw; + + const auto & transient_data = common_data_ptr->transient_data; + const auto & current_lanes = common_data_ptr->lanes_ptr->current; + const auto & target_lanes = common_data_ptr->lanes_ptr->target; + const auto direction = common_data_ptr->direction; + const auto current_lane_boundary = get_linestring_bound(current_lanes, direction); + + for (const auto & metric : prep_metrics) { + PathWithLaneId prepare_segment; + try { + if (!utils::lane_change::get_prepare_segment( + common_data_ptr, prev_module_path, metric.length, prepare_segment)) { + RCLCPP_DEBUG(get_logger(), "Reject: failed to get valid prepare segment!"); + continue; + } + } catch (const std::exception & e) { + RCLCPP_WARN(get_logger(), "%s", e.what()); + break; + } + const auto lc_start_pose = prepare_segment.points.back().point.pose; + + const auto dist_to_end_from_lc_start = + calculation::calc_dist_from_pose_to_terminal_end( + common_data_ptr, target_lanes, lc_start_pose) - + common_data_ptr->lc_param_ptr->lane_change_finish_judge_buffer; + const auto max_lc_len = transient_data.lane_changing_length.max; + const auto max_lane_changing_length = std::min(dist_to_end_from_lc_start, max_lc_len); + + constexpr auto resample_interval = 0.5; + const auto target_lane_reference_path = get_reference_path_from_target_lane( + common_data_ptr, lc_start_pose, max_lane_changing_length, resample_interval); + if (target_lane_reference_path.points.empty()) { + continue; + } + + std::vector target_ref_path_sums{0.0}; + target_ref_path_sums.reserve(target_lane_reference_path.points.size() - 1); + double ref_s = 0.0; + for (auto it = target_lane_reference_path.points.begin(); + std::next(it) != target_lane_reference_path.points.end(); ++it) { + ref_s += universe_utils::calcDistance2d(*it, *std::next(it)); + target_ref_path_sums.push_back(ref_s); + } + + const auto reference_spline = init_reference_spline(target_lane_reference_path.points); + + const auto initial_state = init_frenet_state( + reference_spline.frenet({lc_start_pose.position.x, lc_start_pose.position.y}), metric); + + RCLCPP_DEBUG( + get_logger(), "Initial state [s=%2.2f, d=%2.2f, s'=%2.2f, d'=%2.2f, s''=%2.2f, d''=%2.2f]", + initial_state.position.s, initial_state.position.d, initial_state.longitudinal_velocity, + initial_state.lateral_velocity, initial_state.longitudinal_acceleration, + initial_state.lateral_acceleration); + + const auto sampling_parameters_opt = init_sampling_parameters( + common_data_ptr, metric, initial_state, reference_spline, lc_start_pose); + + if (!sampling_parameters_opt) { + continue; + } + + auto frenet_trajectories = frenet_planner::generateTrajectories( + reference_spline, initial_state, *sampling_parameters_opt); + + trajectory_groups.reserve(trajectory_groups.size() + frenet_trajectories.size()); + for (const auto & traj : frenet_trajectories) { + if (!trajectory_groups.empty()) { + const auto diff = std::abs( + traj.frenet_points.back().s - + trajectory_groups.back().lane_changing.frenet_points.back().s); + if (diff < common_data_ptr->lc_param_ptr->trajectory.th_lane_changing_length_diff) { + continue; + } + } + + const auto out_of_bound = + check_out_of_bound_paths(common_data_ptr, traj.poses, current_lane_boundary, direction); + + if (out_of_bound) { + continue; + } + + trajectory_groups.emplace_back( + prepare_segment, target_lane_reference_path, target_ref_path_sums, metric, traj, + initial_state, max_lane_changing_length); + } + } + + const auto limit_vel = [&](TrajectoryGroup & group) { + const auto max_vel = calc_limit(common_data_ptr, group.lane_changing.poses.back()); + for (auto & vel : group.lane_changing.longitudinal_velocities) { + vel = std::clamp(vel, 0.0, max_vel); + } + }; + + ranges::for_each(trajectory_groups, limit_vel); + + ranges::sort(trajectory_groups, [&](const auto & p1, const auto & p2) { + return calc_average_curvature(p1.lane_changing.curvatures) < + calc_average_curvature(p2.lane_changing.curvatures); + }); + + return trajectory_groups; +} + +std::optional get_candidate_path( + const TrajectoryGroup & trajectory_group, const CommonDataPtr & common_data_ptr, + const std::vector> & sorted_lane_ids) +{ + if (trajectory_group.lane_changing.frenet_points.empty()) { + return std::nullopt; + } + + ShiftedPath shifted_path; + std::vector prev_ids; + std::vector prev_sorted_ids; + const auto & lane_changing_candidate = trajectory_group.lane_changing; + const auto & target_lane_ref_path = trajectory_group.target_lane_ref_path; + const auto & prepare_segment = trajectory_group.prepare; + const auto & prepare_metric = trajectory_group.prepare_metric; + const auto & initial_state = trajectory_group.initial_state; + const auto & target_ref_sums = trajectory_group.target_lane_ref_path_dist; + auto zipped_candidates = ranges::views::zip( + lane_changing_candidate.poses, lane_changing_candidate.frenet_points, + lane_changing_candidate.longitudinal_velocities, lane_changing_candidate.lateral_velocities, + lane_changing_candidate.curvatures); + + shifted_path.path.points.reserve(zipped_candidates.size()); + shifted_path.shift_length.reserve(zipped_candidates.size()); + for (const auto & [pose, frenet_point, longitudinal_velocity, lateral_velocity, curvature] : + zipped_candidates) { + // Find the reference index + const auto & s = frenet_point.s; + auto ref_i_itr = std::find_if( + target_ref_sums.begin(), target_ref_sums.end(), + [s](const double ref_s) { return ref_s > s; }); + auto ref_i = std::distance(target_ref_sums.begin(), ref_i_itr); + + PathPointWithLaneId point; + point.point.pose = pose; + point.point.longitudinal_velocity_mps = static_cast(longitudinal_velocity); + point.point.lateral_velocity_mps = static_cast(lateral_velocity); + point.point.heading_rate_rps = static_cast(curvature); + point.point.pose.position.z = target_lane_ref_path.points[ref_i].point.pose.position.z; + const auto & current_ids = target_lane_ref_path.points[ref_i].lane_ids; + point.lane_ids = + replace_with_sorted_ids(current_ids, sorted_lane_ids, prev_ids, prev_sorted_ids); + + // Add to shifted path + shifted_path.shift_length.push_back(frenet_point.d); + shifted_path.path.points.push_back(point); + } + + if (shifted_path.path.points.empty()) { + return std::nullopt; + } + + for (auto & point : shifted_path.path.points) { + point.point.longitudinal_velocity_mps = std::min( + point.point.longitudinal_velocity_mps, + static_cast(shifted_path.path.points.back().point.longitudinal_velocity_mps)); + } + + const auto th_yaw_diff_deg = common_data_ptr->lc_param_ptr->frenet.th_yaw_diff_deg; + if ( + const auto yaw_diff_opt = exceed_yaw_threshold( + prepare_segment, shifted_path.path, autoware::universe_utils::deg2rad(th_yaw_diff_deg))) { + const auto yaw_diff_deg = autoware::universe_utils::rad2deg(yaw_diff_opt.value()); + const auto err_msg = fmt::format( + "Excessive yaw difference {yaw_diff:2.2f}[deg]. The threshold is {th_yaw_diff:2.2f}[deg].", + fmt::arg("yaw_diff", yaw_diff_deg), fmt::arg("th_yaw_diff", th_yaw_diff_deg)); + throw std::logic_error(err_msg); + } + + LaneChangeInfo info; + info.longitudinal_acceleration = { + prepare_metric.actual_lon_accel, lane_changing_candidate.longitudinal_accelerations.front()}; + info.velocity = {prepare_metric.velocity, initial_state.longitudinal_velocity}; + info.duration = { + prepare_metric.duration, lane_changing_candidate.sampling_parameter.target_duration}; + info.length = {prepare_metric.length, lane_changing_candidate.lengths.back()}; + info.lane_changing_start = prepare_segment.points.back().point.pose; + info.lane_changing_end = lane_changing_candidate.poses.back(); + + ShiftLine sl; + + sl.start = lane_changing_candidate.poses.front(); + sl.end = lane_changing_candidate.poses.back(); + sl.start_shift_length = 0.0; + sl.end_shift_length = initial_state.position.d; + sl.start_idx = 0UL; + sl.end_idx = shifted_path.shift_length.size() - 1; + + info.shift_line = sl; + info.terminal_lane_changing_velocity = lane_changing_candidate.longitudinal_velocities.back(); + info.lateral_acceleration = lane_changing_candidate.lateral_accelerations.front(); + + LaneChangePath candidate_path; + candidate_path.path = utils::combinePath(prepare_segment, shifted_path.path); + candidate_path.info = info; + candidate_path.shifted_path = shifted_path; + candidate_path.frenet_path = trajectory_group; + candidate_path.type = PathType::FrenetPlanner; + + return candidate_path; +} + +void append_target_ref_to_candidate( + LaneChangePath & frenet_candidate, const double th_curvature_smoothing) +{ + const auto & target_lane_ref_path = frenet_candidate.frenet_path.target_lane_ref_path.points; + const auto & lc_end_pose = frenet_candidate.info.lane_changing_end; + const auto lc_end_idx = + motion_utils::findNearestIndex(target_lane_ref_path, lc_end_pose.position); + auto & candidate_path = frenet_candidate.path.points; + if (target_lane_ref_path.size() <= lc_end_idx + 2) { + return; + } + const auto add_size = target_lane_ref_path.size() - (lc_end_idx + 1); + candidate_path.reserve(candidate_path.size() + add_size); + const auto & points = target_lane_ref_path; + for (const auto & [p2, p3] : ranges::views::zip( + points | ranges::views::drop(lc_end_idx + 1), + points | ranges::views::drop(lc_end_idx + 2))) { + const auto point1 = autoware::universe_utils::getPoint(candidate_path.back().point.pose); + const auto point2 = autoware::universe_utils::getPoint(p2); + const auto point3 = autoware::universe_utils::getPoint(p3); + const auto curvature = + std::abs(autoware::universe_utils::calcCurvature(point1, point2, point3)); + if (curvature < th_curvature_smoothing) { + candidate_path.push_back(p2); + } + } + candidate_path.push_back(target_lane_ref_path.back()); +} } // namespace autoware::behavior_path_planner::utils::lane_change diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp index 9360435891632..9002270185847 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp @@ -24,12 +24,18 @@ #include "autoware/object_recognition_utils/predicted_path_utils.hpp" #include "autoware/universe_utils/math/unit_conversion.hpp" +// for the geometry types +#include +#include +// for the svg mapper #include #include #include #include #include #include +#include +#include #include #include #include @@ -40,9 +46,10 @@ #include #include -#include - +#include #include +#include +#include #include #include @@ -64,9 +71,11 @@ namespace autoware::behavior_path_planner::utils::lane_change { using autoware::route_handler::RouteHandler; using autoware::universe_utils::LineString2d; +using autoware::universe_utils::Point2d; using autoware::universe_utils::Polygon2d; using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::PredictedObjects; +using behavior_path_planner::lane_change::PathType; using geometry_msgs::msg::Pose; using tier4_planning_msgs::msg::PathWithLaneId; @@ -382,18 +391,26 @@ std::vector> get_sorted_lane_ids(const CommonDataPtr & comm return sorted_lane_ids; } -std::vector replaceWithSortedIds( - const std::vector & original_lane_ids, - const std::vector> & sorted_lane_ids) +std::vector replace_with_sorted_ids( + const std::vector & current_lane_ids, + const std::vector> & sorted_lane_ids, std::vector & prev_lane_ids, + std::vector & prev_sorted_lane_ids) { - for (const auto original_id : original_lane_ids) { + if (current_lane_ids == prev_lane_ids) { + return prev_sorted_lane_ids; + } + + for (const auto original_id : current_lane_ids) { for (const auto & sorted_id : sorted_lane_ids) { if (std::find(sorted_id.cbegin(), sorted_id.cend(), original_id) != sorted_id.cend()) { - return sorted_id; + prev_lane_ids = current_lane_ids; + prev_sorted_lane_ids = sorted_id; + return prev_sorted_lane_ids; } } } - return original_lane_ids; + + return current_lane_ids; } CandidateOutput assignToCandidate( @@ -475,6 +492,7 @@ std::vector convert_to_predicted_path( 0.5 * lane_changing_acceleration * delta_t * delta_t + offset; const auto pose = autoware::motion_utils::calcInterpolatedPose( path.points, vehicle_pose_frenet.length + length); + predicted_path.emplace_back(t, pose, velocity); } @@ -1127,6 +1145,10 @@ std::vector> convert_to_predicted_paths( const auto acc_resolution = (min_acc - lane_changing_acc) / static_cast(sampling_num); const auto ego_predicted_path = [&](size_t n) { + if (lane_change_path.type == PathType::FrenetPlanner) { + return convert_to_predicted_path( + common_data_ptr, lane_change_path.frenet_path, deceleration_sampling_num); + } auto acc = lane_changing_acc + static_cast(n) * acc_resolution; return utils::lane_change::convert_to_predicted_path(common_data_ptr, lane_change_path, acc); }; @@ -1135,6 +1157,48 @@ std::vector> convert_to_predicted_paths( ranges::to(); } +std::vector convert_to_predicted_path( + const CommonDataPtr & common_data_ptr, const lane_change::TrajectoryGroup & frenet_candidate, + [[maybe_unused]] const size_t deceleration_sampling_num) +{ + const auto initial_velocity = common_data_ptr->get_ego_speed(); + const auto prepare_time = frenet_candidate.prepare_metric.duration; + const auto resolution = + common_data_ptr->lc_param_ptr->safety.collision_check.prediction_time_resolution; + const auto prepare_acc = frenet_candidate.prepare_metric.sampled_lon_accel; + std::vector predicted_path; + const auto & path = frenet_candidate.prepare.points; + const auto & vehicle_pose = common_data_ptr->get_ego_pose(); + const auto & bpp_param_ptr = common_data_ptr->bpp_param_ptr; + const auto nearest_seg_idx = + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + path, vehicle_pose, bpp_param_ptr->ego_nearest_dist_threshold, + bpp_param_ptr->ego_nearest_yaw_threshold); + + const auto vehicle_pose_frenet = + convertToFrenetPoint(path, vehicle_pose.position, nearest_seg_idx); + + for (double t = 0.0; t < prepare_time; t += resolution) { + const auto velocity = + std::clamp(initial_velocity + prepare_acc * t, 0.0, frenet_candidate.prepare_metric.velocity); + const auto length = initial_velocity * t + 0.5 * prepare_acc * t * t; + const auto pose = + autoware::motion_utils::calcInterpolatedPose(path, vehicle_pose_frenet.length + length); + predicted_path.emplace_back(t, pose, velocity); + } + + const auto & poses = frenet_candidate.lane_changing.poses; + const auto & velocities = frenet_candidate.lane_changing.longitudinal_velocities; + const auto & times = frenet_candidate.lane_changing.times; + + for (const auto [t, pose, velocity] : + ranges::views::zip(times, poses, velocities) | ranges::views::drop(1)) { + predicted_path.emplace_back(prepare_time + t, pose, velocity); + } + + return predicted_path; +} + bool is_valid_start_point(const lane_change::CommonDataPtr & common_data_ptr, const Pose & pose) { const lanelet::BasicPoint2d lc_start_point(pose.position.x, pose.position.y); diff --git a/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp b/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp index cab4acfbb8556..54d4bc2e90714 100644 --- a/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp +++ b/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp @@ -197,6 +197,15 @@ void calculateCartesian( trajectory.longitudinal_accelerations.push_back(0.0); trajectory.lateral_accelerations.push_back(0.0); } + for (auto i = 0UL; i < trajectory.points.size(); ++i) { + geometry_msgs::msg::Pose pose; + pose.position.x = trajectory.points[i].x(); + pose.position.y = trajectory.points[i].y(); + pose.position.z = 0.0; + pose.orientation = + autoware::universe_utils::createQuaternionFromRPY(0.0, 0.0, trajectory.yaws[i]); + trajectory.poses.push_back(pose); + } } }