From f71c14a7cf29f0982a605c245a8007853e53b951 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT Date: Mon, 27 Nov 2023 17:21:06 +0900 Subject: [PATCH] Add dynamic_obstacle_stop module (behavior_velocity_planner) Signed-off-by: Maxime CLEMENT --- .../CMakeLists.txt | 12 + .../README.md | 85 +++++++ .../config/dynamic_obstacle_stop.param.yaml | 10 + .../DynamicObstacleStop-Collision.drawio.svg | 236 ++++++++++++++++++ .../DynamicObstacleStop-Filtering.drawio.svg | 156 ++++++++++++ ...amicObstacleStop-ImmediatePaths.drawio.svg | 103 ++++++++ .../DynamicObstacleStop-StopPoint.drawio.svg | 98 ++++++++ .../docs/dynamic_obstacle_stop_rviz.png | Bin 0 -> 157888 bytes .../package.xml | 36 +++ .../plugins.xml | 3 + .../src/collision.cpp | 71 ++++++ .../src/collision.hpp | 39 +++ .../src/debug.cpp | 87 +++++++ .../src/debug.hpp | 40 +++ .../src/footprint.cpp | 84 +++++++ .../src/footprint.hpp | 55 ++++ .../src/manager.cpp | 73 ++++++ .../src/manager.hpp | 58 +++++ .../src/object_filtering.cpp | 71 ++++++ .../src/object_filtering.hpp | 39 +++ .../src/scene_dynamic_obstacle_stop.cpp | 185 ++++++++++++++ .../src/scene_dynamic_obstacle_stop.hpp | 62 +++++ .../src/types.hpp | 80 ++++++ .../behavior_velocity_planner.launch.xml | 3 + 24 files changed, 1686 insertions(+) create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/CMakeLists.txt create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/README.md create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/config/dynamic_obstacle_stop.param.yaml create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-Collision.drawio.svg create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-Filtering.drawio.svg create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-ImmediatePaths.drawio.svg create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-StopPoint.drawio.svg create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/docs/dynamic_obstacle_stop_rviz.png create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/package.xml create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/plugins.xml create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.cpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.hpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.cpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.hpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.hpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.cpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.hpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.hpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/types.hpp diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/CMakeLists.txt b/planning/behavior_velocity_dynamic_obstacle_stop_module/CMakeLists.txt new file mode 100644 index 0000000000000..20f4b3aa8f4d3 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/CMakeLists.txt @@ -0,0 +1,12 @@ +cmake_minimum_required(VERSION 3.14) +project(behavior_velocity_dynamic_obstacle_stop_module) + +find_package(autoware_cmake REQUIRED) +autoware_package() +pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml) + +ament_auto_add_library(${PROJECT_NAME} SHARED + DIRECTORY src +) + +ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/README.md b/planning/behavior_velocity_dynamic_obstacle_stop_module/README.md new file mode 100644 index 0000000000000..8aa3415c3f329 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/README.md @@ -0,0 +1,85 @@ +## Dynamic Obstacle Stop + +### Role + +`dynamic_obstacle_stop` is a module that stops the ego vehicle from entering the _immediate_ path of a dynamic object. + +The _immediate_ path of an object is the area that the object would traverse during a given time horizon, assuming constant velocity and heading. + +![rviz example](docs/dynamic_obstacle_stop_rviz.png) + +### Activation Timing + +This module is activated if the launch parameter `launch_dynamic_obstacle_stop_module` is set to true in the behavior planning launch file. + +### Inner-workings / Algorithms + +The module insert a stop point where the ego path collides with the immediate path of an object. +The overall module flow can be summarized with the following 4 steps. + +1. Filter dynamic objects. +2. Calculate immediate path rectangles of the dynamic objects. +3. Find earliest collision where ego collides with an immediate path rectangle. +4. Insert stop point before the collision. + +In addition to these 4 steps, 2 mechanisms are in place to make the stop point of this module more stable: an hysteresis and a decision duration buffer. + +The `hysteresis` parameter is used when a stop point was already being inserted in the previous iteration +and it increases the range where dynamic objects are considered close enough to the ego path to be used by the module. + +The `decision_duration_buffer` parameter defines the duration when the module will keep inserted the previous stop point, even after no collisions were found. + +#### Filter dynamic objects + +![filtering example](docs/DynamicObstacleStop-Filtering.drawio.svg) + +An object is considered by the module only if it meets all of the following conditions: + +- it is a vehicle (pedestrians are ignored); +- it is moving at a velocity higher than defined by the `minimum_object_velocity` parameter; +- it is not too close to the current position of the ego vehicle; +- it is close to the ego path. + +For the last condition, +the object is considered close enough if its lateral distance from the ego path is less than the threshold parameter `minimum_object_distance_from_ego_path` plus half the width of ego and of the object (including the `extra_object_width` parameter). +In addition, the value of the `hysteresis` parameter is added to the minimum distance if a stop point was inserted in the previous iteration. + +#### Calculate immediate path rectangles + +![Immediate paths example](docs/DynamicObstacleStop-ImmediatePaths.drawio.svg) + +For each considered object, a rectangle is created representing its _immediate_ path. +The rectangle has the width of the object plus the `extra_object_width` parameter +and its length is the current speed of the object multiplied by the `time_horizon`. + +#### Find earliest collision + +![Earliest collision example](docs/DynamicObstacleStop-Collision.drawio.svg) + +We build the ego path footprints as the set of ego footprint polygons projected on each path point. +We then calculate the intersections between these ego path footprints and the previously calculated immediate path rectangles. +An intersection is ignored if the object is not driving toward ego, i.e., the absolute angle between the object and the path point is larger than $\frac{3 \pi}{4}$. + +The collision point with the lowest arc length when projected on the ego path will be used to calculate the final stop point. + +#### Insert stop point + +![Stop point example](docs/DynamicObstacleStop-StopPoint.drawio.svg) + +Before inserting a stop point, we calculate the range of path arc lengths where it can be inserted. +The minimum is calculated to satisfy the acceleration and jerk constraints of the vehicle. +If a stop point was inserted in the previous iteration of the module, its arc length is used as the maximum. +Finally, +the stop point arc length is calculated to be the arc length of the previously found collision point minus the `stop_distance_buffer` and the ego vehicle longitudinal offset, clamped between the minimum and maximum values. + +### Module Parameters + +| Parameter | Type | Description | +| --------------------------------------- | ------ | ------------------------------------------------------------------------------------------ | +| `extra_object_width` | double | [m] extra width around detected objects | +| `minimum_object_velocity` | double | [m/s] objects with a velocity bellow this value are ignored | +| `stop_distance_buffer` | double | [m] extra distance to add between the stop point and the collision point | +| `time_horizon` | double | [s] time horizon used for collision checks | +| `hysteresis` | double | [m] once a collision has been detected, this hysteresis is used on the collision detection | +| `decision_duration_buffer` | double | [s] duration between no collision being detected and the stop decision being cancelled | +| `minimum_object_distance_from_ego_path` | double | [m] minimum distance between the footprints of ego and an object to consider for collision | diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/config/dynamic_obstacle_stop.param.yaml b/planning/behavior_velocity_dynamic_obstacle_stop_module/config/dynamic_obstacle_stop.param.yaml new file mode 100644 index 0000000000000..14483093e8bb3 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/config/dynamic_obstacle_stop.param.yaml @@ -0,0 +1,10 @@ +/**: + ros__parameters: + dynamic_obstacle_stop: # module to stop or before entering the immediate path of a moving object + extra_object_width: 1.0 # [m] extra width around detected objects + minimum_object_velocity: 0.5 # [m/s] objects with a velocity bellow this value are ignored + stop_distance_buffer: 0.5 # [m] extra distance to add between the stop point and the collision point + time_horizon: 5.0 # [s] time horizon used for collision checks + hysteresis: 1.0 # [m] once a collision has been detected, this hysteresis is used on the collision detection + decision_duration_buffer : 1.0 # [s] duration between no collision being detected and the stop decision being cancelled + minimum_object_distance_from_ego_path: 1.0 # [m] minimum distance between the footprints of ego and an object to consider for collision diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-Collision.drawio.svg b/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-Collision.drawio.svg new file mode 100644 index 0000000000000..77beb27c20db8 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-Collision.drawio.svg @@ -0,0 +1,236 @@ + + + + + + + + + + +
+
+
+ EGO +
+
+
+
+ EGO +
+
+ + + + + + + + +
+
+
+ NPC 1 +
+
+
+
+ NPC 1 +
+
+ + + + + + +
+
+
+ NPC 3 +
+
+
+
+ NPC 3 +
+
+ + + + + + + + + + + + + + + + +
+
+
+
abs(angle) < ¾π
+
collisions are ignored
+
+
+
+
+ abs(angle) < ¾π... +
+
+ + + + + +
+
+
+ earliest collision point +
+
+
+
+ earliest collision point +
+
+ +
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-Filtering.drawio.svg b/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-Filtering.drawio.svg new file mode 100644 index 0000000000000..08638931b599f --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-Filtering.drawio.svg @@ -0,0 +1,156 @@ + + + + + + + + + + +
+
+
+ EGO +
+
+
+
+ EGO +
+
+ + + + + + +
+
+
+ NPC 2 +
+
+
+
+ NPC 2 +
+
+ + + + + + +
+
+
+ NPC 1 +
+
+
+
+ NPC 1 +
+
+ + + + + + +
+
+
+ NPC 3 +
+
+
+
+ NPC 3 +
+
+ + + + + + +
+
+
+
NPC 4
+
+
+
+
+ NPC 4 +
+
+ + + + + + +
+
+
+ NPC 2 is too far from the path and is ignored +
+
+
+
+ NPC 2 is too far from the path and is ig... +
+
+ + + + + + + +
+
+
+ NPC 4 is too close to ego and is ignored +
+
+
+
+ NPC 4 is too close to ego and is ignored +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-ImmediatePaths.drawio.svg b/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-ImmediatePaths.drawio.svg new file mode 100644 index 0000000000000..3f07c95c7399d --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-ImmediatePaths.drawio.svg @@ -0,0 +1,103 @@ + + + + + + + + + + +
+
+
+ NPC 1 +
+
+
+
+ NPC 1 +
+
+ + + + + + +
+
+
+ NPC 3 +
+
+
+
+ NPC 3 +
+
+ + + + + + + + + + +
+
+
+
object width +
+
extra_object_width
+
+
+
+
+ object width +... +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-StopPoint.drawio.svg b/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-StopPoint.drawio.svg new file mode 100644 index 0000000000000..0b0953cbea265 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/DynamicObstacleStop-StopPoint.drawio.svg @@ -0,0 +1,98 @@ + + + + + + + + + + +
+
+
+ EGO +
+
+
+
+ EGO +
+
+ + + + + + + + + + +
+
+
+ ego longitudinal offset + extra_distance_buffer +
+
+
+
+ ego longitudinal offset + extra_distance_buffer +
+
+ + + + + +
+
+
+ stop point +
+
+
+
+ stop point +
+
+ + + + +
+
+
+ collision point +
+
+
+
+ collision... +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/dynamic_obstacle_stop_rviz.png b/planning/behavior_velocity_dynamic_obstacle_stop_module/docs/dynamic_obstacle_stop_rviz.png new file mode 100644 index 0000000000000000000000000000000000000000..169cb40875d2dc5172fe2c7cad01dd5bb66990f5 GIT binary patch literal 157888 zcmYg%byU;;_x~tKVT6EmcZf8M?i_+N4h0G6W^_w~NJ)(@C6tgFDcwlt=m0D#5}0HE?=p(2kgbO)Xw->{vO z4P5~M{LX(blw?kPN&tWkpdv5x77E#K_KSJf{icT5bl}$w zQxCPVgVn-kxj|W5+gSB(+mAi@A3@~isCGgT(=!-Cv*=isXd`A;&%}>u6{mX5mPI_? zv&DJ5idlmVj+&}-)tafbRH;Y3h$3M>iF{BOYEntCJERRiI)%s z@;NNk$*yzIU2L=!a#+9;bVN-b+FV$m0+1-YNht)q3v1_Ic&6q38E6)Bdj7>AtN?=j zbY|~Oh(`}-Tl7TuZI9A>Rhag2iXF?21mOg-NZkUoNV>MSORQ9VwqIVY&&e7sSqm7I zrzG88YItF-6w}_usyPN6JzZC~HrtjxbajVM!MrZwo~{CBYh6#1by&k*1NIlIuX@KA zwQ-hrq~3zgeQ)4Nw;sRkmRv3u40#M68{**?WVCn5V~Gfmx+wv31~nO zJ-SDH!Y{}x)6&vrXJ>QQBRq@YD)r}`ty2%&rEY6&k5jyvj~UrzUef1v4n!rb%-{tr zxOY0;ySZ_z@pC(Mku>~_$$o(nLeEfOM@I*0osg_j9ZE4cJ0))=$k2!KClR5ckr77} zD!>J2qa0s%j^5+9EY^^vj%s-4&)0=VU;psN@O6{_s&VR7aZV94hJNQ7C@p3G`Y|u$ zY+Ib{Z={_4!~Q;(8v|#@DHn8juL<=-`s=Xe`K$BVh3Y^%8U&YuWRr)cDj@&>dJAGw z004e^jzHK^0j7wWR?l&7fWhN&FsOXW{57v3z1hL;Y^7FsS4a6_iG07a}~ zh+2QuI^QYYC5jMB4ui!UQ+V??RO#wjDq331z@42>M4y4`A%LHb2+2oR2M7E$2noh# z296#3Nrb9^bWT+P2jrx2!yq!ElRPygrQrOM`HeX-Q^j1P`ySB8ky9SQtYjLY@k&o6 ziwm-M8432yV~disB$o)uIkflNLhXLjgE7Vq$ojcW^!Jlc#sa?QQZ?_Z5dN^X{b=o~{y2oVY=Lel5>hWxpVb@i9!{>t1Z~jIOSm^fi-ISUP^MF@!^S z`mD}Y@3||@2ew%z%a?=Qm|HKyj#Cr|Sy9_&T5kkP-Q*gcgdY#?=B3zpTVHGuD?OdY zE45rGY43C=d;?Rd{xT8$*_NT19)<`tbx0>#-(EL2V$Ag-%@hiCHI8-MNKD%h6y!wL z)ptBx9+J}{=xqvdTbO0y7ApOV=#OzKS|`${Rec{n9i1O_L9 z5%TU3-EK0AfQwI9P&hxtr35)HBubsP@gO6k)hwM4L&~|+ns$}lieihJkcSl{4qK=; z@0VaiCxyCv-P=NVc}?a+@E@i-$xkMb`w9h+eKTkkDhsZ+pz+4aWs3r$J`2KhOG!Mm zLus44*gN2OqoY$T8wzA$VVOG+0%VH0tHN3)*`o5SV0nzoqt;QNb;5l~}}o_RDaI@Cqyk<-$G z*?(N*WyZ3nAYV=-%g zjidEDAHyZ%0i6x>Apkh=`T7sLzmXZ=%Ddy zKcq*j^!Ta0Az=a;8b&`Y=EkrFEDXKD>pL;8j0e$4DvovVtOY4ztGIf)yX(I|?@xLP zu>kin7`!hz`LsxBe1&o zA(JX#M3Rp^ezx>h+zDB%O0Ry=7P0Ir{ni%>x$iC*Y`?Od)zjgP7!cN9%FNbyGo`&Z=WQy-CsVovG z)o_-_8#ab$4UkgAX>x|}9`~_k%QrxukM9i<76}rJV2Ko~)0@GFhBFO((Fi)3=nf(` zG%t0%hJe1}R4s(5H-`lggvk&>_I^U%jj)Akxo_;)i_BjrS3ICE)^2s9pYQB>;++J} z6aFC55EWzbwp=i7c`cDmo?r0|pp{}V`yloa3{M&ZT}u?fxu2dxCa*Sx>AgXSd?&?e6uMBLxm~RhedwQXf<)iFsq#(c1CNX% zGaoafS1Qnwt&rXzU`J;sx|=1HGD`f702?yVxS%IScl@On$`~3Od!vr&&)pN<^qXbb zBA$}a;%|*3PQq_~?k3B-!vUYGX8W61YDO!br7;nSst*rWPw-u)<(-t~F0igR%fFyJ zlB6^qnD6w>BQxX;3uh)<`Rkj<69gEwsRfA_`A;gRDdyx+bCBodD!&ybc-LJM{_*m3 zW8k*znSDBj2#S$I-8{6dvf2B>=EtOJ=b;`2;(KYs$}uZHfp6pMY_pwHRq%UZ)*D6} zUud7tUkxU^vDv|AD%O`8W`G#XSf_0B7&C$Ba{_9yk10X&2IpdpZCu=Qe4U9IDeb9y zJ)ZG1hTqF(>vQMMd?$lA9RY*mTbI+BUSU~5oL3ZS7OM)szb|mnEPoWf_E2wN-$xr! z0T2JVh|NvGK-o`RH!LNXj-HmJZ)Rh85r!-z_}V8x zc6E1jB`|hE^~a%_qYY(U_}rGLqnPguj{So8;< zyUXy?6qgDfxH$q8-hAuR*Kw8WEvx$haGVplxhUjP6Off)^%v^y&2WL&9zUl$<}y0Y zM0xW6B5f)g%S)CXWX9VG3UjLKdoPRl_~8ReQZ_c@=6x8u`mzMt_PQ)6;QMD|>`FOH ze@#MPzpsuH8#}LbdGeBN9O?v2uy-dIiiBsvG3B|D8EJYX1E31JhD|?b(fcx zs+OGI9>g*f<2YrhCg9NTFExul`4yIymP)o9@Y5j+NM*~djeo)G73|5k2$>#IU$!7` z(bc{?%bP!~{wt}H7eAtvqTR#em#*4d#ae{|0&d=kvo<@I`g&7%t!3Z;Fg1QWu~j1m zA9z0{oTW~+9t-cap3iHSdiUe0J&k8So_BV3Zb?0Pd9CVoNAGI^yY&Ui9-)bGju)6q z3WGep8qfbCpo;lp17s6nN$m&epd@}_!;H`@8{LxK8f?C}w+4Ls?D zsD1qE_*_YeQ{Byb7}>R@ovy>OR6`HLalZNlU7|O4^b^TKuUEov46}ZQ)#eGrI`BQq zJ#^IVZrYfbkhWrpSc^Sy{an?CTE=3@JZi5M^J~)P1Y$l%45F09%5t>$0-Si3`$=Bf znmE2TyYckzM&##uHk_H$nP>J#ik%*I*UEpT1 zHj}SSw?4Wn^Ki3?bE=+=ad*>AoJ9%>*3suq8+gn4843Df|8D(b?}ufVWFDi??Ypu2 zzUZ^205SY`eEqgsO=z#%rlQPQBmucHEgY?-N^#*n@8NVmemcii7@BtBBX zRb0+9Dw)r-wg%K|ob7P<&Q*&}$AZ$G1XZ6?DYWS%Sr%+`j^M6T+>*!L}Q_K6PGgF>9$5yFpo zY_eFl96>@I%s0^+<5{0~RM6@QB4QWsu%Vs(df3N>xKhAdm=%nme1En- zN>d;T?bqE{YB4DZcnmh_Jrb27f!m#~LvVbM8;L_f=)=PKxPSu=;Sq`ZRdeAldh{}O z`q1rw-S@!na|Mo?%e_}fBy3c2XDlfA4m$bRtzFx}=zXUZDx4K*NrJ>2ko5PCEUk5& z<}yM^Ot?L(bb4UhU)3o+WQ{XW5Q6FZb7;OqOrvFs9^G$TbpgcDr$Jw`Li{hx+eDdJ zc2WWk8K>8WXObg@(YA-kHwTm;;`jict0l(uh?k7yUl&M%vril8axq4Rqx!=VZxa;h z)+H`Jtx1G7-sR!+ke`s)+ehJCBlwqSE%!bIuV{yK3zLNYd#tW%Urbj-;lIzGm1vu< zKX;TaHdHxJ>GYHJwRx2o>W9+J8PKwSzBA4=VRiFOuaWR-T|$C@Iy7-TW((A(Fj^$Z z3o?!L;avAX~cP)?2V}EAMrWW)J_PTCDz647s8XPpUP_rF)?AH-@&q)JGfk3Wx#gVj*p9rvfgEyYxcP+ z)hSk9;V=a|*X~xO=9Hw+QX8`l| zTl8$1D#z90V-82|U(jnYvD?KX|5V&&>E_@q(W5>MM%|N`#KfLB>NOWI!Y&vPC`>^g z>b^I{&BGHH7pJMNzCT;NHBqXg6i;&?&Hz!}bY1O?{EsG>q>hr6XmQU1q6Uy*KTS_8 zuzAPDF&$5dL~FlGVg8&)`*DW^bF#(-pHK0GE`wb3hw4Wi$Ht%vob(RszfB71Rn?<7 z*jXRG%a7->D!tO^WNuG~sIOT>DZ4VQtY{tYNB?4`X!@Jz7a@GMz2o!k)^V{h@)F^F zTWedVc)oCsP**A85ssBp@LJh#-N4xG(^z{2^5Z$$VRFmPV`0ms{nrj}>+TP}VmbGb z)t!m{gl}BuuyK*vJ->TWzE?AEzb|5b<>p}X?oz-k`3_7t)*5Zj{3I)36*k9tdE4Oyrrk*EU(U3tHQGt}iA11=f-2TF zvRH|UiRFiU{sJ@Q1}J=}!ctNQhdRnwMTr*VMm@_@`oOSFpZbgVjZcx@I*j0{&1 z=pfX*jx5b7P)uR*X{wBfTSoeoZ)lp!l~boFzFw!Q`-?S?lfo6spWNX|S1zioMigLE zl8Y7XNiQ&>j0}6Ei+z#ECIqHNF-DA{K>J zMGh-gkufwdk)0uVo4kx_>|5!sf-0g7IF5Dg0lHc5WD(o^F*nqbDx6qPeOw-+y@M&eXt)3U$s`p(X7rVf}}6%l;P3O@K%#s_w$b>T=SQ+gd|kI~0h zbsk(05uq<5kXI{XX=Sx{)0v)boIGmF5)uE)_L_a)7fa(UTV{fr`PH`nJCZ=ZofKkaiJ{lRPRf)=qn!`0*V6X#e{QUp2$qndT92zRWu7r3JHA7Vq z;r8!8ytyH2v|eT-r(MYSda^4!`P;~?w!v@K3^LQa^r{YJLe#o`HJ#BheT9H+?QNjE z|M=+xGMZ9|XJOF(bUdDlefqy@r($o1$mum;x-2rJ7=M@<=N_YAD`ciFN6OViz zE}#MI&)0zmd&V|k$V$VIeZS5caGp;aIaOv+`(i>Q!i}X8&hmzF2@k3h?}$-+W{fNW z?Hz*9CD!J=I`5P1#HC-JD%g zI4~HAKba*Sa&uzyDRr}6Mj;E=Tzpa#I?a3jjscJqpMfgZboO`naiIHZ(lVxJGmuBJ0wHK*Xh1D7YC)Ytu?A4THv}V()yBb-ch+a z(vtSR9{PgDHRRe~yOh@*L}2j=jpg0b0;$z1$BG@CvRdHoIF{QPW|G# zmeC`eZEPS?=i!T};6B?@bn@MM?4AmHg4z$g;Tgei61UTZrIK|<*3 zlQpq0g%87A&tQpjEni&gzwG%05gB|fd@E}HSCuDi8bjo#r$|&@n@sK4*cf@fNByEh zI1mC|!2lq+R5LA{7oi12<--Hdku?1NTx3O2(dK3`Th#Xv17)Yr4Co)Fl%$k;@{b~% zo;lM6y`q#2T#>LRPR^_>h&gxe`)P3h=jk?AO)A4{?Jl78;vhiKd*rj@Ltk%v3wtsE z@P2w&#TDM4ND#J>eb>9Db41~HFmojMXq;qszku1K>%c_&blr1xxOjKq7;xut`8VD|CiKzV6HkIyW9`Y^BWSQ{w2!RMK#@zr!C_xwkjD zOj{mzvtbi*aLpH~mCe`PN7Pa`#XaE1u9L(7Uu?^{?u;0iUm~};r(O0dOQGhZvDqLz zwZkx5qRboHk?Wu9mN}#4w6fN44C7%W4&W(kwlE zW~gY&mI$2e1)-adrDf5f{cRH z-bDUSxYT$#y_edNdHUEO{gZ4ty9<5j@p1^kZqmBVy>z*S7Tuj|HkiTR7>YYI zMNExr=gaKJ+EyuWsoA41HG!3>LBwBc4&?$7Z|eubOy)$!&Yb*PZ86iHTpHzJ#$-S}wf;T7mdvA81?Uln4J0X;2Oh*nzlHYR zxchLqIEUYbD-;`KL4TCy2hlv3t5u5vb-!^N1s3o!(*4MqGUP6T7EtB(K) zAuqc^GRb%g_F*5_a}ojnf}r1Z5lVWS|6eejE>ja4(~e1RPiZVjHa`n%#VMfW#HPT@ zw@jccSaTcrhE@y9^%3Nx_R#=!33qQdBbcyk4oDDnqamhwYih%;^epMAj7Y8mDxK1N zu1*gAbCl$U`J!3d(Ma?lX7l46oaBbG--inY5a{1GKuONna0tzM=Z)5QC*Zqou$9vt z{YkeWRp&a6ql8LE{FY;+g>|G1KLS5))PtzMb^8uWr9)9grshD0FLol}K>%1%y!|oH8&=!q?{Gx*pM)mxoBpA^5Zj1w(Go|o+cyAv{_5Pqs z_}elCGQm#MH^F@kk^E15*~{_d?g7G)m*9#42*r3DJGvSV1*h2N*M^1$#rysT;o&i;ZxM;Y?T-`RMN~1hH|_0wv>?{MA)wB{ zpr#}-hx7=fysQpy#w`9Xg3LyB)*c`3nmu%+qkky3Zb`JTF8M|9L)p;N zPv<;cK67FzXA4ht$ni=LTVgEysNz!l?TUHiGc-KhO)iI}V0H8fCHs%yIH^ize>mj| z-^HOE)|ZwY5W`y&-tX7iO{6@!WtxrbRMqu&27c!HxVMMllF4G_{mvtROhPnv zAN4de98VqV0K(R#pZ(JstJ#E^I zC*6TB*&SQt#6Jb|$|WRblA9Z*Y-%`rcuc|Nph4;VTF%$#nIxCTnJ4R;Z7<#?P|l}# z_L_QwBOdBfr0(~Yiwnp~zu(Fwgag$Z!i)F&hO7Wi9LQc$nN|l|O@BYeDDp>C9uOTJt@-So!l~6)_QYVhz-(5cg%=q8TY2phwF|%C2bq|)xEu#L< z3jm|?$}t{JUCOvcO0uU;O8(~>u20+$&B5NNOa?!CR=*5@_hC%jjki8%SKBbd|$A9UJb)Q6E(+CxyJaGpI{b-iw7njv;*J#K|P%K|FYpA!oEbA#(t zYsz_io!@SnJ0uchL#_V>b3lMp@|r!8H$#sD6)OtkCy17cpT%*5}2G|)>W6z&U#--4~7SvS0aUM~5Gr#TUe<4LQTB$gf ztd0n>3KeFH<1B%_H%*H|8`n3oAO{gsefhcOmLelJ$D$dIUlh>%1 zx;Nq{B*Ob9nWOzVlOBA|c~Va-Z#fEydCklEeb+}+(_;$O*Jz&R^Cexj-Qv=pfp*lp z1lpVA3TjYBS2gB!{>O@#9u^kVJ(2F(+8PCalM{qhZN)UOVzBw~cR>j!<7r3VC`yeB zHggRi72|O*eBsA3)TAU9tfE94v9@xGY*)N6DvB&4@P1r&4`&RrKsZ&LgrOlX%JrYn zBhwj*ei5aoQGuYqSZERQWb)f@Wm!>*C>QO#DaNR^V7C1H{9?6Ro139uSmf1-B#(7K zJ;bTNf+Kbx-lj0%pc8HSjC2QjO<>kl(4g)?4J}fWN0q)Jy4xDq+JS!BnbYd$y}u{H z4%!j^eI`s@Dau>L=oT>eEqgUm{hRFZ28g*K^AbVyEz!9MozGM2EU8(so6>dl7UoCD ziyx1B%bs*~FdvRNVJ`+frkm`k;-U?>KZ!d;%9P#6e7Do_clLT>|8oVKRC1wKtAdMN)E^C&tB@nqbDt9B>jBp1yEC}r?mWUOz#zwux)ERa=j0a%*B7g7KT?1!)>|dnD^j9*EA}8O0xFR} zGM3~1v;JSI58PQOf`Wp6<2{Lnjc*vC;?{W?!@8gAcF5VCJ=di&hFBz|t%?Bc7ds-( ziOc0w&!Qq#*t?bB*FZ+r&>Zf3`GH(-54=M5DOgS?KMw?r$%W;)sON%2pJzUz!O8xQ zw*%`#-|jyhVw$|`(Ku9}TK*$DquVMSWcAyv?DorP1>9VYWel5s4KPp#@yEx1?UM0s z={MUS%Y?WrPqScer`3dw$=H(h`=~0_y^ZGF-t_cz$zH<&LpNUW!pR)jxKNzb+}yB>>$feXCc5A{nc7*5*;5tU;Xv zbp;(y)avodA2-o*uBk`s*NKa2C92zjS`0C!H*HdlVnUC((NYpkmS`2J0RtV*EoND9 zo(Gwrx}V3-;LaEoCPAF~mym|4gZ`U?EnbHvsPlZ+&FWxBGcN8GkKJ4|(Er%yiS~X> zD)4E~@0Fj;_;j4Z?BIbDXr)WIBEE6O`=*t~j}id)Sb1HM>L@_rx#+InRDC}G10SNg z+bN@Lx}H>u@mlzk*B9!Y{!UyS?=rq5=`Mxfiq5u2IqgoA zBDMKys}XPi-$vXu)d5eBj7k;p$?3yPy=AI?KULR|9EjipeM;%3`LLCc{EyP(@^ONci0}F|{=bi`kHu@(!cToS zHvxQ7PrRGixBK@}pPz05!hBGcv)jX;Xj)jxun#fn$(9$zS&x#fDx6n_n^2bJQvJKb z%Jp!G`T13vsZO*-#_cF74ZMT&l6^G2Z>g#?UCpl2-$;&LbP|KVWbT8IJOtDUi7t@+ z@bOr@KS{u8svR=nJ1qkq)iB*PTFdLY64nCZ-)?iT z$E&8!jEJB*2?*TW@`mH-Zszo~CnfbMyvftw&a0sTzF-2uugtXO;YDk!$VyzT?L6D! zMQuy5zf{j7D;=cTN$V(b)`};N(Awq(7jb*^r;#KQsK=mWkRD6wIlB`Q;;>41 zAufMG(b^^^NDdtOZ4Livdthd^zA&qLhK-T?8NRzqN3QmWV-D1E>M4!~%Mno*?K@!evZ=6u{t` z>b|{hyYV1@+O{+9?%<*3xB8s1LE4X<$^}jYr2@`{Lbw3r4PR^s@6|5Wu5BtD67~r} z671NClu|%9Q{~2EXGq2LBnl{-qlQXJsn}rsAd6L9UHz}>m4;lP*wrXry3#Sa*<-a2 zB&h3sYQ8VW;#obLD|)mR%0M#I)D=VNlnN_cxbNP`cGYIWPS@Ah4;Pz|(!!)e-5V<# z8=HsQ3)tgNy1Ph;B0@qPP`A;i-EXsFdh@!8Eo3^pVa@L2H{YUz-?*%FV30(8q~E$= zE=sJgGEk-V;}2_BQPH|JaX9=#BYBEwZSh}|GVnb)EfUXeU90FK=3RR{trw$luTY1i z(Tbw+qGh5(@t4B^N)-2+q}N6cXEjN)6r5^se0cFo%t5w zhqI^o^uj0E58NJ-@8N5Y&2D%AGO}Tmwv@hi2WPk$2K7)U1gvhc)&9OGmD2fu4NzvE zC2}=wst^`@U_PwFn1IDpoX1f02M+v}xp%bG+%#rAI5Lu&_0lSrR`y$F=DG|2bX%X{ z$V+V?-@&H^E=|zO1W))HHBy~W@H>1O92~rAxsniI*hkW*d2BzM8R!9265em8RU1?0 zaNzJso3uiKM5Gd5ob5kXW^#kHggECXEglMF45`Xt$TSBU>A1RTyE)!XR4*LP*Hv!u z2qyPplT=N9RzS+-w6wxQEb^bOQ z*K_f%c#WVuU}eYsX$PUk9O$#WI$r_Fz=WUeQZKUFUvl$GiEG=tSUP-Mzh$iu^IfKW zIIH8ze%OnRf84t8L~Xkzd$fE=^*82Nq+3GXk>4^Jt%%Ed?>`0FtAgwgM>8i%r5ONd zo{98)W@Wvw3E}UQr_&FEb4*621aG$9~a4b@3X>A;z(^!UgnK6~r2#&~?w))WWS`%Q>#G@PkIaxZx-CK z$dGS}ZDUCJn38ZN3(&?ATB1v(Esn=hBtizyK!ojNc3QklbR|z);%mqVaKv`aOZ%J z!*pZ_l-+JKhaJ6#xYtQ>xliH_*1{gJTUvZ94HcA<8aXOQq8S4b=ey6A)w9+Dx8$oY zBr~L3RWCTSuIljMRmM8}T+n==EYen3)3TjM_}l~w#pnI1kxb!S-J4=1CHn zA+=fh_ghFkOL9``kvHyB6@8Cy7Vxc94D?}L#WfLHo&Wp80BIGk5a7*D+$v{6x1|7k8z=+o&)6o^ymV`JH+3mSV&@Egn9GH@lLKJJ$yYvDh)-|hy zLUB>ELb5I(Ai4^{c`hiJhG)B6{j&(aHuTj|4&;n*LQ55F-LA9ZYmufb5Erb9A2qHVBMNg=Yp&GY*ij~g7>;ptruZZ%dW~y~u18yk5$o%kIU}YQB!z~U=v`4K*A5s4o(yF66DMIYL+H(mY?^D1; z5^Ul=r!T5G_1vGhLC0c>s9;TYuG2AFFi2c>srq%ghdTX75(1f`tW;C~mjL9GrSZT1 z0EozPE}CgqL*GVE&`D_Emq^@r=5lvc$9C83q7&)1R6H`ZaQTrm@Nc@<1d$oCq1HwR zXgXOdrFz(X9*o0nrs}MG{h%Tchk5{T6Swn5)eGBbmJUMdt46Nu7wlq`TsyUwawvDw zeBHo~?QJ%iREwK1USAYs`dCkxj4azS6oITlU8-jSE06m0NviA6{V~<{@{3X!Hy@2r zRZEb>8ZbE3fdV`}pac#WAa$KOH(DIq_{jDx%ct{voY?;~F}u^|h3vPitgbpPq}RPv zB#q1l9<`w5Gft*JSZ1F&?j#7pAFliQZ0qvK(SpUB1$4yjsJxmSlP-+S`4#{tjSBWb zT231>m(MI_@N(I0G(H=Pd&}Zu)@IYwWDJ=MKfoya(0SV(*f7R=e0GvMs3|GO>-zH8 zu6^00HYCb2us2qoYk9$Zy2o#C_vMHwL(%(o_Ox32_g>i_3d!ECx+{DI@9$U1q1h#h z$F2wiuoj!Jk#^(aIF=6Law~DV80f9l2&@Y&H$IH%dJ*-XtMCAtCF`V$?+M%QByYW2 zJaU+=DrAcy@LfhLpqsLLF01B;`lBYr?o!^AXwqc;XZ^#Saa!aOW|FWhe%9)??&tJ* zqDtYzi1zm>Ju6?Y1z9CFL!qXf)AO~Bdt3BOvL-wwM}4}9?qWh z{^A!B^4K2Dt>WS}ZNdAl9_%R3$U!ENxo+GWG?@1z(z&Ij0eMS)`2$Ll2Ke7eSJRCt zDo=H!u-lt_{CDzfOGQrfv54!umSVRn*;aM0r3kfXt!;OvxU)P^ml1KA*QWaCsDf7rRAjfGhTn+C2wM6d%o2GVw+sg=|mc0+HY9 zx17E}g7?SaqkDXgZxHMc+c8ToY(!g9!7x`Q|2xg1V)OF- z@!*SCj5q_RXD3y?%ozSGuw+yFKfeS$_?0YHCEN_Gw$a8Y!pHZ^VX?8Rs|!h} ztqALmi9CfCrdb!AEwg3FcB-k5w^;SO{T%1paHBR5>*K$&%DG0l1ob{|NhmyvM*L!J zITH1B2uUh5kP3JP7%n%gws0ZyrzdQ1Iazft#E(8ZyMnLfX1{|&*JFhN?_2!*L|nIq zvpgMI&bH_3mamAFQb?!#wrn85%5y?#w(PO@ayccdq5T{j;c9c}6K$6`{_#w6bHxvHh)8{T;z?Xpso zrv{yTT#m65J}yD4l~zH%Z+1S{i%lv%>XX>wlsL!Dj%?1@-|}*$<6_5J3qtT=a?O2(l-u3lR$yFaD>`5xwerh)I^2i0>@wXJvt~7F1P^sjA6qox zngMu}_@>_1vijlHOKcO`)u+bycVxk8An|IDJ%O=E3PxB`awPi6QaF`youkivk;Ex1 zv&s_}Dc)&syQHyg>#8Yk?~~-ol^Rm(iEg+C@6D1sGeS+=Dtp2YS-xhcXJq^^Ql%d` zcpQC@svN_7N_xpyPBpnj#s^`ubN?L(R!VURp9uB8EgoLLr1kyD78T6RE=OJ7M_AWZ zGjfA8_fH;d#X!!{g~O(yE{-|TGkE$p;D@-6sE>Auf3&m#_YZa7HzSk^mA(2QAAfoD zkasxbeA5|eX`X>lM*uQ`SZ|Fye+rnxuW zg@3j^6_>H*Ddkfp4xB{?HhiMmk0qs0J3n9kER!QLCO$sH^mB7z>GZ&r;uYd%u5Gk= zp+3HA*w5rEK_hFSAT`cK)k#!U|15n6M^xUVP4jUF?$1Wpu^0ntmkyinaXV%y&o+mm zR9Kka4~0uUETc5a#=5fe(HC$jSuA2=;%yr09IALPY5LG`TK{XL#R@=2x-&93m_s%5 z-9zB7wLqt=`JfJnl>HAMI8FAwe^k;HQGa4Khow{VebEIOY_{I&m8|ErGXL) z$|1Ueo6zPm=W4=pz}`rvm){TtJ*H(SZ=q>swv^}XIXLO@_Z`A(>vVO`_V>SWn(eaG z9vue4V<}Sp#!U16X5&nmDGIMlj!5A z?g-LVqUC#7k#)S$@4F1{apr>ekB29JDpQB|;twB;A~>SV{QdpIBz^UC#uJfBr|bN{ z*h>buq86h-K{nzHGMxwaCRUj{xp}tQ@uY9;f3l#U zv}K?#Y;NN^y_uFcI&}G5xsX01AXN1@rvXg83_)xK9(LxkMfZMP7+_E6fVVh_e%Q>> zDq>(lWo{TPzGcoV#&4dcKT{1(d(EJ=^kLP*#V9wAt-lJ7^9ERpvw(jViS$)2I*eo8 zKQC~)WKkLIVNQdhH3-UK7DIz6!tjS_L^*?al;1M`Pfnt7rS?-{5i5FcI4(v3XF7OR zr(TWcixBts(#)YpSN-y$aLjtaefr%t(a@{k^9Q48UU>8-^-e)|>ODwd=T%}@s3nhe z!zc9n(AOI6+B6RET*%@`w zE;6syllO7yA<@jOR(zYt8OVf$1f-^PsJ_2DrI={$mE1txT^9jF1*mIicoC3tYS5yQ zBR6WKu&h?d`%fhrdTpqxxF`R;*tSxnq4hV)s=CKXJi&PrJc|6P8Pmy{e3b*SE zkciq&J3>e{v}tpO3ShTnSGjj}tUZW?Wf%HJ4y)`0YKP3SZ%7OlJAqC5Cdj{_@meQ* zn~|R0fmW>nl>e=_!m{#v*YShqvheGT2FfUXbX$QRDS8rnH-Xl75L}ED7m5Vc4j0WE zu!tN~%&3A{IgT|=lqa~2M9pLX>~)yNS$Mj06Z)Jw>)%vl<6@3^Oau>riC&`;Y>p$- z*Z00C^LRb8ifafiiS&@~?Nwf=)-C)>Sr;f}6_Y+Eq(M4K#!m9=>ExB3*Ts%D^Wmh9 z*ulg-9|rUxZ&tPkW!W&`+@*uB@i@X%T5R=GpCm3^kCS}*`OyTUQ2 zP`OWp^j(DGQ-A#{ENoCX-Y4l6HR(6v43tmUGn99v>!_>w!2pr4)tWO(4>gCHl!EY9 z`-TP!SsyP7>sqh$$>K@(@B=(oB}OXeL6?sH8XU;!x@N%8h6Ve@Eb33!o84$e+jZ=4 z>Z>D(hrbC@vM1LKZ0`wFwAh zU38RgeJ|*sH-aV&alv&@DWYlHLx5dA4uA-*)78V38an{+uaLE@pQ|asU-tDi9X!;z zx#fu8p)ajhSt%i{9jO^Xq`L!q6Rjt6RO9&9E9oAggdF!UewedEcnapZr_vufvlz?5 zBGCuR;e(%$$L?Ux)AL3+umdLHqnRb9pmrY`oB}W|EYWY$IT7S7lX+F@Mf6;_VX%yZ z#LiFbniG5%f};o)4*hX&INp?E+M)m4M}aSa0tRPQs7(H8-SGbIYWrsm;n&c18V@gn z$Zc22lSnY=YQYr>;^U)VdUu=$04Tfx-R)OHzi1{3K>RO~aR0hchmB{j@E$E*Rj3^x zC+{FMi|*bZ|J)uui2^eB7M?r~GCSAAQ9MlQB};q8G92mWhciWMEn|~VxrRs9n8gnf z1H$J@bfHW95#LFM z1u`{%eLXXT4O0!*eDfy+?7K>Qo#^~AQce?{!ZyAv3Ge$M&25*V_9ZF=)G-+Vmd+y%*eCiPDC0x)aL!*V!e#v_^FfU0SzaAMhBkN_$V^v`L zx?a%I@PiI4%FD+W=J?&KJOmj_Sw+PyV*XKjJQk&ENV`hd`~2w;#Y%V^He^>tiKa{z zAP2lNBtIl3O^V)-mxIsc?Alo4U+gfQppGaYs#L~67mp$$P*ql?NX3PlU@Z)MN3_CQ zMH1I`bhOvB$(&^b0JL{XHD3#0KEeP0jy~)j0z2vn>o_FGNOWoJ1!d8d?hyyMK#6U; zjT+L*9CncLXD)Z|QQ+eENHEBms=f!Sz4Z~4>Hg&Ijt{Wj;uXIqpKJLC&zku((l1R{0*#Di9Zs@aL8plm_n@^{p1$opM{lb2 z+x)U$|QH&1Ap$d_QCr#HsL)DtRHPgti1RIwUxP-#_9h zwqi>xOv?jsbf}E-jv16GPp_opd`%{pgrG4-FCvYeyG#to$PoB4ZSo;s4{#Q7eJ*qg z49tcmd@_e{KK`6cww^#tmgh~!70)!&7{6zhkXrKNUUWdR(lp!fl3_z?N^RwZ4V!VujXphFC@=aI4tC3h+O& zO9u}6F>MZ%iN4Pf3o-_lqWn5(I3W`UPRrydYS!YL-lWnZt2YtK2So=8(OeF;bbuvF zl1A)8HBlZERQ`@7;d*JWGbT=F<#A^u#OLBFcWEBbo6n(winD3x^E-MLRglwyVy#ze(BM%ez}{Wz1) z2yZ>J6L<4+&gsBwF^IIef23h2Z>{Z;^V2_=$DEpkvFy@B@V9i%#Bfjx|Kz)W_qQls z9liELq+RRx;#U{>rhGOe>u(0aS7~SS5+Ru%+-kCs#qX#M6QT^S;7pzp&$}Da!hhQW zNK^6nOOQc*&D$;AV3VDROgGEdD(&uweRXwYSUsBzVssKQpN#wi6KxsJ`FaY8m_+&w;q+_@8w{4DYJHv>Naa!FM?*+Tt%R=^&kt;Cv zIpRxPm}czUJ6zin6voTmQKNp3=;^agcyXQcgqNL#9qeW6>@A~OrhhZ#CgA)%J1e{F z1!9u+)^|pUB=KJt__3w}s8mU|NLGQnFKXc#5~@v#nlnL|6lTLvYnHcJ%Jinb?{Wa3vO@PW=Sv6kIOnv_i8N+s!Y*<4A}Hr zaliO3!Q(6?)f%(+D-H#((Wp)x7L5aMEld&24DT?FI6n?zX9Eb#QTz75h};L&&pL(U z2EJol?W|ifD357i@A%6t0m)=3i6%xgGzom%;4Pp}8PW#ptxRH|7l$ToLRi*38>J}S zBv88e>?u!;Uy_fVo&U9Yc?Q!^5s}u>l3smey60TF^P6Fj$Xh8bCI*X(e$r2_{^UgT z+FGDi)uPnJs_wJC>msL!h(o2Z3eOTEKw@?VCUbtjv9UZ*ZQ*8 zllD`EoV%IcAOCaCe!ns11^Khyw(hef{_f$QeL19~5>t*q7dARq0>K9D$jJ2c(19Kj zgYHxoo$Q~xC%iVtCfXl1>r^$55tRNK~= zmy|VU;b6YJnZ@p)?vm4yt}xkD1JZ}^|IY7k7WgK@eRD)(=3UoIa}YQLmn1mQLv@U|0S1W;)zMcRr-$ z0$FYVAx6eOnFl0M^0U>`83LFmjcaI8sN$Zfz}i+ceq+QMqO9O&&2}IU2Uuq>w1&cp zROkvr8HaGaS`gol2%1WajErd6{`3y?@kx~l%5B3E@{TY@RVW-LwHo^(40(`}LBCbf zZL^40(>Gy20i{*le@&DMXU7$9C0Z}g(i)Ee?7r{9pZBzSfDgwEw;xs$&}^H*3~JP| z;i=iiV>5sTLP|bcw;cnt(!9Q~;PVxj*yqg71_@T9;s!9JP8V`?dP;6o7XKrQ)S^{iQf}bc_w4Ak<)It|2VRb~U#D6b;nv;)v&x zt;9CvG5=4|*46X#*vLT{Ghk%qOiHxu5$!UqYp5f2bvX9jD^&uH%?m2@d|b4l5agsU z+CmsLpG4fnrc`Mz)5rWn!4$V5s2IjVNwPsb3brbkvrGZV7*ug2^c-}qf_Ls(fo@DS zD&{eT-wyxGJz|pw;AP1MfEV#7H1ta$FQFDz{a}vujnS#3W=};0T<<~4F#>-;yOk1| zU#Ni#8qI;;8?5YmxJh7VBCvt@&o*Hr3d#>RcZ6UP9l$I{c$|*pH{(y&f?vrD6qmVw zqayyRRb{#+op>dS)9vQJQnPp)NTlED5xGc_)v@bIU-o|a__1$6i)sSnGv%&ocyqhQ zMR2lhoUsn|CeOdSOdyLoUqiU0{S%%Sj`m6!g5NXBgP|n9VckjCc8XMKnNRxmD1;u2 zJu;(KaAr#SEOFlNcM^#>^nZpTzsJYxQt5O{kbIclu9AX3HpY4zW~0A(Qgs zU%;;FD7a@Q5-9&9-Y?Q2uF`q9CnAeBEfA9jM-l$QEUBe9pt=itVbgK zbJwb%T*Z{$QcIXdYg_9KV9J%u6Qd>AX~~wYy-zw%kqM~59c9_6$v3$xhfmhJt35;q zPue5SMDh{k;B5Q@xx+&w$japMf*VCLkC3P3OS6@$IH^YZLMHvG!gaf}Q-K>GJEtYE znRGc&>&51AfIoc`a(uD9z%9v0Ch>vfB70PN1gPNAW}}l{>pa0qM8O|lmRsQ ziFrx=il<+Hv}0d}qdZ3tB$To+!xTTd4AXb?L`yX1ty}TnQ8{1>1l-l(TS#7&9K_|k z2nZ1m-wiu1xVF#>rDDq)k_7_t99(%BhH@`j99PtK=~$^`!EKC-`jtmC5#P)H@UVMt zFV$lK8v*UHm>mxe`H&xaRw`}ODYof93_D&mzjvV6bRF|yRn8R@G)A~sz^KZI%On-^ zyE?pIxfZ<}h~To-5dr)hI>L$pZH>KdZMcwyz2*t)BnulEj85mX(i&F0^#qG|09T%t zW(q?P#40e>MQzbf1eDs#_?os0j<_we<^;Q&U%SgG^usOjJou4any%BLOn-EUtgBrJ zPxqm^PJ1h4coI#6gce{!UbsITDcmcpgG7dfBbN_2BO^@+DbRMmjPeIl_n(j&IUh}AK2~57$&mY)JjrI0a9L*VGt4s^!lHuWM%|9rJ zPCYkY@)L8x7G@YB68C_K1duxdy|q3+Cr)jj(~v8PJv!AQVkQjzbM(KQiB4bdeEs;i z*gg9(daf|tF@_adIIB4ypy#c?OkdBa2w?)-e^37@RQQ*1+(8R*L}a+?LhF(64(JmL zc(L=V+ZMVxN2o@Vef1>nD?_VVACQ&yO5dCG8K`aG&ibZ$~H;eWX~Ndw}CoA*;;) zmh(H;G5&>za1@4(D=^A+CySJ-z`$b;M6WHuA?4+^W;;&;rA3SCD}{= zw6vHjCq1X~Ad|G@H z<=xYq=~iLN%A%3``uNfXZSk`6dXwKH<}|lM;tRH~TB;JQgMjopo*($*L+##w)PBq1 zB0#=7n})|RSbj=b77{g;I%N|6!?;3pS*reH;scG~tYt20Ba*z9!<(~*GkB}e{LaYt z0>%gdRBHf^E-~5O^E;6cb)Ay|7#%T)+g9@unj#gW&sZj|EAwqOIo5HDPJl1T*#|35 z6fs6Et1t6zW-|QLHh@p7@o~mB#zE-UJ<)n%*!82xn-@-{&f8SVP$P&V>mK?WjKyXCU)0)cUV)RgwLl>U9ZVIH4Lf19UNzw zl+;T;XhXw~0ryuT0LBRd#{7W8zg#}eFO7fy`!Y4MT;-<4tBel@r{Innt+hRk`M2x= zTM;5dgkD)<{+?4t92JW-$GdKJ#(r|UpnuBg>r5e8F%EV^u`BRmRaaLAFJW@#_<60} zY^GtYW!rN7x8cRrrz;Pgxu?_^tZd;RRM2dLa(TcNM^kWm7v!1WY(FH?x)59NJf9J8 z>;MTKzc%~6xiuA*E_J)LF33#Yosd7p-r52~B8u5t!rVfh-Ik zI{h?SmSEC4b3@IC+;ry)8O2C6Yhlxfi&cL$!|Qa0S5 z8KlXpQ%eW{DN8P16cD!q0FbdUG3zSFwWH`1E^7L_5;$Z9A=jOFM--n1A#tnr-lGXH zKR%C#_R~Ngr|<8h zXEkAd>Uk#c`qy^2u`s}1Aq>S7gDj=HG#-jRF#6TI|GRPck@E-F*XM5{83Iq|a&RB? zA3tV**uJOweRbU?`dl^xNC>)96q1O)dd;F+?>ZxwzOr4ZtBcnzgXE37DL1F2dlx{0 z@tF3O8S4DPnfM?b$GO1(ez4woHDpw)u<|7ZTDqLLIfu);au8$Lh^{c_`!(I$f0@i%3yke-_nOe?1}e+g8esS|wz{-gBiyigQ*VwU6kR_wJ2411nyZMtDQC_a70c z$bI?)pj4K}=_cJhr$@N`@&;g=JzKOc{N693XGrIpE%-9+4YVe~)hWdMO2zM~gIYgy zV$Ip-g1I3H)nh7`(<=R~8f25{+1XbV0*HARtdTQ`g-m(()2a^bW>jQDnf4{!rb zZz@t67{9?aAKGGftKMJsIuX9xXL95C$CJ%$ngN8${qRI;wqC7Fzu48y=4U(EpzG1+ zS3#8`Zni)kiaaz@s?QyAbJHi*=5?|HWEU*10@K@8lL2KF|9^1>U?$dt1(sg|x%0pa zxcI%$Fv4CsOcJHhG?!wv*#}jb&~I0j>Y%F5hagwX4vHr!_3W*#*A(YihE}EGvM}s+F>%LFn z3FQNaNC`kzQANqFKmn1&&91CiWZx3rughim4zCxal$2qajdO3Q3^2Ww2%RBfWn71@Os$+PjjaLKy!VNX?uYBPg&{gTw!M2u1aS%-DE} zLKVj7EzYo>S*mY)?qkKC7jhnR)KNhXw^E4!V&$35?_z6?k)!gi2uFaUN{^=>h|HW% zR#^Y;Eb78|^tvETxjFmFk2wurdcyi$i;j%;3%G_K2cQ!Rnu1v-$$8kq6g*!?z2ZGoh)fAxWN8Bn zWUv)Jj=8?@;R^*+(sDfvVz+WWj(@`uanw+#(wGWAt1&gfx5tgF>v`Q33GFK)SXo*B zB}D)loWf^`VlhuzPV!e4VW-VVhNFoKb(m{s%uL*q2jg z!ry$5O>5M?GAKoz8I;oiUs_9pK5sSlGo6&**PlU{v0hfZIAa+UKQFd9g3`g=@*m=R z1;raBqSaWwtPY7!Lhv4jBvHH_x+IhZ!Pxp0vo|+4|2#%PE?P6{>jH;HyB_Gw7%(Z= zpCI^B{Ua1nHg*9oXa$@L5Ma&!2(T%>Zjm8Tx*o32Xr-j$eHMC-X}8O8e?aZ);Cew^nJ^E`&j9T>rb+iHS|kkn6|D>DZ1+ubVp5}U zj2E&J4R^j(+n1c8TT?;P+GG?pe71^to(kY!JrqAh6A9j`0+I=#gh?}7+sJ#FzV_Si z?Q$|VZY`tkQnJ-p!ZgN}K6euA=hTU%JP{FJ*)MQaR?!KOx84swus@SNPxGxjaXf!| z&{!n`KGO&O?sH71tekRmQYSk(U*bI{A&6Io#wZStFJ`T2L-3#9hZ80NuFVFjPb{ zekG;;eep&5KvWtaWpo}Jt%i#TfD9j&bgJwZQw)HWFcTT2hHf7Aj_jV6zZy4l%wy?I; zJHOif@)Qr*VB$iJE!y)s|QG<>wnSWaT>u8lcCIr)n|wa!WZcDDD>NsbOwd=p3w60Y{w zYRUPV_!;Y=wrH-SU*(ySz2_S5*?03t9oEyIv4A)h%@;5{zbhzr-qUPpg$N0?W^@Vo zn)R=^2-NxXJX;39CuS;Pct#Q^f~}7DWoxfeJRYjH`7%%sP3t(+!=aR`X=A-InmL$@P#U{!z|gvr7Lq|{5Wj$|HPu7A zx;Q?c_5m!!$ESlYjRG_%z$>h&&@*%xm6pO{mN6m)Rw!)Y_?`awGK7De(n4=^csNZU zO(=& zlptfFOA?ADpFTnM>-Rugz;24WZe_30TsUh$KK;O&&hW@0^nEP#ilH*+JM_9V*F`=) z0g$qT$`Bsp4i;E{>Ui-BPc^lbyp~taI~cI&sh!d=;jcnxkZ{e$G|n9_oZr5;X;;I@p{w~a#aHK8HWe$&A|l#E4}N`Pg=O4 zX7^wCe`S}(#%QvI7~*ap_*u}4QpiiyYA?TFYlGO6$l$lj8C@y1ZRZ;TafH+ zjOHJz_|o$}zM;pBe%B1IS->4p2RiL{GgCz>Vc6ao&URFr6D*l?JtmV4I)11MYy><{5W@ybk&pd-G zsYnsL&9f3lsQTg!kiMFG)jJ7YN(unHeM$7Gb7OnuFw95j9ktePDUtQ$!Qb6J!y_YR z?w?>Y?nW~L!pDGce$~d^EthT$1t&|E>kqgsVqVIXiufJxeeS%y?HDS#yk5$?GKo>u zl8;5tXaG;;+b_HIB5>|?XQOOG{a2f>A!fZqFc=KM6sV|M!hO;iJw!fzv1?3<#CbE= zRaZWDg7?@et2BL>(huZ|M{CpX!Z<$JC5B$v(d^Q+c%7zA7>`srH{2kr^j+a zg#t!Wet|GDL~_n`N}rv^`4Uaek}T1TUX4g9_(jNDPjo!~_cE?#Gztxs(+(aA6=TQO zeaFA+PbymvW(BT)7)(AsP8?i`-XAX1A8byS2o}Y%a35!y_-FfkaESJob2nd$wh6EbXGAVe>5C zUQ^D0S@~qBmPW&A>E3?R5A#v~t1NHM&kLbmPp70 zTco@$1Eu#G0&HnCOUS6YrTTO)2D+f4E4_dO%~T&auPcI-r&tas;9-_BMz9Cj=N+la zSU=!I_^VB`M<4zM_m*HU6|T<2hfO`e7}VF%?D)TGc6EDl@$>V)d)G4;h3cy1Q6=>V z`@!e({>- z(!m_0J5Yg)>{F+;s!4^YAZBYRFsmLGEu}?;Pu=w17!B?VNHSlbh`+XJC^pdc zFv`($dE(j2TcueeC9~*VkaW~4_9xJ+X@|I5D1I)os;!pJFdM^G9(MRNmQ}lBWe131 zWP1k5%oA>x?hA+0k(^qANpXgn3{L(GvX?R74gC62scJY|6Nz*6b`is+Lv2RvFaEKo zDL#OQw5MT+C9Ax=lw<0+=>g*-d|4O9`px))g`c_9g^}?(hEJbN!EqVi15>S4ApXkn zmV^0fZEX#h^I3)byD{r=JaSgN%N}(-=wh{O^C2~Zs`OE+c(5`{M(Wa`P$Ahz$ zO||nWKQRCUZ%1cS1c$pbp&lN)UCAR*)LTZJ_EZbz1+Z>&CgdT$NR`KX!;(Mf0%j`! zVZWwEwR^6RD4(zK*bC=2D@4mX+w{$>U_m?ljwFK(G98*VDCqyg{mBgYy#`&|;+B|2 zhln{bQ5kH0<5`_7(RW0O2nt3%uXrvx0OzVeD>dNOVJzN+3j#nPfk;F|#YDQXAJ%B7 z8lX&84n|_ICa9_{5Y*+@vAo4$M8#phOFcKvZycYc> zrHYaDvyp%V|2;(5=X`+S4EgeYvBBY@a}t%RMz!L^DL5DEQyn__uE93q3mZ(gSKgK4 z9hq5}YjqjpQM(03OS$xi(FmHb?kW(%2gZjcuLn{Pzt^ZY_<4A#O>bkt$!OHa`6iDh zjIxiCiI@4;3a&&>LN#-;mPp26(}nh#ipwy22*EuLq-~YPCT+jAyumd8ZZ^ zsioxOmhAMOf4_Ee+y|$4ATc9^vb+l)8%BsKA}D4Z0umf&_{$_v2E+fYzQ_Wy9h_fV zq+#$TI=juO(>?D`=5`l(X=`IAQ(|pobwOh>)oYfY9+7Y^*Xah6Vl5dOlsiKSV z^vQ=(B6J{A207Xf`k!8P=m#N=FjzF6UnleW|`K+ zZ!;LtS&Rm7z{Yhz$|BezWvIIogOGZ~Z)q)zvL>1a2#BFTk-Ql-w??Dn9l8)6b9;!9 zJ>%Z|t3ki6%hq!qwr{>g-SbN(=gclUSG!E_3c>W#z+G}G$yFnB^Ya@e_lXa-0>jy} zTj6)j8#ia4;eRM$=IHlMF3yqL4Ko1}j+eM8S?)g4i`$65w(@X#5)#R|o*K9zcljlu zqpI6KCE+!iE$LQzJ0V5njXV$7@A)2#cAxSjf#UDbF++&da?M0;!2%|@Ztj(3FshU* zK2iNm8y!l5H<5mh#0w+S)1a*G_@R0B=g*(%%Gv#@MU=a@+}6uhcoI49lVD9l7nyws zperEz32pB-9|27ze&^RIUsWA+*^{&+FShKOcAdSZ<1W32B}`w@RFi^{-3fg*(cn$d zHxag-x>J*bdMPTXXPqrg*nJL%^oZ&rD~L?U^L5=GA2SXY{js$i0ZEXC7f!IUelp&n z+nJR8H^VSK;pBkwrq=)Nq_)aUm2cS-t-hd#;&va&uNZE(&I>w8nh{Ka z`4p(@&1W9J_6oieEE{$xQVm{4mDaROMk2j&H7aBRH&fR!0DNtdB}gf?HqOyu*S4Ld^F6B$Mp zl$!Qryr>(Zup&EW%X^pF-jetN%JDwCKvFwX&bTa9;n~RP)_nfrb+h>A2B|kfGlZ~^+jq~gg#3|1fFJpe`w6qLL?Q@ohoI@ z*`?G&yFJZg{)2KcOPX~Ea1>uWQ9l!ZeE zDQ?P|433Cn7zT)XL?k3#rlEotFPi^Vy%29?a%~}T7T!W5tbRU^n(wLx9!Ae#Z5E3O zDk;jCXQ28dEvgR3x+!lBksuVi{ITF>GBS0>^0BOCt*tDl`n!4Yg|HMWpRyyULZKW~ z=9`we00rB+us%xklB7%PatSj^t4#|qx8=N{)YN;)n!KD7;NKfbaC6^Ed4~~*a=ohW zzRyn>jAO>RHQMw&?C$4uth3s*RA+V!%TG#|Nx`3kYW*xPWBMh78jAv#oaWloLxD({CsnLn zwx@wJ$CE5i$Ne`l(SrEoq&NjlARp~F>drfNnqMw4v9Y4S;YvT#Er=^M%3w0~p_o$D z)P_kC5u=1wVpjy9n|fGVQ=s>`Sh@e@B*&xPGqjyC8T9_8rj_N-cY_V->5`AVJLrGz z?pH7KRtsczRa8TmceY&id71)j3juxU| zKY6j?`IE`WbL>-_KDyOcFtzgFoN?!0_Ydx7nhI*iBv1r}Lt-IhOcqJL9=fmoe>Q$d z2m@hRbHf))eojWptOC}UUzP`_QG{T{{L}T>*t`=yQVt~W_{?;L)TSk0wh79AtnrWpRs(>C2p6mCJ#46F*)!c*NYAfe);s9O{(nD5maoeY*#>CK=Hzvv%nE8E)||8! zZB&c$cbhbA6iZZZ&kp+K4Tl!16-Wzyy`-b`omYMRbNaEaV;1`NalS7nT^|($?8j*9 zu2$9E5IqNWd}6~KjoZM;8b&QI{SGBu)u_#yA2O(`|LZ_}^;6Sww2sIz{4oF1NcLbf zVO8&{UIWz%?QU5lP3jp^^#1el{4V2H4A;e&*uu*z-gbeiWt!j0Vj(86+8o^?gkF(k zC#^FWdZ`yEDLfTlh{dfWbS{J`$;q|)!k2T zz79ys>Di4yxEI+c+qW*VQlD~EnzO<}8^nG;^?^*ihqOUALs0(#=B~S-cg*{-1p$#+Y6?^waJB9aw`D%aR(2VG=N&5!x z`S8ZW>7g`lnv#NiE=f8^d9#Cn&0bk!a0e&Sv}V@hvTF&oL2>)CpyuK-i#9cG+iE7Q=YjX-RG8a=U0-#6yz& zR~YsIc3f%@`nq$%c8A(k==NFr-Q=j4^guyx$dCIVhpi@>s;9{+L;ae3Crir#$kb}% zh04{*Ln89Z!?)F-&h~}&i>F7Y8+;I%_tA;iiT3ql(Anx(>lN0@+4vFYR5lFCdV58g zb3gE{irCn5?$9dCO2s4?y_S;)eQ@d+%q%r6S&DtwuN$wqZEdL3RpT_EQ4KVBp^&@u zR(_&EAm5(9YefPg6XxPd!r~SaF!t6xn)y9>O$Ny9-;Y!>)j2n=vHS1mNp_#2ChWO1 zuo0m0322{18hYW*QGhboRN-0W;(A3aD&;P@VN!1NkmMZ@QupAA45vM`+LRg$e!rw+ z)m6UCr8!>qQNL$xE%(~^wJ)Ov4!ZEBc3v5TZnCD5OWU+06h&wjy;M79*6u&DM(E>+pU%=nPiXRPAow*9OfgZy^H3 zItCt1oCLxqBV&fz9?F9J`?`xb*lvT2Px(RcoQLC*fs(+qlFKS`3KCiLa1unV@bSDw zX18zUE_of1(fW@aaX(ymQHR>-oCueQ%R8EWZRnYqP;cl;6V>*d7!LUSNKMi9X(%M9m0mSZGD-(ofpJlBmzhk?0!d&R>8g z3DA+~kj>!HauXI@ouCkJh3U_;@F%>9hc&rXYL`XathGn*_Mt(Tp_P)_2zstFu^H4g zuHKGAW!glIoDer7o=3Nr8PchR42}=+Q+?TO)#l!N@LEN$2B)j@^I8TF$kGa7O}6g| z1r)f&Gm}o*@bJ({NvY?5<})-FxSx29MRrF6x+!W?1Kq6DwS7w^Kul&GqPUG(HLTgg z^vTU7S76v(7lSIQp0LcYl%TpWV7cuDGvo^^bs8G*g{jU z0XkbYR2cL5ou-txbti6y;9@{>`v+-IBj=H#CFj8v5(KvjIl}16$ z`2O;nx4%dbJ(42CZm1Smba_9;TM&Ahsg#n_O^GA$#akE+tR?p z*SKbD2Ur0x{ zUrJZBj_LJ>dvrZrJ#5(&>cy_}yWC!7P>U?40tp-4iEr6 z%o{x4dIa6iCU35iHgevs9Xz+UaXc^d3$;D{7P}kE;cxM;@-Q~+lu4$$ULpsxnuisS+zh?;Ei+uXX zMmQr$yOPx_S3ZEFFK5(2iMYOoQRn*+0@S}%b1JSmO+JZ$cbEUtmX0naJHIsk*<(2o zc`umo)3o=!I&t&2%l?-7u@t1$R~s80rzO0Lr`M1Iw~(K`sYP-KpwYIylc1nQD9E%o zU!nc{p_|9f_%1jx=P@FkBYTgMEZa!vW$N8M^60}6av_Dc&T4{qAa!5lPdcc4b#Wl$ zSj{lEx+YK~SOYwQ(d+|;+9EkAvZInSDJa&yjnM$=$&Kd*i8Nmup#6_h`;M_7+b`%g zJA7TbTA6YxQ#0z`vcDzT%r*WyJ->66!c=gO8D*d?VoyHYHnZ-DNmdxnP**M;bL!v_ zK5OtaO!m05u4Lb?$#*LIrkq85S=8~Ue>>Yj6fEa=GJ*M2_6Euf{=m)}rrW8uor0r) z31UfQ&0n2;GI$qZanw$?<^Np4_XyjMVZdB(53z#D2U(t}KOlf$vn!b6VJxF8sUxjn zD4+lki1S_Tj^XOohQc!nxzP4XmfRj@dbNW+fg4 z(_Zv#Qxx&22Vk@xOlFZ3*vQlcBG68bRN!6qA7^Owj z@3sd39I!08Tp&~N13kr=Y&@WRHv5J2@5_cH+(_KYQfTk^F6T*FrrZ9X-2ycs-eMS} zxyyMRPhL>`Q>Pj`8EH-dA+n9SYs6ltx!#{eezuHp4+&bTjj^)yeKEe#EX`y*wN#Bx zq67&Mqw*NTK=Xrx)4tPFZg%J!JeXkj+9dN@^3EE!Gy1%1*UfY77KOemWsWx5D!;YVc zxuwOmLpnMm2?sl|gO?xJny!r;4^#TrKGLIjdO;TW%Ns6@qgg=>#g<_5n! zvFU$lgy7^{(xnT%SDh=FvHeSPar3hW4LOM^gUU8w^db{Era@T*IP0$;Nl-C6tk_tO zE}yxKLI&vERNtom49Go3#qEEh#!QoWZ*Mr*AW@xy(@A9NGAnv9Zufkgn%Cy?usxLO zRW9<&=XSm~pf;5~^E;%o<+*@{2XCAY9b}i%{^@Gtw(aSuP5Px(JA6Hzr+y)9mQDYf zS{UkdHYt5zTxY!;^`@d}QRW10TEqExxbAWBSS-(QN!j`F{A?23? z^c6DlL>Lf~w2fn>y4oy|2|#kVt!J|{V3u=V)8-xjUmYTfHexU8uWe|S0{QMqUL#dF zB!?@qnCpe|HJ%x*#V5)4b~B#i-X@uAaM~Oo&HNL1k|b{8t&9rz`>!OEPwRWA1UQqv z4k$B^8r0eZo#ua^{Ro`4zLe0a`cawE@9tr5YQ64F{-73>^?B7ab54-&rq@{cv5*_t zoh8RGrf{qGMd^wN_y1`DSck8=^XU{E|EdN^25rwKx5LF8{l~89pAQL>2K8l&iTZ_A>Oy+D90`j-lCq! zzXOl!956d&+hVwkx(E=TtxOd^y5-!Hjg?1wxDny{?7kq)N_roX6WspY7agc75g*2A z+WP0_E7=FN?l9w50ugrD1;>P+1nMLe;+S^a)KMy1`kcVO(1a_n*>+wb-;mCxAs z+&iev+H=57V^#2O``P(!%1QXrk3;lw0%ig?F>2ckC=z@8lb7?z|LyM~gr^n;d+&ll zwod3l+4uZZ z3{N&IdOlq5lHI%=a)2&3I1lC%sOSq2Mkua)Xr+vZ9uSl|xV42;yTO*Z?oy=1UIk0I zgmXhU5N>L&dG^N{#@qrYx{#GJ-Gsc3w>qT+OKC-X>7Z} z#rMEVr>x9}3upp;z6{_lKmQx?zN|1@H;lCjvfZGCSIia;)(o&yrCU(ekPu2EBSs}q zKLlc#vfzsXMOVY4O>nFJ%ImXPi7)#Wv-Yul9%~pgKFBNwAy}e}Sgfx%=qBHw(S3ak zUpW6QLlw3tp?lPQ%$@YsoBEH^5gegoZWUaEzo9EfQ;7-kKH1Y=6d-Iff)w7cJ1QB~ z2qKoHfin*c06boc3RJG!KnCg>*`ATzp(6SyauySEvsp+uDk2Zjy?4b~{}Me$)OwWV zg#2ZoMDF2QVikT)$2UTLaNq|=9$PuR;utm-gq{@zJ`S(8vlUzurjARtZwAB&an&r0rkDxH*%$6mn6?1vFtLzw3!Dl22pSzm{0 zYg5C#0z7XIR=hUv13@qb!v9CpS4KtkeSZ%KNJyu2cPbzq0|?SNbc^87-6@TLv~+iO zNOwsOARrAR-2y}S-0$yM|2G4RH_W-~+;jH+)ZTD=Xm@-Z6K&zjd0y!;y{~k&lmH1` zZFtrqV6}z`*W>RkK_0u+t1L?b(D=B*LT-Vg&vCIzxw@!HKy@o zb$b3@0|c~MH0^tH7iV?`0o4D*?^oY7UXi!mEyyT&`r(1HF8rN!&|B6rK!iVo>yGtY zh?UyQ)+~Nzgr~9e3$s_Xu0Pb**K z9B!ckCtN%=cG(jtI99A6Nflu@Z;v!T-oPnQbi~S*ZALi@bIEem;|4A_ZsM@WqbcElW@l$zA(GMfiR#~QUMre+f8c_wqo4=Py2=GAA zMt~yVFu*uJi@C$2$DA00#^)}-v~=o*#{>m*ghrA;c|7berqg+Wfkc4GkeUV6XcMPE zB-zNj13@{iqN(_aF`^??k2&y1lgP|%#I>lMr}@+M`qCkdNfDupK-?%Y zi%TQ`mH1rS^uCP8bdRi)|AP!M{e@ZqgU0CZi<9#(z>QL^)_vDoH~Jlf>15NJpQ_&EftysBFm8Wb>W zsfhWqIBuqK-|ng__~N1P;aU7CV87oA@w1-&3lmSM)nH-_K~aD6HJ7&r<}Z9tH*G#n z2L04_#QdL}6Zu@L*AOp_)>ivffQKrnLa50evaobBd`&@(q^1X28dUjtA6Kfmz3=?? z>1-;Ma#fs$m*37;UdgFCirQ1!Nn5_YM{t6RHp@ljI3E|TOh#$29E$#kV~hxs-U3CIfm5hT*@yroVWnh4gWZ^n&G{^1@+Y|0H-5^} zW1%gIgVHM1RBRhRl7?74)SKl9pkpTg!wDNW0mVVnrix_XfYCR&@V%PhyL_XMBs>_4 z#2T^6F?!}(FO2+%&;paXmjh$)2#rT_)tQ@ux>9Ypa7tcvRz=ldk#awpo&oe_h1FjV zP@N;00yn+dyx2Cm@?W{;{0&Ome_Th4{VsEJt-GmIFmEhJ&Qfp}&e>YKE386C-SId7 zVqf@|9srYz6rrne{wLNCB`1NLV+BtQs@x14ir09`8mf59RL7?AA4wm$Wq9~O(saq) z1B&IG+~)Xs)TiSz%3r+1`G#up{&9PDxPd{;@VC>{7W$ZPF5DZ~wuIt9R&Q}5_}qsO zP5Nh*yPS4P{@d5^nL^&If(J)^JxgXK>a9W=gfZgh5}~Ev-N2(HN21u}f1;e8fjZjM zPOi{q^!i;$38%LPTt`$*;-0Z~m`F+^LhhlM^BZoNn#(MI6=$VhVxlNEMnuCloBrZ}uFvuuf}gLJBF%aD8^oK{lMH5KPse0|-0u zW5P>Q^4`FmW)3l>Jd>s>tMi4~$NWirGI1fJmZL zF+byr|F|WPUW?splm}@&vB&4zt3b9y$ftLd_f14dAN4=|`~lF?a@6D$LXL_RV)Z`! zKdabr#YsJ8iaWcF+AK$KR-iAZ<(}#`3QfR8M_)$X(E)LTy}>VlqT$t3Yn}v47{I`f zgp?Rmi@+86GvnyV^?ZCeegct{b3Z^xa z@H@Ko8N%S(oLsW*_~CzYoc{PIU;$(g0cQWLufSaq&)x3q;-aVsaP)O8iII(v!?l#= zf2mBmG+hzHrTa>SpGc5}aT+hhT1yzYMCFvmp_>(JZ#4NebR1p>cSv;b11b(BI3VE| zq4}@EfgA8>U1{Jz&Z?fhG2(95>q)8QWalkfxblXc(b51#0i z_#Vhdhe{Go)|Z>Y)G6oGBAq9O-}Pqk^rU+g>A&XT{V?Vx-O%D#_*^2TI!A_jHsSc= zq=iHA6?_e#o8=abF3yB25OSIEI(QY%bvLLK+}WuGC=2@BATk{0nr}{Etoq$)(`E|` zz>i59Kk?!O#6XDCSQV-7{!ki-C@n6F^NF_VDJ;tg+J6N-U2A_^rSYF;`2!uYfSxXm zYPrhyIQnY}V@);bXu)*Z|27s@T3x;e(k#01rK=npy68fM+&{1cx-~r&3Y~~&K+kfG zkz3@T1a}VAL?mvwQ6xJjivDKF=$JwE@Se~VVU!5G^Y-zz_h1EeR)OsxG$5?*b4NwD ztEvEy+Y^zPlOexo_iKEK@SbyNE&(4Q{`t63j?lm&EMeCI_3B~AH8;E4^2CLkCCjx3 z`@ApxHC-$H^cSfFZ3Ys8Mf=Cedtmx?XjZQl=R>}P#h78=VRq-Oe(FU>Xa+Fp9?%_3 zyvefL-}OFSZn?y-Qb3k!HqeQ`)McQ+amxWVnEY*?2XW1KWm)x52U-)3priQ)#WXRo z%NKGFo0p(0S0VpcK`ozjw>w$Y?>_lP{KZ{4uG$ZD|4R5?CkS(`;g)(8 zxjRc5(`|@Am-a{z&2DP!(r8r2QHO5%paQY(tAhiwF2xiR2;3euw-vv5{A?A@sV!4Q z{JuM6Y~$JYkN%Sm+S$`f3B>G1z?pBDSXQPqFM7<<8ha=Nsa!9C$OYOHg$QLjL(xy& z^Ny2Y^?pS=eFe;Lf+!+&-fnf~(XRWKms;z;=kaiRi>?5GM1{UH%^L1pn~fK$T;^+Nr_LV}0ER$=a?!Iel# zE)(M_qjkV9o+cV^zcre`z_?o)vo}RlwE*aCbVyRy`lCA$ZepOSIpz*}y_m1;`EPI< z(a_Kqepgpbk|dg1m^Kd6Xya8#EW2Qpb`e>;u2&pPG;H)FfpqkWyf&qA>jp+JgCD+& z{H2&`|IfrEOv9q2yi5mBqmcRH<6i~5zEpV@qC+&5pw2@N_MabHv-lcU!o#y>T zmo*ftujvDb*&Gr0>5nrs--1zk?UpPg!}L$|GN?9wA29>VpvJ?#YQn`U6Jep}Eq|&^ zI4);ihwi2VN}Z`$jjxY;KYzvO3ixGz+fNNbq&>*B@X#bQuSB0(Gzk*sCPi{ox8$+n=n@jSO&MJ*BOo9x%8R8 zmR9JVSYp6DK`UVhj&4lgw`%iFSibEtEJna`&2pX1U{-11N0hn=x^5sn-5Q^8_DqtX zW?BD#f+>&_Fc2Ngtv`Oa8I@dbTTnye7rPu}6cjl{wg4H}CGg?wk-ntl#lD&k zC!1wU6b79`=tYoYd6Re9zdB%~|gdF}>qeFk?MLg){H&;hsKB zcJ6jVGs5V47vhCp50I`mx!(J)Z!9Gi9qw-b-u{DGOL7!@FotC*&igpPqBEIv=K)Oy z1-?r~4e)+^o4-@84uC=3p-@cYp^W%IZ&Fgov(R1+Z{Jj^q~;`r8A?r3!Sq2ji-}6v zQfAmIAHyb1ZanQ)9l8k8Z*9S!4LlYutN+AYwRx`JTH+#+!PtICeYtk$ z3Mlr6WpzKc?P zy0N@zSPKL|yH4>T!8K6xTKHO<~8qE#!HayRDZx)Z1$As;v z8)8|Eipnx(y6G82@N!XrhL};PfBJpcu^&Iv(n70|-xm72hC5B)8Ot>php1WoO=+2qaql z0ep6du1VEX|MaA_V6s9B=**LFMtJ?Q3+g%&~NPAQb6{ z{Vh#jRx`os82?fYDh9e|b$1a=H9o7vD!fCj)~WWat_^CoZL#TknvpO9a;;0Xa~DyQ zhd~~8^%qJ(O242!scV=Guw8ivBQ%gdOD=(n`~UbH7+(^5s2PKnEf@=wg8~Yw zZnb;rT2e_kPxo<-l7GP9XoLWP`fi4J!_!&mtBlIYk+rx&VBu#4=fuKs9diXeN0}^F z8?Nd9#xv#TI{F_OQZ(=Pj%pp^KiIq!xX6D9A3%fLoKpVRb*b|47fIHe<9}Ag!kc}m z&$afNf-+(TIo5r4n{hbWrxjg=cm>DZl}$KSW-3A$8%}B%k=W}}G^fnAjZLvXOyZrR z%T7%0b)mW;Lb?adH!LmF8~>=E90}+S(iQMskNjiiOZWG`4T6+@2Oa?;Y1oad4*FkG zUrzt}kah<=P+s5|{n2c|UI6WQIkiWQgMEZsNjW%OwE9 zD)zkZTrz#T-4iy)9;Tj&sk1#%#Vm`FA;cSI8ejKL%116dg<1sZWFTv+LW z_7+mvTwFBcMfQ(ZV^DEnuC?ws)TPPp*T1OTI}G4hH=p>~Fj?QMVSBesRC@A(1QBj_ zE&Hne1x9RBSpNFk3u zcbahP^kUpB3XUER;Iw397g04%lc9Pq-qcL9^z#0eynFbZ2FRofj)xzN$kJVGe|#f2gDm|2x~T zH@)8Fd*9=o^MF{f;ZS!8g}s6UYpdp!T%xOPN~$EUwC%3RoAX@hBHC`|(uA=D=Sf`Q z|Mi3zHkw%4QE?2BY-tqGt^t4;<5#go2=b&H*)&0Dn8Hkc#YMVcj_tbTW-+Q73!u#d zDqP&kB;Nj$a~}n89S=O;S=OEUxSboT)<0;-pr|m4TjIO{g4QSTk&D~_afq_&YCXww zKY6_F|M_hFS=@IsbHk|9R`*|y_}d?zh6zo(kWj8Cg=)fGZwKO}lrkpV2^_Y=B7oQ+ zHRw^&-pTuy+DgZis8D+DRrzvRhc_&a#JaS8WzrorMM7=>=2=Y?`94l0^>TSxZ@ZC7 zrO$2t2N{;jcg7S&Irnb1E&WGgx@blkP5v8G*2uu>BY8S{;v5`vus-j6@7R@CRsycJdM> z7}jb1Fal+ugH(RTVj3}ouGcVm>9@RVq~e;g4XTUcR=%4It?khou8h7l;dfb}vzla+ zWb$j($7?Te<^6rlJsd*G{Gl4cp&NWqrEm%Yiaoan`Y+Y+R+K5>as1rR=t`LJ-6!^r z3>Y-{KnZ^ZSRFnd0v~tnj5w{1?uzCec!O)~SczCWsS?sI8XiX^0!F3~)2s(hz5wlr zx86pl&IWGV;|AW^dr$EjGy#+FX3|{32S?+IT5lM%c~$b!JOI7EB8!+WD;;ORrYlg& z!=dxyJ$LJzPJME9I7Hjw_p;a7Kv5X}q$4EI{oU7B(h-0BmEXig%rw|`W@1x)H&u*l zt(q})*ZWPvGhxfzsEdkK9j14lj!|X`$J8MfOUMmr<|9C|J(0pYXjzGbdC<2Fw+i69 zbH5~CrA@0$SRE&d6bqzev6B98847#Z_Lzt-b90tO?;R-m9dIbqF zvirtqIklc%X~}{`BM;*Rd>X%gF^|CV_kZLU5-Mw9HeZ9C@%`CZT)=FLL)4y2ZhMp- ztb1{MokGqZv?`Qe)vtrepl&b}O2m{j^o@?@%S7bWm{n8JZXGO(3c=MSmF1eh$l?@R z-n7^U`$n28+r{Vn9-Y#C$=)BsG-29%yRdHHwKofjTTvV-D< z{(ImQyFAb5f98=^`w3Wes*NODZ(anj%x1)BlDoOlIxbiU;KmrG?q0Rss!Cis~YNKIos`_ z-wZT@F+xnu_6V%iB4q1)R?!d2%cd%kc3%)lFI#!ObjiULy)!H;n3wUNM6U${;xp3} zjW1eF3|tz1bQLUS6s=j>rno3UQ9B6gQYt3DP%IGlMqAFCm@B=}6Po8boyzJ-5&M)k z^;;|i8SIBeD|x*$x?v>wZ*D#8>^S`=<42$Y?&R4psp{t4*mk)8$u?_ zIjai)|KEM*5Sc;}MpDV=>g8J3p?UGLDXk zE(+S&%axg4BKhKz%^za%pNNA#`8P9g@M;CCSYpuX;7SIsa_CM{^$-XO$Wn^Tacdx9$bYh;Y&xhVg zzs(6

9`q`y#|ry^sF0B0_N{`~o8Mmnf8>F6_NU`R$+leqR!F@q&Hp5~D}bxv2qPNpv`eEZ!5HTI63(ra;zwfD-^Wet|&+ zelrcead4kV4Nw?1p~QcMi>rj+J3kU1Cc{0LQP{xT%h_%PUsW?srO)J?*es+;(fq-t zk6-w}ieDVr4S2S=be}Me#4N^i7}R++>h@4{>%P9|ohw$#mpCk_&RME4jsXW$q8)3V zcEMdpId`^u7BmW9EOW)Ut}3Koq{0d!+iJaYZinBA16N>7Z*c(tn#%g%^$S~zoBR}I zXrdu6I?dethd}6#DS%xb@yYE-7gI829L|koEJ?s{!=hmcqew<(jY?QslFAnTCd+nP zEaP%d&(n$HNZ{;i(_E^in#j&gFVhUYJbnp6#Niw6WdzDWOv1)h8h6P?Qc}|KDDhn= zAs2a^-LitKwneWjp&5fA1)84j?y!UjxZA_5=I3QP0oLRa0KaG`WZIPog(ehf-O+LM zGtzwadpS>TUO8NS)Xe0V!G?5z1?LiFPjv$)x8O&`&tOgytZLja{5;PK5BZsT>baex*^Sdy$CwaSvOKI>a9~zUij}r z3xg3KRz}ouU^X540fuv?{^d3;{$C1qF=V%BSBIY&0^jLdUH?7Z&O4e#EZAZ!qgsz~ zar$#G%iZ(@J|_~Pp5JpB@b6-UEN*We3?Rk}%Qsj}fyuAWLY}8+B@8#Jh5$WpF4UB1=nYt|cOt}- z`JhCTRdT%_I^wvay~H*5FoJ_W%-1F4o4k*}aA7Pp|GlGv7HB!K{Zp2#NT%$J{DJ3q zbJT7yy`ZScA!Lr&TK^{v?40$}$Y)b&l4LzC8O1E(RO75piQOUO0wUALZBkb|o`|IX z(*g*f2*4NtsPeMKETvh89vt}TWbNfjYmMF;R}KB1)wX~y2&t3~ben2213iQV;D7qN zk>UND$GM#t1>gG-D+v5CQE_SKrWVsX%(k;U{E}r${Z~)0cF$ zz5!V9bmQuuApLws7^B$Dv(4GvdlNUe@`^ipJ=1}vmfF8sr+thDh^hyc^!`j-r_y@B3cBA9w<;j$Xo$7Ec-*TQ?epeDowfqL@8R9^WD!+MEtXBb!M{ zFYli@uCQ_uyH5a9)5J8`{qNp0u;($w)Wl`r3r}a~b$|K0?u*!>4{Hz4w}IyaG~ozq zZ{QD(cI%z5L4uC!RSsN8!!HT3j73c@qIEkDb!tWY?#^G}iqXb@)?;eub)Le;!3ifO zZfx{_@NoZ~SLptOkTJHkW{&=NmdfLF?K4+&GgU=&6jyawz)`XTr;1urgV|WjcF0Ap z;w(N!M?^c8ak0_6pAtlBKHa@`;pu?BqS~-kwJVi~iK$(c0W)FP5Om(R5-7S6cyTo> zAMKEv{hMEuqge3JtCG#H)7|+RSF+I-RTLfM^r*anAa-@2lnkH@tTL5M3)^8}I4ay} z$8+zr$`?ek?JQ=OuUm<;DlO~8(@zCP$+?PlrqP-&^)6K7H769^$i4~|nO`pKDw>?( z=C`SXg^`1+`7Y+bi0k)yrT9;%5;Q-VND6L)5unIT{StN22Q423i$euPYuzR#@NMU9 zMP+w43o^V4$hQ#Jn(@ER|1C|HT7)+LH$IK|o`CoN4M=E-IbD1?4GD%7$MaHXgUAB zT4?KW@nUCW<1Y=(L*|AbHt6xJ=L+`@I~PdnJzZ&zsca4r=yBKirum}Y!>aEqDS+lQ zSWT2ItpJU%Jw`%^j=QMr{O*d_I(-K7SH_B)KYVA&WtB{-_2|Ae>T@PD-U3(^>a=bm zC-xduEa1pwvG7fO81x3<;-CR?ly^PQ$hH}mu|z{6n40{@{28y9T9(TvS`;r<|IVQi zd%sT9m2WXQfBJ`H$pyC>&sW#)hDo`N#}|Go7`Vh4tkE5MaSR1$aWbS@0>vQ!39ta3 zBKvQIv4dxrPGZ*0i!Jkh;xHmY3M3tS>SuT zWIZsNob^5vul{o(qf&Y#zA8p_xbE^nYkQpQlbFOZa^W%SY~6^=d6mK~*RFOXFs5nr zD7PGk7|-QH8HTsbpaDCk0Dh$tmvBmQ$`KJjYAD78`PDH&ULDND^33Tn4gsZn9dQjW zx9~ZKqc42*--hH}m%N&Cz{Oe5HHE3D>w~Vf$@9-4$@{Ho;He+^pZU^!27a*xF4_3N z%@@aZLBopumA3QfG3NZwKs%c%abgn8-&{K$re3|(i>bjcrIfo1`9kcHa{-=irCWax zo6h{p;>P-B897L78i;})1lPej46SDqnOv-ldHMLZvNFGy1!7@JJz{~Zrw?iD+d4My zJN8ly0mBwCPX+h4Uk?I2{FFZ?%C*^bjZ^Z}0o&bk)xa&#PoZ^rTLD8})x<7jQ>_4% zZoi?^EJ2KgP93yaaT-e!@uzT^->ZIZ7QNZP9w1`m<4u08u_{lvfcULcV_x$hnbh$9 zZnT~b|4oa^bt)Vp7e$v1#LZ@B|M&U*`(^_C!}$he9Y|I8ddpbVuNnJdo)r66gXP}s zW#u#McoXmWd8~2c$J)EA<-&NEu-Kz_%Bm_zy=Xy0JEc=@OSyx!Y@1s&9TUp_X%|3uhK=%4cQ-LmvON+Sz<7ReoCm@X8`D|sY5XE zZF9V~G1y>EQ`JW8E(77%wu@C`4aff_|FoxU4-SU#$d^nvwQw zfyVjwDk&IfqVvIDk<(}zMAAn+12dgbTmwpgbMs z1?bt+Jk6s%jFcv1{Y4Q^_%8c-G{8cy^EO9iC5(98XUw!YK0aSvVb);ruG%3-_B$ng z!N>BU`l$wP1E%OtfY+7+Qj@G1TO8|KPM9i|)duFgUo_lh_&btXg&bt~kTOe6HnhZD z^>SSr;qB;5QR;IE zsj8OFFuuvK6 zB^!M`ccek0=oLojw#^v^g{=KvF>>D;$d2@4!>+3d@Snd?)i}OxMR+Tj+S{bQi4ZLh z=XiV@TrD%0vU^PqWD0|pFGm>wtX&!p zU8e>UsrPj&4PZa2kAtZK9@S$*#7V)-kQ+dS97{_+WjeeyZbX47a7a>aoG zQtUi-Da%h>*+N*IV?}A7Fr22wqCre2UAODC2F;j~*+)kkkNGV@rc$_DQ&-`ZDao)M zeV3HThWYoewx$dtzZ=p6Q3Fafr#)6|hEd49=jUs#pFmC@p$?5+3BN{;YTpU^J4%_2 z>$%6g|;E8+no355lHE zN%Yd@4v5WUj7J_90U zug(W>V}w4gU|mhM>r_I@y<6A4TIub^U~YYjj+h&`+v4!pYRS z15Aslc(yHe;?BEHhyc8`xMkds7ENz_h;dvn8r6r8~N^WC`NMi z_@+Tv#DVMa*N;0hE*ctlygzcySXPKIWnr<2N4k9u8=pYTYD{Z+6$bpRm3xW+jO%Bl|kfWXv}l zJ0Wr|G>b0IA2wT1Of!4ZO!@R<1hJ^oeI?T$U($Vma1 za8xT~2B!83AeAX^RqKB?{ft;aUxAma`%WI7&6MfW<`;u*WPnkmz&qaHrcFN#vkA?{ zwO~?onf<5d;Z^XMY$@r1d(v}rd8LNS)pcGi6X7(#_3@+E?qk>$$mvCIY!c!q;_%rJ zj>JAK;o4b?3j#FeyA+<~nO;b}zb>4CI1-B1&byMmCzc0@WWz^d(6yQx*YlxiB2dBp zjZ))8+?e*9^ad|=AL;~N)yE_C7I*oYA1!txJd7ZWux*fx!)xz74pZ;T-7#QDsvb3{ z3Du}-4d8rJ**l&G2j$>7HY z;g_@dOzcLEdRRz6kc7?r_McgS1)tNbfj64*Eolk_e(e3e@x*M_tJs@8si@9as}_y+ z7uR?$hF!XydNhTS{JK_&&{q|i47zr zRZs!Tah|=$1An*r1?1>_>B)B0PZh}iwQbL<`LvIUAI-eOH6qBU{RK6)-G1ePU#Bg+ z9%@Zb7U&%OdG=F$%g)hRnmcwg&J14eyH#j2;KPf;wT*PB9QqVfYIydmIb@}=RK4SC z#=59}B^Pkw(|?tZqZD>OOvVe(f3I5(L_aOR#0{o1_ZyX1(hZ~3uvd_5iZAmhnO2P% z`f;|qffQ64Ph)8HsvYyhxdM~!8-R}D+op1F|NBcL5-OQ0h_*E-gS&;x0bEza^pALQ zdQIdUmkyz7{Slg&!E z>Q`|-(uZ&Kc{3|KKHx9h@ic8cHY+ak<0)~o8Z3rIE+MUt%nsn;wS}%`dlId^7vi&s z+Dx-mvP@CpP`%vV^lW95MUp`3}FWZ!JA)88LN5t%f`***V&~* zOqqZ-ic&KS^bOwbbAf$RAD;9^kn%YBwBx9zM9T;Z1$wsJaZgud-dPOgbn?Q16@+~v zEfOR+C>i*Kr--sR6qHmzcu^rw51Fsq4JonujXI;#Ij0LiMoJeVgp$w%P2CuRX*sQ` zd9CPXgX&8hK)V<&w@eq7)_q;<#a5uQd!cSa7ecIN`zG(3Giwcv%l+^TVER(eH6f_< zU0h~$K4qU8t&=cZyxm>Ku5`!?{EUm`EZyGPLo;GRcAsv)inu-A!h}Q>je6@~FsN-@ zePH1a(SsHK(V1)Dd1F`!QwJmNURZKu;Y;N0@5D<^eX%s&BSqdVh1K)xtI1Z45;%t` z78B^&pymt|2%vqQeP_~j?y$NNIR|wofu>_HRK(HlZ99w4SV((j2zErI$W}W7B17*f zM~`e*^SS>mGT1$3s#tblVO2@^VbLmzjDli^3Q(iHTiqgW9rKv-KXuK05%lA<0}HFb zpxQ$3+)>YoOvF5^)juFwAPN7y3GJMH1XBQ|z$Z!36zXx2Zj9*<8JXdWk3JI-%z6VP^$10uJyNq;vEQ#d< za>1+c%N0m4gnT6_~!Fo%_UYS@)tP#L#7YdcQ5 z3jBDa8{89k((YJ8m3231{rpxmAk3*}z62QQApG&z6w0@_@vkTu3AE;Ogw^7>kz?v3 zaq5W)n%KC4)&w1eKl%Ozc+1#8>lS+~ngU0~c7k@rThVH5_GSYvo;?L@a zN*~HZ`O9nLus>I?mg5CLBG8la=ovqhY2lFfj7+>rvh^{1C4GH2BSEc)#ZhWLy-o+j z$L!l?kiMvSFU7?}y#?7WEYS-oU^3A*4WnlO7rn1?ZQ=+gDV})uRpy7$5YLyPKKkMH zUiMS<(=0+&O>RvQCRM;37-BYN+6hf3LM2oR6_B>Ajw$gMC*l+TS5UY-}a@3u2z z#xY02S$1E_xImQwq`Zqy=~u!kR&q2!Kx6@p|Fs62{kv34R?nMQ``slzSYhg|3Xq}(e*)sR&Dd)BiLWx_cL_NeV z1_{A`GVI%6B9I>>P1I60rmucT{V*c-;QeaB@NSLB-onDd#%7fLv~FdS4IEiS#2WE6 zMzdt2V4k*pMiNnBTC`D1K}PdE-DfvJ9+*8rvET5 ziU2n@9on3cQjSv($esowZsK3dF1OelGUBN0w?+b4&UE#Q@todA{8Z~5h&EA)9QUd6 zTa*Jcrrw?eXOa6C?pE9weXjuhEzIoEC_pj4ykyQ5l*QeO!iYspBHiz!iA{~G%dqxY z+Y!TsBCw3-6=v%|Rw{_5wumHQIl%ChnHbR$C|UXuU+_b+@84jhvW>y{o&#wTfj-Py z00W_{6T#M@p@|lGD~t_lT}L1%IvVx#`N-69=@D8kqGX0;l%v}pysA#bj2#gTuG{94 zs+-cvx)K{XmITU2)?e+e@GL0lF8~ZCVgi7I;A)^Y2)e!?2~79y-aK-^etF1mPv)g@ z@i%RhU~Bg4_x=&McWk_G%=ztX7p;E5boA*o9ZM3N_IhKM*e@SKtoYA_HM^K> zWL0mBj-!azuk_Nozza};v#y)rX4oP)%k^OVLftLhtyN3P7FZbo`40+w;rR9fuyv>Z zrxnz+tzs`yBI+NQxZx5u4+HCjn_)z4dH_c9BqerGo%z#RW#CL3)d1Hotb=zWTbF4VrBB##0_yd3Op3 z@uKFMdtHVBx8>9qI{AE`$WkT!JQIa$T%qfHE$uIq`Re@fd%fD7x86Cqyv+KURV?(c zGsX9N;8?a2^C5o2QQe$(Uq8?pU1q3OLna!kdU|N)*@;997W=dmeGSo1O@5lZaUiXs zvehKXhadFi%6mx-`p^eNm&!!4E6Np;d^6xRH8VA|)MF1I%{!#lpiL%Hmc{E_pX>S& z)oiF23@5!hdzlx&VE}XW21%mtY!%ha@5V>MU*fgqGd6?OiasZZ#v#=$OM@^ zZclCxY#jQ6*A=EwgZ+m~rK!!vV6>HBQ17%8mto7Xt?2`Kn&I#&u-6{7_gJ-Y%MTou z>!ec{+#(k@hM0&SnBZ%GB_U1Tt_43w@$MDDoL>NktzUi#SL*`aS1Hlx^IsXH(%K_! z-*P!V*$%j}ap4aOO|_3U=`a0h!cEYmRouwfj5<7kHL3kf%QODePNn;oD;jJTtu41B z_f}9abzAdCfksA)Xb_sSCd<$rkVDQP2U5p%T&A0GXqs8}A1UM#t54>N*s=Oe-$aAL z(oj&UY81@X%32{Q#?L8-_I9;JKY^3nTgRka8!Srk&H-fr&?Gk({#Uzbr9cbJRyF=x zma}Y3uRK*73ZMnBok<`jWH{&eE3CVV{pzXw;Ta%MKTuX14__of7hQkZ1LBsYE&)^w*mh!>dkgt4i3MZ$yG1tpH>lL z3e6=GOp4SWA^8O}GIBqs4F3J6E^V`mo@yIuFr^Q0!?Wc2CAtl^56%|KUl5qhYPq|+&C6)7^+FWbvd|OSV%6rZ!7bB5u~S9BqxQ` z6~MYkSiMAWPtRbgwp;rF8C1jatnzPd$Li2$o6=5vHu^iDPeQK0u3uSm9-#tWmbw2~ zeGK)|k$3Pg2TtV_>bUjY4VzzqYM%34i=XLP+~pGj*pxG<>{xX7TSqk{M0R>?Z=74b zzP9o&qI{xoz7e;hq^M_(bA??5I8@1Dns4Jtgxo2!-3F_NT`33$j%UL#udj;@l2tC& zeRr;URr(rPjiJb7C|kJk%JZypQ(P|{ncZ@Kx~hEmPr-)GMhXMi@|Y46dTsQF*B6Vk zz?q##JzV#;3Q`F)oSI)=t8$i?HQKTfRf`=Urp0e5QCyXrt1v3eEhV{ZbGats0MkQC zxgi=_(I_`QkpGHXiBwQig#lxUkU>a@;2~`Mj3GP z!Zwi$a{@tdNP~5=>iAR=e*eLdm%;@rv*MndiWC5T#(yO)=GE}Sotoo$iB04+RKj>E zHsXhkjUD#vmR!SB+G3-sh1v%s(OwX}V(3oa%W|Fi?K&;4P7|9@7eF0!VMDrvkI?pm zw8_2%Gua+s2`{y(>WlmB$uKwNDA4flo}ud1zQ$yZpX>^xMbl$>CHxEjMb&`XzIvW?MJ1qK2F6w%>^SB?N=~dv6t!7B z#n2BNl9{Qm1T9p|lEbNs;Z*o&c&$|9S6Mi64Icy|jsQ`&Sk<@4Vwwa)V9eC`ki5-f z-WG8_UvEPmQfhDFJV=R`&l`wK>z%S=$!n_m(dT4FYErrqM~tMT8Y_2A4T+HQSXf7k zuZZ9Tk1Q1FnEz0xav*aIGa+zeEojWkTSFjLF|T=^^G+uV=I0$rqVSpFgg2{k2DyL? zn|p@lRA+EtG(WBY=LwYwEKTus3-{>qHTbhI+{K<;C>c-X9bJ=Pemajq`9<&fJubZCRdLR4U~k`3rh{`?(ZOxK*W%oD%S)IxsWglv zCmPhHPYC{7j_*{!OlNC1Y}4saAugxVf3*+IlYmJXSYmKVj2Pe zPfo-@SF{(IFj0OvE_>$_+*`Ga3-Rr9qhg->cp1rf6!>>USqBjwoRV1<6T&nyvZ=2B z6P(W%tsqC%R6`$zr^^h3pZ3y}k&}^uf`IB*9slF;Sbv>zdj?+kxY?h|j2S&_?e^Y| zkVK=-3r|k37Z~}(?``qboq%+W#u=7yUAP)Yqm>zORCGLh`#CV_2BrU}L;P7FXH@f^ z?3lLl1UY3u2<{!QKe;w&sJBhG$RE7-)k+@Ln#?6k=8<_|5$~-b4PKLt)F5 zl_%+3(!w-e4-t8-Kb!TLKtQG;0YOzS)Y=%i^3dmOmPWHKRS-`b(x{HUh5LGN+{{?c zfNse8kQlaa8pk=oU1uG1zEuI3;zi-SjoZ+C!I$Xt@AVj5luVhJgphBDy8kUs4!uU$ z|K!q-36iVdZ^AT}dnT865&J(az~J5l0B(DP0)mS&PSw5->VR`x09p@q(eMZ4HhU<- zGyItq$PmdKtfjjm?C19a9bKOfbz<`Tq2#)Yggae_&B5=&RoJx&^i;F|Tx1fIV`rbs zpYSoru5l>lz`qyP|Fw^kYnq)d(CZ=_8=yhQMb=qqk!Qx~SokZOeW6gSxT?j2ai6>UV;Q%Az>DOLm_8(uC3dvBn|r&5=vU!8of-q$@QB)D zHbqyZMa6;+3-mq-!%zV}h|MMwgn;c5(#_cpORbLX+bjDTIQIP6@{l`3gcWJ0%hwD6 zb~rHX+k&MmNhKTNgI3LhiCse}qWCF&;5-Xat31(>iGGq787%(a3(y8TL_E;9WPB^Z zM`d*Eiew)IGAr;3TttcxpR<=u2C<@0Zm_)ljfLiZn-ybI;V_w*S}~M)1l=#1bY3V} zWvP0F=%sSC@73K>TGZr$wTL0nEXrQfLZ~eZOPCGRCdzN;0 ztEGR#O2!`%#P2g8>|q(PXh9$RqWgI$Ca9Wms_OTodzGKQOS2HIzUoczD((XwW0hEx z-c*v2o49wG7lcf4{x5ap_X<0ImA-t+JmU$3<-aGJu6;PzXYr)c6fvNC;?E@P@!rxkOoUIX)I^YG6&go<^zs3ouM+a3YDAl==A7`1e%*0 zJd$vq$iIEappnHd1JMoNK3ofa1?|5}ZbgRpbV$aL;o2(6wi7pS#++#o;aFg5*tl_9 zIAEi+0vH9n-P)C+0-l!=Al5h~th0`3j!Q-$%-e*Vdbm? z%aQYlX4AChej9O-mYRm>f0bxRVL)Ll?ev?`i?_O^oE#1$971n`P(<^u=nl25P+&qf z>BMZ|Pr~`#$CR@yyj;qxlw;^G@4(Xe62er+N!1;*xYBLanx9eOl!8NG21Sjmicm}9 zx20=zgR8%5Xf^Ef&E(t_j?uviGYuolBlC=-@1O;#I6WOM)>AC31e{-d~n z05Rlj@_Apn?5mzjN&%n`KKd(@vcqtdlr*jscxZ-2K!PNk+5oJ#EA>v<-Uu+Wpd;I( zT^z4&Oznk|D+4TI)?vyYROpA&<)sG0MPzvTrm-e!ZJ zjkZmDXyf-9VoW*eB2xjC<)&1+Eed~tSf1TxJo8S!>tIjnBlPO)-x4P>-1%@_26I)0 zE$kF7`s%pClHwc+W)-->7h)I=s0~5%solf;zBBM&fCiH$6utEmHe~{lt!xL2xtTB| zca9#aT77wllYkc`1MtN9sdDVNT^`Y*QME?xiD_@9_y7DUTUjEe+OKe*>t}bKh&-gT zLCB}Ap@UjcTm~~-*+T_5K8gD{idO`VtZ*1^x#rxG2J!(MC?F($ioijV0)7hp#e5s1 z=R&MerCkdIWj`BgYZd@nAwc!VqC;1(2w?9i)rE9_iWKPQ5O{ufR6l(F>+bUQKBii2 zF&Aa;%PuEi?Vu2LZ#enu(VAu4PJd7OqRA z4dF?}r*964zWmR+_oF#zi)ER~W-OSg!*QcKG9%333d2B2F|_Jrxqg6Lh~T0qGjXYP zakm}k#j3_k@P8CM*WO$*>j*l&t=HJ(mDpUlCLh2HV}h!97?A-F@yohe!r46Y8e%5f z`sq2io7E_OhiMFi$tSY`F)FmE~Su64Oo0&#e!>yRf=S>wy z;JSSYviZkF>7w6Pub8@tNcche2)*GjxxnNuN>t>;SE>;i3oBqQ^ACZd9F8w)@Mh^I z)k$F$*ves|%~6Xy1FG|0ggo@Z@_6K~G7uh_piv8B)k{ zvOsN0t2iNrUqV7XMxo4`oP#EDao>*XE1(`>%exoZ%KQv}Hq}|;UhR>`A~J>Z$G(xc zFkjW_dP1{4&&nS<8h&rPW7Au%%at7Ro}6~O5*|^Ux|LrMMFYfTQQalji7lxW>_J6m zGa$6uU%<(=|F`+eYS9am8~qcDSFH5@m5=6X;hD7kxFfKy^?m=cv4jK#xg4&J|1M0& z@~tteT&BjP$uFdY=p-HE=N=|bw!GFDPT@$nS4Nhs=i!1?oez4nVey!jK_VI^Y4_XO z7N0;8Zat=y0O93(R!vt{fNHTF+=qQO@g=C!z{rfoJ{RQw>wZcLf(kU(R2SOzR@;C) zi;4u+aw+00;~3r2{G~FHLzeZPk>$J6Ka*R!KTupwI);$H7CR{a$$^1>$N{bF=c4kI zp_2Q^8cohCfH!&?$o6YK(v;Tk>TpW8Z47z z(jy+BQfJUD5(EDJlAb>LEh&Jj>gx-&mD_a_H)Dq?d)KI%;MIpIX|t0%fU<+mz@q30 z!E9uu@Q()n?a8_%w920)TCpwDQkE+w`gZ021m;^44VhjX4|faUqlbTx7lm-&{XKfR z47dbs#n!{Wp@gL!5fugbDZ&d!qx#1_{@#RVLXe9K@Zv0M5HM7Q-dDt#oW3{)@2;7pQwd@PiM)@rB7;$D%z_grpWo11yqV zvrcpC&R0x(l_Q1}Z?$no8h*(FKq1|EQ@p{>FpJVC@XrF=u(ilDzQCdiJvbcW~Q1upf16rzb?!Dqn$ zx^eeCXrGoHi$NH~9VOVK!Y>kwWIHA0BTV&dNm}(MwpdnBQ1C!t(AnD0&|uY2eDe#Z zTvmxK?ESdC7(wUg&rgi;s7FjGDG>jyvNtX*jL+b4#FMwsN4>PCo#HxCq4t3`@;gkW znB)Y_`?Qhhb~qxB$dc?%e@tTv18J(%n-fA5Bm~XOi>fEem}y*19sbah?$Bf|+`}v$ z@h2YsSY4{<5G^EUP@4h1+PAA8Gk8P_yrN?H@|~DZzMPu5-D_bNdzqw(aw#aACi45d zN%`|z+pxtOLq>N>OoJX=VemXLLy1Cr+^8+kN zY6A~0-r%#@cW3q_+7ECNGK|0{od5d4ve(r+t|`!q_(3&r0g=Avx1YjZPPt#7X9v4Z zt;&TUOBp|Yt_+gF8pXQMbV6XTv(~+`_wcXGTB}XRTFNXcQ=Ol2JKU2@vjPt}_@KU` zAov^#P)6A=BN}bKxd&w%mM6}0oag=H8n)&ib!*9#s>ia$kDp5363oqFkzUg|N8hc@ z3xn}!=u<9wjJs)cJXKPfzQkdP9lkx9FVDJR&+o;2yUP(zKWE7GqRmzW-8(3ev_c*l6-L~dBe)~(ZWO=*W1+@0w;)0kRBw4m{Mp( zgV3j6{uEyC4{xM!$b6@sDG}-aK9KTd;ka%3+s_@ipd8c4ePh*GCJ5%8k%`IuwE|q6wrX}HqIamxYz+Pm8 zv>Q`7K7rNQXX+JjD}&r|WK=wZMTqGs#1qxR*VDyOXol^%^ z?o!UwJM9zm{`~fTQ0{|ZxynCxUG64%tFh1db7}(7ZH($itU)g83_YP|MqUuSCpY}Q z>Y*WPj6cla(f~J5kcOlF=OTBmAflnJ^B_)nn!f2XabZj&D!jtF{qoq*B;raJFy!nU z>Wb=HxzH(wGnh7ZItv9Phnw?SU>IVeeMG}da%>LP7T1>-q6TzLiecsQ+~OQj{U zBf#_7m~e3qBZEbLsP8mX z8Y`hDQL$!z=nPSDs$3gE&Dmo+fL(1A84(ddrm+8xVzR#gwU$i+@4Ij!jo3boy%z>^ z=Yat@NN6ICjdJy>By6X;0yWO_#WOB~9|`T@tv;B3j>mM0u%?ZhgC84?w-M`G&v*=# z(7zSV%?-L?kH%Vav~LB-J|Gwv8RW(bT|01jdQ@fo>G1kHy$525q-c(92+LED+|7~zjZe$bV%X(Q%B@p_DbM{(+b>bXHIz*w?x@%Gw z2qI^%mizUdtA;^$oR?fo_0Cyp5vbJoi02_fpKmJX=1Skdt;7c%=vQ}Lhe(z$Dk74o zc;sKw$;jJ`HVH{b@OegAx0Rc3=abd$2`~-;W&`a%!zFOYEEk)-h5IjXrS5NFR)~Bz z?jVdCf#d1qcGYZO$?#m2sKWAB8Cbu^rLlQ7#789=j9O}$)ns`E$e!rq3j?Mp_jya- zC0ennrz0<~&k)HiHtW>vqi%dJNi6Y3Qki(c3+?}VPQD&Efn$ItY)=()(u@nAr4j!m z;;jE&l0?WqQWERn&%3%~9JYVre)?8wu=mxGu6r@UF&TI%FA%74tdwIxiS?&!EOVhf zq!3{G@;2qAIIQ|4`l%}Z)yU%yuk`tiIl-gMbdP*iKF{heKN7^KMS@3rqDHvTYc!0z?`Qy8#l3CapG8DlI7<_ z4DsNvt~+Tf&1e5svLt6aeQ#h?Zw0Sk-A7fuoZZo58GT$1=ZSJ$xXs9T;xc*ZbtOso z_4x03q4n_Zp~_+3n~-jRgkXnV+IFMT@EM|Eq;cq1^|WDPy``+W{Ho}Ep*$uLiK?e0 z)S)w-b5I)VPphoyGn6kpEYXj$TefE9W;;iu!Mut;CiAk&4U@J9Lfds~<|FtD@|5o) zSdM+P`d$ZVh&!lYtyDDUkjGUnjN4-L7^wURH!}WIXGrgRZ4oKdTVU)s{e#bS1$j#= zU8o@7Id;MrPibSIF*YCHVa$)gaS|#ru0y%pMTP$xefhax43x$ZmckWmLk&5ao~(9- z_<>ZJ7r3y=)}QWmV$pUer}Jpylf%NW0Xry3Q~Nr@Wkqv6?zGfDfhUI0{k513qw?`p(3w>!AUnU7@l56ywF~m(0qap1jUq1-e+KCIqpy z;AC{Hlhl;ab7OcIWqo~4O-;>r)*Wm+O=Z~*^1(Pa8z0Ew@QzH@@dgKeB6t)U6n$AD zSg4+n^P4t!mv-fLre4%SkJp>?=ou6{9B&ITPARviW5i=-3MCz%ANv!ze0|q{Px6Z) zs@`GQ2>sktQZ;50XCqlODTZoELb=s0u=Q6268$!rFtetM9&NP4SbYHZN19AkJPb8gag=l?cc{-uAr=dGTDzo4? zXP>19LwR*JD>#&gV{uZpYU!nE{-p377$lqgC%B~y5Bw^xTsNNVgzaHeZTcx1#^$1T zf-_~Tf8sOLsnsGBdeNn(xBWP)CTZ5_d1fZ&TwOWgwI1~lC$LO%5SET}5O(2P-1zN3 zy%Dq9i6p=o-1oYZe!zj2;@rjc{UMTY)*C!9^RC_e*Z0kQ`3&;amB+ySp}g-#F$va7%^pg~F4P7P>!J#O{hG&H!?$6}`!D<=d;wSANRO7nzb?{P?ZrV1 zLHYUlJbpKW9>WJ^Pp$^e=bQtw3OOYIihr>#>HwJC>s2%v!rxMLuIOH`iV$N%%|E>j ziUw8G9zuG)XL-|LpGcH!aG@n8c$=9B=<)h}if&Gu9~#ek%Jv*BRt2wmQky~{PV3~Q zNs5r8wP1w?MfQgQN^E0i*3NhcsI1=6I!2Lt7c zu`w}P+bJAVX019{{rMFq6Q`2N_n%tOlMLtV-ZRoJ2Osg#D-sA6tO`E&l?weK#mbI8Xr|On(<>qb5=X z5^bPT^lwPIIEjW|y|~*XrHJ~8=TiQD7wqoooL7FmJk8QWrQ#H;uQLNt_UdS^znpny zf|2R5;`j8`eEftjZfE&5rOpuU@tVhLt1VLm{Zb37oWvoaWIQ7Z5>xZjjyRXILeh<# z9I`b>9~VeXDqg1tBMct}3Subt+q4e)o1dEn^-7+JE9g;fuxqZTFus&%8>k+7;mM*N zm26puBmVYyiXV76%Bn@!3j#gK22BfR;yexxCWfJQA3i=4e4xc;7c;3ozt4)e)zZc9B12hcy@>b`!V5&oeIX4bkF;MCjyjNYETQ`vxaGRI8#ps! zeqpL=Y8V&8(F2ZN+bK2+he8h-#TKiJi!YvPAktWeU(!Bw{c+DrSc5U}YBD(184C6^ zG4LL)zGrvg6D%o-0U%auglo??k>d0D_W%$TU=B@W4qH!_$rim3tT!z8u+8x;Viv1o zD^^v`HbX$)|Cj(eiXuOId;3v1*!%L|J648zN1-&&<7E?L<4sRHRZnJBh7O)_LgM8b zlwjf(u&}T~J*V)~i0g(D${#NqY7_~3lZQ%7$wi^Y!}5CHcWXP8x`~vmSBK6+qt4m5 z6jx45>wZxHpXk1=EypVxFQwHT+wb3;B+S8r4#lant-;@4rJVd`O(vxBx8Bj${o+C) zLZ>Jh%#DHsN_Na73Zd2$)>W~!>DC+JVCh z@KK+#Ke3jTaUCB>VE;Ud?eT%=J~9;;Ab{o;7t?KN!*ok^R!bA?>i?QXggGuXdH^^& z0id?+cBww)<&Cj@8K6T1A_N^NhnyzU9WyBvD}-qJV|0u>6d6AIL;G?6z+`WXm_11p zADpw&wB{G^W;WOVDx#^1O%Z02f4LSy4_u#Zpxr3?Ii(JPXtm1uUu2Fcwl{xFIet@Q&0x_b}gt;DE$$TO$Qh+Lm`#?3J z`Y|}3OdBF?BYvHUGQJ6`5Y#R>xC>(>1|Pt1ZY!uPRpHNftTeL4(H|V<^s`PHie<2P zTCN!%8kEZ-Ge}K}$N=UYFX{0#VQ6QIm-Q-Q-S}yfW#qu$?_2 zSkqq%cnrz>p2@KH8nTAvKUXu0P@gEn&V4H5KO@>qiM6b{HphKXfPZ(4BkT|rrS7dF zw30q`?V;_+@Q~DzFJ@%rG~yeDsqYp!6}18ITQsz^Y-<>4YJRN3drwT9To3iqHG&&> z2W5%XkY$YurHf~hFsUm0M>#@wgv;ysRGs=O(<`Acrj2-4?R^? z@H>~4YU;FTMjYmPvpe2Y*@9E@j9DCP4dwY&Uz8+94;2djb?eHn)wa1=VQ|He^B@&QTs4^q zgSR3(a7`C*`l|7~haQ1)hOozI+cwPis_ZH2ma0-bb(kfX`sK@R`nUK0(EWFP-irsv z({jvxeHk08h3et^pbyPh710MV-oa5lO{!QFmsDM%7Typu6#sx_3d}X?d{IeVP~ifL zfwK5OF+lGiaJchTRy@Niu92?qKRww`)EQdKjwEa+qFj{;XFaN-6OC=}XUA5pVeMuX z=i5aC1I;FvEZ$$hY@yywm*dVBH(R+1pZPwIjuD|a`rd4{3$NrEaBF0M*7`mADJ=I- zzK_$H<}Ihku?mxtN+SVo1tgdKC{y%T;<*ggnu6qQOgzh~P7V$*@t34>#%@L&byH22 zG6tW+D}ZWyPxxUh@cf(#!#$Uccfh z&n?C9wem9Gl`u{31qz9WEgrv=M}ZS%wcbY!Da+KbvZ^gZ$@s&~ZwX|EpwY8MFI0-a z_vXuvIQT)j0nnDUi!7iVfcF73>^4IsS@>?^ARUGO0S z?)xi85w_jwERBJpB6`mr^v6(p>!QFxe*Oo7c#SmE zgwiMI*=i(UtmDqWXz1LE`hQq}Yo2B;XpG|0A%iKD-;~hTlnn*X*N4szYP7*4=IYi> zgi?`SLy6gpOj^$5Yo$C_e~bdSo`1WUS9=F2U+_gknb-TlxZYZ^MG7nV%;ZSp1+62i z0l@TFeDCL-cotJ}}RDrOqq##wHsggwf)>(L zv5STZW>nj87f46#tF;+w3e`*nFfZ@cg?y|c1DjG+#$0t!zLqcT7&d}L(-i8!+)VP3 z5}yzIn|ZJzBiD#YNn&z=bE+m{F`&k9ojBzx{=xL%U05O$-1tBN3T1z&R@SKKB}o?_ zHS>G8Ad>!Q`6`0=uc>qDbDw&$tOZh5b)@^{P<%+zyt}--yl#)tTc43L_TeNpH(Tx3I(QTJ@}$r`iWL6fO#|sulFwo&mx?&CpbOcUV7Nh zpN@c8KB!O*!reP;bj-8(yiRO6?SK)nq-X4Vl5~kq-rqgLE&5y<58=dF?x;xFbQk>D zR$b-%U3afcvNSU7rO6_+3o#Q&5*xlgvqsEg%8vk{n_&-B!8Z4>8CElamPzVrJ2kj- zQXrC21(ixAf^V>T*39pvAYg34OeNhnrxO2~r$G7*Rs`Run>Tno+%%q>+o2&-LP!J+D?EE9A8N1RY4CVthRS##5y@+F+3o1Dx}N zZ$0z4`HId1EN~9mjRM62Wpqq??f8YA)Ie<%x4tK5TAd}+h$w~XP)F?PuEuWixVa~bR zynrwaAe#yufPS8qc8}@;MpAh-5*b>5WmN=Xz)AMPOl*UBlN_EFFK~{TzaOkws6G_@ zLUA_G%0%~vhI=hnd^x_5(K;Ib0UKzx8va-Rl>Hyy+U;q3W%Va+uj#cjFc&je7-o2&qzdo>!(kNn3e(CKKp$T=&Um! z$|D|D6|eWwD_~(4vdE#M;TGQh(UFGc&B%nBh_0l2X3OZ)P}%XOi$&8?LECxmxGhv6 z!bNo}YvQb5)-ON1jq~t}Sdh8zLDp(T9eUgv^Yf*)GfY`CxlcvN-SOP(u(0|S-==B% z>^ni4NG64-F+F7{r#Q87G(hi?++*e1NqZtt!XFNltQkdJJldPgx6jEoKG0D40vy6M z*A76gPPna1JVKB-Y{liZVJGf(zeAThJ1R@=TRyntE7+CT_pt}t;OQ^{jqHPzPcLyH zxSEvEI^8pneB@oK>baojZ-#x_dR?D1q)!|Gxw~USlkz#=7xJ+W{ zb2cozN8$xKoR|$}WFbxEK#`A^p*HBSC z&GtY0M#W?%Bks11_q@|u3+jr+;Lf7}fVfaZKQ+x?CwDCH5q@NA(}&J7toCV#- zvaY#)2JozcO|4wV*`%F1uo&sJ{1EkE^`$gnU+sQTT+(Z%r4It$5d`1)h2eXBB1%uf ztvADj64zP(?rRh+W>ysTX5r=;Y0*8|0c@|TxC^zKIzl=Coj71K;gbIhrJ6G>9dNWb zHf>rWV2Fs0&h>F}BJc|$lDL~6J*^|3#6rBq@kz@iwbRJ}df^xQG=JhJ^ub#qj=axSz!&OJFaV6{ez;+^+ z5q$A!vq3HMM;e`K_b2#Gus&pp;?Gr6tJrnrV*(KgoEh9;u!w@Z8TESvS{TWvo6+DG z7rWZ9TQy~j=aL9k%KpyFym4E^-BFWqD1HIZt2~>H_UH=#JlxjEnJ?k$t0K@OAWSqx zBv``JyLU;$Afi^1E97iH^1{g`BZ=Tzha{EE*b7}s3_2>)y*ptXGWJY)o|U{Ti2ClW zo8iZ}+3AiMnjl=S-Yg?Eebc$R84yz$Ar- zlM_WMg71rIR{@ewei1Fge>hPi3zwjI+@1U-)i^;!vT_^Yin4yfky0_a6c8~_1F*|k zkBws(SFl3go=y$=nz+Uh1yC*nDJlDJX~PTALu_@8cQ%DS%1mcO?f-UFVdMicQT1I9 zA2GC?e?eWiY_aZ(3_tQ9G8r1{_nvpc9_-*8R)`>5c{OTmXh?!T z2@Ge0yAJL@L{xb@y&zGSE0O1VFaX()1}GT_FK3y{IaNXA~2^-1MpcW z=tZ92NIptgd?r4a`8LDh(YY%KG9@$pTo}SS+IvN+6m<~R`L}-kE-c_CI5^wi|KX~s zr9O8>Nmio;L#m9`YwboX+6PR$5-tl!g@mzQNy1>OVfEixDwYlA1tnc}E(?U8;yaS% z|BLAkPnRpoAe6UjgA-2mzHdtLpWnZ{{KOb3A?b%`d=&YeY!Gki_FgYh~?Hh=teI*O6(A4EtMpqLR5h>*-A@!A3wtcHd^__!aBCD%@~J)h2w5AV$#kFT$ux?5LI`@i0uluBTtrVbKD zSQM#axk%$^o2{ibXmGgZ75-<}`&(cLcB zx7XthB$>g2CAI^h6qlQHWXH!3%g1$p4<+wACF2=xvm8I{ckpimcdZ%1CCOX}0QK6MI3~ z4`#%B*5`m)c7ABW9PkNw9h}IFKWqxbt=jl+Bs2<&b*9PokL{B711Zq(8RJaeW#Tijjwd@;L4F5v*7L zAvDAv>Q*YUslx>#bEhPewgSjLZs*%_3UN}M9y({3tqMajr_%?X zyzlJ%OY7tbV<~jqqP>GWh1%_uf3k!OmH(wv)fJivJevYlm`D6Hl;)^ zCR*eURW$u*T4*JY;|qlx?J-z8Ew1E0=9lT*DL$RLl z?B)f1R8hD#)VFkcVxtgFmWRpHO$DMnNC}8=w0#_xyj8fCvC;6(P0V95Y^B_V1o5T?9E|{{E(WlD?6(vGy;D)UL!v zyzd!mI;9;>cFhOt9(a_9ve4&VBR=`bGK~3LB%^9O*9-ne2p0M25k8uG##BcDpKRm7 zlw#@ho2FX#nl5EaUB)0}H;*r|sFRr*ZELp*Y`6B!{61n=qe-2I$wB6D{vEKxlcOxd zTdyC2O_^FLy{q@#HFq|w+)GKI1PNi7bbHD6wuUviTN6W$fM~$yARTI%WLCwrU25Uv z9};^S_)i?G9q?8J3R<5HqCtgd<@YPe6!K>5E+mn~g`CzKcrC7wkpr}+e+s`SsH5p6 z=`1(vH(^mcn8~>lIOcf<#jgW-`teMrEX(&Z z$?@EgwC{vbK_2oSBcE>eODkO;fa`M2^c5vF7KPC)qrY6=F7J<%0X`|}H``trEI<{D zl)nWdQPmSW=zzFtjFa+vw)S38Kbf_bR5Rra(>@BqI9Xc5l}8go@DkrJ>fcHe1mNZv zOa&hCk*(?yw)d0gB-=a>50N4h&ARdG;U#j z+$9r|;2r3 z;I$aBxSNi`2^Ha+$DyH!OSaKi4DRfd)YNq^ATfrKva&7DntJ2=*^ZvS2;}jJPZJOTYZWX;7j3Jb)9(`77H4Aj@e!=fm-SG*^&%f9H{fF$^#!ULU;p1b&jA+Ak z21Xnxn=o!TzM{Hx6zlO`ZHF7;eAoVi^nxllr+w_sImxb8MY zf_aiy6SjigDPWvflNshA){b7XZ#~idJUa1Q#OBA1Bs-&-X8QWO1~t5&7<(ehzb3;; zGmpC#K*fQi_uM2_G#p8bJZkEI++2uAgm6FEVo%4EEApc>9fi>vc4$I}_uQaL+u9{zh z*Fr38tQ&FYZ9O*D6V27=->hr)U~NoFCMkl4L)j?e^6c)Py&<2_DoHAgcmu`f&u`~s zLiYVY?2FPKH*1;BKIa`#plBckemjTMUs4c>DBcDH27!V)+N*o{i{J{wC7WL5q#j{9QiRDFQYBV z;C`(RKdldn3_@@OHu+tTDng}Tkqk}h$XT@ue-FsX)ZFJ^D$VZmn?V4CDAK5+9^lUd+0nro+2Uo(B#Dp|wxYV|`iN@k>yYz9u`v5>Pxnq7_N2#zio#e8 zyplR!HScQ~T4{y@#P73(4)ou~sESWcX}l7LR(gg)G?2Qq5{pCSav}VH(@z4sMiq_> zfOQ&~F2yqS)F}CNN#IOEa*QFB_wUANIVcgxR-WaKzZoB<9I~*4r6WEA=)y!Z*w)yN zq~F!F9zFX0s=*wGE{{*{I2Ap8(u6wny$+a}j#0e9%8N1BQUgW1yYtLC@__Y5uk}_3 zJdK6|oO;UnE+d32OUGoVpErO?kg9pJ{Kg?y%19(8fR!%NX-jM3lFGk6A!M<;>{*zc zYWwNPK)2T`zLU1!xKq+z2+(=0&1apCf)eT6Z%YV~@wyT+o1GZ+8XrJ6fo4hm_udb@ z>e|})9gzz#$Z8*hB}2M`)+leMF*%8f`)T)bV7$O;bcN&@$hp2r`14jUYr~xA6wjB_;&^0_gb{&F;GaNagpD4#qWuxfhx!xIEtxfaBVh9|;-UXgNGSj-EI^he zQph}?wArlfQl%qr=;(XBCAPJ>4UXk2izkxpDkA27&9Qzhzz=aCFEI@^qMIZv*F6AA zQ$Qh5!EZ(f60cZ{c8cchTB#0OQ|TXsw{GF*A+Wh1M{2gPV`V%@(;>!*O;g&VjUr&52(?h~8t9Y1|E{YXWXp;@~)*4b0^oKF^HW7<5l~=3jSn-Ns z>=}5wjJ|`=O7vLjsP#V3AM6DKJXgk7JyB1Ewdp|ws?;a0U0a)-rsn1J<7<3*l)jGc zfYFQ8VJa(P>8QXM@0YFgAT9Jn@oB&EG1hlOEP*DbxP2t74)EDxf+$r)22OprsdlZ5 zzTC8C3{EFfWI)uy!rH>xQI>v*d#K1~`)n%imF=gHC<>Nmj+;GZ6!p$zd1d7^z; zJ50UWZd8ShCdi^j$Md{d2OeS+3kIL03eSxUOm@}6@@3M}JyJ{ecI5#VENZPYKi`7E zA!=&xllxk7ihAX3&x%JFVpj9=P;fGRi-HU;5UTkaUI;m49+D-OjNA#P$~PCP0+KP4 z!{!--bLZoZI7A5CE*rL?yKJ?Kq!e)LDv3C2Df>^4d7EGC8qCmQ9M0vlT^cz}!*OS5 z-g5w}>6ez9{6+|}YR<_J4cnoB+)zZ*ZI{-8LG+h*Fku`-_q*uoHSmyJ&kpNv?x*c1 zw)_ml?&x(Eu{bO8COaREvu=e4o#t_cF|G$1v1 z`-ffmf@zjtCf5VS4oBGX`YVRb?j7e8X$_<8u)}c5>r8=hD;8hmuyD<>Pl(DNV%3J? zLKF#{cS%w@AKY{31+$YR1C>=ryS&4{Xa9}!-p_{CjHs81kDlb_gHP~m8*3^5a0>oD z0|Wb2TI;R?qU^unZca1@Ytk(jE|a>B_0_v6gk{eR5_S4mrZeH>O=RROgl%ug=!w0Y z9dxA>w3+yN^!FmPq5~R%#oVk#sNe{veBl9EjK}diV0HQ5R0d}7pJ9}qD!|%>bDh00 z)m0a5z@*5VeC;Vj1{^g#l4dz6h*Je`s6XeEkY1kxdx}YCQ&CeWk7-=BG6K1rTRkRY$uwDyyXqwV<_*bz9UFp??8S_f zD^CnvvSRH`UmuoyVSN&8HB$Ry;C;00#BdOU-IsTq@yRD%R!Zl1zp9Y;&*qq&(>LF7 z_a#g^^Y^S0DxB7i7J7#XyFR*%NqP8B=~$F%mV-5*ZtiTXzru(P=!(myTNzYU|4CR*Doonz!}sGo^`{hiV^ zCcL>b&Guilk4=i%`hl0gPW*K@UFxnf9>mp|Z(Pi8ke{IXW-AH!S^;26n(t)|4(2fK zmT74KsWVmbinJx=@%x&$C!v@2T|m@W_SR+rCxZ}!HLC9d#v|Wj7i3S{hlP+rxcW&c zxdj=55N>pEN)?D#8EeIJ)5+1p-El{u@Mq`Ivzz1_Rwb+$%&gqxZyEjjUs1lsSG(j> z=I_ye`vUZ*3)_Ay(SxTrPrrY#pkm0h&pz3DP4@RhQf!P)z9SlmiiRcJ{(&m8!FtKQ zZmiOUO4jv+6(xu$=V|`moCuN59fEtFipkTOnCD>|I$|ayJ|M>}(fD;#Ol-<{_KX6x z&WHH<7k$^RxU?9wwyjbXeOX=u~z)~Oug)-b*2<%#kaz)IB)ZUE|ZS@J^KP7 zwDn9(LORaB3UPG%m>%H$up|RW0toWbIYn6S)pboMJbeSE6A4u_ ze!)ZSU@nXjYCooXUl=x0U_=nx6b{8m_OiP1C&zo@<**<%S5{;Y=GdH4h)PE zc%=;nC+%byg5-1kTVzG+_`~aGiYrgoFE(*;aWywFFE`=Oc9B%4W52niqmU5YLUV4k zRG{o$pPUU69#4QiQe;PdgRTL?2}4+W_>WZ{9q(IkLkIx3kxotbmPp!}`KVJf@AGgm zJ87o>PH_}yv{7HVJNuOhd7b@(>~;kTFHbZMrEzFvu`c->P!9zQWns_Y*MI5c+8(SU1PQDY#UgVu)HQb;SlSV^boqZ~qx_|Ca zIIm^C{gQnldmFUwmI8i$N`dN))1Ks=*&@W+C}fhd0l=cg<^<8QR$d4MNIdVrbzaAq zVeT-~M%Q6n&aKl6Fhu~@8r2=)xZGAB<``ikwNbj>=L4;J%Xo_!y29 zi0E7yYYs`k+-@Citfby-c6=wzUzgnIm7M=a0`!Zj=tK=inxPr9J-nX-i_`UCUv}Gv z);~4`ha>Md=XP4#3;v8L*08l=>bYmn&WyzQDTpjN$?Y=9@^o2cRFtdy*_UKkt3GZ0 zTWS&>tj@K^ktO4>>sjA5*kxJP_3AjguXc^&92|nGF%+HEV;x^~8g4Et=jb2hS>(*h zc&D6FT!=Rm_Qqq@iP4?>9tzY7Ff9*+HtkJJhIiL~&dy_`PFDSJVJbJ{> zk#T*qt&bl6y$J6sCs0jadH0k~PN9f>uls>ccf|WyoN5tzycmu2O8?yt`*x78Dv?Ol z3soga+XI++Uv-1}tXbrT4Kl<&o=0B!+sj@gj)U$pnlzTpNP7R-y_z7#2hlYkSd%Mw z_3!_LlkjU6Er4)N#f882lc94w?p!n~4X>`|$qO)gC7W^lOerRS;qFW$s_&+LP z;simUm*}R2f5Y^){-=P{pJnpJ@o9Xi1njHbkh>5>5!g(L&*Nm;UGt4qz;sqt3pNfT z2@Hf~AXV42&&cDmdcsXE`Kp4seV+RF`&IIpG6V)RzjKZDMT4(b=*|rP=p=h+chlzd zXP!V)Z${+Qdasdq#i&^lBZ>=4QCpJp{J5Z#5iNofDB!uFt}Ua{2j}NW9a@@6i-Tl@ zqbBNo;JT`35B-()yf`l-aww9Jqt$~FZ`m*G2VSvXa5HUFi^GXI0zt*%O8V3$DAQ74 zkTnA)JJ!F8cS^fdB^Tue;Z&i?sn@NDw3ch6#d<82QwE5pVO`kbLs;coJUPT zX!^@;V;siK^^IRIwNUCt65N(f8M6v1kam=j0dwpyK4_9^i-wr{r0WCX#Mi>REyJ`1Xm?Ywu%2 zlrpD^a3+RgKXf)U01Jt2z`)MBdidW*16`t|uwn%nd)Vp+PxgXwTkR$=bGvBU;^HE( zeID!ld-xkjIF+d7x}{4_|DihbP`BaK-KsUC!^6QuBXICvr~0(v zZNNu%@JQd^X-X6|Yuf$84F$8aV{9ba(1q9TApLB=L0Y>(>b`-7|ctIVZ3p)v^ ztcAJ`4L6>Nw2<}VXy@f-@w@hI;m7~x;%mt4gR|Mu%qMcw)MJU#_4&Ii)YX{|aY_=y z$F8sXR8(zA_kw`Yj1qC%g}=Yq??YrrCd_(m|K4nf@cjU)xr?2}+R7sXK!X}r#Ydd< zJgi(t0t@@q4mgyVag!m)r0L62tKW)ufbx_Ue&wI{6_xhbIUH!WY3iHn>x?tOL;;sD z!l~#drZ+)^1tNq0VT*QP6_)33m;wBs^-5%MHDHB&PNq^9V=WpM$i}ERPH+F$=f`K6PwN#XkcrlV+2hq{z}?v5?h+gM5GfS`F}T2C z03s_T3Lx0ZV`1IQ`O1_hLZ{$VrA6Qs1xApL>m(rM%ADFllH6H~gDzNNLL2o`?6+la z6!5|_!QP3IJ31=SNIb2uOS(rq*?KbC#MpsJyo{zGBIYK~<43?^PR<_G28=PSts@R| z0_@L}=*XIWM_YgXJYM@61;8!?B4g^xP1&?yW)Rt8xa;wLXU_8J`cF`8T0(wX$-#^C zrj9Opu$Q}&Qxx1lu0UhXQE0{Y?h^?PlEUO;UPwv#muub9X&K3n*n(fS4WrKVt54M@zpJirbnsuyLT0#~Z>%`ww%RDuG-k^Ad9yM&Ao^Fqin_M3s zExo%x`B#(4eACtScy|>7n8}ns#rS;ui1)^WLjsZ(M7A6XJS$! z1z=zZ;@lgbG(pW;a-tV;-2{9=oSQEwL=iV1rIS7OfqUrY<`yactkuns!gRK1z-_JV z_ou&&&N1hzo?O~d`KOUDD!R1Uf>I2xHc7NP*~j@S;Hc~}sda)VS@VuwS}U{x(=|q- z1s1d4B2B;4eIqb$e20}?acDbi?FNXkPZetwk&4m=!SWc;QII4|V^wKB%pl$ z+*jh)n`M&wW=gZgYVq^dx=YQ0UMFt6-`oUGZVepaHCBUx1nwtUJm49u{wYg{&8#UN+M z%*bd3I1sI?(pj@LK+0HbObh_%w}V1FTwQ_P*K~%~R>nPHgmAPKuO+C=Sss&fbz<2v zoMtdq>{@UM#l`(m1>$@?L*mQF$47r-htTP?=#-+%LRKjz3i;u2$qBa>aWeCPqdv>M z{CNwu*f@D^)%&x$TK8i)`A5nh+l~hFo_7CMEib#ScPK@-MM^I3 zP3SGVLYMxSnk@rM<`x_C`OFtB2kdxSwR+n248J?>3m+k2U+3by9Uky|5@O=yZ%Y>Uy|a5cFV61n*7b`vjWE@w?=uz;x7}DdZC>}xDeE0Qp}1e$ znAxyF2?>w8FcQ#ur+?elmawHItjZuu-0N;~a8NVRDTn~`gFLc9!Gvha*A}xTpa@Zj zB4KjA+Ik{()@@ESmi&l?oAq^{Ox_*vI@9z2d;pUln8Vy{BqR{M~?lMsu(SF*#pH^;B z7WF`aiBi-p(8Ipt$^n$2kXxW$z1l8WGR0bl|4N8n{)P-xbOOF`#Ai8m0cBB_Gp!CG zWk(6+jTKL0tNX#g`%3@5LmJ>!LYZc>jEv_o~FhhnJ@lZTm5@= zPS>8TJqkt2dD!bl(?UZPJ4mJ!v0r}*#sZ!7t=+9mX8CKaWq0u38&Ur4l<>S%emO|jKy|MM5X9l% z#Y0SY3gwyVb;VCzbIAF3-su?&R2EW>;t6(iy6kQul{vfTc{`7ZI(n3$t&|73RQjE8 zGq%!9;UA)J_EJx?=+xGMTtO#op!&OAb#uXFA(Y6~vI7gbs$He?u z{$XIf=Z3xk$cTU|1=UL^&RL7)Ka~Oqtxc4_kkQ7Jg&*@<*&8b&I!*@jXgrkwk}tcK_NP?O#N;ru6x-vtOKJ%a`GMhUV*+ z;&>C!f!ZTJhM58LK<|PC1>wPuCg6(lt>Iax+8Gr`DaAwYLFgKmqXa_)MTZLvqUzAt zeUY8#y^8*&fu^#n(HP770g;P>YNgpd+P~z0zHE=-w6qj(SbsK7IUD7fc-oT@&sS)5 z6>au@97p@OK>M59)q?)GMq& zCqE^fdfdB~LR=txsm^)YS%tOt?nu6z-rnUGa=D5T$vA?JpNQhbv1Hd`nJ$_a!)y=%~npa6Q;WOS?uf1Z+o8E42Qf~jlF=C(W@0vbY+XAA~k*Qo|& zRh>R_k>!uqKx!6b>UgZuJ6vGj0^X@7ytRX)2LZ^x0YuhKTs49t-$KwB>=6vWia-sVJTaOHjP!Mq&@VID zR8gdEgS2YF*+MSN6PF4p?B}sud+Fs|3%*yI*vyLGeLM<8o*hNG4q1O~2d`O|M-u7b zS;u7)4SFTsWn=J&vyL%czgFOBF^Yar@6=CZ4vR+dHdo6HP1UV~b`pto2RDpwC>1ZB zkeCY10fl@_TRZ%^+EQo!+xwcteNuy|lNqa+W+Ip4CCDO8KnMG-@xhcRqlqgl2P*t( zwI}89l4XmtwxrSC)LctrSUWTJi_c@M??&FFw{t}A$n(_qfq2{^*!P7}mHX+L z63C&nQ=MSJ7o-2R3GHgf3io$d5Afe7o)G<(xRsRKsYfm)h`Aqc@KGAl`{7pb4RV7` zVfrTUZ3OP=-uEMhuc(9Y02qr~q&l6Enrvcyg0s+lJjCSh z=o_&wcd?fub`83M8TN1g`>*SCZl#6pHpLCbMBtQY>)a;(i>Sz)fbc%m$_(Dku2z|If_B9p!N2-!Rgj}E zo``%~(3FV5bFP!T53`$*+NFbYz7=k@{$virV&Up1G4#R*#gNx_Xl-qbnH4y@lmGKe z_zewtTR;rl?NpVI0vI3|HEJ7evTjk)IHT~S#D{R1`{YInudg8A3}TR>LB$%8m4<~; zjl{d%MB2okTT~M>rvQxSD z?8OP)#1Yz^(Vz8-vK$@`!mHC*W=jcJ)Tm%iTx^Kd4Gb6bc@m&??h!?ref2;#<}rKX z!{mN>#w3!6ynsR{W@=b5a+$f}*Kg3$K+7<3Ne*1%-sE3P5E^&`o%r*Ke_9jJF3eMr zA&jE-Xv9HE-rZ>l31ndjv#=OvJ9Q5r-pVFl6LWvABgrPd?mdivT8BUnBZv&JA){wd z`FCt?n2=s;!Ew91oq_h}x5mbH-ebQxQ%+X|*@H@$3#EXWt&=TO>p4I{Su?q_A2QNJe<7> z$+c8YLu8{#KMYTg&6)$*1y3c+bSkU|pHjAm45q!DoO%+ouynX8QS1kqns9hAL5v$2 z7OYeL>D@fdbX*^$~^{WL^^{&_I=B;P>hLYEKVm4ipQX+ z(>Kf5fp#6&(2I?#wDB$l7}{cO!QPFBccWQK>@g>J`FQ zim9cTnhn{}0Dg(J4=OsBtbh~KQYRT6q#7+nQ_Z&6<@~rz#$_S6_Fj*~!Lnff3%XMHJ2jd#Y4p6|C;_ zAT-Th**@Dyny|43Q)Kbp9G}|UHw!E1MhS)@zr7!zG(`0i^~|13K?c+}|B()-G!+l@ zVvVx>XIdZ@=0h9cBC|qa`ZTQ7E@7OjK5`)fo5S?o(nLtyOQ-msTD58x{Y3g~chJ;Q zYH7w!+_bvNXyN0IzJa%k&>w!BU; zY~>U8G)DjdyCHi_O}g7SAT8|ssN9~QGrIC-Vh4&z(_ZCX*~YERS5w0+-Fw+{qI@(U z{@s4RGR33+y#Is#xIz~>!r=}lBuHLXVTm{jK4u!`w?3(PQ{RAwe#Pam2RZ`p48?G1DHHTgT?s~$*6S1Jn^AHofu?vc3^ox; zZ8uWNX1LMYgjRU+DL*yCxs;{|vt?|jc@6rk-@ozt@v|hk)Pyrb=_VSw^h?&CyaH$t z0q*b3PxszY4a$FKXJ?z8`nP)}EsvFI`L1k?8Mh#U!*$pl6j?4}V$l~syV8dHQsqg=o(AT4Y| zQ2&JKe7-V>e1Q;V2TkknKm(z|s$c0pyar8zH_feU?a0@Y>jl2~1c0$REBih@qwEH} z9%=<0`y()Q_`C%HQE?64hl71slm<{ZEqjPTvjd^_CdLdHWWTR=2sM1MzJ)&+_UwG> z#yTBpI0vYgQ{NQzTV0<6am5HyRKhh2>11`9KVz3{?xt>h+#k5^1%_om-wG+f9&b-! zSiZJZu zX^(tCZkLGTwruldqlD!Vy#>8&c0iLBHideB{2}JgEFwiGjma7DrDA-=sI+mhJeXf- zyy2cJ=ThvbPDaqrACl+~4I3`qOQ|NJRQhjue1L4y6E+W6R`|-xjr1aOpz?IVe=plC zNsO^ve{?Hzp0;t~o$dg}hf+6}7Dd-j&&Y2mfNMVd{EQeuCX?gEeM4cx+jdX^l1=yq zxJ>6N-XV(6g|#0r-EQk5squMDA3myLhZhtCf zn833OpOhT^?Ep-dMxq<@mokEv#>jp0&sMsnQd!J#Y7^lt+9M{f|I^=k+WcLgSVjMB zdEG0R$+HAj>rH^SyHn_wQpXDPCCv{2JFpO*?20UlA0xlQ3{5{Eh&f4;!nnbN*a_IL z``sv3%T!on4Cy_bcSj-+Ljximkm+{A!>g2JgWSJP=^+=4=`q1<93ZddK2KaW_NE3( zmvkd$@3i%a1&p+Yjyr1oXRx!s(POS|TZL@}k;0_e1K{u6%H!v|IuOj)rn4y~QCCL? zym@yu1;1us%^$i$@7|aEcUU0{oDMtvdbtGOzEfZCxQz754RQrYskHraQUzdh+P^PJ&BKSm#Oa`d;GfGSIc+b$@{=FuLB(fgkQgZ&+8k?G3OVOn4kTEG=jf6aKa+8|>VA;$EgA~IuUDma81z+ZvV zUMWglBl&7y+MuB}X=3sFk1OFI`-52~W_9q>dhNEy=lWI1{w;x^uy6{u$0VVsmcRRO z+wt_fr-qD1hYk^O-*RqnzyV+9+4G}r4AE)K!jaEr7n60S_XZOn!cNj5xR`jvbJ6)L z>|0&|S94VUHcZV{e|gE`dE{>He{w+8qClP#wv+qsZtB+8O9~Jytz?B<*lvI=$0Ffy zPK*${0xj$>H!xWT0P^=a>3E0@Z*`Kt7tS#z<@m_*i!#u86f|2B@xHQBFQIG6PFo5) zQ$)GR7sEJwXWn+lWsPB{9Za@2{F%Tp-h>nK>c7^t!u%ngJ=G^J`I=NHY*Nx7<}7V*GicPyZ*REqL2#A|V06eB@hYY2M3 zHR|eHmp)nlF{~6hHTYA(E(0=fkG|GNzS>4qKfw@PJ51BT&t7RYk^**idwsh3cQq$L zc=n$o+4IH`gZKAZqEclNx1RWwF?gvuJ95z54c_&K8Jk2YC@2&pT339SaDSX#V-WJN zU`h|~jpJy$B9OZ~{7kDa3VD0pU~1u;CHW~gvPrtee-ie}j%vPNi&AK|ed9Jyj?pL8 zmq3*bSzWdw${k8}%4ZTq-S9l+`2Sh}&uXpz++I`AF_fCMUfb!6B|5*>2_Z{_dZ8fE)p0AFg zWCrl2UM>vb3Qr0Axkd3-M4m%SM!>sLH^sM?axlsR%0Kbl?&v<||EyL6)tN$eWTDRHQxv?at1(c%iqfo*$(>k}Pzi7EQ$MNvVuce{JP;TPgMV*t zcq0^ucD$`Gkrk<370xwniUBx3)ZCwY^XbS}BhPP%&#j`koKL5=*EOg|>#%RjowGV# zGrw&F#DOxYAx`D_wWv+-|XNtb8i@f3v57#H79NCWmyI{?-&`5zsQUSn zv2@&0+!2X8jfnVK^MF>gXIqcjE*t+fMNz+%o;3nDTvzyf(pc+B>~X;Oy&h7d-7B9n zcHC1PjA&qqE`X&9owj_j~!rR9VIkJ9)|BYhcKIFtKJFd<{m+axClHnJ1*2Nl4t38l77s3V0(%_z?fs zClcX->DzJF8@r>}D?-n&VU43A(+V@RL2+)UsFl(YW0dOuIlPhezs*0i00!XFM#*n6 zbHE4xnjm?eXN_*>WhZQ6*GwLapv|!l?v75H*av!!+?MjAZlqm?fQ!!D!|6-IKk*CE zYm;3fuMy7+Kw|`KWKv*9J48hwK-qw>I^S4{=(W@ptHqpx{~`X@&fZ=r^bNhW2hFn- zfpFH5-rd!YHA4FXiNQ9E^deX#ePqb0$8Ym~yd(YE)yAtPXkB9kWt;^jHwiB~B=3lS z-z@!o;z~*bh}#t9ZCXUu*)Y@OW<;W=|0HrJ!Xfv&8Gvpioa>(v{9p8G%qLl3 zjJTr$n(FZoZjn6!@FWvjWoUB}p2}eZG74bf_m92lEvg-EZT6^p%>+i z?E7` zXh~SyF(KJSd_Z{6)RmU3o*DjnW_F@a_xeois+MMn#WE&v z3`QIR_4HLzpjF~?`o|o=R`4Vyd5peQ9Y1jJ&i4Hq02(!QF;GD%g;i8;)mraJT{S*7 z26QbOR&5(w7r3vEfz#!zpUiGOHat8W;I06}t}VA$K?Dvops1LW?rSOCI$(6?cD9b7 zOP!v%V(IEAni5CfszuuD|&@{W+$5I@p}M*BkMCWipHa3i)4$|LMC0 zam&tAf*8=?nHpm$Wz$2=@p8-oc89CPZUwW5OwTY9AJ{loZ7Mowq1w<;dv8hiGZbn+ zzmMlIS7D7aA8VF1VV^b`+I+>iyXv-vQrN+uzDj8+nMGS_ELsagzxr8Vq(6$0HRbU8 z&r~JBmzd2!^~}vHb+xg^8J0=ej2pc|V-*CG_Qo4-0ChN5HfK7I?W7^`1rNI?c#ru@ zQ%fS3J-WZ}T!vkHcnZKGInzmF_g7QXmqRdeb&Z*jcIP1u;;%G`neI&Se6Y?t>P`CB zpJ?3zp6=0bcBfnZfSfCQ03pn}AI!fKs*v5G5$B$OxKk7wCfj!EMc6%2O2YZPc1R2urF3DUf{{- z#qqZyeB_l2ucj@XX}tm-1^W;HK-HbGMQz9NHuSL6x^Q~N^g-~>@m00(6+Zfb6nI|K zjQ8OUx%>G6E}01=>08}3_Jh(_r%xzxl|jXP8A>y5!77c9UB2foNmMMA=FQbQ6k0U- zbCdUSk_)fc^Q03{4H%KFL8@mIibsl$GsIQm55L3#tVru7Vis-h(QgR*+97^dhuQF$ zY!}AUxUgW1>Q%|%^X)`*bTlTlKD zWzYE-zETH@zQ2mi&-GL@HJaC7F`Rpbd7KW0#5C4qGwyBboG}GlD<>z_8HFf9&T3vS>$$%Qn zqb6$&(D073IPrBYJv>Hq|Z%6Ynk zm>29it6wyG!ZW%Dm`kjVbckfNS51o>EafItS9IT&iDJIHkBzYJs_Wd^YoL4E)6Q^VZ`-GEFd?HznFhx%9rlV7C zNV=RxHq3qG-;h!@m2~UwPTuYSXI*L{RFv`B?5gMSZ%pI1RKZm)R1N=SJgO<^7d!RU zZt}O7VLfu9QN73zul&dnQM&i7e0=i_wfjdhHwND?e+hx&Uiz!YfVK^S(NhEEzmaOs z+6%&~X7Knc$E{RT3m z^SL-1L3o%Z0IK-Ud9r1gGChhkgG6zk~oNKwn>vSARl>aH^u*EkZ=hUmr*ymGx|7LML(HqNwkid-$vV|9wY9pPs};cqt5 zriaS0+lOA876dAaSbCZP6qs;|I@G?FWZK;pWzJ;Qks23nnz1_U9cpB!$k*ZpM0scE zB#4~=U-;KluC1TlY2PieYBo%8JRulw6oY5AKBAfZW2ryU9oQLy;sri!YK|9}7o{z1 zE(}C_mAa;KMc?vD%+wcuFu@av*RFGbP~7wS4ID3dgJ$9W6b}E}*b(T<{^V7-Zw>c7 z-J5vyOE04p!OEZuka+TSb*+LunSb0=-~N3ZH3A3^00O;gER)ozzdsXldC2Cy_HOZK zRg4Z4GPz2#=u#)hPQzp35Uc$ZK9 z;}$p4v7j-FdZVIk{N2J7gZOtNI1e9L@ugj)&VcEXrm@weNz|80ccb=*uC6opNYVr# zI$1x`3uxCf83JaCs|#*j&}~*P=@kFHn1{_lJJ&Oh?`5!2eyKk-Z{GmFohDKpN5!i2ES){ zgxUmd=|u&sdcp?tYtg4IFnyLy$erP#{Tn) zDdWP*;s^u$Il@s$a~=Pe&Bw(2qfAD=bjW@$!eXJq*8$#tABht-^`51}9yCKax(5)v zRT*}SUn*?ztZE0&;Ux4PjyA1iG`;)n(~D(S75NrEE5;?A_f|Dp+VuWJ)Cc2yoQl`2 z)sxW3#BXQl9+N(0CiK0O#n@$|0ONp*;rr%5=rg~x= zG9WcRKJFn8kwy9PHfX}rQAG*)Pcmut1mgfHfGu-*aAL#A@<7YJ^I0HlW7?e%V7bD&li&l%|$kHNlBim8vuvR z5eURvdiSa9Cqt9I);o~4uI{_$#=x|8oDM#f^je{%YauOUL-e)L5daL_MQ<9T8{bWDX7?|~+%x7qE;`@K^)tqFyk?WGr zY%GDXy#Zh7PKN)d{S8Uj_YmIe<1?3mg8c#)zc6h)y9G88fC9k4zgTM;O5}340*l(x z_*XzUl@UBiCF9ujAM%#)tn# zy4os6`s^wiY##rH{|gte9iMrhkWUi@N$fBa0- z0icNkpd?c3E;-rcAbJMZP1(o^$MD|C{A|)g_s9@YLxm&D54%6oiZ2`K-JEgAuUToh zg@r@QLqYbyng44I8kW4B&DHz_hIuXvodGzY8{m+jz8zjr5P894NbwBsJrm+Guo%0F zvx^KBI$d?GZjf@vnWjE>S+DapdfaWdF92lubgM|GYPXA=~mH|NrAX&6V*Ixo3THPX+wi5 z$cUJ-fuN=7r^rOc7`-`;OSXUmfVzL)Tv~ejxjHRFC zH_7@!1TeU{iEu};f7z!cDr~tkxGq+)2|+8Bn0IV`{D`)OXDF(bE;4J>TIv7cXVMxT zD*7$28IvEy`jShN{)cuCt+Yrgz{VdLAwIT~1_6-@LF9-M&D$Q@47)l+{UDdNSgmc; zahfd#TX6zXzr0V6m+ko<^zfE1$$rL?b-U+eB+B~Y4m#H>`tb;DF{hyd!Aafx8c8Kw zOe~FM@}I_9{L5ymlJ=eo`O~8+J|)XR*V-^vPfkw_t2Iy#^S5oO5=_}c6z@u?i8nU0 z@j>?6gZP`&?M4ZQAx^Ir#Yb89vMg6zCb*JK7HB<~? zohSA-C&yl{1UP65VJSO`DVUTiNGn=$;aCUNt%8B+LAylWmdsfiau|aNmqR# zTPDZMD%YUhmE4%w=#GFHlJES2uo5e~|0!8=j6B+imZ2by@$%EF7oQw0IQ^C!<^DPGD z>?`%kvLru7gZ49rz#L%&gNa|HloAF_7?=WY!=B%k91Lm zuMBzqNJOWR+q|nqo7JGr;ERB1CL*MjIedx^B2CNE%<{};J3V|efP?W%OcS|svlxMt z%Q+lUhyy85EB$S^CN{2}J4T@8-#{|SEQH4FrCh_G*^txXN}D+K(0!n$r@``{59meb zLza9KnFl^)&@O$q`z1w$$nhyi8i%M-fBQHCbE)uS+9%2OPCz5rKD=Fa`k$3Xo-jMS zKsX0nd~}n1hgWwopOtjmCQu;^rq|{P0g|$lA;FG1FS?rtRDag%j6Mkv`Yu9$cD?b| zC&^XquwVGQ%22Y9g<^d*(osHLyQaFK_|WR-ZlW)D78e@TEFUQADRQls?8`12lZ!d! z>O}kPGT~oTLRSf%y3G*Ef%ve~9f}sA6`yf~%R=b2563rrnkG_iYLq73_8$bsU-{aZ zi7+X5twSgUOLRB!R5f&Y1E>Jp=o^QNZ8v^t*XnfjSfrpj#uJ!{t3I zpJ;iH4s<%6ik;Ze5xtU1i@|P;4O-0WYxgaSuw(XmIx)D!siMfooz^A2N`AtO^u*K*0?y+G#o>ZT;!s(Tw3-lzd+Ypd)>buM&EpdaBOHJI=T-U)_a%y*iH^(;* z=d-I?a0QzIuCmOG+Z0E}?ylgL@%oNuZU) zl@FI)n!bYRcVA8(aA#ETh<@7=GZNaTYL?R6_)x38O-%i#Pvd;6V)5#bAQXryWlR}y z&vyYU0bwZUMJkMt%W>i4)pYxD(ThPE;0J(P#gU$AWZbz2Fw3c{t2^pxGAEVP%+sMW zDdb?kj_d>I66+47Uxs0qJC4oTtS5{0p$9#HmYPT8Zj+=V%upQJ&#{@c3gxWgk{rW$ z+tR`!fXW^4{rxPM;kUIpI$q`B<;4N5u4cK%MU|HBFE^g9bBUWfs^RXJc~p6o*s&yIctu0V-`4G=Uad%A&)-|7sC_wKK6k(2H6V!JZ&E(SC z4^ndl8=^`X!a|sYS`6Lxq<>slSL^G7SllexefOhY+b0=%9c{EULX#?}v6=3?A1Rsu zJ>FtH<@$tm|6W#~UhYAcu^^J}^z7_!<#!cUflVIuRs%+ywsJ=A~jh2e};L zFntMYh|K9W{F7^ptssZ^G*yjE8)aWISO6)nk8@E}_(X49v(wB|S;^+C_-Kcr-Bs(3 zrL)6U0}3&7GBbSTLIgBBRZHTKE7NTS4pcRB9;ZFvkueuT!fk5%BHWUNokh#ntAWg;Zm4 z)@$Zu$h^jS(>VIEB2o)}#Od*F31?gUwt2!qEFxd6^lC`ihhURoOCm2$1y^GySwz&z zw0W!6RP+%rrK}@-sh+HZVqKov4{BeK&wCMfwPYc6&iA8s6bDFu@BFn3*ZXe3v(56m zqMazTAs;L2KQfMRH-_&om7a~7O0l|KLqgB;7n*B*66rtwK52M|rH^B2pXy$u$yW_y z23TqRK*KvQf2XT}xPPvPVf-%Qo!E!Cbx@u*YrZZdVhYU*Q=+J&!|>SUZus!vP^&%6 z@0YPZ-%Zu4#CsYT@$8I-<7+&quH-G{>pG#_{+wS$ouR;k6D6i{f*FkXIj&HqXu3;B zL42#bs&IxubsClj77G9Mg*j=&9JV63^_4lu@I(9ZdUzhgU5X=@m{>NPS#sSb(TWQP z2;>DGI!$jd_rt>jFb7j@HdHHA3zyySQ{c)?MLjs;oTvQFST-Yk3YmdIUx6~c4l5f6 zF9H8ee7Ta6()>9` zefGdUmu+l%MZ3E{ONC$P-yH8RLjSZKAIu%j%#3v94M~+`D??O87iI7gqLj|P@_Fy~ z0(S|$on0CyRx$-WZvqQrvb@9`tgM)Q<-X$)1pFFj(EX^+aE9#xu8!yVJ~xQAyHNXSOw_xv>JPgg3VV< zE)XX-cf4BOg-`xcwZ5T1HDL=e?Kiy?zBhTUM&bls=qSH2&kmAQ-j$<@CL(`S3Cjt` z3Jxflhx8__s!)b!I*m6E4ate12Xu1W%6bw;2UQ~EPfr3@Gc`vSp0@**(E$22*Q^A%I zNB_Dv-)a2K4+6X`%6a?9LN=D_{Ojzoctnt&=Wn{pbsT5>in$ZwwN$`fOAnVh}kvIs7MaR%pe)OsjbGaTbU5^W&t~V=-KVNyCw#gLJ zGP3pszK07V^Ok!z>-ReWqD;CO5EVuCInAyXk0HINrgy&I>1z{vdwX|x?K&IQ0beAf zJSzq1aM5_ohA)v6;JrL7l4J(MZ=eblMrUVdm2k)l{Bg%o5IvyU=eqnK%ADHZTABT= zm{%&XqmC>ODC)T3h5ZvAGHg6+1V(mlX?I#RG{g<3`|ph)u%^5+Zz}w`6gqg313J6% z%K1}xGBVg_)>V`zZi?pV#o9kL@$%5jk8oU`Tiqt#AX4^9v||`a$_T?qc2m&if<)fh zS=n(oiJm*ibe>lZH3!QN3?H%C*yPf^Fh5cE6!t6KD{ReA{?d4N@Q5~ex>)Z7 zBB4Ixx8#tC{!z~(=KIob^g5y@gR(4N$Mlxw_X2ey4BzO z??;c2Z~+FhGi>G-6Zc(y2`!zONnm5ksQ%gt6j;$OyD(UR2B^d(?M(C2dvuXf3z}q` zU=`*hS%w2;`&{x^cmJt}9X`AH9ElUu%;%>E2h?cog5Ck<49XauG>Pp@q#y1y2q<>s z*4|yeq&ytPdHML%+Et_l#5pJV_sc}tgNmMq4D%iqz^K8V1BuQADFmt zJdY}+@Mqrnp51l&%iN080T1zQe}B?QGsb#*A>9ytzSH;bA}I+r@7Q-7HP^OhI&MY^ z6&B#|Q{TGTHcR8v>a&7}mxs4-r@7Rejxk@T+ge)+d$ePSJ?yiF+jgVR;Q|1UY`?DT z*ro-ov}cvA`8BzWtms)D=aywRjO$$x=e)L({F$piczb>QwHfFi=Le~Kl}IPuONHgs z&c9XNl#24J55;6VQwKImt-P+#a*AnXq|x0LZH5Y6y@!Wd;#q9`Tk(ke3Ik(HmgWnU z1LlB<=Po_&cwG#&TCfE->LzL)tR0S)me+_Er{^7CK%6H7lLp)(x@W zOjN%q=Y(F!7wFQno}DBLfcyXj(OQd>t-E_uvxmpu;N7r5s`XRJuy=$FSux(UiAAT_ z62~?!o}N_r$T=&Ebwxp}B^O_h^`5VRJi9zeHIR|wfew$~f#PP!{qn7=t4(Uh@k?uC zYr>0uYKN%P;qGW<#@k>`kzC)BvO@FAtE}ajW8v!K6@?di`hLt{HbO#Ect=qY4hcs) z3*7t64tH*D><*ADalYIxS&MfC&d*1``)*?547_0DuS7nqow);lKHgY_ORSUqzZO8G z$;CSU#d95jf%Its+OBbIQ_8DC*Hx7;sIF0rWUUlDX*#4QA|pZ2)p7Q*l{3qUv6C#> z-yh)tIm{OmP3vUSHgNF!36OXaq8lM5(Znh`+!|z3yJzPS=hxNMRjyTSA+%#lHTkgc z^0lj4gp?4bZ*5(!`@tDgJcSt)@BVcIVIejpS%@HTQ1>UYl>g1`ZREl&Ybzx`y4ELY zuQ&)}m{sXqZbt{DcukJL2R`uchw96|8a9$Q6Cj<3K9B%@fJx^0rd%wAsPb$|X?GOSY)K-qg$Mo+pM}@6UT^3vZ+(cVx#+aNpNh zRW%=1s~)!(Q3_n_rx8(Han7q7y~d*AYW<{T4unp-1`=ES(&>(kKk&+Ly>R)RF^HIz zkuhTq35Sxio9kB!N+ds^JK_rw;)aje`P5&`rtHG6PaV_7e6Px%ES0_h9)c&|2j%!m zX^FhYJ3#3;Jw1KF;CsQqP5mpoHQFUD@=kl_o4tKpwN<5uDNexpQiC-q^3R_wdX2XC z^-+|R=xYH-L)3kHucHBvbo0CM?{PM7%3L0X z&sQ8FO~Y=vJ34p*Tz7}yWuPv>g z1b^?@T@1dzPw9x3!xgWCY;`exhz6+dOV1p{;M-H{A5B7yesb3w)uRj#3q=9DyZW1YqjB1M zVidkl=OG~>T87>l^rYa5!&OJ<<_r>B*@*)1<* zU+nbqF==}^lujg#Y>v#jNKOt9FV_Slxwyx?J87?gJLkotoK<7+6 z=KHm~I8V~JBF44>SC_Ga4!_2mIk5wYB=zt3!|de7n;9d-X0I<^z9MX~Ec)82uxQq5 zXJ%&Vd!7(TB*rCTr?05;Vq;@Z&X*!$BzQ}_?njoJ!wiTgc<&VF6)^7d5&XPQr-e|a z>ozB^NiO!!3monHyx^;Z-4g1A`8Vo9c=7ACh|-wcRv`E_164WXL$}$=PZ}AD6_TgT zXv0j=M==trCyT;&slb;i$Y&ZUsqozE^Gi%Dg0I-mIL@5EXR*H7FI|oQjz%OAxleaz zJ-Ek9NssW`@co0bhkjM1-wh4tIc#ifAgWzL@!!%kqVw7w(^P`>hlilX!lh4YO7B#x zG<>aHVv0mq7ODLeyIWK5y=OWVF{WXvcSwXtIU+lE}JKd9% zja+u0?n=O4;yYVen;fxrtgAM4d1nt~PRTK{(Nwk|CTpPk&tlp?ad!W#mt9Z1`3FC>1w$rXmWM6^2Gd?CYjNL zhc8Q>z$~poGcz`yo$=T0O6y)n3T#oMay4U&1V@n%TnYk$uX`WElU2B<#2Q4f460>+3uT5PHA| z=Rb@X_#qpeoghoAe;q!bWTZzFITpiBb-ww1Ui|**3p$$UsM9h-K~-FjNHmOLtY8V! z5bYnCPP2;v2gDWNX~Nl#)92rQY(AWjet*n z4W%;k(&|!ISQlA)Op$$Mh>`s+BE;w6g4t>~K^#)wP~GtHy1upE3WBCpf%L&iiywv& z(BbOi(Y5yHYpbAg7Mp^yLh-mBaA)QF5ub>5V8hGLZ+Lp_@^YojW_&uE2^0ct&V)?DI}(3(?Z0)c!`Bzq$k*_Ap50=h$_0q)8MK7+;PHd3Y}tPC z+{^QzYJL4{+A6tQv{xDF>BvZP=W?%5lr^ktVkPo8-*(vd<`HA=+gVvT?nA3OMJ`a1 zIyW`d0}oKC^O(zI1#Ow*j*xnrOPEmS=&FW+{|a14G9&ZD9Em=u;vxTCB#6BjQt7dd z#>9U0>LSP8mgrLxXO3s&KndDHw`qHg{A4)o=?iTM z+U4ctS#1bPU^~wR@!BUjhKqK+nN-U{u6D)0`#U$io3v|tG9|O`e#evJKbDbK6+?=k z(2P=%1K%-93eyNkb5{^Vt9DF=sC-_irt7deyDJgA_y{j%`l(hbMKh4|@&pUN9YLvG zSyTHeS0f__e@^PbG#s8MSB9DBWW*+}PvHyJWnS@&)7@XiVU~+@{&8>oIc*yN%XL|( z8I)35KbO-?%^dznzxT$EC|II#`bt9~D}Cdvyv->_1fKzQu0C}CGE%_j$-Ud>Wr@R9 zfMoFP%yOM!-Y!vU(M%~7aw#>Xnf!FR)DL$`$+&9on3D=KGj9(?Kv%Y<58C9Q(J?0A zdz>a!^C(U3+0MU zGB#O*a?)Jea+Bj{D8`l^LwIOy7s(isvV74zkAT##I1 zn>Iypu*pvAL&F_)XQSTCTm@AyY0mYWIBK2Bk@akYJ|mim4!TUmKyDEr7)| z@r(2v3K5?x7TND)|HyvD@wJXZJ}bgezN%C~d)0v+GtjQB6xQlV>PrB^{^2fjba=RR zcqye!;$QqL$BOcu=pbQ3%zaI~7X!W~&95btYIB7UjZ#(y4NLpiDQk!FeslbFoIHH= zOl0$&f5%FbFyy>&?9*a})etr9ZJ`j1X1YOGt`Cxp)e0vMnoD%eEXa-TPY{W*F%m2I z!a9U!x1+-9@@J3U-Zt`x3k<mue)3V!YN4H`HupmK%s%@1mXx{h2a|YYZ0kA)Vq8 zn4E#=^&y~ZGB~U)z5K~}7=wmWd1 zLCaA7{lkj~ndh5OONCefzn-hBJd-R|%hG>Zh z^1+mw{JFS}?g=DFv=bYGLrAAvjx*zxGr)=@t8lbEN~2G0$|R}b7YZp<70C$FLI;?m zZet_~Abtn$mdIjH>#N$^>5ZmckHu#VGpj;i6EjuFKdo1ARZ&=`xJSRZF@Jg}W9Oq6 z$zv3I&z$){qEK*rawgI2^!q;|FYnUdc7nF7@_oJsEop2l%>m3q) zwaSn+N624ibrlt{FQhQ6K1TKJiGIJufp7+yg$K}s&DG7Bahg@SM&aMTe?dg3b?25# ziy1vVeE`T9-QL-m=mjQ9(f=GT!RGM0*B+@zFOg5i`ISSd6n(j!@07Dc*lo%zm;9+J z8;R{6k>&hRj!?em=Nui+wr8AELHuD338q@Li(cD_FmH z!QN)P^9LJ8fb=p_wG_rp83U{mZ%xGwOjdkkdk*5Kl#CDzMmKA+m9bM__cME3 zkh$2J0ajMaR2}D74$ZXfr;N9wgqZImA|m|NA;3cVU}uN+k@@X8k7vizHw!?11*^K1 zA?oHZ-$oh*2FiMwWqJS_usqwjG2c>{GwCquam$`JgLw1&r?RxA|5nQme-V)fA5$C3 zM|*(d)ju#m#319hG5V01WZ}+x5y8Rq)_Z?}yFVC4s%IGy0R}FEkt@}jr7r7$A z>On>gqoTf*tN7)&m^76Q^@&MsY1I#EYr)9Y)h7Mv_IUH5PzB1 zr+~ju&eiYddzeNmWwQ{hkk{F>bCvrh2Hzs_f`i?*P2K31KXM_$sl0*%FM_tmpwkdJh*1UGwnOl?09Rn*1xeQ zefD}`O0a%yQDa2`! zxlH!!k6*GeBgezVMt?FGUppN*NBv0L;EcXDiyTq$44|-Qx-Y&tbx1n&OgC%Aju;A- zXwe6q#8P9wuUH$Dv>J{hPYhly0FHm-<@Fb|_GTSR`{h}DhtZ?5B=W<`Mb~gP zxd$xW|L%cNSQM4W@bHv5>IO*(R&K#K5-kIwKwdW67Qw;q1Lk(H@ z_#yc-760~9l@ZImr-7(p3h=Jr%fT}$nv%e7)ayESN;`&*RN-s>S|u4Og=&s=&>Q3Y zx1LaeWwOAecvCG&I(`(U(@eUxzXH~#BIBXOS(UrWaO6t$l;xdHgOsDxpHqz=NZ zcQJ*d_q4Ihc`5Jx^~HHa9@8gyzX^~-fWc*oYD0cgq8Tk>%N3VsNJyl3d5EmpQ*B~Bq%M^cX_%id}IEL0y{6I8m2)$*!rFQ{EIg%PH%oaojIdWpu zb)=HY`xVQ}R+LMy{aG!h+ENzJOHD!acw~93lV+>QIyKs}4wJ+;YxRF7b6KIeT!sb!l^ zNA^4Qfi&}#r==*p?&o^El$H3)f#ffJeSN*WW*nI>#Ny7+?;G#au6`n=rlHBlU5+x6 z_khz&eDC1IjKTSL@}kytEk~8cuK&Xpb}3Ei;`sxR*%Vpd6VBduo#EDz)4M=n{cl5@ z9b)s=JP=rZg*HER&yuRQgFy$*bmgYllBg0Z5PZ1OxH(@>lJB<1^#3q9KwYqc!Tpxc z)6K27==j!J<7w%n_`7$QRB;X?xP$3jGIjU>#to?nr7dG&;MA{&3E^W*7z2AUtF z)jZl-yw#3Nv)}w=6?BP{G#$OXupw1utx$;QZ$ik&>I&ZDhO)T6WW84LN!98~2c}aR z^&Wx}sSYOeHtZ+jFyoEHMos2dt1Ugmek=`CK8e&~voAE7I~mdv5W^x!zl70=a553g zy!lwpT<&M|W!6OyJN}*@a~dz6EKUdgP@#5zu|=*E+Gw5;r7?VRR-)xUR=H{1Pui z*({GONmFD?&@;U06UsgsTH5!lw{$c#?npMjv2e-QVypIZx4^)Tb6z5a2Hd{`9?epY zDmy^Pr%w#cPbc=F{VadF{2<~`={}~(;c>iLc8%g82?5fe6fYe&U>1kuRp?Uhc{)YY z$P-{@hOVRC?^#Qb)y9nEY==!d_FKv;DC&`0H)Z=^$PPIW2Uy@5eKmw%J^_M^n#|g3 z9bFU)Zit5Jw4CAXHk#*KCM#G~>p2iWB+}C8P0jqA-D-bLT+k8_Smxy1U0z=UyEbed zit97Zd4l$bR@m-775g3banU9(oql5cqxv=##<#QF9kg*A4j=kt#z zcNt*9W$}Ru8hoC#F_g?PA-zeLvx53mhi_b|O$Tnz$I>t-g9q_J2T{w2AEfR|$^t%U zOEbbW^Hf%pjVS^)IWv>Cqoo0W?~M4F<~Q3mh4;?c?dS>F?A^Pv`~}SaP@?}CN-DM_ zubJwRPbhz0e#k%}hCs7wPRN(>X1#LHA0{3$DBvV@dU?3NlUYx9ND|HzxRRMcF_l}T z6nt(knzGV({<<2*eKE}wy;Mjl)$OvAi`nu5lT9Rw1#M z&s}T}agWJola5O-v{Sx;KQ;mp0!GJN7&iqz7Hi^wucmKyz~!rkg$d?ptP% zuOllCu7Qq|suJ1#^XudBWI+gcz?S%c7w6{Tl|6>38aaUWFJq$BFy+9eh`iL3%l?CL zF!X^V>-$ZpWlNe!@;-oW9YVz8!yIJ;A5v- zh_)(3gQMlgx@(y!DG4uy_RClpd?35;c@CsCL25jhls@XeTU#E7U;Yfd>sb2c852Ot zdt($8$g1{Ih!qR6mDyDGk_P^-TQgecy9kRYF|=yw=*!AYL!$5hs%Lk(<($STU6uGr zu0vDe+uxs7&8+2#d~Z#yOd_6}%{Cb6Nm61W|6n_w0urRi{_Fedr^25IRo#yUXJiUL zwpODu-_Wa7VFu9UbL#VaTB>2Ek_hhYwF)J&rUJA;?!&Yv% zuRpG5UVZPllKhc@sYD%4E@Uk2`+I4Lq3=deKR)nPZ{l($i*#jWr5?HXW(XrNit3|3 z28J_3!d}Fhg-Lhx3(LTuk2o($_Yp!f{DUsjG);ce@JkSXK6sDpW@q)cJcE zz0BjO$;rne(rqHQD%Rc(vn*}{FYV>Z&jO@~4=>n)3LUdmx&v&jR|4m2$=+FkgsSD= z0y_=8RY(+GFCZTe8(1=1+}suz>Puk)i62JLlb=89pFEL1`>iUaN+XSXU9$#aL3n+_ z44Elm2f@JYF8MejFSeH|F{JVw$4>Qo0|gh$!vkI}_zmf2KQlz^Qve3XskG~pzd zkdS!({J9TK&Zrv)R+#%7)n_Dk|L54NH(!DsQ&M7>6;18bdV}Sz%2)==0mo<6&Bf*5 z&!3kX5&k-dywhKaqANWJLleB5xJlHT9ojtJ^n^b+F~?|c`(8FI-sCjPe_iw-WcPBu zlqK*2JczISi(?gFOusD2xi!ah2umW*#aKP-F2hwRt%nA2Kma4*)G?u@r)M{w7|*%cb?|{q z=U9_GWIfC^c?{Llx-P!NfTV_zheLT0^!OH$Y3Afo&{cb)N@n7!8r z*Rvh>f(mu~nC~ukF5+mZHZ}*^zO!zTP_b7lL|WdWfb9*qbpLQf*5JJaEW<_7=w@1} z-;K~5?6PAc1FeDlH{}|g%l{smlP+4Qc+N-c080V;*7MAakwsC~bDdX6@oU~Un3>X# zScvb5@#rI;;Os(;r1ml-%KowLZZa zHm&j>c2IaSp{~vx^!x?G1jfzQi)X|5yxc+^imye}K5ZvpWpiCe;q=*%n7-!buA&^` zjOI-JuH-G&`ki>3Dd`7g;wo<}{izk`J>HZS>e2Db&DQ%;j z*r&4TJ1)_)j?0aM*3^{v@4J^43pCCKN1-B~V`cCi1LnBGQpwB&#@W*cfJ(Sc z1n+=`?k<_#1KIH@2;kf4Zw>u>r$nNp_vLcSVOT$=Q*CvMmfqH)BtT-bTky-nX;8S2 zmko$$1>n(7>;c==rX`m;z!@+Dj%Xg>=SU$)$1sAZ|H~hh*ff(ORX@ckQ;dtB7zb#F zu?3y*v&+f&Qs2e+bUAI>0nI_yMYf^2D^3Jyt`55-WPyzfrj4Kg z7wL9HH4v|Lmb8+Q*e5D%HchqkxL5~AUNGQ@nT<`6oJZv!#tINfvD^?-SG^l5^!k^e zX^p8-^6E6B-}SMiQ(8xG_K8}0?*btQSFDW{aTjN#(_>R z;Tc8jR?Ks=vYX(R;cUAsG|LzG$rFEVYO>{y=SiX!){cqQ#e{%qo&GE6DN0MDG~8ak zjI4{|h_1nXE#_>%OF1wwu=OsjP#KY)20%Kh_i)J%^oTL56DUzB00ZQ@LXQ7;gejcu1MOiyQf3>9(80{ArcsK9T z5!Y>`LOhrfM`XLk7Cw-&1YD7#qVQUMuCA`;=jPPHojPC5fbU?*m-m7RzoaaZ+@vO@ z+=CKNH!ei_Riy6PR*(CnzBW2_wWEsM=$quMfaTnw&YdXz*~!W7+|SR|)%SwHPB1EJ z2Xc5tz?0K}9aOl*B{k^%TXVqb8O>u1!T?}gF@|zYsQNTCbbN9BAR8NUR9pwvnJuT; zl}~;)(a_MSa92`gNc>5j_as|OA*czJ3m!wE4YKxHJT@U#TVy%Sx2rKfQSSUXIoc$M zhPPngZv;vRQPJ5SKR%3aF8QoI(9lOQdCHSjXq8SsPJSV{KB3r9RBHFQH*7cJp64?) zOrs65thV>Uy^qvo^2oyTmRMATilu!nx~;rzu>`WWNLtk@ZXf%w4X{n<+zt&2X4mCq z+8nf3SL=)kyeiJ zBDwMe2*ZvS6?^&wbVvz;DhUj^^p{Zs`OI$bsa?^*lnF7pM|`v)jGgCVE|F?e4@Ej; z6!v-|+n*A4u)De@z2nTy)r1(k&`4x-$76x_`FUOyMGXvKwu zhK2&YcP{Q422Ei;2fchiJ9?N0zL(|E=fiqGu)mHcveiw4HE#~FN!RvsEpzSQ@L0Em zj1ofpsyejfmhqYu83|hoJj9P&cG3=Kb2;K>-or}q>{aX<->wGucK73S-RRn~ZEkvy)d>r*JhLg^M>5Gn@;D)5$8o~S}xhP{6SQkOt z$z~O^VcIQ5dI$V!?>XH@gNp2gBHOGqlw@Xp8=>9IrEqHU$3ayUM`-;Q=!gy>2gG7T zHYloJjhQdA947&IWE5s|C<(+pksS4Xk_qdM#L#Php2vBw>>dCtNLCICxFTQuAFq0)xxm(n3-iLPG>l2^>Ci&Ff6KRyM8dGFk%^} zi@9rUsm-Ec{s~hw^R6&2Qb4X1zU|FTv28rP_j{n%nDOGX=wYB|I7!(Ryo64)V)I=N zI@NUQY;LCU!Rn*m3vGO?5J>Sz(~+D~>~_mb&R#o9)E~X;SIQPBgn2icy{)Y+XcpN5 zz8lEFltaqsc84VEoQ4SCUKc&oiD`nWMhL986I0yD3 zFEA??b8sb0Ou)xJBF~n9;cA@&*F>|TygZC7kH7TAC-@&d-UI~PW_d4S1O>I_U{#3K zemhiGRH%j1F)(-|Q`efX5JkGyIyyvwzezWB0Xsg+188ah9~Us2kEX&iEMxB>{$x76 zdKHxqpsyvIATZfaOw@utIB>Ml`F;uJh*c?!nMjDLjH8wKh}u$LQRoCC;plBj?@%2) z0{Vg*(C26gA^c{|a)p9oV&|7T)oWcqB)iooF_qw`SxAaa)}x>?2(9@wISyd_uKOX3 z_j>@gW_i6z^)cFp8CNx)4zGt;^IyimVEPCuI5;>w9Q!Tynoi?$Q&TcD;q>trAN=70 z3jQc!sd189l)X|Z_aE|4%fWWd?uotfY)D%|2rxVa8ZE>+mujEQ5onf~$svc!p+q1q zK)<24oTBVB-9(zoi|@nzG4jX-l7mcBIJ~oEZDwZX^3pfS`OTZfI(vc_(Tks+alYkI z=i9GXZlRP1p?R0Kc&6I;Y%one=`y`kXhO&F$=zt+OsdMx;Z``&q8E5Rap{EkK%ITCrL{jVg! zP5pGhXxHJDB


lTLyCD*1HLshGxUrRb-`y9J6mu~{@|OA8 zXeA5ha)1|ZJ_xG}dRw_-sj-?<-3b37bjAZ)-|t1&u&qqz?<$)qk- zW_kocKjPDeC9i92X_@n5>+`2iT;%u(vbSO~Ea)#m(pqa>AP=&~_2OPn$G^?NjHyeD z4;1tC=P_Hn_yrStF6fCKKL2lSaWQ^pMx8?gTRy1VEs^7aJTbt|k+p^^=jnEWS}B)6 z%b@H19nS0J={eEEjDJ|m{|2Zb%z@qyhzr&%#2c}J456r~2ngSPRKcX)LUj4lMc*uN zQre`iF)`5Pb}R1?3rKk*fm}h4x%Jx`^*tdFgM5EKSt;qycJ}_p@~SJatOkB|V}=JNSP%dpuYdN4$7UsDkQp7INxUDD`%fXz z@-T4n-Rt~b@u>k`wWFGDMec5b{w)|=&CBRMWMwpX(;q`Lad6)8^OH;VVt< zRN=ZCM*|EU#jkfvUD~%Y=jSHT1q?TbJTWn2nwq+85{nGE3P0qGs}MX37TL?1J$Hxg z^mGduAq(%#2#p7>e9ja73u~QRKy*`AD2@y7RE{%z|L-%T@j2(Ckj)IBc;b5`1;02c z_CUFVR`0#+Me?xA?S{U~L9f6K>F&Z7(OW&3a;<(t7w+9~^|gkgVvps`wB>7{cLp)> zU;ywNlKOR9(rUP{(`V{wQTcR1F@~yUmvr(^-sg14Pz1 zym7x0PJds&SKs%95CVSUy&%qL*F5Q9RmgG3z*`A#fQc>`;Fsk%>%ZYrD7z*h&>~Im z+$L5g0Tn6ON1y3-PAdLC}@8nW*~ye75?R@RtV=d8z2F zglb$@Q@RC&OxXbHM*nZ#_F0yyYr(Y`Mj3as7Y$KYqy03Up#@v8;cSYo2edI@j)?g# z)P)3iTDuoq7AaenH5v_+!=uw(@!+ke6v|H1*MoyVNUEFuF6=-oF5afwBrvL=`LyQ zy17(NI3t5=%A-$G4Mrc?NC6q8$2OxKaoB}Zn)M(gD1tFM|JmoKE4Ag>SxP7{+Nr!Y zlVw-d>rGY*S{oBxT9+oh{uAL*)zCl@svRfL-q`52rXrC}9L|)D#cKdI&@;(cyD`qz z)Zx~gPyO;SH(GLGFzxqB{CUa@w?6EpDEZDc&~Y)VTXWq$&0Ojt^-N3xr}570e(Drx zDtiaK07K<}n~U@RC`)FBWMy!t3Ck}~m{7~4UZq;nlHWwX?z7x}vBlix$bt)-J&tBx zwAay1!dnocGRC87Vh@tP-Y&mI+x5J6;l{00kGxuN9R&?Zf4w*2PY0ZyL)5*)==lx|JoqKwVhA_j zzaQs|Sg4nT`wm5V&AS+P5yU$xuwgadu?jFdH*gzQ^C#3xY^H6J1^YX(;fCm!hP8U^ z1Lt>6IRhrhkEyA*7ig4Ct(c5Ve9s%oOM7?_(7=tL(96rq zfQH2IA2wvu%-DDqM6FN%3j`?1)E{w1=9}?@jOn=8Sg3qZs1Km0{%Zf3Lgw3CK?NDd z3>x>_c#;fip?pTCqoX5p5_nM(Lz{~h1w1p>6>_Dr)x4Bv{%|miuOGjJQXSZzt|#jR z++8iH7MbyzUcFeUvzOxUdlLRn2?vIjS8P|HL6rzET|WdZpWE(~xHn)|0E^^ICbsuE zR|}i}8<8$VfkA($h2as^D<;M@{0M@7lpm1EM3b=O8MOT)*c)q7hd&$#{yvh5LtluZ ztV6x8{9z*9!iU2+;+hLF(nF5WYfiUGE@{|tA*Q6$v46JCrabB1u z0ng+#BZJbKoSInr2WQOSVSn}8pJhy#?R+`%CBx!MVSL{y4|tSVM+kIy*(iAt!rV`n z%05%)_yx2?xPeF|^LM`0W^Iojqq~ZpeSSXQC@uCF{jo_!=7!rxjrhfN%eQYU3-0MV zHd}LWzfr&eTBzR)zS{rpvVM(YP5ox>>nl)|7=(APFR~tR2G!@Yx{Rgs`LB{)_CV>97z{gqhtOi`uK5(=0@deVPa!OFrjYrbIyKG51-{3Sm96)UIRc`O3 zrFo4K5O@!4z+==a>HD>`>)>YbfaIZ}%TtoxoV89q>>6W?+5qy~n2vLTl0_>TEL|d` zgLQ6?U~i7icl?q7T=vZ@kEP3*Cc#i0sUzq(xo=2|A_fGvT(o{;nFR`!Ao+URu=Kzi zxsu_Zha)Nw`K#Z&4{^t?gP<$IYJLeYfyL zjctKDw1B!y?0}Ncl~e~EY;{4$;z4f|vITfE04fH(a8hjr?g#3JeY>+#=EA18R`+2J zVLV?`$~Eek>qKuEb0Od4yI-2~VG*t?D`Sl#EQ83){u^*4du8f~cgUo&&no-3ng(iK z9I)@Fa+;i5bg9wFn4Bl^Nmm+1#*O#1TH(~LP4Mmq$A!+EAHnLQFJkluyHML@{8;}+ z_kK5{^CwYRSy`zUWm)?SS%{oFSXWQ;+e52GCqLrU#-~m+Bzcq(8l+(K;-J=C{06BX zHf=5BAnR?&wTPuN5+I9B`>%uKIA<&GsZxNQpyaAZFW3#DZjCx;o*rd3H8v(W@Mjad zAzQW^9yxkLBkb}4Kkg zzyV?8aC&=91wfh{|kSoLW1NzD8MuRi-;GDH@(X)7b=UCe;g%Qvt zhQlg;O^zHY1A)N`V&n&Nr}&^A(ha1?&7ke*bZ0)jrCdc0nLm43Tdyhdc!1S?(okT7 z*!V$kimJr`p^mW!^r?&TV#3GqS*UDck8!?68Patzx+dqp_2rVoEG2mB-E+%!8Ce+_ zZU3wZ1=_=eLzoWXqz$jrq@cs05l)rAw?IH0O{)M0X@7q|WI5-lY$lp4x>f013w-N~ z^GAe`lDoNCZfEXf1{O6U0TK%wpK|xr-YEB$g~`e8js&Pm7DhFXA|qnL&IG-R$pQB= zz--X#uiXBMpUq){G%Y3z3z{20K0xErKU`10GPQ0kqBW6Pdbrb(&$$}?2kxUHb>~If z>y#hLDCWM7`xpX5r>;-lb4GvgMuLoif?hA7-2L|+@hTI{f5l}t&8Wk{Z2yuV2Ld+O z@d-w6F999tl!?>NkKr%4{hK*~i+zkT(acm!x=%z5affj`g2#}^)fzH}aQTAZvlU>R z;-mT@U7HvRR^$=*gT$3*9MZ75^W@}Z|D>dNz?Feo6Ecw(O}NOvCgF9^S2&G0uo-94 z$T^FhCP-q;c#8f+sQaWEn{GSw0W~tYrdl->hoxqLlS=n}m(iOGMUu5v-TWC&43Q|c z2`W7SXbp>ty$0&$XL265dJvn7ArVi#BdDe-Q6M8T$35VD#_z`a_Cr8pLjy{5Dogt6 z7Ijox?~s~TFzh=0xdw_n9%IzH*e*Q#`mnd*xQD0UHO={DW#WHh+esJej4*iEPWw^Z zdj}BI2)Y^?dS0n3-bYuun*SnCL3824pVKTU?LUe!-Vu_%Tgw zWunr({A^~m%U2f_|Grzo^{^ka!;LM*D76>v;jg}!xJ-{#dr>Ks*S!(ek+kd>o#0Am z#|JBdtGiJB-l~C}IDH0$e;)QomPC8Wb)Fq>owx*E&HHrXEMAMA=Tr9uLAdw|$=XSZ>{Tu0D8e%eGY)>e_xc*uON&AyY;)c^1r4uP z23IX!VWf4y#`5+%8Y*9#=2gZm-YWVz%Fx@|x|lFe&3pW=wf!!8hk$_ggdBn{))4?# znVllw?uF#DJ-rf zk>z3ZLK&}2$KNTKhVDNQIPVydc<)L0BTT8HJ{3Lkm8(#NU$X3(vVru7OJ17pZL3lZ z$ntwCi)O?z`=wNGKA`}B$u9&aPjwd8<2N3`Ar_aM^UAQJux0gr#d*8Yu(x#8~&awg?l}W zVspR!zSI}`ubybMc*|6Q%W(`yswL&+PS%fRwAlDHKIP(v z{>C(AnW2P98$AklL}as`Sf#blOT_074)Y3h33mNsx4-78yIy-q98>s8 zBigwG4fH^ZqWLvw{~EDoda45qO63WL>n;Yywal2+N9$cb*3J}#t^)KD#ox@@OnvJE z&*ykl^wQY?&RzB+9PdyEqniLoxMp3{;m*AfAM3#bogj0b{9Yo3P^wQ*>ywDq?wa#w z)bx>Wq@yM*uu};1BOi<1M86ABsu1n3#>zI~@uh1|#@#XF!4*N|Ev*`U&xE1)P?%d6 zHnouibVtP{3b2sOO^s&RcC=jyiCXxe3@dl-b*(nAI22s3=WenZ^0wPQre2MswiGJgaylk7mVi{V)IHKexj_*d1?67?n_ zcyI%v)(bd6Bi=$~S#i}b3SkV~{S{vA|9VZd;wnroLt zst>#MAiv9R%-(1_sLK6kkvKk6EOpLYO+K4rcf?cO`sy`^Dk&F=1jyDZ0Lr*~5k->B zb2S-K`(4EI3}`^6b!opSI;MQ|GfQXh(d9tkUxz@IfiOl~-2{(#$+d+13#?GIT{nYi zH!II7x6YgriECgphob{YYv-g+ErL22I+b5MSn!IJUFXA*V%TzFXWk-i%ceqJ*^&TP z$OkIz=N5PteC#C~2(IOm9YBRTDt?~p_~B(o!0eyF)P=^{UE%T;@hb2p2MdV;xc@_rcLQs`5}WfBqO zdN^(D?WpxLnleELQW3U7GbD}qJne2JFE3hIPqtzSA7XBPdDu!LWYx7o(1LqmI{+SJ zeZ#NJuZ~O`omXVt8b(1u<#njo^wR7YE@%DKinYROUK~=a9*8`SF&4(OzAlnV-yCkq z+4jfz7$9rl_}zMl%q2C_2_S?jt+i_vu+0dGu?abo`dE5aurLg>*j+^<8 zXRVIpBv5(yO_VS_?|?-~Y`$6?3#{5s2ZDe8u$KAFCzkWFpo`ejfMPPDFumH>T#L18 z{jZW2=wNvh!g$Ajj&dj~2x4hb)_FWQcS(N3MxpBnt>)x1^SrRD0w8I_YM^p@_POY7 zcCLkFnjrP5qj_uZ&Jbb>Hl*9_-I9q+N#cbuQnmej^62+P+@j5 zCJWy2iww<;i*z#8-C5ED-qDybMo6yNlDMS1#)rs^#Ns$6==tX;5f-gZ&ryMn>&F~h ze99Sy4zmn^I zL+O*oTPSm=RL;N3s!6W=g&6D4UqMO95goiW+QX&mu_ad_f|pd|`MkKBp^U`A{r3W* z@h5xwz{cE!2NycA&bC9{SojtZ@5)!rGd4}FoE4`^pqo5j>8)!M7k%d(ZDV$8Ad9Vjb{G4#{xH; z#SgJJ2Hs0ymPegllanq$Csh9JMTp=q2N_0?z@miv`e1l}oWpq4NnAj&K37;VhSk>} z8#+6RR@j7EmC7-FA_6Z%=(+TMp>|w=MspJiu@Kb?|A(~0gA?{eF+WMsc=DJt zs0nA&3=r5(RSJB9_D#G=ez?;b5xvEbv$ZYwXKrU^Mc#M(<|T8qF(DgV9^S>2gT=e( zh~~W!>3R?q1UIJ)nU-cltPhFu7<{r42NEbf3u`f6Y3}P)+%~>dv47@lfHUuQ1)YBw z13F?aCz~Vg$9No8Z6_r)DW)Wpxe$Eme;V)dFT65rQy5a^CwRBX5Ct(sU)Tk7e43R9 zEl(Vo1s#WIdG4OUy5Y<;O72%c`rX8J|q z=~z1e)=hiz4SpH$C9Ns@#68aU{L^adomPl$x%@5867vO6aXg4S{koa*>34oe5@MWGn;7WLhOYxz;&@OoE{Y3qYAlRrfS?4 z`bA$-385Yq7huGUi)>B*ElBb1opq}!RpE2w?0RKx;rbJMBer01mK1nR?96CIP~iaj z=c;;#pxsb8pq!U|0=RM66HuAd%SZ*oy2|;WlgZa&%Kv}@lpQ8a7L5KkM(QT$vSU15 zT4v3bK2w#-(H9ECJLy(Krbtt5z{c^>+v#=iyB_K#=-D)p*e!!WmKT%SUlmK_HrO40 z=&TQzrfo?j{M-@kkddftSK}uTpW3@&(w| zla0qrr+XZQc@c)~3lV%&Aus%;!br%gtQrm`-$BQ07r zDFm!gnqcI4sbjOhP*^Gp&r6ew3a@FK#uWGn4PDsUYrBP={nI#*Eqk6Dg zG-GLFNw?JrQ)e1z5KLPKQ=XScjgn(DkD!4jO@nuln~UIIA-7a5JH}+~u+V-^j5Meu zh#gWIVOVfFY1hDlNbo0Mbp9w98A-sMNkZ(5$Wq>|PV@K#UAbIz23JYHqlbUYVxXrl z(u!($dAGf)E~RF`4ArDw(*KeJW6md1YW*dpZ)R{?hM-53OPIuA4;5ED70IIVtw`m2 zNhNK(R+OYWb{rd{u7bgHHB__jX5Im)8ATn-JdFp81X;g#@){&dKJQ5MQHVv52l`q?VAro3utcm&Y zZq_3@gofe~sa)k>pn!Z)69yWl%nGjYJQ@4o%HCB&6dvPuuJUIJNkru$gI`!N@Z`xt z0hbn-DGV}XYJJIK3>Ub6H_(R~-&h8G%M#5E53U!aSc}cNBHvWNRS4@tH;3&c@`)Zf zWLWV(l8QWz!t1_0BkS6SnzguNwT?9fr8dJwI{2qWk_CSOwLFYo+8EUEGDNmphMgI~ z)ORVLI34!&dKC>mZT``=l~z<6R+Xwqbj>wPNLV<`MgF-z6;N-}2y2S*45{{*V~E-Br|0%>h2RC=9DN zZ?tdx8rVAc{bnT6Qkzc7LwmWo7|EYsA`GR-tP8q|5xjzd}&J-P3}5$?IM;{2hOiviTj-kCR&|+Ea2?UYN|-;9^6cL zG{PX+51#$JOc`e9hmUAzNEOX+lXS%YGfv+8RJUD*V%=;3vckz~q%xd^+(;V7w8NLE z;lvclap-w^Ix_#mO%o}8*&M7qS<9W-Y062C4|rNhSpO)M_2e__dI)3VbQ;}|R4$1P zq^pe6i}&;t*H1J1ABHS%J#)^BI9pN=rwV2pw?@rH$8wUa4q?Plm6QhZ)uh1L@>Q^R z2Td>Q(SS*u3Y|x+Dtp$gPbbwyf93!yc7VOC>>qPi(AlH#xXM5Em9t?snm1fD1gW^( z&EJJ4pE?A{oECHx<$zeexnB#1celTnFgxuKq(e)VaK_+DigV?>y%i#rr|DHBQSglH z?od>_KHmqaRVq)f4ePzTryu-r(pF zY<;^$nh4dCgFxQ>T}NisYlMYSW&1z9I}6nDQ&9ldwQ5*!ECCH8gQuJj%m z?ms$Rx=@sm@jWTId$Ag5W_E&88(aX|@X(}z84{>^LOqCjlx-2TmRyr1O;|Lf4 zAH$fY6VsB1S{8SF9DHm}DQ8*gcvTV4wVA;#E=_;r6$M_mW0L*UYCUEBTyM-b_>+pV zO<*W=?aP!L@bANnvHDhg(v;QR!-;*x71--vmP>mp|D!bQK;5VQ)ByYrmXAcr?T58U zVA9h%nG_8eD)vQ`=F~Q|k zmNhO`Opnj&Z%4;l{0t1pEV&Z?Si+Z+gZzfBSGNq_j_Qf~J6;FlKp2-i1uR?bE90wU z<5snc&!5|fH;rD+%RxHrTJAfG_@YV$Rxs?hr<*K!(nn7IT8^nj3tYex>Q)%;YCr0m zZIo*gr`sJ7NxHi_{88?^heKE*Dsz|u2zX#a*;<(MK{xB%K7YG5vvt08`~I)Ek7W^q zsM|Epl~NAVS0541mnriabcvQ%1zoarAyum zSKdX;^d@(^Bav#aatS=R?-Uzm8mZu8r=eM4ZY#hg(ej0j8)IlDaN;VA-F}l}-vkI2 zU?-_PzpQKpa28O8b8%Qt_=t1Y6(i19{VfZv#G-1IwNluZ1Z?O2BY^%7zKPBgb` z@lU7C2#g>~m(pJ|jjyf$67ny)Bl-3}#JPett$RNn9#>^^^ha+;Qzl>?92O%K38l;L zjjnfkB+e@-XEY(G*gn(C%5CVJy$#opqj0(3uQw4)_4MMZUklEz4#8V6-&0I5K zJ3%94%v8njUqMkMc$Hlz#)~nMQ_(v8wycKv#ZfmWsxPT2dbzs z$516oU6od^ET@Tl0yx|z(VM+8*!7T7Z=9vY?cis*_8kklg>Tcf(yCuXl1q+QAn*S3 z^^0%oTCC*b6E>w%CfR?haqxWRS*)VerTre)aAE>;bd8~OOSd3kx&rLv~e zFZxxcs;h&JyTL@3!9!Zk^vwq4$~2KIoelNCA_8J(4)MVfNV<;49{jQrhfi}6t%^Dh zsAa17FD(U)YuWswTK9b!UF^42+QLjz-)jTnOyiz(h=o*Hz%=LyG&(mbaZP~}?0cn} zl#)v9FY!`C<%vyUd>oZVa=AtHD}D;e5yY+bv%Z;ffniUKPV0R}N-|8U!i-0Rk1gqp z;vKt(oreiC`%Iq|!!#JOFb z@lTEJNPl&-X8;kD6_QV))3hxRYsPZs!1Z7k+OUl7SoaW0zZdlLsDdq!j|9?4F-Q4g zv)Zyld-^_=%f$Dzi*go7P=O^-I~cj*UTex236bQ;dO5EwU4I6s+4;dqvW~lulBwzZ z>guY;xHJb@Y|`b1Xom@Rs_(mZHxpup^s!EjMaP(wF6Kc-w)qmTMCz?}YOjIt_6Ce= zJuVE0;XDyU`f12I8qc3_v;~z9;iA$m^Hla3d{&|z@;^jxNDKeucsuE^^yUmYplYy^(lu2i7S z5Z6@i%$Mr+;Iq)*8e{K0zntC0m|y@{cFwb>885&{=>#Eu0$oaL|-}- z4)7)y*yZ{wmV^YTCUVKP(u;W}Wu&UHVXpC}ILD`5dsP!w-|%7D^(Y?ogF_K@J|&dF zMH%@Gb`R}NK$pti&7;|PMTM?!2X`G6sfemS1$j=kXW*mZhMwnK_ss zQtu->`y1^@Df>^;ACCe`4QSPh;<&S5`)uF9L{n@NQC6r#G~e(SMqR(9q<-;W^zLAk zDU!pb^fkP7rj<`yJoa<*bwH94L>@^~!rq+SNv4T_H&XQLJ1aS|)mN02_N*GhQUA7A z>N3*Kl`@0Cm-g{vsa$ooqy6t(r&FguoDGegQY^$b_o;r+A-o(3 z+92Ly?_Gr(dPTeQj+v5*Y?YG10t}ht-(Ws@!fY9@B zKs>FlYbd^@X9RM}(+3=Dzy_{;%=+*|IO|1GItiiPbI2?B=Hh~-({8+PQCH$bwm@nY zpejWQqT^llQ5pvQG!EE^Hg#mpjH*`Y%pLldi6pk@ByJz(C@)$!BH1^sFdBa?#=-)$ zQZ+*W*e3yz^(0@c--q7VMQrhSpEp39JIXKq5|_+shkQY(bb!nSIQJzL6n}OZ%{d0= z|JlKHX8-O+=z)tH8E9#~n_#(zA10P*&6g=a^Dd!wSfBKSwI47divk-zcjMjD=99u_8; zV|hkMWd4u@skO-Y6?)Nb@x*$20_#-k<6T&FLNz4+mcTY^ixet5!Tc5i zrkhbT`_lEdOtw}U^5*|GjOs(3!Jr!XV}LM=C!aG_R$gvK6LFA%?QLd3>-1^+Xx>kb zQ%z6r7BciMbyVBHKxuRNq18vu(2$Hmd*_S^`(^w~KqZx^Wp3)1ti}H05d$^Si2^j^ zU^XN9grDJCtS|3vC3dGoKl!3OVeQ7yOgwT4jw|?nZ)u6~@_{^hsnEC1GcnUjc+)|! z4NGVIDcq|L#J5UiuqV=BC4h)+Xc|ERyv3*{sqj$%c9O75f_RGpXl9bRALTCOK^R*? z{Dx)={1%(afF1O-Lru1WUY2A;o?H%bGizG)Pa)u%A@G)lxEz=z{ley?7fN-wOTdn> z4t)LZF%d~gS36m{2m2`K>jT|9k2g;bL+1~M&h(*@SX#OjvYynEX%p&=;-PK`M&~yM ztG?xPdm)}{qf1EK0~l8GQEYA^$%?h=xe)zWrc%h0t!`_x2_vG zW~lsJ8pNr6ybZ0u3d#*P+S=L&lC#9zlvZjj`)f^l@xOdtkPNK$#?rUxV$UwGYIg7` zlz_mp@2v6Do~y7h)Y2KvB%)j|JS4C=gSM$6)@?c(E(T04;8fcOrdx?9{h6McP2!A9 zqBQodWQxIsqlRUT?j0SMmX40*4kg*BO^d;g-#uY7O5Sr9fNHuQNzIQRv8+62ooAw= zRZ-B7adQg`blHpn^s-h8JIko0_SC6A>@;0+j9E&jyiSOQU)b4UA01;>3uH7?NcL$- zXVGbC;bHK!KxFNFCx!kg!jAf= zk^bBv>EK9=UzotQsrzTsF$r-IE&+*>0a5QCrEe(w{st+5 z;seNH`Pq?Z)kZ0;CceIRcXxkxHXUL!TO6^GOR(+O$yzKWZ4_Eq5PBgFN@(VLH~NhQ znJ7{1#{sy>Q#wGBR3O4j>xYp)d|{Qarg~qpph7}5##Vgng%VXfAgz;5P0bSPrZ!6B zk1=c%k%o9K#aIMpj2%(WFL#D;9kMnQk zhC;Lln3I+H`7UA`aBRh|H~@9M&VYqb*q0HM>1MwTVxix)gPhiB8yfw5UhXXmYMN_n zeP+PU1hOwE(i8H1QJceO^zXhRh6F)fE@jR;P(Eaio1Pq=(&k@|ObGc^`|$HHb``U_ z^LJU;I`KHYGJ`BEEad4IZ5v|AMFcrHodMV&3!Tk?@N-Krfx(nT%~Z4VR#}O<$x=hq zGk528%BRI2zYz!sJx)#A=#1T_mx6=gqjmvLo+x3tH*-jY-bZua+uPfpo}K_DWng3g zr%~rZ@2iB3QU($y5^x@8B-%AXzjP)XSuPpjQ_zCn(*G7k#LS{c@#Vz<8Q$j!Q`&k5MbzZp1Juy;ZuKOkKD^{$`o^88U#Z z0O}Dg!>yHlq4cG_iaY?GwCjg}RoW*4@K{$rlQ_5dFqOmk%tPC#vhd zx~F72w&@_wsPrW6oH_``wJeuQlQSR@MosB!p(TD7uBok^9N|f30Z&g|90ZU1+_Dvg z?;Q#~0aZ!kj@G#)^uF72qy;;7#z4T2X++4w@{S={vM&sEKF*RA&{CLNpMIv7{n$vp zOyW0Te1T!A2v@i(G?}f2;ORVj@3#aT??3oVQ2x<~#M%=8@+^1olf;bzCEN~pKRyvV zEi3-;EC80=)&{g9VyIK6lC^z|hH zHPkn9ynwm_l_-D0P(4CBm&~pnHJ^gM@KRaxMEdD{DI17ZIXqJ(B&MczGIqL~!m3?a z!G3sX?g-@#f%ALxFNlZQHx`BtH8XYF+Bw-}@cCynE%s{4t_$TNn@f-VQCR92{>-wa z&eZtP#^!tPCNg43iAuIH>5#HK6}7Ajm)V6(*nm{L%2R1+=>dEdGgCH|^7h|#XqJQ^HLSHB>gCoa zR5xRkUO{`(&Ss=b9a3AHC7kG`*xKMc?Uj)LCo+tzBctouBOHA3=_{&qK>lomo7(n) zJNY4VP@j7Q)(@64+~8URTKOe!_~GF+Pb4kI9n7ud2Oy{-+sXsUtFUU+2sp;^URlCj zxzP3{O6Q}`&;TYRy22>Eaed6Trw(s7d;3g6Y}`Gh*uP+c#IBr#+PvUi)bzzOqsLI;-2)v zoO=7uoOvx}2 z@8sZMSZhAq9I?&nalG<+PvO{02?O8UAPYtGNJYNnN$?d8Z6d49r%nIqm31k@wBX~} z$>opdJE*z$|L*T^&VlILmbkhC@%?I|$eqimy4ek(zPNuEAwQgD#lXgP;&8gan^qb& zZ_CQeT&Gvr=6Qy}X29@{jtTS}t&}Fn%iYc&<}_D2j2|^`E8_9M11hqz$d0~7>F0L_ zl8gxlKVUTw9gXg65)bDNJD9Kw%29^O3i{;DNrdGqqAV8(fQO7w1iFeukgWc*fXeRY z$Wm3JJ+aB&D11wi5Ps`Ien{!t7f2`0`n^db7bPwcc&571jQW>{G9&Va>KR~p1ov@g z&eqb@Vo|9M@MOg!nCDDO4criA;fLh4N>@)8Flex+5%wIt!j&QNRFkVT3m&< zZc`uqtRq+u8~-v=XqXQmQd6U1pQalOu%3=9w}fNvlZy&F-j=k4OG%|9@KY$Uq-l*H z;Y2`L*;FCYKRBsEg6%iHG}Umr$*W}YDeG%)w@vm7YXV?CKQQN|=uE_Cuf|7rl&I&7 zZy&>q;lE!~U0dt%=hyai-pTLgtt}MI5)A$DpoxkPxk2ZCVaN_CilMbKxbG*~-wYG= zx%PdZ4DwQ^z#BOWb+)YNr_iE?od`gD&7RhR-<+53AuIUO$~UX^72r#V?@}8P#3e$- z>d@pRaVMwQ4BHdH&l5DhbF82^F$Hn~ZVlnGq#2_NwUhEKwz+UKqf;nQq+PiV{DNu%u$N2a&;a3N| zxP^@^yOBk-W2cDHN}&lpR5TZVI4NG<5_+XH1qg*|2W=0Va2k|2oi}6luyrRvzz?5* zSP3FlU%xf)d)vs%ONK&ULpnU1UZT!#%)xUGjBrXx$9>CDOL&Syb#E2aq#2}}o|6$=% zUCbec5^C2zA=#r+F>&u_uK{2uGH^3bn#%tU#K$$y4E{P>k|8MQlaP?0np1(I)Ryp$ z4u6%kqO)<(Y3~M}`17ykOO}+ro12MWzm&pzB`5;@0FBdO8TJ)o64iw{a8V(cmL4`d zu6%eXAZ`vacaWElF}deFR3XW>npekQVPYmh0Ja=aSZdZzAhmBOs75D29SByMT92FS z5&3*N{Iz=|=nPB{L1YCO3M5L7G=kE%LtGF_0bIsght@BUEBvyCMK0>CMFBWUkVW2sB&9NS3>;bh zNkGoyLTnDFqGd$!sV;p-+|b@oQ`3m%ck=T`G`Kewl2JS%U;O0a$35O-)o?hhyr9BO z=L}oOAyLhzvt!U-~an6Mfe`M6$aU#3M+0;6}{=Y}-xAc#*fYi{-GBWZ)>jo7^U!OGx16JOxpdh>?!S zKxfl#*@}>D+`Njeju`Iwv!lI(@>1r6UcyH3f_}(?@^gnoEsL-yto~IueNk$S|9zrw z>A=;uCXpD0YH*H9LrXL`vtf0<-*P)i55E4yN^2T(-Ovk^Ax9H}Eb;yL{*t?KA$Hch zjd2s-xA=O~G*SlbZrhB9Y#vWj7cS!6$C>ta`r~3WLK(`-5*%E~c<`dn{WxmcHtX-+ zQG9KTjSULwyjh?_MK7kOU!0peS-zBzl3EL=a6E^ltfnZdY34Ww6lbXr(66qv;_!8q zJhx+R{sARg<*AxUN$G29PX4A0)QJymph_ag#+O~&{x`S;DEF;@*9E^_E^q-=9pAQi zp+ML0v=wx%lcF$yN|!k(dVBw!ynOFQQ6vsfw=+W?yy4ByJlc{gqrc6mCs_RlTv7mN zVjnk`*{bs=0l(+a$jHp2@SPIdJHy>0E=%MweLk<-s+|*QKL8d@0cj@_u>tmwXSL;4v{278sHAR&)4qk5V)Yo*M z&7@0~?#|8^sc>7MDN0HB^^2R@?c>T~=La>lzku6!o!DiL?+@$KzYi~iW#uGVwpI~B zf0}88gxc!rE&=Eh&wB?9AVx-uaL@LTKC|m1N~7-uVENy8_mydCObG$&2>I&fRTUn% z4DLzbPgYnkH>@fhq&J5LZy(m8vm|bEnSq4c?xIDD8W)RQ+K*MGm<80q$q%j3K!`&+ z_i>NwU^BvorJE-GWPfK4)5uitEebE(nx_2@QKF|^2WkqIrHpu-^YXSoJMzZ`?;}S8 z6uLhI7y)B{OLEkk21(6)ha8bn(4iTzpD(5;m6X$AB`TUb`jO}>AQ^mnJSC>0Axtf9 z@bcG^r#einI+M{|7kP?OODqy&dyjZk1%*!}fFw~i+MY*XJ0PsJ;iy`>n#kT_9yEI> zc|XVBW-KA`Ci9{9Zop!+5f86{m$#p&-#COd!h|G699}VcL$ary9JdMziC~^1&L@i z3Lhn67b0$o54wnQI4w`bi0y40*&xHfKuqsI5>@c>5qM0Du;bQ0DW62Qe}mjuX=uv~ zznM5s8k9p`u;Fy&rK*o}B103F8d{w#Jgu&was0WN+G<=;^Xy*fJ|_kLCCC=^Yxv?q zQ4>26rbS^n3HYR|Opc4iaM0F@1k}~iGG3VD;f3`Syu7^8S0)2_cXU>;$eNn=)R>jT zk}g-ZdojjxOF|S=ScZp&N`a4~tZd8gZ!nskY>Z%hP7aT4QeG*;N1erDA0^8Dxy&0T#o^KOlo{w>R=j2AY#DzQ zA}g%M#pCD%*(N5SsUWLD?b}xXRAveQ92;QdR1_x?TKul<1lkrKCoGt$^mE|-W+Is?Drx@$o(G7$5*=m>QTa0YjqAz-K~hy z+n=&q)x=>TmDBxZ>&ths9)!-%%_xb)B;W*S^u$|2UlimFrDBQ6coWJ&!6#~}u&$!C z-D^vVay)Ouf;y8k@h%T=jh8*Aud+tZyZ67Q=6~fGZu7kFp4-R7j^CXcEbhn)V@2j6 z1}OsvUjCzagKM{ezVh17FZ4n}+>FCM4{nCS>`c_o)GlpnL_|ctRKLn!?(rrkrIGtp zpY~#sYy@^a>vZMUnAz;B%spcz?M8ypTDboA#n%2;GNcmTZx&CguE6T=oa;u;doqcBKC1~i9I2qI4=2Z-D%kb#bc9E829$r-B(jYb>T+M>Y9 zVUHLHZst*d*#rv4z(B^LVQ`PTOyG3+dRbZvTn|Tg)h>Lb!SrSrJm0v3nZmr(a|wuH zoSQ+27{fUmuIfdE^}gHZNNeNuYf^d>S_W35jn3~d8$af;ED`_3?7UgAV_CwM#Wp_o zab>=#bFisqe|XS`n7iQ<_N>lEFl7BQy|Lf>;QzsL3H%m-vvCjut~hLC!&0iTvsu`? z>JQy;9!;q2Ld8`M+QgNm0vb8*3!qrCtJc`Hb=)F}148QoxzG22egQ~bR~M)`_mx2E z0Fr(6$5{o6&`DuVU`w@oez*pt6uf}R*nZP= z5nn#NY(+Ft5<@1QJxVeF&qB6{LB2#*aPASbJ`$M$G4l!=uOk%u029^9y8qQufQ;n1 zAj?HzBuXAq0H96o9qa|{xKvpyR0&;1crAvv0IueOxJ+|UyJ$g*AZJy`bOb*k`hj>YlQ5ZHqSq##zB1+H)0+!?%Shp{XcmuVus zPOh7#Xh@e~$W>sX{F52U`+Ax&8ivz&`hVfd$J?#g;5SlStp@VH0|xW@ch8%$s2WZC zTnwa^N?bur;68^1%L2L^rOs+CK(mR?9#-o!Buf6*Y*Gdi`eE?YqhOErS5Il}ubj#| z4j>1!EF~<&HjzH0jmPef0qsxk>IREP{BFKbo%Z!ptDudysHAl~H^+}n|eJ6D|x#A1d|wu?<)LjC}Db>SQxxy_=`f{xDpiXd``>_}>swxJ(&4kOs;(G^u|c``ZCm=g5`ZvywI$SV40yT!}2djrK{ev{=oKG946M9W28{36 zb7=mSh*21sliQMnzd3KsM+OIfIhjTX%Thl&;EKiYkSp!V4@nL?M8MYJL;3`OA4VwV z(JsP6>j(jh)V>{0(ElO|@MXjv;(@p4ORI)fz#Vp?ZV{g-X9fAvr#=cx>R>w5+U`zu0<-l zv1r~{cAV*Iiz_`^% z{;qY+qYvmm0ASr`^9rrcB&uh)veu2ns*qRZzHw=n(CJ}C`D8LE=p}aJwcD1KnoC+G z-_!z+fWS^CODBghaz|RHg}bvPcdyX-+SbfscWQ5Z#RTmdi+0QTYiP+U;8VHu*VNhh zyiB{?E1!8n$z$xjbbeDi{?Rru<73djfjFz>Lh1eStE|mJ0k$tjtju?g+ z)bJqyGFsRROLj}^SUpuyQ4!r%kPoZXZfLit%S4Z$o}Au%m$pJuNm0RF6{xiX6pFr= z1L-GA9<<;upNtb>eyrnVx!fKF^0$t=r!#&p|i3El~?g~UgN*t zyK$y&<<_gV%PT8mVrQ=^C@269^g@NMxA#AVmmGTq$WnUz*7Q3C6mT$8dFmoUZ=rmm z8-g8Mb~;Z{M}jb1v&00};b6Ti(m+U^z=uA$!)RnRNxU}#usim@2rukg;bKplW-t-D zx?E6xyBC9`ABuWA`Mpc=pslUgok=;3kYQGxbcV@s^d}`{G&j$4v3EUIILT6xGFB3G zz1?4NU5)&;6&$6#S=EW<&6DRb=;+owzu(b^-&ksY9zFGr_%3i=^4|U<|dp zb^xr``g5EF^TY`tsD68ar1L}d{0XdO&ixb~riqCe~X4Cz@!eFnWI5@|q)zV)e1RB#SaKX=a7r7&Q zlob@STVNVvKjB62$g=r<2TX_vdZyQbAei$sVHj6>w-1)Y9P`<)HXFvsNLUd1X3?D+2; z(~ZvKp*jIW#**fX+dziZsnp}m8x#3W@vG)pitp=CFsrECZR8>|qJHrVS10S+bHC41 z;$TF58LKy#jdFwvmRMS~h60MT2RoXeW8X%vF+vj># zGPNhVR|bOqydznV|A)eJE}0UD`s%2YYU55ee8>ty(jS?1Fz9IAiJ-qTU;_vmr_3L! z4=)o$0tfOGY=m;K6~u^!H;l~Zfh=}|r(=-k7akuaH}Q86)dl-JLG(RNRd-(>1o#KD z5zJvz)1U`lYF<#47H;?Eb(7Z|odo;Y+wSZH0IB+N63^|3l}~NN?siCN)*)QRVoTab z;}2{)@K}K{N2!_?qd9Cux}EI+kBE^T^e=@#U&YiJI|v!AWFY(KkdI7JP*ck~!Xz|1 z&@`}Oqa!0+wcOKlUc@c+_|nC-SoW-B5T3MbwsZT1_O80R_oQNn3XYuCiTc*X?btYU zN`N4ylC!O!TeYXK(Dui6TY$g-^xdz49!1h{bsB$WShEZ~%UHsUApjslIUe4ALLbzp z!RWX>o`h?5QqR&_V2*qyxC7SO6=PT0{|}axbCCDw5@J-1L4iz!qQGa|RaQN6X+6g# zpdY==GIMlzD)7-;?J=2r*B6RCWf!4mL}DL--jwCuwRt%BjMFQau2x$;rUf#8}wahz~CXP7%E%iL$s`#M5@F?!a zfH^J52z2J&>iAvC2-Np;A7D%1bX@nmv;3{#n&0A-kcfuQ@;hpe(Os=bt$@*+mI$F# zgQlM*5UUEFi~PGJ@X3d9H(nhu1{#9RZ0?-%L#fhELf2*OV#>lDE%?c zzkX{UlnKAUs!W_-*uc(|4`%bVIFMa3Vy|-h`X5k0M%i@--~)}&Z!XstBQEYlIE}C_ z5Fr2?4Si&Xeg1LkzL^yn81#zpjT`y{WX^t`uH(Obm2{7L`-QS6)NQrBCrRu>ZtqUX_IOiN6_aYh%czrprgIkz;Gb+RGo&B zl8iR4#)$k=;mKOreVI>CpZe{TJ_A6fV50=}(d@^IWSC5x7QrP89u&dH6JX+IYmt|; zg!Ld@bUYD%5-xkJx0!u=nS!v#dYtZ6bUQ&Wd|SzSf4lfdvF3A8Tl5m$ULkxv=)mCO z&VX@>dw0o&6DUkm)wepa*P~C-q5eRJ3HQi_nTearEm&3Fblgv1G=->N^k+u)DWJ3c zgIn4_Gqz5^Vp=lm85A;RqG+JDo@Q+FIC1;VYyd01?pxgDQ#K^f%4%XMKj$3h?uQ+L z;p0U{R~(03fW31(zj974G2>Fkj0+_%@AbOxSvI#->=3gm?HQ9sH7!xyvHx=6mpy~a|CO9f<(^Fc9ib?YM_?@#feXZ)ERt2IDdXd} z;xC~(lDMg;kuN1$sIQt_+pGg#ovEHA9^V>c6a3w*2>a@2$k{He^_Q))cIv(p77NVY z@VKepCHkQUWlbk?IUohcern?YA_X2<2p5{AvGk@c)3J=|{PsqR!v**j5Y7CaA(;ho z;>nDipX1}>yZEkm@2&FkCd+F^@1laGAU=Pkz(jEYrB~Qp?;`iL-07aIIM5OOBdgT+ zVThI?|IzhdE!N9Bl$+(cRzacr!Mebw5DMjV;ob74wXv6W$MdcBigrUG(FM9DnaMO- z|DMun+uptL%zyp>gDs`9S3CHF|1k5ctgQYhf~cK~-BB_OBvsS%KW=OZ`nmU4-Y6PP z=JHizV@k4K@ASU{*k5BKAMxSb;y%__B5q4-C(c3}MvPrnMgR(C`z9IRygn!vJYysu zOF7Z-LLmO{K1^|Bso=}@V{O!}zKB~!A9cHkP&)Fh`ay5E*LmPF^+F9-d9Ex!w=W|( zHq}=MDX?%{(hw_=8BaD7fYC%`-BR>N*3*x+TaLZ+&eYxgnmzD-6i_-i`_*ze43;0?TcuAwjZ%c-A%_5cR2Mta((^ zQ|_L%iz5<)PaSd=jjr4O?*INR&amEkE7Yj#s-$DMdwM8v*GFR~wuFt2n8?j#9dUQ? z|F{5E2KQ^uu6ug+5v&fZs!unI;TYPlzuPvtT-K8zJD2yJE~7Et_bRu|5k)w3${9Sv zj!jNW)tkN>k4CDhFd!nl{S)=Wx#)Sd|K3cqa+SpA?0$8SKCpJ_&<(IPz3+N`?4s~F zpemT=Hyel!rwH%@d_V#1TcZx2>rAK4<*6x3LH2%qm6FSUig3HB#*TcMV)r|Vz<^0t zS=kZr3!{2#5CHeCE3&ohOyx<1g@s`X|NZ%Nf9b%d@8EC>2mp6^U+xta76v|TQ>->Q zQHTXRoh;YE1^vw6wIdI>+XSrHEOKQR-)PazoM1L`sXis8 z|36y$Ygnk8=|#euSDblbfdMZ@e2J|S)VU1#B3FvIib8e?LDJKCNyc(8%JD%1z+#&Y z8!PXe-nt%TiGOUj!83IELm$W8I`^sadrUrvJR=jtB=?==G{KX>;Nuo=2s0&Y)0ktYQa zyX(f};^ww`Hg`Y%RkV?r@i>Z>ee3@*FyHC`!*j3Srrvrz3y=iQ+0X+BE5K;ZEueAi ze=$t|Z;y%I{WgBNNd2ezjQi(uWoH49*9W|AUV)OYd;5GWS1j;wrbx%oJ$c&N5BOX} z$R{xa?|LI6BY~X=pi_U=+HQf(%f`TPchl4*VmX%9_NVoD&2z&aD6;_xSrTGmKzi;J zAS=AC0{S8=4R-&wZ&Lmts_a*qHTr08E%TB>zW;0?I9&I5WAK+v?LpR@@i#c? zi1Bm_o2x$FD6J>b8ug2as_0p%Z!5|&1aaam7FW#@D+V7#{AT9WshL4R+zo#B7pJRD zVwYpwkgIMailo%k{oUQ{z?XXf$Fs4qQGMC_zM?q@wa)k53W|I_YkySHQ#g8m_ObJi z)A73Bu`)F<($Zo3^7i&F0*ML3AU6@`SBu#b+N5_xyHKOPJz6s8Vs>yH~=8=fFm{ zYaVTF55vo%!$mgHyO+IR@`(Yr`(pmp{+VLGRjYOFj$(K5cAUIlJAV9etXppHGJSQA zA}FCNc5`!k+MyQ{@Him^=~gZPQup7zUffRudL3}MUp_8BJVxSEKbXu4QLwSIGclD_ zRP2zm8F%`ft~98M-h&_O8XDZkGkAfhDo%+7G+sbJpuS(83;@Jd2gE6>Ek;uojRT+i zB5(q_x=Ko{0N05`RZ-`*wI~Ai#$|iJER8+06|if%SnPVa{z~HLb-U&n(*3R9bh+L8 zpZgPVnaWK}y!;7=2^^&^z^gGq5&KIPs13EZqQf^t>|uH$At4Gz&TGFc>3fT<{`Y?W zd+SQI1sbSER}*MF0j5GDTJM5?P|BbhFJ-1VOGcWJV#tn}FceF;0U*$TU%2{P*jw7a zMd5s7w@0U}4NYBsiba&woD$Ju~*>>lwZEOjuUj zby4MK$3Tfdv=2Gm9l*UeCnF^M?I&!)&ByTP@UMZfoBR^RR#C?<87|B5e)(af^=gA~ zBI^SEg}3eJMRh-~ldZyejGX`1)ke8o(c=IJCc=Vw3cf~~Hl&paLxIllz4`ea5Vuo~ zVX6F(UIX|!?RiYjAJ}Cqf@3Ac)k&qz5k-4O=W;h$+javyEekBZvW)@Ef~pExjf@#8HDF z(7oRa&Ae{~$|;|nt^TUGVx5S{nhB46famP(%ZBGltD}^msu%C zc-gV(a(4~L^|rQUqq}95mG4-wx;(4=U!DN}?0_La-}0X#>2X!p3oyLRvdHUwVV*dg zl#*gux4gts#O{BnXlQ8o&+}$-pN2Z5n*&gJ4tTl~I%@~)sVaf({P{BnH@7Q*@*^N1 z&?O$~Z#;ZRLJA^O`c@b+w3w30PBn7%IQ#UXM!fgCd!@yddoWfRr}L(?kEqZAT>Vp; zsB`JmqlT7fWo4xvg$c3GmA)u`BRDwt;bH0!za%&hsRMgO77S0mkes3IOoVyudf@{sI~uZx{d4848}w4Ow{1z(g`Ba6W6@cKs+qe*Zb`IU zJ9KG!Bs6qi>Y5`hkctQp)!##BvhPCpfaR*FIO)uNf&wD~u8Cxf-6qu=VoMsnTepFF z9arUwuP=Lr1vpM2g0bm*)=oWt~kkZLP@hlx=!`&vbJ`Zg;Yq~){lQc_w!`ov|NH?-t&d!$ScW+aT zxqKJKbj1{F16!SLC)RSuGI)jPg$8ZwVp-XU?ay2VvvUDsL0MT@Kvi5(F>3L+$mFxL z@%+8vxW{EZvk*p-2d|LEN%m;!FHTbk8;S#gg0rA3(Ji@TLRY!mAcX>A<@?J6G4&%IRET z;bi16dO~zT(pcbS*Vm0uWz~m=fj0$+W3{!l>608=n-N%$N=df%+w&pi`o=`*(~E$W?a6N4iQas{*{v^f|GA2Z2R^n@(vVabY3y!30U1*z}HaL7+i@);2KD~*Z{k{jbvH=8ACFGe`QGx|h{nkz$DCJMM9GJcL((eKEGdYrAfZbqZE8=d8aXdC4=H5Bc}7J2@v z_L8@;S)N`YE*}TX+wXq08-#SLseSa4`qX_#Ny|_ACh@!bR$t=fp0U?+Dy;KnaStYz zZxRPBUaAmTUT(PD^DS1+b&y~3xt@m;S%YYCd0)8Yk1IO<^$v$xe=u4%F+MAKzm_CY zY@M=P`y9!<>gwuv4V1;@avSQB2DmmTl@fBZ!G0()&4b&e6c;~~JYgC<|Vb+53f z==n1D)%>2dVA|{T`SxtJ2_|6Dpm&dY2LPnar;V!tw{07|@86@*X5mS)GyO2`x;ZR4 zych-A`dsU`SF?L{0c0BOB9Y=xQ1L4M$e61aj75D%H*^?1S9N$yEjq1y51c&L)Wu99 z`kFshmET2t@vj5%0Uv;vz7-G9zW(=Pp%K6==7!4ZAk@mLFx>-KY6FDl$#U#3v%PFu zkfkMdMq(kPK`HcGGyoosEK#Fgt-z4g9+1xU5-OcJ`1)NcWY;b1MX5L;eTaKp39P3b zpc@u)CZh%gFww_7lRu3P7Z~}QyMO>7#qGsO3aujb3vOIa&ieFpUiR;V+}yy2E1L-O zEtZZ?^`Q$lU}~Djq?rDpCIRA1lEGN=#PsCd%llea7ktBpA=|o%F4F)jPXZ8cBTwMv z52p;Jy>W_m&*`x!?pbbt7R!P^dJl|B&8;s$cI1>ZO?k*ChL*H7{3IlM){}NJwt!@% zcEZ%kv8XG?epJ~W!h_G^MH#8VA=|#Lyt&fsm`!K(Z;Hj91HP3@p?9I`g%5`K+@7|4n@YZ0dHCWvl#&xK z>Rnb+x81Jlc^gY?!9$Ez5%Jg*n3j;UetiBB=kyWdx_rI`Y)qi|?)$Eq|(f`JpKE z^qs)y{;H{ymxCiNF|iJC@E9cbJ^5GTclzD0clhS|-z@9aSpsqM8n{flOG}3ho439^ z922nWx$S3r)=KY$mxE+nT>i~VJg#oMq)4j(krJq>Zl|WE=yUzJfY(h+yPKA!KnUsX zdfH{j6npv%XnM!f$U+YQ3Jy=Y5}*|MNjWt+*}Wf6r~Pt5D3MON_32`igoLDM)$pn? zWXv|F($B*WQrO^9R8yN!4K*^VN>nhqFbH)?{nwk>*c|c(kix~$z#ki`T0W##O)3kDj!b_4`pqJ?=vL%nd> zC>g@@k;jN6w|ufCZfJ(A-ZLAyOei%rUi(0Yrtlv=ph#&X6m@MVD$8EZY6_&=s-FBI zL4KabB0kL@8YVI=%#T)w4sCvhhA{e7D6hJH#7ay^n3?5%I!t5W$WXQ}mQzr0QC00r zV~+~YYVm$ohIwyMY*p{hfN!KKuX1>J8lPXv#=!@Wi;0LFdfxsiK$ThZ9z7jAiY2S8 zWF*#~TUhs4FT4zRn3`OIZr;yYv2;EE*rtzteN2QI;i5-l&RDl~{C+_q4tSP(4T6K1 zPmB>>&ILBMU-{h%kz|XtZs=+K>NwBc8)FHXKXP(X%n`Br8@@r4zq27a+p&}J^U#O7 zcFn_T%m3EXh(lm$!^sUFfWcC`V{bYi&&-Y`=GI<&_0FbtE?RUK*M6@x@-EFfq-*~X zGgxc8$h5X$E2#S!my&U@pZXMD*1p=5t}vjB&qC_;v_aC;*)^RWxLC(NM^SO$XyaHa zy3^_PVdCx_#?tbqD%(L-?7H6WD(zIL@%HLQDU-|pD2cJ@SB=}RK9u)Hx4S6Y16{zj zuv@5LWMTO~G@WyB-0j=NH@4l_HXGYcnlwpcHnwe>4I87e8r!z5#zvwYNTUEGw9UFB;RD~^tv|K?o~hHO1P-^Id^ zCo;V&+_M|X8FS6E?i`gc*oFeZ`&8rHDHIN~&qHtBG{&)!|(Za{A0dGDeU zrin&rL3*gW8;mJ04ilxl8>T@3MgQ|jp~#rCku4-ZP&zE{{puFB*MMcb-Quv9zM3s_ zV$IE3$ocO}Y*Dk&)m4yQby~Qps;aB?re4>JTehEjXyp$}I;L7ieb%daR+x&^@=ylVrB&8qv$UYs6FhGUc*Q`@P|<@@oYvH1@cvy+CwoXyyU zDFT5X?~Zz|+S;qTR#i?)&eRkX1VRqp@2AxYIc$`SUng?n{}V>lN)!bE)f12}xHsMR zdP5NSB$d31SpODv9<`}CmY7j*zJ82MLhzY+zwFKy$=%-E0AT{3cO^o=Vza2EMCfTd z2c!9bZ>9fig$-48_`vJsCmCQ{d(L2vDsNUj z!W_oy;1B#>Hs#`b`bm}_Mk_0Qobe;6cBJ|vV3;I?b|B*L7ubCxo#>MNayUc?&vj4; z!}T6JqE^35wPyjgjXJ5w_)0%UT}=c08uoz47s*KNr=dxT!s0^LM`sKbFCFndOYMOL@-9br$7a}unzsK8^#$&R3L}pP`%SrizD_*(bk>%m z0tCGJvadAlWewx{S~I``+aNZ5F7af%+S+>AhQ+(GfNx`OB{4(KFoK1KxyyMxomFfj z2eB6XE9*W$H0C0E!!t|-L&cKXRDZB-M!phAy z%`qnubJS|gh~7R~FfYtfQom&3K_C=^j!6lz)J-(nPU2f&r`D!sY^Lz4)`@(J}NhX}=Mg>2P93#tb$d4XO%o zCT->A59A}l(Vk=64smjXogr2B#i{<34ligf(QH|ab(FR;FvzQrL$fL_Dx!Vv%pp41 z!xLyii|YmNzx8KO1k9f7u(IY=I_-ZgtP^e!ZC{SoTJO-DpCh7E7=`mx(WiPD$iA=- znsz>+18bAp^No$q?WvjXIoPA$whOk0@9;Jr!ikUgH_?ltnbJ&OpaK_ILYr*invj*? zmY{XS=fy%NBq7jr6SMiwg(bokUT_QzJlFqTvzzO(&9nc#?_dDA2We=n-qP2lb&$h&4+#q zB}qVIqC)oZh8@QAK84CZzMIP@|JD=thkNtvxtbGV>J27OCX_>JcVi1JoCQ4z`tz-%yH>d>3Pz`F^6es2`KdREF|-X|XEj1^690qc0T3_O zDj!ZF=^iq09)9)$Z*QAy_aLt2I)WGXbuT6QTrG6q*+fUnCA@q+V3xYvczs`~Cy(xR z2TsCg$FkMGF(S`@el%Ksv$Q+`>fGN3@$G8dqk2VfW5kDx#_-^8S4&TOZycR?=q#)( zcS$v!2{RV{GkS#pgPH&TNG5@Hvdu`i+H&j6&!%m|_;lHkDFwj|3T8HOahZ|SkKv`L z@Y3$JNi`~!_>9E)MRtN89|4FKtz(7CNDer7Eyo*2ZO#nn z;Liyb2}pRY*)thkAIIQwC={(k^znDGNIsYHjl~TdUbO2l2E>#@%qEriWaX{u;e&rr zvv_G{e6s_C$YjMXB~k`gD_E=)@_^n zb_{5%wo=zef9^?j!!shmO8N?knCs zfb_WTgd)-TM2>73e#@BuC#_n($i&o)P7K@hpRj1l?leknrBMU!3=K-)O$dofFbqxb z9G%hGteLCHGRE2~bht%tY1Te9F6hF+-8Nupj&;n0dd+z*YbA{?J7M*$I$rk}0AO;X+G1L2nvwz(zW+8ST5X ziyjLP7b*#nK|s2swwf~}sf0EyTC&m$JG7?pOlY6ciMj%2P5h>oeY}{wR&-$dHPks+?2XK2b&-Rd6YFP%Y zy8ZkpCO~d2!DL9J0vi;oa?ir~4P31Pf-!($g{h)Xq(TGubSE?ZUdZ`!wUgS!MP_Mb zdD6KX8EQWt{srt>)-RbNh=~v!u(mVAy6f@|KgkbbG)lL;CiJs;JpG7DhzUcz8>A#) z5OyeD{nCo{l?XB?^uJlbT1p{`jO(Bsv+iF<7l4{1Q|yEV>v{E`j)s#MLl(grn%~`! z7gf)T0MbMe&vAnk@HJUh{6W?n_LRg+CikGZaK<$hN8g=PF(IAbQT3;v97+6lb$(@? zJ`7DvD|=-e<-DMN(n|(du6b@tD(e-eY#)W+l2PuAXekI!K-|_vT>Ick7UMxo(a=zUL!6ymXLYr3XTXm$D}aRO_y2nV z6cF&uCVqu%>Z(W5DLK6~>gV#mzZDQV{-PFIS^VCiPZmKVG~lb9ZZyzij8@XOdDpYW z6K87^uDN+bbMeXv(~5wapaByB#I3LcPfk+syUGcTOfMNQctj_6ssgbp036N>_}~B- zO_ID&h>YyBInRw>#dnSx*#wFldd@8PlK~mPp(0BsaXs}(F?S{=8aQZ+oy1}ALtz8I z-XLOBpsan9+m@87@2QzHG0I?!O@i*bke2M#Tu(Y|c5y8({%q>d{iVp%8Sk#NM2&2> zx7Z-pyr3@Eqak0zBA59uGG{B2cy_$;|9fo4v zi)YF6AlHuIJ?XLH-iP;_6Xz1yZ|h7R^g*Lx8C=~)W~)P8sVeZk0aMtXO0vnQC+i~B zNwDVC82#6BoqZmyYNUE+OuVc4;n8w+QH|cyB2cuGFGL~8Xn5gOZhE<95#h~$;NWt8 zlald1tmamVC2x~P?Y_sO_H!SG4->`~NrrJ}?a?4l(< zcvGlEo<~mxhGMpH?bC5l^K5!)lEH;L`R0z?H90&{l3H1om$dPj)eNMr@?I8f2z>kI zwlH7Ayu$){$cPWP>#y(s$h9>M5=5&}Apoaq>tI|p;TQA*dTeXjbGTD0G*ct&$gdhz zKQhwOrNvdlLp5AP`5lR_|ETWnGh%C+nwt@6H-wWFFx_T-?PS!UxhT8K<<|3nPN6U) zijdkduI>sUiHy9)Zq)|}^t*mhvhXEn4)Wos!hQc)qMg8F9PheUjM;f@{ALLlOUQn5 z>XZl1DOmKSu>wiu)wpDKX({IFF%S4ti#;sNVhgl!csgTDGRIhloD0?PLgtUrn*@%7}snTjJ< ze&eReAs$hX?2~0mj0PE7j`I0s=mzUekas<>>Q{UGL%bJs3(S;jrPZ-)lgo!=X5#Ff1GJ5|aUebupFY zyoav!A%A!A_ALd}f>vQ&w2FeH@viZhU5RCjA|T>S=KdjxI6@*ht#Z2aKbD zHJ^l!1_2$WNCQr@3Sw}UIR6dIb!*;|OouXW8Il$SWPQFVRX#~6Q3*V$kOJWxstU_J zqFgk_0Y=c7Lw~OIZZ7nj(z={@(jeq>lS%`k<*f8@i9(j6J|03V`I(_IURac+N}7AUvrg!>SU*;Q%m* zfu0`2m=pPqWD%h z*g_!uSU(!^2sukmOeGqK`SPj}$Db5*xQM4Lk_~Cm zND0^RtZ&q7+n-N*^jJ@&zRL^*23kmzo!ctL%F}R(0mDW#u+XPSnD7Il*Gak2p@IHg zf@D?js8GWeG_dZcrnBm(xbXN^$Z$4KP+oE(d0oCd1~qvPOA4T0PZZUwj z$wbhobSrR~1TChi5^-}l=oc2%vlvUr_k(F^K`M?nutz^*qUYJ|+Cc8@4O&Oa7jTEy zn@>^IoCV(e4yPKh%1uU`-OipnwzMcEH|Vll089l8=X@!US)@qJMMDkBCp6ilF}DQ6 zo9C{Yli3xzAhO#yKWm^3X_-q$H1M5RLTZd&fO?!9h@|?>;rKw~uXbXe03^n$Qp8{| zY>Fy5Cr{4;X#u9rfzfEym|r3E9CJdLcOWC19p*T=ab$uwQEKjP>DkjL^e3&zt6ACMen=Ts; z{Qz(D%eMzwL-X$rh|u}`Vp?i7f!PF#H$u;!*5n!RFJ*cr%T2(+f-j@aB7FZNo_Lof z*%>A-lHxUYjXm^Jjw|`j@(f9wi|z{c12;Sx_y!jpqHNf2J=!KS9R2$?R&2BTlPMP_ zWZ*q85r(BBQ3iCYK%8>_VTaQ4|Au}=7z3O0CJx5-OAcI2ikyrNTP_10Jjc_QXUmEM z2NL>J%qJn-JK-l|T>REe;*7>slVKBA*MOep{x$ZL-EVs^umKvtpqh4#2Rg=&k_+UN z8bBuA&4%iMe%3~v;qc{08^~Bs6rAs4*I}i$MpN;4E;21LwJFi*=UDh-U>`fxyyWvy zG3JN!Q&D_>^Fe56%RAKORF+nTeRn458(iAh!S(cVEyn8Vuks2k2+LOfh(H?l?hm)_ zPT2l@CI_8BTz83|BU4k{^+FiK*VvY{{p`}ujF@vIA5{^?FejEDUem)#^m3Vi{yZ}F z$VEqGgF54}NP?+_1A;Y336m_T>5z*pQ zWDs~s@Zg;<)47I;(c*{Gd$z;gA?BqX!+godrC)ICaM82Q&s|I=g|sej5sRMRau&Io zmvH1|6j^@BOD4@+qCiHpw!Xf7EYBfgC$Vndx^b82%<9a_EkcER z@4#d%D9_^aTmB9ND>p}BBhn2a_Uns|f%h!a<1j$!WCykWjtU>5QtT(ET&>v_Ti;&$ z%%i|J7q-n=KZ610?5q&*u$XJ>t*BK zS99}}xcTIva=e{$BM6Lg^@Xfp_s~r#XZ%lj)$9FN?x}Cyc^N~3HF8_uGJ|swy*UYs zR(*}T@)MC7p&pRGi0Ml33{#)H`J;ihmvkU{3Y!m_hr~9UG+)&9`QkQbx%Iurf&w;G z>CQiu^7`Jtwkx<757Ix4WxVV}SkrzukZ!tJdp!DlE_8YQ6Z`cQwLvt0luob3k&;D^ zWDmA@ekZ~HVm)cbfwL&^n_cyN-wSDPQi>p<@ zOiCMpdhf@$=~02r%!SMAf+a;D_~oW-&NIq7)3XZ}jP<_GcTGzM#Yc_)gHA5kQ8BZB z0u{RwGAFR48xq3VR({d4zF2SVv0}cu$WE#oDex8^c~TpNPw_GP({U77m#j%KEVCUu z1MaQ6!_A?-n9MRGG>MWB1}~&C`oeP8NQ~rV$Pr{)J-oDy`)I1G*vottusq2}+Ox_x z$e{sD{-GX{=zY<@rC8utH1;=A&?E-Hz|3$wq!65uytMufXVSx@s@k;})RI+KcMC|9 z%VrGhN^~~nr!N%9j;gE1yK^$idon%$RO=X^uEcPtJ_&&}51_gN)xnwK6Fx*PH1^kJxXxNjNqJ3K9e zYc#7WnNMv<(~=M%!Q=^S#bIiHZQHuP#m!v4Hn6R_>U{LEaB-O+Z^;2HARelI_Vo6+ zgXf_(pNKEl4|E@!CJmK6`hqn;0Ixl~^lKntOgUcPdJ=nIG^q{9) z$d{$$|Fhcz5@tGI2|naOGLD|DG@R54&2ESg$nYAs=NiL?N(p;zyJiYVOsOa$w)MOj^EY>s4pg-E^pS<$AN% z+jo#^@O#S1(ib&jX5{a7eott-LH&ux2}`9`r*xgO^(gFRh;0%!^PLxuriQ;)PB(Fs z!l+b~B5|0zp)ltJN&XACG~&5{?n~9Gkr=fl0>5|yE!|?+PqlYc+8X{rNb!VAkLjy{=Jcea^ZTHuRJPk9 zG#ANZMkva5-$P29PH#=_mRAOe+O#=4&_8*NrY$j}<@dFTamy zTP{EHu6Rk@1lZqvr%2J^NgXjU8oDiOS(!gGq4X9 zEZZ`RDVj{T@qON=(F;7n`Q-b~{OJqAiMe?OHTPHqy}^yR>WkVVkmz=`Z|ES&DRcxA)! zYuL12r;A~(40Nu4i(YqO{mw4OP34cmJX?QXTiu`92^ZwE4ef7Xf&&WnK1ckLm|#OB z4$s2JyuJ#?enuES`h7(zD!&5-CrIIgdpj_TqcxlGXnsQ3_8%;$bt9mu)o#!1PlJ>F zJRh72%EzzY7;l8d>bx~$`(YCY3c9}1M=-fF=iS&*WTknbpM`7Ue#UE>Q6-s0J*tcF z72-Nk1GDxKR)n|pPIPxqbHwleOk5q^j9+&Lq5_N%x?}9mAn2KkPK$69g`$5i-$X0G zr!nbj>*?j>=HiI{sU&2uDn9#Zy5Hr{mD|$N;@Q#J(13~iPxay6(*xKZI}m_k_e|=O zYQNvSJ-b2t^}H_^VsXHIVwUV}I{%MBsjsh(ii#Q=8{4t}z6mH|M_k+;QI%0vc3-pd37N4DF}$41{+go$3fk^bi<|zBbxf@;#qCwL6wB#7HAn9BpD{FxifSOu|qT9<#99R#1L; zwS1bS&i*B8@<@q! z;}H}O4z^f6FDwe1rlZ@uVCkk^>H4$F*UYsF8~t374{gjYt(=U&wFSRH6mO^8GyYNmtHPTf7CN?w<@8sd;+jXQ$`!B+35%x;t^d3fZp%CLLhCzPx9`-(g7idS54g@{PS{GYvJ) zNSmR*f9>xs$y3Y~yj?bqYteOcGhSmS_Wt?vxbgY%q=?w}Ii+jT`bWpx{7|R!bD~h) z0bZ90N9oe(`-MfgsAQ9TQ1{gRIFHQR4m9-VbJ6NE=L{|CHZk0GY1D> zSJ#_ZG3BrTp=KJxR$3?zHA^=`LqivrZ{lVFOy02 z#%m;`X-zjM8mVUcIfA3QrySF+`~`a)1q3AXvw z86Sc5ZA3{TMp33!b20HV{?~j5l3;JbQ&l_K#JCg2XF3^}V{AIMMmHS+=jh4mh@elc zda(^-US%`fgR8tXNHZbYlopx!pO&sIy5RaY~W|G^6~53sccu8?0YrRv^HF|;{7Qh;aG7Sg`-t7 zoT<`iH8W#YiKt0Q!a-3C)Mznv@~(6#@I$*Qd?uHdY1-$9l@lG((GC}*CrN?g^)su> ztKt2wDUmRigw7umz=u~6fWbMjAk4yMj5)1QU*)ooKWt#Eqs=1xhnN-7U$p^wV<821q zJ>QX5kk4+Oe*Z?kjSmQWvT>Gdd>;&ml;zwfCm>Qim(`^_wR^tDF6)!JUkp%8MCzza zR?91T^UQb~w#zYb&RDos-1ijN&F(59d znnZN6A3O`Rs+XwhFpTLAho#V7D|66wUd9b{t&d%rK9)XTxvi?-7Cw)8gs)&vNEhlO z0ju3oS}N!gB7(>ZOU->Zg8HxB2pC9B?Z4`^WRdEa7$lh-zQ=t4f6&leBJz6!1En!< zEw5FK9{;GXUttx2XSPZwB6KeSG5z=(FHK?pPk8A+8j%?a#N+dFmqM@UENNN&ox$}f zilA@oG=Z+4ozpjZ^G3Lf_G^W1Qxv!DA53^ztb4zclC!QiIZ(;&wN*?g1sK8d(B6`s zx5_m-@L?3W_1UQ}cYScMYxn88o%z!<3FsoCK(=Y4J_g~S>1QKq-aXOobLKq(NY$nPKGGTfM%*VYnH88 zJqES4y2+#|_rpFOSACDlAB`1UMA$z-3og&$aMNopBUxCR1hQ!Yj1(D~9E=n+84_~L z)bxWiIK1Ygke+9~bWP#xvPm}MGo7xTVu(#JSp$u3u|HDZE+lM3T(G<-Rranh_+Ah>&a9&Tmrqk^178eqwiwCwZT8 z;4jbC8}x3|C}-?> zxJ!OnMTHJB8d0y;P*^wxiDoMfKZ-FY*m4{#E$*)ASTkKhf8~b%L$0^KbN+sMJN%@9 z-ym0N#qa;VApo+n0*d9FHee#gl|FkbA3wN>(EXjB2lPMIt4)HZmma{P_tbwY1MP=u zQ*=ave?!(n0x?5dO?bb=jBGC+9$qX|z#IgF%SjMG?=?oPerp-%gKS0iP~!#c&Q&G{ zYhetXl;6^5cU`2@(UaXm`^Gx^x}B}w&2z3#80XxU?yl**A0yssQ6KBVf@D|-zZqnl z*+qF8oiOsef9G5#qGs1Raj?+b4gXWeOi?=)Rg$%NH)oObQC z?fSN*ZwHq!-Va5Z9h(>z$I4oFZ^N>6ZR*o1SA4&8RNm{Wm52W$h$_+<;8N5ai@Eg$g_W-Gt~BN2Y=<;E zGf)q{mDrC;h0L%N=C|*R%i!Fp-LR`c+ECmPYW6kpZu1P@!UKLqbz)U1I6l~Z>E_LC z(303-GrzZivAnn3{mnMVF50fn3C#tkyVUhW?h9>M^IQBXy$azU?-a}bUS#w&onj$K z-n*^gjX?dMGI!Y6qe)3bMF%1k3znR}?ma7iFn!)h34K8sa^r3SB2B(^EuZ-8HhVpG z4vB%=Gj+MYoKEdm>-%*zHBI4`-e{{Pc&FVS`5n2nOPZ}~{E}BtI6pfZcBM#Uz=X%Z zD3dH`>C{_Y!OI9^qFl0pnQjgeoBYT7rqHNeIWeJ7)DT+^FaO{MHQS<3iUl8%qW{|1 zH%9eNX4)-JRI!!pi#?|Rb@Rra+q3na4G_$<`*z1*Z&I?5ot16~0lRSiGW>)KzWfh| z7j2t6^_L&QAIlMlb`uJU1aaSgyZ@p7UZI`ifa=Qk?EaMgPd=XSd>Ycp360u_RD5{# zy^!(n@TjsoC<9+H#|^B7~(&Q8#`4#OR*$vYK+L)|By@(c-a@M3Q6y-g(Qj=l4xw zDhrEfG`)k}ej#rD={+)c;oiM>hqzBQJ#og{5Qg;zN8){C-US94HBM&uPt)?F(aJekt2)T@5PHC7UOZy3_cnMXMuiVF#WTF@|}{}PibyM}>53#x9f z%kN+8?PXm_PfyRtq%Q@V-+wE`DY(^tnN6$G>wq@^BE)*_FVMydT4Kw}XcsyGj2(!b z>v})8OOvG(_*3-e&NS$(M&$*CVdshAtjF8zcbrD$cdv;Bx4o*SH1cQHFw5X>!Z7!P z!|R+A&o_yCfcXc_+i3N_lL=?F$ffss{U@l-_HpJP|A2w1zw4QMw*FnN%h~P34(#t! z?csi@ZItUUP@6@cF+j8(#nz0`)+jg|- z+VSq#^JHYeqaBf9M}>-!isZTX8g96j9B8*wdtxfwiC->9KrJKwW^r#ufR_+$d-Y1f z3uB-PhdAF+q7nuNh13P6k*o&x<}Hp@|2TQ@BB`0?ctU0cCnpmQZ6g^Tb?8K)0@aB< z%=$b^7^9Jp#XJ7QN3FsQhKB4W#jO)i*%h_-M^Lrij3|!LquNlFziu8RY-uT|LlUbm$)aA$66(LuTN-fBDa|uzz5?SLR;|q3k zroMUyFoBKFu7uKr(6kD9kHGSToTroaNy|VEbS^< za}xHSv0$s^wx}^l*wVgU+ETshZ(fe(*5`u$*k9ct6-vJJy9%mUy*dXiE=Ho_vKMYc*{1KAfg)uSHs{|a-_im{ zVn3K3_~opSV9zLZE$w5zNcB954{1$e1S zx;uQ;%I61cl0u~dM@IN2GSwqT1W}7!pyUzx;NdItLf7Ia^YV=xn27+2JDPN1`vQ5;317F`rzQ@2`(7UMY zp2~S=65@pgYu5kqO`IxAs9|u-^&0SJ<{2Tp-t@tdPOz#HsNS&O8DQvGYI1>0%9imM z#pv|Kq@`F^9>0;rkY7^6g_CYQF38?5msY{v)D4zxB9QPpU##q^pP|?(Z{@2y2R*T1 zwcuX8tca;&is@}Jj3TgV*JF~%ia96$QRxsr4q7caK?TERirnlB3kF4DNw|Ib6G;B3 zJkwHHgC=HU>aI1;Jt5L5w^E{}<)>)fX*?ZO)jdhS$-zy1RBz@S{9X-JzB<~86;nmb zw|I)&>5Jj?tkHpO+g!iKH_{=us*@z7l+jTSAKdETJ@oB-BTLh?i(fy>=QlvFC z<&I>hX}*;!>y+RuE|w}-Y`T;$W3nDWut3DAgw`+zdPE^R-hnw;rd6X3NV`&_Yb!T5 zQz&(+fd1rQ)m-ovuj8e(UqI+}%u2~yUL1qy15B^n`&{W@HN1S)E>x~+FWm!}utt0#&(a%=%23Z;mB)XV!!0J=^bKrmt)TfBi^ zYrO0g96JWY**n|@N@>hW6E9-Un+aD?NlrhswZ;$k%{D?Hm zN#ZRws{7dC%xxv)-ZP5nbZTnt&;72Ci+i1@d0VI2x>nm}tE?#3wm#Ji3U}%pI0eNm zc5VUuFK>ow3;`O1*xMk)8aQNwfJD3*MwDJ{#2~10JQ@NV+dUFYe^R>v(-<|a3owdb z=ZgUJegThzC=Q8t5C{rb`5G{rm&lC)f;6=B^mMo;kdnFjnPvlr8V2fyVvv8VnIQe^ zkLb+mfWA)34VM#`X+qZSdTPeSo+dB=TCREQ#|K~TLxJoLuz4eeVJPG)y<^3l+`png z$bAUA{2fSJcC@pQhm|gq>}`O475^d7&bxv8kLzYm+2#{HvW~k1OK`!9U7Z1j66`*( zw3R-C<1QXVwY-w({>|-wLx1Si7y1L{uJn&kOFn5QbxBVsSXh-#=Ee7G#+C-MKEpko z&E67UIiX|YVc94}sO$tb)P4~%#uKcOcI=N4JG@;TrFNJ5&L}?@)Gfyj=#RX4U2*cX z*EQp)Tb=Qg|r+$vYm8b|Mc8TAEdGqIcS6Xc@@K(6q zl~98em1HoXkygOhY=`lTV8+w!JMYyNlKpoq0s27Pi({709Tu`D=x@eMCdIlM(BZv0%Yrv*|`K^So}G*sClOCDJenj%_V9)nm2>h)-L5{pIeX$Lj?j@5TVlFYZOLn)|PFQc}oHj?sm7 z^|cn6RCrPx8~LIW zi_7=TODLxDy$nMA6C_{ttTE=$oM(>#dan>vm4I7}viW9D0ShB5!<}W%>;7ZgF7@xy z@G36_Lh3+Rh>r`Pu0J2;=4NN7oWA{Nbso9YI`2FZxby%xJuYB!yKkL5MMKcF2Fk?G zFD^{$lf1liJim`MEXRJ%?-|yi>|>P~=>q#80N7HddAkY|y2I`BPRO~6?o~M-(%;X% zF87&_`da=@T5XP4b_?by*Mq5t;QUf%d_BG{n)ip5>K;2X;AYr_Segi{)rnW5A+e16 z*M;bK%Zh}XIfku%WVUbDJpgMWVy?f`?1KZHGjmy_4r!G*9b8WJ=CII9P!n?Qsb$}ul%>@p+!wWM2>qi+0) zq5!;)!4NwT?BCvmAXnRyEyC9Ewkl5A+TZ;fS>m>;QmM1D*k$A))rn;iMw+2)j%*ua z9Rl$Uk~OX(-IHNmiE`2Og6aQnb%P9#gYP{c0le%yYtV1rpEzQEBT zr7)t&4+cj!8iM(435>bjPYtraY#9S4jTGN-za_O(y#q}wlvP}UsDI5m-Vjm}62n-c z=TU$n*sihPaL*se5yF(POP5ckAeQ{`&CGtd#@%-JO!igcl>FqtX+hxLL^r~ z@mD&#Y2H>J<}ZxYYBHp;3;1Kq-rRmJ1LXDXcq6ld`&pIhOe|{0BZx2T=|t}DOIE5s zJKU`eeM*axm&*gHO4xC{biZcn;pn`agq^##&Dm~g>ra{10Z9=+sG7%(kCLL2QX2PT zuHVHokQJsuNU6e<_8ca-@^1cV?6*UtgcIsQ3@)X?dGQB*gIT;`!#B3}`8g?0@Ws7R z8%nuSgO)&>Imf=dalWxJB*eI)!j4wRk|P@kp#jPbf#$pADn^FL-k!&g8|$mp4F^-;CK)km)YCk-FRR`$w&f!CtXqJTUp;R#mChcDn9Do4S7w z+|m(B>L%wICkHd~zKe34Qb^%K^Y}~H3t#{J#|eEbVN=W>W#-WZIcqk7AxuI| zy1ru>fk>kDA>uz!t>@)p?uHME-D!?$QgdXegjVQ)?5)2T3xkT>Jee&QMABbbwN`Jf zDGW=&bJ8dJBM9$~AW*!W+A`HE+G)mZgC+Akim9HBujR9nadBb0NHxrGKlA%zJa{;n zK4DdUsj;`JlKH;<@sW$_>N>0QQ7gULJL86=FGJn$#0W=C37lWWgI9KS<**V1@FSqq_Qn z*WFL{&*FaMf3JRS8%Jm}Lr&kPq%66*{d}HsR3d>@I(hEzy!3jTEJzr8f2TsCykKx~ z*WrKOe^q44IcfI%xJSj3$7*89BD^GpkRtwS^^uvn;QjQ@7DYYNaw)$T@VYDHF7Wn} ziGh*P^%V7~?EZ3mTA8Y+;R|5;7`ac7gOl0Z3LYBDDW?iVo1~DP_+i1a%)8-ugUwE} z#CY;JKX(;aR)}4=d`Q}_D}@8FrHzt5=WE?P)0H@&^1(g8l?gwb{v<>`+DUeL#9Pjw z;YvVs*FQ^AbYe_Q-YmMd(EV}&?LSzrS-SBuL9?90>7u`JG=!)1H*fXa6#3ClOvx1BNa)saE>Sk-q4W@)Sru9iXLq4|h zKhf@_-s=Lochh1g*Ig-1DBI;Ey0k!7dLTbQeA3PLh1AVyy> znPk`q26|}FXy;Pz?4+X32S+ad90!#mfX)By3H~dXpY6R?(6b!b;LdE$pU?x2k zA(bxjurtz~^XH4|9Z#TrzUnWBbeePG(&n`tmVgShO%tIsocmuwKP>`BrV_SWr12&^ z7wf7H;>!F}MUm#U1z%%2bp3o_1@f?lfqceS!KAS zZnr~4FFt=GyXxm9{k!l=AeG?;NCN$sIa+UVnjDl2xDDy;Xr?j;0WvE`X604ECBS`4 z>UUUQo}~!A1vHJR#at}d`Mm3n6cR!Gn;cu6rid#L(>Ot-3@lu zBbgBVZ)ri^<2%hgS$M9!H3gY~_z_w*(GSVBony@VhY(bMVK+HvJGk&u&Cbq_HVF;r z(rMw+k%(ImT75~#GB%_zY_}tW7CQLwLkN8-9Z2vB77Q3JLn;5J^C9J&T^CPKw`^G3 zDrsJHkicX^W-~@;expGE!Mq43M!p(JB<>pci*e8hL)|jCH?B4u;iFqHBl0798#Evu zmOXyF=%8b$&!5_jgzg>)VU*(()E~Nd#lfsdtJN}V=e+0;8E4C@)l#~?l)78X-!~_! zTSF@B#F1cUIVxdfd!mwJ}M6U*$aSuGE+IXhG%JySH zcP~0$;E=ItZw4bL5ucP3(ln4yM21l{aTpShyiVJIM^n|cbj%8xc%K4RuD6YFyNu#x z{AV%d9QGVyeO|e+Xfv=YmTi?}jea)+d|xPD4}5(U6LY+=Ol<9Gzy^jtqw=qE;Wca*o*o3@ zMIFc=Fc#-nZp0crIG6&{rDuFqULQ?Fz5He0BhN=Pcy^^asU>>&gx7MToDZ|*w2x!C z$Ha~~mBkN{KVwD&PL5aloFs&7 z0aV|a3TLEg;!Vm^A$LY>{%B0x#biM7SJp#y&+eMD3cyEd_j#-8K_l|M z&*8;MnWTlKK{nct`JD~6jSTu3{`TIS0_iXETWJhOPt@ifRIO*FohR>sYHt7!A7EcI zYEt%tX#_7rs*f1*6IqXItk5z|NkaPR<_jHhdrX#(kUW2+B|({%Ga;Gb2V#1L@r6#) z2s08fZN1r@zQh5|TKwAD_LyNuJRt<+r*YQ`RTlKP&z9&BPy#egDWJY3VJ{{4zAz(C zPiXq+L3Tm?S}T!Wf0He=1LBl)`$)^e3`rB{Ba z!CM!v=`Nbg0?OZ9ycK%sM=|&#Y1j2xxeY$HC->0sb41Xz$Z{Fr_l3(Ot*1W;VewcH zzobgbt_rB2HMv=zzaJQvj&W<|(;dGA>M`fE2zYa51Fkg7`vn5#0wD z@6T1{rn8|f$mj~`+k$fBmr?pP6Xrv-fqc}GeonZq^(iGIN+Xm3uUf-1G%_z5AdPt6 z76=J&aapw5x|tk!vHD)v7`&vPUYqJX0?728)mI*biK;Nj`FoFqs`738^2X2gqv&H$ z=oZVn3_n;j4=u`k|3D$p_9c5=N2fMSCBu1g7wT`12pCa#( zhz{qYnd@sungk`4A%TOt!sLk@p$|aU^;3)cRsNVL35UUc8ix?c4y*VTB8k49|8R^a z<}K9@fJfi|1)`D&`L5OA4S3V}rph00&5L<%;HzBA|M{D7it6_# zK>|K_+4=i4Q)#*N2qp&0F-u|D7%d`8&^lwAOMtPvH^4ou!_WH^*MPB86u2N(B>FMm*32fJN*_qAZUK4NzfBh zEnODIEA>JOV>}J~Kr1&zIG9PH1H&1Y>!BFsqyC@FR@zJ5NjZ7sM16YaKYg6Ua*9Xn__FPwGrDvBvL zIQ0OTrU*AF4KZI@!&<|MZRz$=9ry4T9kX@dvyP{?j2Q-Xb_dT8ZM|-GO|=OK0(ewk zHk61sOf2h3g^)=6X&nv~P)J~(3mAEbPmj&WpEN+t=BuJJ8%yvW);> zpH^GH+5>F=Ht0$C+johA2&N8WB#|>S%B`AW^}hwp;2RRYnv*# z>DT9eNLpm=bujvu31P5;2YXXlv0+ZYg%sGvQQnIG5MlM*M6VjdLtuC>24{Rm?I*KC zRb2_A%q#SRPcQ;P-AmMtZZXqr`7xx;*rZw@fZ$|e!_jt=+*yZloOpJhO%xoo3JYax zVTxu#rUvy3g0oUkfxEOD25p6mFi5|qsU6HHwJbwbLD>jL&eChhL;+8hgfh7Obv0U~ zP=o{Jb9?(WY|%<=U5Ru_) z#Qa=e9%nuiZanK;PNY~wtD_oQ?)-GD9rlBq>jpfIbHDN$Y+&y3D$&c?S>BQDy6Js4 z>^aI3H=INC??&ths@KS?Y&Ng$0&P{cX5z5=q``Ulh~_`j7dyR9$+3Wpy{I}na3{;NJ;kFo+Dm&wva zx-4$Mblvcy3(XM@R29)jRY1C2>B*t%_zJ*=0ymj;`J@xSF(0txJ647xeRgi5mqx@n8Pqrl^ zSl&FS2KSQvx!`zwdinkfUzr0sGfbG#z?7I=&8V2aG!py@2i z3>W6D9?c1_f{dR|H6C1RFr}iJzUhisdRTc_JQ#`y2lo_`|BkpHiq|fY&yo(>=@dWM zZvqRxEKinCYaqj2U;P~~@r_g17h|tmM@c0*(Dki*^7D?b_9MlMG_~ee@qJa;9j+G5 z`|?dCv_Ia)W|2kD^QZ~)iSXlybpoujENjl3^AITwpq&hWm*fjM$OQA$lF!nb2#QT9 zA(5QxPp+ntrKjqDaggSetrreCR|EqBlwlf|nR8B802e)8YCx5NI(TtyO;<1{rPs#F zY8dMZv4cKg=@C6ylE->xT4?RZhT6u}qAJ6$&IBF;i9x#)}+@cqTrdeY@;22;e09(`q= z<)mM;SWt5AV#~)R;6@`3#Ov6=&xUcCtO~94(@XfWIg4yzSmWXPR-hi z7mqEb%aMcFadt!@>cnkora>}6dZXzw?LzJz<2>)+CzS+dW|Jj2=zoy-yzPwoY8}=? zviY_re~k^5Sz{MtuD??wqwcIh3*3~xTv=dX8xZ?!D;PT-O0Y>A9h$$hWCf{f%D5b5 z*fVi;P9z^A^DD-;bq=Tg-W2S#59{8d{XT?Awxjdzy&X_z)Wu&waZwc+>-pVZOKd~y z>K+AEXo>iqjdoJ!U^??7!!ocg0|f8chNhj5W@6E` zsdcQFgWlcUU@<}xtw7B1IBJt7o_vL-AOPbJsJ)5iUB)G0Pp$}tg!tay988Wr7ri^@ z`9;5G>D>#NMs`z9{*A;-zVHOf%Cc;SgShWtQ8r)wZAq28PN2$?g!^BWC8c2t#7?zZ z?7yIQAb`%M(#SLwW4TaytnPGgN|_ltuv4kDTr~%(AonDuz(8BqPZ|6cZRc{PC}=(U ztkd&lg&pq?{QCYM%VKdVNOwX!pbAT*nx^sjlmEXcU*L;3Fq4H!-eY|FM+PA}Fb@Gw z&du9LmofTj_kJhKzFl{N!mzuM(qFwquV&Ha4mdNxb3F@$ls93R{9Kd*_xZB*W_Zc7 zHgdRJL~VRY58i^HC6u$3*=PWmgT%!U@nKx#U##3UGJ8%X4(2T&bE~L7sikb7oX$vD zN(s+XbKy_TMD6Y8a9{8!9w7W^LQA(lC1du!YveZ&_nG~xooCb+5dl;?Bq2Z$QV=F9 zOzuQ|ZA>qfKfs^PDkvd@Z$p$=?#40wGdVVeLKDiq!>a6m`f+CPX`V#9DjiS5&&GNu z-QIiA2vHZN8Us0}Gu*Iq+Lqr&tLBSqlB8HIl_}Z@fe9-{8JT(yKP&T(Jp_X&RLf6_ zUzvF*-}iO6K6Vw}`&7!q{SFh}P+!4WF>jM^{UNVN@+YJa5{J(ZNWXJ`g^+#^ zFUd~lbF01z@q^FRWeEx0FqRExR;i?$LKPpZX=>uY-s5%JA7iZPpzyeR+`#R+guyPK zM&&=2iW$jx&2aA~9e(s64hSjL!@f$-&Sps&E%#morbv=gQUFFP;MH_{oA&F7LQdsf z?!GtzbyuM9{N~Gjd6oN{+7&~a$74l-}Da>i)n zOZuZQhPju}B<;a{Tc+HE*|b5$T&Ysh6G(i{9*nQ$${zj0or2(}<>L*jS?ufL27$T& zwIVypG$j~DM@KX+pcns#9X07^aau<GuR>9(YeB3Mz*_JVq5m3zcD?8E;?a8KgMZ57}plY%owS^Rvw~63p`$b zVp7K%HyT%#v#pa=ntOQjl%c`gn$@wT(Ig~B0Ft2NA-4Yay8iuZohZ*h%l`UiJg>TC z_k=nw{Fmpt;BG6uaT7#73Xjg{)6R#~IV_4OjXozu z_Z4BMYPh<(zlbRS*}~NF)t)GiWVQ|6o4~|FyHZKJ;e$JDb&u0AzKxnpkdF)CuDksV zxI3ELh}#_1Ugwz}zIhMSL_ZabDX4D0H?;!+_%T&adC#Y7Gy0Aov`+mRRfh4&NucST zmXZeOhG;hi}E5=Z_m$q((As&GH8S0{SRv5YPyIl2*gR7M@WHO4?>10B>y}HoR z*@;8iqf-GRiTC^a?MsQV@Q-Wz&yX_KX>5T&lR>Vde01J>`$(O?H6@F0dC9k7h2Fs~ z^o`j{g&~C;l<%H{9VY00?Ow^1=`KUYIYz=;|BfT_6^9N3*WM(yW17ZYiH_3Kj409s z^0Ohj=GSx19>tYzm$xcH-4=+R&{O(zdjx+bG)iHXsL->lY&5TF&}rSx0cIHgfz(8K zE+Y9fCI?Gjl}?dofrx8N=r)(fewgSi@}ft>I?Y^+%5Bo&6>G&@9tou)Ws1BfEXQ5B z_^@y)39WPNIqVyw@7y4sTnF4t41EHgcv~Q1C7V8sZtp=n1dm+zy!~}g^1OVBE716u`ne0XCut%Qa<-}&230>#iPVo6v z!+NmFNy)_cX^matNV|ic1Q-Sly?j3Xq%CYGB9w-vq~tsbwL)*`=K!o!XOX%6vcH(J zV*v7RR?&(HlPh<;&$Yb}!bXY`5VfMhCCmGDbb*#!D{uNWD{eZF5J6<*WCY{IWB_{M z`AHr`w5-19u#AEvF;ggeVQ>R=odkkrrUrglS( z432a>3-#R-rbX}%tn>1?xc(YelVYMGfd?qCjjLIof@^Obx4Onmd_;4GBYX$_y`$&WI5G+xhblgyGC(jTGp8vxgcWy3e$y zh>Oj-+*?%+zTIstie+jSIWfT*9Ccq{z|4}jMo3^7*wJQJ84h7?6ljFnTH%t}9nfwN zh=~M~iivNaG8L`Jyuu*_2HnoqUawX8yMMj3xc5v3*(!+7C)m4*JwNo5XOAs`unw7&P&&XcsrtfL7u3@OI<9Smgn% z7B-lk-4P+*gPpU^)2WRM+Aj-9H}jkEQ3VT|BZ_rIst0eSci{N;ktetVZuAKj8jUXZFsMj74iWN;mH< z%2+^amWKL9xWUf1YBmnp1e$2kO`e=c>q#w}noYLZ)SztZY?F0S|JDA>1*=dEykp8Z zs5rSMtm(sqkS+o>m8)X;lVW@d9ot(aJRu?HfDO=Q0Jyl)#pO+brT)L9B-38qPm|K@ zyE_`!&K?TK7??7b+L~Z;XKlMLdyyQm0A4=CoWh$Oly=0=1M32}RsZB)Rz%Yt54|ua zvpMRocSY3r3m6IlcdpwyAt6j7!F7MCz)-UpKUATgzalgh^zQIq>IM}4Li9N@>%;<} z#l{8+N~dje^s05i6>jlgR`=Jj^>`2N~OWA&JwmSaClm1_zU zwzL}-&YO0AmYleLzXGu!ptW@jrk^!6x9ePBn`>1;g}B_yG=&}En@{g?X%J=bkxv9O z6&IDKVpx9R$o_i#^CY{7da(-3M?qjxT^k(Qv_hD|QsdfQ_k)TgVlYg!88d;Jf>&Vr z?C$=aq4nrpzf46}aNfE*PSP}3FN3?4Wc2Ll6T@9OXAzj6lcbZ{;7xh|%Oxpwf*T2t zW-Yi2NzFK?khQ-zWA7Z@ahdA)-8moWJ4fe6Bqsan_x3>z$(oJwQCl9c;b%Nv zU0fc`T0lrfB~6&RZwj<3wp{OH`^_kl@|zyVDv-K4H53;b8Ok#LfbLyFN6{ve+nN*l zIM8^wKV&qxlHKBUJ6{7P<9$2LuKlR=^*S(ga$eRB{;TxI#dsHLS3Of}(I8KdM&8{=e)Iopj(lwDqY7G2Cl9-6W`mv@3C*{$0u9nI)P7IS6!WbT&UAN2b+)!EAn%dcAFuf(RU^dG0U1)*>|^hc4iH)ykIBGOR!n3 zBFg#SQBMD0uu3{floo62vC^W;LCfHuIgxCZFd>fYTHap&5RhR zRBXhS={|zgX(t@S+2_?v+465vqwyC+s|!bV6GNcEC;sPevZr(2wxR}W#JK4U=hEC< z%{HvSbRC-1eYFouDo%v8z2#l7qqhau19HD=y3o6c_5Bv+%x+*+1?9ej^tnfXbSGXx z>}GzUjmm|{1&wW))Yp_4D&b1W15@^%W&;{fZy}Z3KD=03e+J23u6{g_ezbH|kliJ3 zlI%x(rGAmUCpoazIFK9c^=`XTM0q1%#FRNZKRdfP{S?bK`ptVp?>$ce^04#eFJR7B z5k>MlUpkFm^CiRfWuKUd&BtA`2u99U>d<4r4f0)C$K=?N9vUT@ChFQX_od_HeKJR= zruPd8ae{maV^a9;->uqh$~eh(VzNOwW$`DCSi}LW2sU!X?bJ+Yf|xBi$s%Q77WKA1 z#J`%L)AJi|vNoC8cDioLkjdbL4WjemO}3_PGnJon&mUc< zYEFX-+=3=g#Y^3`>2Q{_WpwGwA1BPzw0XP~_r>j{57e}J)GlDp(|%WMdB#!RF3+7g zUNmexM!`tbob}}^MMUNg=NhAsUi8s=ifP4?Nu~_y0>>y4ihSR0DA<8YX^#*s*MhzK z=d3PGx|Dmu@%;>q%}hyfwXOpXc?kTve$T}}A?Qea$#?XRP|{C@m2sY<-#m~+uBukI zKkP1SO?KKQ_&(O~QFw?Pf3yAt=TTYHh3AXM+s(u?&epG1V*ZusWByDoa{b3Z`2cC! zKAm+L_6dUt&DjW#4$;(2#a4$M;kbAiM>^0YUoErcNIUK{h*2wgw~nbkUtcPm$gvMh z&a*q_%e_54%`^EiAuva*6h(vp5>LpbFjhJJH<4;q?d&~8ctUWcxT-M zeljf`s+xL~`SZHjp~bY{?(Xhr6|$))QeX&JPkx^U;cO)k{i?!4Yjqo-6DlYj^(iP>_MXh zQP0oMnoR0CI$k&XS!s?^OgNMj7iMrPYwd0q>N(kDGWc>S7wYQj>AdLuJ3sB@WnRH~ zc}C{@=PEMLRaI3W_OD;b_dBUx9xl3n1U$KxV8>l!25{o9yaD#HC?xztoWF&OKRhJv zrn90z&OGO6N*4R)Oapt^KIWo(fi!j7A~6csP*q`08o;T`;~MF0cGy%`!=};BnF^m{Vi4L^$1m5_*V5O~t3uIWWnyAtWj;uD z{ovS=cZv4r#fDg_L8nN$nHQ z4fzrFX7Xmy5`QcO13Ab~1GlHwFs|!nlnS6XjOE~g9e#~r=PQGwZ{67>)Z}MnCG|WM zEM^)V@BLi%_u^f=J2Ut*>C-`ZwP$%7KII7mg>@tsh7zDZV*gbF6zm-kidbP2{HiVZ zAET$-118c#8Qo01oN>4s&)3!Blvd;XJh^^`%?J9hqvv=iXu+bnvA=J-NB9F%fg9-1 zY1g{Knz^_{(PMnO0^@@!(wbW3Dx$*JxcFfV$pDLCpudJ?$trv{f3@I0vms@Lj zu&~%{!&E$_dJ9gbk6PE{9|X>sxXfzU@Q4aUZ{qJZ(qMu2eD~Q`A^w*##>JZZ^JT&s zhtv^y*1en23Y+L1RSgXVc{zZ&QnjnmtF|TS(ucsE7asnDTeja=joaJHb>U~`nla$* z;q2<7*XmhRS4WN$#musI{p2lHYwTfFrpY8PD+`#|0hT$-2;3^ODiIM#{l-eVOb#@Z z+>Vc-JKUr`uhVn40(@}COfzvp6~MYh6Ew}+y(#e{A&NJlSYsW*W5rz4GnOi`!_&RT z_4o)VX&|qxV%#7hoz}uHK}DQ}mbDM&eOCyhCTz;bn44e3j7x1{*hSigL1&&|W@2VG zW5Yjt@u9;Sak|;u?oBa1_%_$pj<@NnG5L*pR6sUrW{KxYnFYZrf$^{$_d-U}$<7Xh zrAERhxVVsPXT9?C{Z&^dqg+U}wo^S0CYjUeFB>N(O@x@;fDECOQ!hr=eiNJMZvj9G z{G#I~dXDsSY4P+W9?jL#gWO=q9cWsuVMA1cw9tVUE{9u_4hshtw_G%dnS;3KRZSU*uZdJIjn3T&u$A`tJr?)AJlRz!h^C9- zVCns^cro+LmI>0&%O`hm!1|PrC;AOp8P`Hu>l?N9>HtluV_s2_m>`v`x>B$=If+AN zX3I^*Oz6fVrK2myTC*p5C3$gnmeh?!B~_%HkdUx% zNP($Jo9C`Gg#&swKVte%Fn`nc#ZJytu5S%_l_h;ybXK@hXiL7XtqP$x(&CtT4sQm= zymJrtFm~kEug;UJ-|lK^*w|J^Kl94#*}ehxW1(CNT!7K+;PJ7xj)n3#3oAxrTG4Rnf0X*F$gt z)|8BmR87+TpanV%rDAu9to7+BbsZ{Wj3K1_`mhD@gBFA9uL-!J9DFfD+foJeBnDbq zX;~QsUP$!XH7<>a1?}xGfCWl9Md;uTV5GZZCXgme(_G`{Y95y!UoH>2yGpm+KbH-o z+R)BOOYKH)<6Dv6_q6$Lde`}3Ry|wCF%Ec_j3T!a2i=@$!=9c`rQz z?i}}bcR*!9O`nX_FffcRNxDdx{w&?ISE?Rx>jPN%byD?$rMcv5T52giB3YtsxQdX} ztvTWxm5!Hn>&X8=6zGWoN%}e(FPax7>a?hZ1qo;~=%>T5X|;cX5*p`~+Tl5~vGtsF z_@A*zyhKuT>200(zF*jv;%B#dvC%cI=^b76YMU^k!z}s*4=49jdHMcY$z6w3Sv+>11s?`dRud%ng?p3@AeKa~29D-WaZ?;wgaFz!){ zhQ=K1BCp3Ce3Y-i)=F{Iqs@|gQDXZVa_oAEOe}LDzm~naqlF;&X=;w|8piP1i4a+S z4ljx^P&SOg@u_2G>rG8cUCrCt$=$t*%Fk-m`EnGjcQdK?+;7U#!vpk^Md%w0~>{BO!G9&u?9-%n%2SjN~E z6)8zMa|TwXZuy;tvGVuUVwMxaIXlV2%YomS?$}c>G&-ZjX=~?6aFUsJQtLyP42IFM zI~#wDtDHWC33#A!=hQiUgPzD`Hh4AOT?fpxG4Ca6hh>x)o0klGc|9R~0BxC&zvkJ5 z=ZVP>BN7EAC2kiRJ_!kFy7oVR{)|4a>Rf_Lj<;|^$neJCSC8r;tIbEElPaY2YhQ3DViF&gv6(@zms~ zhm}^>Z{LrUzt&Xhxh|@qZZ1q#f}C^dJ$;YQ(_|M|)?Kz_!1y17+Z^3{`}bPwMN>wj zDC$gQ7Y6f_ePL}wOLqHIg~ws@?HR>&#hxp4eCz^UBbo7P$JP{J+;gi&Uykn}jxEVy z4=gEigVJ&UbC~mvE)WIJH)*mnB)hZ6R#!nw?e4KIPYEO-+de5{R_Uj<^BJd2Wlf@J zKU>*UkdjVf#I-$t2gR*SQMeUr-1#BQOLaD}ao6P^TsW?nTYxlwLOuUU9{OnSKQ)(> z5Tx@{w~*+8SqNfE0R6E;N=O*B3DD87>dd6bZyIP`7%_B`8@ffWmCNOqGfgv_Fs~c* zP{+zmz>m0{E^g9&)lw`tr63snZPBdS=R{##x3t_~5kt(kzmX3eOs=QQCJd|z7fH7h z8%F4gjVmV~CujLFleH6d1`EET{TTEZQui31+myYl5ckXdnMs21FnOoXAm_oMhKrhr z9<6mvSx0M6COSvwZU+(rB_~XS^-mFI^)-5}V#`p1eqyKj0W-T$Jq*#Nh~gHqa-4e% zy#V#5L{Kslb(r{HQf80mbn?)--@f%@eO^L;pF-^lPFvGXeVV7}c>GBuNP@Mtj48@1 z^cXQ01>JK(K~cdI)S_Gm%)3SgUNU2PWwbC?+Wg-czwoxP61@Gem*-cIc~6pe!M!?6Pcde#>s0ku69?!W@PQxN<`dk zYg|{U(9rEWjy?gnBt7i%iZE_)ja5FCBD$tt+ks_7a=0md0XEBid@LD36~J!bvcYZc zi{s@xGEQbX)s5(5(%J@e%A%k2UViC*FqoKhP82&JM3D{|pVCRbP-nO}o-G3G?&w#i-Veg)Ae2X@uGgo=!)P&uVTz5FfJeiwwSBaLy!9kj7MapT1nn^bNHQlW;IQKdPkDQjEf=sTvtO(TIJODMiT&n)-=50+IJ0xZue#$H$Z|ro^DY09wdFHA`FmbXhnHrP+bR0%wUctc8WLO$TT^_raXiAR zD^J3t-N6sG68hcpbquo9)RRs4%`6)beQ)_lVpi9f5;A;#&aS9t`C1V_%A74Qs#>al zsodor*6KGhhqzM2<$p8o;H$F8BqAf~cK(C2Saa=biKeb$iKgc69@7dI67Mc~XJzhA z%T#~eJYtnBk0P$%q@FSjx`Z9$$j{J^Ao6O@4LloSdcArPeGHH|x|Z^T`)CH=p;ORp z2y!zDWvmb*i6#7j`hskhF#k;8>`vD7R8k!JMUmRD_O7q+e!ITM-sb!Hg{qit)g8dx z`mpp^=JC~i`QDfw_&U8D9hLH@o`eneT~!maH>%uom}UxuHDj0XH9|>*EzQ<)$tYQO zeO)gF=o&7jje&-rm^n$YB89IidA8hBCh7$xEgXo2qbM+gj&?e(M;KSCCaC?WKFwc5 z)Vvw!dH$;nVZf=l?$0z3(M)2}M@eVN9gh+0LB*!?a3aOdb=S#)fhkbnkgi|j&7fs$ zGc=RuCOH}!l(rD-efFWD{D|1r`Y>hV5fXCnU5E{v+nXf{+GurJl(bJ;i1~JnH-lf+ zcHR9E;$EeEz8*iGgFQU8*L3;c6)UrsvoM8&`JW|YCj{ja00M1n)$;Ok0nnRd7tB^gj@Ozgb$p>bbsf9&Mi=)gu%+`;8XW$E4O6*mts_m*@ zVJC?_)}%C*l!_g5O8&wfj0u}VH{hv~&Nm$)<8Hc&3Qp^-Yg0fQS!b*X^s+rqYVK&N z)jrj^7jd>P!h2i^fXHPLb1_^+{uv*sc>js;AeY7>MSf|Fr(E~lZu(p*bThe)1)_e+ zb=>pW%(t6(oq#t+sbL|%IVr06I?c{|Ra#7sx{hYg7EbO%$9aB&)fXbQ?&|1=XxppT zryGDRWsEA_68FoiH@|eAy<4FN93w>I^L5a&eo>AfyU){ z4uMlYS*uU4#0*EL5@8Eld`_#-Z~t4)(dp@&JqhR!T^iP79kCm!lO6g~0rTE@O@;6x zNXxMdQ%_$VLn&U;B7yv0%rA7hY>o$|l(TY#&_#1;`Y)&iQ||`q@xz5I=;%re{RV}` z6|24bfn#wK>1fg5c_80ON&p!42m^h~)Yc^twc^ECbngOdX5M=awGc~<|9A$@1@TFf zy6gx;PW1#;Erm=^M!Y#99@NHJZtFxMq3@%SDThib$b_xTn;~5^7Z6X2w;RJ-v6Wpy zlMh^^(d4fni4DDrqocR1O%HK>h(t-M`P~R8D4W1Q&@Pb>$?Jq$=FVW&&S3xi6~kK~0va@Ia288%gpvQQXqJa;->sso-p z3?&VX#pwcxB75U@vpCcWo9(5g(iZGE=4N;|#54K-?#&eae|wAW3HiiwcOJUWrff(^ zs$^DlPBt?T4mJOGm0>p}MZCBG9UVBjHXNvCKm!kxN^X~LsXJ9Xc%32!x>O~Gy;Nld z*Rs(q?8~j4R|K+&pqzgwi$NDRC#SUgx*}Qif@2IlChFhyU&aO;v~44D!+{xXa(l(M z@ND3DbUKnF__=FK9pm3yIjgFKbb%13a_*LzfYdVp=Y#oqFm?n z*bQ`Mj14=(5fQX(gXz}^kd2Mz4UYfs%s{t+t5~wDz!p*2SOd65Dw$^qc;Qe_&dl{~ zB1Xwh!RNZOQ-^uS0(--KRo<#Cv(nT4Qt0f3^<$o?+4XdZ#OFS(>5qt#d>8`rHZSAt zgtPWQsr#5jPdK#mPZw{_42}rqZ&IK5;tL-ekkd+yj12^UzZx2nWWq_n)Wevgn^C$> zXF;_eqD9lhY0ym@>jUojT<5J)y3L>FwmuX78R`}LNfHI=bTU0cDGw}VLbXZyV;kjd zm9n|@6L5U)^LJjz{swAVMhvBJMshu8=x_;MNEgH-rcxyxVxJg^tFFV+5?^YQlbCHS zzY0TAm(|_4iC@3oW|T^Rwb4?n1|k3_*Q`J^bqm>{tg9)QY%ztVw@4l%7@3$s>miOF}yU;K+29gWfclT9ViQ2 zfl`UB3u7$8%=jjcVRec{yTtp^>5msNMA`h6U-1&2S|XIc81$wHpRB!_V0H zDDqdV(l}JS#1}G`s`yd|0;}uIzKbp$k#YbrZ{Q6rE+MfjK6}J&oft)1x%!;zt}a2- z%xfbr-oY=JTSO;C5yyXf{xmT`qGZd#H5g{;v6+1uk<(UNRdxI~=0xFD8ApepRH?84 z2n8-^(If)Trwx;BSUM}A!=_V`);aWzHPW%wD7|$igZh4NcX4rX)z#ID`d)G@tmPp; z=i!JqmR0z+;!>{Cqgm!tEU&KFgSI=VV*a~WAlwB8-o}@DL9&UoF*O&4t=@obWt3D| zR|iUjn?jv&up;9{c(1R-B%+>+UO0N2d6A@N)FpB!C`fhI5!u;%k3#EdVuYjW1?iSp zN6s9O_~22ow;%MAAI{LRlibNQP#ai%%isH0n}q5*C)&J+teCGlD#qJ*HxSvUn_#vk zYvwS+sL=b3?>IP`=I7&pdM`k+-WlLHtNSrz;bgRc38rI2J@BpV$DyWgJ+c0D-JQQ5 zn!EiQ0FlE0q71W$jJ@67TK@T zGZIsW@fHCG{VwrgFI#Y7b@M3fRGU5#-qOQvLIN@I-1^yPRLr=wJw*#3Tn{`ym$tV9 z{a1M>r*m2%`eNk>Krur=AOHE$;)6B;f6{bdaIgjiwS+dFn9KJTRZlPL@81-};3i#r z@)RAid|C6%$Ukwp>-u8vdC7%y(?cc7Wq<-qKtRC#{k<*cO9epur~+@W?M&l<+N3Gs zLd6SiZf>3lVJ(9=Ousvt&Kx=G=;+AF$(fj#=;&k+6m%`bGx3yL3j$)IVW9l>cCW>1 zJ!E9$JVm;cQ8Tu*cq!||xoMm^;VW%H0fEl5Gd@Cs^zeRRDrG`MV9rR9ogiv(r>Ut4 z8#~VsaBzk-dmR}WS#IcNST2Qq*`lVzN4Pd}QKw2daGEwIIJUue^0)iq8w>GziMUEhu`aQXy3 z$-H}$M}*Q++y`jxZ>FOLb4gKQtgv1tXIxhehDqff1Lx}zQ#M>y{W;3l;_hytILXHi z;wDN4)M6DvaT0bc-~g z+xK=218m(R)yOEY;u3rn6%yJy^UBBrz=-KOZu>`$*S0Y zHN`}#a0ySgw2t=dROs0i-y)S0*#=1Nq?cpo-Pawq^B;>^*pNwig= zN@Mg>`r%+zaxj=QiWk{uP!Yz&lV2v&j4Yb}0NjsHPHZeKFXKBRJ+At3CB(%GS#X)= zkH(t!+Uo`0>;;g@&&~byKFmGd>=StG_fq{WU?BcQ6L-_ivnu z9Nb|WDe3QJz?;%`zVVIDWg8O(-IWICro@~ zEVWmn{GPX#4h|07L?rn59y?K7fEww9?;(86{?G&`2M2JD6)RAxTToY0GSb&5aFr&6 z=9CJOsr6fC24iq-Z0JecXlN|0!bJ0oz4+F<&P*FXs%u?Y3kyWGbj8)nX^i&G zp%&rgG=%r6ABsyj@x%Yzx+rN%IrqbaPgEdTD^wpEynysl{~AWpFb$M;Bl;=g;8#PngxJPom}|$<^J7u+%`m#rPiEjorL|C<7%; z@QkLt~K_Q?|5B z-{Z0#RNvh2iOb7s4gIvIe^6>zrNdZou%+!fuP2_*M`e@};dgiPPB+AHLp;9TAHBVE zbE?2Ud+bG;n2Nm>2^>4NE;#O!^77(aEdv%JGA71?4PQ>;Cf8CL3es?xkb?z`;5tR4b+i{n`{Ut zk1Hj`OQ=W)*DuMI_6zdg^E@5ZT;>f3R!CMFsm$!HaU&)c!!O~H0fze55` z6mU_A5j$>Bn3-WFvYht!X;MPaAgy<0JCi^EiH83 z`fj!tC;v_!Lad{%N{^qLH{kGm!2S{C5cGaJ8ESbqYEb=n(w*$NHI>(E5~KF|wuzhL z*X4d^{c|$AC+*ur5~He0!~L9!suuq1@?rFbkLD;^JaOy4|9{^DMRsQa8npl->E4uY&^v9ZV%a zGZk%mqtmP3IFl-6^uJ>#M|eEQleC2Z?n&opNS6vo5VLC?POHt)Nl8W1(@27@h)+w$ zO!_BP%v1Y-G;GDV2@;zGFK=M}V@SCQd}3i$^h(o=R$Q(9`)+a%LswZ@S!-+BS>oDu zxe-GW#kmIk)DRgl^^x!4oLVK=_pSod?+O=`_%SPl+5T_@Mr>nT$ zJIE9xemjKNACECrewT125fL`)>v`Z!7H4N@76TUB)n+d>Q;;*PUerl zg=+Y>2CZwpkZ$CKBz9)$Kd8Vq-tvvs=gpax(aC)BXOT4ZX92?$vA7Y22L04mYI4PR zjQ4b>kZ^X+gyK8iq_bTSNgYdIxHgSY!lqk(_Vbh|A-&akJQgHz~>~=lLYx3c9#V+RUKeAt4nu(+m+%rF3~1-7MKn# zQ(J$iwB`q@Eo;q;cg9MYFU{M*c~DYPZx=F}maamfIyA95x^X*h%bOFYPUs!mSTXF| z?aJo)l&LCxzTao6y)(%UM)kU^_M>Sx_}k5GC2s7?*V5AMV%xVA{0u!X?WBR8o6T2+ zbrT^!>wZ6}arW(3v(d=}(rd@}d%6oLU9KNXXR*I#XVWq>NpA(M#!L!-Z;8W1<+`Q3 zOwqm6&us|3#Zu_O+5P1=YPVM+MZCj)8aU6XFK{bs5pNk=XXIW<5F8-A8`7io^1IDv zGYgP41MFWAqj&R1g*B&UGWtJ$JUAD=RZjF>lg%g?WW3R6>zgwHidvGZX`5p3EM*~& z(@mSZ+wA`UX|4nVXt$%3|G8JXuYjBP<3L1C~_qz#GC3_mEL9+-cK+okFl|#Yq z48B5Wz{a4H0&kIeYy@mBJdEHolreuHf=Ky_*HQJ+HWGMVsqI~0RX6SSboty$^@7@% z@}u%7#Mk4};tuICWBd_N4HNflgRA5pc;CsjV7q3mmh-2pO6#>7gX;~HA(d%8hhITv z4+U8JbY?j_&ep9ALrMLRq8Nu?WU}Sg@w9cWK+{# zWMM)40cP@-1B(zf*m(m34WB{f0?(@Ts!hYm(!oODdjubX!K#U`tT$~mRlJWBY~9`2 z)O6hNw74S^R8nh^C!IUJJwV@|V(l2tK<58HI;5bWjI;^MQ07OJ-E~xiTIZv;n9dWk zW&8nu$+@9hruc+cH1Gh-b~YG=ie8X@gel+mQ6b4 zI!|?nSC6=8+oOt8?ovBX~qvbm#2dO-JRatq?%Mi|@?BMml z4gw8jHV#x$$i}ib>nnq%9Uup;jX&rsYe!wC*bDdg=I5LrrmO;r|iL|Lo^cn7M z&Ge+qgrM!jDA+-$B%aBx-|WsGobilrXh*rzzNq&qSz`Qi^HEXDE;3{2OGE+{ zzEA_xbO5|_b`{|p@!okoXK-U9@Qr~gsjlxZSd$VwIsr9<1j%|39{xEGJE!kfd~+)p zi;6od0C~E# z&+6$Hy*mut_A_agd8pZd__TL62EK`umD4P0wC1od#97gJkdT_t4Fq@e?}-)XQk_<# zA08h}U~JsgrrUCAnD@$8Xvm%@s$(tNvZ6_6M(vmJPM z&lE+3U2RHDx#&K|fUluRED^*iME)<_ zm$~QRCvQdO{(L&B@8$J_FuGhRP$blvLZCd3f1K+FUcGv?K?8+-_D`R|Vgh^r@6fNJ z_C@%8p|OUbS5y=CynFX~^bLaRcOmeze_>8o0>wy%R-5Al{CbFnm=L4kgJ5tf@%F_k zePdt&R2mK;Tff(70XsM`%d(Id^<@5nTj{0=4wntohP$FZ;-S7)L%7u1>^%!DvaT+;5bp}@ws&S^rgwiL-pL7F7r z`9Z)VCMOXQF8lpz_RSA*q_xHg()Q{wXy5@aFopv|A9!$^qr+K2Y>RtI5GE+ZF>rm^ z9Cg}|!lMhG4COWhwO{ZY#mbG&Y3&tq=D;y2DbT52%7I;EWRz#|T$L{cmAO0s(v2;@ z%FK5Z!p)@D$J&CW;9VdhaU3}NWK%@PdrI!>z1zPh_xKz*#LX0C8?z{~A%Mw2t|cA% z2F4SS0WXHjEzm>+~ zE*SF_U%$qY4_dnO{0s6wagMXD&rG@F7nP+$mqCYeFaJo2A|2#F7w}HEzYOUxs-lXhU>XAvVtnXDK^@~?C zMm~+kosMp`!%`xqkOrs*#pg}g0tDq`JvNJcaDef(%SvxFbJ|lqpk%_mu}lN^du?s$ zbM?h9_dnC=LI?S3N9MtWj+vyoI{)~t&NvUC3_dk(OglRGc+mJ3B3w_8!B1MIFBXOJ zMfM_W%wiE1mRPGx^4{AUt3()yIjGFCG7dE|+H$l9~Y-&F9%rZ*u<0G5@Yl>Pf z#kCYxF&5}CgZjN*g+?W*Jd6w+%bdFEY^=E7H7*DgW{GxadU!5C~-QpTF#x9=Ge~%~sMWRhe>n zY|4V1j5u{&o&OF10l`4L9E#*klYi%+@A`>P1eoalGixRnETrs3*%e-T-z~^hTO87v zexxXdphWb((9N%Y=?D&nmTN$WV<0Lc z`-QGLo3>d5#viRkb8bz*E?fW}*=g@daM4aCOV?XbBDUL~k+AA+di1Mx2bRiqHVy5; zD1tmO+EikF44hHu-d5q|;V`#{5*fDOi(tCo{(0KvB3m$f8;o@amwJt4`@xN>7+U+_ z@Y}a<7r!=wc1q>hrR=2$(AbVvY@9UBbTRC?ZZ~3^sL4*(O_zV3qu$x!ndikhVg(LR z7)Y{P=3{45_Nn8bw3&X-?BoHdb;K{40sfGWPyL#&4HEiGlAkGRIgWDQ?v>}opC0)D zqP7o&?tp8UnJ~@pN*9pSEJXVbAJ$|EOz#5C-p<-OwH6KDH(rlze2s?TZG3oG6tLMt zc$VisIuBn@$2_Tve868bf>%rus-$MED!gvY@@O3CUkn5L+v)qrMY2Fy7vD1N!%>ko z19Jq1!>Wi;5)Z=?HS8Om%)0%0fxP4*!2Ux|P<>pWCLN_YH>rot1216GO6o@p|D^Yg zH-g{Qps6+hvklUl(ll zGHul_j`Z;{bSK%{X=5esG-$yM@cFLt@q9L6zLMHmHa|92=YYI!2`UpJpw=6JQkOJs z>~zFRh8oG9IP5jig5AoXH1XkXJP!H0Jc(`e?W#8~mG8RP)X-NNa;@g_quxXf(ntBU zxtYr#E&KQhXWRo-w!85=Ah^kbcMaA_8PsXQ#k39Ny5ibmEQ+d~^29JX>r~6%DbAn+ z+0Du*JlS0Idm?CfpPCDg|mQJ_*j+KYbb1Jy?8=4_tAVl9B@7-ZT+a zI*7ckpHYjR;UbAspfdNx$WL#d7OM|SoFj)-SD#_Exgo@o>QS9#mU4Gxm*eL1MWW#N zHQh0P3|=sz#p!{^Sh74JG4uWsw(C&$&KtB-wR12MwbDB!GE$;`B$#j)ta0DmgeU(k zJXSE_5a)lQz+eM4tTOX!h#a%t@GLHlp&{W7uHl4Mx$g*t@WNlG+04eKx2-JNxTbciaT>v1gk4}iGJFA*`L7XmwZN8QB_t(_ zii)mAFnZ<8E?(gpZHl=jff6(J^qgyNf23ROiZKH|mS*6}4+ua5eSc`5>D3|?iBZ>M z5{wtWpI!HV7-Kqaxpjq^k((Q#NnJTU8fShMM1f>gX4}DYtlZ)B z{M`-^b+8VkZ1m-%)^qx}CB4Krdw6rEvST-7*`oio8SZj67kDg8ZQ&IrPGSE8*#+@% literal 0 HcmV?d00001 diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/package.xml b/planning/behavior_velocity_dynamic_obstacle_stop_module/package.xml new file mode 100644 index 0000000000000..7e9599c49bc2d --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/package.xml @@ -0,0 +1,36 @@ + + + + behavior_velocity_dynamic_obstacle_stop_module + 0.1.0 + dynamic_obstacle_stop module to stop ego when in the immediate path of a dynamic object + + Maxime Clement + Mamoru Sobue + + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + autoware_auto_perception_msgs + autoware_auto_planning_msgs + behavior_velocity_planner_common + geometry_msgs + libboost-dev + motion_utils + pluginlib + rclcpp + route_handler + tf2 + tier4_autoware_utils + tier4_planning_msgs + vehicle_info_util + visualization_msgs + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/plugins.xml b/planning/behavior_velocity_dynamic_obstacle_stop_module/plugins.xml new file mode 100644 index 0000000000000..2f5662c7998ac --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/plugins.xml @@ -0,0 +1,3 @@ + + + diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp new file mode 100644 index 0000000000000..46c58d6be8805 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp @@ -0,0 +1,71 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "collision.hpp" + +#include +#include + +#include + +#include +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop +{ + +std::optional find_earliest_collision( + const EgoData & ego_data, + const std::vector & objects, + const tier4_autoware_utils::MultiPolygon2d & obstacle_forward_footprints, DebugData & debug_data) +{ + auto earliest_idx = ego_data.path_footprints.size(); + auto earliest_arc_length = motion_utils::calcArcLength(ego_data.path.points); + std::optional earliest_collision_point; + debug_data.collisions.clear(); + std::vector rough_collisions; + for (auto obstacle_idx = 0UL; obstacle_idx < objects.size(); ++obstacle_idx) { + rough_collisions.clear(); + const auto & obstacle_pose = objects[obstacle_idx].kinematics.initial_pose_with_covariance.pose; + const auto & obstacle_footprint = obstacle_forward_footprints[obstacle_idx]; + ego_data.rtree.query( + boost::geometry::index::intersects(obstacle_footprint), std::back_inserter(rough_collisions)); + for (const auto & rough_collision : rough_collisions) { + const auto path_idx = rough_collision.second; + const auto & ego_footprint = ego_data.path_footprints[path_idx]; + const auto & ego_pose = ego_data.path.points[ego_data.first_path_idx + path_idx].point.pose; + const auto angle_diff = tier4_autoware_utils::normalizeRadian( + tf2::getYaw(ego_pose.orientation) - tf2::getYaw(obstacle_pose.orientation)); + if (path_idx <= earliest_idx && std::abs(angle_diff) > (M_PI_2 + M_PI_4)) { + tier4_autoware_utils::MultiPoint2d collision_points; + boost::geometry::intersection( + obstacle_footprint.outer(), ego_footprint.outer(), collision_points); + earliest_idx = path_idx; + for (const auto & coll_p : collision_points) { + auto p = geometry_msgs::msg::Point().set__x(coll_p.x()).set__y(coll_p.y()); + const auto arc_length = + motion_utils::calcSignedArcLength(ego_data.path.points, ego_data.first_path_idx, p); + if (arc_length < earliest_arc_length) { + earliest_arc_length = arc_length; + debug_data.collisions = {obstacle_footprint, ego_footprint}; + earliest_collision_point = p; + } + } + } + } + } + return earliest_collision_point; +} + +} // namespace behavior_velocity_planner::dynamic_obstacle_stop diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp new file mode 100644 index 0000000000000..ccc3fa94df603 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp @@ -0,0 +1,39 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef COLLISION_HPP_ +#define COLLISION_HPP_ + +#include "types.hpp" + +#include +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop +{ + +/// @brief find the earliest collision along the ego path and an obstacle footprint +/// @param [in] ego_data ego data including its path and footprint +/// @param [in] objects obstacles +/// @param [in] obstacle_forward_footprints obstacle footprints +/// @param [in] debug_data debug data +/// @return the point of earliest collision along the ego path +std::optional find_earliest_collision( + const EgoData & ego_data, + const std::vector & objects, + const tier4_autoware_utils::MultiPolygon2d & obstacle_forward_footprints, DebugData & debug_data); + +} // namespace behavior_velocity_planner::dynamic_obstacle_stop + +#endif // COLLISION_HPP_ diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.cpp new file mode 100644 index 0000000000000..cc5dafa218654 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.cpp @@ -0,0 +1,87 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "debug.hpp" + +#include + +#include + +#include +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop::debug +{ + +std::vector make_delete_markers( + const size_t from, const size_t to, const std::string & ns) +{ + std::vector markers; + visualization_msgs::msg::Marker marker; + marker.action = visualization_msgs::msg::Marker::DELETE; + marker.ns = ns; + for (marker.id = static_cast(from); marker.id < static_cast(to); ++marker.id) + markers.push_back(marker); + return markers; +} + +std::vector make_dynamic_obstacle_markers( + const std::vector & obstacles) +{ + std::vector markers; + visualization_msgs::msg::Marker marker; + marker.header.frame_id = "map"; + marker.header.stamp = rclcpp::Time(0); + marker.ns = "dynamic_obstacles"; + marker.id = 0; + marker.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; + marker.action = visualization_msgs::msg::Marker::ADD; + marker.scale = tier4_autoware_utils::createMarkerScale(1.0, 1.0, 1.0); + marker.color = tier4_autoware_utils::createMarkerColor(1.0, 0.1, 0.1, 1.0); + marker.text = "dynamic obstacle"; + for (const auto & obstacle : obstacles) { + marker.pose = obstacle.kinematics.initial_pose_with_covariance.pose; + markers.push_back(marker); + ++marker.id; + } + return markers; +} + +std::vector make_polygon_markers( + const tier4_autoware_utils::MultiPolygon2d & footprints, const std::string & ns, const double z) +{ + std::vector markers; + visualization_msgs::msg::Marker marker; + marker.header.frame_id = "map"; + marker.header.stamp = rclcpp::Time(0); + marker.ns = ns; + marker.id = 0; + marker.type = visualization_msgs::msg::Marker::LINE_STRIP; + marker.action = visualization_msgs::msg::Marker::ADD; + marker.scale = tier4_autoware_utils::createMarkerScale(0.1, 0.1, 0.1); + marker.color = tier4_autoware_utils::createMarkerColor(0.1, 1.0, 0.1, 0.8); + for (const auto & footprint : footprints) { + marker.points.clear(); + for (const auto & p : footprint.outer()) { + marker.points.emplace_back(); + marker.points.back().x = p.x(); + marker.points.back().y = p.y(); + marker.points.back().z = z; + } + markers.push_back(marker); + ++marker.id; + } + return markers; +} +} // namespace behavior_velocity_planner::dynamic_obstacle_stop::debug diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.hpp new file mode 100644 index 0000000000000..02f550d314d39 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.hpp @@ -0,0 +1,40 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef DEBUG_HPP_ +#define DEBUG_HPP_ + +#include "types.hpp" + +#include + +#include +#include + +#include +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop::debug +{ +std::vector make_delete_markers( + const size_t from, const size_t to, const std::string & ns); +std::vector make_dynamic_obstacle_markers( + const std::vector & obstacles); +std::vector make_polygon_markers( + const tier4_autoware_utils::MultiPolygon2d & footprints, const std::string & ns, const double z); +std::vector make_collision_markers( + const tier4_autoware_utils::MultiPoint2d & collisions, const double z); +} // namespace behavior_velocity_planner::dynamic_obstacle_stop::debug + +#endif // DEBUG_HPP_ diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.cpp new file mode 100644 index 0000000000000..6a0c61963ac81 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.cpp @@ -0,0 +1,84 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "footprint.hpp" + +#include + +#include + +#include + +#include +#include + +#include +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop +{ +tier4_autoware_utils::MultiPolygon2d make_forward_footprints( + const std::vector & obstacles, + const PlannerParam & params, const double hysteresis) +{ + tier4_autoware_utils::MultiPolygon2d forward_footprints; + for (const auto & obstacle : obstacles) + forward_footprints.push_back(project_to_pose( + make_forward_footprint(obstacle, params, hysteresis), + obstacle.kinematics.initial_pose_with_covariance.pose)); + return forward_footprints; +} + +tier4_autoware_utils::Polygon2d make_forward_footprint( + const autoware_auto_perception_msgs::msg::PredictedObject & obstacle, const PlannerParam & params, + const double hysteresis) +{ + const auto & shape = obstacle.shape.dimensions; + const auto longitudinal_offset = + shape.x / 2.0 + + obstacle.kinematics.initial_twist_with_covariance.twist.linear.x * params.time_horizon; + const auto lateral_offset = (shape.y + params.extra_object_width) / 2.0 + hysteresis; + return tier4_autoware_utils::Polygon2d{ + {{longitudinal_offset, -lateral_offset}, + {longitudinal_offset, lateral_offset}, + {shape.x / 2.0, lateral_offset}, + {shape.x / 2.0, -lateral_offset}, + {longitudinal_offset, -lateral_offset}}, + {}}; +} + +tier4_autoware_utils::Polygon2d project_to_pose( + const tier4_autoware_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose) +{ + const auto angle = tf2::getYaw(pose.orientation); + const auto rotated_footprint = tier4_autoware_utils::rotatePolygon(base_footprint, angle); + tier4_autoware_utils::Polygon2d footprint; + for (const auto & p : rotated_footprint.outer()) + footprint.outer().emplace_back(p.x() + pose.position.x, p.y() + pose.position.y); + return footprint; +} + +void make_ego_footprint_rtree(EgoData & ego_data, const PlannerParam & params) +{ + for (const auto & p : ego_data.path.points) + ego_data.path_footprints.push_back(tier4_autoware_utils::toFootprint( + p.point.pose, params.ego_longitudinal_offset, 0.0, params.ego_lateral_offset * 2.0)); + for (auto i = 0UL; i < ego_data.path_footprints.size(); ++i) { + const auto box = + boost::geometry::return_envelope(ego_data.path_footprints[i]); + ego_data.rtree.insert(std::make_pair(box, i)); + } +} + +} // namespace behavior_velocity_planner::dynamic_obstacle_stop diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.hpp new file mode 100644 index 0000000000000..c28e89ac6c9f6 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.hpp @@ -0,0 +1,55 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef FOOTPRINT_HPP_ +#define FOOTPRINT_HPP_ + +#include "types.hpp" + +#include + +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop +{ +/// @brief create the footprint of the given obstacles and their projection over a fixed time +/// horizon +/// @param [in] obstacles obstacles +/// @param [in] params parameters used to create the footprint +/// @param [in] hysteresis [m] extra lateral distance to add to the footprints +/// @return forward footprint of the obstacle +tier4_autoware_utils::MultiPolygon2d make_forward_footprints( + const std::vector & obstacles, + const PlannerParam & params, const double hysteresis); +/// @brief create the footprint of the given obstacle and its projection over a fixed time horizon +/// @param [in] obstacle obstacle +/// @param [in] params parameters used to create the footprint +/// @param [in] hysteresis [m] extra lateral distance to add to the footprint +/// @return forward footprint of the obstacle +tier4_autoware_utils::Polygon2d make_forward_footprint( + const autoware_auto_perception_msgs::msg::PredictedObject & obstacle, const PlannerParam & params, + const double hysteresis); +/// @brief project a footprint to the given pose +/// @param [in] base_footprint footprint to project +/// @param [in] pose projection pose +/// @return footprint projected to the given pose +tier4_autoware_utils::Polygon2d project_to_pose( + const tier4_autoware_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose); +/// @brief create the rtree indexing the ego footprint along the path +/// @param [inout] ego_data ego data with its path and the rtree to populate +/// @param [in] params parameters +void make_ego_footprint_rtree(EgoData & ego_data, const PlannerParam & params); +} // namespace behavior_velocity_planner::dynamic_obstacle_stop + +#endif // FOOTPRINT_HPP_ diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp new file mode 100644 index 0000000000000..99981007b20c2 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp @@ -0,0 +1,73 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "manager.hpp" + +#include "scene_dynamic_obstacle_stop.hpp" + +#include + +#include + +namespace behavior_velocity_planner +{ +using tier4_autoware_utils::getOrDeclareParameter; + +DynamicObstacleStopModuleManager::DynamicObstacleStopModuleManager(rclcpp::Node & node) +: SceneModuleManagerInterface(node, getModuleName()), module_id_(0UL) +{ + const std::string ns(getModuleName()); + auto & pp = planner_param_; + + pp.extra_object_width = getOrDeclareParameter(node, ns + ".extra_object_width"); + pp.minimum_object_velocity = getOrDeclareParameter(node, ns + ".minimum_object_velocity"); + pp.stop_distance_buffer = getOrDeclareParameter(node, ns + ".stop_distance_buffer"); + pp.time_horizon = getOrDeclareParameter(node, ns + ".time_horizon"); + pp.hysteresis = getOrDeclareParameter(node, ns + ".hysteresis"); + pp.decision_duration_buffer = + getOrDeclareParameter(node, ns + ".decision_duration_buffer"); + pp.minimum_object_distance_from_ego_path = + getOrDeclareParameter(node, ns + ".minimum_object_distance_from_ego_path"); + + const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); + pp.ego_lateral_offset = + std::max(std::abs(vehicle_info.min_lateral_offset_m), vehicle_info.max_lateral_offset_m); + pp.ego_longitudinal_offset = vehicle_info.max_longitudinal_offset_m; +} + +void DynamicObstacleStopModuleManager::launchNewModules( + const autoware_auto_planning_msgs::msg::PathWithLaneId & path) +{ + if (path.points.empty()) return; + // general + if (!isModuleRegistered(module_id_)) { + registerModule(std::make_shared( + module_id_, planner_param_, logger_.get_child("dynamic_obstacle_stop_module"), clock_)); + } +} + +std::function &)> +DynamicObstacleStopModuleManager::getModuleExpiredFunction( + const autoware_auto_planning_msgs::msg::PathWithLaneId & path) +{ + return [path]([[maybe_unused]] const std::shared_ptr & scene_module) { + return false; + }; +} +} // namespace behavior_velocity_planner + +#include +PLUGINLIB_EXPORT_CLASS( + behavior_velocity_planner::DynamicObstacleStopModulePlugin, + behavior_velocity_planner::PluginInterface) diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.hpp new file mode 100644 index 0000000000000..e461cc9c16445 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.hpp @@ -0,0 +1,58 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef MANAGER_HPP_ +#define MANAGER_HPP_ + +#include "scene_dynamic_obstacle_stop.hpp" + +#include +#include +#include +#include + +#include + +#include +#include +#include + +namespace behavior_velocity_planner +{ +class DynamicObstacleStopModuleManager : public SceneModuleManagerInterface +{ +public: + explicit DynamicObstacleStopModuleManager(rclcpp::Node & node); + + const char * getModuleName() override { return "dynamic_obstacle_stop"; } + +private: + using PlannerParam = dynamic_obstacle_stop::PlannerParam; + + PlannerParam planner_param_; + int64_t module_id_; + + void launchNewModules(const autoware_auto_planning_msgs::msg::PathWithLaneId & path) override; + + std::function &)> getModuleExpiredFunction( + const autoware_auto_planning_msgs::msg::PathWithLaneId & path) override; +}; + +class DynamicObstacleStopModulePlugin : public PluginWrapper +{ +}; + +} // namespace behavior_velocity_planner + +#endif // MANAGER_HPP_ diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.cpp new file mode 100644 index 0000000000000..0411ab2d01cfe --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.cpp @@ -0,0 +1,71 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "object_filtering.hpp" + +#include "types.hpp" + +#include + +#include +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop +{ + +/// @brief filter the given predicted objects +/// @param objects predicted objects +/// @param ego_data ego data, including its path and pose +/// @param params parameters +/// @param hysteresis [m] extra distance threshold used for filtering +/// @return filtered predicted objects +std::vector filter_predicted_objects( + const autoware_auto_perception_msgs::msg::PredictedObjects & objects, const EgoData & ego_data, + const PlannerParam & params, const double hysteresis) +{ + std::vector filtered_objects; + const auto is_vehicle = [](const auto & o) { + return std::find_if(o.classification.begin(), o.classification.end(), [](const auto & c) { + return c.label == autoware_auto_perception_msgs::msg::ObjectClassification::CAR || + c.label == autoware_auto_perception_msgs::msg::ObjectClassification::BUS || + c.label == autoware_auto_perception_msgs::msg::ObjectClassification::TRUCK || + c.label == autoware_auto_perception_msgs::msg::ObjectClassification::TRAILER || + c.label == + autoware_auto_perception_msgs::msg::ObjectClassification::MOTORCYCLE || + c.label == autoware_auto_perception_msgs::msg::ObjectClassification::BICYCLE; + }) != o.classification.end(); + }; + const auto is_in_range = [&](const auto & o) { + const auto distance = std::abs(motion_utils::calcLateralOffset( + ego_data.path.points, o.kinematics.initial_pose_with_covariance.pose.position)); + return distance <= params.minimum_object_distance_from_ego_path + params.ego_lateral_offset + + o.shape.dimensions.y / 2.0 + hysteresis; + }; + const auto is_not_too_close = [&](const auto & o) { + const auto obj_arc_length = motion_utils::calcSignedArcLength( + ego_data.path.points, ego_data.pose.position, + o.kinematics.initial_pose_with_covariance.pose.position); + return obj_arc_length > ego_data.longitudinal_offset_to_first_path_idx + + params.ego_longitudinal_offset + o.shape.dimensions.x / 2.0; + }; + for (const auto & object : objects.objects) + if ( + is_vehicle(object) && + object.kinematics.initial_twist_with_covariance.twist.linear.x >= + params.minimum_object_velocity && + is_in_range(object) && is_not_too_close(object)) + filtered_objects.push_back(object); + return filtered_objects; +} +} // namespace behavior_velocity_planner::dynamic_obstacle_stop diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.hpp new file mode 100644 index 0000000000000..22857f6db1bda --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.hpp @@ -0,0 +1,39 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef OBJECT_FILTERING_HPP_ +#define OBJECT_FILTERING_HPP_ + +#include "types.hpp" + +#include + +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop +{ + +/// @brief filter the given predicted objects +/// @param objects predicted objects +/// @param ego_data ego data, including its path and pose +/// @param params parameters +/// @param hysteresis [m] extra distance threshold used for filtering +/// @return filtered predicted objects +std::vector filter_predicted_objects( + const autoware_auto_perception_msgs::msg::PredictedObjects & objects, const EgoData & ego_data, + const PlannerParam & params, const double hysteresis); + +} // namespace behavior_velocity_planner::dynamic_obstacle_stop + +#endif // OBJECT_FILTERING_HPP_ diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp new file mode 100644 index 0000000000000..98b7984bab1dc --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp @@ -0,0 +1,185 @@ +// Copyright 2023 TIER IV, Inc. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "scene_dynamic_obstacle_stop.hpp" + +#include "collision.hpp" +#include "debug.hpp" +#include "footprint.hpp" +#include "object_filtering.hpp" +#include "types.hpp" + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop +{ + +using visualization_msgs::msg::Marker; +using visualization_msgs::msg::MarkerArray; + +DynamicObstacleStopModule::DynamicObstacleStopModule( + const int64_t module_id, PlannerParam planner_param, const rclcpp::Logger & logger, + const rclcpp::Clock::SharedPtr clock) +: SceneModuleInterface(module_id, logger, clock), params_(std::move(planner_param)) +{ + prev_stop_decision_time_ = rclcpp::Time(int64_t{0}, clock->get_clock_type()); + velocity_factor_.init(PlanningBehavior::UNKNOWN); +} + +bool DynamicObstacleStopModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) +{ + debug_data_.reset_data(); + *stop_reason = planning_utils::initializeStopReason(StopReason::OBSTACLE_STOP); + if (!path || path->points.size() < 2) return true; + tier4_autoware_utils::StopWatch stopwatch; + stopwatch.tic(); + + stopwatch.tic("preprocessing"); + EgoData ego_data; + ego_data.pose = planner_data_->current_odometry->pose; + ego_data.path.points = path->points; + motion_utils::removeOverlapPoints(ego_data.path.points); + ego_data.first_path_idx = + motion_utils::findNearestSegmentIndex(ego_data.path.points, ego_data.pose.position); + ego_data.longitudinal_offset_to_first_path_idx = motion_utils::calcLongitudinalOffsetToSegment( + ego_data.path.points, ego_data.first_path_idx, ego_data.pose.position); + + make_ego_footprint_rtree(ego_data, params_); + const auto has_decided_to_stop = + (clock_->now() - prev_stop_decision_time_).seconds() < params_.decision_duration_buffer; + if (!has_decided_to_stop) current_stop_pose_.reset(); + double hysteresis = has_decided_to_stop ? params_.hysteresis : 0.0; + const auto dynamic_obstacles = + filter_predicted_objects(*planner_data_->predicted_objects, ego_data, params_, hysteresis); + + const auto preprocessing_duration_us = stopwatch.toc("preprocessing"); + + stopwatch.tic("footprints"); + const auto obstacle_forward_footprints = + make_forward_footprints(dynamic_obstacles, params_, hysteresis); + const auto footprints_duration_us = stopwatch.toc("footprints"); + const auto min_stop_distance = + motion_utils::calcDecelDistWithJerkAndAccConstraints( + planner_data_->current_velocity->twist.linear.x, 0.0, + planner_data_->current_acceleration->accel.accel.linear.x, + planner_data_->max_stop_acceleration_threshold, -planner_data_->max_stop_jerk_threshold, + planner_data_->max_stop_jerk_threshold) + .value_or(0.0); + stopwatch.tic("collisions"); + const auto collision = + find_earliest_collision(ego_data, dynamic_obstacles, obstacle_forward_footprints, debug_data_); + const auto collisions_duration_us = stopwatch.toc("collisions"); + if (collision) { + const auto arc_length_diff = + motion_utils::calcSignedArcLength(ego_data.path.points, *collision, ego_data.pose.position); + const auto can_stop_before_limit = arc_length_diff < min_stop_distance - + params_.ego_longitudinal_offset - + params_.stop_distance_buffer; + const auto stop_pose = can_stop_before_limit + ? motion_utils::calcLongitudinalOffsetPose( + ego_data.path.points, *collision, + -params_.stop_distance_buffer - params_.ego_longitudinal_offset) + : motion_utils::calcLongitudinalOffsetPose( + ego_data.path.points, ego_data.pose.position, min_stop_distance); + if (stop_pose) { + const auto use_new_stop_pose = !has_decided_to_stop || motion_utils::calcSignedArcLength( + path->points, stop_pose->position, + current_stop_pose_->position) > 0.0; + if (use_new_stop_pose) current_stop_pose_ = *stop_pose; + prev_stop_decision_time_ = clock_->now(); + } + } + + if (current_stop_pose_) motion_utils::insertStopPoint(*current_stop_pose_, 0.0, path->points); + + const auto total_time_us = stopwatch.toc(); + RCLCPP_DEBUG( + logger_, + "Total time = %2.2fus\n\tpreprocessing = %2.2fus\n\tfootprints = " + "%2.2fus\n\tcollisions = %2.2fus\n", + total_time_us, preprocessing_duration_us, footprints_duration_us, collisions_duration_us); + debug_data_.ego_footprints = ego_data.path_footprints; + debug_data_.obstacle_footprints = obstacle_forward_footprints; + return true; +} + +MarkerArray DynamicObstacleStopModule::createDebugMarkerArray() +{ + constexpr auto z = 0.0; + MarkerArray debug_marker_array; + // dynamic obstacles footprints + const auto obstacle_footprint_markers = + debug::make_polygon_markers(debug_data_.obstacle_footprints, "dynamic_obstacles_footprints", z); + debug_marker_array.markers.insert( + debug_marker_array.markers.end(), obstacle_footprint_markers.begin(), + obstacle_footprint_markers.end()); + const auto delete_footprint_markers = debug::make_delete_markers( + obstacle_footprint_markers.size(), debug_data_.prev_dynamic_obstacles_nb, + "dynamic_obstacles_footprints"); + debug_marker_array.markers.insert( + debug_marker_array.markers.end(), delete_footprint_markers.begin(), + delete_footprint_markers.end()); + // ego path footprints + const auto ego_footprint_markers = + debug::make_polygon_markers(debug_data_.ego_footprints, "ego_footprints", z); + debug_marker_array.markers.insert( + debug_marker_array.markers.end(), ego_footprint_markers.begin(), ego_footprint_markers.end()); + const auto delete_ego_footprint_markers = debug::make_delete_markers( + ego_footprint_markers.size(), debug_data_.prev_ego_footprints_nb, "ego_footprints"); + debug_marker_array.markers.insert( + debug_marker_array.markers.end(), delete_ego_footprint_markers.begin(), + delete_ego_footprint_markers.end()); + // collisions + auto collision_markers = debug::make_polygon_markers(debug_data_.collisions, "collisions", z); + for (auto & m : collision_markers) m.color.r = 1.0; + debug_marker_array.markers.insert( + debug_marker_array.markers.end(), collision_markers.begin(), collision_markers.end()); + const auto delete_collision_markers = debug::make_delete_markers( + collision_markers.size(), debug_data_.prev_collisions_nb, "collisions"); + debug_marker_array.markers.insert( + debug_marker_array.markers.end(), delete_collision_markers.begin(), + delete_collision_markers.end()); + + debug_data_.prev_dynamic_obstacles_nb = obstacle_footprint_markers.size(); + debug_data_.prev_collisions_nb = collision_markers.size(); + debug_data_.prev_ego_footprints_nb = ego_footprint_markers.size(); + return debug_marker_array; +} + +motion_utils::VirtualWalls DynamicObstacleStopModule::createVirtualWalls() +{ + motion_utils::VirtualWalls virtual_walls{}; + if (current_stop_pose_) { + motion_utils::VirtualWall virtual_wall; + virtual_wall.text = "dynamic_obstacle_stop"; + virtual_wall.longitudinal_offset = params_.ego_longitudinal_offset; + virtual_wall.style = motion_utils::VirtualWallType::stop; + virtual_wall.pose = *current_stop_pose_; + virtual_walls.push_back(virtual_wall); + } + return virtual_walls; +} + +} // namespace behavior_velocity_planner::dynamic_obstacle_stop diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.hpp new file mode 100644 index 0000000000000..c7bca149890a0 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.hpp @@ -0,0 +1,62 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef SCENE_DYNAMIC_OBSTACLE_STOP_HPP_ +#define SCENE_DYNAMIC_OBSTACLE_STOP_HPP_ + +#include "types.hpp" + +#include +#include +#include + +#include +#include + +#include +#include +#include +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop +{ +class DynamicObstacleStopModule : public SceneModuleInterface +{ +public: + DynamicObstacleStopModule( + const int64_t module_id, PlannerParam planner_param, const rclcpp::Logger & logger, + const rclcpp::Clock::SharedPtr clock); + + /// @brief insert stop or slow down points to prevent dangerously entering another lane + /// @param [inout] path the path to update + /// @param [inout] stop_reason reason for stopping + bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; + + visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; + motion_utils::VirtualWalls createVirtualWalls() override; + +private: + PlannerParam params_; + rclcpp::Time prev_stop_decision_time_; + std::optional current_stop_pose_; + +protected: + int64_t module_id_{}; + + // Debug + mutable DebugData debug_data_; +}; +} // namespace behavior_velocity_planner::dynamic_obstacle_stop + +#endif // SCENE_DYNAMIC_OBSTACLE_STOP_HPP_ diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/types.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/types.hpp new file mode 100644 index 0000000000000..74fd5ca818fb0 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/types.hpp @@ -0,0 +1,80 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef TYPES_HPP_ +#define TYPES_HPP_ + +#include + +#include +#include +#include + +#include + +#include +#include +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop +{ +typedef std::pair BoxIndexPair; +typedef boost::geometry::index::rtree> Rtree; + +/// @brief parameters for the "out of lane" module +struct PlannerParam +{ + double extra_object_width; + double minimum_object_velocity; + double stop_distance_buffer; + double time_horizon; + double hysteresis; + double decision_duration_buffer; + double ego_longitudinal_offset; + double ego_lateral_offset; + double minimum_object_distance_from_ego_path; +}; + +struct EgoData +{ + autoware_auto_planning_msgs::msg::PathWithLaneId path{}; + size_t first_path_idx{}; + double longitudinal_offset_to_first_path_idx; // [m] + geometry_msgs::msg::Pose pose; + tier4_autoware_utils::MultiPolygon2d path_footprints; + Rtree rtree; +}; + +/// @brief debug data +struct DebugData +{ + tier4_autoware_utils::MultiPolygon2d obstacle_footprints{}; + size_t prev_dynamic_obstacles_nb{}; + tier4_autoware_utils::MultiPolygon2d collisions{}; + size_t prev_collisions_nb{}; + tier4_autoware_utils::MultiPolygon2d ego_footprints{}; + size_t prev_ego_footprints_nb{}; + std::optional stop_pose{}; + void reset_data() + { + obstacle_footprints.clear(); + collisions.clear(); + ego_footprints.clear(); + stop_pose.reset(); + } +}; + +} // namespace behavior_velocity_planner::dynamic_obstacle_stop + +#endif // TYPES_HPP_ diff --git a/planning/behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml b/planning/behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml index b517b77b328c7..8b0e215bc550a 100644 --- a/planning/behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml +++ b/planning/behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml @@ -20,6 +20,7 @@ + @@ -41,6 +42,7 @@ + @@ -69,6 +71,7 @@ +