From 641ee8f69ec061acfac7d7e7053b638bf71c98f0 Mon Sep 17 00:00:00 2001 From: Berkay Karaman Date: Tue, 18 Apr 2023 10:12:15 +0300 Subject: [PATCH] feat(predicted_path_checker): check predicted trajectory to avoid collisions planning can not handle (#2528) Signed-off-by: Berkay Karaman --- control/predicted_path_checker/CMakeLists.txt | 37 ++ control/predicted_path_checker/README.md | 98 ++++ .../config/predicted_path_checker.param.yaml | 20 + .../images/FlowChart.png | Bin 0 -> 62997 bytes .../images/Z_axis_filtering.png | Bin 0 -> 22632 bytes .../images/general-structure.png | Bin 0 -> 84656 bytes .../collision_checker.hpp | 128 +++++ .../predicted_path_checker/debug_marker.hpp | 92 +++ .../predicted_path_checker_node.hpp | 171 ++++++ .../include/predicted_path_checker/utils.hpp | 94 ++++ .../launch/predicted_path_checker.launch.xml | 21 + control/predicted_path_checker/package.xml | 45 ++ .../collision_checker.cpp | 314 +++++++++++ .../debug_marker.cpp | 329 +++++++++++ .../predicted_path_checker_node.cpp | 526 ++++++++++++++++++ .../src/predicted_path_checker_node/utils.cpp | 345 ++++++++++++ 16 files changed, 2220 insertions(+) create mode 100644 control/predicted_path_checker/CMakeLists.txt create mode 100644 control/predicted_path_checker/README.md create mode 100644 control/predicted_path_checker/config/predicted_path_checker.param.yaml create mode 100644 control/predicted_path_checker/images/FlowChart.png create mode 100644 control/predicted_path_checker/images/Z_axis_filtering.png create mode 100644 control/predicted_path_checker/images/general-structure.png create mode 100644 control/predicted_path_checker/include/predicted_path_checker/collision_checker.hpp create mode 100644 control/predicted_path_checker/include/predicted_path_checker/debug_marker.hpp create mode 100644 control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp create mode 100644 control/predicted_path_checker/include/predicted_path_checker/utils.hpp create mode 100755 control/predicted_path_checker/launch/predicted_path_checker.launch.xml create mode 100644 control/predicted_path_checker/package.xml create mode 100644 control/predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp create mode 100644 control/predicted_path_checker/src/predicted_path_checker_node/debug_marker.cpp create mode 100644 control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp create mode 100644 control/predicted_path_checker/src/predicted_path_checker_node/utils.cpp diff --git a/control/predicted_path_checker/CMakeLists.txt b/control/predicted_path_checker/CMakeLists.txt new file mode 100644 index 0000000000000..d5e9de0addc03 --- /dev/null +++ b/control/predicted_path_checker/CMakeLists.txt @@ -0,0 +1,37 @@ +cmake_minimum_required(VERSION 3.14) +project(predicted_path_checker) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +find_package(Eigen3 REQUIRED) + + + +ament_auto_add_library(predicted_path_checker SHARED + src/predicted_path_checker_node/predicted_path_checker_node.cpp + src/predicted_path_checker_node/collision_checker.cpp + src/predicted_path_checker_node/utils.cpp + src/predicted_path_checker_node/debug_marker.cpp + +) + +target_include_directories(predicted_path_checker + SYSTEM PUBLIC + ${EIGEN3_INCLUDE_DIR} +) + +rclcpp_components_register_node(predicted_path_checker + PLUGIN "predicted_path_checker::PredictedPathCheckerNode" + EXECUTABLE predicted_path_checker_node +) + +if(BUILD_TESTING) + +endif() + +ament_auto_package( + INSTALL_TO_SHARE + launch + config +) diff --git a/control/predicted_path_checker/README.md b/control/predicted_path_checker/README.md new file mode 100644 index 0000000000000..1b194a56688ba --- /dev/null +++ b/control/predicted_path_checker/README.md @@ -0,0 +1,98 @@ +# Predicted Path Checker + +## Purpose + +The Predicted Path Checker package is designed for autonomous vehicles to check the predicted path generated by control +modules. It handles potential collisions that the planning module might not be able to handle and that in the brake +distance. In case of collision in brake distance, the package will send a diagnostic message labeled "ERROR" to alert +the system to send emergency and in the case of collisions in outside reference trajectory, it sends pause request to +pause interface to make the vehicle stop. + +![general-structure.png](images%2Fgeneral-structure.png) + +## Algorithm + +The package algorithm evaluates the predicted trajectory against the reference trajectory and the predicted objects in +the environment. It checks for potential collisions and, if necessary, generates an appropriate response to avoid them ( +emergency or pause request). + +### Inner Algorithm + +![FlowChart.png](images%2FFlowChart.png) + +**cutTrajectory() ->** It cuts the predicted trajectory with input length. Length is calculated by multiplying the +velocity +of ego vehicle with "trajectory_check_time" parameter and "min_trajectory_length". + +**checkTrajectoryForCollision() ->** It checks the predicted trajectory for collision with the predicted objects. It +calculates both polygon of trajectory points and predicted objects and checks intersection of both polygons. If there is +an intersection, it calculates the nearest collision point. It returns the nearest collision point of polygon and the +predicted object. It also checks predicted objects history which are intersect with the footprint before to avoid +unexpected behaviors. Predicted objects history stores the objects if it was detected below the "chattering_threshold" +seconds ago. + +If the "enable_z_axis_obstacle_filtering" parameter is set to true, it filters the predicted objects in the Z-axis by +using "z_axis_filtering_buffer". If the object does not intersect with the Z-axis, it is filtered out. + +![Z_axis_filtering.png](images%2FZ_axis_filtering.png) + +**calculateProjectedVelAndAcc() ->** It calculates the projected velocity and acceleration of the predicted object on +predicted trajectory's collision point's axes. + +**isInBrakeDistance() ->** It checks if the stop point is in brake distance. It gets relative velocity and +acceleration of ego vehicle with respect to the predicted object. It calculates the brake distance, if the point in +brake distance, it returns true. + +**isItDiscretePoint() ->** It checks if the stop point on predicted trajectory is discrete point or not. If it is not +discrete point, planning should handle the stop. + +**isThereStopPointOnRefTrajectory() ->** It checks if there is a stop point on reference trajectory. If there is a stop +point before the stop index, it returns true. Otherwise, it returns false, and node is going to call pause interface to +make the vehicle stop. + +## Inputs + +| Name | Type | Description | +| ------------------------------------- | ----------------------------------------------------- | --------------------------------------------------- | +| `~/input/reference_trajectory` | `autoware_auto_planning_msgs::msg::Trajectory` | Reference trajectory | +| `~/input/predicted_trajectory` | `autoware_auto_planning_msgs::msg::Trajectory` | Predicted trajectory | +| `~/input/objects` | `autoware_auto_perception_msgs::msg::PredictedObject` | Dynamic objects in the environment | +| `~/input/odometry` | `nav_msgs::msg::Odometry` | Odometry message of vehicle to get current velocity | +| `~/input/current_accel` | `geometry_msgs::msg::AccelWithCovarianceStamped` | Current acceleration | +| `/control/vehicle_cmd_gate/is_paused` | `tier4_control_msgs::msg::IsPaused` | Current pause state of the vehicle | + +## Outputs + +| Name | Type | Description | +| ------------------------------------- | ---------------------------------------- | -------------------------------------- | +| `~/debug/marker` | `visualization_msgs::msg::MarkerArray` | Marker for visualization | +| `~/debug/virtual_wall` | `visualization_msgs::msg::MarkerArray` | Virtual wall marker for visualization | +| `/control/vehicle_cmd_gate/set_pause` | `tier4_control_msgs::srv::SetPause` | Pause service to make the vehicle stop | +| `/diagnostics` | `diagnostic_msgs::msg::DiagnosticStatus` | Diagnostic status of vehicle | + +## Parameters + +**Node Parameters** + +| Name | Type | Description | Default value | +| :---------------------------------- | :------- | :------------------------------------------------------ | :------------ | +| `update_rate` | `double` | The update rate [Hz] | 10.0 | +| `delay_time` | `double` | he time delay considered for the emergency response [s] | 0.17 | +| `max_deceleration` | `double` | Max deceleration for ego vehicle to stop [m/s^2] | 1.5 | +| `resample_interval` | `double` | Interval for resampling trajectory [m] | 0.5 | +| `stop_margin` | `double` | The stopping margin [m] | 0.5 | +| `ego_nearest_dist_threshold` | `double` | The nearest distance threshold for ego vehicle [m] | 3.0 | +| `ego_nearest_yaw_threshold` | `double` | The nearest yaw threshold for ego vehicle [rad] | 1.046 | +| `min_trajectory_check_length` | `double` | The minimum trajectory check length in meters [m] | 1.5 | +| `trajectory_check_time` | `double` | The trajectory check time in seconds. [s] | 3.0 | +| `distinct_point_distance_threshold` | `double` | The distinct point distance threshold [m] | 0.3 | +| `distinct_point_yaw_threshold` | `double` | The distinct point yaw threshold [deg] | 5.0 | + +**Collision Checker Parameters** + +| Name | Type | Description | Default value | +| :--------------------------------- | :------- | :---------------------------------------------------------------- | :------------ | +| `width_margin` | `double` | The width margin for collision checking [Hz] | 0.2 | +| `chattering_threshold` | `double` | The chattering threshold for collision detection [s] | 0.2 | +| `z_axis_filtering_buffer` | `double` | The Z-axis filtering buffer [m] | 0.3 | +| `enable_z_axis_obstacle_filtering` | `bool` | A boolean flag indicating if Z-axis obstacle filtering is enabled | false | diff --git a/control/predicted_path_checker/config/predicted_path_checker.param.yaml b/control/predicted_path_checker/config/predicted_path_checker.param.yaml new file mode 100644 index 0000000000000..0aa577de3098d --- /dev/null +++ b/control/predicted_path_checker/config/predicted_path_checker.param.yaml @@ -0,0 +1,20 @@ +/**: + ros__parameters: + # Node + update_rate: 10.0 + delay_time: 0.17 + max_deceleration: 1.5 + resample_interval: 0.5 + stop_margin: 0.5 # [m] + ego_nearest_dist_threshold: 3.0 # [m] + ego_nearest_yaw_threshold: 1.046 # [rad] = 60 [deg] + min_trajectory_check_length: 1.5 + trajectory_check_time: 3.0 + distinct_point_distance_threshold: 0.3 + distinct_point_yaw_threshold: 5.0 # [deg] + + collision_checker_params: + width_margin: 0.2 + chattering_threshold: 0.2 + z_axis_filtering_buffer: 0.3 + enable_z_axis_obstacle_filtering: false diff --git a/control/predicted_path_checker/images/FlowChart.png b/control/predicted_path_checker/images/FlowChart.png new file mode 100644 index 0000000000000000000000000000000000000000..9d93e37390c6b78687c754fb3f802d04fc43f296 GIT binary patch literal 62997 zcmd>lc{r5e_jgG(mNF<5Vu)nl4aqW#eHn}~CXyMunX!#sBx5h7kV2wpA=&q`M^Z%D zlC2b3LM3b7ds5%u_mB6F_qyIc-ap>!8q@SV_j8_mIrllA^Eu~^$C&9KU_HvZYuBy= zh6X6hUAveN;Ex2^2d<3UgkRsai;b6t#?vT4F79OKU1CbeonK;#@@`&!G%+QVn4+Si zx3{d5yQ8bGBgIda>P!Qdz$%v(ru+MR`Rf8F^(H1vRXqf|!!-&X=mJnt}ph zr@f=AGxe`PQ?C$rGTBi~QBOry9*B~_D}ZMZ;FmSgpGx!J`EBA(^$!Bqg5atSs>(ap zd;@@N1$lK@`IF#|zB9?w3rJCvSC9uE1#n5v-PhU03p}Q$prFVQ&giN$&CzwIn{Xoo zA6*q!q^Yef+R{xi*q?-i@3aYU_Vsi3qW&F?f~PR;@DBxgo*B{Z0+ zzf%I_yZ@a8q>3fNPg%(ed5{4;We8Ej1<|ZkO;zRmn9_8EtH?WS~Iv#rdnM`YYfRlrXBc7KS!7V}Ex8oD&s{OC5{z3AE5R(W6-- zX(1kNShSy!NeC5VPLfwMM-m$gS{Z|d>jo&GZ9EZyDq@NVC0{h!L{}fF>=xi| ziLs^OJQOL83O-&`TQfHdxKFcn!U5r~7%LASEK=E&pib5&>BC*UjVyyOa20uH4=WQ- zI4;nIU>FFRs~EaCS$i9SCsf@m^sUS(%5Zmtr8AgpL|_Qq3`Y!fR#pXfm9cJyrhzU* z6M~wLnmJZqSJm8zY-E5ocEM1rRDI3OZJbCJUMi0M9>FewhG;8_Iu5C<Hu_aib!U?oL=$v^>@y zO(HofV07_DD0f3kQ&TJ&iKG~X7z9}%0`vag3j`62ZP8>) zT_-;aRT~vE1ku>jJ6H`tFd-65EeLR3f;A0^F}4V%xCOYN{ZySO{&-ugt~}n|(ae-+ zYC%B+=vo-l-~?YqeN~dbuL}unOvQNzsgcdhU6rsdR?hAUVCwXoeXOa96m{j`z>q*? zjF*xs%1qTw*V5775ZpAeaFoXoRjIDRw1y?a8>4WYEC>W{fnKNdTWD*P~osu7*-2I+I+9!FYL$ zg|e~>&A{CqH22d559#Uo`Vx%?H!$*X^&*?$z&}_=OLvTiGTtpv zA5PUZw6YDcatYA44M9@PR81^>LkzvtgRBEw{DOUKY5pdPN_b;cYa^Y74XzK~O>}8L8+ydgxh^72K?xkxn*n zih-9RL#(?OP9I1`JCpTX{D6QEb$5!N6%p&AKx6D+CoGN>U}0i~+cJjUPLkLu?}R&}Q-nc*DGd`%Rsi8wPX0Sn&bgrT_l z0b_`AGF4C|s4#}Xa+oU;C{FVJjy6O;AJafHHC1Z^D_t5f#1LntWQFxZdEikbG!KSiP%1*?RY z*ERMx(|32Z!5aZv7&{ynHg~DdfvK*a4=s8ytO=5S3y@X*vAd57(&Grd|89NM8cC*l(8ftInd0^ z-GJm|=tcDOrGlFbA+n5kFK?i3qjAvgQ$yf0*m0~MD_FZ z_qV3_nS+%>c$)a&v&;HqXzwFoeE$GQ3Xs;b*M>ZuSN89wL&ADRBgNz{rr^)KI#;TwNnVu#|Iwb zPsIBpd>J!<^9><-So!&3aW)=!imw`2OtPt-62U}8m1yf}sb&)73^%7yeGws!s>)~u z7gKq2gkg{+#?cbYyPgsNO$Z`GUlA@uFEy&GzPyuafU$zNA3=>q(sRQR0$fc@tc^(? z_z;Ytl_!B1|w+QJiR9^j<8=qU#8^ zOWOrvqjbWB3w-i-FJ8#KD8buQ7)LxfAfP}(>7aGkAAGvB`9-E`E!N*P(51??GW2u7 zmy<3xXNrnK3TkI(t?oaPte&I48>+cfWSPV)news1-<=b>oAHr297*;+TOgAn8KrS@ zommpQ_)6jo<>b0f3i3~j$U$fa?u!`gP=ID=p|c1Hfg~d|qa{jsgZVhUv|IB_kpwKo&-xKl`~^sy&M5RM zv@_$;Ydc*rx?(%-WFokD0pgT)fsS!m`;7hy1X;Y2yvMls>G*DzoXo=hIUXZ~L|whV z%1+-FAqJ4>c116%YtYX3k8GOIjCZYocM%<;ryO>%-p*{I#rRSdk< z(r;(*aZ*5Rb-x{bSq63}rxSzQ8CkE0Ff4^fR?zOyZWdSt+s?bHx#H+hkDfb`8?#Ru z>~v$lst&t}4pezL1oqpyrp9~zTKHi9{qrmP_mz|ndwK1~wKf-9h<&F%T}6(Rb!%nx zt7M0KJsG&Y^{cM^SSb1N_ea==liS@cWd*p$zNu0+E8AZEg*P`=-g{ZqJ}+rMHml+P z^;448`gBT?To}f^)9MzRAtW{C)@#l`%NEBJ*#XJnJsZ?CU)*w#I#lXR9jW#y^8507 zAyMv`_ZhFJKaZMi;vN$!Qfl@h;>w{yr{>G8O1_Ak#TDX{eb)ujO(1*YO|rEP>Dto2sr#9jp z_1>f4@kkr5!(6}zf16nR`t;o^BlA^b3;Q^Z&B++F3;12)mp^x5d*gm~xG(st-T2XG z{`9ch2mb;8y7|hC_rYJXKB#}m{3wIKyUI3f`l`8f@yR`c8iPUQ%np{^4PBqPZ~rn) z=0m$s#N24;x6^@d(7ZJc5nJ!(!Tc-~)h#T~$k^Au^`Gs3by-Mzlv3QZZ{beVLEo{6 z?X3oB#0z@Qm+Xk&PnJgl-cz1wMrz1DLe@HsDknS7&Y-8b6;L4C|-IIpj!}m>tE62h^)o9Zgwa^vvuc;djwfUwQwQY&K zb^VXeY-n4(mnUc8?c(dDK%Z7oQOYL>$T5GLr z0;nEq8~dqKUk1*GzRC(+s9CtIHtG$=;2(P|o<(qzf z8yge4A~xNvy-fq}xNqLD*n{^$NR()5Z*P`)zR8W|bmSC0$Vxt z3&rRLY;S0TjlXqbNz+3)Q^|d0>BRNhj2+-#>qDS9B}xi zwJ}##PR9^~)8rf$`kYr2>qX1Mx3>ZviW)`eQ!%SA9 z`wo?8ehB^clsefO4@RiP!p0-*eVJcv1t(Gzi@v%q5hR)Vrl#Ld#?(wU(^Y4y&arim7qWlXcr7DT${hJ=inmG32D8!6ESZR z*p42RdiV7H^&KlGq9e?MnErI#d?l%m*~Ma_J1SjR{!;W5Q$$vy2=-}+|2BV%)BUV~ zVFCiewm)1>P=mJEE}Q^W5#WcwVlMKf)om=)Z7IYZmOg=xf+FyAJ}%K8b3=U-(5xh= zku=9e*YU>4(RI2Qd2X;|q2|l&GsX}KFdomkAZfzm``Z=;FXrD{KF4{HzgZl@9;{%} zaaDjAtGG9E0u>ey&1N@Ts2U4zQ?+KvfsDN9ytt!J46V>=@~}nk+qu+->dqGJ0Wd^Z}rALf7B*_gh__)=&9un z(WlOAQU`DXNobP^ozuRbI=Eh1J+u_l&g}3e-H^54EOz)d`t+$h;>TegL|?w?ce_Pv zVw`mPdUjznFx_8A`wSUoL70hC7}`8v1$=E+G0~x^eAPIxKqp+#nn5LiD~bMEWkom)oHWOKGA-@xo1xN1B>V3f0EK z%HAT}M(cyaKlAg*#msv%yH+PED$MZ|iqgwe2Xe{mdqoz3NfXkR(N0}14%?;l#bCcN z*UU#@GmYqI=see#uL1MJHE-_f-xxFzqZ^^_?fI)DM#5YOiCl8$=`+sum=fu|jlI#0 zM1!Jx!Z0isY)kgf4uDz%r_cHLNWT=~l3m~j|Aodq99;z2rPyYT=n583{J593-97*S zaHngp?kr;maK?yzM{&NZOt2WfTaqvIPZWAyJNV4}OIG0Ry3e;f>$NQhFqi585W{xWZ;OiyQFFFMGMgdblPnN0^7wsW zstH2E^MOBX2LW7V0ce9=S?Kz8XlFaY<|adeuo^?G-sv>Ylb{QS8)SE81hWs!i1UT} zR@*RP*uAtJhXAz!7kwVrK&H+hBoL`Ng*)B7hX!4cvD2uQ0JlAOcXY%@Oc-`(;8r5$ znHXIJd!#dAXWj^4puNp`QO=x}{5ue)Lkv7sgUy)2^4QWlS?Xn_c8rn>lPx#G`SnAt zIE_ehMcxBH% znY6o}4nSG8r1hVf*v$z^1t9GK9N@MntA`1HW<5^F1x$r=Oo8%y`BQezE+Ez8PvN z4VKX{nMQSv6oYtT1QU&=n|WVCw{3Qm2zw^k0>PM)p8bVxb-t6EXZ}ab+&AvLvw& zFg~3rCry!3m$^D6A|F{76uI@@d%+8gGruEm?Ww!GR+E3beswRC?O{X)x%9;mfKM87 zyvCj#09euCSN8Vi2{!awv1XBCw>KiLA|0oHuYUXvz)<8vfHTjZG0r&u?$FN8LJ6la zmx|N7SZRd1fcY4$rB?0=lA+Pfvx$wsKz}?4AHVR;^>yZuiQB*SMa-pQbV3F7!}=OP zYV|&Lx+llB#pS~{SEpRF{QIr^K6j~`h5c)t#9S&uCqu|x9|Ffdtfi9%uNlK`K+4_T zOx}2L{X|ujVu{^_9XELa(wd-yqxb0XQ+~X%6_~^6FNNSHqU7*dq{`70$kWc>NRzW~?-xE$YS! z_{N0-ziI4GExoR_^~35Hz)Q6to_lZa_ezDjx;T-OpPdeDjj6SWaTWn?%B)ZP@<}o17&pEH!8SyIb2}IRwQC+Q-`RR8Nf5O(KHr|Z} zHa6IMf&T61OLFy#7dIFo9Hr{RXYyg^Um)tLeq1#=43zCW^`%S|EuJUmh>}Znk$qk5 z746@H6cEHMJm>eKom!~A+wi=FLwl~MdXly3ToaQVHirGkBnYP9zd+1amnL&&-H-f} z;?=gcKKtbSFhB@5-UA?JKe0&zvD;~|Pe#8YgFtLiKM1=FUN>-=PoeqC6`fJ9nkk-N z9ims9?g<(}oS6%_cD#NES0tVdrm?y4tzqo+_bw&s=dPR78}0Crv z$i2YNH(f(!&57ZwTQU69#b(I;Z`aMWhR%O~rRLen%Tr>i_JL-qA$Tf)22gNOx5FSn ziR4@(^FJm>ID?reLoW^=7k!(9+~3V^QT{?aBWSi`vMurHG;Cac1lYoII&_jr-;L={ zc(Rap(QyzeWfMw+u?959Hux*u};<85FygQQS%9BfDq2IkY#&W81l8 z5M5d%326ujsI~#|BPbVeadUA4$gRJ^$#XJh2G9~35d;PaBp5g{FRAeL5ey_+7Vp!tU}O<>t7Dn*jX>yBe@>ixe7ChRc`Q zW=3ktPAxX>*;>+VB%qIm#RvijBL3*djuR?16z)erI4_VCk+{QvD~$NqacQ;5mTw|b zET$r)_z;Zljdw|B(RUWfISy0y8rAfA+9cBAEs&ew2O=%AU*l06MYj5G%b#BSuEl#E zRin4*1(W6_dAFp^0v#(7A6=Il~CoS{^r?ghbqb`+8vE*DjXPvv_tZYS~p0E@#y|%OY zg=~^(dF&?b?Z4t3p9l+YdZ)M;oi=8b|9(KBt=L}tA{`_CK+<%_h?6;ibK2wXl0OgP z$BcVTA_-t`LSgS;+q4fjCq>M2UPx2Z z+aKpblN68NSbo^>d%eJco;;z!V=pZLHOfA}a?`=+g8O>BQitU;gM|G?kUWS{>|dVk z8t`Pt3&gZ;UV|o>+n>C@Gm>p_5J})H!~r~VZoYqg2ex)4g`evhq~pZL0J#vaqYlDiTw;TP^mq@QMu&S=PQvd zd()9=?!L=LoqyF!_7{tJDfNG0Kiy1N3egc@xV_HU(T~En)^m7uSkmMoZ=Vi*Eu`$$ z6P=c*FqOe=Z~wQ)y(g|7hP?&8u>>#y8!rH(VYjaS_DHgL53n^u*H4&_wkfKg?mc4t z`7cDe17Y+f;6oa)WAllX+wWo?MUTJ$o(dYM@Eq8`4OHg3?|rOf{LUz~I6KmyzN(u2 z!N8Z*wFDrZWSL*^t0=rKZt4pR-{9Nq@OAg^b~1N6#r_0US2q~=PN!zbB_j)W-z+O5 z1dzVx#?JrpKX6pJ<9xF^ws|ibPc?%e1J?0X#HVEae3J~-$CQJI&Cxr&Z3mKpGxvs7 zQ2}w4%`gvD+cu?174FA;uQ(?cSQk{*8(tT`4h*)&2&=c3G+U0z4lN$1!xXs;1u^RG zQ~2Hb_>_v{1D=Gbzb@o71G^Vs5E5beMizf3PZ0r-a#$f3VnWF};U9A21llt}N`!U;eB1BO}G}0~!JEUcmC-G-O zgqe;oAf8r#c-kiw9;xW;@_$l6tiaHgbmeVB$Kux2-`Gw(sZH zch{Xo`Bjp?3={`^)&kK}gSc7dv?Q(&{_(w6!_(%gCLMm#lFxRwWDLu3)*OQP#bPy4?7rh-c2DkW+UfE`uEjsTe(h`giQ9uAi87T2KQ#qU zFxkS+5#2@s{tI9D1tL5QPWD0KPAu{1@NPQh{;|^`m-yh`=d$W0YgqZ&m|XH``vtrk z+kqLde~)*<-`v?(afc&WfmI0d>`GUt^Pld4;f~n2e2;BRJ400;p!ba8CcBsKzm
$UW0L#y4b*7wWz}OPoXXyITGY)j^nx9Rvf4D6X2% z&&hj0M+rMIA!FEW-xb(AF}5kP3-;_Vj7_zRFrI!?%w?sKeB8TYDj@_19`8_KT7^8W zyh>`b^zn^v1VHl@ZCxS|we_U*TyU4zoTTyYNWOCIcVJ$1j)0Aky8E`-tAmkzG!z$N z$ene{H^xL zjWcS6_e^DHH3St2?7<-q-C&6{9d->7Te@%cf%ZFFQ}X8zn=&h!17r35l7F-!SDdc? zaTxZwM$+<(f?I^e^ZWJjI-h_;LqAJMY5LO@^$`u>C=Q}k?_BofBi9MVE zke4Lg4GUo(c1T$|=_LXU28J^EiHNiOKEY%<=Ac?15Gj!VBsX5?GfN5qA{aVXQUo+= z0Ypr)ezJ_zo?6HcHvr65D|&}PFge2SRX@>Cc0S)O&nVR{n$>BjMkr$QjS9%pwR(>E zvEi}HJ$6sgc+4&DZ4W|J}wtn=TEt|RO#OzKpD%S*yLCz|0*!_M@tWfx1RhIs-;8yD*yPCltU@}sTARx74 zQ{?dW7H*sGSZWS`~Z9^&f|Gz_14P!I!5RvV^`fXFa!joE1zCg0NJ~-eZ4Fn z>H-5_WvB%*Qg01r8^9pgGon|JY?=WP@R!Q>)Kh_LQ#a~B^5?zK`wCB+s_(B))hWG( ze{}eg_Hzia5eCp;-$|p9_YQ8()(DZSSC~a)=v-1xU_d`PR_sCW_&5Y143lJKOB}y* zQ^~a!oyb!oQ#DeG{aLsDdt+n&DqzQN_O5}y9KjkjiLykcpFfaSe~&js z3GQT#bWCq4zsLf}`&l1IXMImFt(Jf(pI@g{g{}FzW-N-I{srQEKYmJiG9#PX+a1(& zgjV^sjS-oD-v*{(!>pwGYA*B<(Y;W@|9NKs@nJNSc&_Q<-rrvtxyHJM+Sz(|riy3( z(Kp>*Vig6=LmYGrfEJsHjb^9jQ_AU#+=JIg5VH~phpw@}7WW?s{#Oftf;Pvl7@R3Q zQ&ki?lXqhzn)mE9_32OCHqjyzx(;Hs`eLuaVn@On%fTYcyo56)BK7%Ki5pVZXZ=Cq zO=pc;!UD1dG9(LyWv`bx439mke=Nc}-BWT+b9?hU6(l|vK-Ty>j(2onO`GFSI3L)n zHX3yIJZuE6@_f z^IZc;(!2mToj~motDx0930N!g3JGN0=U2BnrJnp~-dEC=q2kpHURU~3)(>R&D?&jE zc#~gE5Z>bB|Ml%jMTgTNKfL34U@P=f}p$=wA)RzR9X2RdFwckzB=wuXD{K*lrM_Q^aaxmrIICwe4+zJA_u+NrE zDyePz%;TEYC&-roB|_rO_?HqS@+f^QeR}Q%<=MHzay+W^B|s>AjBZpJu=^P7*Dc1H z73tMQ+c~#k-KUEaXnJ-a=r<|ZBb-8>`F zabFH~?`7s}nP#MIkxgQ@!faJAmK@@@M>u|J^@OvyY#`u^-^9#hr1hPC@bY>3h0CZ- zHx1&u&9(1iWgBS<>vCnbnZ#&li&_2YiBlKx!i##*V*AU~CS&)jMIQVHm{h>MqKdDH9eC#W&ln2-#~1xp^q!L7O5k)(DnVv%Hupf9Or zNzfUr(-`M>Z?SQ!s5lXxRJkPMLkM}{Zp~^IylL?@!LY@qvj)lA=i-w5X0AeG?0DZ? zu+EbZf{m7zJh%te7vkKyo+2$wn6@is=A2G1zLR_fEUw@&xu;2uz;yBCVcT zL!dKmyBkn2Gkf0vEHxYPaa$m<1HCBRIgP(~Aue|hYEXZgP~&9IxV`n)bm9LitCi+(Pt758kw^ZQhqheeKy z?KK7^8c?ej3sWc|81reQ&08-hl)GH45V^_2EPV;j%*JsUHVFONx;5y7zUp1r|4$Tl3UDv*6x0b2;2%qf4ZF}rFj)Ksm(fhyEZ@8)*Byq81H z<>{hJ`yNe5y^kUmsf;b?O>+{T>J16&^c#GoVl;O zw?*cnYNybV0mtxkrkAX8`{Rb25pfeIZu8=aTzi;qt#q^TeDVIaubXMP)0m|@3VU0u zp6u90td?>cW3NjFr1#!_mqK!V%D6u23=*HueVqOqU69Js^X2htquZ4k2i*jvm{^#* z2wLyg1#ho8xE?i$*FvoB7p5+%kI%F2rZfblgvIS*Ul6| zrbzIjkEV!ty4DpTPFzOSXo%K|k51{oU1D!G>e}ksa(LSl>cc@`$*Gtb{O)+^9m)0Vp~EO)D`r0XV%L{${K@O> z>S|FrC|K)zVGfy?Tj`gh_k3a0bEP3kJx%+YA<2#M5FBUW2~BDB*hcAtg`!=P|^3J6fJqUA@ zA@Uq_MeVxO~Y21P+~tP z<@lnIhy(k8@TJ7>at6JeVywBD-f6O7*?wby_?R4)%TCh_ z6!@xN+K>2P)QV^Ls-4)_RN*Am(9>a{roDYqUz*+823 z6j~G|cJhs_#!wlZmwj`Wdo2FyT1Gr8^ROB+x}MK552@_9)E1nvp;-*MziyWbC1j+W zCN-3(_8_!$A65zr+8kxlaEe<$Vqf&9Qwy0pFAE3sRYfbNbrUn68IbGW8!Fy{OPf%42nT=sde_@$4XO zufUfhB8~>^1^R|;%K3wwZB*Shi22fwv0t|<8~3%e_|?qnDa$nm;)KOSyme z3Gt=K-$zR!=mPX-b1Go+?-yD3azPkW2wEccj1S;5DrauEaS}_=Jg@RZNlS$O10)u1 z+{Y8eXx7B{rKc@|_g8WpRdTsB#*}dS$cq6G&Ev_H;wI_iYFAt`#CewT1f)@&B02Fh zhi^dYjuy8X7ay=p7r>9CiP>E|uMkykdnfg=+o0DKL6Oz0JSe^+#aRmfGkcykxc36u zeCYToNXqrcS68(l(i|;_2Xo?$xzFa#HOd~6wnZAKWH~wCfU=fZOFYJN|Dk;j&GO*F zJ_B;6)Kpsx*7|6oP~vsK337BZ>nG{l&J`&}-h>w__869S`JxzAqwDMZ9IDZ1_61Wz z**yChfs$A37dd<`H1cT%6&ss8sopHReN^gp8B%v}H|z(9HVP|DttVBWh(eKWk6C6E zcR^iQDAQzg$G5plIy%Km+uUaGrYD216P62ylhR4?e3h(3ewl^CC{C%mvZLoEXAao} zu;dhwL)B^FOT{I0OWx-@{8( z*w57UtPvy6nVv*(^MCDaBKe&A=~GE}9E0~~5yy-w1)4AF>UZ&&GXkJ7Qc}{Csv- zm;mv)o_?%-`7~4f79ZzPa%k)5O+~M}G z&CiGCf_di#4DP?UeJv82%k6Ua95Z(=%Vw5-CBjsJ$`o=7xr2 zw@GaV<>O(XklK?D9eDn=M;bX0`_O+|uO2V083a4?s`t`zv z@Yt+_&_mKI8E%}Dz$?bJ1)t;?AZ=@{jEgwLosgEB`x&?EQ>|SANJY7`!BG7t?`Qrg zTaa5}WlIP2*P3YsXMUWmwC>z@Ui>94e&NZKEy--K7+ighBv+Ok^4PQ5v(h`vV}kQb zBbh!h{D+5+*WWb~qYvuv7MK-J1PIeXfytCwGa7OUkSAVu5`TW~L2~>=hz?F2b2wVa z5eaH%$8R9-?9m3?_}0|}*|dILNKEJ;c>`d%Up%*DDhG27Cay`)2g~^j_Vr6KrAhUk z;AqN!jyH!|fkgO^;E7+LBp9$(UM22>#W^G^O3ZbrA|xIg4Gp(ue+P@P6f~0V)Q2<( zE+fvlu}kr3nL?E4uYYfR`*t>DMr`{OVj9py1kuI8Pkc=;_6m-p$Vh?Bj93-Ksplv*nx-{t(0|ns|3|OMgYo^I~CkKKaH|)=DWq z0YMQ0YxU+ys>a(vAiHB8Fu__E*>GG;&!iyY((LR@JxBKMZYNh#bq9Zdy7k1zAWvNb z@_@B~3sQTChUB!B;4>1~@Kzmtj8crO``pn`9*Ls(pZ7qTxCpQsqq*2?(2M(dgnG9C z9k#i6#M$HBqtv>!&lyjr3aYOz^zivJnFk3I6G|Z^k?I40p~~L!79-z2zcLiz9F=oQ z8iD^{WV9cKv+KA8?KNv23Xho%nc-?op@>f{1dLv#b-(Ie+M3sx2-S2s`MuV}h`Ffp z?gQ7o-()Q}^9xoBm|yqqmXCQb?F|6apkJ|Vnae?Ab|e9BQyeZ#AEfaXFbgV2<|s+a zg5_O3w*_NH#Eo(4vq$gUy>wxUX(<=+!L*m$fDL7$MpacLhtGGCe>5dgm7wK}) z%;I#5gQ|rtE(9N#Jq$$vc;xV8nZ(#_G2^sqaH0e*9R$v(e9uS_?LBvm51NU8b8QVG zmLHW@SbbFm=JdHV*hQ}}ieL?ml;A3kZRYZmukTn^RZLj3x{VUYP>ApSp zuCbRJZrm5INa5Fa7w`%FF+I`7l+;FBU0ofIZN^|XR_3?fu1wOQNzJP-egIxAkp;yY zt^yHdKKxtN#?B|2*AA}Im)uuE5^Np=WaY%T$+MeF&lT|be5^o$rA^?czkyR8qu=5t zQ~}PAz|$}O7+eh9TwNMvIg-=jEtI95%lak?sr-_4eEQYeqVA|z zd@;gNq1im)$eC4$!d&}Rp``IVP6UAK1&mWDr?+$IP>KMoRUyuXuk4}vZ?iZXX*5Kw zRrdEe@~uoGjbtcd-yB8Bbm3_9Pl4q*$K1($gGTDY-WB2ZEeE%y+pK8mfMxv*xpy4Q z$B}hm#rl-$B+O)?g1{Y4%`W!Y{>K?r)#t3weLnQMja|w|i-$`i1OQkSTnZXeqU7Ft z{M+Isb4#!iPowwD?k#%(_+aJj(~}n`#FI#0;ezS|jYr_=Dlrc1IH95|&KDbAa74mj znY9gTpZT@zVt>XtiZUaJA)q>Jc@5>Q@HVDecP{zFvNtHaS>L`c=TbWn6;+(8t#@2x zozDf)_3EZl`~54^2+cHQ&r5l`SUFBBkoVR#_kB6ZjkJxkrn5VnWoij2i@}NKk<*;e zC#whe-Q(i(?4Ly~C85xs6vZ<}rR68JFlb@kppKWj3;yBdwq##a510Wrg!S; zn5z>os_XWU>lSi{g-Gd{Pjc?1Ac2suX5={H`N_Urt3CMXhr(QR< zmGXk67)zJg^SG#$ECjtLJKzTxiG5H?2y#?RPWH`f&TP`F5sF6?!y`>xv~t~zA?R{q ziVSFiVdSqbTEwTIbPx}YBi?M;BP445?`DEhl9VhkzM&(M(T6~ryj>@AV?h$_|L(C; z?&8yB;l*gPjI`5YdBRL>+{I6)!pqN#tG!Y_p>7;&j{lcP7Zza#1mDLe3>N+|`EpI% zCxf95G*iRY3V+5#_-VisP!#R8Kt7(u_+LIAMb~MGInX`|O43dU1&;V|zDO=jPGmk7 zG7VcvLak>qaP8EXsGY@U4fvTIb z8K97X{+~hy5maMLyM|ZQhk!uMpKq-yL{ns(#q=Sxxj~-^P{j4R#Ia<5sl{>7v6KJP zu}h601r|Wa((tE#1^KP0^S?d}sJQhA6VUh0e zeYf}KH?M5=EeTW{P>a=6*#DGq_=sIlc|g$pd}HW-A%e5O5WH9l^=~0{m?sT{i}#7K z!fc~OaM!_mZQ}mxy~#S~4iGG_t{q)DS%7KvutZ2~vL^qhyd<)kv+*eXr)y1{5UXPM zzFcdWNu}csIdN|v01=1(y9=U=k1~u|bHd*OlGdv_w$VLnxX=!Kt1iv`6e4ip*b7fU=BvY60-G&bjQ-bv&^R7!B%CFmD8Nc0f>6oRr zz_hqopFCC@E%>V(ov+U@T#QfSub4ZzZTWd9kPjSg@2!7FR7z|hv>N?LL8tj1p_UY* zAH<(mD;@vUJzw^uje~93-=}F!itY8hdv+-#wX}D6t^6}?^@|Mkb~h9ouv7G=!mN0b zjxSs~nn;ofC=IGXOY4F&ly!R%GdvrbT_P>6GBS!E*IQV>sDR zSmLzn_6&LHNTT#MVz5U9=~@bTxRqvb!DsBJ%(CG~$K*$zUnZ*yUK<;ATvolice++% zAZ&$zyyVD@aV++dp4^V|qbVl#KsG2B(P6exjaT`~T8gUT&~fK`AhCqaCumUnMoxy^ zm@zTF^6LAbGhY+36;&fVv7I{qjaxeW&~im;=1%#>4;D>V+fV2kIiP4UV#lw`C+6ELdzDbT-BARFZUP zGdUkdtm#W9ih+8*{Q=g-F*(H^(btf{Ww-ZO9XY&HQ}?Ink3I|BN_}Td|22ZkQZ4=X zk2_6W3D zeew6?M`Su6ViLT;5xZyyb@s~#%J~Z0puZ2N?3A+UWCG`huC4^f&5AN>{byGmgUaSF z(QLd)S!!ORmtiNKeA*f3q&~wN`-{U4Sx#Xe6Mmu+0|P+rx)YpeKKs3yP0mg;CV<;WEz{px|M~3$D4_3e07VU+Uez%EmEYVTJMJ1d z8vI2j2%Jxh*!p-y`*rb?QR$7TlpQtK>H5>fW^g>+LH*SLC^iUHCBuYI{Hp~Ra=Jbr z%OQ03K1c)`TKzd@4N78_BG!M*WWTpJd(=zpwy`13D+f zFZ9n0mXJExPne_^4>P~X1qE7~&KIYp>wZlBkbCm?IR7N#95`|^Qv(V^R_@Y3R&V+# zIPfCg2ONe@XI2n>*^X+fpg%oZsQc@fW{^DcY^revCqLrM(9_UBYC=X=&Mh?GU!C!d z+ZBFyrCGBO9LBX~_-DeQ$7iajZ2yb3vkZ&!Yumjb$j~!1NX-B$-Q7bfNOw0VErOIH zFu+g}(kUWJcPb#=B_JIN0#ZsN0laNOxPvwJnr3#INF_mQWRPI8HkJ< zF&ctW$v6Kp(Ya%vV`3sKAg6qK18fsic6(x{EexLk1MrWF!_nNUDO301GmwS;V4`gq z`^0lKHvm6xWxG-VWW|+1s=M9$!Pv=@@4_-qewevM;bKJJQs zRe=8r24pPD>p;(4JP+)mHWjD+w{si8@$|{kWRdPi0r|)E3>Wrq1q+X&fihQ5D0NDN zd?yDuCj1ExuNOP#(z?rnV2&`!=fj;t$xQ2Th2u9dmU`6xynA;zgTvQFB{~9wPaIa% zBS;v=w+tV*XuLN;`hG2~#cU7*~@>Q85j$aJK_nkP}*d8^vs( z!QtHw!+0hZfC@-@xue8K*9xBT@>uAarHkZni8aF*!n+5x@5}m0V*%p)(PlZIg0nVWE zH4xRY?7VFhixEl=|7X^l#h>X)eNdZ@#q$`@15C>Bfa} z&!4lE$);x!+{IhG#*X;H-vFoG8nOT_p*0csB34_n109GRUyyn@*zBrNv} z;Qy#?Ww0`Fr@AdP+_!-Yupmz%VoF^$Y;v^m`|D_`IC}9%$t|y*)EGPD>&oh?yj5d% z4~tJ{iYqs+S>FR2u+My)V-g~t`OSTdC70eBOVp5X`~UhHk;-M!{EJ?&`^Df~_rH9d zShq%EW&ko^+c-%3opoopG5i2%v-Wp#uRzXazOBvdB0?zr*7a|P+K^qBoXgXl+6j&O zLp2{YfQ?M>xv=0}5VnaM5=fKvTq^R>1N1M_A#^flm71+M(`cdR68I zL`j3V1Hfj|Kj*FfHvQqt2SzccFCX=*zOWF=MUC}Ly;5-l7=zs**n2l{gtj#;08fht zj3I~7oXg-v3NgJaiusN^tC&X&mBx-O`$*%)JN!Y=%NK-3BNa(3LCjJ1!;A%Lx!Unc zJf+Auq0eYYFo6_VSS`H%6}Nw0=-M^zHU9lF) zT_B~ufr!oMZMs!D@;8wB3#2;~ard0ZOP`O{Y?t;;)*ZkXK@eVq_)ip=fln}!?_wbJ z5p$HRfh&ZUeh2pB0-%69Zg_Ayy{^zXY(>kNaqah5O1JwnASa!!`j{;~>A3gko`egw zNKsol8{kp(o^tIXoI-t=PeI=c(FUAMCv87~P2@5#gn$}YE>!ankeiP28TPXpX z567&}{ps=PHG^2Y3L$ZJ)KJY8#o-Q|?X>5_*?;zc*-2;-C@*nu<3Ye*qCbGS{?`&$!0@A2VjRdD5WNxu;@jWa>%&Kv zZ-v;LP1)KwC6w8BIjNk2P@*-yzG|pkIey;LKZm(j3%09G$F4M7&N-J4_C|i?4GC0! ztv(Y;x#$IRMwmj~N!8ti_vu|sHOHAR#DU90S4ttGJGkxF{%UHj_mr{bEOtR}H~iy( z?G%K*N1gA(vU57RuaD}UF=wPXdN)ITh&zqXx&wKWR&GH$dw9F|%%ll{GO6s(-rXN3 zQ27qjgghhOWcQY2&vyiWYPp`z1Zr1SEjQ$`W_^fsY5iEdSYz!)~f&IhJq29nQSw}GNA-%4N@Ph7u^h~m}{ zWFblB!mPg>Ugou8*UbE$7O6bLD%bV*U=6}H4f@^`5_`EG@ho9Mbx+6??t?C)Fug4r zm9N7}_I!%2D81h)jLV-cLzI9&_IKe|cu?E;1;}eOrCOvN+`(HpxZ39#VyndlE7Poc&Uiz1Y zr;YdNew~AL#?qxGI=A+#wF5P8lqIEuNN*K6aw;L$nNs2xu!vor1Ho2Fg0WOn>TgOz zv#PF>>MBR1Qr6awffllq_lor|`}HrmlO(XRY0Rkj8PQ(e!OoJCFxA6P4D}IyB4;dgP8-_lmWP;pZv1N?a_e(0eL!myFGUnXYGM zP;^^lczjmDx*h24B6S%`l4NvS#iP1D0}r`2ae6<%xi~Z`3+sa$v{|I#Q8x1##yyl7 zWU&Mj(pe&g2a?!AbXuAE)p{)i9tiNk3a?24n z(5#_#DAmdy9jsS_bl0<`X6d{Pl8RYFNw6|H0p5w?k= z_6lF>yfEGRQ8#S?Q%IGZ^#dzL_L*^&%Xud5`OHP4WPw@}D;bhKKWaJH7>abHq0Fk% ztofC$^cErg0Or}{IEe&r-QsSTU)PA_&xILfqAeG&L}{-w^j`q?A88E95SaW=9cKsm zNIttO3FOm`=&^>ym+kTmrHIK6(><<96Rc#HDEdCvqZS6PXKq!Pfg6ip#x>+Mer5Vd0 zDY6!b5e>Tmx%)^~hOW%*eYwoL8;3T6_V>J7&7T>`}>DOCS zq&2_X+C2k%uV5xF(Jut~I?V%5bCgijDMc@+EE~|*-VY%p(K60enMx?F>LciVQsaeb z#7)V#nwcIO3Y3=gP431LkZXuYyH@NCNHWRAydN;8$mw$PY~mv0sz3O*iWlrt&DTGU zHtc~=aYcQra~^T3v@;71+Nta5NQ91XPGyl1i_{X`Q8rLt-qWA|UY;WEne2;?8sn^J zUa4P9NqxH$rUKT{S6Wl4<2pEa2kK-$5~9i(LyMrZunj9Lq1)0 z`y7n)c7(^HuqP`gI&UE?ev!}(NWPa6ozBrdKn(|!GSWLpTbDfk(aL4{BXjw zr2Ih%49exOm}l*0JImrkZ1SB|EpG9oFjj zJ=!9`B=6_>>{ZnlzBlGGy>UO4P1PS~HO>DSt)xpSvD@^nUry8Zw`{Ky;SzgihKe^X z49K`fXEn%NT5B&C#lWvxrw_DOS-on^`Gn|vAR_zB77$K#d?B+{n16AYlDdkq7|cQ< zB)`83y-?#9%%<(Os{Imlb)LKW%(01N{_7GyffeEM`}-oZU8gr)PSlsH!J9%otLedj z{gmSA^-&^IrvBNGO6S{oJeq;wek}{6li>ERpKbuTK=M{< z+gkdrC@VR#&{yI&kd%LV!V0##g@MqVfoH zbPz{@Vhy?f39Gq@uF@@T)z)^*gbHuJEMelMtI5xH)pYLw23fzQR z)*DxRR26{R4RZSi>tzIp)HLzR9CJb72D{z2?`XpX-k`o%bsD0^hH-Q4PE?}BjDET% z0OXK4HJ2QODx9^vrqN5jU+WEo1J#cc9Xa9nfSxE4o$lcWvOmBGyB-{2ROJqsec+56fCnVR6LedwsSTd-Ug^n z6+ugfI`h@`YFFcnWu~G(-S)wrM%*A`J>7iL`xk?Dx3_OjjS6Da-<0zXmy`@c4t~nJ zu=OSDpz_AC1$jouF*ZzPkip=4B4jl`MO;2A-n#=g*W0QCSd^Rx z32m@sv&V5RJS(S|-Jp!Mq8IMZYJ78)E}T_!t;0#E_*+0+m^a$xMN@=Q7pa2gD)&lS zOry1gj7``POi#tAD>2j(N-947ei=bBdR2vP6JJ26S({lWeB}z?qH*l~O2-5bUsXLs zL~|8qa7ioD${+)b?a;gY(Y`E#IH|FfqyegPf{&#gLO$K`|YC z*XwfA_YJ^bLy0o!N{~U7-MKmjBr61cjq6t79(cmE3C9#6dHki)*%H=8J{AjB58qrz z3R!)HUw|F?(m0AH4_^Q9^MI)-K?KG+@o{#(Rpig^HBK$)3`NR|$Oas*dnZ!}a`ecF z!U2J-HUyp}7Jhg)I@1m;NvE-lUwfL2D##T0gu<;lxuSpS*t|OY*2AgBXIW0^&|Yli zt}dE(yi#2KCb_`NPt8Gu_(fi`!2X^lQ33_B8I}W_hA)J3p}*7Gt9%f53QZYT!m=eE znAT@UQO_H3`9XdHKS68u?EsdwV3Qd{*F1-TwnP|^cq}h-8j+KSX=xki;Ye(H2EoUx z9>&s(kAK8b)Pj7q6YE2SU|Gw)Pufjz+$^A~8u;=u^c8Z9FWq;I?o}Ft$Y_>gA2xV4pl4<^6x{TWO@Z!SI|MUV5&+Bni3oJ*jfe%FpJ|%3l#h zvGK(zHe{WCP6oND5{<4~8DF)KZ{~N7nZ23zQBYd6g$;~~H%YEDTwNN_RqwYUcEaYI~s4q$>sZbR3RGzONuS)OBvo9()E9=2%uv)%iM)_j# zY)LFQst3LMNQiBd&@Y}&1d%-9tD&x~0MFmfS9l7(itJ-7f0uc9=xTHub8PqSc%7^c z$wNO-m-5BGvqLPpFlLIPNwFECg3Eo0r4(j_!08w{vY-(7&8J0Qa4p&sy`&0#>j0bx`xPLuD)s~L4+ z(dR`q!ouvVCU$$GKF( z=Z zI9W8(9+hi7!=cOI-GCh8&dpnxY|nUcuU=v__D7Tpw~gd{Q*H-@uk>h59%iO`_obfr_25l$|L!IhnQ0?^@af7U7bv!&Q+cn;LpgE%I(yM_mJ!Ff)O#*C z+sg*?HCC<1wiUB3u2ak_j8XP|b_$YhJ={NK01;w4Z_6(}oEA9M7~d1&ewheO&)qkm zgRHhb#vxMSM=4%csk04c*8oE{_KpoY1}+kQoo3x;hLD`2)0SQ#-x0=3C+*%A=-x5< zMD?*5`7L!1vHXJ@&%+?rUBmK>!~3JltiMF|Z?qAky&*wtHO*o-UmUz9fc1(Ky@dN$ zk}wac#(C|*{DG%x`WFN~UTMMq#uLCoehc*xP7`=VlNlX^TQMA%W$H()trhTXOLWz~ zH!=|`xKW`M%-oTF)OfJuOtjJ8rgGfD_b5;v6`u^`iI@G<&a`qS7{5+H9CpL*o(jrR#k&k81e3Vofk-0UPc z6eEn^-s#!Mwb#+thkcrU9BHuw3@fc{9zFnZ!M1(7^4H2hu&!vUx*6WakFHPgF16e> zdKCil4GS??`77`LnDwCI{f2o(K52JeJQvWR?jELFy-({I%uZH<&w$kn1Zr&UlcNf> z)*<6O8j$^04aDco-@jnR*$Ua*c*%;j@!q+-sfUoEl|?$76RJQT2kr3hyeTbsz0p%S zmTt`vcTC*cd?ox9`M0vH2G@gFK@J5A`kQI0e&@=K#{h`)L}-DTXi(e2jrC7YDvRe7 z%>!MBK;=gEvsm`4bO=O*+(fN(HTuAz@s~B9v^YOA+Aa1q@IHh?Y|vEEP*O=#yU7g( ze)ahtlQbGAvX+~%9`)A<(2}s?sFhXoSOBhc}Mpcy@pLlWp zXw16NI2;*07$L^(=M1;TF{TR=lFN~fj*fzNmh+^+a#XqCK% z#Q+ABO_&(n>P-rW4Hr`EF;0zj$c7C^ZV|o0F@?98@yO-;_)x|gYx6s$1a@xW=rQj# zYuJEd6BHS9@5_8DsXSF4#Y1sj86>-zNrYXn9Q#w$-e>D@wUvPnXtIkZiMaI0OcSob z6$`*AWqw{sQYps(CzC-EvA`dpjd1pzfhgYQ4wc$%jR~B<>%J`NW}Q(#qd}K|)k>i>YUMjIp(@5n`khCo5j?BK)_1?*H2 zMqP2(U&$fxDT{X9>^$NrE$dG)pQwy^;j`-rL}AGkAm@jmSY6hIBKdjD-5jM~a;j~J zG6mt4^K)yRyaV9A;5(0GE9IXAlrQM(Kl3O4sv*5#ZcvpuP zggMJJw~|II$0|aj-j8*jEa~5uW<%MS`QaLmc3If&ze}7YbE>EsIxy!v9^aA4?cM=1 zr9ks}pg=S8HKXy2>}pheKFZA4yjDUJGgp!EKknfYq&GLlLn|F5x-#}3eNO~r zp1UZUiw`KR7|x3CrPG4)k5jo>ebLRG-B5(2=rZJwQxi z=d^PpT0O$?&hGVS7n8G^?iGP9CHym87R|w$Ny{PM45E5E`nCnWh!)=8LP&bWD`L$yw z4U`s}^|E5_!iBkusp2P>%rrt5wiEgK*JsPX{ANCN$`>uL3xfTD{QyyD)^AYp(>gl0 zdQp8TLJS{nX*|_7T6aUH@l~)2aM`Mg@XWuqjucmzm)5HKu!wWDGf;F52ngui@W_zj zW=-7`!y+OrpST#MT~>DpP7Zpt{FiPBGM6@gOH?z+?B1F3J6z}AHpqJ}w}aBs@|tSH zGg4Vv^wF(w`orzF*rxknSUsW{WFY^Dz{R`VLY9iMUOM(ZzA5FqH-<@NjYefNb=Pg6 zYTkE$j8T%HJcw?SSl5zXu=w+Wk6&xT$FCwyvm4+6dap!ajWa|L%?uWy=n0;IcL(ou zre+B8LOMQMYi48!J2OhzbfM>fTiCd-pelV9s(h)hTl6iqZU?!WKxbJ zV`82BpUu85<7jMuE}4c3(oVy&7Ffn=97oSWZxGwG6!AA1N+jP=!p@w-$$|ml@m&8& zYYB$m{La@ziZo!mtRd@uSneq%p;CL7PwLz_!7>km-GrbwNn@s)ZT34f0K+@O)_cjY zUR+L+T<#EP+YKBcg7QvoHen1+V+oU#4+V9|-d8yrmSH)uv z?F^i`bZ{Xcz_%J*a{9|*cMN> z=5NJ$(}~#S4qp%eJjC!SD*-^zhb?|uV)X+xU3p(K~Bh#$1qsZ?= zeXz>d5KKUqsaE6bn?8FDS`JO@h}jHp782>BF_R&_nva8my!Ng2WtZ!YA%K=1e3#GY zc@B@)YrjO0po3ci&Z3@p0myfE4k2{3ihkm-xUdy*#+=3B@-dDVM3X)}Ak6K%Z zw|NElBYu*UQH9s~u%Ie^zL5r{u`VK=PiC^oaFgX#Tq%g>Hb1vRRaTm=5yb(JUaM=E#XT`_J;W?!30%YWI>Bqjg7&`~7`I?|V;3af< z*|EMdc^OiCClK3@6NQ~r&u)2Ipq9F1qqg@~J5jd>OXcpyK#J0LFSVLLLZihczq#FB z?Y`qbxUi&@=fkQ$Yy=bCYu0EuW*@H6W+%8vVsSBwKVq$U{$ZBu%cp|jni0-)xh2B9 zYY9b{@To5&B6XH)Aa2h61g{B94Wy2Zls*%&m7-X?=UR_Ur(hV-K|CdPeYdXceDU{x zi$0zd@{ZM0f2)>x`dhEY+01RaQHB$D;4oShQnq-_<$lYt@?7ot)1kcgBS6@jdc3|5 zj96a)2>#2)$A{+~l^ox*N*$5Z|3H)OBs_1CBNa3Zn{Xx0Ew+CeyuLO)C1B#_b~Arx z?KFgpxBNPi1tYc@m|ACk5+~m0+8%>-PDJcmjT*uq8NE?C`g4euMCJQk+K+`i|LBFZ z46uoJas5$E#yhT;O4%d~5^p|Nv;snE$?mM|vKf;_O{(R^^JkpS;g6sBsgSjsfDu$f=27H5~WWTkB4X zxXw|SUSMiGxJNzQHh-#L2|r2o>){mWP6je3jv?))67EXjNrRhZ9-vNvf#%nwB$Cbf zhMzj7w2$k!qr4NuUEPDdU*yok_jk|8k&#AwIn0H0;G_aWLA4o3yMC9sL z!s|~$xi;pKp!f2zhx~RWOhZ~4BB`ey7iRSoIWs)m)-Dy&UUM-%${eEoaWMWi|L`A? z+v~e+DR$zY9MXxmL993#MD@z3ns%nj<~yovd*@gyDXHhG?~p1AZk(k8isI3B^V?Xw zWmn=0kDH_x?*Jl`U9i?Xn3mAOPPAQDgeow_+~4ze>NM>?f+J73RjYzD=<91|b*alT z>x4plJbt68fo~TgHwfc}24)v#Z5ulg>>0k6Hg>Wua-YPH;N2Z7$Q+BzdbjfwWIpkkMs-1o*`Cs)X4d&iO;5 zLG^@|j-KGrnqO9`soMWS9PcB>K2-+<1uK1jd>+VZF*|y>0F=9Cz3W5M~onGWVR1vf&)W&{S% za*H8Eymgwl24Z5>unyq4Tcv`!K$ZM&<~p+mPHX*;oBo|nm&{3Kjj+DsW`MqZ8xBzG zo%%%>1go4Ggx-qw=?tQ#o5RGeiQ@N-QiToU3wJYu#O<>r=zu!08V1Au@0+F>SrKnp z=WZLh*zCJTH&8%cx4GZpS?iw-#9a5`|F~{#eawwaM@yF=cblpJ`SscUOl!d~2*!n= z&i0q>{?A3l$i6$IyE*K?7ITo9J_Osgbh;Gi0FmK8nkP?Ik6?R$wP@-d{==pm;F24f zto(0yJeno=kb7c?Q31-X7z4DE4jil#NGB!v`XX5e)>5utS3>753F!#-e@OGeI%Hzg zBhK~-vo-`U@a89_6ZF?Y2_D5BGTdx5V1G^XdFO+DI(yFFc45I(L)-d&xN5q7zw>-S zGE4@xeM8TAc;U5Wl#b}`CtN<2XxpW0fM`Tfll_!L{g>?O=OG*Bk8!3ux_eI?3h(^A zXP+jvqiIz`gRjOjD%m-Jx*SlyOnL`J;+UH=qkTA(AyqTe=2WM(Vxud9RJql@&JOYa z`l2b&(80?6!A9W^wU%rZfFfV&Iz(Cl(kf^=3s2dj_;xM~RRK)&|;uM7us!FBgy<>$_ zNa*BRfjgb={vOg`W=6U3{Q7of&Xr>gq6v&*$T7D_^)LPZV-xjI(2(!fqq)8v zf9R&>u0CTzeiw^QHJ0jI8OOFp1$`1umw)}Y3;?q`2EW$01%`^QxHb$q`SU*2{*`s_ zYMTjQ>58JDqE5uoV)tr#x)1)3KgV;2D2?}Fy5XTaZql2QU=A>Ua4dtB51 zz0DN(A6@bPcp+Z=?IUMQAJKy=dFcP`I;hIu-WCS(W)8<7wRKpui=k(3w;Uwn46^EVIPVf#lW|KECJQ*kw}rY-!tJe)^Y9u;pV|D`0xl$7YG z1CPgT?Wq1+Ibbwe6Tcr{dG5iR_pguGC}TcC3B<VUczZ#Ml zzdHloW?27;UGwuVA#X!5U|C{a_u7}IzduJHJW$*$*PPQwNrHTGP3DRB7 z1JLM?S`s!6h_fEfR)0>>8IF4aq}FJj;7-6BzvQIiwP@A{dljmo4B==t6$%@TS76Ur zL(OB>r~$ONA3;9EGF|D?g+3~&Y{a=POl(h!QBD385_dTUT&gI5`K-zx!3Y`72w14Xf z1Obo7I_<^P+HAfYE6{E2h3vtf?p(}H$D^?IN30W--~!O40Gkg)n^W7Eg?Bk}$%v%wgS?wv2_X)wEM zO6{XcjH+Jq+5!doA`q&r0<7};x1~x23eNx=eHD{ZvElXVgGV$v<`O?q&Ibuq;SyU# z<_i3s2c0aM&%l8+1CbIj{0eByy~=*1OP}~tL^DakDde(bp1yZpYHl*E3gK>+-bfWXxQ z!<#n+f3(!$w}&3%Y1`K@EMQ=ZK0rL~sA2g7jIJl7QhUz@bt|@~D{{|)cKq^;MLEU; z9E)=rzOb(MQjvH80lN?8sE3D~Q%m9U1jlNVk~M(r`0_W?s9$FCnV3mNYV%li1GI9V z3hs69v555N*_{|+zXoARGa!9m1S!c~lX{m;_3U$@P6()Sp`}NMh@Sw{+oSjX(Y#qG zEvm3F0Oj0up&utC!x@T)D=dJ+zz&Am9i|23s~7P`%qUD{Fn4_<{SHtulmooF8-QtB zNWqeVQ)`)ZVn1B#Ia00CAO&BEqE?{TLSVAO>Q3t;sym=ih zcZT6#$eye{v&YZlB7ma?KuBk^qVdbsj3lWCdsHcLDy=q*+!+~pYe<~OnZ%i-&{=Va z)1jNo!FpKSW@L7`*?GifgdoIPiNf3vO34Qb7`j&ti%B;)x{a!z4jGQ>juKDkel6K5 zt{4&b9%=OaF>M*-T{9w4qTpZKNg^rc^=%FGMMb~jchEGi^_>R-;$JhCu?e}p?8QVL zeFN#W6IRsGjBT9XU2>fqITSO~`keuD4A_vCRVk3^?kISdHzIXwrPsAT2Ql>zZ!E%{5vf7bQJC~N@sY9iF>~8@xHzOgRpWfHHj*=5Z zFe4^o@|VUPVR>|9c>oeWX72kn?B(5lK%v~!ms5Sp$GQYGN^hBwg`apDzhH}=F6dg= z$vq6!+XR}Vy{%HGs5uDSI>SE2cmb#%M9*M)?yB+ex0L2PuS3b__*?+)J@A)DML4H= zx1R0Sbe&^N-8Ee(eCHMNBS?QSRtQkQ9;t@z$u>0+NYj51_67@DUf$GfwFX;)m-8)T)@fukD%(O z5JH~se1R|Sp&E;P&elFk4qX7y*h2H+$Tl0YmSrwyECn+zJP&t(isW?b{UbD#tg!L- z2q5&ZqoG~5#dyeJ#oKhR2Ev|0Jv0;xBOQa$TG?o*;Yh&o*4pml%JX(Ayn|o{%}Q7Z z&Fr-%px(k8P5oP;Lp4wr zb+;mdt=yu;2`|}fkAvE6V8mzS6gpjR6c0Knz4Wv(cJ$oFi;>t0jEGGwMJpZ7wsMG> z?XQ^F$&{xS<~Wp5&qJtV(1V55Q3X1R=#AAawR@=g85_b=;7yQJO?Qi}JNdok1!u<5 zK{8J$e#amcbuK{BkpXVNh5fS^Gf&nBlhqVoqp0Bj!e{;<1c0H^j&r+msy->-Z0e>m z9nub>8ppsTg&A7{PEUs0Wfy_jX@~z+YOUA9ORVlQq%LEW@J;$5fT4-h(!r zVnYV?leuo=1}|9}CZ&%l^Pz^CS&;PE5eri=A;~s--rn;V6!O@&XW`Eyg23KH)&hK; z|LZP$N;HlrnhAg^mw8AE7f#qH$>4u_H%LK1&(2lBEVuEJki_YBBkm9`Gs&*m&R6Aq z%w)UW_LH8D@DEQIEY;mfFg2>tIuIPaf7iCNiQ`i9tjtG4DT6KB6oT~OI)&dkAp016uzP%UIYGS@)# z6j6NQayD@|L2b{mNIqyx8vnZ6xkQ#s`R(~2HiWCOluVcmDLzOqJ)459o&r_Jy$Q3rGg+6u!;EGcmVx+uznv)d* ztLY9aGG0>89m82W?m3REf4n>Q*|NMnh~e@}2+2BW0b0wW47+Cj_>)qr>n8=jB#68( zv%eG*8H!j`AT2fN<=;m(Kr1DkNrVNG<0y#S%%jek(Qa zFvQR&3^>~T2+_TPASl=Hki`~nJI4QUPj%+E$JzDI6kYidPO`|AzbR0pSLd}bVa-Be$T-fS7ZcBZv7I-tJ(d@m z8m<%x{iQ|9(H~!_vSK{xw#Ev}qd-H+nWP_R*~80MA4-YVG!}hM!3kB_7)pMW#b5)W zO67=^8ddE4^1|0L4Buy1F|_><+tW5UH8eE^wM1nw60Mgu_wXp&fYl$CS3e~8)DR+s zi)~L1ce?`|NG{L3A_6_UGwWdUbVEewWr#eD@WZ4AAwm^xnm z`j$@-O`J2z3{!oaC>ow}iBPd;5z_QZC3{^EXnyA`rFOe-S zv;pIfP&A8QD|( z9W%hk^dL$1QF3^R9rCb#C6I(@2{nTdDTaq~-WV*kRaI&nR*GUl{@VR2*_C29tayCg zIFH07MC*gKDe7@#+q|k5vrHiAIsKHai>=Y9XL`sdp~x#hD=)IJ$ElhFXB}yFg##qi zMbGDrjUu|9*&BIZ`R2;+E^eVMC2U2%g}1g>t6S2)w3zT7?4-<4Gb0Q5kgr2ota$e2 z-c-6H-zx{q2DIVaWMQ>beS<_w<2yhnAA#9}5)D;)2FmwZ5cLyt-BPsvcGl>OMpMJ- z_?~h77RTLts#pO~<_)P3xWC<_1Fo0U{p4gt9esyc1bjB35G|^A*Pgv|Rg8()Jha)< zfj4m^LGldO6=71Q5s|pGD6)Q1<9Ujba8qmX~#&U zbl4?y<%TwgXe2~G7}6dHBSj2!KDmwPBJF;Rk zQ5rllp~;S<>>CGz0v`;>KgVZU)Rc-JY!cV|y;cC=0O9 z(IIT(KVOE@gz5H(``!sm}6$W#;(yAj;4!sMnkjYP-Bq@0ws!QZJJ2@2r)8zO=hI3 z%NQG8KELA21y(sdLTmYA#cKv+{)VkgY)I9I(9K6tch)VkZ{imY^35o`rYJq)hoZXV zA7aB+3YZlL6td%G<`lxS@@#L*4>9XNkwra;tv&u45J<2HVr)+l?Ljd^{JF!JXAYaF z**Rgxi_eHuma|A#@eUh;q7KGE4?%08k6z@|WjUkG;=U2sGb3rn^YFs@DBc#vLVJeP zl>-e?D0%v>>zmNrFjNNdCmS#scl5-De!m~K$ABgvgG)U}K4Mm4ecbiE;kHJWSURMA z%yTP@L^{Lj;CpRRXgqV+UB$vgLz86~Hu4oV4qXmJ|M}gCKqbXOWyL#mUxYv(C9EYt z!kp3Z1gbcOLf2s-J68H}zlr;y_>V&61yj!C5hxh#5R-y9*^LENyZ9eCky`OqdAAg% zO;k}H)k+Mi^{??GDaRS#C=fM=*TMsgM6D(i;adHgX)Ue{~u&56reZ<^dk!HP$4@2eor>=}nLGa6rPQum0`Isf_vqJHrIABE?7{f1c~UX(|jWhv{`uL zY>FipFEpsUscwwTTxgLPTuv&?I|VQ!7u@7lQ07`5JKeijF(;M$9Wsz7n^4Zl&`FpJ zY8oUhmf^6ffkUto-`z6m=*4-cWYHODL>N+ZkC9=vBo6yA0F9ttc&a*ZN= z$B$#GB4JdqQkpJwXp$GTW5l{ti40l(+PBD<=`G~7#wu)5b%(%?7`+__Wf+L~X0>yF zfsSnVivw-0*F@}Z9_p}Pp zTG;VNXsDALjv^|<_d*G!h@yM;I~uIu(2`K(t1@ttI?8tXAWQJ=JG~R4#uG}Y#IJAO zq2$O}DvNQqnim(I3{7;=2)Ryk<9wzTIeAL-955?7^uT&{CVo+-tY4I2!orNubMDg5 zh4wLEM`!3RL=1ZcZ7kH85xWUui=155Lr5APQT_Qh7r@z6{>sZ|dR=FNQ%>=YG*@Ol zSc2X%_#DDIh|8HX6Kf7J+n^#7S@nz405+4(w<)45*Lw7g`% zg29Jz!1;lUx$@l^pX4qO734^_*Z9AYhw@$dS!VwHz)~t{=uoGIKpHco)7Pmf-cboH zcuNp0fv_U62bbLaoWi z3O^3|exIjTC)3;80qml^J@ku^a$w?;LhKa?`;!a`n*L#rV{rN=5)ILJe5`~j4lTJy zi48vTjX2o6tex7pNA3c95O2NgdhC(~EN?5O@;@%p4BzvP7DD@6J@mUVD7#Tc9=q`O zGv)vB87X+>2jLT`LBV<<|JRpNg9izITZ;J&`ig}TEL;dZ1~dI)C=?sXtO*Hpj@@y?e{Js=QA%9wgA1B-*`CQA2KZCQk3+_< zYw%_q&AFJ8ROG5B9WaBY$JSuSnOT^u5xSUYJB2Q!t@(6&Z8ICaL|Q^y}d{I6tKDF*3d~jS;e0wOWg-} zDfx;{?&mj;Z{C>IH2Rad#>7Sb{rJ(~pmDgJb*;3}hSA%lKv>>m=Eb?FrV#=16Xiim zlbqRukrd6k=Ik}c@uGVLe{b!+(Gt!K7-e}$%}0R27@8iK{!}*(+AlpK@Wo)GcN;& z4;Hx3VOPqDiq~e&GrVY`PE8c=w9G#LhPQ7oIcUqR@C6EDiD=S*@2$UYw3%cpAfKvP|lX8z+5@-F%J+WcZkqphs}*L z&vzW$NSQZPE(ptT;T)6~_E8}G`juAC(y>lze)O3QbFBFoCAYnqyDa}J(Yp-d9Y14e_(S;EXtFu~_U1thra3C^ z0x%PwS$k3dDLLf_rIk~%uIzo=G727mkW#Rzb6H)h06VN$IU&!1*7sN!A_TxiNLofi zO_Vy>V@&gc`e+@q`w;PLo4>Jpp4per!Is$_P0Axs{t!}537u3?sM83*C>8;VX# z82Q>SaHJNr9e${<1nL!GQ-cUb1t?*-KrA8~Isf+W*y&^Wd!M=@2Y|{I#3QDAtabJ0 z(mRx^^ZMtZ`=Ai%Z0i*$W;5T<$NVhw@6%*<2M@*Gx9jcJT;28|5Kw#{I1%g|)|<$n z4Q>J9@F9>p3-A5$A(IyG*c?2m1rVQ3`kI&d5Ln(bt)`RTP489`#p%2h-39Q9G!IPX z#-8tsgvH;77ccs^<82B%pVcINy;b~R_(dE3?W`{#-=b>O9z6Ua>^CnMpFA)S{MxIG z1nuyctX&5G8dt}xOdEfjc1;O9JF$lu==gQa%S;@Mc>odGig!9g^WR279*}@JWDNTE zqcs2DKH5DL+ycaf^}QbfijNJm^Uq$tdj?Sldx)13PkvlX0hj3GqNnH82WoxYqA8VP zi7IvO%g?%t-ex@90?Zfhex;Jns&Fk_9RHJ@v#KV7-}WG(G#UgP?V+Vn4GO{tr2aKC zrMJ<~%SSbPydJX1DPXE+F`By8>EoR*_QM|9d$|HQ>4<9l2Y}}3UGnH8?o^4PscKH1 z1XuwoGmrm8+uz*j%sE=QqCB`tQ2ku0IR!@p`}J^Lc+h9&f_@hh+N7fYFxAGazN~>2hZF z+la9Sye0+8K}PJc&X{jBHPgvhry@h8!UAVA2n%UO&y-$;!w*7Tz5vso2Y@VcVN?Am zzi#%Szk#4oqaStief1XL4=wnk=}X>j2+042u1_V& zm)koH2s{ee0>6_fmE36=3v+jYu!3B!6zDmR?@SxvH)8yO8q;$*S1Y(Z!5iqYI4ga7 zQPUfC3bK>8NVcb+9OKRzOjdztjxX{6q_@deQlRrug-3UYelM|3?_yPpD7D>4a#Tj4ihShAZW>A(HlCb%6 zpX7-If<-ljD`TdWYQP~tC_D_jf$GH)<%3!P4hs6121-xA+-fHU39{B^ok_rJ##Prv zHurg;ZKTQ005XV&O+RLzsbwZYoAN;Na4ik|-4C@JRCbiz=*oU{V$umnC|TE0>#nj0 z+L^wpJJX}O?L(Te%{U`LD}Ou&5|HiZ*|2Nr7ft*?HoQjlB#?e{nHlR2G@9;`e8hz? zQf+&Ma@&vQ9Y7uR=D@XL@qR>;jV!#WE7oB#hV7+0PX%boADPbg{Xi_<lZ|5c|IhCQbx1iXWPOqc`;jXjOxmJPYhvlH5CA&{PdV?X_+o zIV9OKvqjkpEew9A@%k1gMab`4FwAk1*b<}G~RU&lJelY^NwUYhc7gZ4mZyk*N=i&*iFS}O3Ex4Q^CTE&%c!=cDOI+pq8MOupezK7!1Qnz^lKS;>sYv&X#-_gae(sNN!A(%8nW`u$#^BVCCU(+eZ~kC)Bsq8f@Y zUEjy9*&b>lB9kv8L_*Jlkg&SUERY&`{VVYoNb3fY19jWFwL1Mh`B!4sWMl3HE zeYk#(PjlI(DM;cXINUv4`t4gCCywFaTAd)YjxgL$`oL=Ez4(by zg=PiJI^TW(z3*L5Jzxl@i8rXD3pv?&)UGTi{Zko3+-&;7b8WTck^Q<^56Rq~v20rO z`HLm}ZSYa9{5l;H8IN1wMDRo7XMs+Z82VQ`%Nyk{+k#WvHs2Hq%htVMoi_$uyRL+J zmG3`$H%U!~7Y0d=eo8#L)P*Rl2F&bz0O$QH=i#jG7JikKmm;G#8Q3ko&))hFL)g6%`F# zj;aOC33XOBkXKWKJ2}T%zV9Om4Fc#OMD_qzKxEg#MPZ?-^X~(DrN7|fEAY<{ZiWUpC6B@@7Sz4yQ2^f|ZAlYHXKzJ)yRu7X+Nrg))#JX41 zP3|m1%3iNz*r~nIVFA%xJo5l!8GsFVn0i|*TilsFwfiNOQ`AR*qAdw+czu-_NMzBZ z;<4q|+QW2CP1}jIvYQwuAFVZHAWEU1Y9gcI3bs^YP2k8UdPojlfM2fY!=Hg3MM6<< z2RDeHJ$$Q3RjF)#t#qM_95&jRAEAAiKsb1dmod>5A&rgHYB z0qq*aNgsvz^q^W(9>t4uLK1KV0H{!%4=vU#F8NozHq zHTFAo^X5>pe1g)#JlLb`>^(ibFjU}{d{%YjKRD0(aYP59 zh)V9m;>R@2ugf!#ha)kk2Orv7ll$nTTBU>1qR;r*B_^|p(5~})TUPQW7~rQGk#g*- zXb!ZN{M4Fx7D>&>zFOPqpYB*;13XXQ0@+Qz=ykey$RCBHS43!)U(p=xT@mkY7@M~N z$N}l-F{AMi!p>K^>jmpHG-y3L8FEGh3dfNnHztk1lIQSUkcxfCaizHwEBxbd_5DBt zAA5xM-Ge{hRkNVxY~jwTKfw)ytws;Nz1sX%atdoEx=Yn#VX2zshwHAuXFr-)!?EvE0z+0sDpRrEp1R-?uKO zL(O^WmAvt_6lD+uT=63GZ12QW3R0#}-8*k4FKXyT{j}#?+cR!79uFyd2k3+E@f@kJ zmaOG?_%Ra}+T}SNjZ%P|;YP9n0L*3<#IEw7S_Gt|-#pW23ahj0a?^}i-A_gN`_Jf( zPBEJYnC+ufIwhfBSpvT|F5l0~Eu5soLJzq&3X#gFf?H8Yt=uKTd*Dj>wf*9YtL)F^ z!iYV@Ql@yO?JE}uDEa3^H{w{jHoi1P?CZ>=>^v%O z+>EhadDPCC^-*^kW3g;0rOeBxrzMpKeHtf=C7eK@JLeK}PiVedWq#CxW@lxK)@v3- zLnRSAsz=|bUHE!I|InNc;{${)IGtZee~z`(Qp8}s$Kq)fxDZdB5U65Zzwek5Dn;Pm zI(k+L7Ak*@er}CBhreGmEph$<6;P@xTRRnjSaJDFmY&bjm?|zfp%W=#5FL>M$sz__ zsgfXTVR#f&E6Svj9%Vav3j{hwF0@R^hAFkxgydiMLFZcO?&{#*o-s_JjV#3CDjP)z z#H~_E@+oS^7D!O^ZOj3Yn`(lq?pdvtRRiCI#8qr*^WMSO#ca18!uw_Gquh+}x>j2n zH2$=3SK>4*`i=Z#22+(0cWtpgR#?OWWKBr1EuE)i4Z}nyhfTbwNm(;ALg_R09nO

v+5!)p&VnwxK}r zo2m2%jkOW9oH@1b7!2X;!<^DOBQTNs&R@$g&Lv6ahh(_hP@+pcBdw?9e^K9n zQ=l-ndX(PLG%<*dlVP&-7FwSGWzpga78Dfoe7!JKnX5Hgv%(j#s3fWx2COlw!-bJ0 z4CP0$*S~O;!3x~+f_kO?OnuT)Gk04uA!i93>qbY@(e=_iVsb6pi|N9YE zRkG}EbC-sM3u%@*POLW;$UVBoi*1(bmH43>qWbzpSbVizBKaGChquOeef*t;==Qt1 z(H;o6K|*@ob1`y}8)kRDYjcU2K7_{9`=&8z-!ZWe=b3Tn79`@w<8+>H)eh*s`3etr zoWjSvS1?Ea0?6e-n&dmR2iQfi#D4@E&TTXG6uzr4-uT3B$LfESgo?lJzaaNk2W|P5 z;yj(~GfzcH)?i5rhuUlF_$!{=h#@)l?o)~s$55R%cV|K$f=o5#PyltBzq9IgE5fXe# zULq|-=%`O_w^NG&7s{jOZPGjA4FME8k&~NAn{ki#I8j$S!rSS?+ZuCyO2wS1Tes|T z5;dkmEi}UY?J_qV;_Q;3qxQYT^C-EVLWZq8%D6h1p5zW5FloMxiQk13pSQk($xnBw z;&QV1UNFTV3L1q$Q%P>k3QJB+_g1Kk3d3;3c+H4mu}wv46>g5Gjs5qcP9)b9h<93 zoa#sn`hLx$)g_aR)nF( zOuvL;TvooL59S^+Wba;dlHWk|pknD(VJeei_=PVRBgZAV;#$}R0^Mh(sEFGMc3rJS zF#zmf4qbLtXz(M6TTZ!CaNouR7u{jw!@#sEom%&E10Kpm`yxY^$XQZro^U26?sQD` z=v*Z%S$Gb|>qai18Td1PL;8A&cf-Eu%BJ36yk)K=lWFbSzZ@Ho3J5BQfcnJ%5H3?z zu9N7dqBAs0jv>1q?F83R?{JMa6;WhFD4oLOw37-&zyf%_pXphcTEAXAEN|uG0_KXU zPeJtq#}DQ>{GMbECrufdP=LvnIofiF;=GVsu@+GfG4H%>oCT#M$G5SLMcqu)m^h9R zo{gv`!0L(K_qwUEzpcb!cevrAigz8IX~Q~*lZ!l%9NuD?QYRU8WKYnno<+ASlh#wl z{xf6RIF|0nWHAH$(kj==ax9;++jXCXRLXW=7$-pw>M-m!Bv+g^HQe(s-UW0TcfR%W zi20a3K7n|jJ)HQS$@oKkc1-aV+Gvf+%CM#trAXqqo8d8r28%2qOKL(JY86mNNn}v|tVc67HgO>_T@CIn>XVFh%{s z@TFfV(N>DeNw(%>mBi}!N(U-cy4!n!d~VTzj}zaU${|M0>Z9PIt7PZ=)VWNNp6t=p zWzVp9pPJR&n<_A5cAU(>yu`IjyKIHGDc+(nrP@TOOl+w_cSC*9X5$Ir&cjV$rgP@PY- z`UzspJLd#2t-Nn~sUJzgeqzuNM@^j=)d!v3hjCaai@;CrPs)h6^aYcrnE(tUe5SY+ z6`bAZP66vL#zKE9l)ED=wD?s^H{DgeDDhI@(-o>|S}qkzfR&h`uqT!6G9r~J-#$*3kU))7}!<=dUNW%cX$E83` zr`C`}Jn+Tnqz^~ELmMsOdkcHYUZz*w1}(6} zXb2<4O-5C7^jWqQGOp*1rF5iO_uqc!&;=zU*IQ-nPU;@UtlC?CCwzvXxt1Q(|LIJC z*2NMpj6lGq>nj4afvJ>;z%A5>D4SgWM|1N&G@IG8agOUTBnC?uvB8VP#W170mj+hf zQoV_~Z*$Icr4+rVk;8?_s|oBcxGgyOWlHZ6e>m{=9)TY0XTNJc>Ts<)Wbx2DqL!J9+xs6V z?A-4;UZr{Isq6mFB&PmBq9TU)B<%m21^A_nBf9qJ?KO zND#Qu^)mT%If5;xx7Pi z!-35PQT~bTf@O;O8T)yaua~kDhU6@r+4ZS0%th z`OmA&s@s-mh))t~QwpD0g&Cs`0&#%>=PT)PjZhZzE0tnNcK!)))FjV3V`SG?CNHK_ zy1TYVOjbOPq=fnO!B#6OHLpw+^sXC1m^-}P>0B_A)v21weZ(gi%~_#dgNyM&tWfy7 zi>i-7N20OIj)jxrc&V~hxbfMyIUgiMlBi^>eQ6ZTVU|q^jk0*BY{hR zmMD~*Tw?t2t?D1GPU}JZdEPq$y+2~=HLh&xt;BwZiOTS&=yS)!{z-&R+~T*o)I-{U zh)SvoUGx6=dq4MA&C6kLVvrzuTsCnEX+C1LPTBM_O(y!Gvt5sb#Q5c@D-*Jdb_sR` zQ(`O^gHQsUf)YpK&u*YGD^E(?zQt-rdz;;OWBUIP6e2)9cs`RyQhj_f9aTp#vwLs2 zH%pb}hQ`qJ*`?4#4uHtydbljzKF1cij2}`>h-j+HcTlJP(>hHpa2~`K!av5zP)@MM_kGh*M1{`=6R7J>!-8&^Rp*AR#Jc&@yLStWXfy zSj|d!_NNz>dfE40T5kzjiUVk*hSV~j)A(+M{44? zw(cbbomHRtG0)cfVZbJBBG(mj#`Luub;dE2YPmpmgkIkA&S@R zg=HGy-9IFVy$mE$_HqRR+pBv%HVtiUxUmOmXBk1^~z#RiXK?oJ{ zIW3AP0|DvOT8054WrAw2^(=>PCbrnVa7&aX(iW-d@)fu%G=pgHt=1;}@IkcIY0vs& zv&3dO`@WOAnksBcI|dWlXHsfox3#RhR3@I6Gz;u*eDp8Y;r_Dq1Y|Nb$wBkX_Vv&g zt8(nC3`JE)oB}D;mukT2?jxhXnTsj43}h{J%AEu=y~K#)=8w;>x|Gb0)+4yqKZQ#4 zzEc6IuZ-IIgf36>nm*gTh!g9cI;$5?%XRF0#{!01eiU|JyNCe1o;*3^m%@#ymS&NR z6Qj%T5?aT1cD}MzAac$|@&I>_d(-HvBeTWFuk;%vMEBWPdxBY>CjldOBM{_oCV7L* zSAh^_lXp9(1jIAG!&qtd^TF<>1{NzEI#O~0Sc{BmVC0Z>$pHcF;;&VuRA)%V zW1m3e--lHFvJE^ub(HS!pjL}2btwq?I*zc zq-%KJV;6)%ECY)P9Uw>aHOYbT6lh8ZKeh3mO_2RPWx`r=*a_mDdQ^FLxG1f1??4o1 zZ~wFTeRlp+)XzDPxIJ-?hnA$2862G>Q+vZS3wYgNQYqiLp}Gi3IZI_ZAPn#&mVrxG z{##YU%&oynkPj{`u>3d+QlX!~7uBMmqR;gDUiaZHh>Bi{!F~0@Jn@5d2(Ez`)*Vp6 z#wiC15w$lk@9u;--pG}7eJX^;WN{?K-su0K8};V|pkNs!8-ZU8p9V$mddG6OX1XKl zm2RL~yUUxZ6Raj`)_OKpH{o~puUmO_%j+IBkJreQgERy)S&R98)x>Gyxu`r2^?Sd* z{y97>P$xA{(!b5~7jwviuel}niEI$n0t(GPNrJcS2Xhj5+rN;(XO75xTTZC}c@AzJ z0E;8(HUH>@QALh6uuiEs6zv0S&@WW%|VEg5^S=qLv zy{lzV()P?KF}fo2s-57R`(aSxN{>XoXAtk;bK5Yf$K{p@{{#8R6JY$%lyO)gi$ov1 z;P*yNqQq|f(c_gv@pIm`!>!4l~4^Sb)^jqiA7-pFQR z2vJ|&-}t^8m&#iBh&-;JY9%ay!vLPb>Gz&;!O#gOjfC`}BTRVHy(tfbBM`Q3*pEhCW zv6mU~ZdCB*k2|k3P$tDH;v+ZqA5(QJJd^|-fqeNhMzV7LPyJ9`-*!eoO^8>s6*%Pl zeY1WJa{X5$aXu_^831I5!nLl_%$@Ju>B?w&NCjVa-WML^vOO7)?S>u}GW*9~9?k|` zR&pGM+=%LUIPg(qcF8LHzgij=SsM=v9zqUIoep`b5cvtPd@cN+>Y-#;`jXu`HJP}^ ziQ)n9)w+@*Ib%HzFSn^3Fa0}^|FT%O;?3SQKiVXH3yrYvFZvC|i(VZI{O7NbdMcAm z1%b$|ay<}HJYEYp(Ddx*PJbI$K^rV_u4a#}nO7*jniqdKe?F9t4QizDFkiPW+pwtv zoBVe=!GbyB?bhwmiB$o>!|1=C1Sm=!i&p40z{pVPk%kC`IQYSv0mFZ=_#Igb&u8H6 z?qI;RO*(|itp5$c0BIIXHu7)RP5le7M3Gn=-<>gectLAY`m_jG2_J(Sl{0VYmxG}T zc6<-8IDgR90VbdV{`jHurQbIJfq8DJ_mw81pqJPAw;6Z2$HD7zl1t(Q29s(m| z?i}HFte^g?U@@SFICozDVYLn(@usmGREP$r5C3FgcvTk1z%?l_+VIP47EZEs>8sa0mIW%= zUx0>}82QzB(;UqgL$)LyU-{3-1|Np9d{;^LP}=}>@J2ibde zVkl*r01Y$K|A2261i6>;>xTP|0ggcu8Mlv;2gSny0Ao5Fu?PNQZc^C*j~SWyk{|v9 zkQz+8pkTDIB*XUYV?g2f#IRTkpU*$tJUtnC3~Ge(Tu9nfKLBNudo%;!la2f8e{7Th z89^%DCzbN|0jH67uK|?j^Xm1Voe_+tWc$&rILoBw#0f3|Oobzv-wepFhn^$tO?bC5 z!C!=4+mQbTP#w9H6@b8e7r?;YlW+p5orUwh3!1wP?Z?BrZlDPAmfpEL>8b!EnxU5) zTIgE_5ZocJG#s9A?T-=d_=ok zrg!zfE!f5gmgBS+UhmHN1LkKAnl^Q3L=~BZ!Vn*k2=(88h>WC^7A>~l#MS444(m48d8y$@YM!+T??+c|#V3MbgAJ^JqTK*(}Ux-*t z!z{R$95!Kf={Nr(7*qbRbC!CguM^7V%^C`Nwbf%eHy`Nn_zjBJB;~WGpMpZmMnGWA zK576aKZhrzvctAKQc3KG$n=DJOY1Q&C?{;ZY)D2mKR_L}?p7zmVVhatLHJ0JqKh50FTy?+9aBW|BOd(ri}AZ z?^ST-=Yu#lgT|Zz-AwIrl#3^wsS6U9u5SxUAFu*#7SP%CJ)oW$la(v21V_ZZA{Rc=;NrCESgo7gJy*e_K}8;F)A&Y6Y@O=_br8f9`=9`CPdWj!yKYK!#1{^T9$ISs(%spnNgK zX#3RSHyTxBREz@y=`N9V1HZH-3|J9o7^>|9##OCA&iok(mJ7`S9AHLY2L2bFNEX4Y zx?#M3B^Y3TtLSPPgV;-Xc}pGF*H?Fqs#|RGrXO$D|M_3+E2-h)a3a!otsw4xT~~Pc z;fJ~)Np-9}+fp`TnF-5_owjhATJ($XU@N28x z0#N`alQ~0mq#SSod#nlu-s?qaypZQNXT>uwfx4DGEsL?8cU6p#8LkvJV^mZD;I~&` zE<02!t7Q8a9t(kDfD63dypne+Zc6Uzoe3-Z>9dzMf%t`>A>Ou&yhZ51w0(JtkOm#q zIMA36Y4^HmwyYIs)~AI>ULYF63wEygrCqpRt1?k?baS06NV8)y4t|&T_H`)My0Tt- zGqOJHu}3|j=VpjYNr7kIS!ibRkCCU_%Ht!tRKiCpj9|pg=8>UV+0p8Bx+5U&Il=C!tQcCXhjTajusJ|aH8w@* zxT_sR@(ELNS#2UBO^67B9+EL6_B;GDz4H$eAEgcmu)HJWnfXQ;lfWVMHjf+g&3idWew_t0dVKZ6^i#VZ zQkJzGcwGri(ZzAS$shULH(41eE=t)@S~HOuVSw^$CFdE^gyaIrtq}NQ<^Y9BaNv2OnP(|524X~ z>s(H6daJRnXJXHNNq0Ji&3+9G!xE7brUFbVxnE~LhX`{+FH(mc#W&Cyz=Wq7VEu!` z;WupSgm`<_ljk_Qew3aCucbAq%g5Z-H`%)bRR(*-1T)N& z>R*`zvz^iRu|)3YGwNjwT3F$LG{qPyueoPumVjTue_V)QcI(Bh-C{)uykN$7`Yh** zpnP%y8dDZ+^Nk$TYVm;s=>Pp1g#@#8So;O+Qu%RS3WXE?7rglWz_;+vhdzt1^eQQR=&>ycO!g8gW8;uo%Y8n-Kud=_1+)idO9_J8P9UT!Bz%&*$0*}KG^G5%U3Ccv7 z3$JnbNR&O&rOYPb{Lza^wPZ22@M}cg5d0!@l0q*=y>^;@_|O_9x*KU74||FAJ(DO# zY$WAy+cBAZ2&_AB#@&8Xw9kuA7(M~u{FbCyYI=V0#SPOK8IGd)L{eM8P)E}eV5bu{ zvK)#Lju>Q*O6n__oKtGMwD)c?fGGre&*aH1-_B6u8C&=|E8IYqFDzW}4jNmaOoioy z_{S{zA6(~ii0sT~tUlQskNWA588!t0<~>EnC-dI3>myTEG;r6K*FAGVNKjQiut^I&Cz%!u~h~H z{VM$z+^hEx z8_GT}Wj714gl3f<3nd}%gGg%skf5s3h3>Rd=1g|_%o?I1|Fc$qe6iM;q1|@pyQmZ< zDU;0-X+khBY0sO&WWn3d=yw{(hJ!G#h8Bj5k+hHmZi6N^eEtf&tS{DRqrI zC>n0bAU%}okOc1RCfWQOjjN9&ueM@qr&{^4HEWGYV#XWx2mwsNYYXni}rK=b2sW$L zihf6Tv@pyynv5@uZON?FsHU`f&5E;v2cbn^5`;-1HrPcNr3}G0_ZEEqqB`N)XLIIC zcDco=h}2q+JLJq6&D)q^I%R`4RQ?UQIZ3z%Amj^fd>sYo5mfww z0R4L6=Ps3%G~-s((FbDYn;n^q@RVBB>jp;n%xlUFv%rm6O+_GM0_eM)Qlq;ESkR0r z4x?X+p`#>@SCo+k=dm}C8$tZ}lB6s`+G(naUf+(jlmPV1+(#h@QGpl{CYo;};x^h6aU!2#}W8n}d{^YjZ1rfInbDptz3_Mwt}U z@xl;T8>kks#Fmb6TzeNwEN0A9k3PF`4#q624@<+`cK9Xk?!Cj$s&0~#yG0H!=eJd7 zreig>p*Pv^MnmF^IV&U!|3w67=) zm+1O}&f;}ReoX6`+Gw^67|+q;&!0a{@5yh+Rz7$1&%6FhJV)bKoIlhr;-aH zS-BW691wO9DjKHsAqJe`xGrHtxemdcqLamN4sgPh7FteounV!2U|IgHT^X2fbA^J8 z>DjP_zruZ}mQlvFu%OLZb@3sb9ib_%+pQpmHG5`67>?OV2&GOnVpPLbB4b*2e|(p8L}?#f0fA(phL~MuS?GZH!|cGhhI;<=gOH@qeh9DE z{`Em~j3q1F$^LAP;R*u9IT(p>(x$}(I1`YWVSWT6 znf`AwAEk*n?P=oOHO-Q@!!++Bv7p!;mdZh2sz1bQ(h8$rcedBAL}G{@{evJ;^5fJs zO<3X5G6AMYMfeB?^eQrrcKil=E#j0>-{-dZ>f=?8IWPW9@%KZYH1P?J9Y22+ZH1l* zXEY@iI3NvAzXEeg<2Z#V3KLwZq&xFwVA=TRpKW8;oi81tH+2cF=b-S(x1qL)3anPi zGLt>47EM@T6ZF|j7c2}`rKo4zm(-DJXI);`1+fueoJkhJ`Z5zXrOd`;UeLocG#-+F zB3gOP(cNzz?`C3g&tS142k%fc+7moOnwWFk)uWt{RBP||U<=hwTgHqk*S${35w%ii z;Xvj*D)7eD@#BoRmtpNaRv%VpR!1BSm#)g_x(8i%yiRtScro+=A6V-jK+Jh_EY{f8 z&)eS>RMk+SNedJ~DwnD!=;H&a?$Fkwy){eu3%h0ZeNFaV8b{5(?s6>zx7+X*T6buC zoM(^u{s0dxn8pqb4=@C?Lf?_>J8#}Oi$D>W$ZqMEfOsUc#(kCE;4|>3y=vi9WW$^b#cIn)CjP>k9EMoO=kmpV!49{? z)>6d_2stpq0B861p|bUdB}?YC7__cN7(q9 zM?}-ahw}N%#VFR*KT1bqxC4Wvs+<|VI~Xs#jwiiWsg91hS z-z>oO&ChOSO<+5Fq+Uu3cS?1n?v8!;6+SQwLPu-AUmL-^`H003w55LSy=KBVKF5Z@ zr=la2Y|R@Jr^7PI;79j|TYox9G%1EdU4riXeB9@PvBFK5x=B5|mVZJCW4{SdV7e!L zPk@0#wmZ>U#n?AlK6(7J&~ho(y>*cWh0*CP3&0@IcnMDbvv=qdxts?viTD}|bhiiV zw)#&p^B@!)bKHBxS1C=Wk|NI32#rjL(8;bwO8B`*{|N1PO1Om#{6+Ig2*-j@ zvi#A?rS-bw@Qk9jnK{e#s@>v&FQFxdeJ>?8b&1eWxA1mPj`;VA;FGNCR5f+CfX&|2 zT6BW)45zm3Tb|CTnwN5JMTlpOJ6SoUqk&3U4O39Re-gBBr9&MJ;7Xf;O76@WRma6) z#VSKV(_Jl*{I%dDd4u6=p-=H+n4FJ#H50!8X7RDJbdzt_VINs!cQDO>(^cVzSkgGL zLSfcSvVPIqH;U5p#lEQ)cG7+`@Ty{Tee`E6GX?sdMXLL6^FW&!lnnce*!W(-fmMt0 zVfL^Z$0|QxX6hWOyf2iC#VL;5q72hI=e)hmC)gD^a(!g7S6V{i(q!<2M}o=Y-CP)( z@n`p8Pvp>l z(M&B0!`pneSx~v&J8VUO6(2Xr?5s z6urlz0HISYKR@S2Fye+M1oN(OaWUXwA!|yTXqr0ISmQ!FAvrl3;u$+>0rqZ_PegtP zDJw(B@yYMMNn8^i)FlL&c}udC_hueWB`mp8q8a10uD(4OZ0S9s4Z|0b7LlZks%@96 zu8do%^#QHa0GIQe)A`h`8ac~}r|@Td>v&G+AsW-_wL!Po%Qp?1Ge5|{Lv`j=7&)f8 z#$G-_=tgVh*#7(u;{Qi?+~wc~_7C&KW6l(sV(Ux4nW+{($PU!j>`v*^^hwsCF^jPJ zc_Ep`x<|HBuk(aPK@~yaQ|QFc@W4w#VY~GvLw4iHZY2{j-H8h(pt-nj9dA~`@-4W6 z?@au1H5`%xK`kMB!pud%(dT{zIKi@89qXIOmQpLj{W?v>6u<(X=V(KVgBR2aUS=88 zT1vdZx_+CV3b&YAESR^ezaa9*Na#=~)>ez$au1|TOZuPwQXdb(U3*ZDD(QV%SH}-x zV3^axD_odcFUtS$A2{G(p73!&4*_sY#(B;?Qy3_>VH8DppJ@^usykj|sJ55@|9e3g z9Cx*C?IWl1om#pJI9gg4vP&#Q(3k<4$^Q=y(Dngn{43Uw9p4J}c0rr3asADs{XYj< z&YrrAX=cR;_*S%mXwZcp7xPj{XK=OQ54F?fLHVqyX@d{2!gp}buRQ@r^rUYFcwcDW zgp>FJjq=-xtK3am_xCuG)$&_`00|k{4JZ(#XjKXlD~bvlnb`g)e#-h)>_h)4+r^a> zB)7xqy3_t{X>;;pEdG{q8+bA5ikDdEHC5%Q&R6=lEAZ~iC`hQru!DLDxR>r5g$~Oq@`3fq&GaeYWldPvM%mDKQ_84s1x{UGSxo4+H93uAu)>nI ziY`>-cxLgLR%R}Gy?a-dW1g5Z*&D_`i#|(d`hHLKO%NL(oCh@LiMJ-?fZf1&O;g>A zmX|-pu4&WHV+Dg2rn1`4Qv&=!2ThRX9wqr# zI9>T%SrkLTobgMmagda$!|~oS9>ay&94sjgHqf|Lu1j40t$K^j2661T#7HeI9U4h@lWeyO&VtU zcH9T&?M}wP3Ra-_X>13c@u>2sa^)lgg<-NiDSdLT^!-?T`4wI2PkU=8t{J|P<>4hq z$c_u{&b>$2)T}}LUL9*07)@MUNhwY0v5@P)>3t5#F_Hzjg@-O0GY2e{pbs#3s7*qE zEBPe62uk4{C9iuCfrb<;9YV6Zb)h07AWQR|;s^W-)B>wAMFzjhGr{Ajj$_MGgau{& z(N0>=0`dByo9jaX$?qkzt&JM)-LG2DLy$?@P64kXfG3STr}th0)reor2Jzney*nlu zO4XoK3r)@A;>{lW4Q_Y?#gF`(9Gx|0#ped6HoGKJ#ENcQ4y=8pzdpjD7U&x%F0Xq7 z7aO4?&h911N!;;D3*`$oRiK1-3ijJe##OunnYdQ|7~vLJJ_xw9kQ}n%O^?{c_IBbE zL6_>h5Jv!ZXgzFjrJ=&u5A=Q(XqUv&M`s+}@CNi_(K+EbPHdd;M^GOhBc!vZ*?ECr z=ZvdiwGVXM1*hP>()p15{`ubqXiU!orNYq1@VRqM9;M?p(1qY3$!qjgM9A^mwaeT< z`{V7@|GV~w;W0bTneDcYA;*VLru3x`#8*UquL0Yqe^`INzMVdz_Pdm3+Oso8YD0EJ zbaKLUXL=TpUmgsMSP)ZXrNW=Pew7GK{W zAWc&QZdhjI<$yHb&2zFY{fbv?&EH-iZ}gSfl~cp=Si(e9Y zP}X->c9)7RJDn&tV!#j)QTDQ3Nn~SAa8$>jC|#EPv1$MhN&G!Ph&;mLE?kq@5r3y~ zzw2ApthJyQNOs8P9$nm>4{ryu9u4icUj5Pl_@lu{tj}!o?>gak(Ny&8(rkAf{D))8 z;wlb}8y4RD zTF}hrkh+jk0dJoY+!|UNEoz#zx_|z~kMARX6nB*nwYxwVq`n(Z!@TYW$#OpPkIwQWFI^BdC^xy}OjeDcQI?h>KE>bXM64T*_{7|k1S<+hbs zcAHP0R(1%8XPx`R?}HEo@|V#HKoYF(UyTmEh%J3XWjU+Q0KkdyCr0f^z)#8CXh!JZ zvwixP&x@mr%aD)+pjMK;n1%XJ=)vmdGlJO!%9>II2uTAX0zgCmOGNzt^FucjJbT=N z@7s`kM!3)ZA>UyWZo;mJ7O#01=AI0N$N4A@wrc;Eni3rfDdo48J{_SsOfch`E`7C1 zL6Qs$c`}+?k(36NaQCHeP`e7ZajiTxb~kAp|0ak*(!kM#O|I(>XtX7jO$pD$>O%w( zczi&~!m}mnp8}@1WTVMnT*E7fVo-by|I((2vg_f-7mf$*ho3fc?}_9Ke+OlhlKnA2 zbIY9$KHYx(WW-TpzOFTKg~@g;KI4W5IVW}IfCD$!`4Q;}vWY=9tdQ45ZFyqqqKZfai>)b(Cl`ykDhk2qx zy2sV|YWHY*th?`^>B-#0Esa4~L5>~k4FWTbDve3wraX1=`t@k!R>W^-&p|&(o}DuY zU6PiOQo_HAP2!+7N7S_#Tl$Vzop&SX#mY~+xyLbRc1h=Ue?MS9><%M{ZN`#NoUb_m z%Q1@AEWr{kZX^Q9q@mc3_zYtTbhrK<37XRV%p}ve=^KH3IspBy=9g>>(I{kSI}u{WLrFrhQ7FpuDNiwZNcPH5>x!vLmo`AvTB7Sc_eNHV<4tQhW+8S@?zNYC9IT^yn@5< zLm@*s9~F=lG-d##*%)SlO^hJTxkrVrYQs7Ul~|>KXARPR0@RCwzL{#*UBZ?Y#9n+1 zo?pko`1yC%!7H0R+bAt-8TYvf*-L>9bwm0#`cQciIM0zs_CL2hL$<`>$HF$il;?N) z4<>f{qbYegNsVP87pM)9l;&fp^^BRxRWu_ah=FZ72t0EGV+Km^nGK_(%&qqf3g%Et zV9Hcb-ubD%QwKjCo8Kk@!FOx|>9h~1WAAncv0{KVcWnNpyafMJUgPp8A~S@5H$EF= z>8N}ji|Ous#Sh8mAj?ICeIN%|WAepLxiWNT3*?)UlK_v5~A{~ylh^0}_- zJznqU>s08I@>!Yl0wxE3at*@0fs#-gY(m~z9$bA0ePO>gXt=oz0)cCY?p2}(Ve7jC zF#)!`jAz5g0Oc`9A6ahz=*722xOyj#fxD&98!2thFZ^LRo&wHPW+x9K;Gk3`T#S8D z<`BpW(>*n_fPrPf&#nuKlOxcZcbtI;XuG{rBt%9ree1)y;xKaLu)7mB zoh@gPmjL?4T&Z$Rl=D!=m z%Im0Q>n)*?H#fd*{{HoRulaL(EZ5xKrl6grO^!wl#S&1CyTfDZWLS#Im04+x7*@h< z_Tr-%mN#q*D)?KEKqoU&Z68QWa$*bvM2A~@*^`!rQswzK7nEq5iT6g3y}cmkD(M7M z%7K@6ZXbO|#NSwr&i^hzFPJAFj;G}&H%~`lqejn!&Xp^LD|``)Mb2HN_4f)8o;LC8 z?$Ir67R=jDn3{4C?0&2?0w1f~$tI+lwQ(JoLjO&o$^a)u6~|xLiueDAqPp@VF!uz+ z439n-Te(JRtV11k)9s>7403?&n^<`#F?p}rzb4XWFZODL9jNV|uY$MFr;+}McY_;I zYwM6aDtiK-r|Anw5!cc(lH!naPDTAamOwBwIbW4sS0N@wQlnGU#OWEGf0o~GY|V1K z%(E`%G+N{YUNrxQlKMwEQhu?123=;KekrnFWjkW@h^I9>^lC|7@;~3%EX> zuBe+~OSm;oMI9r&r}T z>{F6PE6OC*D)kyK{U9+7iZBdvU`M$gAFk)KL+5Y5=dZ>EB8g%ox>N)_XEXln{(;WY zud&%(&~Y}x4jZFG^Vguw_zU3x^r^>zoDYIGEp7t??RQP0(8)myKNh+jNk>imdo!z> z%C|um(Mac_ajADPAlmc;!LE>)BPd#V1D{JEKOjDP#vI|WabYl-Uk1hMp%MRAT_*}D@cm7 zh1TvhbrZ~8t|5PPzV%94$@}rM@`l>94?5<5U6~QxVk8FcE@n(D9qe`U*=sR3c*!?Y z(>sL&-)7Q=-Ji}s{*bvlhJK##?htD`-LXeE?Pfv}hj45gXd7q$vG&rv4NAazIB8$s z1SM7v>5d;OGxnQp;OgAl;eHDZ^XEodE!0rDg^%r$W35+^8UVk1r5`^H=iJe~Uj>7b zXvHTTxj4LRmVFd|PKlH?U;%}UsgPP-V=F=X(3PJDyx8L^m)pjOaAEz4((0NMNj7G;F|J$=fZ4Kl3 zE0KXT68AgxvsX)fp9>y6<4x4*-+!FsqCJkX+!@v8B7WGJ@RPBUj=pw=vKtyoBylvQ z#vzrzPL;aqMQFUzUVt6u3+7YaB6ogIb8FLFhbq9#TfP!&bZb*f-@S2Fg`VG6Stdog z0wKu`Txt)Rgn--a+w+t_Ooq31Sd~S2bh`LE;1{d+NdNv=$nFo3C;H)C8pKo>Y%Mh$(2Png#l(L? zPT##(Lp4mqGqpWrbzuHr0p+`Ku(z2x9gWOHkw9_n=6nqPj;zh4jK(s;!@ zNa0MGH_LO3-4jh5_h(-a|ue7`(dmpojdagVB?VK|(i)v6FkSDmA>>0-*X@+6^?CmK7JV7opr zk40(6UrSNBdyah3`6HLXsp-T=g+RCG^dYEaf>w1L#L_E=&y}O`Uo~d5>gifYvj-m@ z(dCpJbl;DbbH!e!jtQ)O;VeWLwq5|v;7^}q0p;$psTUoLg}eFuv^6UDVYrqH#+X}U z&=|B!`x$8dqjgM!T~rWKVk8=E*rQN|G+#X8vpzA7kJW@O3ezHswliJIWz4GLj43@z zlmm@h5Oo&@mmg>)8Ae7T{58B7wqEA>cko}k#oO>=lm}lO+Jtaiq`}ZA%ib3;?%2c! z>sm;vBEFuDHI|JS{Y)Kr*RSU^{Z^!^GOF^Pk;bFDX?*By*bq(WF%%+u2?vIFBkToh zEdSp+I5~FSRVl@yoIaQpU825ss8Iv-Vj#ZiL?x<^Z${Xw3!f`v zXZ|)SIgu0OuLYNEd`v^Co4L`ghI}V83zOAH(pbrde3en6NS;j8aQENZADZJ);|CE;v4#@sbaC_irAaJa z>z3iK$}O!@oEo3@?4^BL?k$|^RI~!=L|XxWLf%XElS0S?#uCJ{!@8c12eA15JG31I zguEG{eMOBf6Nhnx`ET-Pp&+pw)S)A4@`z{A8V;~B$x9Il0g_8P5-y?? z1|>>#wmm4~o@dnIOsD3#J6_T5{#M6eR02!@UoR~NP616IjGvg|&n}`H-?6gv9dJvd zOKA2UL<;+Gz4!FVNz6H+zerL2_)4;4zaH*PzYjUt5UYtQn4>pV zYq?q@OF6vue=5|gnsyKQlf9Si>-mubD;UFrWgw#aqO({PuYHRR+M>#JIl9(%crY2# z0!TNRd?SaxEOM2~bV+GPsq4Ui&vj%H4UZ2XcHy*Rth`YQ9XyKd>qV+0Q*-^w>v99b zFB+QvzI|uBCSN+P(Eqt91ZM8j+Xv26k6P$%!N5x1!*yiX4LlXHzYkYb9NEk2uSYG# zz7vtuE0G?$-e0EpjLvsei7~v#Vf5<|Uyq|ga7e*CKw-HpK+8yB*32RYac(p~n`i^9D2`tWc;*jjg-dQ_g{#4t|9QMR=g@36 zxdT)M>v={77aC|y_Nd#`x(%eHCJ6v&REnS9Fyh!59i4sq*qn5=HBDyfxKp9Cjk_?+ zmJ~6GBzq6z!+ervlWlj$7knnpMK#D8 z4NI3iNnM{BMT!nTtv6ymGEk@2dH0U~N51SqXrwwtAbGq)!cvs3FyF?EU1%TTm6Aw! zP*}o^CJYKwSW+n?9Gpw4hhLGi_GT@^v6+#z9o=}+F!agq);M&wmzxl^p|LgT0HQqe z#nd;)q}Z=pP;X}JmNgk0wUcM9QUD`H zt?s^vJR4v~H^t!v%w*qfA9#a7m&&81=5`rd6Hdz|Jk%ZAB($@a(g5M%m6*u+nMK55 zjC4Rn=k3Xv1^i1*2ks3~lY?lIO~=Uuoj|uduPsK-jWP8yv%d1m0Q{4HNR0qwe*&^{ z%j?bl%9F7l=V3}|A*A!DQms*)Mbv%9N9PhG&f5$fwv(E=QWaa6T zToL_^4euxrc6%|UjAd+_^qlkbx%W}kSI91^oMm-BgqUDjU%-BZWU9HROVwJDW;6J^ zs8=p|9v)i+T{?Jgu)!M4Lu&3dHl1wBZu&_5697%Q|Mw)*y~!8F?wrL*o|mmoH?yhC z%l{IcGquXk5+5@N0rkZ2azhRxW!oB+(lsM_8Vfj1(QFfM=3pg{fx@!K}i*Pd= zC&#?y zRV7I@Y8(J13%(w|!uG}8FDr^NeI$!J2BkkXQ!x5bjwmyB2j9HCR5szx)|Wk4@HAtI z3nL#?)60UHD^!s4^F>z!H_?rcm;yv@+75`oWn zzt%Yb@vVg7NFONuOs~%jEe-rqXbF=Gb7{lOY>AdGwbp*ieXied5?+xr}(rn>B?*W zunAvH`E4i8P41=x4`+Qe6+MuL!cQ^RAs1f`SQSj@0KoLaD&B&e`89=9a3lP2U-Do< zz1GysHbuvFMIhkU+UlEEcUUCNain3<59&k%03&bsO{pD&H{qE^Defrko62O6cd|Ss zZQY?Nj>3*%DPg-~Tc<|ZraqVsS=5L3nG1rx()pcIGdT7(NVXenVL$07JZU>3oki$$ z_9o2sd~sw4D5_gC5&>kO|TH9|MX;$;TyPs|D8Qki}&m(M%TM@(sS+8?; zeEjYH@^|)&$HQEjS7Q(&X2O5J#3}xbF0yw=93*Eghz?Vqdbi3+`0dW|f5rQn$fm|n zp$I;2QN9c_r^+*>2FRjh=zXASBxr3fAZ!@${l(NMA_ke`Q0-ih_H5#Ebiu>_@71Qw*uV~Kd6uoAR>N~ z$>oOPhhtlXhr|KaSRo9lw!F|ROkbvmszLXZ?Rx|Ti6synA?Gc5uFPvD%sew}Yj2lC zVJYCLIO5GA(B`Gsr?9OTOpL)0C5APMPgfJsE}AbWUY(;qp>($?Sf&F3$A*TD4_nwR zG_3!*+D`-W90ZDu-t#+uOD*|R6$CX&l+w&7PLVa!6dH#viqIbtSz|Ha5{gY6J`jfr?o%fLmGnZ3{uM2LDfz*wa zoKrvbHO+n~oO5w3r_-*KXY?#Db8+Rj0IzxYxG(mpZ$OvWeaDT3n&S#WuC=Crtj321 z3wOPix&ITSPO{T4>^6yOdC7VgC;|8WL_K=WbC{2et8jrcDa}OO9u(fZ#cndz4 z(v!4(I-4`Gg@h8;&;Bh5v%i_NJl_}TQ)YDSSdhKQ)fWWC$VFsc%#Y)GA1`L*FY=Xb zI`td<)J;t{HT|31^yLgA@u?}J63Ob-`zb}#3+r;0e)$|7qbd=^%gHNVHbYKS{X|9- zUzDcn=q2em(wk>1jTOr}-08M#xI_#&6rmA%HfA&wF(~TcFuGZ8&!Plsc)qxxaJKQ321W$G1r$79==~E_rZ_u8GY>vl3n0oK+Y3bs{=W62(n!tM(H>88DgAMX$A0YuDVO{|dUO{m~@K#tsL=^lH6z7u^7B~Ib z-_p*;^>9Khw?GGHXG?Y=RZ%_xFcp`Hpdh=jB6u>g@^SU{`T4Br;OgTK+WaNNEW|{9 zwt4zurxlRo6F3XroVT%das#sn2?z>+|AL@N)xp!o)(s3(6%-W0PLAEGjkl%U&uywI zxtzVHrkxB1zMwDEPY{?T1n zgP5O#ToLmFA?2&idZ@D9A-=xgDur>UdhX{v+m z@#}0ybGrDS_q24k*K$MJID;vW{zqgMKRgpM;Ae}VprG*2W$ZkU7CKxP+hE`jc(^0M z!+~}_4oDlX!@-9~baQj|c5we=qqUo>tBv&`#|~$-^z?M|`(rm-H|N9S9rketC;!9j z*aib@OXt6BHFiLH+yCquvi?$X8bsPkcim%Sy@&F|;Hq{9n@3oBo~md-wh#QoXe%2l+P){ryZoj`@!Xd&C1E(l%}`Hr}2AV9$QP zv;K(l_P=obsLj*H+0xs=_m84uc_@K)zfJd7cj#B%{`!pNv#y&1&_zJC{1hHR;X~FO z-YGF*$)AKgTFJ}J$J5&8a1@p%|6C;g$&w;}T2e&pPfL1RdfM4||8FcQtOPdq3$6b# za}Im|5d44E^Kb5l;9m*lp*H$QLitCz^RsvGwlQ$G1gce7*$-&FKMSch5P=_>nHLZZ zYbJgOy^W{0%@O~8Ho05=pUdTMdiIYJAtG`3`xm(t#IhK>m0tx{?6B=fa(esK=~gu)K_<)ZviYaRLwf1%whogM73-m*1tZ)||p zQv?pQw*zqV6b@gwI3ST&FXS&V#UByip;`P7MRdQpkw=0kdT5P*(T7K}`YWJ20v|`h z^M4=Efmq4kx_y5o1(qNT^8cmar@wjRDf|h*h#dX?_mhJE8C?In^Z$R=MThE2wD!TJx-LVsTJ{~4TibdXdFd+{+E|>iFS<*_7BLpHJ;}2qHCdNDbL=yX;YATy;hA)4?T2Jm4hZl zOaq~$0lU=qI(LYmT8shXi)_^X&F-&kogp*<5Sb^x6!v_|jb%vo5)r<7F}T zcIWYzk4=-=yOVBKY>M&_2rdgVJ~4Au97b_R>F2L_7G^Zpwd7DbydUpb(E}XNACFfH zAhGax#UjGPap(cYf7uHz^zk%)3s=)x`|6gF*A`(e-`D4@T^l~85mz=XJ$%#K6tLEN z?n{&P#mdVrYE9iP>?dO3~Y)-ycY>4=D9HRW{rDzVk6&G6fWflK%wGc1ga)s*8B2 z*1ZL4EC)=*R+@6YI>aA?ucYHVz=yZ(2XK8%I`^&_;oS@}~jmN7Wy0ZnXpJq6Ylw_t`gpN5s zo-Zb|E4BT>v@i-NLZWl+Mc95#z(RR_S&m74m(N9F`J|v#Y%65I+lhyJ=ey-k!f+^)g_jk98FQoI$ z_K8o{@_(_Kz6tj%5(r$kui2i>&aQbO`{p}`=Yg#K0P|Wq3BQR8vL}`ORXPg=R zhGPmKpPgQnRkuVEQE_B|CHe>HCD~Ehxl);Xo0F55{NDN4&cD2SaqY>SkTwFk40746 zCt0Nvp*t>Kt6g;2@BAj;$uovN&yn;ht5k;JM}{YN{?jZ5jFeOaQf>!m;6 zFYERC{zW z*hR~ty{6ggOI``zVn9#vmh}hPU=1~XJQ!-d!ll8FQ2l)v%Xh~cT4I9M-HCPDK5Ra>nANm zNyv!OM&Mg#CLy62&u;PTL}2o}Ux)^7g8f#v+%q zdOK{tVNbjOEy24S^J!}HSl8nEojuBfI$A_$SOQ)qOVL%gyMf<6UmV)nY&~#!5jc}w z(sZIMW|AautnuOw`@Rz&I`)8`K&s<%b71CiM*k}^h!YGF19VG@G(;oNNSxmPU z!BAV3dila{tx&vhy_rt_zj%8^n9YJF3m;iMa?xz8^I9^&J*LsX3bD2nM;QDs2SLS0)fG=#vG6oyt? zWP~EveCKy_A7R=pq(`#P;TItub@0T$f}yx{lcq9YsFQpe*NWKy&8$#h0@XXcx=0G* zUV3HQ`<=_UDJoX!{gZJh_->a$bAu9)oO4YD_Ppp=yl*EH&!S_e3Xt|1V1xV*F|d6n z>SrfZXzx5JQ$SwR_`3^NGown3O0%$6*BL0%3PG&um>;+kDLG$s!&ylBd&7Kjc5e^o zZRgU~I=9IQj;@85cTo-l`By*eTLgTh8LG69TdQx~>suAoKAq>)FIns`R6M&_^TIbU z&P5!FfqLyM)xVJxlzZv@*~@$)Bo@dOQaRIcB|SkvCd8{2!izG(b_r>E>P63?8IqR+y=YWVa+5~iI3=|~L& zR}$LB=W#y*If%6eA>X~Er zYwL2r>O;qoXYk8Sqt2~+8?!)9)sATo;tfD9mYdq#FCVCPvslBhCXMdDIQK<*ExmR3 zZhQ6Yi`#D6=axjyiGMG>Se~`SX;EWRYoF4v`t-C`0=;N2&|YpEqt@gd&%b|rZ6Qv2 zT1-SKhD=l|OQf3LvSm11+|4yF^t*#_=&t|JJsqYU8l8E)?*Tx?@Uq;YS#c9}dR4m_ zNvQPd;^m3q>iurHeZAzZlVNXM>P6RP`)VZ4c=Za}wnq^Gv-7Z8wCcgdbXM)!3Z}5# z!S%(lA?dC6k;Sg>9v8d3dFUIu-WHZ5x9=}(+k4W??lkEggL~T7)<5j#iUH-CE_txK z_L?dIQ_y)&C7s|}I0hzQAF?o7ZQF*rIXu#If~4ni(2~u9q#v*|nwdgfm%{eGrEx)9 zmRonfUbq0si1Wv_4t$o@rN*`o z9$+52{n7SS8RFIOdjGjE86Tggn-%1z9ou~N_G=HGP~f)_W39dK-Fj&nRHs+I-iyEKmQqLDCW6H?mV(0oux3C!0`98*lX1PsM_ zJNRX2Lo47NfrUh`j4|ESN^24P%g=%xSP#CxZY`U{Nr5XXIDQ7%6V2~i1a#uXovHdXUNh6%$3GMV%-rZIQoqsL9!;_&3M_=^ zm*&m9`N6`N5pL$wGm+%7Rh_d@@P}_)&!KSfDw+o5_ST0|F?b1tFCTv{DRmAjqMOSD z3=q9Qo3TwV>S*Zh6bDxf{VMX7@P{^HiBBcqzt~d16tb@8HEJ0{(_9F!KzFFaT68Ze zgU&e-{^+EZ_1i}tvo~~P5jupxkYA6o_1JvpmklIrREk7=GPs64J-(9^G0;uKnR8_W z5RUZmX=(qe2S%l7J`wx~bm#uXG`N8H)FoAcJ$Y!kS^dM#)n4HjqhSYgat98g?3_qk z2TOXzfl+}QQ*LKV5m&Oz8hy)047p#znI#$awzE218<%YR9Fn^LE_18oWrLv#%*;sf zl;x2W%#UP!%#-0<*CJ(_R8X|9q6{^e2`+aw*>Apale++si1k9Q0$`B=2sOF_i-ZW| zGE1W0`&~|x@Dw!94gEg9;j}$$pz|#nzH(=U;Kg%c&Mg+l*A*_gGrdImTuE@|<7#}j z;mqk1%|Vr|ga^k$Bw0vy#ge%rTJd8<`Gc34UQV@UJQY~@_`Nh1&SljZBFHoYfX~D6 zq5YjNZasKIG#}#N@k>|s7-@idxu5JO>#Bf$UmEiC`l(mfr`Yu4=(s!EFHpVN1`xtA z_gPaDR8fV6ilItbZq;g*AcK|U^3&1DRn!#@DWD6=b#T3ORHhAU9xbAuJAV}4WnLdE zHRj*>NU9+3*gM9H5D*)u>bDW0#lssA$w?;IPbDCs9n~*xS`4WE;5>IXaTZV2_;SGA zQ)130dgu%(pOO*G%65L-0F$kB@Oc=?9C@UvY7Dr+Qj58Xmy+SJ4DBy;n*+an+oL#R zgxODUJGLX6Xm&YI!bR}Ld-sn7qzYFqKAw)}DGS57VUP$9-TP*|)6St0n?7;&UXGQL z6^~KLOdLEm@$ttrv)&GJIp?1Fw_Y#m$ecxT^a@qSxOiKZ-=z|;T^-sftLYb#+g*ud zKfg>8rp40MmSBO8elqn!l1PnEm|>qDf;ahM@H~^tjzxo~je;;WJu?!wr|R+*t+4lS zwEK6i`{p-+I2R~Sj*Y5>(Dpy>vE}KvdXL{-8KD|(aeT>sV{t6*n6fOYlNV9K0SA`U z^DzgBqO73bO->1y>ZzTxTYOvJ`E}em)(R5!1v00G4*>hh)#LaBTb4ga&wX8?L?}0) zM6f0_=!qzz^B_&6LmzwpBeE)1NpOMPS0j9#gn>yoQ;pPMV0zDQJ?@DIw)!WCVHWPJ zZ13^VkAk|Sv7+LrII~dvEu(oYob=^}gB=#!o?}hg02VF$ghgUXuzrXK2Ry4rpm7n6 zA{}BMA?^?2FTmobsmsr|IfRIn&yMr!6?}1aPKg%I(I1Ofx|-9)Ou<@&tL}a>Imfuj zXA>5<)tpb)Uzdy@<1)x0`KYH`(Xe2TlIClFHw{9foBI~8E0xy_bikbQ6yQ~v3>u(@(w%qOl}en+C9;T+bp$rCCjOzdYr(NfIk`c7@>cQ zvCM8B%ZZ|6LQ*$uj}NhC#;PajFp3HBKqhC+$(jKX%P5nCubSkQ9^x=;t2 z@cbCL%Vt;K+98d%7Ay`N3CS4jhvw(*t*{KW14HfL^iY`v94~*_RWk)(8T~Q(CA>G^ z@)aV32e|=u8sjLs({`NTRC3xiQN9Gmeo<52R5uFNKc6(2&y}o8Zp9wN87? zBcPB{8SfYp{j#mG!9!-(b>M3&uPlU{ZGT=T41Fq}g(TI8mXcd1^+~F8_sm%mgIbGr z<;L1-W!k$_X&I$kC7p}Rz|UZog{)}m-x5{_VC|)&inOr^RFit9qy5xnwe`Cv_pS6C zQhK`$A1W8VcV`df5?8!tEkePqkm@4^9}FcTnSa?$fw-AyK3maQ-_~%V_LdceLEu)$ z8%FBqRxWBK>URY6-x>r|8%|yCdwKVQ3+=}$Ky-M~1*Y>zJt^PJ##E}woJC(s(YrBn zIZLbWBgw~Mh+*3{egz_ACEoU8!(5*2c&)=jHN;84U&3b-PoW6^4t`)^T1Vvy2K(?9BvPGNpJaO4+U?s&WL05G*wx) zMg15vMvHYr*&Qflrf)w%QX9@tesf@EBMv6u9p_hIU2G0ZiS|2TFnLU}Xn<{io9pU@ zMOoz4Vm&>wvogE;t|Sp8T%^+eD_6XBSG!MZ5WFridOoS}Y<=SyPvz+NSDuSyRSS$o z_O1AF6>BZG{ilh5FaE}pANYjbf;GG>gp{P7gpuR#4e{B|E!9tknpygqf@xjSPYK(a z@Zv2cN-gwdi*Hu0!DM^@w0Kn>b3cN5DV=$ccS4+rFlS}16^qq@FFo-ImZIXpApFj% zKS$E{!*vG9m);AnTteQVfa~$(lJ}sBuXUZnkS*)=^_8GWv76LS@z=3#J5b{j>z_xS zW8L71bH0Pe9xN=3l-f=Be;_qz^mU;#e(Y4TH%-RhYWiUfCLb}E5t##F8T!(Cu&-+Q z8b;Ep`$A1lo9FZV6n}_PvQ!S#M*9kIoVH)#pR7G~f515g#2~yhEDInSwH6VI4|hY? zI?A_$5N(~8HUug$u(zTbyY?{D`?Ta;O#o(UTJnpvvQ1qofJ@m%`l-q;*vMz$Rb3q6 z^C8$7UxTVlOglL>YI7BAn!de!RkXm!kS!x`knbzGZ9F{wLn&b=KJ#(HNI365=sOVWbral_ zd}GUEvc7WejYtt0C+~6f-2txe-xln+fsS9CPBuH^Gptt(@X1E>hkEs8U zv__ZWg2@8;u*kS^>ET1+6cu-;o6qv@BDQMEfE?CE7po>Qx&*F&vOF_-Zm}v-F8BB_ zN#X`D7H@6u_BG4z(rX~6=u!_BVxWHdFKfC5*rjN8t&PonZp}}&9uV63E7NLI7&ab+ znyb~U)KU#RTW*+R+!3HOSLSlA9-hi0T;H~0SYE`{M{S*jksJ)LmF3E)CeV|4NYTKS z0yh>NAog7R^%D*Zn3#>~8GmdOkbL7wcE84P`lxba)jm%P_Q8HB^ zCY3#tG|T{yB|3!5Z_I{{PNuWwEQJ{eOH_^|f=Jev=WHspciS+T40x=rt$V)NMr{vt zP16?!ymMbkQy?T%jF*ttJgbj027Y2G)k@|*)*8k1pu_wGlmF0Ijollnk4&LkmV=5W z+8nHC_lTDVd_Im?@ec#%=-pU93w3S05}9OY@Jie9i;-VpFx2#?RhITsboDJT3~p*T zyeSsbP7-*k=_0avs^ErH4j1M0m|4B6OHB=7u9UR)n?!?mQ1*Z_(5=8~9TLVqoaJuv z(no@(-9oZeNurGDxQq&|c8c-2%sbB(uOez}!TLq6b8m5{Vh~iR150(UFVAM$kAv?YFfwbV)G}lcNJMKX ztB*eD_)vRhd%A1vI|#<5OY^359pry_KMNpxJjV_XxpTpCtUfE-D>n+nR)YPro#*IN z@g3epWVZz@BiJD@4K8AK!E2OdTh3~-#__T6eUxb^1x#GRGlR^_K6$(x)7}?<--Y7^ z;tD56;+cXc!;18)5=CT5L%uWY-Ns93o97JOOLH&e7LaVc=tdnuhuVRGD{p7`pOOh%)^9SX+5#OF1BNsu@ z@_L5o%QzvYY9V@KM$_BpfCu7Yi&Gmfpn{~}7(aWGX9=nB*}a{#`rzx`>+wvRK=q7Y zjDqr;KOWXCe3yU(#+sJp*_1zUKgL3O!U~}&D%AHm{d;Ru2`IRLr*S($o+UL(cU19| z1XWYiRc#sL2%pcx4=OG@BA7|EFIh`v$%Z^G6~%0`Z~4awod(f^5%dEO`X0PFcxW7d z>+VaAy`2uG{ru>S@F!Rl`hu_tgccKn)P)gS=1~~I`?BHypq#KDZ@fT-xMF?p?TmGj zjIGzwiXDpgq1q1RHP5gp_q>pevDxdw{q7={>3d-JVaka(r1>cr7>@4HTN`=|o&ga( ze%!uVbstMHP>@MOErs|_*|H=zMyl&Pk%lW>59Txh6rz zhv8O@z@6t`9LE_hv9&Sd9_wP`MN+6z6j+%Merv?QxR3_pZu&h|Ands@{Ovqb2y$uO zE-%2gsK5QDYZ9p|in0t?0#OjueLM#CO+4ZGvIo`+Q`TELlcHjX;q-o6ltOSyPn}M? zh-yApQXp*uOMg?=^NF?J9uIyZR@d)=#e?qU!02$#P)WJ!WANr+r_QOb`>hY2e=|I# zz-D~mlh8G>rAtH?^)r|PW>RPpvz5`YB@jJ(l(8-I;VNv&UBE?j;A@znbh3rrGf3_k zp?rM(j&?R>8Ff_PT&^Ft$R2wfyns)U`t$ThQVw)1@pe?=X*)FY*V(4E{+iW2d+K5O z3Fn$V%6RX`#ai0DuowN3b2*-Fa3Ul{I`%*(4wsThC5XwxOe%X*RqrWJa{2f-iJfFO z8C;2_9d|4(7t6Yo(*tu=i7hZi91Tbz=owvp^nuI^LwvS>r8=9n?`Y!sL&ylqk|Q@6G#wHOC>J&AXgEY+v^H*MT)-u+Cdx^FUt9m3iF`I z(@CchoedB@!*i-g3YxD(XT%-R%svu6mA6AS5T$y_s+S&g+^ET1Zd%j+kyzlgm{z1! z=Tf8|aYVrj6lL#xP*tHFO_0<)4}ov*s-L-BsG1N}knzsJdR!7jUtCI-c6G<^_rTP_ zLB?fZBikan0q@5N zP467Dzn2$S(wuIfEooC&p*EuR;3**~z4MCMD6;K&^f+YLZvw;~%BjqNU2q-G5bf^t zdWEnXgQ+*z*WJg!;;=N-PKmxSL(<$d8Mwe})?A`nol}LG-k!T%Z{ZrPc%CGMK>fYI z+D(~4CjNsk=!MP z+U0kRZx)DjF4Z~S8i8lb85x_~kUTEr?adZ{(X=&!cN9E3$CjG!ehq5cKr-qPjHWCfIIv2qDIh%1aVCe%35TB3Ek|^5`7+u>w!me z{G?031AT$H#|srTua%@hgrYPD-*NP{pw{5=C}lZGH1in(3YOhBAbaC#5qq-`zOWSu z=cXseW2O;7u7HROqWumrU8bQIvaJKtEUyWj66|KMCSp5Jn}K&ZaGpJ~Ax2UTq^^pA zrVwlP9?eqWLldDR+=;4BH1=23bgPzYD1^)C5VT)CcHFcauT_PQ;KIo)71Ma=t%zo( z*T^h5P8EpX`F4Co%YtxUA2y=rvUU87ck-T4_eRoisqu?z_FvDnrr4lC-2c^byl(_K z>v`JUa~9k7>=2jj_|K!&9|F5HJX6SS5y6J4rD2J8WEa+7@wr8*_gmM|{qBb3 zR;JxuGuYf>jr){hsb1BqkK2P0Fq8-_*j*(u4=xb0(*E?OQWgXgaT9-wZAE-0Dp)Ba z0od3E1rfslWHm5UW>o#a$93lKRtg`vL?#Hr%T*q8_Q!HGLIH>u8zqUx;MJU3 zoyy2!j-ur?HF?PzarQiI@@cPd{J58j*5SIISt=~(@VANQmLHMMei&)Xb*r~+u{Y5; z!#MK6BKT4;!aitGxONm+rLje@y^A|GFDy&gpWyW+gO|H+f#%y#!uc8wSL@Q(+=Zdw z)GXZBY;;>u@K7b%Mmc2oWcYF1wz2EvI9@NX0mxhrWoeqgfVuNZ6c_rR=TwFSliAbO zIgX4o(|-neiF!RbaL zvID%LACdTU)-+OBi1RWAsC}vXS{0!el)}BF5>AUhq{q8OfFd&Gxwo**Z1qJRuHD6h zKt6z^7-;Uf0ypLKV8*wY4`*UFsw_Lo_`@ANwgk4m@~CLAJmi>b#=)Wah^+-6(WHyo zqOCDY7h*D}I)Miz*oOySa&1oow#-TGeBz6W<0=XDGE8$?lU+h;T@ zwIgXXSWsnH(I$`oY2nfoX_N6~sd__Fw^+lK=v&jNh745vBGqXO;CIHgLChH03`wDq zjx zR&$I$djQRiR>dZYo{LGC9y^?5I9LRMGjuThIv&+JO zpwz*SC1yiD1`*3V&Mi;~Ft#R>bN4K$qKJ-%(kSsYO{&mNS?0#4G$pH4OZ7g$;hGX} z!_|2?JYz?}^(_se(!HoATW6)81~-hlf6{8|fDa8}T2oH?6b*m0s_2tJMXIU6@#3of z%Qrjh+B?s&vu;N>9qh%zce_PKWCGbyppyaVB|O)}p%+L-=0;Dx=H< zEN7Lediqd%YPnSUpLvw3(?_^N%P|EKs*Wi!;l}8Ep7yiqUhPD_>g$mA0~|KJz~6D| z(_xrqBSd(aDt> zS$i_9!qTTXW_a+ChQ(8n7D|ranMuTr&}dfy0e`-UIHo>+G!BH4PJiYTNXcqQ^QkxB z>U-piCO>XDpTsEU<3EH3zXt2sJ1-cXkib#cKTJ2k2CzG0N zQ|&ioAGaJAdo7Y#nck{=jSGT>$GV}g6rCAFO|&(ho_yT?10q<*gdj#Ry( z7*cRs+%|9j{>x}^%=MiNJKpHJA>O9oLS%P zW5WqL!q$x39LlOG{dx4Ou8?B|`MxrB@9W2GPdmM8e@lR%PDLZz;+!;1v}a8hFRwSs zfq2bso1k#>mKJU2h{5Ze(S2;Vg|J(|^(NF%AF1n2!YOQb33Fq{kom;tvit-INuQ*L zo*ks(CTmm#oh#8R6ye(sGJtifoxOCtp&`?$djDIaAHFi}gkY~BdFTy-_Y@`SQw%UK zwh0Q8de>YTKY3gpPuA7w%b(+%HT9c=HXoW25#i1!wQxb6N)i+MrPRlH&lVMQBk>)Q z&4|$++{s;ZFAS?+H#~@(stv1KO9YPBxoer9Ss-W}`4Xb91gIf1eJMO7N+tV!SKo!x zx09I^ad}EO6p0O`qa?P(H8%8JZ=I;Q$-&1yHVG7{Th_OC9iU9XU#_@B7L-6BDWFvj zOJZE;Cl&o9$L;ES$(Q}eqr<;%EIH*q%ZPaF_l0r%6uw+MR8n1UnUThPiW3yY$PM<& zTPUOu45X~qf=t@Oj z$wAU$N_3Z9+k$9X?Cs@bE(ggK3U}h{6@6{-7#0OO7D_}^b^Kv0*UR|07A=m3vJT&6 zIWL@aua2nl)Jg}CyG>(;@V^5Ibfv2tWiVwJN;hq2h#5wrvtsjQS^$G*2>ee+i|aG^ z&q~~@5|mt^1UB00tlAjIla#(cPEq>#w^NuP6?*qQy3g2wyklC=i9!ZlHfq}QV*Lxi zzqp2e&CCTWZRb;DLqlu=WI)lv3cke#9~lZRpH_Acsr*sI^CGeGc)b&WveBeNf3hm(gyivUlHWGPQiL+3X2=UbY znWycGO2tNsmK_@1=GYL($>TrP!r!)k0}?`Aavp^-TC}5!gWSLo>mR;#g`I(>6`!73 z{Xor+@)|X_qM`lnA$J0P<4y+$2~M7%^);=^+%(Fv97B+)e%^?ZfLvTf^FOS)5}q|1iphi|$YL~+$ic3_u^ zJ#bRMRs4LX+i6o&Mq?Y9bdXbwHJTO_>~>MZOzH)=>WnurkI$pq!1Kg2#QN1g^HmzW*7CIQc2Fm$Re8A??`&H<>lr(dZ+F!j z6h6voH0wKM4b1?!Dg^ZWBw^6ihalXLhpmMuSH0R7R?{a&65NWf7sa)rZY%)On@1_F zTc%H=;3g2t1&T91BSyyCXg-Pl7g7swrH4i$=|`|pto9qIyb=dB8t6ILM9>$RY{p#x zIR)hQw+j0vqgXSgFBUC8SbhAHRbqp2YofH3Y1zYRzp}$n$+$Y--Sx8Xcy5J&!h%_l zx)B3)Zr_40;@Wv*>l5&ygBo2k6^+YiwrKUm@MC0E9QUen+QIGT_Wh!;2XF#0;@~?C zVk^dmBQTx>fg`q$t8WAKFf5U$E*g6>`F@sKH0}T-f2Wqw?8-8c>)#uL5#8 zzZ2Z%dao{=Fm45u_1WYFetwWj)?nGsLQS{SNvby^h8H!MuW&5r8XhI7BDmqyoiY;h z2FNM=yT9F^ZuJ@*X-)a96YhMCG$kt()ia&zhI*515}hJZqo$qThG$^=S0y>*{6n0k0;gFB;|keqSRtY?S|1r6vb7+wG& zY#7~y4-BR{dy-0*?2Eb7s8{xyLnV$M3r+$B*V9x|2KCM&(q z-(V>H6p}AeDJuRZ_pFLQKov^f-%*hp|i|Aue192<+cAS;Gu|-H7?}(JsD|is`+fs>D1lwImiZNWHS+-#FkV@KG4!tpWXNa_pEh}N31m9$T; z9@7HWQFCd$PV3v}5tnJXN=547i)Jo1eOGMQ9S%98x16p&ms7W(Oe<*O@zUjnZv_9e z1hHtLdd4QWM`ka>*|?1>oIA9i2Pt@x>&fmiq@J6KqFU^6)Tm08Nh_;Lepg;U;V6u; zBAdPW853vmYhZ*4$z9DF;ThNl-~WMi})7y0_v7g5BD2Rl}en!XzOg-e)^v!voyPH`lB0YAmly zaQ1km0xfrU`u(@Z_cu|mx9z3^Q=&VJ@}vXMGVD22FE3L03{{vn5(hn56m*-AUc;6j zjg%T^Z!EpZ231~TroB1RjIzOxwCei8)UPJkR)bR1@eXrClMm6?Etn^BrrjSWX7^XCXL7f^L(Q#EvE#o$Vb0c*;}#Z>ljw%P6D-~x3U+LM49WUrykzDDZK|O z5wtq4k&?#DuY4@J1JN5yfa*rx-@G7Sf2+h*g_a%8=|k#&hf1r1&QApov7*Rcr+ioA z*5Y##DhQjf>syJ_b;mMqvXeaXP}C-&Ri4uFyz9}J%e8s9#B`+OQZ*$(^jt#b{2DbZ9n zzm7vW#){ObvR^(PowvYX>yK+Gl+-|ktIYQ$C_Ua0C8mIzJ#=P8XNWkw{0=Du_i~hf z5~%5kkDAZj$keZtc89)ry)s&Dt+l!Q?##CYUj;S_i_g)u@sEO4oE3st<6`xsv5;tZY*-h>!B7G-TD8;Pc zJw>^>9IwPokfeD4!ar@#Q#V$uQ$N3JtoNBPkiC^IIr;@ayNxI@+j0<)A1)T|HdK2$ zPQu?bV4LH^no$lij5MYpuHs%Ow9Ctl3pY(vL?2?>3BDp}yPVg7AWM~4=yD_E$!@N% zqu~D4cizpMyFUn5E26tuyZCanR=U|k_g(2EHO##)?t_89@q7b2kj1(g63Vr~({4>u z61R0Pff6sAY^hn!V9vXav}AWQY--A=Su{RQ&ld+PfD9${sc^qUhm^1%NUD4@z7+8B zRCbhhRq=)s)e&XpBtH+Xe$CYl3jA5RX(Y0VmwC@y7xQNwoNH2IqdXybk;gX=&#*v8qH6_@XUqS(%mtULYu&sAa- z2}~o|i9um%LE42Iq?EWcEX0)N-*UZy@1bs?&^IZJ$E`SXO3^177qpx*LB6xa>%QZl z${WUfWyEC*@;)6nhASSgW5>X-lms8`Z|3@_2vaK1^RvyXK9%dB=QP2<$^?|zrzsv9 z(4lKgg3AeZk&|B}R;~1YNJmbzDE8h($*gFD2Z);DQ&QgdLCHCaMWs<0RO{PedrlQy z6jYE`iM2vQvs7mR36ZWnHv&4q61_e{WkZo*2^pu%@pF0<1;c#hu5bk~h_coMkzEoG zwQ=e4Y4uPAN17Yy`Scc?sF0-cO`<3$C^O;LdB|}OraWfq_Ra+jre$+#)<0(k$guSC z^Hco@FfBVt=I|SEz@mzr*<4XTafI1w#@otxXcv-2gp}ny6jU!M-sU{KZ7x&2l7@(L7%Ur8a`~l_36d-5qhmvLyM=4{jfkqW9gX+AWyAe zl)M<0I@Y-%trx(kGx|PY<^(YFtLId$Jz&)CD`jCyJWFO~H00RFo7eBal+Pm6-d%%o z;euTg<=ZS#f?bctFN8)vc?yVF%fqdVomdi7-DAM_DFc^BAz(W%i$RrrJ{)+AOL3%7 zT?&{B1boc#Oi3PjC&ZEh`x_tpCI$mATl?VD*WGa5wLsltfqb&)Iye=>lpW0U-X%dH zv|!b$t*2-|5ODs8w%1o=eg#&wYL?#D)&{u%P?Jq`6^@N=@)hej0j+TE6&Rpaqv-A!~G%=k~JsUm@+h-MTO9n{XcEbJdRCtOwfO%)fjsuxV zjUIM^T+IN~jh%0o$V~%2FrXkf;R@h5$d*%FE`=#mL{#31mL~+{Wpf`iisHJ8Dn3hc zHHwuPtu}xMl6Mib7Yu0d&VnPSgcBH16yU>Ci@EUifg2BdN&e|!Wp2UgFq{`lY{fI@u$B-ZOOfzLgJ)6IP| z8@@i{Aq`9a@m16`5EEFDkwU3_qx^Guu`wi-*Z28**+6v<<{PPjqeAh1T<7V}*n()v zPRp1xwtJMj#y>tkQNsiKPBxy8&r(*fy76@AV^i$ml8Ny5nS|a| VQxBWK18~4Ubro&p3dJiC{{yym>&pND literal 0 HcmV?d00001 diff --git a/control/predicted_path_checker/images/general-structure.png b/control/predicted_path_checker/images/general-structure.png new file mode 100644 index 0000000000000000000000000000000000000000..86f3016db5c2c492a0f1c57dfad87823919ea2e0 GIT binary patch literal 84656 zcmeEt1zeQdx;G&rAfN)G2!b0C5osxr5(Sk~x_e;g?gkZ62?J0h6+~jlp;IXdVd(CX z7?2tozV#COu;ZM)@ArN8-m}j+{`~38n)R-=-lw1c^DO`SG7`juRD@VqSj2bl+>*n> z!bM5reN?W=Zo0;h{aEf!YvV)~At8j2IaNPu-6!q*a?CkeGOBq|(JApALJ|1lz zupIQejRUkSJ3lKs6Zj?p(>JvQt8lV&u!FxGU`X8924-jp9uw!_;Di>3jtaBWHQGC- zw6v6p#RFq@TU|*9&Ra@yqS_|BdvhFMHnzr=7W;3*!OFqPxA%jcvlVP_)BxsStPg`m zxo$JCi-Lurzg%Mbv;ki%bj|nY-UqMC0uBUiZ@f< z$38KP?2Qdzw)+q7J!xlYX=Z0^^~*thOA8B_{yxX{SJbt!v2^_9G($_X{ny){V+G#) z7pp@9^7^`Fza3RJHn4;5&E@0XKOQvu4$RmHey}rO?cOQPbq^-*57@$W4J;k^p5Glh z%$7Yu9+1<<(h{t9h--&`KA2?gBnC5ssC_`k{e6Hi{nwxUnHn}fi~ax0a-w?L+Db;+ zoIDTi--O@3ZDGYDV{;&14!UOc`^4R&l&zif0ks|B#&$4yD_tPBT(=y7NC7>9+nJkz zZ;;CA+FI@L*wEMsQstY#448>onpxWHl9kKQ(2!GKAB@}D*;tyw4*g=lqsPO|1Af`t z5~z9e&nXZL}v4zoZmyNY~8R2(o4RK=@#Qmp38)7y~5~-T%Sd*uVgik(<9KAU2lv76!YP z9hkTO9R^?fErWS}hre9=WB)wt1)gk|zlU@XW&jM}zDio!*ugE0EG=}+ZvSoc<}V5U zw>eUlmOx>5HPr-WXXm_c&2{bVECFK<>G9s4&_=s@%lY?Ikdxik(%xp*7=TB9S3bG+ z*0R&JF#@iBHvstEc|6d(f2jQ-bS;J*AG zvabxBJZ6v`H86GnAB~`oR!}U#$!-N%USJ>hCje7_XwGls;FntZdxrCnM*ed;Qm$V+ z(gUM<$dPg!IM>6D^kCjUk)rMzAYjn`7VP{F7+T;@ZJbs1ZSw9HRq%zKl^Y1v?$=vT z$O5^|y>C#!@;4{?|HVM>8>l}t&>Xv&!oQw^@4x>)R&WQHnWet59TY?U+bj9cLGWKt z$@in>|0N|qq}RJ@{K(iZ5O9bDG}{0DP_01lV|D~R#-SNnICpI?d(2k$(LtG(RLizp)E23j45~Ii1F_e5e`!HD z55W0@yl@X*+J6f2(|-)H?rrvWx8ylUJr8`|!4VF&+>4R^FSg_Y?gU`FKf}%cm@@mb zcOl+Cn)xS@;C)*DM+N~Q{?16=zW0 z1Qo5_VjmPXT7Wnc9NN-mKc;j9g+NeYhT_d%o(N1dHiS?GfWSjRCUj<7XInd%Ie3rX zKkC12w(=XxeW0j^TpH&=MswJw9gH0)^glt-?ziFQZ^DINMg;#=co@d>cj~OX{CdF2 z{_m9Gt{rgV5XZQGFG1iqnD|e`vi%6}5K!&Dr?MH4{@8fK#l+`qV)rG*g)3=E7xNgnv}{kXsk!jOI?d;bFV{nzC`?t}F0kbVD) zl>ZKp&;MET{&V?{ot2#z^f~TT`BeW@32^t>`!E}0(A)&|Aw0c8&p~j#Z@#&I51Tsxiw+0d z2V)0j{(nE%K6sNueEd)K2e_kakSB+n(mso?9T4h}^*#X04s-Zm+CLA6Irl@2|5@X` zN4!4#w1%T)!>W?#Id6`sM(q`?qEBuPrjq@5Ix85f=X*4*V;={-+-Hn_2|NLG-lml6ekX z^ntJa|6hyXI;ejg1bWx@vB`ri|FU`d!PTZiPDR|(%nTG@50G|nw+jaD(?FN7e&J)- z!MpF4AZ(5Gz^#UVUxRcI>K%yV0fuuZLIfAa_6YRP9U^l57PQd^!eG36Ne|#OP$u{9 zeP@REz}Xz61Ak#=A6&xx2RGUN3*P4tO7nAHwkiNzpc`*{ZQ1{?{hNOn`0t7D|3%<` zNK+4d%V9-582i)E{hv7k{9Y-^`$XAivF@7I=pQwE0~x7x3z+rX^tVc-(?{Gul9D2#)} zW$RplnvEFjAfr`=TLNn-W53!!nj-BWAfMI;%K;k!i)1F|0?O-%~CB%$3zEx3&x3k zpo1@J3b%KGxFpmII$^)JQvKAqZ6PwfiyJgZ=1fx zLVPasW>gQvlXL^{Ej$1M6!d0PpOsfk4j;j!Uy-UKtn z;~qqUBZv?hgn*S(?&V&8X94z_Z1Cz11H-5!j{W!1l@~!#L=CXPLus&GC+9~eF$6ej>!kb- zIXZf9D#Ke;Z3Me#R041REy*r9Yf=fk+U)U9?qC=Y0rx*d_zw~O+azHW4?)Yi(>is& z>9a$(u|!8Tjbm>UNs?yYY(aJyx6srHfsq-l_T>n9gmkju-431H=ITyI(~mu~g>#`x z1&Xmix<3O&p-OSPOtq){U$udxZ&OVYFa=-3TkvhCSC6n1cIR)&&YjpPlkbKi8sWX#mTxN#^SwLac6*Tvn@ryHHBY6-g+miZue$&Tczh51VIW3`alF|+mO zYf8l?c;~JU+L-nuW3%U)J4l2+Jr-PVmCUi9wsdfr);C`=FQ)kvdUc?cCndtfRCtGT zeB&L@mVqW44ScR%btYnfrF7F|%f%u4boKf3D#a9Uz(IF_mL@&8uxIWLnTOzGNQ?f> ztUk_#ldelOH95L%3Z@8d*{i|@fxcI(hIZ;Y4O#FGD|+6D_T~Y zw!SN|vSDo5kgY0D>wqd)^`+pM2#`R}mG0#D22B~r3f|}xO`uiNFZLW7(zd!`-U6WtBAWtU@$2;TLXHVIY zEWESXVlt!MHCtF5P17@)j>aH8=Er!IN_ssSI3lmDNl&|%Yw}ynDBvUfc=$VbQr*k% zy}oQg>t57--41OjIT7fHy64W9_ByL!+K8s%#^>%F;|v;Pl?!dUW|mzhy0B4ecI#=j zOh$F}adPBiv*TAZfO%^>vug{1698X`)vL%YKT&)oRoik^qZgPGenPNfzlsi0&(IT4 z{YIr|hACpmM|ER*g&OSR-7;+uws1kXxofv|dq&^g*}3bQR*~6t*zI@V0hnz8`RZI8K0Q>fh06;A7VMn1R??rRYg$ z+YZ1T;50D_<0=M0XZd;F(R>K00cFnH;7x zYZR31%+1E)>~ohV3B(cy-Ybrfqd+8 z>&mK`0&ocds>;#8tp(!@0nwwH-DFx1W(qzIAA3ERy#BnN|G4o}#d`0r=fmvMU1`I0 zzP-DKTx=A~{u;CV&ayO@wGY4ZJwvq023Me?HPW-9nLN}#Yh zBu7_|qGF97c^1kxcjYZY1YPCMS?G)RJu)U6>-{9fo{_ne4E!~+HmxcP@~i2bvn54D zCO#prFN%NI6sMF&g;$7vOxg_%|6DYn$fxP4@l_<2oaS+&e>3gbDmIAc#DYj1p zND~h?KvUbPeT5VbkcbERXr)j}lXL>IVrLE>Cw1q!xs- zs9%>>%QgvlZrH5l7sHKa>SV?GdlC}NhAdfZ5a7}Ma)h!kNijJ^BIrDc0;6>Js0Xip z)p65qWFl^lU6{H>e&zP&qUx-B(HL~>3EmTJ-5b& zzZh#~8u*(URX(L4IY#U9{X()r;>)3nBeO#(>qK-y9-B_4P46GMhB;wp43+!!_}~$x zJoq5a`dB}ZzpC<%Kr2P^j!}g5<4BuYCI=8-b(VSK_FXLdj88kW{#Yp?+M~c$5F07U znqR?>@EXIXbsN4$DImqtkH#TAtz^A6zeO=w$zI0oDvRFO7g7YJwp+$D zJsG}vH_|$M5IGB29mV*g$Io(Be3X7?m}U4a6Nr1SXn$*>yr%nAGCacq`|0ui z$(DqmDBMh_AKtRDkn~5UB9bQy1i~%zm1EC_T0{oeUNR^ zmg2sFA-O+M|8~TS$m@1kF{ay80A4(mluWJAo+w}4aAQ%5l9BGTWTOh|-oQ_h?a65+ z-Jdz^b1nM1Ki^o#^`v!QdSM&ZgipD(HW8gmAIPUC5U{z7J>z?n*rsv*#;apZRXFZX zLWoG!5=RiZ{Wi|{QmTQoe(gY?+beloF=o6ZHEmgqLZ+lQet1d0<*aN^)ttUWhLS;r zN9}xin5ZZ!{U$TSDFyNn^AA4o?)#A^gyhH61nj3qds9r)ig_s2yxF#~WxQ`M`pPhBK$SeJXr#Vn)5NV5aZ@v8ZsVxYci{~h%?lvQ&|=aKM8x*Qf+C>n>$izpZ` zZ#^tP+*ir#c&^pZmq)2lAO!6fJ&8qO`T50F<2s$nrJ z?Rd8vehWVva|c^ZHRpM<6#sNemWH-9)0PY~9Z|#skS_?Sm$>EI8t6~HJ%$w8T57?7 zv4R3%G%eKgZQ_&9-LD?HvHtx--+=R4x!`ix9e8DARb+gO@--H#O8qe$I3CaB#8g{y z)kq+vw>1+Ycc zUXYj>iE~@1VI;ZXr4%|i96H?lK&63@eZg_F{L~=tfLjYV&;+$c3_BI_yv^4O7CUI$ zMnUCI71-8D-#ULuDK|dX?`5a@Elbuene2EA#ZV|ysl@-VTo2$Ozl8nW@glOhkwd>K z&&cYOs>ic)RFaLiVnPUTLXXH738t1!%Lt%HLp63Lgm-G%o{iPLz&b;K;A_!x&p_(v z{iMX|rKDjKdO2$*qF4T>SPJPgyyTZiQ4i;j&78MyeK5NsWytPN2WM#wZhRVs$Ne_a zaE#Xl`1!Yjvuy%UFe7s5N-#S}R*Jgvt!*b7`YdFbNvQCCV4v|47$gs7(JIPAXqWZ_ z`%k-ad@d`RY!$2Bs_wD}98byXx&{|v`Und)O#31U%Ldz8pD(EpoYrGiR{<_K8TYDJ zPHQ-RaH`oMO{@4+?L+`?|94EzaC6Dd_J#vW6raDE^sD~BRVymQ&UxhU8P|jpxQL~5 zjv=Rr)UY#wuNe>=0iL3&nd>BcIr{vJ@EiXKRO!N4U7>@uAU_|WW3M)N-H9%N0KU-E zV7h0$1{Pw8Vj@B~%Po9@9#Eq8HPgt=c|b|*s<#PjB*J7^KJ5=5J1GfW{Zuo9WG-!5 zWQKp6u}(WkGQA(hguqIbwVdOvgM%Dh(j8BbNnXR|$ME1p_g}bugH&NKW+*jtiQG$n z&QuFUsDdMU!*ALVh(#eo3|13x*l3bIY&ah~!DZMQ2VLcPiSBs}@)T*q9B^MV7!eyR z@;YaJ_Nh9yQachR3o{Qqm3Tp~W6D8%DtdLX_bQG)teO&*G0lvjkk*^5xrpt@JH)ph zDYrh}acN;mXQz?cY8gDr=XERkl5}{UU>sl93)GbHw)?RQK4rxqSHVXT_HoN5~47-JldqH}e|@q)e5m=ZZGZj9Hk z8O~GcvWim%y?nhAgM{g${FrXJq849Owd2o+sBk2(I2cb?Ul-&HkI@*zxr%Fxb)AtO zS2yBgJx%r!i_#81`Q^7LLbycBD|t75*qJxai+DTIh}WKsA#KnkW!3$Mp3h zsMMzApBFRLQnRYHLTao6f$;7DuCJ*tcUt%fQ+P`)w$cox;Q*JP8i(i?Z&|7PM-bna z26bQ;kKdP1X+4RlURmVCQR~7fd#E-Vr}iM=Df?*dr}Zf1VxM-qPpLe+Ihb4wJK-n+ z;!$Gf4y(lk0b|4f^=D_I zZI5YMt8a9LwQo(uV){2|yJYwi;RebX+Hmbn9qb`1_edhLsuS?GmljhUojo+f>1R3?g7!m=j0#?_aTD9pZl)ghc) z9`pBbdt^mzS>{q|dDPX0c6FrY51UQ*W`q!#&eeW1pAqEkhIRCsNE!-*l8D~D+jn6e z@=ehO*%#o_p)Zpp_A(B+c#(TC6uBW|iCD}e2uDiOr0Z{u(G|^Pl(ysbZ}VMYT!?{; z^~L25Z2`wf{}Z*qz0QSZP{yS{#qx`GFORquIr9@-I_LePWVVp|xX6;#+8zw%H9kV_ z5odd>sb{igR(L?sn2CU}QH=$_7rHcawM?TCJvso~s8;g)@!q%ePC|BNhF_07DQV8z zIaV910$6zpb$YL}034w*O+M|s*5xq$P0*~W9QH)p^6D+%dn-chQ6lE|^oJ zi>as2?VNF@Re2`QmK|Lh4og-_%PNqtOBb*mo&ng-IZnM4X;<6SZ{h3dn!Mk&HolLv z%|^17Y_^Bz%osKb3pNMBRXRkcjalAx3({|lN-521<;5}laJaJgPDI7nQvnr@A-{~Z zpN8J|el23^!!c>i6l{a%)%MP!poYKoYL?;J^^LGsnnw^dN=U2a_){ic?Q*VjLn1F1 zwughz^|r1(-7vN;$8)@@{(X+NgX^C&LmbSKXL&rUMwGI|+dM_5Tl6h6$O3yDENv36 zRCm?hZZyxWrbx)H6;0^=XwMb#O!9Mv;39IoeQ+>59~G|rPGlO8EQ3s)da|EQbL)tD ziH?u?s*66!{bj^Dt2jf>#YI|sN~NwKbVMGXo!iBW{tv_i9%!ZM9pWR+ZY$YxdoY|+J!XuBzj#XEEPf2gq;G5rv* z4egwn)cWAb15cUbi{V%U0d1&p{@PE1OB-g7(&+KB@x0o`))A+ zyKH6H;xz(ZnROM-lc@DX^)ODbf4V!n5}l%9ioU**O*;NOD-t90#e_zM+o*JkBp)5s zzpir5tvsGYO}S`C!=e|jQAN-4BWJ1q?a=-NJj7(1Hewg{h!YtGNj+JIl%>HFoU8QX z*GyAo76@ggLEaH^K~RBrL4NRqa${z9z{co`irn^jcwa(m6ptG!Cw_W{&D>q7;ci!* zc1E~gPWE<(L-t~W1v+ATYdSYW*;eLw;5c$!mNXC#!H0O)Q5s@P*OP<0*uYm9hTHy_ z*kt0Ssg}7MTksTGa9NBwxWMgm1v&;WdIp=ZYa=TPxiE&Y^~`nowjLq2`Bb$sA|55e zT=$B|Wy)HVj1C@<8WEEnLw|2>AEPKBKgNR0=0vxJ9NV8keYvHnKY6-PPn)t+sd#?DLqe7%Pp1|fdaFT3IZ&+brOsUKyQ1!^$Be+VTDKgRve-)38^R;pUi1ufr_Ag6w0pT< zJA%NLeDdYR9`NEuapx>jT+2TAYa4#VvBEmmLbHyyXSobjT0TmT2r=+JfNyQB4D=}q zKVoVc9;Z61!_*QR;+y+*-U}P|)JqUJ+N4<^)Uszl%9PO}E8NFtb)^ed@#JLwk6L@` zUd?1dpv(MD%kfldjsT#4m#gy@p}v!C9nt z)rE4;IxLs`zlKl*B=Ywb#kFmDP#oz1t^x(rxJy+wVa-$#|&m-T_Zeg^>LiKV-xYfj!2J~5@ z2;GDTo2Rw|M@gvRj8RVS?a|$BpXElX0wT$(`=VLYkm(?u?aA{DDGn;*vTpIvvbL>8 zOR^Ok*iW}-KO&-3dqha_eA<+6$xkKE^tFH-Q?H;T^*LS(Cx_(w}oLL1Bxjs^V;s`1znKIzGIJj{RG@rtz2g^s%J`fw$iY-_+on#>$v$L>|r9> zvp>IySvl2iB~obNE4|VOabjglWWlGfh?l~%lY*N+%F(fY=QBx#H&J5`n@c@C9UDzj z=0&L^mg@NE#O-K=JvJR=n19GdSQgDct~EOGX%Uzj*6x;Yv)e?<+DWm? zU&WVazOb4TQrZbwW+g0tJv~tftM1a0dpp2x%mOEt&mm9VGo3LaAlWOJPPIkVyhO2; ztbP%t#DFw$%;dh$={@0O}1=U^XXgS@P@d5XJqwr4eC7B3#Tau#fibrO| zncxdNSfLvNr2L~N1O~luHC%i7iN1P38Pr36`m{XyNF}T{1^G#j3(c@ch|lrx<#_^- zi~1T)*3RZ)P{3KPD(oxiH$1o9@UyVib^T}z0S3{Z+6YuB3$U_Pl+GRASCE};+)_2^ z8zuEq`V8h9?||JF!()(kb!@$L154H~8-4b{JDtpmwNZvkitMp0?NiG!o3uL;*Hk%& ztfHb7aax{gLj$17!5pV?$=9E7XF=!sW1$N4R^cb%lINrVT>V=tQNExfYC5zK^1Uaq z-tv7${Gzj{>Gd|{o;{rR{t3L7IEWBtWd~Q{Afa_QC2qqxuj@9WckmPQjJ?iR?r>S? z`;pL?0rKQ$;Og;Zh@73ne%thP0%@aI)0=M_$weSic_pf)wpo^1T!f@duaO~@odXx~ zEu7mn_)cs9w`qGP$d3g?$#}`CU#)y+W0$~gZNkbu<;V$W8M{205Z&;IK0?ha(joDg zyjeao`M{%V{s+AP9h8hO?_$SLltl=-=9r$#(}wczn_KacVXP!>*y4n9!#8nbMJ~9S zzCGr&(&rdCA{hyPqA#uclNV;dbH|0*3&lJmSiy~ZTJ?HutQa{+cL2emQen#~Md~EF*TS=$)X$vMl{-HB2C>M~js&8P>=8NOsSPd~bE|132_=2y> zR`MG%Axp6`8ih8@qO2uALX({k;K)uUA|3td8IMYm+DECk8gR`5yF^<}CJ2D>Mcsj$ z_ZQ{kTG%ZRTCI1RrsdOGzwx#ne1`)f%;9IL(rN5XUfaCAR${FMUha0Dv-uO-@wxbj z{tFUKRrv0>?*Sgv)VuQ5sZ5g+DNch~hrOgY(Rxu8<)xUgDK7gYhFb?$acI9sp@fi} zO3fI1wd@76c1e+`6%f+d6Z8>xbxtz230&yd;Trs!snL5otu(ff>~zBAjYs-lS- z@XF;Bx%j6&uWIE~bl#FV*M%_WYEB5kVN9HO$}hGMSFw+ZgKz$3JvrumHoe1@&jg$> zdet09(w~HF3#|_Nrm||>jnIuS48@10nhF#VTCHRkm>*dXh$6 zHfDUx;4K@cSEWuU!Z@5;GXgN$DUNFD5t+O(cDhh}S5$2wmUjHTkch&2W}7swG}gEP zfBzm)BStFN%3pgmtCAxSU(IuS%?Q8#g>t`>@COnY1DC1$p6o(eonAfs?3M zF>?Sf=jqr#CNYex`>F7&9ca6+(K41T>|w(_mMSOqc1i&M9aM8rH&l(;#jAx%ICkaS(LqD$S9+!v)@`lx}a)pOl6w!`uU#tk2Um4-|LYgtiVO^Rf;fM ztxuy^ z(+MC4GDm=)>IIU@95GB8Y(7Qbz%N;at)(}jF!psiuzB&pU72K`_R;TeQq+!c*T`|c zS%zv_I)PHR8TM*g{#Sy@;nK*a^cz9v>IgFP0B}4$NQa48U-5q&&$d=sv!D~9S*95O z9n{fIN9N!qs@|7B(e`Drfg&u*NO()Lt-#J?Y_?Ld>!VjFzUjq7EkolkIH)B;^KnvU z-d5(1dVP?(>eJq8poj{miX1V&jiO4E8*&TWEXkdv+nD1@>s*j+?{qfGb-+@eE=wAk zx&QM0Y2>B5cNFRO&dCINh{8D&efv(-*{Dv{ztjkM4@T7Nx=+U$ikgZl5H$*HZ+fh? z%l|A>$zsjH}w@sade_^-r!hir21wnO=jJdS; z?S>Oc5l%WwIJXVS%p@X6+F{WfA&a8wY`x6BmpDF&^@>px6C;ef4^k__%D@jyqNdb8 zJz9O?w6O7|&XOM=6OcP#+rUg>_Mx1F&^m3AR1+0mD(}~%8>H@F| z#$kdA+BY*s;8#w5^8avM@Dw{9Vfa9ha!TLPbbb;uba)$e*@Emxa#7Qd269`w^;rX` z@;XzK?LvhGs-@U>eApiP+>}mtiG}Mi1wY>`nQwQ)Pv0E*Y}%RDcoI3qwNLd!tr<|o zbNwYY_vfh>@8_9=XEt4aP+_KRk090~4l(`bJ~7{r5(6=?K?3~gl~UbOAqiAcX+SIDwE7tKpB`Vi#J?hl=peZ1n4(d;fjsgE2u-&&)O$IdFQEt(lyaK%loN-eunLQ%9guxyJEm$&Sj5Ky%qk&OHyK{mSiad90O@73xYm)%CWuTZC6SE%(eF9IrUU)d?8BIN{=6RpI_ z9&dgefhO}+XT1-FQYV8fz)-V>lJzJX@Dx+njmD$pSlplGu4*(rWGPK700gH>wN8QW z;caD7pxuTJPY&uDc%)a|q|h02DUfyYWHgR$gXQQlzvlHQJwM)*cdwzU{!bsS>}O}> zpw2BF+i7wSs-1Hm{c;>^!1<=h;HF3Mv~4Hu#)z!CjVvu|J;Vu}K;;9Qk^ze7CU$qc z_aC>uRvG3PQm+&PH8Qq*HqeZwhktu>AvSPVZZaXlw8yE@5c_~PqBFSQs^6&_^f$`Cb?E&Bsec?2uS+8JzfZZkN|rf$oOiu2E8MNdqsm#s78u*b&6rw_CR$;WZrR zyPvj8{I@CK*H>A|C3rGmk3qSYir55dTmpUbTF?n*tYZ!!Z1C%TpOjB~*~d%FIAln} z+u@pw^l6Qg&50qA)+V+qjzHMX;!h<)GE65AH6Px))E0CfG!78o4(H^#BWhapk*6`x z+MPu5NkS?2K%`J_97cTFYI$jfT&#GPXLr2sLyZHlZgM*nK%&Rowr@}7#&B~jsGzi* zIwo%XK$T;vN#YS8#GH*Lq_{$kyjQ&6dhqK;43mp-^5E3h+el@4u9Ei0b^{~oxih_; z2uhZ$Wk(tB-QMji1!o=f1kB^6iW4D(S}X6HaWAt0fuSO|Sh$L>W|~VK&0KZPvgid- zdelbu``bkR`+h-=jvYLQ`-%|nB{BGrb)oJv`a=wNUjAK}fiq3TXntB<7+Wr=hd1)4 z^JPFyt-IW8P6Q;6oJvNgK=#_6iB!Q458-`JqT9!RVrh`AbhG)q=ce^US?E>O=FiM0 z>Y^3*R0?#E9KcnoP)kj6OEjiI;^s6cE*cA>=M&q=jZ9JE__P+veBQ zDS_sy-mZa$8|b{5(@aFJ(U+0y3@$^DD5=Y2qJ;!ketZPghZ{tS3SoN+L>B^xAfK4i zUF!m35zD=5C;r9b6Y4rEuhZn}JwzseFMD;|V6E6T3?E9O95QlcJvwq$XdxYI-}Z)YE2p zYdtp5q~$QQtvw~^`+HiCPIn1Sz`0F;*nYg#G2xUzI=xO!EVEzRcmg){`Sj5-P6Qi> z*XjFw#Y%9z8@YcbHqOh?wlDL?(h5!OHuTc5fH!aXsgUZM5;%NU z_}bFSx!mREsB(0z=-mTqsmd`ci!PH;%OliYMiCnt+3AGMY#xrVJ`xhnww+McOBFK-?3=qp{6?0EI|!BOFV$83y=~9fSMv(1#GBL+j-u3 z^knjb507n)1rwG5eu6Yj&98zdOTFdfF=@SQ+VU}A!=|s;)iD|5l~D5x)T*@KK4aNY z1K9md%Vm-QzoSBg1|WXf0P(B`#&CGbU#WD!xUaxId3mO*g>N(2tSfWYne=O-FP~D1 zimo56N1oskN(=+Km-su9>?WJ59ufrGO~!{&&F%n!FvrCwv17eDr{%uf=1|X3-3eM5 z3>yVkBDmqGvXZs&a}#nvQyP_0HTX9`qe+TFqFk!B)QQ1<4rHpt45z^eeI%+a)OQ=Fxl zDg^au%^Q3rd7(?WdX-Px({;tlPhPy#EfNN>ov+@)b0}WV`Sr5AH=MAiE$y^oDIRXi zZORs76-CaA8q`I$<8O@$lB}z&zvo9GGz%Sg0A9FabPvLRHdp6QPrFwcgO(}H^Hv$^ zIcCQCRnId{G2E-5u5LXiNn0fybY8HRk1?n<*JXJM9nlVo>7SQf0lJwQ*^W@3==I-z zR}7NtstwoK`~;|5$=v}of{kACT@~an9e!%Q5?^f+?Z%an0dM+=_wlOKf`H8!Mfcd^ z*Ejk%f*Z3MuGg*h-dL>XVx5J$y8>Pn3E|glu}L&h&8@C92p7O^LUd0a0WCgNnT zYnG0wBSiqHD+{Vdi4NykkC=T8zF_h8VmiT-e&>lulH;peNaGeWkSXs>y%{jZqcWZY zJwY6^TLFrtv}$WVk-E(@oJZmGVx6R$Il%6)3EYp6d`}oK76jbal)^e;AzasLo$E#B zWnbonO>*-InbQQn-MeeXFE_ZbM%dtPH4I^A^w0cQ?wAKfLV;s%uiGc#Mlz=rHGgJ% zbz~_~yVN6eNnGUlZQR`xbd>kn%8>r)DXjgaCzfo~=0 zY0{Bu?!La10s2MCvZYDhM#KbZiArKUCBUYmO&~>SfYv+fGPM*B_QzJWXBjIhH>3iC zJul&V@#zFvf9=$N>0N~7h9sMIkD=gwy~3=RG)fod@tm5UbDZx|pvpQszi9NQR|H2i z9LqRtoY|wv2G@aibbQ4wyuJFt9e{E?Mh(=30Bh1Ld2^gj8P0DzF2!4-LLg$HpDkNb zQ@y#i*jGWI`u)~N%U z7vH%a?I1QX1F)I{IGI51^DkkZ5j86Vo&)YRD-lX%AKlg#8pg1PvBV-cK|{sYD6z^g zV>Hmb<=epU>%A`G;h!9=d~o!M*BwF~oF#004|pGFgz61* zZyfqEhWAv4e~f(MIPT?sPFR_j@P`XAGVi?Jl-|0TTuOq(dk%G*tPqk=&5xjP%tZv< zWAF3oIImA86l!4K&U4xJ+4#1I6`Mf040_#a0K#to6w*HCF8@S?ZN!MQ`zX%p5+Ukg zIq|9s9@_ib)E8JBd#snoD7TU@RwC%4E0`~j^Hx^j)C9GPUcqE3&KP{M3sM$X%1BZv zaaUS+Wj>x6)AQSUpV2|wfla)jLf?r1q%@O}DnuL78`bfCn&Z^HL3H64J*m@l1I z`6wgo-41&Fx&xRAtvLzGj2M(QX5{f~KvyZc|H2NODqmLMl-eY-{@aMb)|bjc${9lV zBJO9N#&923m3w{`N(lAk5(Dpeqpk$|qox?dIwmgiT>Ze05NW#07&+QY0{}^pSzz~i z6zjtrk>f-wz@xs~aP+#Ee$2oL1^TLju2T~JIO4R1Gb_rxL1wMVl;>F{e*;x3r$y&= zD%pcn4g09ZU7fF`I~43Aj$YU5?$STQN94gpnD5WB$m2crdhv|4;42H+(X!&3J61SN zLGkr@%~zY2K%drf2X-rNE8jaU>?d&2yjUR(#e1(VNk`=H#qqr;Q@n`8c>-qYE>qH- z{(kh~jT3lYU187O9lMI-s-;Vf(zY3=h-p(NL2r>%zwO1!%vkph`d~O$D7Gyj%0HQg00HOM zt2mZBdiIlnF{gfHo^_J-v!)7Ljl?>EH~u;L*^POli(cxopD7r3)e2Y0I(bjlc z`tBq@MfP~QpTSum5;YY$70aFp#aa%ds>QEyM3v}X0lQeZvrb(ivhe5>qr{jeVMTXK zH)uM|H3(xv^BIY}S6+SDXd@mPwlH?K`k9X;(V2NJNk4BTx?_WQ%_<*jPTj`@xBz%^ zfg$?kG2}3o4I%S#Mbf|=@)Tw2xj;5NWt)jeM~AX{Y#uFID|~Mqy4pD;&Vw67A`etD ziJoM7k~@AQ?Vcf9#>_&{t%a(gf&W7#Pnxoy%rkOBZ%S1Jv=F9TB1B-3x-*_8{6Tzw z$1s&?Apt4JT!~ zhn2Kvp#9r(q(7$~F>af^;tCtqw9bzA`+^Y35lI%74`FH|FHJ! ztg9)x7a^v>6G4wfv^pxu?>Ro;_MqCmf%F4R%-^_CRNM6u7_kI-~uO z%v%YwJ%p2)(B`XDf~rm$AVu(5df}m}b+wAho8>VYID=O!Va6=8G#NOfBFw=!og72n z^7R{K+<}+so~+H;UqrrVeMRqeDwU}&h+Y!(ja?qL!?`gdZLok<%;$Cal-{tlS`CE- zhqE3(PbyX2-8Ct!Op$Z0YTg`PuQjp~C@8}jhOg3IO1tXKz_UY8(;uZ|heO_#T$4B7 zTcxt4Q-sO|S#MJS!vfYSZVUC5+c&PN;+I&xczYEquZ>!ML z)l}8gapaP;8YVH}X#A^dw=JUr9L9+CaaM29SK+N^#C5+r;g5%SUZ;X)#6gUD2_j!4 z;BR;aF7rQGc{pRY6D_-YDRCv9dDWZ(Q>al)pX%}wo z!c7sca$7!s@=j4noj|raK&PFH+U;BT9M-|d8*yl`&S+Pt9wj_cO@zpEyxOuP0}$Sj zsEVX$-0&h-HEa@{=Yo$bp5aPeCC7{|!1{YipS3)F=GbGNn~xigMLy{3`wB~O@Z2X{ zCF_OvqRd_d><<{NZ-oNf+(^}i7=^8n*Ux7rA}bmbvi_Ccz3T1JU@yD%V;UI|VHhil zt^~>R-i`~>(KW(4jhuQU*b9_kUgx>Gi&(Cgn}{c_rFpP-iEJmnyL)W5BA$f=2Ul&9 zt$`Cus_=%SmQ^)VM!%6WyQEGH6MOxwBRUNWvnnHeZ0=9It#OZyU>5kX>OY7wzrud* zY3al(vps{3+!z|=fAl%E2XU07ie?W3#}Vux7~<&+UF@DYpzXq>w;aOR1HEVh73Oe$b5U1}!_r?Kw{H-V=NdgrFnjQVWf#+aoSV_?uV?I zr&{!8UA^;|vB#DO=Va>K!8ZJq)_zx&cYz&hg)Qox*~(F-pfc-`&`sQ<9-Um+i5DrG zl@R6r&7uJI9HFsP+~fJ4%w&yTiBdS-%O6T+dzpff06*W#k~#Id>n$d}@R^Q)++%7Z ziuW2BAjiY0pgCj%e`Yr>HDpxeIf;|R8lxppbX1g-7u4ceoZGmorpP$$?ArsJb~ z0)#ucf{uTC)P5Ad19?=sA%mDXVVv3~15Nb|>JWM$mgdkf9VBdCvt}#1;!5{=Jy7Vq z2P<+x%5QO_C#jNc)G$`&1BM6Fe-7a!F1zt8ueqi;1mdQg zf-Yw}Pl$I+RPZ`<;nvv5M<8M-NN9fwim0t^ZdW*+3d0WNKN}XG_ErPSZZ7x(-O{TX z#?T%c^S{SJ%p=}Tzr|clCU2r{%Q8XC%wn2)7w3i=)TFkdvV|&`6LM9p%Mt9oAhT^# zCmqJ$k=-wff2Pib{@DbwgmanZ9QXQN*Tpe&i5dA%bMINrXS}9D>S;+mdF@8&F@06i z4h^a-=w1un?gczD+?cqVUnK!`-A2ki-ANKYxFnFeGJdU6eirp|ucgNTx=Z!=X_D9h ze3H480Y?!YWBsPuE$M9dMd2L(I>9^47r`9a#Nru$>$J|~mi|5xHPWQwQm7qMJ>$FQ z3JI&)LI!Sw`kdPhe7BvSO9oiB=-i(O$B{^|IL&D4>#j;`9u#tFmN{ueYe-i4`I zea|K|qGq4@;R~tca2m;)37dLW&08cc1fR?83rg4}yZ^*vF^!@YKLDT&uTK&~7?y}G zgj*?z7PH~)R|8a6;T|ZLMwT3xlLx&3xFhJbuz}2usB@9F?&V6R?(J zYt;Ipa+X;&&CUqso7TWI&a_KIB0oN_bRECOq(yGR@(6|L4jv-TANJXEb3UP%bBI-7 zDOgSQO}>@ADoQQSZE`*0%Va|CF7kv2E~TlRXj=*-zZ?TFDjdQvhO{w!#5>*{GjzdH zMm()Yxa|pfhQg&U4i4yL$4>X$m8=BDqEJ`aX-4Lbf)-EVRjYW#%em2g_NHtCsjBn| z!}PL6a4`$lixU-JSsYC2KJxqVEj#*Mj?* z29Sf~l?N5Qzcfp!f8*=6;VkQT?L|+~Ine*MpxyEP`^8aDA|^P?%;nY%IXY~hY6MT> zCCKE;JjbMOvRxV)I_KAGsh+cGl1o~6i6A@i>3aw%c6*eCUXK8=T!%&8&`|)IRXOO{ znAfrv&b&-7%ZLdnkMh{ras;T4_!s-rOOL(^U2JC5Tb?}?zjbRwmRya@pG8a1>ytMw zK0wf)^)mOOodKGm)|CmP(RdWUnmv)K(C~23qtEGC47XOi+)6|Yx4l|21CtKG41C_- z*O_jQ*jSdCH59YRYn8da{pmgYCzHtfFFQZVgB(<{8ZfQpzI{v;S3ZN%r5cjIc4^uc zTqA>nJ7t;RYD85x(pVql*w!6&R=JETIjkz_WwW5|#c_bK5xRDR#y4d90o}yXp$t2n zho_XUS4oQSY6`v}1~tuD&zX0of96Mkj-}jPbjy9|K@R|-Y;nQuw#ck_T?uv2(gAgg z<@rFZFA)Be|0-Zjz;j6G0d)%08Md{)+-J|Xgr_pP2D;h!t10hbcBDM9&Ub%|0C3CE zV-I!?+Rvuh(jD7XjmCKRO!ZZy{+fy>Y6+C`ofE5&Lx_Q7WL#F$S3pt{! z1VOpLhO+!6gXDHRugp&!(^j>cT}IL7mc`4VpvR}KEkL{?2i)XRDRe-at^OFAZOpiL z5xLMyA9Q1QJxV(gwBdjS=PNBZKY$iFnGS$0^80b9X@4qI$= z@Q*C##c|a{x%lHO-V;t6qs9ZE7NSfV@42%r1Ku^x*rw*QY4v&66hUzJMybfj8dnXU zn92ZT^3l(NR#NkZ2`4(MsE8ONtbCyBbMRNqnJ~%ew&bvlE?c#;D}pXd=}?~=xKT9` zrCRJ_uaFSp_;n1Vv{O?~KR)Bz=3r*VhKIPy3A&^%9b86xzeTE!WdaJ8bOeMKT%n4S zY^r=$%d^xo5sShZ1LzD6+}^Nv3L$BwU2yxL?}H>Z1v`P;i6%;Dayek2FW^ZH+Rv?1 zr{V$lT?lm1k$t-GCTKlUiH=Zb?AZeFb!k^sFyW zqd$EJwDBsR^SX_-0<{rA-GN&(enK(!0EPQM?7d}Fm0h?lyy%jUP6?$Oqy-i&-6>sy z7=Y3pN_Q(It+0s2Lg|u51!)kFl- zh<5-f#gOMW0}z%u5w~?cL)KiBOq5pW1{jy;B&-^UC!?QQw)^P=Kn|2{&SP`p$NBM= z(=U*lZpl=YMz}uafOhXV;}e2(GM30RY<--DZjItCib*TJ;Wi}wUyR!oUBAww&(F8c z370zXU;tj|TIsV8!CHTM@UdFASc9OWrxS$s8*{f#<%=EsP-;PpquSZac*SZ6rA{K) zJMOLU<0?*>=%GrY9obtT#qM5LYE+enB!~I2Y&V^li^#Oi)Ta+! zc$vUjw-(ByCBM=L~ zpvydnc&F5MRfwO-1r1il#LZp0$?$Z<3rj(buj(cV$1p*Odx#aca=Ev-z;A_ex&>19 z+F0-DO@36%M-UUNgMb-r1@(K5^sl<7{!L1;v}>7a+XaP?O{nl-+OWx)+OS z4has7OL^IuC9*+N{BguR%djL&&lGmuE)n$2s#)Bdbd59YrI!w8SSTLH8|C2SU!M|T=>j4<9-#halao0JF^&0*gYO)S;-CH4Yj1P1nhtS(q$t6H zUGi>!y|kjVk@_ja*{N}dr_EG-vt>=t6i(_9oH^&0b7+Y z*jHV9e!bj=Me7{+?!G1bH7cc`F$um&hOL#dSm!%zYkEPO>|Sh^h{pCMNN!FqfYJ0$ z>isul42z`abY+c(nQffp-pw!279avr$3OirQ6P0lhfii zI|RpK);Jhv0!ha05-`cOiZchPtq--Pq=Y6eD8?T*YT}%5DdlB1KrLxAlf!a^lUBH+ zdUFz)Aw~nqnAIDqVlty+jU49Zsp7**xhdCZBMF^R^la8tLaM$&&{?~HJgoCsA3(5M zg=m{ThTNG@RGK~6z|V!>`x!;&X3o&~*efYjnpR{eSbml%t=tKzlwXs^Fnq(ZQwI`t;V?y{=53u9vQ%KfiUL_b1!b?CdDrL%`+fTTduxH6iI$t(4Yl;x?(i z-N6RO8DIsgnL=WtU#1e!6VkPKw?BMYMXsMbt0F#+Qw_9~#2zTY-TK9_IEIOdW{3q5-xO|7jC zJ=3U&iV)#?&aXkO^(H^esn1;9@-8_-AVNl36pB-c>g+rYdDt@B7^kb|yBQ?!!$K0s zLeR>jk-H0s*=`IE?*y9Asm7sMKse1}ni1(6VVWV`2uBch&z9?&s z7difg`Vms~`9+#tPpfE{c7k9aeerRkDo=0qmC;}yPUBK^Rh#s6yT8TG91nqjtSSRP zIf7WVtg2POq3ga)P6TxqrOQQ@0pjrjI>Rzm*Ig`0g_kB73?SbSBKH36^t`noc}WQK zp6Ez435%0J6M#8Lep$E3MOq6EI$T9u+d^>m?H0^5NQLnp`;EYHQVI+lXE1RMH&l0DQuCz2j|#8 zHDHCPCM_qqRmEL$oqL@N8bh8ZY6rw`%xyn{q+I>jlqrd zcMUx~g7fE@Uwhwp1HcVb8{m7mRowJHlZFFm*+<3%4GfOa=XR>Ie&Q>Yv6917Z>BVm zz^(hNx!7-4AWQ_)^WT*S&a6I^Amy8M7?O})o{sQnS}Rg1%{Nj&yp`_Q!6ApotL>v< z|7OFqfOv%RDu^F&m@sp3HK=|+p}L+YHQ07uif5r4(K}so_QPhy^f`fdJ+c9Z{`8Tg z*G$NIMHGpzn0oq!dfgp>ATW>k{2@ScB`$;0y(CRHDoKBWwcqgvEq3Zx9W5Bu%5+9w zM9+15jZ$V=RJMXXF7?a2J-+OTif{VrAGU4ss)`l>h@V5xfJSHT2F$?|HULDzg3&KQ zo%8{&;vjze6JTh4hqnE^0kyapA?Cn!;7-0|OyLyLODt~X{ye>~jZ4R836)I&sdhp8 zua!W&U@BH(d$pWro}n<9Jm4#mLgLcGVMxH7Ul~XJkSmfT!^ZL3hr!tzi67@gcqT{? zz_!Zr_o+M%3_ALV4!LVlJx*#wQC?g`$J>vOF<>8bOtu~d(Sie?8gmVamDD&28UB6%)Q=jRy=(p>a}m{vBU0B?7G52U8>`D`|`Z|-Z9F45C$Iwe(TWD;g^V{4Sw4xI6NPtJbyAW1Q zjd>r6nZ40sFTY-uufkmx6-#xCV;dygLFDwa^J_%= z?A0eg!7-~tl4crqUd^=zZGRsE_zynKt1Gd4$F9qLbq&t!poad^BV~wwe>=;d@#&<1 z;ffNypDkckyfP$2**}@}sc4|__>rf8sYUO#l(6mbU}qfAy+C1q`(zql)gnXGGFrPf zC)H?>ksOf?qJ(YS0w6&#$pa!gWYyV+0-usIfw{uvfy;uthk)Q>XfMWggIT3zTT54% zA?pb~+ElcDwvDgrz#lOBxs1l(y$UH8dd@Ruq{>GBYlANKMcOTww6(j>1x|Wh$2XB` z98)Zq=jv^@fA7@pq-4Id*eWxwjy#v9Q7~x9t?4Py@6?(51vak`$Iu7JV7>QRlmSfT z^{Y4UKMfymR}=cxK_hKxo>z=e~ajB^*LbD-1<(*qUkh>;|F}8P3>& zOtF`=P}E3G$s;|UOmA%<2M47-LhF)ybF0d6xTubI^pd6rf_gIjQqu_#Z!Yq_Q@GB} z!~1yzEpKH(@TM>vP7fT5vwk;kqD=+LmDQKm{ieo>YNd?d0}zdRQ6y}`#tXKB6b1`K zLm+Fm<1Enop1YPtK=KL9{>+Y-$d1 z-wp#Xj88{v!`*G%Vs&dp@22mygABpyb++AR;Bm&|Y)1etOCRpvF%fX&a~Nb0IqnrC zA%#o>^^uuVn|3r$xrWQ!lwK?rnZToO??f7yKdrih5cBzXlhGoj1E#p+JCBS^%Y{Jy zPFE8oWL_i{G79nq-6%WwBGYqHg1+wIS+)D?!yr7|?gAN^M|Yy{tg3Sbe!%*D2O)49 zHTQeA_a(Mc(1ph(j&KxEm!L-iP7-LFoxg_MJ$k$IgTYxuq^=&&G7Z532fM3MaO zP@28et9^_V-u^o!sN!oJqK**uxp29zI|JXdBqT&)crOA;ETKsCjWU4Q83Xb{TkYTQ zOprn63S}yrc6;5+#+FxWIvYcUQ6Yk+Ot=<3DEthhY)k#(<+Qu6r2^5*rvaX2`k?g@ z5ZBlO)J2auQdl`M2Kt=TlmlwqVLpUdq$@-vyAVDDuG&h`%2xE(%VhwQ6BpG+2m{y_ z7k*a{uFBsn(xWd;K)nx2@;Rn?{(8P^em^gczTgr_rwpbtSCa94nT+6*!7GZX>->~}He!>xiO4cAIc(Jnk#AkScUX`hbMd4zwfZH9oIwJfI=9s<<} zDuqEo)lI${QP^TZn7RSaOjE|gGzC?Kt&7@*kDlne8(34%H&7L z9uy_{M`{Wlge!?N+0epo6b2kjEp|)-wR7ZL6?e_--4bNnp z&IO1*kpu+k;_|R)P+N3Ns&2?|#z#2G_u`ot3q&rev~i zQFxlL3nqJQOyD6%@qG$0@QA40Hx^hRpU*%p}x~a04!^V_fH` z)K+SSPJay*^T9~Lh;q`oXz?c9%*mX-hC^v-2RqYT`o+L&K`EDQNrpq~r4@%o${8=h zupycduF-BsjBAh~^6~qDi*+X~gFgzd9*Nf+&IIG_yrq5#fjM;5E(~yWuc(v)S)E5L zyli(6@O$rWW<5>zGi)?#b4R7?j~;_MgEeprM?roZ_BBdLbj{1<{s$KI z#>BV4juCf&zu z=Rrw(+Tgflfn}k6pE;mC6i0ibT?TD>mEMQbMQ&0lsybX3vkZl`%GxT9B^MKWkYxas ztJd7Vm`sG+p=f6l$Bvg98YxGE14HyKL7*!1KU#oD6we(7oWQo;LZ0XDu<;Vc~rOnmSlAyJH&!*Sfe6UZzD3{Fn%Oolf z3SU z0!QdO_pV~J!69;DGD;05XaI?^Qc z(W(ZwcFS9qgwEPSF}A830qn5r`2*LI1Zn%j6N+QuB)oH620TyW zTLJzr1jzdmQfCx>vv9=l&5)y5rOA{H3V|9|JHzb zVjsz-FUdn*3ooYI9uI~DkL78y6ca3Rz>9U5PjM?NXrRlMWdJAmMeK6cuf8o#$~!c8 ztkPb?B@CH6XB#G;%Khc()STt-&fDiE^+ zU0nR9>^BeMOX}DM?0vV8qLhpgx3opJn*%b<0uGvv4^k~&=Kp4h47zHVJZj>-rL9T& z1P)gJ?+ROBa=x{A{3WCjA(cnx`!kpbs(@J{V&(04zxe6-*>b>O{lWLn&Cff(Lu-|A zn~*$^{L(ab)@yS6r>kavil$m%k6{W4MsnT-|FE|;LHqSVV%u-3oaR;BvzhaTEz?_R zH4R5QZvJzN27w9ye|Hp6zuxgHkIH84<7far?s#k&P`H@c>&+?xl;K_xuJTv&Jeu2y z%O-cqjXr=7t9fS+V%X!H!&Ur=C7%muBFuR7)yO5hmXN5s4&Cs_eH8vq*S=2CZnn{@ z{6=lgSqN`@GIu7LN^s#xmxZAz?`6w#^NZdwzFEpV$ux&+yy4W@7=YSz@)ciWXOAZZ z9am1!P9cQ`E!f5O*6r+m&TKebf|Em=qrI7bzSn2HwjXhxEf@TeTLaSH?w5PrKaqZ| zS)Nx)XB5RFkm-E}q$+DjG(_8w6+=+NGByonrm5AzfFYgg4OYwZ#W-nd)kQHJ8g7W+ zwt39w(+!RuiT{%~y6qwL-0uZ-R(0GFDvj%+9Y%>vg>5A2Bql8L^a5bGS7zU@o2jDB zC36`I=nlQTedP%t+@OkQCG4?nx^f6GSmtA&Us!m!VQIMmIPV0gj9MdO#|Dpm0O0<{)#$j0g^gq`>$4y_xY}^3%BkRj$CxwNm=Zo?3 zETCBUa$8V7L&~qdzrX!8-piw9SmS3P z#zbmhE}O0Z4E^)88>GUd^XIhyPz27>$dd4IznTJ*u$lStJAb*^LJKP>Hh)G+TL=TW z1}Bgsrop>88we0sILO%60OXh~l$xA>MDc^xHvy%?s$tV-#Qg*$(4ZJe0vK=s=TAc`&59hN;5rG);FAOl*RbG$>e z%2v|nE?ZMIFwGn(0{^oab&(lcq}GS?GC<$54XOlO23#Nie3AA0lIHVyA7{lYFKdA| zi%X3Suz$88Bw;jKwrfXVN}qzVVAL7G9KGrn5L%1vK5h?=2uFhZgFm&%ri$EvGOqi$ znMWNz>eKQ^pT9c>U4ujg;+^x{02f`cShB_4Cue2v9!0IL#jMh*>qE%>9RKh!`SXr0@!oY$ZTOM2Q%URvgEtInlCF8 zbEP!KduASeZ=a7ppJsJBr+%R%NM_=;@S^c9!^8jzYHcQfKfC4z9$-8KRa~=I2}m$C zSmKYNw=lw6`Ik<(9^28gmB0U7OxB7LjFffRp5*32G#`yUB9M*1D>*j3ABZQi15(x^ zsrRbO$gyH2%aH-(2A*mhyQmKkc6Gh5KL{~sO*<)}ph!j462t+;8>f+y`MK0!r^)wn zSmPeoF-7Kp>mG~7F()kTuuNx3sFYDSwu&E(+J3zdX21e*Aj!>t0HV)w$=RqQ4Rh+m zM-23V1(5jK5yQn(3W;4d?`4uOw#g8mjrvB@WRuQ0Cf--Jk1&J6D{taF@)0(^dNNNu3?!1s5z77NOdI%TQltiqVG!Ged z6@-S;-M$yEMg?(@!zM0etnib?SsN7BKbw-QqM$zb?2Ig_^)><dj=GyP@fu!|I;Suh4)+ER(B_U#H z1&L1y67}oikLB`ru=~LGY(YiGnck6iKbPZ1VwQO0A--2JfDUM&-6UQE$|jO`^T~{| zRdQS6IY)oLi*(TNWcA|)xgzJ(exR#(XcxifCg>F?%oTBm-#YYVk)#8&e|ZF&%2mH_ z#{JeKERzpW;x508;n5+gR<3AlfC9hLLWLyomzWelO_6Ibk=>3E=ZOxBn+dg!e}4ZR zcZbo47RNKu!ZPiBAAr~tE3t9pR@E|2?90h0ury}%(V+L;m7yTv!w#Pd?wlG%>I{gl zqy+fPQNrYa6RoO_qHam(LC=SdaN)TEs8vETRD>saPhMpsx#fc7`a-Dr^*6_Eq(+S& zU^wK30e$xz(o|eD`5(Dt4>69}fiMDsn8tF846+r3b%&4P!5xQAG0Z;W;I9&*sR_(O zj)m$BX{ho;*(>orJBqSST=-{_7q6R|T5DI363!t6;tmab&Ilk2yZ|%^Rc@K)Now^< z2i~^{+v~WtC1|v!;`IrPh-<6E0sm7)Haq->SBNW0`NFd6C%3Gw5Z$rOyqEZJ56Ffr|c5Z;sXTpsJ zBi~^@@M4``sINkh#s5)HEtCLKoS%F!4as)Bfou^iWtQhc#P_zlMMkZ!hcS~~Pj6qm zaQS6q|JA<_s62PK5m)wRt7J+6pu#CJ&s|j`7l|P5)J*teL30PYy89Z8BoNUbTyBNj z45`aChe>{wRmTW#)JnC~riM*^#S4eQ_0digHPPPMSkYu~V8fjx_W8J6SDHw?yen@W zr&0{xuc z!0sOyCQX-%bAnaS>j}dxy2{YIG`xr*iqsgi5e^Kbd;;IhVJazGJg{=8y#}_tI8P$g zra&-r`Gx|yBN?P*9q~}v(BdKVts&BAk%8#TASQS3eWZNx#daG)^>lm|EuAdV8m`J5|@MsVRFi z219T19p2Xk>X#;!H;0xQb)CkAgj{%-ltGoA?^7tf#wGkRvYh=@ zNEs#%@lPs$14of2W(?edz}y-roNQ7x_$^bCFcBG0Lmej4D+c}|=7LR9f(+yqr1CRi zs;-@JHs0>XjtU4-pZ_CEsp!{*W3^>mNBTH9V5oPO)ozCw0i#%%$oe0v)z`tUBEut$ z!-vwP?-Z+8T>a~lQi@b}y3#>`^)uN9CrRMy1xEjsp zVTmA7$^`aEPvDDpl_qB=p(-PF4bX2V8NJSBiLl13zYhQI#BhT@68}M)KpFpS zQ=Q?!Fj5`?KX2tn!M_68FP;*{!j5t9=xGkGS_Qre{jsS^}YX(ulxc1V+S7U|9imzauzO0hkmIB-2-_U^}KZD z5*4i^^xJ5rulL_QKpIq(JFB?rfB4lH;9IL1de^O;!HZzBQphv?J7Kz*mwyr~|E z2%P%#?42_mhL;rxu-rSz3@LrW63s5BrhRsrx@4&TNa_pz-%INMT8(VJT3~qe>FnO; zLyzmrv*(jLK!t1j8uqVR0YfIPtU__<<>){F zPhJVO4d5lO_`FW%!&pn}roAtx?xC4n9i4?-fwIw4AZ4#CdJPVPYcfs)1QsO&s(plCeTj>V$q7w<$j<#RKe!{3cxVRvnZX~*4K28@5|T{Jgs&2YU}Fdm z4lOx7lWqyS*%aZD=>NKzk@52P92b{=Xke~F$e%RDFH#k ze7~L?>6YW$Te&=%i`~4KK)fzHnp#K&w46_m+6eUG#f2-|S*LrvWe4Bhcg)K$2ww)E zTEq*=pWv{2AAl8f&@nvBOAo^By0~v3Kq%k)0_XGX%jPuXfzhZ9(%X(#Rp9J7g4l1Q z-0VV1N_)d+DM4uo$acL2L6~@r{eooGE-9XeHgxK5kw8`9$3^Evo-?C{ltpV;g zpqA<^2KfV2qv;Cn^_?p893V5dQ4P8(az(H9l(PWQm6}_(qxZJmgNt8YMtO2$t zli=g;dc9!b!N$Vu^5Qc9%w=5yIIlzX5+2(?VBRzVIGm*;^#U+ZDA3C2_*JNxW3GVZ zma7@x3f6TGxB{VI06I0@4~la7&Y*zs!7WGJP31LNo;U#gtO4ll;pz{$jdsx=70C41 z;wd9c`f@iUP#erh0VoP_l>Ges!f-ygHCVOLb8kCo3Xwb>P3h4Qja98Pm!!46HU<6c8Sz;tQNc(@x6xIM0{i)9Yg17cS9*n9f8(>E!f*6;EDzy6C3Uxx; zm5@|n(SeFMQFO*$%#Wm(6Xi$nVxWiTnN z+US>wV?Z*&Nw^feK*A92S^Et`alGs%r@|WoDh*qk1Tr`7J$d0>lb39 zEFI3Bf%7WyFDxqaM!?q{5BfKMV#J90A1POt=MP{izB1ilF!!8B1oY za-zm5Pwx6=AHazEf8;9(-Q9>N<{c6T8JGQs_08p1WY{Y}ok8EkrRVms zOCGJXziB7hP$YA0Pb$;Pu;Aq~B1K>P8*mo@5T1MpQfNXUcr4P69(f$E z+_C@2R!(y7P{Cvm1tk?dzxKFR)_k!eB44!}sVVr-+^CsWACj-aDKK1q{-CNAizM3` z#Ze)ZRyDb5leS7Jf&*q5>=hDBNZ5*ga2tN{``wH6UyEOE`G!LsV@8ubI{GydsFlzK z-^#pk@_jK~OIEi@(T*#lAWQ~7pMFUwO`0&YJ`!-7Rs<&=f-{j8I56aWb?)}9Yipuv zu~`z=22#f_udt#k% z*p3yLSklE+b@Yr+kezkqB}(VeU_2_f6VqL!XJP+LIe`)8pFG|mnk?hxrAVsg;#tWME{k&Fy&vV^ zOX#sJv+GWozQhqi*kDrXE=p3gqYRmdG1wheV~wj?ef?T=&BnOF>WH}x_3L2v6{td^1I z!{7oTO+8p>Ey1JUad<;IIT1$I!!Z>?#8?{UZyCW&pfCH2;eB>joLZ?d=n}XVM-G*C zHZ(flr-;<%4ShzK6-a;xAHeZH@P(aXgTsk+uuXl&o!^Sie1WPXObYJP=xP8nlR6yTNG_i?!v(rscKU7 zfYeyq_HNZH@}Wq-c+scW9`(o@CF-NejTJYCLr>?;G&2kkVVf++&3Vv~N-WY0^>8Kv z%XVU0+r@alP*WMMJ=)``yjl&yt|99lO8A@jyV(31T*t4xonN7}>hr|g_0XczvEG$y zcYZ6dUD7%6Acj5+HG>^Sw6*HFKx&aGa4RF)`$f3~O~)7ABC_#q=xL<~CB25_2X2Di zNR#OeIko9RAr^8`JJEWhT2;<;+2=sBrs!m=p1y*(+-Wb)p=wNi~T1G@Pk6ahcgU|`7x z1ef9A7?|^m@}0W}JNP{u1Oe?~*r(1Y^pzHdBNev`oISP&b@^O?->; zrKqoWc*U-(Lu%?hT?3&?r%Be*JuP_fh9588#bV?s9vHA633>C#Yf*6n(ZmiPGxz9)&I8B zhFNo7-1V%lLT9YDufQll#BOgNAO32#Npjxe`80c$Ph3)y#XvKmUj62Bp~`CyyZyt? zt}tDf0CMZf!o<=5V30*@cw6=Xe1xV5IEx_lzh?^IEgwD!_~ z^5^~Q5y_NAsm+pK9>j%SO7(6ftarNygg!++;Cc3LH2!zYM~9hrEt8xuiMaS2UW=6A zvzL9L31-n>HnY?Ag~WS&6b_soQA(WKEAn$T+aEF)i8qSvjenH_LsrmR|JP3nmSJEU zihRnMS}bdn@ZN2vlR6sZjSWq!bJV+Wg|vcq{xr=YX2)M-1DfJWrNssp>()G1Uv-!2Psn+G&mbCS8lyaGQ-Oxb+da z*_e+*H);mIhr-hSoVWVLI+P`Ln?orsCxNN(UGLbD?lN$3N4-V-_?3w}ZsL+*W9A$w zoJ_BO^%V|9F1KxGjB&P5mXgBLk~oW7MxNUB$9}ozxDc8kyPk*PsQ&ie`!XXw75}TP z`bM+*57G3q$|_{MMC`Ef@?Y`Mb(~bsz9zq_C`cAIQ*;Ob4Hpg7@3fx4uS(ZW%D23$ z>%V3USyVnH8#1Yd@??lS%YFLOtCdn!x6aEYYP!+w=jtP`X9wRJjSE$G_FOMJ#EhFQ z3sg1;rOguur0F;uby(xfv}R_7Ih%{zdSFZznwLV=gvkbij&PoT);$q+Bm&ch;b{oE zwHyRKRcgrljnpbbD7C`o20rbFwW zd&*o<5aD|6USaS0dm1BU3`O!CZo$#^3yC8%lH~XK_I+^_{=%uV*UZKi>YT8*(+zj} z^(#jvk`M&cQtJM7-s(>b*cof6kMD=>9biFZOwzv5GiC@jms!Y-?c{5c_nq6(E2(S% z21eoJ;A_=rxr4+;2A3Q^lf-)(VC9kZH*$}1kPV-dj_H58cr z?Xa>yK>sJu!MWPWUfnsSPeSk($2(T1DcPIk_*CW63N8r%-?N6-XzbnB_~xGh)BM}K z*Gg{=n?6s|!EqTq_FFdE^f{k8{ZbL~{IbE}Tw$ee?u7%hfh0 zHa_+3x>QGhUG=@}KV;z*C|IfAp zzA+ohPZiGNu7$(7lHw)ryw^zq1KE;Jri;72&>*R@eE@gr0~ZJ$R)N~`8hdm3g%ka8 zc~*0*lWXPpH@AWE&wkzP?Z68j+XykmD8`ASmo^8AWEF{P;&f9##U&-f)PTZlJKQoe z@T;2B(}<}ZKfyxG;PeM_ICt-!MRR2fs=;kFN^daX%cVTr(IMf~BkZhB&C}(R0|!b5 zy(7l`OocVERS(FqnA9mpM<-Ui3~*bWW97_KlSes5y47zC}>o`}Oo!MZc992Juwwk)@dP zY3Mx>d6%z)1pDsqADm>}iI&WdA5?#I+;?yj!P(Rxd|x1L$B}IKRvq2${Qbqy%||-* z@-mWTYjg8S2}6-dVF!vM3FGhr-S_g2Pey9IuY|>X925|PjIhy|=-ugoF-rQeOU9TD z!{k{r>h*owG{i!u%8rM?l(^ldg*v0UbjiJ~hPcGI7?Oa!>P^j}ZcR#L~#{XT$c?E{%#X2+p|;080ZmR&h=pq%&7 z zgA6JasAK7sXw9Rzg9*P}nEkQbpSA(lGIa`;Fifc925Rh$04Dy{Zv)&zNXl)Zw>}0d zg&&SRdf~`I;1NL1t|Jf9EnKw$WIpta1FIraaUXuwF1mxlAJ`@2lMNmf_cXIjo&E3$ zu4F8n$Jw?YDzwd1uXckB05d3Gds}dyLW>A!MRQNuvn4z%>~Dkd=N@gVo1$8gnyIJ%j3t%AmjqnhS^~(BAZrohGWn1ut z04zS>@Bk>k4^cAS3F3%1%)CP@^4!$!h5LNAL3Kn|xm0zbkb4vV&Q>-WOG)&?;le5i z{i#L_&HZ;T-gq@(`>ES^izKsNzg159ug6Z&Lnom0ttVb}?-0<2bs|C_NJ%?XGkY`8*TLL8CUCEmlMI&pua?Z17v|R$QS6N^1lJ#C}n_?NFfA)7dltNOr=#w zEQMc*erf8p$bt~SyVC*l>C>TWMzndjHrx;3Duuvu_T6T}=h@CM&^$mRz6RM$P+!$W zsP_nV1rc&gr(xMx&V~3lTuTq$i1JAj5mtkc^J!jH>A=$u5oRx}Z-kpQ84li-YCUTT z#=KBqhh6U&e;SHtsmh_dDGmBxMjnXPyH!{<`<@USL4V`xhyiiJ6g}Hv25+|Q0L4#L z0Qlhw@|!(XvK{deuaoB`AKJg_WQNs#wC#?idz%po_2S@h>>SdxrDSv^;@Yf}H=y); zgCOV7d&qnn;~8KPD4KiD&$6fY*fT9gobZ|V(BjI|-HM0Fy9*TgE2SWBCROaaEl@+` zj)Oc#|H~5# zgGzsMM}a<1rL?s zGNM8sIGH5)g`;Y3%cA~9_mt??+^|zy`mhP;6VnU*A1<4c@?*E);f494udq9>21Mhr z7eb!qlrq?i=gOd+frQtQ>>i}_$$2RCi;H@k>#f|Um^SM)%wy*LEAjc~Wj8LB|cA6@keB*v(oP|%FG zsS!Pi#&LU(&!w-Pcu%h)+!9CpFd(_C(kEEGiI!{D zW`F_2(y*`@2L1iO08k;!gWE?XxUehe4i>_Dh|cLO)Y z3xz0eE+^ke>&QJhW}JKGyXCx4kuky!vmdfGL;8|X)HVhpCr1TVM*5zfCLmKdwK80+ zxxuK|qb5t9pzM|vzj6II{BG(pQ^P8Uakahv?Jq+{jTHJ_rUP{aWX1zP!*eZLkL&eo zu0{D-+up>P?g3_)QDk&*8PoA+YaBk?5%6Coa3j2eS?mR<{FFRsIFF5HM8~`8^kmh{ zE^}KO#aFba%&_MojQ#M7ABZ|98uakOM@|C}F_NDxeD@RzfLl}*Mh>z?!JMhnvhCWH z(j@({j3GwWc-l(#q({~_90g=$2{npsHN4@R*VEvTb=YXnw!wyN&>>I&XS`K%c-_%I zkZMZao*HA)F8uy+uZ~H`-ayVXPfnqGcABXCo#W4ev7J&VDKdFC+Z}G)k$rcS<-U-X- z1$*#`B31v>1pZ@16JYf}w9_8-(TwM`5lkxDDzuSZXjkb`7^~Y#H6<9>ssZVTd!>dI zso*YN6=~X5qlC6j8N+z9-AssYO87B8${Xvu{lmBTT1WRK+B(UTnBV>>8uGTYWFX!Bz zb3@+3QR(OIUYt*S%~-E_jH|SFIy!6a*UGZloL>Z(PuTfhA14j1^NKYq{S8w%P>UXN zYV0cfeh#o#U1lM18*M70?QIoD%m!fVmYH9-@ZzeGWGZ9Iu#Nu-uL<}KDBN)I)Mp*nX zs4mD6TD4z@>fyq1wL1hURe?6o?@YoSQG?*tyM?G_9~^)Bbx^rQAKV`#Tya#-{BhjZPz{C z8a{&@Cl66WYs=pLHGT}}Y%qRHg|6HEri^71f>B?Y2}E(bWgYP~^w?o-^PA5&lMP-d zPacSMiJaGJn{0{YOgbU`U1tHXA(HZUgx$INJ9Qp&_1fXkqNq5{O`Pir7Ix7;Ira+M zD@05^{sb@nYf1QT=OSGFz{P{-w0 z3_%RUAY!}yi9%ibNn@bxq7tQrN@+|nZ-d64#RGnZmLX`6C>QbOO+&E(yU|_5dFlyAV;IYIbH#YF5HK>{&stg`{-Ns*3brkZ^sFM2YwEz8%|Nf!>zl;+h zC?1_Te7ABmKhS5zHx_6b?bTj9vajSgU?%rGV9R0rvkDndRKeOZVY;;$s*9~VT@XO}g_bNjfuuSo(p9stUS&o*(V1+3&7~|u3$^{Os<1TWFf4G9h3NOUzusG|_ZUCzBE@QJ3g)iHIU&{x#Hd1Qeg z5Dm0PM`TOzLmYhNSj1}*A6Z8?>k)cd!NQb-Kh^4otCnqp?kHQ9yvx*T@ zQlUk+{`U3n7!b*Ww_s?u*S&`{7ud|eISo=Rjcf~oV4z`N9$$RdHF-uatBd)!uYbn?n+d!HkySN2FmJ8|p^1<}q2xo@ zuyEn1c$KB*-z0M*SX)Q2Bsokd$hD{5)}wL>dT>Nyn%<=7h+iG(DvC6ya}dxT7J7yp zf&jGVWZ@I5=)-@g7G z19Y&Cgu*K)Nx_;E!;%I4r&c*1b9^`SB+ICh^{?@s1q;)=J3=!dkR1#~k)ZJ z9Zc57?qu^pvcb==!DN)bef=lV4%QL1{KV5p&{`(id(eM;X1@)Dx?_z7*96Jm&9VbV zr)jaH_+cw47z$lJII%S7!4*1%eTBBk7p`1d0^|&f27>lbWPTIDz}5sk60KrQHegk} zYU9^65hMKD+NL6S^f|n$>8Y>+XzhED z7U=(*#AdgtB7_Mm`R3oP8R!Atch+S=_nsv#7z(guBXYne{=sChznY< z@z(jR1O-IYFXQN|Jv)m(C8$#QNKsJ6HuZk2)qS9+3c>AnyBV=Rx73S#hpF*+Bp0lz)jo(?xFPHx&R_rAJpH$M`fu~}{|)m5 zakOI$(z@MqIV&r+uaKf8G~muH&!8KDLB5XP@b}n*qVfZa;ra$?ZUg18AAtL6_W?Uc z+!jI0^5;YcpF?ZGCV!)PPmBO*Mm({B^(e;v_hBF%Fe6)(LdO}%qx}-tg(Ea-i+>#> zVr(&Rg!Ra^5+ECZIs+pd@+AZI*SLef(^Y{j<iS;W?;mgI!y5Ywb-DLO$mNp zOcH5!TN#06B*3{Jru@fafudRgEBrr?ToR;3!~B2yPDV+sAeUDNlqdE9X1EuSf|dZ% zPXO?vkar0HsJMT^;~YQXso0(AI$aZl10&D`{2!!!byU<{7p@>mNGSq>bVv#cBA^n2 zbV@UHJER~XEg}ulAW|<1A~AGHswj;yNJ@7j-EjBM@BMD9b?;wyEthMJ&ivw>efHUB z@8@|o>HJ4%+`$HUvG^B+6fL#skdIbe{FRpj`M}*?A=i0z`Xy*~a%JhZ9u6TMgfK#{ zDh8>LCw&nEA71N+d|u6p)Pu&MkKq|By^ zn@-}OQ_4A4-oiAzF4%p9QaP7ckTwDCY08dO_?z6y7J%r_XTcF14OKvMa#<=uxSzb5m>o+8BS zzeq3Oi9vex_Uj3m!FtbfYZauQCZ&BO*Zt>s8_(x&eebMPSWY!sC`%by77= zeo2=92n9_YLC&(jwpxM%`zp!vFMM$jyvdvy{0!;V0w&PCkh%j1#WogbPW?c@s)G&S zhH;?k(+OFVY#?j8OnxCu9GFM)D{ere5&%%?J}B5t!&l<28{DSsg+|d26nV1Al*0Rq zj0#*rs;&yzvH|Ez3k}_NN{Gh52D0U2SzI<}RT33+*MF@6P;vh7DZVdcxQl1Nwh|$M ziKYkQ7v;T8Kw~K;^BGO=txuKt?7O4@D^XGriWXduPpN{yV(0{S{jE10uXXN9VKMJ=pgX{ z>cIdb*or@)){f>492)V~;Uts~s0XcZNm@ zfc7P7U$)d>{tcE+bjk&fYi~r5CAfoua6*O%>Ax8 zge)1FO3PZKHUZANZ4t&tM2eOgd3qijcB%%@V!!JM(ot*h*pyxExMlMx4P7SwfTh4{aNPNW6*VuhN^C@NlxSY0CS5BM1KYNdbR%$YNI+)juD3C|Z)5?qE zV-0@nu`;B6dII_#F+gI}L^Zrl@!?d57YShL^!khAG=~pV7YOPg${H6A0BK2$T^DFv zCB0PRwVl7(9T^&`PADCW)h@H{&hLCw`bFp(TE-e#Yr3K@c%>#wiYYp+jJ#2?KOY>& z+=u2+i@}mox0&-0R9mqO2PWeHLDu<>9dDWTXG$C{3+}@(SV5{EwKh`cVFlJ)`(hVU zJ*q(pwBYDvva;?Ni>T8|9!jlwZuF|A1WXE$Il{{q&m_=W}}3 z20N&`VFM5fWLf%qq__(E#t@VIG7ESmT|CFJModZ%(0=B{)t5K#xh*DG8zZGlxUug2 zuVq7^SX1ytiohaHht3gi|HVHOv~;|iU+>Guh(q!-lKII}e{ugzbBxTdFzHlCy1{&$ zXsKbtJzOB++4%w%2p8a*lc8Cc?QNPvyV6WbljbtBWwgu~Am^N)QZxoTOUgR8#UI{R z{;9x|q#4L1P{d#V=Q*FQ9|)>)VvM_$#V`NoAa2$0*QjoSQAM14F#?-eC?yVWw?kiH zN*W+f)$oJWSvsGNf5b^trqjVI4SGM*k+_tVi$8UPg_p2pR4MBi0AQcrP(5?X(Gl7JfrKsoZ!i4zLIOw@qqxX45eP%ot6W@Uo0_e4H!hMt?xOd z-J#pg(6Rhy47&Ev_csH~vE>pvlH$;oxk{uE4Wd`2;nXJA0tR4+TY?$J{-zABA_)Ob zy=Csd+e_$~oteq;9LO!^5wIFWh!wRNm&ZuHhb>iFCSwIWVvJ-A?A?LHY2C5N?oUEE zzN$;Woy5o*e+X_0fr1DrbxPr8A&!L7v+A!SxevPziNNFA|H+ymOYh&K%ikl7UM8Fw z4sM#0A-4SY4+C5ex6R>}g=z-B%NvT;ErO#y1Z z4PN4l((Fn}3DC}Rf1A&Q<=@27r4nIy)P||n(RgGE`tgnub#%`{cfELMjnx5Atz*el z*fewR0Wg5!(B;qgeOSq1Y^rGkODDAw1kNvujMNgv3MKs9p7Z~mL_$1J8Rmhy#qF$X zI`?tE!O*y=7K&=XFosavFhK3DjqwAHJr?Svo#3r3p%5tm*lQXg+XMs>E@1PG7x4HA z#54k--tV^ITUcPSBUNk5&LoxdWDLBX8`D4MyD}wAK=hnT*l{=pAoT5EDu9aTE;Ij1 z)Q$lBH=$^!1RM1Xga)Wxh>O@j1?Ww7HoEreZ3*AbPa8QzyVBEVG z_GfnQo#m`Y84hvJ9KbpquHJD^L#Ew_m7D+_RKj9$##M+;f{w$KoQ1YTh;&qG-$Vm-DPEAK|+K$DDL~dgW4>%(bwDA3I*W|4`?67 z0g*xhAdyzk0UHa5F$9LLSm^B!1>Scl6F}{5qfooY3}ujnY=wA5C)%pamww04n7BKoP)u6UzP(q#q05 zJ>`O&A-Dq=1@GAt497twtbGEJ(X>}!BL7=ygvxKph9p%5NTHWKo(M};2>mY>K&tx@peA&8OKX*uK%R+- zT`}Q@blPy|$AGg!OJF)WpUOs&`lU!Dp$1aGXp>V%beV4zERHhXLj=?k2jE+ZFy+%= z9#xU_cUArtCQ^l+`Y5^dWIn@Fjx&Pw`w#E^jfV$bN-||rvV=+}sWasw8#7W-2N@tM zK+nRe4tp>)s!~FDDAL61}M8iB6ngD?cY&CJea?` zPyF9el41IRMOY*Vtb(D#73z0f+W855l*Sd09s<4+cydbdb&Qja9{apBS0*;F#x+r0IhZ9-EMOe?wz2C@oRKNcwt|+??RY^gW#U-Me;g; z`8iMux+9h|iigcsV1*zv0Yo}}dowMI5x#f@hlMXVrkjX+BOQ?kjaH&0Ve;+X}q7ecn! zZh3Fr0ddVGBmo18cJ}8N{bp3`7uV;E46~jr^V|O8+VS%pciwypw8e<}5_2ddV6&N(M+$ z=vCRLjDB6LWxexbrPS}zV_dKtiZ@+1k$vpheI_kzctZhsKaHTZe42>!bE*ggR9j}* z{zfT@L-`eXh5H~meD4Wi8iJ`YpK-^V`-b!K-VG%5n&?3NUCu6eQtX(dv!6&2M=JS@ z;7c^4iJDlenF}vG>MU%nuUq4U{yNzla7@?f8QfpOT+QOKu&`{2_kkYAZy&a0aYDUl zupqCSX3@yNF(CyroKGE!$Q>ksgjld!T7~Wjz6Jk@3wb@-Gw%!I5K}9J6sGOh_a$m@ zFL#a`aP(=2pgi2sN4^KCNZKn!g^9@bcp(LC`yr-88oqa%xWocb4$O^_4E&t&ESQ@}Xv!RJE+4gL;l48=IV?!UVzxh$T`bX(SL zsWt2fk+NU2Vx9@XTViOacfyhTDswj6@rs6$^Q#`HV zsC^XjO)2DHF0f_)3f?}F02FLw*Uag~yj-tDg-bKz*g>`dbys|u9(k%)NG6q5Q3vWG z_w77<`20c=Hji!bKG@EJ+CxQ%FO^UuJM-k%(Z3cp24D4iI~4&VOM2}G$kFUW zv<6Hxang4mv*INm!B|OmW@3 zEl~~EkPsjfe&;LOLJi|ar#ueiJTK}cpu5p42S{_^*ui9>SV@=9A!CJ?1|u*YI*8oh z%EeGdiN?`ZT7KjDe@6fbmu!Xy{uW#Rq<{t5So#Ejd1n1D^SqmICPW3d52CqBoqGdU zk+CAU0%P^@N0~V+u^TKusvHa&qM_6BZL?e4q(OMgh&iq8mF^#N1`rq%t3_O!2 z>`D{WTr-ETKUkXZ@c^5t3cQqEOHjk#xTXhQN=2@N2pQH;B%`v;*9S+4pr7wWE+agv zguXwataA5}O^OUsKE9kR;>Zn5agP`l#>bz`CxNY1`h*VLM;`G;$QgfT!4OtEFj)c# zTv3dk*!W1@2Ns){}ZR)2r}| zzh8vYBcXD@0IcVhmyBaD3vg9vzxuOI4?2X<|L3Za$W=LC(Gek6{qg{+RQrD)_ms87 zbJMyZ!VSWSFW}5foslB~e(1>GBn-0oceAv6!DKG0jzh8lCbQD6e_8zUP9`2ml42J_ zZ#;=X29rq&J;Mtx#}wd=xcaxdrSDYJU(3S}?ZGM71~Qc*hQ?-k9>$#JvObVuo{bPD z@S7N~SzOmGN*f9Jd=mf60&Yi7VN3dp2=Aqe=NF<8Q${*PCQa$sx0xcYe_#c{vtPjz zM=?V}kL7v?d595#rM)R$jbb$2ju>IYMXD_1OuZf;G(y|6469haCYb z9U{9^GF)0&v1ub#*(iN`q>z%Tey;v)Lf$7ZsBw)WMki%MXBHV ze%k`6UMW2@+X84)~BxdW(# zz}BMQ$PVFm^Fl6zCaRh1HQfccjWXWeG2gve{2ZZslaE?B|4nU-Lm9Fl`JX*KNrFGg zHP1|~a=)&&EWF|d=BEes*|O3jY?-~n%?S$ zUwImehS+clq2F5!%onbaCcOz7C1{R)A`cI*3M=T)ctOmk%pP^C9W70^v<_o^r(T@o zC3ca5Ph1(d6jD`D^b(CLcLQ=Ynz+78Q0p>8Y`!u)+NV}X+B>&@xN5Y2JbQhAbJ=~2 zXZr7n(ex&6Kk%jUHj?7(T5szY+AOQu!|PZm-S8RBtq4}*6}|LtD#EPqEAy1K{C6^r zwvoEiwkOV+iC2RQTW;c2nS@-!R%$ogxOyF_aE(8}MH}<8UX{q?%+su&|1uG>4b?U? zdgILVa_DVBYDPGD|LZ|^qCfVaH`>!BPQ!inAq^UH*QRP;muBp*E4*-#)1)cT(VtVd zz9h)&YtbtiFjFdp!+vRWr9ZJK?!PB?vtPZ;Q#SI&W)yDvf2N!#<(porWGi*nn%$BD zKP>+-4DaCOE8bJuvuiz#u@oU|p-_&bzi3^2UID#LM8U{{^8|4{6KyCTj`5BvfzHLd zcN@WBnTp|d_BkdkY$kVN7g!7XMR(e6!G!gw4>htNCCfIPfiN&d)t^MgjV!;1p3LJd zjOB5a7fw*3UIydQ$&C+3Q|G7$$-21r6SYQ-pwGUmxO06nqg4q#WB6at&F$3M=#S9! zH}U++VJAnkH*#81z4O<58Q`u9%Cx1>ce0OeejjuvUat91!PDilCKOd4q*zoCgLzv? zWzl~klTP|`Ev9rj;|~LqoE$DGEBV8`(k;h+d7`<_nUdJMPihi$Y+A%>A3_GsM?iR*w)ZM_mrGx7JUKl#~iR@{whI-pK1N# zr5h3O54>@+zoheShP>6bGxM={NlaRn(lCEv-+n{g^I+y^qce+tX3!>MXHTPj2xHY- zcvC#+@L)}t-J#LNM)dxFU_?D78TcI13r~rgb1Gc;{tE~JNL1Q2A!8=O0=dszjSCye z$=o?(iS6aoom0`Rv9oSGO1piG1b!(_J>D;-zsIZe*$?x1_jSc}|K3$xGG?8gYSV(7F?^SmFIO^;N55z@}o7G;Ueff;;f2i=sSfl3njd;W) z(l~`3N0VH>UTB|hT**<4FDf%1>5pTd;wkg!w#U?&wFZ>!etg)zW9vmTT=`+T{UrZe z=FiNo#EbE>@^sSAQtM3~2CKdLs%)os+(~p|`tP1|*b}HGzI9y#CCzxYU<-yWQND!n zB@))@ylPgkEtKh_Z6M6ulS0K`Q{?2aei>&{Y?NHhBb>N?_O3!Wb-esZ8RHfFo?E|s z{hG#ZBu&wNpZp;F#43?5u%&ZdbIx)L&ACNkni@fT2vY|56ZUa0e0On75b;|E4rZ)$;P{` zhWWxv*G#UbF>%FnB!-jRX|KkQ7S%v`{zw%a!{^?jpwZK1(^P!2cp(Ip=1O%oM~Ke4 zP}Bkr5zVocNH!D_j%Gwd(i3b#_XDlp2E!c2^pzgpl@F`lw8N97P3bx-rzUS8t;NbM z{PXxdw48shoLa3s%WuH3H0z)J{n&NAEW1lnv55XRCwaH?**h{BwRawOX${&~+QJdI zE&Rl9GbwU@L}yH5;~4$H{Wy49P~Za}TFiGxn< z&~=3OMs=*eo)DJO zRmE>lgRzT|B2N;i5O{(-(@E1+)x!y=>jwdADk5L0vEjt%*)4vanjE{^?Q%WT9gn3i z+ud4Y4iUcot7*;7QnU4{f95Uc&xdDe&@?5&FO=dfTU@!kth zY<1FSyA3~ksWChd68_v|es@`dn?BO2t`fDA5ZHn>ObE;5!_L&iODq@pH+t_DEg!6w zSSvDP-oO2ky1QDv{KKgt?Qnh47klUFuKp%fi=BKM^fw3z!wVM5+- z)y7k6XUpkE!6D_;YeBAz8>MWwcE0bNoGLFVS}fcsvr@e$CXzO5^6VtctB{H@a*IJ+ zKRK^_SnVTvGaTFDkHZI#{q5YPe^El-KNEWV_Phhw3K{;c6cgn*c^$tyihhDgOR`$F zyo@{c*Nd~g7R1qFPRk12Mw7nX9kX4pA09+!uo!r(C6i>T{Ni1nr623SqMM@{imS6F z_k-i^8oWEqraUxJ>PPdK@Si-GJmx6kTe)t+A~hsbl!x`&{6Zy0Ks4AxwVf{?NISE2 zhBI_?U#vjOr9gOzFI7A<+Z)9ryvlO7NsKL-tca}O!%Vm7XY`4upmBM|r?8&94ReLV zYvuXG1zu^livjc^MC{(LUrEU)W18P=Lp&s^e7%q3RokQeKFtU&9*P7AI{Vz{H3k6-)agv|6wzV7dA zYx&NhxOkcWe7XMbikS*e8FXd$FXE?iTo@d=uJiKa{;>G_UX%PEtEATYTMhnB?0J}r zKgp6J-4gyZdj|~SS3dd8gReb2$hXMw7^;6$amU(L!u6koz7UqlvuvhFSnSE${k|Or zsN2*!_YSy`1f9Fx_1?ZDx%m<*DKnF+ZhpVabW^L$e#JUP-2Vfw z(2jZe7v+D=@Z$f|49$F+xznny63=CNFgFwS1##bsE3eaey8FC2)8+5G_*}y#L*_7<^L8&c>eFdhF}0k{@)}0YMyrP@tH_r{RGHEmi^Y5@PEXg~p!V#2CH|^$+od(}C9JYNJ6sm)YC%ZT@vr2Mpe7NB> zRQGtjihg%4!%r0Yh0H5??xf^?&0HTZ`dYEy(N6jHmPS4Z-@v*l9BB7HHtr!J?^AZf|%Rt8Z~g{NS@omX{!vDNsiJeS>732dD& zYq5#1o_~E2Couytm_g{{iWM+ubTBANi@*>v z#w3JJ7EDS{TMr$bloI;>VYLZVg?dk=&X(`-#2ThTJY&Oc|1c!om~02C_i-ST^m%IY zVGc&Nd{w~P$DhWgtw8wFiksXp!*GpT^kpB`kbBm{l?zKx)uZYvR$I&Y2x9ip?b#|`Jb-e zE6f|m)8!a0=4q9M5-*Hm_txa5`^Sou-m0FpnyPAu`yATy%5P;R`mVoXdY`YWtgC~* zE^HYpUSyeUJ=DX$J@h);8cCP2%5(UWQ=^%DvN})K6U^eol+OF^V9FTheK9qgy$WCZ z*Z5V<1)oePS~RZ2(!5>kzDc!4DB@r|XoLc#D7C4%!}w8rkr!&>Cwo&HkOOKR2!xWO zA|M$oq2O_Ujq7io>YsS95)7rUiT_@m($e52^&83{0k_}n;cg~MNs+~EqeA6Yhofh) zwfzM9`yJZSxS%fZ$%yU#(cC#VBRJ`Zx*jEDtFFHxUK>QAw(0mfqdeBGNKB7%#q^UW z_-z1Xe1yY+Jd&aLT3f5E*y^#U>vHz3)q8p`ef&`Z^>K>7+s!O3$gXZnKhkJOP;MM9 zQ!-XfG(7Ky=DWE6WC{D-F;F6oriDL-pIwRfL%CJl1Hvh#Q&p9j53c8CuqTxoBjlF5 z>-SQ3u77x9o!UV}Bv2--=7aHPIBqwjxru%mt{K0})A5I}{8kUDR@DHlQTN6g#r$vt z)f*ohd`}E*N${IiKWSE$ippyF*FLwlZq!X{)l6Ay+NK}Y@~K1XSfblNbd#SXlQ05m zKMhd(uO)jq9CpCb=e>P~;EA}+&(|(qtpWMd z?HLvA?T^~t`|;>**2TF4m;GdubN$;#_5SJiwiCqsoCTNa5{k!6x@`Lwx0fZ38h)XB zB8*`}N# zAOi(+P+7bj1IU_o5PRmH`<|H$0#_X%sKgGvQ3QYs2&ju_BumO?T+a#RsyImbFC9Wb zDIRj!ZJ=Py2FRbj+XuUA{22!Uk=9^j?0|~c05noZCw~(!lw9IMLkU1G*k6k-cKrpp z1s&9?e%Vm*8}mXYvER8K^mnlzp4f1KF!{7$OC88$B?D$-VGJo7K$42Xsv{v5@G0_1 zy!x*95FW9BDAWbm6yhGpMqbIyaz#xR+uvG=TxZuqq7kq(uj9rARF27IyS zJ>`$2e7M%#Pvp_ZB{n?mTJOtTZFd@f73;{(@*1-?h^KLKRPn{Gsb$9VUeva#V7}Fs zL~=z;yU$^i*&s(7`(FpY^?`UbQ01B$IzjDBB~#P#{~};*(<8VMIzCpNb+H z4q8VbZY<#ZNLbPC7B+mz$*_~#|K_Z|;g@zjT%YkaLN5Ddis4GzcSKD}sNXv@Tr^P< z(rgb)Ox#|?mX4IV)ZW|dFsQwJB=P-gZ*jL#nQR9ozrD}18yp&_^-t2h0&9wx@U;cO z3(3XFd7DY?L!MJY;;YA>juvgYR-BSldTsv9ouk0VKgcYfS=`+|jF>r3{txMdxQp^9AhyIx(*bXojl@!iG$cjg1HMd}Q<eQH*@*Sl4@}Ip` zmA9yMU6=-2zAb*khuftQYTt9*O(wqEi3lCi${WhBapJySlpm`j!1zph(4rsR0uHY}K^dO@eYr}3+igMZhqwCem zAyE2sXFT|vY!xQz7e)gG2Z1+hSt^$1a8?^tw7bfh8rkeuVn}JVROGAiEhc3?+wGg& z+3ZJI!doA{=#M47O_hkBn-u5i_iM^hGL2PPwKy{Oo>_DfaQe)oSn!Dp2+JV?+I+_^ z1%?~eN-E~XyT;vA%4lg$oZQ!v9fEJvD%s`8rq6VdQ4@bVt(z0_#D2LWS4Ne0t%+gq z&&Q_QyJ8qm#d>~Luj-#`H@daD_11`kCWd{eA{l_b>I4!*%T z>9=oK^gTW?Z@5?@r^7a0;YrDfRsmF3$CWP>=YUqI4dFx)mPoYg)y=oz=D^3d9BcGF z7>4D+FB5+GXQUmV52pbI&=USWciS!oWqCO^{lx>8hzN~*Ev`I+>LRUtErruaUcRz7 zF@W@W4?SjyHh?034)?;RB2;BQ9YS)&v^}pCcn_M(KO$GbiwfC=^KyNm^)-QRYrZ{C zAw~bZHZ~{d9;?MN_bQes)*spm2t|Y!@_wNkv~bFywD?_W5n`Rf{Kfk6zghOD2%Cfb zJ(Jk%5}CgTI!fU(q%k8u?=4(#%ggrG7hYpE3f@0nV4Qw?KYd$CPj>MAl%!Eh%I$3> zT&|W0nN{q8_n;DqDd;h$7Q_4@t z4hMW}rHqkPv{-&|y}nN44N}}E$$hiIzmjh5BuMc+EFn5G=wMk{I(>Ms-n|i7dYS$l zjovRI#{Imx|6&2qeQ!VspqF^vHJz>gQLpanoK}2+7@ggde_j$Xy8iMlqCbdA+Vs|0 z2)U%n)9B~#Ow0JPUji5Q%o7l$%K!xh-L|%1DOsa)1y3ih7;rP?tYUSF3`HpwgNl2j36}`A5O_*>rOEPAWH6r7#&M>=D6Yp_cfd90@G981D}H}w9)Gb`EN#g=1-tvEA}Y4G!EGtY+PThk;mvU*HGhV6 zVd-Vj+d){`t6o0Ics`I|-@d5#jByv)-YQ^w<3p$KEwC7|+}&?py>p2-ad3OYtUZ|{ zm1wSAaL#J@qw0as@?9C4-%Wwm4<#P;uZ`l|bxhG&mie?$s3#CPnSl9 z6<6iaaQKqfhxV)qp!LKT$ocv zb$L5{iw{prKRbyth4I&;9#E;$vN$y*$}z=U;#{ ze}nF8ZzQ*v90#5(Mpc;8+}sI}QZ<@^Cf*1zDxaKXNz`#zjdbGfh( z#N@q*pG_9$1&W{E5_Kcll-^3Exs^}Xy&0vXh)Z`Vy{$@}wiRYB5g@{C>@)c@4t>#A$|{?VXk12YgB57Wy~+`tSSyx58ha zyhV7^3)ckRJj|)oXjbJW^}Tybr}WE-27zhkfi`P$E1yZ7e(`VT6*1Rsd~Z}KV?|x5 z$wl2}Qw0|rRy(3FG0&ZPIdu9x@6uKOuNgYL3g2|!HClVT?W{1r7qjppnCX6SY4#Nd z;=?`7#6G9UnU5kcVsr7XYIZX%My`YlGl5HtBB5M&&|euk*&!$QT6Ai9htb1zK_H2U zUqCg>?O@^4p75WnPoCMOty|^o(n1uA8G|pzS(Q%eOF1edooldb!j80zNp#6ZEhna+ z>GG%ezC|wD{W8bdDe`M{vq4KPd`2fSw6ywuAO-L4UB7;x2=8gU^Xtb^vm-gaQz&fJ zLy`qi`!`)j_Bki<4_e$~0G3jQ_tOgXa4terv8^Ju!BzE6>E6LHJ9*?Evr9UT<0XQ- zc7^vUXTERibVjZzl~em>J?UAV^pkM5vIrt5J1!y{H1DAzecy~Ptmk~`_w#tHW|J|> z?=Edxj~3=ev3X}#^6pu748SHS+WG*GHVtr%SbSdSHQC044ti=X!MRg<`_T_cfEvBk zS0Z3Yng!I;bbI{v50+)Ln8#`wpF)c_vJ*X>2%^5Hxb*(vTUUuC2#Q@L_ylU&@a8%a zm4ZG%c;aP>1ym5DWKPNOB{`W%HYF~{OjJNbcvcR44QOOXR~S^9bL*itW*~GIv^by@AFo1$wOAQ z$~q#$Wod^|)}6Z?0-DP99m<}ZO6S)+JJo)T8$2m?bf(kX5KrRVQ;8&|A@%yqpGO{N zDC@m9(*>~U6oX|Mqnb%2&+fL4oEw&c$DLd`5v9L=xq02#si=*{mm+?6ynwahvLB|Y z?Ho`8H<;+{a;QtwyQfP)H|ZXk*T+ zKvEGjYC*X~$Ham*)N`hL_(HEB9MS+bX=LR9=n!r@y|Re2(dzZ>6;c~9DqoBTpoNb- zpq;mWWPv=P!ReS0YTL#k^)^7?q>QksEHXqRb73>(aM0=r6thA(>s{J;^+w#D@RR>r zzst*|GCNl`!hI_qb^^UZtEjY^Qpq#+_-mu)@fob1Y6D;r619I3{*;}iF)aB-Ld z%QUQBU>y1|rWV=LTW+mf;PcI7PhYXgK(d8o{(X~utJdt*0ue9TT#!!k{4GLR7ZbVq z+gLUI@L~R~)%?Ty(vGuJR|Y<$6y1>Ye>}9KVKIZh(_byP_p3-tBUO?Y61UlN7pH}i z8vV`fk3V)$gDx8WB4yEl-XcxG1=JN~VW+XB-b5R{k#UE0D`QWC+{8?f4iX4M)G`z6 z7E7ICl-efo8GTHT3Xe6*Ux73W6I=O(op|#F{-i~g3$&^b2dMs>*5g$}vZv&tDN zyGqj-4x`>u!SrNr=NPW#Ns_LND&BVd{g#JK)zRS1uIQ3Gj>YNCBGJ$N_eMTkF#GJ= zSrg&e+&7|8=6-dAV~r1^*KybTr>*|}!lV85$?qH13kPNEn_;yA&8bVZkIRJ1ss?uc zELARPv_0C4O4DcH##BZoveg*WDF2ia7#J`iQ3!fAMa!?&?<>z{>m6(x^PRv=BguF*gnVE6V7nn#H(*ThB>~7!R>~hUP!|69QS;iqX1XozKDJ5wzAP={^8H_TX?Y%%V9a-FPPj42WQD>{ zt8eewB;7YkT{5#7HTDd)PpSTz>^b9*uH*L&aHU=NpF;|COALEe&-H)%=er1wo_`-L zjr?$dt^57+RGsOiu2+Y=n#mz2OUt{+R)mfyhxZb!>G$>Jrm^O^%>sENI7Ny@+HSRFd z@DnPk_BuFKdmg+s@y*Bs{nc;XJ<3)Q&Dt4S_DLlB0)9zD+G378I%=VoZ`qeo_@DUk zMytz)Q5E0YBwH$SDO37NHRn22r%p^SFMBE-p&stLuh@%y?Cx2e)0JT^|6TN*bI@*!=A7;m2LXXRnb8hALn|E(D?0B(wKctWO1FJKY;-02%QbfK zm@HN*g z+x;Z-ak?`0QPAD%!hm4pQl9!_s~9C?1L604xqS`HG)k-ML>IFuF9qcc7d=0o4ZGCR zQ;=aZ_a(#ylD?XUmEd|x0($#-nw(`qi^Ta&gkO|Ndn zHa-~|I6Zj5{Gc^bbHtlCm0a{Z?`gWDd719R_F`cBPLN}L@i1u(h&O$(sjEmA7%9_q}$+JCpP=QvqT z*#BLMAuKo?+l+*5=^Xm@%#Zdj`a_uRWl{=bd2N@LifCn(l!mxVlRrm#788 z*1ML;MLjx=#z$da1RJ9h1;q(Cop?X+>Fkk2V}}Zt$Q#`4o;$njpRW=_rMv3~Q8ij&=@(_X93 zZ55L*wUfpvKIVNCvi%hUt;NpQ1H$d&#d4fWdk7T1(pp;N^v{^>(dY2OkFryvTDu!1 zOO)oU7_x%913$^;_RgoW|Mrgg*dT^sq}A^`4Oh~+d)r%L<34O5(>FcBhBO)sZ;EwO z9r8*n52AM8PJTgopo6Y>);^)8`3?#8MTTzs;&=UrS(;b%wIJhJ7EFH_eY2<*<-b-- zES=!|ks@5U-|g6pz$jw1*)qs^fNE94(Xj40^Wd1c7Rtu=B&hU-;7fbq)w8Onirivi zSCkwrYFF(7n5&8o!`2(xk27>&I4wSpVsR|q(d6QfVXf*YLR@<(B1hKHZr>{=Gb|#V zR^HJMjj75i8+ArF@7~I$%4N4GUf+7yKtkiU+6Yvwrke-B-ev2b0)&wvTwt;2dqPa)oK#gtcvrmZ!B@(Aj%qcD)}n{wcgmy zrX%jX3dSZ^nFfKg9*yq8N#7=J#6EYLPEcsBZNJds`#K|Ah+J0~&+E3{^~L}O{v|TL zfTuJ>o#{Z%J!!#FUM*W(4C3D;!yd>kc)9p}&mSjck;hChT{G+tq{z`Xm;0FPNm-Xv zxL$R*@X2F!_-9XGAbSA>{J$E?BdGb4K$Kl6>=L`>YqM*+{AOj2dQ`g^DhK>z`zs-a*jyDd3;8; z3BNvsA>m&~J$xE|hm`&f8??|%f{t3=K2DJCz(Uva28l|9uev%c3XGU=;AVDPoSHA< zw}?F+mu#rT-z|kazwV&~uq{3rThN_c4(0I~ZUtqRmL`Rr&j>ZUkEkNiZ*OWba=u7Y z@8**PYgP3a=8u%5GLaPbt7&xwO-;y(9IiO-F_o^l<;3xwklwE>Jxn{?bblkU^po?(|P<$3dXlnbW>-Dz9dX z=Ekn3$1!~q6xItagY$}?pMLKYojQCu2q`;*O-E_5mVazg&&PUe21-cd_PpWWi2;AG4IRmWxV z7gw~#05pdb6TP|yBn2rz^7B9~r+*0z?R)Z9?m=k~$y{<7R25d(^{?WfSAJI)Lz~wJ zL{z+-HFdXZcbR&CN&R!lN&P!?kjMd&F?Zcfg@RnaU-{ZfOTYh>1r4X>=L1wdqGBcg0I)BxbtpBdaI2Xyr3*&){h!g_8<|@{)1l5#Lgv5r)6C2hMKsmqd__rh zitk%N3njIlYUmPO{_TZ){3_^?vCAVUtDJ_}xNG%54MRpVnBb|{&X`-hSb5pzyGg=B z-``<&YCNR2pH9l%S{j8fA3cwna~5l@*zer_){@g=EL1?r^R?gBejxKB#UHB^v-TCQ zsf-^2EghkcdG)Fy53R@ADEEAwCfdIHDmQi&JT{$Z%oQ4#3P@mPJ@8*iC#+Y|{{4}W zawd^nKu5ren@dqE_>B~c6or#h!fXOt`66Wst+;0RqJw1E=Ylvx4NlrN-j0L=;=Guw z>a}~F9y{KvD;Y~^Pj*Lb$WD(BM@)w6c2VCCBzRiK%KL^;D!-P1O?xBpA*Kx0LXVcA zwjq?O9P^`*7E1em^@>Z+aL!t;Pk!B4F8{6wH3!Uu>+-_G4H7;VP(oE z3)rsQ=z`^MKr4Tzmg%?}v1q0I;{s)ADv9o3)FQPHsol&0>z z?LP(cK^3)PJPTyFd>18AM!4yw!o~-G`e&XDHmI77ot%|LMceC}U#G-MD_1$5KCE@O zXLY!<8zaQ1Cd6udRdl4x!IEFw9ZP%IK|JzZ=LXA%V}_%(pSAm){mGcvoUmfq$u@3` zTC~5>iOu9?E>F}?WlM>t772sY)s9ovG?bp*f&F~^GyQh4dZ+Ai`BFkF9nH3G{{*1cQ@Wii#sMQX%?QA*M+)MM5)_RP^wD(tn%7K-#I zx;d*(E{SSLwC4BS^S_c;X1ROkoR~_5X-=nQ_w(v(<-8u^kKU{yFA}&Pb}j2V{GPd} zPrpA{nk}@$M2)FfT)Nsqwq%jfqbr;serl_U?(NsGOw*^Csic6Up<_K?`rrFT7FnqpUoR-v=HXEZ@pu?%%w{-yA z*KVwl5!M^1V-Xo?1>Rb2YiKBMP6K45I<^n?n^z4OFA(Kb+L(;sr$rl8+9sv}Up`L4 z->>{~4KO@`oK0J3?{S~uc1=1m;gW}a7H&}j4 zub|8;j~5v0!&)!2QBz;3i^V7(B|f1vq0emb?%>M3;wg)2-peJoAU%hZ-D`l}!G<(7 znlsn+bJZVW2^L)a{oAjK&YLM)sx3iN-uPgL)tJaU06q=G1Xj35YiUt;zuHUgk?WV^ ze(N>gIo$p>M>dhj#bnH^jK_tkXS!6)x-M5+t;cn;mqhjZd9bI2Qf%Wc!Hv`U6tj$xmav7;1v~VO4!hf0 zWmVQ^1CTQPIa9~o2+g)`CMp@}+yh!*ikNqmzE{EVe3oo2nb1xLH)hD+{X5#K#%F(H z15_4Xi*KLFna|LPVmJ0#AA;6cDX|uqqx`}pV*`w;9lLIhHc!hP)m(m3bC=gQR-~DN z&tMlZ3*(h!r_08<|8SgLB5X497Uw$PKIdy=d)ihun)>^eU@m@ZypEXj-sjnL77jw) zIKPoQHeOc2*7wJ@2R!EWo(Qb7Q)k$ylJOZ=$Pf1f+Q=F^ne7%_P0JuL?kw(^%JFr& zXnNww!+1aJn*ApC2sR(?gKpwZ@giCS;;&PFq!+44hj)9Njj|T_o?n+ed%YPwr!SWC zy8+AeO~{qJSNRo-_vO8w#S=NivdAdsR6**;+}MILwhwBg?a&mgYeJ#c|JG8SO}V0- z>i4`eb~0K#1*o6BGo8@d7@-k=jpEPUacx?G3P-mhPvR(|;Q=rND`;?xZ26v`m@yNl z#OJ)_FPPo?u>KZlKo?$&j#GDNiSM2_P;!69n9R}iNc(`BunwWX1GC3o$G~Qj2p#jf z!?bFL-mP}`cG&f?w-%j`?fe$gXNWuPOu#062CWjDw7DC+(mdw*W^^&&$cu;3EFyTH zx+=0xa1@+Pc5epwm;5!IUfrF&Z7J08YthLa_P>UD;de+=_558%l6|*~n_}u{E7BSz zCVT&)98J{r3sbRBh24;YV{A{@wo!p!V~mc3P4s}T+!^$?PRHk+iM8to-{hqI(ruJM zbKuEGBV4n?C)d-li;mU{D|&b_eHIrd=g3Q9&tPp?m9M@gf?JWa`SjxLZ)?}$QuA)| zKjzy0@(f-R(zeQX)$jr;yjV!^E>hvj7gP&4^oN{o?Fv|8?=s5whR_W^#W25Y zDLM+i!Yuv$9L}r>-}w3?LtL{|U3s2U!3Ts)n67gKHS%ZBZWrBgjb>(>Psg4}goQ31 z3W#njzOs&5QVOw4RXl8?PWB*}zScBKb1rr-@yzD;;*?GIVdN?W)pKuCe==hnvG0n1 zP=MzXIv02RC$ro%O!=jjmbMmufx*)I_f__^p2;X_C_LM@;ZPY0 zzeMo6UJ8|RsD(;7OD=yFCtHZ*$CG)1ShCaoh$I??-r@`2^33z|Rt#>(#$PzwziKRrM;-DYb~SU}%ky~^0@O_7EHFp!Q9yu4(3a+4yBiM+})2o&uijs~w`7r)nEtW<;1 z8C5h~4mkyh{^;<=W>orbn8;%n?BJWqO`Vf@Y#SM5neKjDiNeh=gC zas!hVCqdVzRwIS&H;K@0Hpcr|)Y-jc`YbIUVN2=B>=3%zSWc>WU~zhF!L`$9_C^lT zOvgJ35tfof$$=9W8=iZ#okB3hMHjJ>w~?g~qjMr0dPx$Ma)JCYSkxlR@~fiTeoei1 zlo!T7N%xs4diELdYrp1KQB&Vq6bUFfp84kdk88|jxQ0eejp+TqW@7i8f)%ft8N)0u zAiYHj1KVI|KXUTc?G<)4bN97v{;DQMzoCrs!GQSD$lJB3jJ9Io4e~zDSN>+*_2pBf z$mFJ{tNGc|qqjAyLVI^%JZv=gdcKV$y>}d~Y94xvs{XaPsB2eph$XmR3v|-CL`Y^uDh^bMsX? zvry}U>7}b}#l<~xf5@Mm!F$w+vg*A$U%Likq8REP5=c1-cuSeduL(9Cp z_f^qtwms+FG#xMJDbS?zGq5!^%2V8zI)h6dsss{MF0it22(kmtU|-+c;<~7y{V@He zO@P}gjfiW>*T&Rut1$^xnQqy$PWPARG2bANJcCOJx1{)dIXv}!MKDV@F_s6s!54v> z#|@Eh54BiLRw~}m?$;LSPkmufo#Z1`RKQJAb0X;pU>8@pXeJG}{Ri7YCvpuZd;3*r z4G!)OTy3g6ZF@q>Zr`cAWjlIRGs?$#P>xA$0jdn{qe^y+4^hw0;4z)S;UH8;yTuhX z4auU86Zzk4i^3Xwf;-2nXHNhA*ZAZn@>9C^2vIN7W+-)n6*Jm(;o*I_<1@(}m`!Wh zgfsus)MH`M>aS^Fd>yqlRkZcRK71TA?0O(lCxvQG@sK6KA&~r748Liz{&rFmt8G^_ zD*3vJ1N}R#Dpx`!Ev3u+iy>O)1Z1;?V$fFV$Q0tjG?3Wa#xq>OzP=^E@JwQf) zQx_vlsqLF-JE6I%8uIGDSOAC^mAT5ccDDrBHA7nBt6=mTq!px*>oASug3X<46JNkZ zZ!5eZ5WIr-oD*Yr+sB6fU4rl$A*>_Hjzkh!Ebc9$Y$3^ZOHSlhQj&1@`*9R>EZEmf zoQ{G2qq#2+hx&W_m$WBJK0?VZl#1+YvJ6=YGng!ut+7>>Y}r~!*~^+J#yTe3NOtXZ z84V>;S;{C>cHwuQQJ?2~{jTrz{QdaPHSe?C=RW6N&+87^!*WHC%v(ROu);}G1k4M8 zu|wGf3GJn8IouSq;QrmXzYQ@@NQe;7N4I#P^dym%L=ZYxzhknD;{HD;&b$l!h^aKm zMcF+MZt)UWt(&a`x^Od@9yv|#r$M(h28lMNRieV{MKHFr1TH9KhwFa{TY*E+_Dc&o!i zC}+){;MK$jW@xVeD8_tAZ!9yrC5l*3h|9NV$H2vm4wCvOeq0i4g4EhvWd>0iIf1g~ zbIj9+s62UI(z}W{8lxyur|K5+@^tE&6Q#}wV;#!1eq`G0mHXj$4Wve#7W;a}kix*G zh8s=yxohH&#W}7Y`SsXV9GztB<<35$AuTNB2 znkZ{|wvR2;iv5NdIzG;Oav+uO%gki-2KsT@`sHsr3D}_;3wT z<`Qa^_hJkj((2$3y!m-@vMs?KWZWia_6uln8*x0>8JA%AMt<_P(CIT}7!uoUoyKL6 z$)+1BrLMs~rr7=(xA1b^@=I;b%X@alEh5$YuG#i|i~+TvnZZ?H)`Uu?HQ}2eYfx9z zINh}lx4$L!Zm;*DMYAzl{^*5{BW(Z6G}**MA?wgGa{=;Qk3-D7&Af>tmq9-jaz5gVj;N){^3+8U9 z-X(2)J(7vaQ+iFt3T?caSO{f7B~&gfhSIz7cFt41(*RVaW9HPJM$jq;vyEEg_sjJR zKlxLdkPWvim7ZY0zJaksVNIC8H4}yLqxffWPC5jcP(XOIYzcl}?&73X4!ZWMZ|exE zqJr)hVu3RJR;lP(VOsMZnC_9#wA)n->Ab1#M|X~7S(ikS0=!<-xT&G&Hli#yzRyJ- z4v~8%W%Upl!L@XcI9Bv14i`Lp>zuXdA*c4;E*Z|x!dMTSYy$^~ejGnp{LG-hT_Cz# zD3P1N&lj%4sGA*ay{=Fe1Pxh6MMEKT@~&!uf1U{h%gKQSkg440y$j=l)FLTpSsC&w zYxQ1Ng3-N)(!aA4rd^#kwi+@+3TUZTIbi-c#uP}c955l?AOl4neI}L&!)o-H2QM*( z#7M#sBG0MP6d@hdi#_r#OQMvu^Y@dG16n9j0FW{l_HQN94pWY#F~NsxFn!F7OClZi z&R>+1z{Wx_4A{J}!H~Hn>0pHxmXz1|?2eK8l9%~Y@U}cL5W9$&ij^_c|95GQuVDt; zv1FSmb?u$ZO#B1Qbv;?f@YcFU;fLXJ$XWZ}4uLU8C`9(*XnuVSGDoDpD7AeH!B8x4 zK?iBv3;`zw_fSUZuxlZPRCbxrugwfVe&yRtd%4RI=(GSYH8vK{MU*m%&4E+3(kRi z%i+L^TW99=a%0&>_SkNIr=CT-WBA$(A;D|tRE4e}b)J=>mp;KV13X-b7MATKwZIvY z?1dq*>*33|hhXJ;#pT)}!N;~LXN-Y4)E!#hS;XO-=BfVI8UO+dWjE{KrkCg}p0i@+qmj^iq_=vJ@Uq=-* z8w?3cLuEz84pTe(52psDOVoWQW7B-k);*pFsuVDIc~#zL!h%OMA8y=lTi4f{45W+`2R; zBMt(Td-C;n54$mv7AfCnYL~E6;sKGpIzhPQR%z+HFZ~|ww3{ZmmSXdSFYc8y&FiUy z52Jr-tb8)5H!}1)|3T1l;Y0lpImI)3Hny`gpu?uJaC}~RJm1FT+ncBHc@(46<+`ao zO1PjUw|YudL8yxAq`>^lBH5#*c4_F1;Ps)F^WFLhH-`-hmjq|sK0G=$URi!m#eae< zx(@kI!(svqjTDxBM|(@6w(|ZuC_x@gOPfMkHa{<{v`f%|aKNVKF_KD5zl! z>Y|<-hBDnbL=9pQ!r9G#4$$>8M#t?T_bf4Qq$Q~X&MshedWDb7FUR3Ja`(MnGXl!p zwmpf>NmgP)>%DH1cxku8GkkG%0}EGMef@}iy>9oRXvbt$ssEB_WzCZH&nD%A%}``n zK$fRGDR*xGX1tnwRprOjt)EYRzxerMic9zrwLscxrT0B?<*M~isFXZUXkk}jR?W(S zr%4&!p|Yam#Jt-;ke}Ndj!k-`m#_2O%$t&xjEtf%Q{@$E!ftnMrOaik-aeOcdwQs{ z^r$t*m&EVt%{`trNp8x^=JZE%)!Vx|>a4`&`)J2UjJSoIw1_o^U-*8$xG9Tqx$mTY z^(qs~Z%|UE?Yh$<6i30aj4*KbK?NcMg-oa2iQUF(^I8BUD+Co%%B=Bhd@8#vn=hU1 zD}j3G7IN-=`|u71LrS=S2ufUZfLA13`Vh6Uk0=;7AJ$I;`$j=>oRXnoL{$pzl=i#O zfU%reCgs?XLmaj0e5}h}dgu?YFO{&ndFMc&SN@81T*26AoNa}xe@a^La9gR%u$3Yh zTlTc7C~DnUR_W)grr@}4ogSZrd)v>bj6WWhtq6~qvMx01j(C_d$`N* z@;>M;aPGul%}K@n`KK!ubbY`o7uUUoj-Ur9dTpF_8mg`&N)Y((JYMbbX#^zJA&6BZ z9=3al0q`{8bc&--Fq9c1LPexfmmVoafCAJW7|74eEz+L{oIPz)72ui1Lo)qct*?RL zX^qPWT4*vmA23Z90kM8N@xZBO-t#pA0MHj7y!KAh(=rve#I*A&P~Z4VZkgVL0)W`(e(0`GLz_k<;*MBN3oB0n*6Y z9?G2Q&@(Ro)Z=&$PZAHXsZ55vDYCWw5HO+IS)1|W^J74~9q#k&NPx_W)E|$WY0Z5B zm+d#*eUx>%hkQzm%f|OXBmld5agW11OTWuk$Y9?`jh}=k92MTl@h@K`@PJ;x5OASs z#Od-1rX#USB?zkkEE3I*4=(o zp&n1BeDL+zYstOcww5pGH@En%xW1scW|ygE+qybeYo+5hQO_?HUQMp@3f63o*nhN} z?*1*iCE@)gKP}ur-%}dV)lSs6{a!A-g-@ls&b~@d{Kwo%;vOJS4Gi$* zKkcshydM0Z1RY7VudYHNl-@AvEbBW_G5{aO!Iq*2f(=E7@cdR?eRw(6GkLA8;5 zstX5Ot^)8C-z)-!ecL$1X>KI|*nT;HLUGV>{zsI8`}XWPKHv|-=s(Tt1CuLMSLO9 zI})%^c1x-XgJP1(m%gzF1|EkPm_Y!W`tM?Rr~xZhq!C_tabVX$3Bk_fdt@NI6y-Q^VX)4F62K;XAEc8k#jJR<+#UwW+ zqyPP)xHvX5`CSo@WQ3yLSljH3tTZVJhwss1@%dd0kD0)1?lr?_+&wg(Ozjmb<(g@X zQ@6h`5zzLlC9x>c@NUI%n*Q*Pc-;5;bM^x+D=S5m_OxFmmdtIVPx3nsq$B0v?$KdXsgPdhPQNbG@XRI5Sg(MhRqT^ST~n>8NxqsFF=m(%UWB>R8W z(XZvjiI#5iDS!#dXwyw|SI;ZxBl;=Bc)6)_ULLd@f5TD$;k1`Z(?L z2?7~_gSYY=X{0>B+6@Cf-eI90{0rLgS4nYk0$=X=*z^Tqn>i|vWOUx717_cWlTp#~ zadMBv4uh-WY}(@%Ze~S2l2jJ0r>^EuVUbmk-kwp#ufeTPbSCPKXe#v&*#1nva3vBF z)U6l4`%sJ9_T-!;;0m9c$w3ri7NhOm85xlofVa!`4jj6lTh-Gi;VBlA$b*$=3=9l! zdf4azqB6taoH1!!y*9^G-g0urSA4hSj>6*sr)>K%4_z(f1qe&-Ei;Yj-5=t&E55Us zrPu`P8Uvi8{LikNitQn}*i|zDjM3B`k2KWo#8VtAa=jr9Tj#af!dD@v)5ikvfUa6H zV@D0dw3eB7P6Tm2L1oI|@u9H9$*OO-btjU#ojK*l1dJ@RvD(IL_EgE4)1sWZ*7(Bj zx^;-Y;Z&fftFyj={= z3?3rwYK$09I4VH4Y0^>{ROlXkBH>peK)Wzx0~syi(rD z7i^H|@5@P1R8>f)&?BC4$xZB3)O#F1HP)?onjRQ7t334`Mx9Gu?E7lVkF3Mi{)efsmlshM34S{=(c1>K;B~ogy7~6Ki4kMz#xM1lS9iCD=H34GOV1^;`V?TXTnDuN1RmXRqht8Gc)_z0}!t#Lvi zaF{)W)icF<9Ia*X;x zHW8|+r|ipf+1Mni^LvTv&f~^AA6k@TD&~Q*(a90zdGlB{_7!7d`kbXw=oG(lpI|i<0kY^s0903$hR?~xN5JmpfT5YZqxSuespZ0tWLn&rI z0m|Die*FeH0!@{Sk9xC|v7pauZM4`Z6tgR0kMbqgM*;Z3{-WGz=NHD>Co_6_B)-;G z^(jcWm57@WzJI8#ezzfYIzhgqJ_GVzEH5bo{=DKS@pfeKs0}2=@dh{~bXSj8wU`A= zpU#K9zPprNMR|Pm>iR?qJ^r-nWxd%FXKzbVg+zfw*+9^un<$}8JldC9Kr`d~2(s;{ z6uk2vg$#azdD5X*W9CV^W1Q9t%7E^O%uCbOVKp$@0!OCiY?*`NaQz*@K1Bi-O?zfT z+fAzMFPf|>{%gP;v0mkg-qsFSq?-52IY8-l0LiXXJjIl=Md~sC_~?@#<2{eOM#*(6 zW=X&3*)8r^Y41w6?&GuebV8N?xlX$n)x=R%GVI>*K-jK@0Kl#;YqhX@Q$R4H76dqB zb-ay{wbpjV6g1roKj9gE(LEL8KD3LYrFIFns^u2OOHpLX$WC1q0!`%E@x=YxInR;% z=*yN6h^G$vE;(QJzi;N1QBWt8Bv}il+SE_BfQg{E?&2>IKNxmm12V*91oZg{gmrsZ z_+!DLAnSceB_#kZs&Q^AGs7Hz46#4&nDU+gO?+*-z~?PH;iD6yQ~jr7aRb?rA&7;q zfqR>WKIO!t@~r5BT7Wn}-|2IDXa-PQGM75N_P8}s04=_xh*!|G6<=H2-dkL)W z?%XLG;72|K{TrI#ue;+Kwi%fPOt1_l;m#ZZVPW!uKUd(oCx-I< zc#OJOf*G37oE7Tp*cdBN>iNZpTgfXAo-Q`k=;#`sjIN!sKO6WWwvHpQWf3MZ@nv7* zc0uydb}2j1kNMeEVC|D0sq`BltpeL3>%x)PO<7R%oxJ~589Qh#i7SkS+7gX~+8 zmlym~02Ej3_qUSIdXEKS`sP6QYk{f`k;Q^!K0SS@XBv3VO|h>$89JpJ->PeA)t@qM*Uw0oVrnKlBtFrf0j2DOw+hlsIeeOl5S5J&}_=LqHW=~uL)<$(OkcEd{<5S$;;{fW~HK=Wv72G|HAYE*Cv19s0#LAOmaAq_7JO$}? z`lL%drwFv+Jc&ZQH}>%5rRknwu>BJObh!~k%X#ATr|`XUEm!Qa%b^;j&gN++i7Xf= zW_ugVy9tUaOCYRmaCJ)f*2ql2aUSRF18j+b8=3mwVYZ@0wKJ)4-H;{F z3~#w2Tj{~@+F5e%<;l=b-tCHCk_TK`OL{Dw?uh`5_3cycl`o!8KIbrQ1o-913)^^( zU`E>SNy6JC*`+{uPHj@@;V^bF0Vy^-Pr5~Fc#1ZE2B**vsP9p{q-aaYZk{sf*I%$B zgMsQKN}>d|S)~HZ4np7Kk~qsKNeQx&W5PGkhK_^CBtjxxSY@+fl02Nh4~@qxvNZ6| zQvF^sqE{Kf^1&l*5s=7+BR`_svyakWl>=lS#LmV?OwK~O?M5ws|Sb37)fzz1|XCDz|o}yoa8gSEcQVp7pZv~Z=rnCnKQWPnd?HzUxptE)0h50V|76U-#ZRpF*D z%vN}7k0e5>6?aLuLu-}2;*5zRHWb&1-iBLdk`9l}PWMQZRvBX#Yd(eX8Vs8xDd{3Q zCb4ntJJE2t8tCV!_)y=a#$tL=NsiOq`sw=utfXgA^TkU8J=r}a0eJ7olSWm~=V0HZ zk5jThaF!;NEoW)oxvf_8yRzme_%?L-p7N}t@^rV#xFf-{EDTWtne#?k_lhZWJ`+_H zy;;gjebV@_nK(7O2-1DZXR2XsklDnk)X!T$>wuKnyUiJo9$d*2ELgNGznLeU2g3%t zdKr^ussUy;AD+R#b1K*%Gy23>;vr-K$t@m(9KG>S+9ir}fuR4>O=9+Ea{~wmYo|;+ zH{O2@yS$urdQU)?IQ?>b_30&A|r_;D7S zPn&}fip$G~i(c5}gyWY6%tK=maQ(WZ06bzcT4$CnZ)LRp7$B}2Bv`P8D}iFvT6fm^ z^X^j*E}h-c>G&B$%0j+xE+O)vVvPhM{3>O`^V zjmmK7zsY>8A2i0`OcEI=qwlFK`|G$4le(mOrhu3NJKA4q(B`Bs;tCJIK&n-oOJRX*4k*rYFx{ibx`AZq}@vG!>K1<-M(L+Rou z^;Eylm=8R;ZLf{_p_I@79Thct$dwjl6=J)L}pqV-7qp;SJWD=0dz`OlIv z_&4e+g*-O$+B=h&m^N?M(>iJfY<~vWKJ4(=yBKbQgA|HcVo0}&N9hNlZ_(BG>wk$f zVk9}hwTwLax#t!4iN1EWd zhBho=U8T>j1gN7huCz28{HU6IhyD6BO4z=4TRG8On4sAjOs3&62mvtb$*^M}Ae*{T zWc=by;G3P6y{my)G5E^p#I)003`zZ$&KordYb+eOxMmZiK41j7QDiza7Up&={wqsZ z1Vxl7;uQaBE)Y^u@s!(}fqyxjRaS!;qd?J|TQ#!_+W6We4#CZb;Kzoh=_jvaaeIX$ z*jEV+-$-*aq6f?@R=@;R8}B|`1`0ZuFz6SO0ka8ePAn@CB)9*}_TFfZ8VFEP@CYJm z4D~eB9!S=-W6Ssw#^r)%OQQ;M8J{-M+_{6wlW8x*NKIISf?)g+a;y*p+a%nk!M`2I zC3xrYD{&yLsXc*<5$sKauau6`GTa2o%dNa87m=ac^?aSMD^Zp|!hRRp3{99Dt6nC@ zE>UVKldyYeh&Aw7HHK;=0qkIw_hT!=1R>r6%1ZtGFvdlI?5Z348sJAJv7Qabj^P7i zg*6$Wr8V$Pv;Dv6Vj=pHTr5=W`_5c(w81W#@)9FCg^49z>_qmjj3)Kx9HHP3TrZWq zbtBr#85RgI2n8=Ug{%Ks%a}Zpl#nHYGK$bf#zMY?tb>=z##IY9M1u#YM7U<$gI3Xp zD6Mz5juEW_J}rj1ICJUshN8oJ5lHfiL(7-JdvF!oqx7n?XgfA;fK9Ftdn3Jrnr z)+U|^L;KCohhp-7?CFq@y)ar(E6-u1>taw+7Rn=m-l0DY{_j8zN^S@f`tLEMhI)s~ z)H1dkJ~(|4c*!Q6vK~HcCcyKZBG7w=hwqu|tsnqU`BS4ho2OJ_F;V@cw16Ig~5;s&KmuYPJ(*DXuZNeYHO( z7OD{(b%@@h-b0YA@loj7@^_vyK#A|edM>CZ6%-tYw1TaF<{7#hdNN=`{RqGvA12(n zm1FfM_CrAVh8@ip5cQq|<4DW@Ww1#hpnHs^kRxg)4%eJ%$V;KW^CaE_KAzdh&LF!F z^gezehwJY=zX2tBTW)uwo_s+L(cisc-}QH%is&-uL;d`@Ke$C#f8sw4ln)WP^9fOJ zRr)gMh*&@u=)Sj1rxi6bftx9ZDN6V6JTXX9_%6=Rgoa-Y)EgZ9JI}X3iSi^dGGf(9 z@KMnIW;~(~JfJ6ORn*Tlxc+(KwPXxdm!Q!AD_V1W-!sJi>@jfA`rvcMfDJJ~cXh|8 zWOUesHBO@%M^OC;m1psyztPL2E}+tZ74H4^5aXtTamj)Qf%tbJv1&l>g|}U3d)K_$ zl;%a%Gs!z4pa{^1!w@Nog;yR;aYDNGkmHU@Q@vWuUHd<6PeEJvO+QsoTQ-heD!#>2 zV?D;(_NuuKVI5>4051)1%lxJ~byasOKKOe!nL@K*!j8xt6dJH xd-?Ys{ +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#include + +#include +#include + +#include +#include +#include + +namespace predicted_path_checker +{ +using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_auto_planning_msgs::msg::TrajectoryPoint; +using TrajectoryPoints = std::vector; +using autoware_auto_perception_msgs::msg::PredictedObject; +using autoware_auto_perception_msgs::msg::PredictedObjects; +using geometry_msgs::msg::Pose; +using geometry_msgs::msg::TransformStamped; +using tier4_autoware_utils::Point2d; +using tier4_autoware_utils::Polygon2d; +using PointArray = std::vector; + +namespace bg = boost::geometry; + +struct CollisionCheckerParam +{ + double width_margin; + double z_axis_filtering_buffer; + bool enable_z_axis_obstacle_filtering; + double chattering_threshold; +}; + +struct PredictedObjectWithDetectionTime +{ + explicit PredictedObjectWithDetectionTime( + const rclcpp::Time & t, geometry_msgs::msg::Point & p, PredictedObject obj) + : detection_time(t), point(p), object(std::move(obj)) + { + } + + rclcpp::Time detection_time; + geometry_msgs::msg::Point point; + PredictedObject object; +}; + +class CollisionChecker +{ +public: + explicit CollisionChecker( + rclcpp::Node * node, std::shared_ptr debug_ptr); + + boost::optional> + checkTrajectoryForCollision( + TrajectoryPoints & predicted_trajectory_array, + PredictedObjects::ConstSharedPtr dynamic_objects); + + void setParam(const CollisionCheckerParam & param); + +private: + // Functions + + boost::optional> checkObstacleHistory( + const Pose & base_pose, const Polygon2d & one_step_move_vehicle_polygon2d, const double z_min, + const double z_max); + + boost::optional> checkDynamicObjects( + const Pose & base_pose, PredictedObjects::ConstSharedPtr dynamic_objects, + const Polygon2d & one_step_move_vehicle_polygon2d, const double z_min, const double z_max); + + void updatePredictedObjectHistory(const rclcpp::Time & now) + { + for (auto itr = predicted_object_history_.begin(); itr != predicted_object_history_.end();) { + const auto expired = (now - itr->detection_time).seconds() > param_.chattering_threshold; + + if (expired) { + itr = predicted_object_history_.erase(itr); + continue; + } + + itr++; + } + } + + // Parameter + CollisionCheckerParam param_; + + // Variables + std::shared_ptr debug_ptr_; + rclcpp::Node * node_; + vehicle_info_util::VehicleInfo vehicle_info_; + std::vector predicted_object_history_{}; +}; +} // namespace predicted_path_checker + +#endif // PREDICTED_PATH_CHECKER__COLLISION_CHECKER_HPP_ diff --git a/control/predicted_path_checker/include/predicted_path_checker/debug_marker.hpp b/control/predicted_path_checker/include/predicted_path_checker/debug_marker.hpp new file mode 100644 index 0000000000000..51feee6b3a70c --- /dev/null +++ b/control/predicted_path_checker/include/predicted_path_checker/debug_marker.hpp @@ -0,0 +1,92 @@ +// Copyright 2023 LeoDrive A.Ş. 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. +#ifndef PREDICTED_PATH_CHECKER__DEBUG_MARKER_HPP_ +#define PREDICTED_PATH_CHECKER__DEBUG_MARKER_HPP_ + +#include + +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#include + +#define EIGEN_MPL2_ONLY + +#include +#include +#include + +namespace predicted_path_checker +{ + +enum class PolygonType : int8_t { Vehicle = 0, Collision }; + +enum class PointType : int8_t { Stop = 0 }; + +enum class PoseType : int8_t { Stop = 0, Collision }; + +class PredictedPathCheckerDebugNode +{ +public: + explicit PredictedPathCheckerDebugNode(rclcpp::Node * node, const double base_link2front); + + ~PredictedPathCheckerDebugNode() {} + + bool pushPolygon( + const tier4_autoware_utils::Polygon2d & polygon, const double z, const PolygonType & type); + + bool pushPolygon(const std::vector & polygon, const PolygonType & type); + + bool pushPolyhedron( + const tier4_autoware_utils::Polygon2d & polyhedron, const double z_min, const double z_max, + const PolygonType & type); + + bool pushPolyhedron(const std::vector & polyhedron, const PolygonType & type); + + bool pushPose(const geometry_msgs::msg::Pose & pose, const PoseType & type); + + bool pushObstaclePoint(const geometry_msgs::msg::Point & obstacle_point, const PointType & type); + + visualization_msgs::msg::MarkerArray makeVirtualWallMarker(); + + visualization_msgs::msg::MarkerArray makeVisualizationMarker(); + + void publish(); + +private: + rclcpp::Publisher::SharedPtr virtual_wall_pub_; + rclcpp::Publisher::SharedPtr debug_viz_pub_; + rclcpp::Node * node_; + double base_link2front_; + + std::shared_ptr stop_pose_ptr_; + std::shared_ptr collision_pose_ptr_; + std::shared_ptr stop_obstacle_point_ptr_; + std::vector> vehicle_polygons_; + std::vector> collision_polygons_; + std::vector> vehicle_polyhedrons_; + std::vector> collision_polyhedrons_; +}; + +} // namespace predicted_path_checker + +#endif // PREDICTED_PATH_CHECKER__DEBUG_MARKER_HPP_ diff --git a/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp b/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp new file mode 100644 index 0000000000000..187d6b866337a --- /dev/null +++ b/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp @@ -0,0 +1,171 @@ +// Copyright 2023 LeoDrive A.Ş. 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. + +#ifndef PREDICTED_PATH_CHECKER__PREDICTED_PATH_CHECKER_NODE_HPP_ +#define PREDICTED_PATH_CHECKER__PREDICTED_PATH_CHECKER_NODE_HPP_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include +#include + +#include +#include + +namespace predicted_path_checker +{ +using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_auto_planning_msgs::msg::TrajectoryPoint; +using TrajectoryPoints = std::vector; +using autoware_auto_perception_msgs::msg::PredictedObjects; +using geometry_msgs::msg::Pose; +using geometry_msgs::msg::TransformStamped; +using tier4_autoware_utils::Point2d; +using tier4_autoware_utils::Polygon2d; + +struct NodeParam +{ + double update_rate; + double delay_time; + double max_deceleration; + double resample_interval; + double ego_nearest_dist_threshold; + double ego_nearest_yaw_threshold; + double stop_margin; + double min_trajectory_check_length; + double trajectory_check_time; + double distinct_point_distance_threshold; + double distinct_point_yaw_threshold; +}; + +enum class State { + DRIVE = 0, + EMERGENCY = 1, + PAUSE = 2, +}; + +class PredictedPathCheckerNode : public rclcpp::Node +{ +public: + explicit PredictedPathCheckerNode(const rclcpp::NodeOptions & node_options); + +private: + rclcpp::CallbackGroup::SharedPtr group_cli_; + + // Subscriber + std::shared_ptr self_pose_listener_; + rclcpp::Subscription::SharedPtr sub_dynamic_objects_; + rclcpp::Subscription::SharedPtr + sub_reference_trajectory_; + rclcpp::Subscription::SharedPtr + sub_predicted_trajectory_; + rclcpp::Subscription::SharedPtr sub_odom_; + rclcpp::Subscription::SharedPtr sub_accel_; + component_interface_utils::Subscription::SharedPtr sub_pause_state_; + + // Client + component_interface_utils::Client::SharedPtr cli_set_pause_; + + // Data Buffer + geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose_; + geometry_msgs::msg::Twist::ConstSharedPtr current_twist_; + geometry_msgs::msg::AccelWithCovarianceStamped::SharedPtr current_accel_; + PredictedObjects::ConstSharedPtr object_ptr_{nullptr}; + autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr reference_trajectory_; + autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr predicted_trajectory_; + control_interface::IsPaused::Message::ConstSharedPtr is_paused_ptr_{nullptr}; + + // Core + std::unique_ptr collision_checker_; + std::shared_ptr debug_ptr_; + + // Variables + State current_state_{State::DRIVE}; + vehicle_info_util::VehicleInfo vehicle_info_; + bool is_calling_set_pause_{false}; + bool is_paused_by_node_{false}; + + // Callback + void onDynamicObjects(PredictedObjects::ConstSharedPtr msg); + void onReferenceTrajectory(const autoware_auto_planning_msgs::msg::Trajectory::SharedPtr msg); + void onPredictedTrajectory(const autoware_auto_planning_msgs::msg::Trajectory::SharedPtr msg); + void onOdom(const nav_msgs::msg::Odometry::SharedPtr msg); + void onAccel(const geometry_msgs::msg::AccelWithCovarianceStamped::SharedPtr msg); + void onIsPaused(const control_interface::IsPaused::Message::ConstSharedPtr msg); + + // Timer + rclcpp::TimerBase::SharedPtr timer_; + void initTimer(double period_s); + + // Functions + bool isDataReady(); + + bool isDataTimeout(); + + bool isThereStopPointOnReferenceTrajectory( + const geometry_msgs::msg::Pose & pose, const TrajectoryPoints & reference_trajectory_array); + + void onTimer(); + + void checkVehicleState(diagnostic_updater::DiagnosticStatusWrapper & stat); + + TrajectoryPoints trimTrajectoryFromSelfPose( + const TrajectoryPoints & input, const Pose & self_pose) const; + + void sendRequest(bool make_stop_vehicle); + + bool isItDiscretePoint( + const TrajectoryPoints & reference_trajectory, const TrajectoryPoint & collision_point) const; + + static Trajectory cutTrajectory(const Trajectory & trajectory, const double length); + + size_t insertStopPoint( + TrajectoryPoints & trajectory, const geometry_msgs::msg::Point collision_point); + + void extendTrajectoryPointsArray(TrajectoryPoints & trajectory); + + static std::pair calculateProjectedVelAndAcc( + const PredictedObject & object, const TrajectoryPoint & trajectory_point); + + // Parameters + CollisionCheckerParam collision_checker_param_; + NodeParam node_param_; + + // Diagnostic Updater + diagnostic_updater::Updater updater_; +}; +} // namespace predicted_path_checker + +#endif // PREDICTED_PATH_CHECKER__PREDICTED_PATH_CHECKER_NODE_HPP_ diff --git a/control/predicted_path_checker/include/predicted_path_checker/utils.hpp b/control/predicted_path_checker/include/predicted_path_checker/utils.hpp new file mode 100644 index 0000000000000..ddf8456868b8e --- /dev/null +++ b/control/predicted_path_checker/include/predicted_path_checker/utils.hpp @@ -0,0 +1,94 @@ +// Copyright 2023 LeoDrive A.Ş. 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. + +#ifndef PREDICTED_PATH_CHECKER__UTILS_HPP_ +#define PREDICTED_PATH_CHECKER__UTILS_HPP_ + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include + +namespace utils +{ + +using autoware_auto_perception_msgs::msg::PredictedObject; +using autoware_auto_perception_msgs::msg::PredictedObjects; +using autoware_auto_planning_msgs::msg::TrajectoryPoint; +using diagnostic_msgs::msg::DiagnosticStatus; +using diagnostic_msgs::msg::KeyValue; +using geometry_msgs::msg::Point; +using geometry_msgs::msg::Pose; +using geometry_msgs::msg::TransformStamped; +using std_msgs::msg::Header; +using tier4_autoware_utils::Point2d; +using tier4_autoware_utils::Polygon2d; +using vehicle_info_util::VehicleInfo; +using PointArray = std::vector; + +using TrajectoryPoints = std::vector; + +void appendPointToPolygon(Polygon2d & polygon, const geometry_msgs::msg::Point & geom_point); + +Polygon2d createOneStepPolygon( + const geometry_msgs::msg::Pose & base_step_pose, const geometry_msgs::msg::Pose & next_step_pose, + const vehicle_info_util::VehicleInfo & vehicle_info, const double expand_width); + +TrajectoryPoint calcInterpolatedPoint( + const TrajectoryPoints & trajectory, const geometry_msgs::msg::Point & target_point, + const size_t segment_idx, const bool use_zero_order_hold_for_twist); + +std::pair findStopPoint( + TrajectoryPoints & predicted_trajectory_array, const size_t collision_idx, + const double stop_margin, vehicle_info_util::VehicleInfo & vehicle_info); + +bool isInBrakeDistance( + const TrajectoryPoints & trajectory, const size_t stop_idx, const double relative_velocity, + const double relative_acceleration, const double max_deceleration, const double delay_time_sec); + +TrajectoryPoint getExtendTrajectoryPoint( + const double extend_distance, const TrajectoryPoint & goal_point); + +bool intersectsInZAxis(const PredictedObject & object, const double z_min, const double z_max); + +void getNearestPointForPredictedObject( + const PointArray & points, const Pose & base_pose, + geometry_msgs::msg::Point * nearest_collision_point); + +Polygon2d convertBoundingBoxObjectToGeometryPolygon( + const Pose & current_pose, const double & base_to_front, const double & base_to_rear, + const double & base_to_width); + +Polygon2d convertCylindricalObjectToGeometryPolygon( + const Pose & current_pose, const autoware_auto_perception_msgs::msg::Shape & obj_shape); + +Polygon2d convertPolygonObjectToGeometryPolygon( + const Pose & current_pose, const autoware_auto_perception_msgs::msg::Shape & obj_shape); + +} // namespace utils + +#endif // PREDICTED_PATH_CHECKER__UTILS_HPP_ diff --git a/control/predicted_path_checker/launch/predicted_path_checker.launch.xml b/control/predicted_path_checker/launch/predicted_path_checker.launch.xml new file mode 100755 index 0000000000000..a35c11b80c1f7 --- /dev/null +++ b/control/predicted_path_checker/launch/predicted_path_checker.launch.xml @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/control/predicted_path_checker/package.xml b/control/predicted_path_checker/package.xml new file mode 100644 index 0000000000000..ac072ed685b8f --- /dev/null +++ b/control/predicted_path_checker/package.xml @@ -0,0 +1,45 @@ + + + + predicted_path_checker + 0.1.0 + The predicted_path_checker package + Berkay Karaman + Apache License 2.0 + + ament_cmake + + autoware_cmake + + autoware_auto_perception_msgs + autoware_auto_planning_msgs + boost + component_interface_specs + component_interface_utils + diagnostic_updater + eigen + geometry_msgs + motion_utils + nav_msgs + rclcpp + rclcpp_components + sensor_msgs + std_msgs + tf2 + tf2_eigen + tf2_geometry_msgs + tf2_ros + tier4_autoware_utils + tier4_control_msgs + tier4_external_api_msgs + tier4_planning_msgs + vehicle_info_util + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/control/predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp b/control/predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp new file mode 100644 index 0000000000000..ff88c96115098 --- /dev/null +++ b/control/predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp @@ -0,0 +1,314 @@ +// Copyright 2022 LeoDrive A.Ş. 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 "predicted_path_checker/collision_checker.hpp" + +#include +#include + +#include +#include +#include + +namespace predicted_path_checker +{ +CollisionChecker::CollisionChecker( + rclcpp::Node * node, std::shared_ptr debug_ptr) +: debug_ptr_(std::move(debug_ptr)), + node_(node), + vehicle_info_(vehicle_info_util::VehicleInfoUtil(*node).getVehicleInfo()) +{ +} + +void CollisionChecker::setParam(const CollisionCheckerParam & param) +{ + param_ = param; +} + +boost::optional> +CollisionChecker::checkTrajectoryForCollision( + TrajectoryPoints & predicted_trajectory_array, PredictedObjects::ConstSharedPtr dynamic_objects) +{ + // It checks the collision, if there is a collision, it updates the predicted_trajectory_array and + // returns the index of the stop point. + // If there is no collision, it returns boost::none. + const auto now = node_->now(); + + updatePredictedObjectHistory(now); + if (dynamic_objects->objects.empty() && predicted_object_history_.empty()) { + return boost::none; + } + + for (size_t i = 0; i < predicted_trajectory_array.size() - 1; i++) { + // create one step circle center for vehicle + const auto & p_front = predicted_trajectory_array.at(i).pose; + const auto & p_back = predicted_trajectory_array.at(i + 1).pose; + const auto z_min = std::min(p_front.position.z, p_back.position.z); + const auto z_max = std::max(p_front.position.z, p_back.position.z) + + vehicle_info_.max_height_offset_m + param_.z_axis_filtering_buffer; + + // create one-step polygon for vehicle + Polygon2d one_step_move_vehicle_polygon2d = + utils::createOneStepPolygon(p_front, p_back, vehicle_info_, param_.width_margin); + if (param_.enable_z_axis_obstacle_filtering) { + debug_ptr_->pushPolyhedron( + one_step_move_vehicle_polygon2d, z_min, z_max, PolygonType::Vehicle); + } else { + debug_ptr_->pushPolygon( + one_step_move_vehicle_polygon2d, p_front.position.z, PolygonType::Vehicle); + } + + // check obstacle history + auto found_collision_at_history = + checkObstacleHistory(p_front, one_step_move_vehicle_polygon2d, z_min, z_max); + + auto found_collision_at_dynamic_objects = + checkDynamicObjects(p_front, dynamic_objects, one_step_move_vehicle_polygon2d, z_min, z_max); + + if (found_collision_at_dynamic_objects || found_collision_at_history) { + double distance_to_current = std::numeric_limits::max(); + double distance_to_history = std::numeric_limits::max(); + if (found_collision_at_dynamic_objects) { + distance_to_current = tier4_autoware_utils::calcDistance2d( + p_front, found_collision_at_dynamic_objects.get().first); + } + if (found_collision_at_history) { + distance_to_history = + tier4_autoware_utils::calcDistance2d(p_front, found_collision_at_history.get().first); + } else { + predicted_object_history_.clear(); + } + + if (param_.enable_z_axis_obstacle_filtering) { + debug_ptr_->pushPolyhedron( + one_step_move_vehicle_polygon2d, z_min, z_max, PolygonType::Collision); + } else { + debug_ptr_->pushPolygon( + one_step_move_vehicle_polygon2d, p_front.position.z, PolygonType::Collision); + } + + if (distance_to_current > distance_to_history) { + debug_ptr_->pushObstaclePoint(found_collision_at_history->first, PointType::Stop); + return found_collision_at_history; + } + + predicted_object_history_.emplace_back( + now, found_collision_at_dynamic_objects.get().first, + found_collision_at_dynamic_objects.get().second); + debug_ptr_->pushObstaclePoint(found_collision_at_dynamic_objects->first, PointType::Stop); + return found_collision_at_dynamic_objects; + } + } + return boost::none; +} + +boost::optional> +CollisionChecker::checkObstacleHistory( + const Pose & base_pose, const Polygon2d & one_step_move_vehicle_polygon2d, const double z_min, + const double z_max) +{ + if (predicted_object_history_.empty()) { + return boost::none; + } + + std::vector> collision_points_in_history; + for (const auto & obj_history : predicted_object_history_) { + if (param_.enable_z_axis_obstacle_filtering) { + if (!utils::intersectsInZAxis(obj_history.object, z_min, z_max)) { + continue; + } + } + const auto & point = obj_history.point; + const Point2d point2d(point.x, point.y); + if (bg::within(point2d, one_step_move_vehicle_polygon2d)) { + collision_points_in_history.emplace_back(point, obj_history.object); + } + } + if (!collision_points_in_history.empty()) { + double min_norm = 0.0; + bool is_init = false; + std::pair nearest_collision_object_with_point; + for (const auto & p : collision_points_in_history) { + double norm = tier4_autoware_utils::calcDistance2d(p.first, base_pose); + if (norm < min_norm || !is_init) { + min_norm = norm; + nearest_collision_object_with_point = p; + is_init = true; + } + } + return boost::make_optional(nearest_collision_object_with_point); + } + return boost::none; +} + +boost::optional> +CollisionChecker::checkDynamicObjects( + const Pose & base_pose, PredictedObjects::ConstSharedPtr dynamic_objects, + const Polygon2d & one_step_move_vehicle_polygon2d, const double z_min, const double z_max) +{ + if (dynamic_objects->objects.empty()) { + return boost::none; + } + for (const auto & obj : dynamic_objects->objects) { + if (param_.enable_z_axis_obstacle_filtering) { + if (!utils::intersectsInZAxis(obj, z_min, z_max)) { + continue; + } + } + if (obj.shape.type == autoware_auto_perception_msgs::msg::Shape::CYLINDER) { + Polygon2d object_polygon{}; + object_polygon = utils::convertCylindricalObjectToGeometryPolygon( + obj.kinematics.initial_pose_with_covariance.pose, obj.shape); + const auto found_collision_points = + bg::intersects(one_step_move_vehicle_polygon2d, object_polygon); + + if (found_collision_points) { + geometry_msgs::msg::Point nearest_collision_point; + + std::vector collision_points; + PointArray collision_point_array; + bg::intersection(one_step_move_vehicle_polygon2d, object_polygon, collision_points); + for (const auto & point : collision_points) { + geometry_msgs::msg::Point p; + p.x = point.x(); + p.y = point.y(); + collision_point_array.push_back(p); + } + + // Also check the corner points + + for (const auto & point : object_polygon.outer()) { + if (bg::within(point, one_step_move_vehicle_polygon2d)) { + geometry_msgs::msg::Point p; + p.x = point.x(); + p.y = point.y(); + collision_point_array.push_back(p); + } + } + + utils::getNearestPointForPredictedObject( + collision_point_array, base_pose, &nearest_collision_point); + + if (param_.enable_z_axis_obstacle_filtering) { + debug_ptr_->pushPolyhedron(object_polygon, z_min, z_max, PolygonType::Collision); + } else { + debug_ptr_->pushPolygon( + object_polygon, obj.kinematics.initial_pose_with_covariance.pose.position.z, + PolygonType::Collision); + } + + return boost::make_optional(std::make_pair(nearest_collision_point, obj)); + } + + } else if (obj.shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { + const double & length_m = obj.shape.dimensions.x / 2; + const double & width_m = obj.shape.dimensions.y / 2; + Polygon2d object_polygon{}; + object_polygon = utils::convertBoundingBoxObjectToGeometryPolygon( + obj.kinematics.initial_pose_with_covariance.pose, length_m, length_m, width_m); + + const auto found_collision_points = + bg::intersects(one_step_move_vehicle_polygon2d, object_polygon); + + if (found_collision_points) { + geometry_msgs::msg::Point nearest_collision_point; + + std::vector collision_points; + PointArray collision_point_array; + bg::intersection(one_step_move_vehicle_polygon2d, object_polygon, collision_points); + for (const auto & point : collision_points) { + geometry_msgs::msg::Point p; + p.x = point.x(); + p.y = point.y(); + collision_point_array.push_back(p); + } + + // Also check the corner points + + for (const auto & point : object_polygon.outer()) { + if (bg::within(point, one_step_move_vehicle_polygon2d)) { + geometry_msgs::msg::Point p; + p.x = point.x(); + p.y = point.y(); + collision_point_array.push_back(p); + } + } + + utils::getNearestPointForPredictedObject( + collision_point_array, base_pose, &nearest_collision_point); + + if (param_.enable_z_axis_obstacle_filtering) { + debug_ptr_->pushPolyhedron(object_polygon, z_min, z_max, PolygonType::Collision); + } else { + debug_ptr_->pushPolygon( + object_polygon, obj.kinematics.initial_pose_with_covariance.pose.position.z, + PolygonType::Collision); + } + + return boost::make_optional(std::make_pair(nearest_collision_point, obj)); + } + } else if (obj.shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON) { + Polygon2d object_polygon{}; + object_polygon = utils::convertPolygonObjectToGeometryPolygon( + obj.kinematics.initial_pose_with_covariance.pose, obj.shape); + + const auto found_collision_points = + bg::intersects(one_step_move_vehicle_polygon2d, object_polygon); + + if (found_collision_points) { + geometry_msgs::msg::Point nearest_collision_point; + + std::vector collision_points; + PointArray collision_point_array; + bg::intersection(one_step_move_vehicle_polygon2d, object_polygon, collision_points); + for (const auto & point : collision_points) { + geometry_msgs::msg::Point p; + p.x = point.x(); + p.y = point.y(); + collision_point_array.push_back(p); + } + + // Also check the corner points + + for (const auto & point : object_polygon.outer()) { + if (bg::within(point, one_step_move_vehicle_polygon2d)) { + geometry_msgs::msg::Point p; + p.x = point.x(); + p.y = point.y(); + collision_point_array.push_back(p); + } + } + utils::getNearestPointForPredictedObject( + collision_point_array, base_pose, &nearest_collision_point); + + if (param_.enable_z_axis_obstacle_filtering) { + debug_ptr_->pushPolyhedron(object_polygon, z_min, z_max, PolygonType::Collision); + } else { + debug_ptr_->pushPolygon( + object_polygon, obj.kinematics.initial_pose_with_covariance.pose.position.z, + PolygonType::Collision); + } + + return boost::make_optional(std::make_pair(nearest_collision_point, obj)); + } + } else { + RCLCPP_WARN_THROTTLE( + node_->get_logger(), *node_->get_clock(), 3000, "Object type is not supported. type: %d", + obj.shape.type); + } + } + return boost::none; +} + +} // namespace predicted_path_checker diff --git a/control/predicted_path_checker/src/predicted_path_checker_node/debug_marker.cpp b/control/predicted_path_checker/src/predicted_path_checker_node/debug_marker.cpp new file mode 100644 index 0000000000000..b3c5b8a8e8707 --- /dev/null +++ b/control/predicted_path_checker/src/predicted_path_checker_node/debug_marker.cpp @@ -0,0 +1,329 @@ +// Copyright 2023 LeoDrive A.Ş. 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 "predicted_path_checker/debug_marker.hpp" + +#include +#include + +#ifdef ROS_DISTRO_GALACTIC +#include +#else +#include +#endif + +#include + +#include +#include + +using motion_utils::createDeletedStopVirtualWallMarker; +using motion_utils::createStopVirtualWallMarker; +using tier4_autoware_utils::appendMarkerArray; +using tier4_autoware_utils::calcOffsetPose; +using tier4_autoware_utils::createDefaultMarker; +using tier4_autoware_utils::createMarkerColor; +using tier4_autoware_utils::createMarkerOrientation; +using tier4_autoware_utils::createMarkerScale; +using tier4_autoware_utils::createPoint; + +namespace predicted_path_checker +{ +PredictedPathCheckerDebugNode::PredictedPathCheckerDebugNode( + rclcpp::Node * node, const double base_link2front) +: node_(node), base_link2front_(base_link2front) +{ + virtual_wall_pub_ = + node->create_publisher("~/debug/virtual_wall", 1); + debug_viz_pub_ = + node_->create_publisher("~/debug/marker", 1); +} + +bool PredictedPathCheckerDebugNode::pushPolygon( + const tier4_autoware_utils::Polygon2d & polygon, const double z, const PolygonType & type) +{ + std::vector eigen_polygon; + for (const auto & point : polygon.outer()) { + Eigen::Vector3d eigen_point; + eigen_point << point.x(), point.y(), z; + eigen_polygon.push_back(eigen_point); + } + return pushPolygon(eigen_polygon, type); +} + +bool PredictedPathCheckerDebugNode::pushPolygon( + const std::vector & polygon, const PolygonType & type) +{ + switch (type) { + case PolygonType::Vehicle: + if (!polygon.empty()) { + vehicle_polygons_.push_back(polygon); + } + return true; + case PolygonType::Collision: + if (!polygon.empty()) { + collision_polygons_.push_back(polygon); + } + return true; + default: + return false; + } +} + +bool PredictedPathCheckerDebugNode::pushPolyhedron( + const tier4_autoware_utils::Polygon2d & polyhedron, const double z_min, const double z_max, + const PolygonType & type) +{ + std::vector eigen_polyhedron; + for (const auto & point : polyhedron.outer()) { + eigen_polyhedron.emplace_back(point.x(), point.y(), z_min); + eigen_polyhedron.emplace_back(point.x(), point.y(), z_max); + } + + return pushPolyhedron(eigen_polyhedron, type); +} + +bool PredictedPathCheckerDebugNode::pushPolyhedron( + const std::vector & polyhedron, const PolygonType & type) +{ + switch (type) { + case PolygonType::Vehicle: + if (!polyhedron.empty()) { + vehicle_polyhedrons_.push_back(polyhedron); + } + return true; + case PolygonType::Collision: + if (!polyhedron.empty()) { + collision_polyhedrons_.push_back(polyhedron); + } + return true; + default: + return false; + } +} + +bool PredictedPathCheckerDebugNode::pushPose( + const geometry_msgs::msg::Pose & pose, const PoseType & type) +{ + switch (type) { + case PoseType::Stop: + stop_pose_ptr_ = std::make_shared(pose); + return true; + case PoseType::Collision: + collision_pose_ptr_ = std::make_shared(pose); + return true; + default: + return false; + } +} + +bool PredictedPathCheckerDebugNode::pushObstaclePoint( + const geometry_msgs::msg::Point & obstacle_point, const PointType & type) +{ + switch (type) { + case PointType::Stop: + stop_obstacle_point_ptr_ = std::make_shared(obstacle_point); + return true; + default: + return false; + } +} + +void PredictedPathCheckerDebugNode::publish() +{ + /* publish debug marker for rviz */ + const auto virtual_wall_msg = makeVirtualWallMarker(); + virtual_wall_pub_->publish(virtual_wall_msg); + + /* publish debug marker for rviz */ + const auto visualization_msg = makeVisualizationMarker(); + debug_viz_pub_->publish(visualization_msg); + + /* reset variables */ + vehicle_polygons_.clear(); + collision_polygons_.clear(); + vehicle_polyhedrons_.clear(); + collision_polyhedrons_.clear(); + collision_pose_ptr_ = nullptr; + stop_pose_ptr_ = nullptr; + stop_obstacle_point_ptr_ = nullptr; +} + +visualization_msgs::msg::MarkerArray PredictedPathCheckerDebugNode::makeVirtualWallMarker() +{ + visualization_msgs::msg::MarkerArray msg; + rclcpp::Time current_time = node_->now(); + + if (stop_pose_ptr_ != nullptr) { + const auto p = calcOffsetPose(*stop_pose_ptr_, base_link2front_, 0.0, 0.0); + const auto markers = + createStopVirtualWallMarker(p, "obstacle on predicted path", current_time, 0); + appendMarkerArray(markers, &msg); + } else { + const auto markers = createDeletedStopVirtualWallMarker(current_time, 0); + appendMarkerArray(markers, &msg); + } + + if (collision_pose_ptr_ != nullptr) { + const auto markers = + createStopVirtualWallMarker(*collision_pose_ptr_, "collision_point", current_time, 1); + appendMarkerArray(markers, &msg); + } else { + const auto markers = createDeletedStopVirtualWallMarker(current_time, 1); + appendMarkerArray(markers, &msg); + } + + return msg; +} + +visualization_msgs::msg::MarkerArray PredictedPathCheckerDebugNode::makeVisualizationMarker() +{ + visualization_msgs::msg::MarkerArray msg; + rclcpp::Time current_time = node_->now(); + + // cube + if (!vehicle_polyhedrons_.empty()) { + auto marker = createDefaultMarker( + "map", current_time, "detection_cubes", 0, visualization_msgs::msg::Marker::LINE_LIST, + createMarkerScale(0.01, 0.0, 0.0), createMarkerColor(0.0, 1.0, 0.0, 0.999)); + + for (size_t i = 0; i < vehicle_polyhedrons_.size(); ++i) { + for (size_t j = 0; j < vehicle_polyhedrons_.at(i).size(); ++j) { + const auto & p = vehicle_polyhedrons_.at(i).at(j); + marker.points.push_back(createPoint(p.x(), p.y(), p.z())); + } + } + + for (size_t i = 0; i < vehicle_polyhedrons_.size(); ++i) { + for (size_t j = 0; j + 2 < vehicle_polyhedrons_.at(i).size(); ++j) { + const auto & p = vehicle_polyhedrons_.at(i).at(j); + marker.points.push_back(createPoint(p.x(), p.y(), p.z())); + const auto & p1 = vehicle_polyhedrons_.at(i).at(j + 2); + marker.points.push_back(createPoint(p1.x(), p1.y(), p1.z())); + } + const auto & p = vehicle_polyhedrons_.at(i).at(1); + marker.points.push_back(createPoint(p.x(), p.y(), p.z())); + const auto & p1 = vehicle_polyhedrons_.at(i).at(vehicle_polyhedrons_.at(i).size() - 1); + marker.points.push_back(createPoint(p1.x(), p1.y(), p1.z())); + const auto & p2 = vehicle_polyhedrons_.at(i).at(0); + marker.points.push_back(createPoint(p2.x(), p2.y(), p2.z())); + const auto & p3 = vehicle_polyhedrons_.at(i).at(vehicle_polyhedrons_.at(i).size() - 2); + marker.points.push_back(createPoint(p3.x(), p3.y(), p3.z())); + } + + msg.markers.push_back(marker); + } + + if (!collision_polyhedrons_.empty()) { + auto marker = createDefaultMarker( + "map", current_time, "collision_cubes", 0, visualization_msgs::msg::Marker::LINE_LIST, + createMarkerScale(0.05, 0.0, 0.0), createMarkerColor(1.0, 0.0, 0.0, 0.999)); + + for (size_t i = 0; i < collision_polyhedrons_.size(); ++i) { + for (size_t j = 0; j < collision_polyhedrons_.at(i).size(); ++j) { + const auto & p = collision_polyhedrons_.at(i).at(j); + marker.points.push_back(createPoint(p.x(), p.y(), p.z())); + } + } + + for (size_t i = 0; i < collision_polyhedrons_.size(); ++i) { + for (size_t j = 0; j + 2 < collision_polyhedrons_.at(i).size(); ++j) { + const auto & p = collision_polyhedrons_.at(i).at(j); + marker.points.push_back(createPoint(p.x(), p.y(), p.z())); + const auto & p1 = collision_polyhedrons_.at(i).at(j + 2); + marker.points.push_back(createPoint(p1.x(), p1.y(), p1.z())); + } + const auto & p = collision_polyhedrons_.at(i).at(1); + marker.points.push_back(createPoint(p.x(), p.y(), p.z())); + const auto & p1 = collision_polyhedrons_.at(i).at(collision_polyhedrons_.at(i).size() - 1); + marker.points.push_back(createPoint(p1.x(), p1.y(), p1.z())); + const auto & p2 = collision_polyhedrons_.at(i).at(0); + marker.points.push_back(createPoint(p2.x(), p2.y(), p2.z())); + const auto & p3 = collision_polyhedrons_.at(i).at(collision_polyhedrons_.at(i).size() - 2); + marker.points.push_back(createPoint(p3.x(), p3.y(), p3.z())); + } + + msg.markers.push_back(marker); + } + + // polygon + if (!vehicle_polygons_.empty()) { + auto marker = createDefaultMarker( + "map", current_time, "detection_polygons", 0, visualization_msgs::msg::Marker::LINE_LIST, + createMarkerScale(0.01, 0.0, 0.0), createMarkerColor(0.0, 1.0, 0.0, 0.999)); + + for (size_t i = 0; i < vehicle_polygons_.size(); ++i) { + for (size_t j = 0; j < vehicle_polygons_.at(i).size(); ++j) { + { + const auto & p = vehicle_polygons_.at(i).at(j); + marker.points.push_back(createPoint(p.x(), p.y(), p.z())); + } + if (j + 1 == vehicle_polygons_.at(i).size()) { + const auto & p = vehicle_polygons_.at(i).at(0); + marker.points.push_back(createPoint(p.x(), p.y(), p.z())); + } else { + const auto & p = vehicle_polygons_.at(i).at(j + 1); + marker.points.push_back(createPoint(p.x(), p.y(), p.z())); + } + } + } + msg.markers.push_back(marker); + } + + if (!collision_polygons_.empty()) { + auto marker = createDefaultMarker( + "map", current_time, "collision_polygons", 0, visualization_msgs::msg::Marker::LINE_LIST, + createMarkerScale(0.05, 0.0, 0.0), createMarkerColor(1.0, 0.0, 0.0, 0.999)); + + for (size_t i = 0; i < collision_polygons_.size(); ++i) { + for (size_t j = 0; j < collision_polygons_.at(i).size(); ++j) { + { + const auto & p = collision_polygons_.at(i).at(j); + marker.points.push_back(createPoint(p.x(), p.y(), p.z())); + } + if (j + 1 == collision_polygons_.at(i).size()) { + const auto & p = collision_polygons_.at(i).at(0); + marker.points.push_back(createPoint(p.x(), p.y(), p.z())); + } else { + const auto & p = collision_polygons_.at(i).at(j + 1); + marker.points.push_back(createPoint(p.x(), p.y(), p.z())); + } + } + } + msg.markers.push_back(marker); + } + + if (stop_obstacle_point_ptr_ != nullptr) { + auto marker = createDefaultMarker( + "map", current_time, "stop_obstacle_point", 0, visualization_msgs::msg::Marker::SPHERE, + createMarkerScale(0.25, 0.25, 0.25), createMarkerColor(1.0, 0.0, 0.0, 0.999)); + marker.pose.position = *stop_obstacle_point_ptr_; + msg.markers.push_back(marker); + } + + if (stop_obstacle_point_ptr_ != nullptr) { + auto marker = createDefaultMarker( + "map", current_time, "stop_obstacle_text", 0, + visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.0, 0.0, 1.0), + createMarkerColor(1.0, 1.0, 1.0, 0.999)); + marker.pose.position = *stop_obstacle_point_ptr_; + marker.pose.position.z += 2.0; + marker.text = "!"; + msg.markers.push_back(marker); + } + + return msg; +} + +} // namespace predicted_path_checker diff --git a/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp b/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp new file mode 100644 index 0000000000000..24fdb6c2e1c8d --- /dev/null +++ b/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp @@ -0,0 +1,526 @@ +// Copyright 2023 LeoDrive A.Ş. 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 "predicted_path_checker/predicted_path_checker_node.hpp" + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace predicted_path_checker +{ +PredictedPathCheckerNode::PredictedPathCheckerNode(const rclcpp::NodeOptions & node_options) +: Node("predicted_path_checker_node", node_options), updater_(this) +{ + using std::placeholders::_1; + + const auto adaptor = component_interface_utils::NodeAdaptor(this); + group_cli_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + adaptor.init_cli(cli_set_pause_, group_cli_); + adaptor.init_sub(sub_pause_state_, this, &PredictedPathCheckerNode::onIsPaused); + vehicle_info_ = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + + // Node Parameter + node_param_.update_rate = declare_parameter("update_rate", 10.0); + node_param_.ego_nearest_dist_threshold = declare_parameter("ego_nearest_dist_threshold", 3.0); + node_param_.ego_nearest_yaw_threshold = declare_parameter("ego_nearest_yaw_threshold", 1.046); + node_param_.max_deceleration = declare_parameter("max_deceleration", 1.5); + node_param_.delay_time = declare_parameter("delay_time", 0.17); + node_param_.stop_margin = declare_parameter("stop_margin", 0.5); + node_param_.min_trajectory_check_length = declare_parameter("min_trajectory_check_length", 1.5); + node_param_.trajectory_check_time = declare_parameter("trajectory_check_time", 3.0); + node_param_.resample_interval = declare_parameter("resample_interval", 0.5); + node_param_.distinct_point_distance_threshold = + declare_parameter("distinct_point_distance_threshold", 0.3); + node_param_.distinct_point_yaw_threshold = declare_parameter("distinct_point_yaw_threshold", 5.0); + + // Collision Checker Parameter + collision_checker_param_.width_margin = + declare_parameter("collision_checker_params.width_margin", 0.2); + collision_checker_param_.enable_z_axis_obstacle_filtering = + declare_parameter("collision_checker_params.enable_z_axis_obstacle_filtering", false); + collision_checker_param_.z_axis_filtering_buffer = + declare_parameter("collision_checker_params.z_axis_filtering_buffer", 0.3); + collision_checker_param_.chattering_threshold = + declare_parameter("collision_checker_params.chattering_threshold", 0.2); + + // Subscriber + self_pose_listener_ = std::make_shared(this); + + sub_dynamic_objects_ = create_subscription( + "~/input/objects", rclcpp::SensorDataQoS(), + std::bind(&PredictedPathCheckerNode::onDynamicObjects, this, _1)); + sub_reference_trajectory_ = create_subscription( + "~/input/reference_trajectory", 1, + std::bind(&PredictedPathCheckerNode::onReferenceTrajectory, this, _1)); + sub_predicted_trajectory_ = create_subscription( + "~/input/predicted_trajectory", 1, + std::bind(&PredictedPathCheckerNode::onPredictedTrajectory, this, _1)); + sub_odom_ = create_subscription( + "~/input/odometry", 1, std::bind(&PredictedPathCheckerNode::onOdom, this, _1)); + sub_accel_ = create_subscription( + "~/input/current_accel", rclcpp::QoS{1}, + std::bind(&PredictedPathCheckerNode::onAccel, this, _1)); + + debug_ptr_ = + std::make_shared(this, vehicle_info_.max_longitudinal_offset_m); + + // Core + collision_checker_ = std::make_unique(this, debug_ptr_); + collision_checker_->setParam(collision_checker_param_); + + // Diagnostic Updater + updater_.setHardwareID("predicted_path_checker"); + updater_.add("predicted_path_checker", this, &PredictedPathCheckerNode::checkVehicleState); + + // Wait for first self pose + self_pose_listener_->waitForFirstPose(); + + // Timer + initTimer(1.0 / node_param_.update_rate); +} + +void PredictedPathCheckerNode::onDynamicObjects(const PredictedObjects::ConstSharedPtr msg) +{ + object_ptr_ = msg; +} + +void PredictedPathCheckerNode::onReferenceTrajectory( + const autoware_auto_planning_msgs::msg::Trajectory::SharedPtr msg) +{ + reference_trajectory_ = msg; +} + +void PredictedPathCheckerNode::onPredictedTrajectory( + const autoware_auto_planning_msgs::msg::Trajectory::SharedPtr msg) +{ + predicted_trajectory_ = msg; +} + +void PredictedPathCheckerNode::onOdom(const nav_msgs::msg::Odometry::SharedPtr msg) +{ + current_twist_ = std::make_shared(msg->twist.twist); +} + +void PredictedPathCheckerNode::onAccel( + const geometry_msgs::msg::AccelWithCovarianceStamped::SharedPtr msg) +{ + current_accel_ = msg; +} + +void PredictedPathCheckerNode::onIsPaused( + const control_interface::IsPaused::Message::ConstSharedPtr msg) +{ + is_paused_ptr_ = msg; + + is_paused_by_node_ = + is_paused_ptr_->data && + std::find( + is_paused_ptr_->requested_sources.begin(), is_paused_ptr_->requested_sources.end(), + "predicted_path_checker") != is_paused_ptr_->requested_sources.end(); +} + +void PredictedPathCheckerNode::initTimer(double period_s) +{ + const auto period_ns = + std::chrono::duration_cast(std::chrono::duration(period_s)); + timer_ = rclcpp::create_timer( + this, get_clock(), period_ns, std::bind(&PredictedPathCheckerNode::onTimer, this)); +} + +bool PredictedPathCheckerNode::isDataReady() +{ + if (!current_pose_) { + RCLCPP_INFO_THROTTLE( + this->get_logger(), *this->get_clock(), 5000 /* ms */, "waiting for current_pose..."); + return false; + } + + if (!object_ptr_) { + RCLCPP_INFO_THROTTLE( + this->get_logger(), *this->get_clock(), 5000 /* ms */, "waiting for dynamic objects msg..."); + return false; + } + + if (!reference_trajectory_) { + RCLCPP_INFO_THROTTLE( + this->get_logger(), *this->get_clock(), 5000 /* ms */, + "waiting for reference_trajectory msg..."); + return false; + } + + if (!predicted_trajectory_) { + RCLCPP_INFO_THROTTLE( + this->get_logger(), *this->get_clock(), 5000 /* ms */, + "waiting for predicted_trajectory msg..."); + return false; + } + + if (!current_twist_) { + RCLCPP_INFO_THROTTLE( + this->get_logger(), *this->get_clock(), 5000 /* ms */, "waiting for current_twist msg..."); + return false; + } + + if (!current_accel_) { + RCLCPP_INFO_THROTTLE( + this->get_logger(), *this->get_clock(), 5000 /* ms */, "waiting for current_accel msg..."); + return false; + } + + if (!is_paused_ptr_) { + RCLCPP_INFO_THROTTLE( + this->get_logger(), *this->get_clock(), 5000 /* ms */, "waiting for is_paused msg..."); + return false; + } + + if (!cli_set_pause_->service_is_ready()) { + RCLCPP_INFO_THROTTLE( + this->get_logger(), *this->get_clock(), 5000 /* ms */, "waiting for pause service..."); + return false; + } + + return true; +} + +bool PredictedPathCheckerNode::isDataTimeout() +{ + const auto now = this->now(); + + constexpr double th_pose_timeout = 1.0; + const auto pose_time_diff = rclcpp::Time(current_pose_->header.stamp).seconds() - now.seconds(); + if (pose_time_diff > th_pose_timeout) { + RCLCPP_WARN_THROTTLE( + this->get_logger(), *this->get_clock(), 5000 /* ms */, "pose is timeout..."); + return true; + } + + return false; +} + +void PredictedPathCheckerNode::onTimer() +{ + current_pose_ = self_pose_listener_->getCurrentPose(); + + if (!isDataReady()) { + return; + } + + if (isDataTimeout()) { + return; + } + + // Cut trajectory + const auto cut_trajectory = cutTrajectory( + *predicted_trajectory_, std::max( + node_param_.min_trajectory_check_length, + current_twist_->linear.x * node_param_.trajectory_check_time)); + + // Convert to trajectory array + + TrajectoryPoints predicted_trajectory_array = motion_utils::convertToTrajectoryPointArray( + motion_utils::resampleTrajectory(cut_trajectory, node_param_.resample_interval)); + + // Check collision + + const auto collision_checker_output = + collision_checker_->checkTrajectoryForCollision(predicted_trajectory_array, object_ptr_); + + if (!collision_checker_output) { + // There is no need to stop + if (is_paused_by_node_) { + sendRequest(false); + } + current_state_ = State::DRIVE; + updater_.force_update(); + debug_ptr_->publish(); + + return; + } + + // Extend trajectory + + extendTrajectoryPointsArray(predicted_trajectory_array); + + // Insert collision and stop points + + const auto stop_idx = + insertStopPoint(predicted_trajectory_array, collision_checker_output.get().first); + + // Check ego vehicle is stopped or not + constexpr double th_stopped_velocity = 0.001; + const bool is_ego_vehicle_stopped = current_twist_->linear.x < th_stopped_velocity; + + // If ego vehicle is not stopped, check obstacle is in the brake distance + if (!is_ego_vehicle_stopped) { + // Calculate projected velocity and acceleration of the object on the trajectory point + + const auto projected_obj_vel_acc = calculateProjectedVelAndAcc( + collision_checker_output->second, predicted_trajectory_array.at(stop_idx)); + + // Calculate relative velocity and acceleration wrt the object + + const double relative_velocity = current_twist_->linear.x - projected_obj_vel_acc.first; + const double relative_acceleration = + current_accel_->accel.accel.linear.x - projected_obj_vel_acc.second; + + // Check if the vehicle is in the brake distance + + const bool is_in_brake_distance = utils::isInBrakeDistance( + predicted_trajectory_array, stop_idx, relative_velocity, relative_acceleration, + node_param_.max_deceleration, node_param_.delay_time); + + if (is_in_brake_distance) { + // Send emergency and stop request + current_state_ = State::EMERGENCY; + updater_.force_update(); + if (!is_paused_by_node_) { + sendRequest(true); + } + debug_ptr_->publish(); + RCLCPP_ERROR_THROTTLE( + this->get_logger(), *this->get_clock(), 5000 /* ms */, + "There is an obstacle in the brake distance. Sending emergency and stop request..."); + return; + } + } + + // If it is not in the brake distance, check if the collision point is discrete from the reference + // trajectory or not + + const auto reference_trajectory_array = + motion_utils::convertToTrajectoryPointArray(*reference_trajectory_); + + const auto is_discrete_point = + isItDiscretePoint(reference_trajectory_array, predicted_trajectory_array.at(stop_idx)); + + if (is_discrete_point) { + // Check reference trajectory has stop point or not + + const auto is_there_stop_in_ref_trajectory = isThereStopPointOnReferenceTrajectory( + predicted_trajectory_array.at(stop_idx).pose, reference_trajectory_array); + + if (!is_there_stop_in_ref_trajectory) { + // Send pause + if (!is_paused_by_node_) { + sendRequest(true); + } + current_state_ = State::PAUSE; + updater_.force_update(); + + RCLCPP_WARN_THROTTLE( + this->get_logger(), *this->get_clock(), 5000 /* ms */, + "There is an obstacle on predicted path. Sending stop request..."); + + debug_ptr_->publish(); + return; + } + } + + // If it is not discrete point, planning should handle it. Send drive. + current_state_ = State::DRIVE; + updater_.force_update(); + + if (is_paused_by_node_) { + sendRequest(false); + } + + debug_ptr_->publish(); +} + +TrajectoryPoints PredictedPathCheckerNode::trimTrajectoryFromSelfPose( + const TrajectoryPoints & input, const Pose & self_pose) const +{ + TrajectoryPoints output{}; + + const size_t min_distance_index = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + input, self_pose, node_param_.ego_nearest_dist_threshold, + node_param_.ego_nearest_yaw_threshold) + + 1; + + for (size_t i = min_distance_index; i < input.size(); ++i) { + output.push_back(input.at(i)); + } + + return output; +} + +bool PredictedPathCheckerNode::isThereStopPointOnReferenceTrajectory( + const geometry_msgs::msg::Pose & pose, const TrajectoryPoints & reference_trajectory_array) +{ + const auto trimmed_reference_trajectory_array = + trimTrajectoryFromSelfPose(reference_trajectory_array, current_pose_.get()->pose); + + const auto nearest_stop_point_on_ref_trajectory = + motion_utils::findNearestIndex(trimmed_reference_trajectory_array, pose); + + const auto stop_point_on_trajectory = motion_utils::searchZeroVelocityIndex( + trimmed_reference_trajectory_array, 0, *nearest_stop_point_on_ref_trajectory); + + return !!stop_point_on_trajectory; +} + +void PredictedPathCheckerNode::checkVehicleState(diagnostic_updater::DiagnosticStatusWrapper & stat) +{ + int8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::string msg = "OK"; + + if (current_state_ == State::EMERGENCY) { + level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + msg = "vehicle will collide with obstacles"; + } + if (current_state_ == State::PAUSE) { + level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + msg = "vehicle will stop due to obstacle"; + } + + stat.summary(level, msg); +} + +void PredictedPathCheckerNode::sendRequest(bool make_stop_vehicle) +{ + if (!is_calling_set_pause_ && cli_set_pause_->service_is_ready()) { + const auto req = std::make_shared(); + req->pause = make_stop_vehicle; + req->request_source = "predicted_path_checker"; + is_calling_set_pause_ = true; + cli_set_pause_->async_send_request(req, [this](auto) { is_calling_set_pause_ = false; }); + } +} +bool PredictedPathCheckerNode::isItDiscretePoint( + const TrajectoryPoints & reference_trajectory, const TrajectoryPoint & collision_point) const +{ + const auto nearest_segment = + motion_utils::findNearestSegmentIndex(reference_trajectory, collision_point.pose); + + const auto nearest_point = utils::calcInterpolatedPoint( + reference_trajectory, collision_point.pose.position, *nearest_segment, false); + + const auto distance = tier4_autoware_utils::calcDistance2d( + nearest_point.pose.position, collision_point.pose.position); + + const auto yaw_diff = + std::abs(tier4_autoware_utils::calcYawDeviation(nearest_point.pose, collision_point.pose)); + return distance >= node_param_.distinct_point_distance_threshold || + yaw_diff >= tier4_autoware_utils::deg2rad(node_param_.distinct_point_yaw_threshold); +} + +Trajectory PredictedPathCheckerNode::cutTrajectory( + const Trajectory & trajectory, const double length) +{ + Trajectory cut; + cut.header = trajectory.header; + if (trajectory.points.empty()) { + return cut; + } + double total_length = 0.0; + cut.points.push_back(trajectory.points.front()); + for (size_t i = 1; i < trajectory.points.size(); ++i) { + const auto & point = trajectory.points.at(i); + + const auto p1 = tier4_autoware_utils::fromMsg(cut.points.back().pose.position); + const auto p2 = tier4_autoware_utils::fromMsg(point.pose.position); + const auto points_distance = boost::geometry::distance(p1.to_2d(), p2.to_2d()); + + const auto remain_distance = length - total_length; + + // Over length + if (remain_distance <= 0.001) { + break; + } + + // Require interpolation + if (remain_distance <= points_distance) { + const Eigen::Vector3d p_interpolated = p1 + remain_distance * (p2 - p1).normalized(); + + TrajectoryPoint p; + p.pose.position.x = p_interpolated.x(); + p.pose.position.y = p_interpolated.y(); + p.pose.position.z = p_interpolated.z(); + p.pose.orientation = point.pose.orientation; + + cut.points.push_back(p); + break; + } + + cut.points.push_back(point); + total_length += points_distance; + } + motion_utils::removeOverlapPoints(cut.points); + + return cut; +} +void PredictedPathCheckerNode::extendTrajectoryPointsArray(TrajectoryPoints & trajectory) +{ + // It extends the trajectory to the end of the footprint of the vehicle to get better distance to + // collision_point. + const double extend_distance = vehicle_info_.max_longitudinal_offset_m + node_param_.stop_margin; + const auto & goal_point = trajectory.back(); + const auto trajectory_point_extend = utils::getExtendTrajectoryPoint(extend_distance, goal_point); + trajectory.push_back(trajectory_point_extend); +} + +size_t PredictedPathCheckerNode::insertStopPoint( + TrajectoryPoints & trajectory, const geometry_msgs::msg::Point collision_point) +{ + const auto nearest_collision_segment = + motion_utils::findNearestSegmentIndex(trajectory, collision_point); + + const auto nearest_collision_point = + utils::calcInterpolatedPoint(trajectory, collision_point, nearest_collision_segment, true); + + const size_t collision_idx = nearest_collision_segment + 1; + + trajectory.insert(trajectory.begin() + static_cast(collision_idx), nearest_collision_point); + + const auto stop_point = + utils::findStopPoint(trajectory, collision_idx, node_param_.stop_margin, vehicle_info_); + + const size_t stop_idx = stop_point.first + 1; + trajectory.insert(trajectory.begin() + static_cast(stop_idx), stop_point.second); + + debug_ptr_->pushPose(nearest_collision_point.pose, PoseType::Collision); + debug_ptr_->pushPose(stop_point.second.pose, PoseType::Stop); + return stop_idx; +} + +std::pair PredictedPathCheckerNode::calculateProjectedVelAndAcc( + const PredictedObject & object, const TrajectoryPoint & trajectory_point) +{ + const auto & orientation_obj = object.kinematics.initial_pose_with_covariance.pose.orientation; + const auto & orientation_stop_point = trajectory_point.pose.orientation; + const auto velocity_obj = object.kinematics.initial_twist_with_covariance.twist.linear.x; + const auto acceleration_obj = + object.kinematics.initial_acceleration_with_covariance.accel.linear.x; + const auto k = std::cos(tier4_autoware_utils::normalizeRadian( + tf2::getYaw(orientation_obj) - tf2::getYaw(orientation_stop_point))); + const auto projected_velocity = velocity_obj * k; + const auto projected_acceleration = acceleration_obj * k; + return std::make_pair(projected_velocity, projected_acceleration); +} + +} // namespace predicted_path_checker + +#include + +RCLCPP_COMPONENTS_REGISTER_NODE(predicted_path_checker::PredictedPathCheckerNode) diff --git a/control/predicted_path_checker/src/predicted_path_checker_node/utils.cpp b/control/predicted_path_checker/src/predicted_path_checker_node/utils.cpp new file mode 100644 index 0000000000000..148b1d3b78a1e --- /dev/null +++ b/control/predicted_path_checker/src/predicted_path_checker_node/utils.cpp @@ -0,0 +1,345 @@ +// Copyright 2023 LeoDrive A.Ş. 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 "predicted_path_checker/utils.hpp" + +namespace utils +{ + +using motion_utils::findFirstNearestIndexWithSoftConstraints; +using motion_utils::findFirstNearestSegmentIndexWithSoftConstraints; +using tier4_autoware_utils::calcDistance2d; +using tier4_autoware_utils::getRPY; + +// Utils Functions +Polygon2d createOneStepPolygon( + const geometry_msgs::msg::Pose & base_step_pose, const geometry_msgs::msg::Pose & next_step_pose, + const vehicle_info_util::VehicleInfo & vehicle_info, const double expand_width) +{ + Polygon2d polygon; + + const double longitudinal_offset = vehicle_info.max_longitudinal_offset_m; + const double width = vehicle_info.vehicle_width_m / 2.0 + expand_width; + const double rear_overhang = vehicle_info.rear_overhang_m; + + { // base step + appendPointToPolygon( + polygon, tier4_autoware_utils::calcOffsetPose(base_step_pose, longitudinal_offset, width, 0.0) + .position); + appendPointToPolygon( + polygon, + tier4_autoware_utils::calcOffsetPose(base_step_pose, longitudinal_offset, -width, 0.0) + .position); + appendPointToPolygon( + polygon, + tier4_autoware_utils::calcOffsetPose(base_step_pose, -rear_overhang, -width, 0.0).position); + appendPointToPolygon( + polygon, + tier4_autoware_utils::calcOffsetPose(base_step_pose, -rear_overhang, width, 0.0).position); + } + + { // next step + appendPointToPolygon( + polygon, tier4_autoware_utils::calcOffsetPose(next_step_pose, longitudinal_offset, width, 0.0) + .position); + appendPointToPolygon( + polygon, + tier4_autoware_utils::calcOffsetPose(next_step_pose, longitudinal_offset, -width, 0.0) + .position); + appendPointToPolygon( + polygon, + tier4_autoware_utils::calcOffsetPose(next_step_pose, -rear_overhang, -width, 0.0).position); + appendPointToPolygon( + polygon, + tier4_autoware_utils::calcOffsetPose(next_step_pose, -rear_overhang, width, 0.0).position); + } + + polygon = tier4_autoware_utils::isClockwise(polygon) + ? polygon + : tier4_autoware_utils::inverseClockwise(polygon); + + Polygon2d hull_polygon; + boost::geometry::convex_hull(polygon, hull_polygon); + boost::geometry::correct(hull_polygon); + + return hull_polygon; +} + +TrajectoryPoint calcInterpolatedPoint( + const TrajectoryPoints & trajectory, const geometry_msgs::msg::Point & target_point, + const size_t segment_idx, const bool use_zero_order_hold_for_twist) +{ + if (trajectory.empty()) { + TrajectoryPoint interpolated_point{}; + interpolated_point.pose.position = target_point; + return interpolated_point; + } else if (trajectory.size() == 1) { + return trajectory.front(); + } + + // Calculate interpolation ratio + const auto & curr_pt = trajectory.at(segment_idx); + const auto & next_pt = trajectory.at(segment_idx + 1); + const auto v1 = tier4_autoware_utils::point2tfVector(curr_pt, next_pt); + const auto v2 = tier4_autoware_utils::point2tfVector(curr_pt, target_point); + if (v1.length2() < 1e-3) { + return curr_pt; + } + + const double ratio = v1.dot(v2) / v1.length2(); + const double clamped_ratio = std::clamp(ratio, 0.0, 1.0); + + // Interpolate + TrajectoryPoint interpolated_point{}; + + // pose interpolation + interpolated_point.pose = + tier4_autoware_utils::calcInterpolatedPose(curr_pt, next_pt, clamped_ratio); + + // twist interpolation + if (use_zero_order_hold_for_twist) { + interpolated_point.longitudinal_velocity_mps = curr_pt.longitudinal_velocity_mps; + interpolated_point.lateral_velocity_mps = curr_pt.lateral_velocity_mps; + interpolated_point.acceleration_mps2 = curr_pt.acceleration_mps2; + } else { + interpolated_point.longitudinal_velocity_mps = interpolation::lerp( + curr_pt.longitudinal_velocity_mps, next_pt.longitudinal_velocity_mps, clamped_ratio); + interpolated_point.lateral_velocity_mps = interpolation::lerp( + curr_pt.lateral_velocity_mps, next_pt.lateral_velocity_mps, clamped_ratio); + interpolated_point.acceleration_mps2 = + interpolation::lerp(curr_pt.acceleration_mps2, next_pt.acceleration_mps2, clamped_ratio); + } + + // heading rate interpolation + interpolated_point.heading_rate_rps = + interpolation::lerp(curr_pt.heading_rate_rps, next_pt.heading_rate_rps, clamped_ratio); + + // wheel interpolation + interpolated_point.front_wheel_angle_rad = interpolation::lerp( + curr_pt.front_wheel_angle_rad, next_pt.front_wheel_angle_rad, clamped_ratio); + interpolated_point.rear_wheel_angle_rad = + interpolation::lerp(curr_pt.rear_wheel_angle_rad, next_pt.rear_wheel_angle_rad, clamped_ratio); + + // time interpolation + const double interpolated_time = interpolation::lerp( + rclcpp::Duration(curr_pt.time_from_start).seconds(), + rclcpp::Duration(next_pt.time_from_start).seconds(), clamped_ratio); + interpolated_point.time_from_start = rclcpp::Duration::from_seconds(interpolated_time); + + return interpolated_point; +} + +std::pair findStopPoint( + TrajectoryPoints & trajectory_array, const size_t collision_idx, const double stop_margin, + vehicle_info_util::VehicleInfo & vehicle_info) +{ + // It returns the stop point and segment of the point on trajectory. + + double desired_distance_base_link_to_collision = + vehicle_info.max_longitudinal_offset_m + stop_margin; + size_t stop_segment_idx = 0; + bool found_stop_point = false; + double distance_point_to_collision = 0.0; + + for (size_t i = collision_idx; i > 0; i--) { + distance_point_to_collision = + motion_utils::calcSignedArcLength(trajectory_array, i - 1, collision_idx); + if (distance_point_to_collision >= desired_distance_base_link_to_collision) { + stop_segment_idx = i - 1; + found_stop_point = true; + break; + } + } + if (found_stop_point) { + const auto & base_point = trajectory_array.at(stop_segment_idx); + const auto & next_point = trajectory_array.at(stop_segment_idx + 1); + + double ratio = (distance_point_to_collision - desired_distance_base_link_to_collision) / + (std::hypot( + base_point.pose.position.x - next_point.pose.position.x, + base_point.pose.position.y - next_point.pose.position.y)); + + geometry_msgs::msg::Pose interpolated_pose = + tier4_autoware_utils::calcInterpolatedPose(base_point.pose, next_point.pose, ratio, false); + TrajectoryPoint output; + output.set__pose(interpolated_pose); + return std::make_pair(stop_segment_idx, output); + } else { + // It means that there is no enough distance between vehicle and collision point. + // So, we insert a stop at the first point of the trajectory. + return std::make_pair(0, trajectory_array.front()); + } +} + +bool isInBrakeDistance( + const TrajectoryPoints & trajectory, const size_t stop_idx, const double relative_velocity, + const double relative_acceleration, const double max_deceleration, const double delay_time_sec) +{ + if (relative_velocity < 0.0) { + return false; + } + + const auto distance_to_obstacle = motion_utils::calcSignedArcLength( + trajectory, trajectory.front().pose.position, trajectory.at(stop_idx).pose.position); + + const double distance_in_delay = relative_velocity * delay_time_sec + + relative_acceleration * delay_time_sec * delay_time_sec * 0.5; + + const double velocity_after_delay = relative_velocity + relative_acceleration * delay_time_sec; + + const double time_to_stop = velocity_after_delay / std::abs(max_deceleration); + const double distance_after_delay = + velocity_after_delay * time_to_stop - 0.5 * abs(max_deceleration) * time_to_stop * time_to_stop; + const double brake_distance = distance_in_delay + distance_after_delay; + + return brake_distance > distance_to_obstacle; +} + +TrajectoryPoint getExtendTrajectoryPoint( + const double extend_distance, const TrajectoryPoint & goal_point) +{ + tf2::Transform map2goal; + tf2::fromMsg(goal_point.pose, map2goal); + tf2::Transform local_extend_point; + local_extend_point.setOrigin(tf2::Vector3(extend_distance, 0.0, 0.0)); + tf2::Quaternion q; + q.setRPY(0, 0, 0); + local_extend_point.setRotation(q); + const auto map2extend_point = map2goal * local_extend_point; + Pose extend_pose; + tf2::toMsg(map2extend_point, extend_pose); + TrajectoryPoint extend_trajectory_point; + extend_trajectory_point.pose = extend_pose; + extend_trajectory_point.longitudinal_velocity_mps = goal_point.longitudinal_velocity_mps; + extend_trajectory_point.lateral_velocity_mps = goal_point.lateral_velocity_mps; + extend_trajectory_point.acceleration_mps2 = goal_point.acceleration_mps2; + return extend_trajectory_point; +} + +bool intersectsInZAxis(const PredictedObject & object, const double z_min, const double z_max) +{ + const auto & obj_pose = object.kinematics.initial_pose_with_covariance; + const auto & obj_height = object.shape.dimensions.z; + return obj_pose.pose.position.z - obj_height / 2.0 <= z_max && + obj_pose.pose.position.z + obj_height / 2.0 >= z_min; +} + +void getNearestPointForPredictedObject( + const PointArray & points, const Pose & base_pose, + geometry_msgs::msg::Point * nearest_collision_point) +{ + double min_norm = 0.0; + bool is_init = false; + + for (const auto & p : points) { + double norm = tier4_autoware_utils::calcDistance2d(p, base_pose); + if (norm < min_norm || !is_init) { + min_norm = norm; + *nearest_collision_point = p; + is_init = true; + } + } +} + +Polygon2d convertBoundingBoxObjectToGeometryPolygon( + const Pose & current_pose, const double & base_to_front, const double & base_to_rear, + const double & base_to_width) +{ + const auto mapped_point = [](const double & length_scalar, const double & width_scalar) { + tf2::Vector3 map; + map.setX(length_scalar); + map.setY(width_scalar); + map.setZ(0.0); + map.setW(1.0); + return map; + }; + + // set vertices at map coordinate + const tf2::Vector3 p1_map = std::invoke(mapped_point, base_to_front, -base_to_width); + const tf2::Vector3 p2_map = std::invoke(mapped_point, base_to_front, base_to_width); + const tf2::Vector3 p3_map = std::invoke(mapped_point, -base_to_rear, base_to_width); + const tf2::Vector3 p4_map = std::invoke(mapped_point, -base_to_rear, -base_to_width); + + // transform vertices from map coordinate to object coordinate + tf2::Transform tf_map2obj; + tf2::fromMsg(current_pose, tf_map2obj); + const tf2::Vector3 p1_obj = tf_map2obj * p1_map; + const tf2::Vector3 p2_obj = tf_map2obj * p2_map; + const tf2::Vector3 p3_obj = tf_map2obj * p3_map; + const tf2::Vector3 p4_obj = tf_map2obj * p4_map; + + Polygon2d object_polygon; + object_polygon.outer().reserve(5); + object_polygon.outer().emplace_back(p1_obj.x(), p1_obj.y()); + object_polygon.outer().emplace_back(p2_obj.x(), p2_obj.y()); + object_polygon.outer().emplace_back(p3_obj.x(), p3_obj.y()); + object_polygon.outer().emplace_back(p4_obj.x(), p4_obj.y()); + + object_polygon.outer().push_back(object_polygon.outer().front()); + boost::geometry::correct(object_polygon); + + return object_polygon; +} + +Polygon2d convertCylindricalObjectToGeometryPolygon( + const Pose & current_pose, const autoware_auto_perception_msgs::msg::Shape & obj_shape) +{ + Polygon2d object_polygon; + + const double obj_x = current_pose.position.x; + const double obj_y = current_pose.position.y; + + constexpr int N = 20; + const double r = obj_shape.dimensions.x / 2; + object_polygon.outer().reserve(N + 1); + for (int i = 0; i < N; ++i) { + object_polygon.outer().emplace_back( + obj_x + r * std::cos(2.0 * M_PI / N * i), obj_y + r * std::sin(2.0 * M_PI / N * i)); + } + + object_polygon.outer().push_back(object_polygon.outer().front()); + boost::geometry::correct(object_polygon); + + return object_polygon; +} + +Polygon2d convertPolygonObjectToGeometryPolygon( + const Pose & current_pose, const autoware_auto_perception_msgs::msg::Shape & obj_shape) +{ + Polygon2d object_polygon; + tf2::Transform tf_map2obj; + fromMsg(current_pose, tf_map2obj); + const auto obj_points = obj_shape.footprint.points; + object_polygon.outer().reserve(obj_points.size() + 1); + for (const auto & obj_point : obj_points) { + tf2::Vector3 obj(obj_point.x, obj_point.y, obj_point.z); + tf2::Vector3 tf_obj = tf_map2obj * obj; + object_polygon.outer().emplace_back(tf_obj.x(), tf_obj.y()); + } + object_polygon.outer().push_back(object_polygon.outer().front()); + boost::geometry::correct(object_polygon); + + return object_polygon; +} + +void appendPointToPolygon(Polygon2d & polygon, const geometry_msgs::msg::Point & geom_point) +{ + Point2d point; + point.x() = geom_point.x; + point.y() = geom_point.y; + + boost::geometry::append(polygon.outer(), point); +} + +} // namespace utils