From e337576f8a22a015df9a21f21e4beb12bbdae2b7 Mon Sep 17 00:00:00 2001 From: Berkay Karaman Date: Fri, 29 Sep 2023 15:55:55 +0300 Subject: [PATCH] feat(predicted_path_checker): check predicted trajectory to avoid collisions planning can not handle (#2528) * feat(predicted_path_checker): check predicted trajectory to avoid collisions planning can not handle (#2528) Signed-off-by: Berkay Karaman * Added pkg to control.launch.py Signed-off-by: Berkay Karaman --------- Signed-off-by: Berkay Karaman --- control/predicted_path_checker/CMakeLists.txt | 37 ++ control/predicted_path_checker/README.md | 103 +++ .../config/predicted_path_checker.param.yaml | 22 + .../images/FlowChart.png | Bin 0 -> 64755 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 | 178 ++++++ .../include/predicted_path_checker/utils.hpp | 104 ++++ .../launch/predicted_path_checker.launch.xml | 21 + control/predicted_path_checker/package.xml | 47 ++ .../collision_checker.cpp | 231 +++++++ .../debug_marker.cpp | 329 ++++++++++ .../predicted_path_checker_node.cpp | 585 ++++++++++++++++++ .../src/predicted_path_checker_node/utils.cpp | 429 +++++++++++++ .../launch/control.launch.py | 32 + 17 files changed, 2338 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 000000000000..cfbe95df99e7 --- /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) + +include_directories( + include + SYSTEM + ${Eigen3_INCLUDE_DIRS} +) + +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 + +) + +rclcpp_components_register_node(predicted_path_checker + PLUGIN "autoware::motion::control::predicted_path_checker::PredictedPathCheckerNode" + EXECUTABLE predicted_path_checker_node +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +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 000000000000..24e4b91ef441 --- /dev/null +++ b/control/predicted_path_checker/README.md @@ -0,0 +1,103 @@ +# 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". + +**filterObstacles() ->** It filters the predicted objects in the environment. It filters the objects which are not in +front of the vehicle and far away from predicted trajectory. + +**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 | +| `filtering_distance_threshold` | `double` | It ignores the objects if distance is higher than this [m] | 1.5 | +| `use_object_prediction` | `bool` | If true, node predicts current pose of the objects wrt delta time [-] | true | + +### 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 000000000000..780d86b5e980 --- /dev/null +++ b/control/predicted_path_checker/config/predicted_path_checker.param.yaml @@ -0,0 +1,22 @@ +/**: + 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 # [m] + trajectory_check_time: 3.0 + distinct_point_distance_threshold: 0.3 + distinct_point_yaw_threshold: 5.0 # [deg] + filtering_distance_threshold: 1.5 # [m] + use_object_prediction: true + + 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..15b32417d2a73a0783c0c36e5e244f51459b2ca1 GIT binary patch literal 64755 zcmeFYc{tSX|37NYNM-CT#3+$<#xOHdmN7HN7|dA4Ap5?Lb?j0jBxykuN`;DqP%2qM zQc)?Atc66DtXY5e)cgH8-}C#Pb6wv*&ULQy$GNUCGhTDQp09g(-uL}{J|2%dg<@*B zbNk-y92^`wjfgmN4h}9X_;ZD916PKu<1TS<2!w^=>7o7+9^QWL9CAp5zu)B4;a-6u zp>jx^oVvO*gQ4o??d%!s>>r{U;2sJtf#3ZD-Ml@#-QE6{QHQG|Rp1&b>S#-Kq#RNo zuE~B=S4C)O+5Ro>?CBoxk3o~bC~rSMXE}9(rYanmQlKLca!4%rX5|tV5E}OPJJ~xR zECO7Mz@Qva8h@_^hXb<+xRxsXF!;sL-PJb`SW$-~;NXP-mk8d$?jC{QHUa{n&Nj}j zs(Yxj=ih32n7Z0hND-lQ59cVV5z-7v_hz>clnHka4)G2Q_@^}pRfH<$?+>Ao4EMiR z-Q2^yUESGNk$BKk|8xns*ZZGNFwiu|hG-xIan35nZc(=GrlDbxe~kn<`~PEv0{TG( z)Rb)mO^XP%LYbfl6b(dxO90X{Dh%TnZtLT$MMt26g3t&W0!h(Akc_O1;3RWv0~Zeu zx(mYC6Kif{9!fI^iSqIEF|)Bif|?SHT}hE{Bs1_W*vpNGx9}wSA zRFJVL!{6VCfd<`-rIQWKNI^ji6q$&}X&P8W`nc;`fLm=0Nhag~s*kNcj){mMT6lW< zJCkha>LHfMKr2L)iI+a!mV^#>^EG9H(m}pa8h8@c)zBA5#s`J_TA68Cn+9738zC_! zaEma%C{0_mhl`I1!i?(Xivo`&Q7rVS;M2y|myWiAQ!zNIzZb@o0C%N^L?ZmaFTw1$ z0CPB;ev6|2sQKd#{|2;iLQo7vOx&Nm52`y3?)P`eS9>r{vm!Imf;~ZTO)m> zF*4K(co2c<7Dx@pnHb_VyopS*W)v+_3uS@RC#f6wvuj1dc|`gX&3uVbWX&*ZGt*F# zm$@6<-_+BKL@@PcG6)z8B9@9Ldq<+_Q66CtT9|MRlsie&O2gCN%E*~a@F(gUlJwzL z6nB3syagVZM4^xvmoT(}KD%cuDXvtkhbt2}m(F~T;?+uxs{WfEpa*7ORa+7Jw=7Qt{6bCQoS3We~*p7X#Y>PZ}H(;swVC(kMm<6Eo*1FB77T34<9L6-<*(&Jiwv_NntQ2h_=OuGO{vyQ zteGdA8bRWbGIc~B3(>10{u-uDN>lV zjkURnjdhd()|AAcX{aNxeo^MO&fX-rg+~~|SlvGm5r7J!hod4igEZlwCkZajhVJHA z4QKX1;Y{@1hz5q%W&uo>aE6OBBGALfoyv?LnERU`G^k!y{#MSOKE~mmzFsEb?onuG zf+m3)?BZ+fZ$KijC!qx%LGd*s6J3}QI4yl!3N6^h$0v&E6Nz#UL`NACi9`wkZDNI? z;L#BtRAht~mgs|vU|12XXb5Y35Z0Xrw~F#NHws44X|@*D=Eg*4b#j=Mm8+JCz8Rga zsevQv8(Bs9p)Jjvtr$etAb(GDf`tds0=NQ}X&mHj=tOcm z@~6@?2yWgMT2^pFZ@9IVahQz>#>Ll%J(5-!e}AMQ3FU8Vh_xahsFWyh1DfJSLE;%` zB)eZDDFNVvVjF30<`#?zrG;Qz-2#HaC5>QpjJK5s(kqI+6lvLpdKeJ`^^L>bBLZ-K zI1X_%$HF+M2RHrU#f!O*hN zFlA3ZD=(53#Wm7TJ)CSqurcy9#9-Y>SW|y%8-%U735i5E^h6t=!cm&e)^6%FQ&UeX zPeX(y!`2UOjPP*L_d}^0hX+Ll1=C6XzUCTH41ZH1+LXw&h8t**;FJIohKfT*1lVZ# zXnKJi3rhxnUj7y#)?p@ie^aI(0dE-Uf&oneFZT$#RyYF8JzKOV_}4E0Lkrf7Fc10r zt1T03kXV}#G9@&E;u>mYt~|Q2(m#$dYQUW5a_6Yz#vo@ zff*TOO7pNF+t35F&}8cfngJmwI0%74TZLJB)5EkP2$nvY{$TCF`g%r~__+p#s=HwV zBk4ZomLWdY*1opJL3&E}vOC4kKhV;fPWNSc5~EzhtVtT| zp4PBIhD9Ne1nUT-p;n-cf3St0flWZLk9h>njZOqnK(GnJ)ZEpEX6j+3q9_FP5b`pYlaFmOtxi!j` z;0)U3;}YfSLUjv_(6B<8qixWkI3GIP24lj2v;7DZw+Z$ngoCf48ny=5D4Z+a1%oj( zjdI2T*Ctq7`n$rJQChyJ2=^d(P$UiMu4QeAMn`y=22d?DeAG3Zspc4Gw56{)isoZr zV{72X2-YIvNu&UH-g7~$$gN81{CScSTn61<`?h|sVgq?v61#?q3#?r0c*AQ622 z8z=q=8o~enMA%5Y1ILFD4h|U(Bb>fvgu_%GU$!W|hhQ9h{yIchN0bx6L3nMmBOA_V zX=(ZTIwbiFC-OSPLkQno>eP@Mg2m&Tc@$)}@yL08t1tdCCf%LapVL3xo1gPAzxeo< zpJj}@k0*cHJ-pi;{4Oajt0nWD=S|7>3k_CT=%1xBT(W;&Hh8CdJ2GkpGsRaIyD&MN z-FrGm?v|7Vch?AG_sHMhf!E`~>G3ql$iPImwH!4yz$&EgbF`A+6oMv5f{Pj4Y4m)n z^H4>z)pk2}N!;~Po`bA*61;QfGPHeu*YzK%Cm_jsSt945?Z37u&x{yDGMNGj@j_6x ziApHARp40v7_mx^IMGJkRlHCAKAqA0yPumLupZ#vF_U>x6x@-B;y4v(Tl(y)7VqCvX5W8K zd-}Vn_Rp%VFVPF{44-^Gr`;hH`R#&tru?Io>!)@Ft392?-kDbUafrX*EkzObx4VL6 zpuRBH?rh!oXD`&Fm;9JNt9u^5kdFWICL8hmUUm1DMC`=-!ZM$acMpFRU{Sh?O!}FF zvEwy^acj4h<7ONA9Bw@YjX7N0nfQ_gm4yt4{CX+>B&0*@#m74qFX~o*l$6;$4459f z8W;|&##CUxPu{N&2Y=6e-(J_Z9pzUoJ6>C9_bevz&U7Yp`_8Mv!hiZPnLnXa2s?WP z<$tA*@qA~0VEx7zuaK@hIeX}ertet5fe;_lNh@<{&*E8weiz zaBO|{`E*TRK*%XR!6oe3s@3J0nJtrE(_@R4%PkU)kHUX`t_|z4@3AY}ZpSj!-3YZV z!16LXk1dzJivGelr8d)^sZXWOJH&4Q^id%+T$^Gk33gqho>J;md(3_ zfMMi&OB>6BGjUrROy=6phiip>X1W_y zeX+~^_Jhx2`F&qUFz+*5)&p9Bu#B(PkZp&N@mPtb!g zT?pQ=$$Jks4I!{^#P}qs@D(%bp+Ga8-?#Rm{Id5UJzgvD*b(uO0`9JwtqgoE3K1@S>ZWFk1 z$mGhST~bFLS(s|I2$Y1LWKoV(h2DcCvzLM|kY-zmbM0-~y(^wIE-l+1&b97)0-n*8 zx=R_gW14;fvd^zPL4qThyD7&re*!r3D4v5RS*pZS^zO&Ul5t*B8J5oK_XC0aIhwv% zCH7Bh>UT}HIVVYtsT^(muv`493A+D-ebhwZ=3ZRSb^TLclF!MF-?c1SMZ-kZoSrFGSt_E#>>oqqyc? zSd!$(1HEk6EhsAiYWs*$AfY#VbR_uzEyVQUDH5d6nB2o&=T1PHQ}jv`DL2w7&R&oL z>A00fJ0sdX+tIwcLWjxPyqvHm4KO^hV=6}aULWsfJ{0H0LJ%Ko{O#1-wkP4FVYxXu zkFid?oQQ*&#V2QsviM z`4Q^{mZ=avNyZ7^cQ;!0zI4)@?0rz&>6)rivtqVCMF(qkY%$~EiD72d*5+DtV_TKe z5q+$Jl2nLCYl$KmMDp;;3=`~{(26SjY+)FYv`Juudy+q)b1>9Qx&!S$P~ zC4K%6``15+DOJrT?m@V)9)2F8#QYw;9IZsWkq&)^N)}j8D$f`aU?EZ1yVmy|&P^a= zqGvgQyIfwk6mIgmY#$zEeLN`9akb+Ia&vQYZ6=z}vy_&og3Z|JD`@)pTSC}Gb&tdR zRx9kvgz|dm>~EM9OX@cT)xIB6@LW*$i(T%lKojTM=w-)n`TU3*&lC1aA6P$?AG>6u zR+_#4V0wdLvOo82UF?~)Y;#w|opC8y4=j(AuqcWdp=p07$Z`H}XQ5Znf%y`=E0a!( zkG|hXefk{9d2Qcj8ZTcXGVF(?ZeFGWt9(jEPiKABp#G?o=TzPDK;H%!1ojlw@cE#i z7J7P@)DLkrhpDcn%2T5$8WkLA(z*iz8U8iBt!tyA)#*@|_71n6L2br1@=B~!2~o&mm3!|w z*2g($496$Vqe|MiQf==_(Xa|u=8sMP`qVid7bVsRL}{11;^gTw&ON~4{BDrU{{DCg zY~<=jPtHaW?e4+4oa5J=Qi(_gnM!9*WyqXzvA z8s5u-s6|}W{&@BY*7;S|-!4b7!;`V@RQ+B#mdjg+;>o|4@9+~LnS1jBSnQ$+|D&QA zcw+3II0h%v2kv%{7RUOa#1Cqw1}!}+$<`=zon@ki)d?WvYB-Yv($xXnGLC=&jED<W0mg|tCZQF|E9S1JG;1CA#l}v;uL>!RJa3Eh zw3z`Qw=nFkiGOlMvlnw5W(Rqlf2^+#L|y?y4GHn!iN)!Qy?m90Q;NkPL>uFGBSUh; zZok^4J;iusVRkI>Km|5SWM!!@us?3?C%Q%XkV@rKMPJc+5P|B}&39@#As2{# z7b=k*n6JGy4?LtS&b2^PCPD1J{E}~f#L#UJ!(ys5GAX}Byt<0s1P;c`?_7&9QQmrw zb2w>b?GWkyEl1(hFBs#amGy<7qSl|k?zm}vyCQTQ#f$otA3Z%0^MPuZX&{#Ap236a z5A7PP-`b4suz0n!aS=7(_u$Py4kpOurb6W5pRYwCrYc^1sU6SP9=Tt?`Qzg6FUb6x zwZzfSeqpV9T2Th`C7IAO*Td9hS)0rCTd~@4>nkRsBBJ_WeZN>2wRi>X_4axI?d*lo z;~AA6gN0_-bPPaR;`pSLe_}I2Xl1@r7i2L0%RfKdv9NiUGYR&>Bs)4*;Y#b9WT<+4 z>b1C);UtfDmil+HEq?)(KSVfAlG2VtUn+ckyTlcAN8iwr_n+-SaHNcYC-qU*?G$6ARZ zKVEpx8KrxQy$)%W`fVSd%zJUXdxEmouK1{wz8XZZqhb|qJ_=Do@)vyZ?K)mc-M>>t z7+d=(LEuM*;RfdBJq1_>^-JyL92RA|+FP|-A$=Q^zu@>(gE00&&0QAdRz!$y5V$w+ z>+#zKEQ)H?jUVUP_ob=)_xo&E!4=%EWJSG8ND%xP^s)%R3pP+4iF-+qQLNJ4U6CKs zk)J;S6rv?BI>!hy>Tq?;CGD3N#|6BCgm$?yc%V-=e*wa^^^t(;qXxEL{z(bP^O*S$ zcJAvxT%0>HMTU9WO+2}9!0<6AHzwjp-7H9JF@2Vub!*d40;a#z29(^Z2?ilwPM`1n zx)^Nu+uPA#X7&TG%MNZz*IB*2HhwMs3%`8s`CrFUB=&Roj<7P?%zluY8ImU=z=L5}<_Kjzm<&G#K2$8Rc} z0A2a&gLGG&)+Fn^)Q#_^M_bIi7bU>`Tf0XFnc?O^yXT`|ZI5%iLuW#Gct77SM7=tgLE$E5iyB z3($mf`eAM7Vbh?W7r0H2V9O3B3uEPk6#EBLf1qoSmC}A$YL1)NaFf7}HbpvD6* z**@O`fqR+$scnUd&{HPV--nD#Z~bCOcdCyRJ3l|Y`Fr$0^Es`OaFnQw({I~UB@@l^67BJ?|j`9g~M=t0L3-)j8##U4jbrC4;x7&%bC@uaJK z$`dec2c3WRg6zB>GT{`@P)BPe|LZ+tevZJ(k` zi+*mGJXC4NUWi|F$3;2gFPc5azm_D5g*2Yz4FI#@w^{x0OrqmLcyh&z#qrJ|;8NG* zembUz7r1RCAH`gr{PjwWIX~XHjOFEweT{hWXgoi`k-lQ|N(+o6*3J4tS4na{yc%;3F-H(4L^mc`aFO7G8IpWDg@0FyT8;X1MXO3;}+Fd`p+f(f;mcNVW; zQ$H@1@#z{s25!m@zB{^a0jB+>7wm{_Qj7-9fcA{TTNM!A#pKoB#A=j4Y_yzCS(VR)K5iHgp8gZocbiR#R2b6piF$Yb1D8) z7SD<{wqm$0|%cC{AfPaIrKS5gSVpOIkZxB4fbnXiKYjPz5qB(lDYQ}IXlxSarDq*_Z7*8Itd9?0 z+sUH3M2@}A`Fc$^KT*-@Zp2*DV$vo_delabB9yJ;5Lmaku1C#vFRA+J_?qK=-+Nq& zYUQH<@2>QBv4;g<$}!0wT+@$rg9xfaAh&txW;)1{dpBK$1%5a3Nl&e@r0#rO`VwNM zb^=NP7;RC!^!$a(3apEZ(WO-Vc*SX{H++ij4Z_V&&I%g5S39an%Y|;A|2=e|;PyDC zLZ{`JG=OT0x6T`Wnxl4@4Q#~ti9}e>Z)MnE6&{#bnhF#QKTldy`*Qsz41)UP#Qj2G zuacmkI5&iJjqg(Z0m62^BP!kd%f33l_=UaRh5QH)pQ1BYCyJv(;M_cF3o-|Hd6640 zpqFQz=C31(a4V~ugq>*LZe{ByOZA>{I=|WuY^F*M%Cew>{Eqz~?08b*Q1`h0^!=b` z`&X`Pu6#|8?JYOwO;BTOvvP3L*K1DOjc5`mf@6iS3Q)a1`f8YRN7bXa-I4fQf*TeR z)Hsw7aR|THcNo`i&d(y2-}LZ{UzHiMZWfi|Iz6GbP0QgsH{Y%WtP&M6H`1usvXS8p zAo8WSec_*q>yspmhoR)OkN50)uAUaqK5|J%5ISKVSN1?;c;m99nri8;#szNg`Oz1H zTnOv#fJ_{IWk#~)RhQ30TNJp>=ugAGxc~Luq zTw>2e>y&Rp`nN_1@f?>ZpK_&+em&_uHUgko#dN*Zo^Msqrq^u^(kmNq%Juf&@AaH! zU3SslIfV_UiqE^dI9=hWV406|eiPuG6yOvPI=PM7czGVx=l8XK7Quf>p4)QdMC%FG zcm3o!xzlpr0SLc^0OsCU5p_-NJk0l9^$-z=Vnw zw6Dh}?UFjm=TKB7;n=;x|JD#vh1_(W0CNFu@qp#F0mgrLUskE~@XcoANtpw0<9APG z?>DXjAmpo5ZAh~G>d{yX7>wBUmAQcz$)3sHLm>X^9&D}J9*Yc8yrQ4+?B)EPaE0A^ z1p4C_Hl{0Yq+c`S`wt;*o)O5ZJ)O7>e*p!}B^BDVXTke1e|Z4=vMD!A^4JIQL~p^RBS% zT(lVF`)9?T#+T=cOB`g~h^!1Yhs-q$ok-HVehF;Yx8My!2F*Qw&M;OykHxkX={c)* z>$jlNV_Rvroo%_}A^VkM&Sr~v4$1gS>IMz9mUf0=VtzHili_W{9I1i3x(`3|f*#m$ zBE||~(%R7WMf;Sfdvjw(3?fH88LoFx)$w@DvDrnFy%~u|ehm$`of#C|O1DaF6e_3z zc=3HiTBAXmOe^w`Q$Ei;f_BdO0GZHkf8-pyQEJb*)Ooc(#ATv_&ZZTWoFkdbvE`bC$~ZNc zX!kznH=)6%kcu7od>QxodA4ywtvvD5Z)llf6r?WQp1U<-H z*qbk^+xO2kN;2VLt#xE>cx>X^p~jXQ%@SfBRy;c#dy++8x9*5q->)Pp$lWcy&9LZI zgx4~ldNgTi!{5_F4mjoiiskOnzy zEEOC*E8!(Bh0Q{h>;JK}zt_r_3yA~M^B zmd1P1>%~cZkBA&(Dk`CkMX72rRavYIxSegQig!#b6dsf>sylgN_W9it2D&B9+2VR+ zgqR3k!Gl8|TH)iD&=N)cmN%?X{UG%4iOb{jjeJOH!#fMHAgj{|*#3|RDdaeORn6H( zeI&_y&l0P#y(I%jhb0049cQ63_EQJzT%qcJWaZvmWy^aJkG{*6`<1uTX+jvfg}~Y- z{2rmV+_FMAO=qta(V3&S=U1G{-F0Mk8H;kI{MF>|A=eYVoTaN(#S&`&Y5`u;c{XV+ zV!DZOxgI~mv;c

$>#N+PgcG$AAFOIsWPt+ZhX2D?( zQVw^$Aoqw>@7-3=9PCwOS#Eo%Oh({= znXez+t9Ouvoj}Zy53(_beE{?P{}$%3M+h5U)@@dk>BmRk0l-NSFl+zUR@Km<^ zXZ?bE^Bm_`lwIgb7DXfNsu0Xgo=-OdkXv~XAmhSW2o%}|{DripM1SR#a^%Wqy(uWn zd%iTl;uqQL5h7=~v?Uw?qy_d51Nu*Q<{w+DIy!U!_Fw8}^RCaYb~Nk$r&?^<%{!;f zRRq~sTop($Cl8<+aw+?NC*_R;IAFPXcKCU^4#DJ4{&PF__YEq`9Zqa@RML= zLQ$oI`@UQcMYYjO&Ro3ySMLOAKd)A*pHkoUq3Fet!0L}Q<|qEH>h}AO+qIOrzP?Cj z9@>4#1OTI7%io_hI0C-qEwn4$ulfY=xDkqEX2DsWBjHnz8diVUpj4I^doHzS^%b71 zEG#5BnpOu*^om7#wz8nL=)i%e#y>w-^DRtt700bD{j>)ti9y-9i>VhI)_>3EY2`kC zchj(wongl39*qosqA;&iT-DSMVZM<)6YydQ; zu6{#Xy6Aau(T1gvkb)rBD2&y9Ge75bh}|o{+bzedvfM7-{PkB~0ZnKF3{he_zzbuF z{)6Dl!T>t0LjxR4jw1da+&mdjRg@LF9IMIm?!P#;j4&JMcLjotYj^(T6B3AQcsF)o=A2`2XN2~n5QiK1;oAiHS(5e6V#XBBzVyTIVZ?%@5B&l@llvgU0 z{f8Hmg^B~3g+a{se7W#&rLN_&O1^v0`IZvp;4yk4qmuexh!9~wgrtuRW?4$5J`iRJ zZpB|}F>ZQA_%F-_9;|xG7d!I2jrv_Ge6SZw+;(mkEI0pmyvy0+Z5(QvV3llXO_%f% zx(4I@4>huzZT=xu_#U=$TjDF)oqzZcz3*V3z#9H2-~KT}Qz54OKaSFL2sjFgI&NBZ zFv+HL|Nl0KFIg0oS8lqg`^4zzrq>qUDSA{Mdf3AcBje(_BC`KHw2ddB346Ngr{Nb@ju)TG4q53 z_MY9t&9OVh`JbO!mC)`C6i?!04)Bn7yom+6o6dZ7_x786UQ%+{qLdSmZ(^LRw?P2s zkc{dwL4WKhxl&STqu)@P5m3Lew6+dt6|c);yfoNf9;#}x8X)-#eIw@ijIEKF_I z0r8$2h_2MV^p|l4lorA19$17{Fl z>^T59aKwl9+f~40NXDkie+y^e0GWOeyBb}~CX1I3Q8?L@xr`_9#ZkYmG1HcVtl(l5 zD-m|9lJ^0_kE)Z~=cU2w@wL|8d z>^_w71yfAi7JQ5oKk_`ZR zR=_0_)L|>nPeAt9|3`2LY-UV5J`TN8Vq5L=-d6|s+NTQR#V%yfAs1ot2P1Y?~R zl%D4Ourl|x|E2u3sl;}z@mvePCOm(^9gE_}?ys`6v{~qhIw1BcTpQfl9PhRZtXmLp zVDOzxt-%0@Gv@c!?{Vp#YF}#*E{l9j`|AqsFv<<+e^h*cS5WDx^0r_CF9W) z|50rI1ejXD!uNLpK*dJ4f7pce$_wkB<34<9)7mk1^wCU{fLiD!d9$VN3xHUtWvd3| zY*|@AUl_IUefVE3Vtnj)N8Y6@fk_BA^VGJTUjXs*9W@ve!UT}_6EIxQFVsu%{J4kz z77tV}5f_#~Wu8p;KZ!08{0()8-w5j|Hk0nWiGeLF55^Z~Y_cg5Al#YO*<5jbI8k)9 z%!9{}B}5bFX$5fG#B}{u+}5&)+0l1w-elk|EdzS8XQqB@S_KQ{!%U0QOrVYUBCo^<%@KO>L~1=f+UAK&(B`g~*SCG#UjKtkM^tJO6Z zz3nOBx{|+6+Jiu5o#SO{~tvhs2Af>FIg#VO%_3?qH*<~*w7g7=fEa^`G`rKU|I5-dsbgR3R zb^^6(g3J}9=ehe`Y|ZFh%R3`%HY!n~sQ?4Z@L45Gn4@^;m4KTO#FP?}4>SvQ*+Oi2 ze2lQSL5LZ5Chd+HkK|&*UI_@SS*R(iO6c(i!3*=V&jq6g=ucYDNlhkx6*80@X46W{ zH<~?|B0cYYD}0>qQd`o(&BPC~7KDLVSlFxYQP5Xo-w(Gd>S|Ri%e_}UDpc-l7q{a= ziOfBiNY0!ed$ZQI(88hgokbR}p~IT1E`>2>v`^Ayj)EO?;No+Q9V2{7+zFgBED=)% zm`K&>bP1qCo8D@*goyJg%hIS@fm}Cu-ZkjGx^AMgqdYRttk`-n>{NgS&3Vt;h$LmnY$1^umpp%K=L zEoTM8T_<6X(&dx@#X8CI%+xJATthWw9~s#S0bFa8{sNoQsh`_Ap4x_=m1&2f^!0GV zC9HB|&}kQMypzUV{{ry?lt?jvk7uIhZ~8SD!f3&~LJBGgy$?Lsdb1L^`8J&&Ur&EC zeU$RK>V4gPI*j$mX*G2sy(xinBir@d9Je-%k?%3oy!!SAK2EgERe1Rr5^^_c+54HzzqvVdTff0pYAmVp#(vM)n8e*O*mn8aju97zd^r7u9!=|d+^d{5-X zURtZTA_R?~a|2e!tf-0Wl|+2~@3E`>((&uV#WI(8fuvE|*Ite5op5=2hw9j4Mrtj` zhchVo!u)g|zvKCV(_;NaCRekB5SFFTrpOuqtFpQ40d<@cqh&AaK6&JBg&w3jp#L+% zJ(0-IwJA#$LwtfAgevnW<5mh}9Dp`iHE`GoYUt%uN8AC{b+Gkmt;x=v-Ltl*)?p?bmhSNlOKKPNT?tAD=Zw!q3`q=4n0Gb zQnxZx2=Gzw@YPdZ1+h>U9%W*(@OtW*2atCtNGV%*XxGE0 z3a95})!xbS@Zpp=d_2V~)0OoSKn&&@tEV6t zd&l!=!0cQD=Wb3`Lj#w2 z24D|b0(t6Xl%dJ{a9kriLCsF9AS8VZ){Q77XwLzclcV!1LeABZz^A+ErVhDKm!Xyy zJcbisos4)T-0^0|TVR#!u3}r&Ciwo_^J6O|GJ0neB|1JpVA~imHqa9ZUTZ)hDrG^W z8`8>-|CWZ~o+Iq5VtxlNgY756nR*dQl8=>qTe0cH?-~WIcxkzNata^*64EK$ptSlVO6$D~m{U$Y==+v{A1qkNkN z8L4;Bte~Jx-bx65WgF$a?D<2S(J$hBXO@62C*u&tK3|;EL+7>Uirv0Jl-Xpf`SIg7 zpo;h_6^{!`_bFx-szZ3!!=dKew}cyXlQYBUJA=Ys1ePAu0io(KS*SEuP1CsigK2cC zS&HSw<8n@_nihUVo+e3OA&OVKu#ghSDb+YrvYfl3)4fLXrplmF%SOd&@~HH9Ou54_ zCVf!I!i6qi{P{Xi)O4uatsI4MMz`E+f9_M#o^yy&4xbqOdQf(UmI^By)s&DuaWuCY zDMsf_oY@ibJ)w(H^sD1^41@l{Q*p({JV%a2lD$=*sz+dl%%aRqk3+DGdjI=ZB!E2a zmMV;^f-O@k8Eflr0)cu!-(3%HkRXyovQ;G#yudB^SJrnVfTq*j8k)exj>NaiLY2U0 zh0nP!DrbR`r{Kc`Wsw4;}La(Y+daH8px!O}1xZ5tfe4lQ@yh87ntgk8U+KiaDZ5Iw~ z2vKrh5^MhmRZ=xQUhj^N(0HLyk)pQf^xPKpz=VAN5f1b5go?vS*Yi!^8pdk;hJ|xe z_uP6@VHr*@(^bwDkzLWYgE3g*SH~(RbzcyIwsY)T2quO@Z_69P=GJ7&kL}>|4Y|T` zbv5`TXECMReJAW==*5rrfCO_WsH(gInngoj+kP#Y$6OejyQ^W24B{q+WU2oPxfK)3 zhXYZ*%Rsap#Yug?-z7(H8BowGt}KOp#exiBPEV^t0_(9r8Zl=m$&N_`becK2TxW+G zRS|U~?VWKxxj`@ad7b%KZ`p@sS`k($kuoeG3LKppI=q_9;|J}???pUjWK`= ze6O1FcA9W`^A~V%x^SoRcoOCI_soOCI!8Lf+)j+{mfy8BcGh^CqcT*op5^7!QF#jzulZdTP1w?ooGZ+e(wL->L z4qQ8ll)Yp47@K@_xUu)Tq`wutVV0?E`0W&?$p<$8vE9XCwj&vLZs4T5(FEfjixTkc zpk>K<;L(XYEMKPR^+Ga8kf8HR-o<$}tF!(*d={i!zQ`6a>qqRT>c)U2f5+b72c4g3Y1A=vln!1%9p-&GIl$VlG_%wxn zC)-?qi64d9Mtm(e?%;r#6yhX4`(_11oK=ZX*~wd%OoLxYhMbj%PUL<4 zzR-B1;4{RcSvgClP@?Z zOy~$ap!7&%LSF*(3c~fY@0Ujv5?tV*NH_osmb$P0IRKP4lo1`{U9Q6ev>pkLyAn9p zK}xu2fm(Mf--U(uKX>i}VMxWpw^iVv4RQFQ0t-{MuVh=d5?7Ye`{ErCNo57P8PtLu z(Yp`Nq+q>zE8PcNx~}VUzbN=jmWR1Ph3{;Kt>4YQYp|p6NG3fa9q?iqi47li)8H{z zpdOGspq=Vrhn|}=kOH9dbggax2gqtAawX5F&AJ>(=k66sP2|okcY=8slZtO`mffki z2$`6PGyonSc*R!i%`UD&VJvyhsj!0Et|xo%^OJAuh1%4D+3;WCunXHT7QU1CReP?UsYOofCUIN28l)SAIyiiMk}Lb0j7 z6(})@@*+yn!@;;dZ8Q1pFlEZOl*L;hC=Ost2gD06vYW%cF`Udfo~gp}Pm()2A6D*6b^UF5NT>}7 zmN3{hopnE`CS9|90aSL!4duR8>R!Vy`NyK8Do(f}xOH@NRtn%^)j(RjR`|1pA10YN zcWI*U;e82_WYu*aC;_6l?yp+E9<26=;o~9W>Ga|VtDbrT+SHg6{9q)_w;a%Wtp%Uy z*^HN85Z;NPp=FRO|I9ltbcDPNg4?^$V;J0ndmQHmz6eS;L(Z0W zIPDb7z3zPa+OCtlN}}Qi)^E`(64Rkwapd2_ko+=y@@6y$^`C&b*)*>PmY|&={D4_mXU1zv`BH zi(P0A5L}0{_oN-`!A zg-PjNrFL1?r#-rHPni*|@^=78GtiWoM@4Ufb7o5Pf)JZ0nsa}!QkxvsQ0 zEyCi9yjIYoFt{AcVi|b*WbtJAeuO_uk4O##2N<8_LR5=BL($2{+Hrf%>25}BZDpip z2CNLplddMfF$d)pe18arz$0v3=Ld*IQ(JoD?iW6^D~QGBq4dn6TXH?l-|lIQ=*wKf zLNc|wMW@3tcMm7)=`PUEppRJ3BY+q-VSOHi*;Sq?g&KMhii_mH}fFx9%^v~Nk zuT?AMXX+W^hqsBf`(?e}ovt+iz3bosDX$8f`cx6$*Pc}Er*{61$F3P)E#D)`$d$}g z$SwAw2hQZxeBfy}hVb&11#Ep9lub%*OF2^K;pcYwf!M^ciTj$F~*i^~2(vQxO zgHk+y4tcnI!PHt-{SwF4Hmi4qIfsd?oqPByw6*=uaVvE_V3_-SX5xIGIDK|2MID!~ zpOKjE{TZA$^4~3H4DeV{u(1?4S<1?>A=VU1%oYee25YD<0npkGPEX&S+L4Lf4&Y+* z6QW(l2U#wk;fh(na~0T}L*s26iG8X`xL{=y#9Pn&Z(an5az-8qxq9~~CW->C2@vQ- zmx+*;DrZY&&|{S%<;Vwdl_sWFGmps?%5b%als_1as|h)TK6B+#ZsBuzz@q*=k^~ju z0_Q;+n}fc#`g=sbZn=e1B&Z5!YlR&8Uv#}?TvY8AH>^kuJwr*ujG%N1(lMlf2uLGH zhm?TQ&Crc>ND4@INJw{y(g=dIfC7r7yw~V`pL5>l`8{9wz@FKA_TE>lwf?a}S5z}a zUOfF;{Phm_u*ttDR6r^eQ1Ls1KtXCD9Bi;EDoO>WYlr{^2A{;*^}kT)|M`^@sCDgn zvO)VHhyVp+9>#-+|JDS^xv7BQU{pf8@>^a-2Ef%&|G|t*Wjp=_H^t6(YwJxlImnq6 zAkTMaojO4wb-c!=I+S0X8T=+z<$v{2JyBAiJk;{B!q7`9Tf%3j5d@M`l}{usnKhki z!mmk4JGLH#06lp}Hhwy+uHauTz)h}QVVlVU9DXfdaJu{dJ>AQWKVW1NV1$Vp9I(yf zWm_I_6e^KhVKk5&Sg|h;ogQtzyE^~&?pLFqf&^Xi01)qAEW!VMu#6aUD%V1nwJ1WZ zT$r8ff%I&pvFyL1FLV9?W~|`KB`Pl`%WMS5uB`);9vzG;mc`KGcZp5BZO%XMhBwzC7~? zZ^+Xk0J@_C=84~M!p@olFL>>a3+0@H=Nt~C|3S|f@o~v0kb1hoi<|(XKe3OL+qxcU z@L!40020h7UWdEr+bb$(9t>|b_^+Vre-B!@C?DRBEbso063iSPP=lB2Qa;wG_gJrZ zUwrS%@j;gv&iUmYh0~D4vMGP0_@uE;e?^vgwJ-HA^K}p(t=wBEOkVpyaS#7Ly0Exl zOkL?d_ZA=4;TY(A|LTg(Vyukdm-o83xvOvPLteix)o86tGW?Y(m#o0{7X%CIAd^w+ zG_BRhV^M|d+1o7HRR{M-Jt;saYutuhj=ut1f`o*yt!8^0c7^&;JqsK9%5XQ<=CU%15v`@9} zF@ON-f&zWm+8eqEi((pl6ubYWsYg31Tq@-)tBISU}c#Rn$guz<}}KPV{)l<-*P!l{l7l4AXLiH>~F(=-kAJ86qGa2 zc%_u!pEH!+hXgMO?QRYJm|ds%R(lfAyRu@L`|{Sbq9UJfp;^XZteg zB+36CJj_5JTzG;$*gTN1)_RkuzJ>i_?H|#rR5BXObP59JUlvk{{$$QO8wtOlP5di~ zl@k1O)D|3F6ne4qvDqAC3;V6coq;$2Qu2}+7-Sdzi@fXtu$AnK;7cgp8z+ETIJfqS zJ``S090L23LA1lCx17|xragxsg3B^Hh>xpL=llC=<`lq|-DiIru6f)y*Jjk_`D+iI zpf7uDW&tdGqhrah8?93t17O`LfRBDN)LM;8jQaj`n5%vC&x_ELN1uWaoZ_s{rWrtR zpIQL2<^bYhw;2auLNb{salXs%HmzqhngL3lH$il_8mFy#ru7$f9U%U*fLY<@{-7xe z!Oihv)2Z+-#?46w$)HNwN-D3Jb{eC8llSSN)dOgji5|C-q}M0-pE)1LiTQN8Y|a*_ zDKZtd0lu+h1;9y;LiI3MKqAfoWm5BEglWvgjDF}ozx#LN!dAAV21dc)hCGE>dNHya zBf04hDF1m&&SBSl^N%~dy})B-Uj}?6+eh^Pg5!1vu+W}?yT`pFx~ccdyf%)wxn$IN z0OT~(Dc64y8Jy$jK2Z3q1!BA zgKA#^9JzR^U@-lBXABsspv_#4&=pfXzssLGI;A@qbB3RGx!X``2llhM;LUXti2;{} z=ho+LTbvTWih(}j6yyY}kI(NB_YUV;Dh zVNnPTGmdB7wVAwkJ8Y~j@{X*b)axf`2t2RZ&V;>l{}YHl4AL0X=+3D;u7Fe#K{VyE zw@KX4MG(4k5N}mN@OK~&Ddhy5MiU7<$!XIS`j9IVTGuy~^2C>F`Mt-6=#S*n7(|$5 za=p}BNpTDt0bS4gR_jyK*)ufS0Cj5vJZgQfY@g#ncV;x8>9&z(HCFq*P@GIR%+jJ2 zI;8eT2b?2|A*lT997x+9*0+5r$pp{`xpHf6Dn8I?1|&6HE!F^Rov3jx;AkizdH+Ey zm{`}jzfQ<#m+3lf>@_YMHJ8zewB2SodrBVxQaVSE*Gfqt^D<7-ls0UHf2RqE2!r{3 z>~n|fFVBBHnFqjXj20dz0VR*|Hh=>jPaQUm95!*)p_0@zFg&}tukTXyV2HC&PNk}mi3m;5W|BVHFDu@4$#+q2_V`l$sjK-sOb*(DafAqqXl`!Q?}9P(MgOCqktJ8_{5ry)EbK$UXaF z?W|GqcTJEtrZEt5iRDbSu{nP?1q5Obnx)csOfbA=s#7f!I15eqmz>r$;%Gd801yxZC9=etNOSHyRNOSxWyb+1&P>j$W8$AOm^2g{`ysD5B9(~hoLE*@u zj21oU&D6WlhB1{~4a6(Ic0c(glRuT`z)M~a9>9TX4vHLoB4^VS8YA=h3EXPlB9j~E zc2*^U1I^W}PS>g*fbn^~c-&dE*OWe)s>SkW0Jh#wFeK-?3U9Ob=ZLW(BQWjKy*$7j zyn7|)aj4d^{))`;g9YMRz>uKPq7BWKYYl7FQ?vR!LH z%}zOD*($vi?-d2daR$Bf2D-INY(na~!$5qlfw@jQpg736TEJq`B??C8L*i~y}%Q?^B|2cm^5A|I4gE?m=mK_ zau4!)7{um%Nv;u6+EF)M`8p4m+Prk?zNA-}lns|t3_i98Z2dH=tNR;sek~6ewCZ9= z-dOoUzQR-@B`V_<-CYcH-x)!xccY2(t*b1Z>XHXMMKmuJ)$X*{@ZdpmLz_Y$BrU9pM!{14~Ptt z2{F+G84IgSr@q<->22OQHKQb6GfW~A=2Y=-wi#hzYmnDbQ$2jEO}9y1j{2jhYC9~k zp>E?Ad{=g3>^i84LRx1ltJb<+m?x0X4s8hHzTQO>MBIuSTNy12N6f+oM|MduJB_wKwcSS<&nJjegiCY zeX$IZZN|K#cZ9V%A#5-Aki~+bi*vqGIO*3)EJE`wy?l_4rlKP+l5q1*8?GiIv2e~u z@x@;*Dpp1AK}CC9Bg(UArqnq}aDM>O?WOZWw zq@%JNz7fAbyQlQ0Gj<^hV*QyoU)6VYHZXj1bjcOBa~sFAJg!LmATEL$Lh~Wm?TRM- z>?FLy>=%~qpqO0Pa1FHFJHegZ9k?iSw$w6F6;PvMH){`M=K^IwqvR1z3l*hCD~5n{ z*AOQ5P-3*L(o@GDGT9j*edqR~#Z~5Y&YuC2RS~>Ftasd0Vwp<$L z$@BMeSC75+>ZkI1UwXX(4|zRukAueRj%LT3{ffm>lQ*{JchVlujU(TXPDCFt8!K!H z*)Eipp`Ly|5qz}8TuZz`W5=vJp5fT;!AW|<Yv)zGzTc~03b^n6w?(^wEU zH^^T2LL6{uX6L7K>h0c`QJ8Tr=PmFlTX6@U0&)|9>Wf{CGw;)67K&zNNN*lh9xKST z?mqsKUgE=(ZN)GWgeQ?&+FPHwu3j$Pjhn!4pdQ@7w)`Ir*V-gWJ}zQ^;X!D;qG zw%E13oAakh`F!(gyu%!0$YQuvYbyVb{f%V}D?n_BqI$c?I))~*jEqOvFD!Ek^>6%I zd}BBy5D!(N(mFOwy$*k#uHH%264}emSwpr>6&ZHRw~uoz9XdZMks6AYazC)^%Q=>( zu_wE?RLwCC=+iyB9j(Cq%{|12;EUR&5eGiCQ?4m1%FZ!#!9MbcYdW{|)w3?#>cv&D zRae%OHT#=ONylm&_4W(j8pT=1*i(>+PYOwp>-`dknf#2X5IyD%-Q6rTs$Iu9{=8LK^9$F3kH{~p^ZIHMq-Ec({ctPJ zBJh42wqtdfTKzm-`D8gQ@P(jtW%~&2mrMcE0((3;+g^b&lh<>hZ=b!yzWK9U6=H{oufgcQ1h2T zyD~b^VwyVh8&!fxhwv(x=oJAmEPWoCejItd|}`48Ev>nXO3aLCqpD$plOCy zi*LSl-P^HK8ZG(h$fLf_1%#4U=ic~W)Ge~nv{1}GpTifF@eh+<-1KJA+QiL>c+q86 zF0<@0dH;@9bRh(z4z;Q_1d}(&PPPo*X{f=uSwK zVB8*T9Aoqo8o0T{5+@yLG8tZ9IhSI$Lu>Hh&IJyZbo$1Dc5^`FJytDjZnWP_3pkuj zFTmK!X^aG-M#NqB#wFVW>_~i$+oZ^r`Q_Obyi$Ai85``b9g6KdVR)f9TjV-Y%_l)Uu&xN(l+oV-BcvZ?5C za2#$vUyzmDp4| zYJ5A4sUG{d(#Hco*U$+CxRO~kE0AcChXQ1GP+J2&=f^Lm{T)CS=Qb`8+xI;}BA@xp{o>#qAcyZIQ7>v#aqs z>f}=M?H3L2s`GvX1h!J&TztfZ9N_rargH6Pqdio6R*J4G={{ZU zwT6Rov`6G+Q>V#z6erl%bmG5YoC*bBq z+PnI{SG88a?C=Jm-| ze(Z(L^}H}ID33SYgws7B@wU2?&;rWH9&l8cbn5KgCBKOAWvD1Hy>mi4wb6)s*6|;e z-$XnVJ3yTSAkSxR*I$$S@d(p)Faa^z5)!b_ecwh0ga%1HczuqOgo7UtO6dhcUAjPv zqAb@#)2|?ecp@%fiTHreCYm_D*~utq(uH}IQ$z~*g^@BpY1x-IZ}X(dyh<3m)O%*n zfr8pAyvqfg;@w)^b?*#^HUYE8b=MCpLVupAB;djq96Ip}CdF#sC%2z`1T%KF{$_TL zZ16xLNnp^8Cotp(Y|d5VwiLPcyg(nrs%voF)P$z#)fg-RnRrAo^tKttZLaLs zE_$x!v*10*# z%^2}xU90|IC&XJ^hSo@zhMHgZa4^ty?swl#i|s!YMqh3113w72Mt9(GLf0a5G{(io z@H?g$!LYQM89&gnbc~0GANw%WEilO@pxJF!GR2MGEiP1Mlo31JLLZ{VudvlpX2xJc zm%9O2hen6Ax+IEnrw|iX>DM1RtKLGZ${3AzmAlw?S2>Un!U{O8%Ls4#joQ43%2nfh zaUkdidi-e`4q3?Su9XP(itiq^(V`S|?FG2cw?O_Ngu+7fwf?+ZCT+w5>+K1nQ!4#0 z zSG?Ee+K3CfX-n|drCRRuI-U1>iWerJx~?Y0;oBMqQb%6yiSoFmr}w3dZ|##_(www$ z@_pAn_(0*LBEMKg%TSFxgOqf0m=1Pwho#Wkh?~PgH(zid zo)Og#Xj7&bn2SWd5!sk?YU)!6+ZLJ>TSjD*+*T%54~d<4MUiIeHHlanQ0cTl?2b|; z91|JFCK>-2th#|5kocY%eP6-`+vim+SYKz*r7W~3$NlA8P5}Q|UvfkvKT8PPMu~uoaOc>^Mn13%O z`70I_&#jtlB#%Hy{btjbDos&t2Oa^wYjEnS?@(V*@o}_4Moqu~-2b(lGq@Y*NOs=s z?mectdf`vb0-?nl?ǦlV6ajmMR>+Jt)qXS1N7s*k%b3wmX0z{Y*98vE>vQJGFS zJe69e$|Skhjg^y=tgVofvH8DlD54_=%)lY$HZNv|=M-8%KE;N7$ylx_ymv|ZPwk=0d zJ@olyP!4jUD$h1vZX-X9&DIv?bhjJvTLzNwh||b2Udt>D5hJZ@348BkCGB}~V62+@ z6ozB1{qo@ROQOKrl!;aI#vZHRjpb!gWWPRJM+a`upGhFMts=wfS0}&dNw-!%jhdoK zeV1>Pu@u73WUsDdJBBI4C`%4F69*TwAwj?}T&neEss;so5)rU@do`QRu-A^*WDb50e_J%?RRq>3`HRV0-0dv63a zF$zjYOs)z+K`j+Hklx{>sUfC3(vX8BWnTj9aBg=IE(&@PCc1Qw$7JHyNm&B1r^Y(E zGI@~E-cYW@tjf3!J?hS&`{evA>&8FR=n8g%p~Q%p7h4?)xjxS6EC_KF*%O8l;al#M zvO)ey{#uUV#1Hl6dt4n1!{mnB^WHAZkPW+hq1D}Kd?iQp$|6pYOco4*AKAdi*kc(k zi*-q=4886&5=m>4Na-Gb%Xp-6_=>ueNL%B~1S}JPZM7ze+yW(%1B|eaoBJUD*gDq& zT*sjZC5E**?Yh2Y0b{A|2ZnEmTwisyotB20E&jre~N~?`SlHLGYE$4h(nlZ z*=ONSjII{3IZ?8EAz*R$Mjcgb$oPMs(s^FcMW;Q`>Gr5>IJ=^2Lu)tVKw=CR!7Odc0s}V zh5FA{#cl$?Y~?mA#Q475IWq3ePKWY%f{js_pNh;2%Ac?900G~#8hJ8axjr(Q57$*( zc=v*FleT#)azE6D-^_Z&ZS3pVHBPKZ@Yt*`%1J2y5X(OpV$#zsO*MKjF3EHvc!1S$ zBkTplkGZy0C?n=D4-eKauJRJ@Sw+M+q8RJ-9p(v2MB3*N_+*t4?`tRE?{a>Z1>Yms zLl&3g6j^oMBc{Bh`|$8-sy&^levz)e&}-~$wE)Jhv>&O561D`JgB=Pi#r#*XFJQdN zS2+*#u1V!EOji6z>+y%Ky6H;co+QAPw(ey(9me3U+p~mPjN2fZlcmq^5EQ(({a3e$%M5ApI^AjIGHo^GxGZX)Aw8V5Zu0xG4=w;Zt8D} zT*UlHt&k#c5=TP55?0jL68HBOyhMk&17@97n7)Fbr zkiM7?^g*RY^iGCRUl@<%V8XMzKMhjK5V|-``oGOfJHUmj-&rB zU2@qWUN1+sqm{)f2eogFKKra#Rcl0v_g+(+N;!2ThMOJsg_^YvnCw8XF##OKYbvxeFGkL;%$E8@bq2+PpC_x!@?JN&F>A z0v-LJrtW=dw3Jit;ur9VpqSxmjHF*5n{0l-l{s%?wf#(pB1P%VICW&Z_0V+;SeAe` zplv2I(CQt`7)#e0SeA#0S)fa?IS7Z@=79GRI{r*Ts50G z#Y+E8+Uhs^QcLVvr8J9%Cl6VQ@Qbvr8SdiFO59hrSN?^r1=-E0#b7~1nMjekzMguE zj$hSSNquCZoPN_ z{bWIdOK(mST48S>DBDb~GS;cA4PSsbC+%r9b~Jo*@6=9pUL!cKSoaRI*fdE|uT^|r zZPB4+f7JANj{Vkg)}Wx@V;dT2uKH1`Z?W#76XwXUOYhl$m;5qMb_=w1 zKLbCnP-hnFVT{(>&BudZ!=cQK1sna3+Cd2>!A`SL4hX&CrwS|Ey+&fb)cSDeam_mdBr0aVFMO3bN*EfUPbPf%h z-Q+TZ)ug;=zJBiB?K!3>Jo);}Js&BADfG6p9b;oYxBBHCTuQfU*ts1WH<#AI1N~{){B&DIKB&~#z)!ShxaqE47@A$c1CfmmqP5INa-)M zc2@O^W_Ri;?IYf4r-p`X7<_e!3iQDm@dFqp#jFIkuD^z!R?^p0bj2%}8T@gIEKa8* zb$PYdBQfB5_iA(AwsQ1@%F?OOXU-yplV0eVvD`vidy&2GkQ2WLL(P52X*iK6S0yCbT@*vca*c zv|#X4dA(`RbE7K)pS$&0lHQ2JD^WMDQU`K8hQ-rKmew zTiSXYaN7ATd7CM8R%YT(lGovG`aWoK(Y}sGwrZblD!kYeUn#Rc;5K`y8hn9J`#@Xr zts(YZw+g|>sz*!gYma^^L{tBa4eyY%lydK*&7I41HIbN-OnPexjE;&Q+m98zQP1xS zkO?I!e*vU{07TKSsjaKmd8fgk-b6S%~2|9E1~3c_KOs$6aaJ)^S*Sl?;I4z z_{Zj!@i>Dz&8z-Vv<6dEJZA^he3eP}-rjDD2*^haA{s3=Er6ctRqgBVE&zb~Rowsy zag!81WG9nm)IoI@-VO@^ols@k=0nsr2{SRP=ArZQ4D^imky6_C~hz>%(9x@fL3 zY$WsGOaH@r*LzyBlj`w$p#$V_GEFB(0~6P80Ms-bC-Nx!lyiO4ZbJt!2n*5PrW$UF6^nlmy&0V7`yzR1}ja(3-ZE1Y#3yd1LfCE$B-zq0jEDH0^SWn^w&lbc{w zm8Mo*u9M)1V2r_><|}t7&%67w-NvM_t3`kx>NPJd75==Lp4$B@T#iTPi?pDZQv6FK zONZm|9(UvG)yt84#;=8yw8vgq-mff>2_ev10z{FBhSyS(=Oj(H+ge_{fMeL!TfblZ z0E)5p-oO_2W5c$#PN_Dh^bi6AxO}=v{yxbE#jzi)0FJ%r2i91P!+EQv#p|;EzlzFv zS{8dIl+KGsA`ZGFexzhTO03yC0W8XX=eb_CJ#bkJoPJ~eTc(UsXsmF!WI^6QxYo2o zu=}jPu#;lpsek_naoE%~_L_Euz9NjG42Xy==(}RShhM7X9q~FLQMRM~drF#xW9w=E zC;OQtoynhPEf6MXvE7&6EZ3e#MQCm6{6Rkh!|<(F^Z?dP0*cfn5>cXUfD+dp{dTT5 z-Ns!Dg5qu2`3F7DmydSs$n^vt;S#TRZa)Iu8h*q~pk=gou*RN!7;07=GWtX33YQ|K z;ocWiucNs`ow{tpv18eu{rm1UQps;~E!nZlRMjlH$u|+%D76VqQT@$!bQ>3|Ua38x z%d~hv`Wtu)aD-;wbKRZYK4$z3xpbN)Gr}SVJ_Z51x2g!OjDUac2B*Dzt}3v=8G4P~ zke(#R<8nteQ|QfSu>o%hBGw;*0}Ajp_7Yu+@f z=PN*_(=dB{Lu7a?n2OHxp<3WyhQJ`?xpDAZ`}w}XOkZSFxuPX`RonSy8|XXKz+y+F z`iZ+Vyz5R}Ba%hRCiL*9ZjJe1bOY8^M7z(qHX(!4oJK2}K`}o^oKynXG7CgQG>;oT zK5zWXMzg`4jaYkRCwExhKqn)&P%bt}KIlr)kq4v_)p$)UJ&io5PiNCH{EmwtN|)(+^)o2eB6g6d=GA<>rG>9|Na3fm@?jG&LY+M z!gz0l$few@h(e(TOLQS`VX)(9@7c%ZV@D1t=aAv>ihL!s4GC3%AT5T&d2IcL+6<7) z7S8U(0((@3h^OapXkEq0U7W0j&V$S; z9MxIUI&+1(n;G55Rf!Iha(~B$)9tEzq5cco$3IW~9VQC~sV%a2&9E8X9qm3p(Zj+q z{VF!#?C=1{0I54NXDaGBXU|jJO&*3S*(|>8d)>g$i$|(8)*#1VJoYRlNs#W-oj*)3 z=tGPK=HY{eq1|Jky3%O}roS_ViJw~Bo_q&fgLy>N`X@Vs#LzE#hZpQgD773=eBf1mit#Ct(_%cu zxlk-@6F=_m&fFyC`!*Ut^qLkLsJBhIc-#-F=>!T}9-uqYWfvwiX5!`KfI`aOZWreF z0yeb08!S$FTT0_IUZ+6Wyju1h*hlsk(7mD>Su6E{6RlAe+WvirZ2kgRI$RMO;JT(? zu6(MoDkA%rQFzTNa7DG+H#td^I|6hT(ctH2usaw7osM4D?6InM9|!5)HSGyo7bNzM z=~X}u$q)YJ)|%f8h|yjQ#p6I0&5!rjmYy^}(Z|h=TbQLS;jZQ%@tjRF4jP4>g~Ywo zasGz^DCfUjm5e3#yW3ZAq+)f`*M=FDXY)lXxolRxTl)?ArlcC6LKApHQBqlf7~Iv_ z9El!025fP}>mQBj9F!oe35p(Rh2u@3!1tdaU40Cda~2GE=l5AzdC2EJI2){w$7m zOcS5*K6S00&gq^!=B@?Y0#2X-Ak=xyh8|~gil4>Uf83^Mu`pY4X&WIyzOSo7(+`qL z(6ik9R)9avdl(h%V_`FLzxGW_Z~g{hX%O<$gFs=7F(=<&KmRajxM+od^mdw7ZWwn z5tw~(#Y*w8HVnE-kjYB{Q$=}F(CA;>re;#oLT{Ic$!HpFh7r1#K{$}qL48c)qg#L1 zokYkHUCBV`%nmdnadaPRFh+gnek=0-_*R||j&9FYC~52sU{MqH4vun{DmCa)PZ#G( zmJ5>oJBXM5@O?jkK?@ocf)S8t^ymNoX#)Z;Vuq9PO$4q1|I~kn9}Q58_BKs{|Jcyt z=2|zg{TTuS@_(4E0^mQ?3gCTK{JoPJw9QbI!2={qX5ZXQg2y7FUrWrG7mB>I@D9g7 zY;3i3#r(AFP*))ZL)O#6XQdO9f6k$XX&T~Bk_#bDCCUAc(||gK)KzpdigHk-;`CaJ1>4qr88P;`}{Y{X=cgN@=>uaOF!WGaI-GCwPYh zYB=6h^)(V@Dx7?ZK=w)uMxJ63%{O|FzRuZuzX`6-_!dHo_5?cq4eanjIS!^{ixw@c0k8o2XMqLL9PdYh5u74Fk;;REe6l`fP<5} z4{$kG2vxIFjU1TScrD9P)U7+)l>{ND@GCcjh2diu*w;_p08LpO-9RQ;PL(2PD_X1Y zIo-BG?+mDI#R0={O?56M;oOl8HYDCB_aulUH;=(|F9!j|#xUe=`W#4uO+?#dL>X*D zbs+V*^=Rx|t3XDGw$D{C;eNOpQz)}hG9r!}c&7lfzYHm%2q z+4FlijP3alARv7#kb1zihrhuB(y>U-`^*PcZw_LZntE^q*`ckybY*p?l=vRng;tdQK zGtj0-1Cdl)9^Yhu@ceFfDDgeO;ut+?k#3h-c;&gn`sj@Y^FlvxURkCE;qC@#Z@~K1 zw#3UQ;g68Ie``Yir(QXHQsMC0%6)0#3l~rU4;-n#C|=yZ)(ujd?go#3Hzt@`?nv-h2ff`v=f#Y}`G_3#w!7m(y8HKBZcB+?*o-ZXKqhEotBJ^(4S%GK}7 zXx-8b(77bFH}Yl%xca!*j|rJVz+LZShj{`%$|xWuJNBHuoC9pbQD7Ej0SHDGuOC3^ z3nb&%n)i&+4LoWAi;$Z4j8B2yqX124jSBM|1?n{iG;(=<36}{;B@~?PP{nE!bNi z^p4(wbHW2U2!OX(>&4-4q4WAsGQ`mPpjVrDBW%LRYtQ1fQe2Rs>s&8jW)6FU`%M;; zwg$~rOpbtaNg4xan&=xt2GLk&LIR>kZIAV0lapnJeFHD(%*ns1^?`&bEUrt6yhravj*wkOn@j=f^S4wqEZTsNEF#GzF^aDH z8X>g;);vw2U3{Zjl3Xzoc-Ro=zG7zk7<6_#1&X;*fKS`T(PsgkyF9H&8t7n{2+IX> zIvS^AO?lO(jYd#2pb;}eh&O{SJ)F33w7y+?5|!8wgAarXMeu>eqtXZaK5SWG(gkpX z^jFvHW8F3Dmld3Aff+x|PB+Cs2BVEP&cdB}VviNSxZ6WNN{P2)br6_TqM!Y5*u5{l zc1nLNuY|&DzioYkEIieFI85 zkGA|lHx?`nQC5AUX||vC{HHi@(kg|*cXJ-U69m3>rF@zQ%`WzMS3?*J2iTzSBK@Ro zbr6XP2+U?EadLw^lO$6Ci=r0Lk(lc@I<(=z&>ajbutD2+RYgnBhbS`E$aFA@b{T9hA&SW-)y5k1&YSdMjAZr&V!U z80?%F8D-JB-(x$M9ke(+DD zlIrKWicf_jq~0T-!ib*vn6=-a2}o7W^79W5rbhxIxq%H?edq?DNKN^Mv@sXrrRthz z>`a&2&iG6#ANvCZe}?$+Z1?n_i2&X<7}@nHfmJ5VPQ~a(vjXtWPXt~DB|fFC4eT&B zDC`Wd(RK?A>#XAictRjfF9|TZr=D*rKx$k-{x^$@$7-s9I9-VlE-40ECmrM=g*Hz$8K12K+AK2Ywz4@`T=J zI%>MRVv5@k_t`z2eK^vbezzLi3b$us=&(qHVIPQ4Ez{f$V2OBMVhY#MQ;Nu z56fYBQzR7>p-8$7yf~|6!-v_RxDHTs^Rfm*TD9gqWu@E5i`a3{Nynhj{`*(bM!(MM zdzg*>&DVNzvm(V8S$u&FfIZzwmW)~F@;1-vA))<-2JBvxLKLOR0>;6LGhv1077og~ z3x#{ELA;)OeZ_HeR%pvk9YMy6=rKmhgSjB$0?H!Tbp3de{WcgkHb4WEex+>C8A*SI zFJA-f-o;U<1{qiw2ZkODu0j+yd#m#s=jt#ynOVW89 zjbrQkr8PO`kh91KucGM?r~+(J4V62pLMxcIJ8`-*963he6Tlb5`oW!N8G*JG5b~QY zar<@+bC$_D(k#XJq=YI=j5h~mAk8VB#%|~-vBK%a| z-)b`-8~;FeFwQ0HO$77wgZ0xVWC59sapbVT3FC-sR9))j%1x{$FE>o_alPmrzMKBO z22)y>K-H-E9ejw-K>JgV$V1N69O%q$MGz8yy-ShHo>c~3Kh(3zvZ#HMtycZs zp(rBX4$11&q_fVHL`dt*(b#~cSFa3*B&&LSZn*XV>`7#0lS^z_9Z{=4-u>jm?W=1Lw$63ZtJZH@6 zk{_rPE6^&Ygg-i&kx9}4J#^R!k4WI(bLlk`xJ+VuYKuSd-B&^(8Ida9KMGWnf}3JW z4;DvO3$^7)2|IA=JM1rQk>i!PFdfbLI6R7@CyFxh~g)C=^Ac(P&Q80WMQVicYmn_@v` zG~rX8FiK1e8+=<4L2>t=3gk%k&HAj`r8 zB8HBxEL0_ZRF(%XPvQ}Ey#>j3Rt+u8G-0(2>Qnb*==PzQ#VHJ~2<-`_!Bx@k3drG> zCmzNRlni|?3#q=XO6s9kd*38@K@E{ecy>l7ms0>8NQDFtF$D)95+XwgY4mZLp_E|+ zI64H$di`+`&oUy{6j0w6y4}J!2h+oMaB7frvzWQA-3^d!l7Pne4Jq#v`eWg;{@K2& zS6}$B@@+`2-hu3`YzSgHRbeQqJQUXo#iU81VaVlo1y?l@TPQnR4+B5!|I(_5z z>{XK|vBbxIY3df{W2`VWk*K(>&yZAQF(~V9MqI^vqhorW&OXTCO%m1=wTFRJm;&er zfg>A+0Hh)>_K-Df3Q~mdVe7JhY)>SVkW!N3G85xOA`b{&TlB-Bc?!4hjPrTKi^1cS zV#LPZT)QP0cFn>G@3Y&ye2;so1UEJ}IdJ0+hk9D5l8x2YXXwVk9Y~)YuB=;59v~2T z>pM*2E>j=aVd(%sVt%lQ`FZ{pH_x72>j-OvZISyd_RTW}OD0cdWEuzVSs6kt0b(wP zT1AnCIuq@d^){>SUyH3{Nx?m5+|8VQG)oM3fWB4%Nf#{?p31!{E$eaOAhos~{UgRi zzoaxN>^h7Wu@eM&7KHyrhf##& zUYwzhnx+t}*2Z6f)8*)qh?4CyJd()_&As{7KoKYCOZ1O@H+v|FKUu$_jBIqDfGi~D z7II4#7L17KWr^xR$@RYit9xXjo@^-D(J&3+hCQoTNL`fr1@+)pqLTX zb%TWoM?)5=5asK&J^9)~77`Nki2M2066Q;Vq6c&+%=@ZJs2Y#gKSd+_5ph@;at~28 z9R=p?d9o}IWd~?JfBZJj7{4A5X|@fE!&Ai6xl0EN+%?vUJtG{1;yMRO^CzFGB2X}@ z5e6Ay66{4q^SFJX@VJ-8xwmCz(p3OGPL58op%pire3HIE&Ku_q`BM=Rd%3rm@105D zKYHr0__jzU*&Rxx&IE)7#`Xh3R^`i##9~DH&R{p^ z1`EZ1O;xn#Vd*<#VE3wwhBgSs;qQh%6AR{q_RT_BZ+g%#(A)V}ZG?W8ih}G8)yo&i zElPZGDLdzVCjT@^1=VyMUWaqben;vp$~tNJ{b1f$*EQ-4hM~@qY)@+%dpFsz1wzHl zDtzadwkC1^_w<7Dvp6eUbf&?caUz+~YLxL?Q}V_B>`~g~ke(aYnUM#SMVWOP;cC~z z)ZW?#%`O^WL}B7|1@TgnFmS_=H8-xW%rnk>;O)CDpL*|5tlEZAL}(IuPeo7B_1TVG znxg+RcPwe?cM*oFY?8=0c!ebLISWHVQ1v}0TgAGd3=8kE2lswI6jw}W?VD6AZ6Z?2 zD&Ar=s-tq-rBstyWaPLQ^2bdy3HpUxm8R7#XISkkk^eDljHIInA z8$&5v?cW?AN4D5HwBaI#6{dmE{LL}Aip!)cMA2Q%WF&>324Wu)pK=3O7#2vSOnFtB zZ3@skwQ!o=EQWMQm78;}g0qIYKQak|b?rWbI;Ij0cnr*9zm-tno0mUy5SpOD7@a02 zTLcIZBM_8dzOjSLkbT*vDce>;1+El4WW`{P>Zl+oc1djdHrs^aWtpo`hLp_l9ou91 zH|9aQo_ah@JQ2RQ^H9r1;1r$1x5H-6$O2~J6PlT;F{I;{FU)3~?Vkn1;;OHt5kkA{ zSeIXSE4p5X=zuGJui}_X0CkSt3EO`1fDTAl{sJpWVXk^f95Mj^J&sxEwcoovl}kFS z$+sH=-n02fk>uj}7djGJ5tu?Y*A9}8ydkhC0OWEYbQ)d)-J>o*qmpNGWD%8 zkl?60z9jcnWLvrx9xANRSC`(ioXI38J);BLM0?i$(DprBq7YjmgvlMy#B-TkZ=5f5@^(~n|)9jz(Z zH}?ni&L{RO7tVm1AbZW*zDZ>2949oPO8=A)OpPo>qhzZ`1k)ug?XNCnzla@;w#>Al5d$+3p zR=S;Fc7_5^6o$uHmsTn$H!y#;BY3j^aQmL1Hjd|iHjX-)hPLa*wtk>bSY4An^^xuV z^O42qV8!g%b3!kBcyIh|S>pfs&(%kFDe9_i;~%JZ{NJ|?r-i~$stN^T+=^f^T)LnG zKK`dys6Xsr9`x{k|KB%HDDUoEh8UWI8)DS|Kkf=yGjNXQf4?gSlg*|7{gIG#51rxv z`#)EsTbj%lR{9PVD=w@Dc(onW>*fs=$``%M2-6j!O|<&k5XYRe+-vc6ejadR|%kaM>rlV*60oRteoAA_8kzauk8jD{Ay zc5qtjH#krYWvnBAc5)75`tBP2aj4IRUdd{=YW0~$-lXdzi{djrVmMhJ z3LG_}whzEDE7;ElhfoOu377 zjbrgO9r*srD>w@p$0Sb?C2?MN$+6MJsnYUeBssvvQMbT-vm}DF4EeVF>}}0nNN=`c+3OzAnwLp?rRkuy)fx|4hr1& z(!ZboEcJRTEFOj?T7;l0eU%Ls8NxCXRXrj`Fp)ytpDGF)J`%f$(Z{ap{u1vGv5Roi zN%b(YrUQ%9oEgLYz2SHB@^lL-_>8=NP$Of(XrDybMxVOrolV?)aP}fCrH*ORDd=Qh zWskz(Ct3c}llv6&Y)zBRTa*NXU+#E5(!BZF@S-kQkapfiJGy`JzDYi?+Iiuf_;;d_ zq*K%@)EJu^UAV1FJU7e3k`C+c?gQOAlj zS~1P27b6YeL}OM26sHdW#Ua3g35>Z4$@ zov*w*eVX&c7X`p75Pme~02z2!23-`11}3&SAUL7770_#vseTHHAkRX=l-XeAU(Zic z{)^;YKackW6ruKJPyn=L6H>RheW)MOVO;J7tm7YpXyxz-gcQ8m0IOH7^nKD?zgQhk zh2sJr;|UmDTM+MEV+as~MC(!`I0-_BzJ2WH+Pi!#1zmIFk8q-am)PH??iB)kkn4V{ z$zO-4S_QZ}qf|Erhv`f2lDNSZcM3>oBhLY2l$*T=7{7e+zi;e3iP~H@Cjq!{TJQ}} z>9GQ1^a{0Jw5CP*R0B8{uipen*t0YjodeZ>wQx5(_!YQF-Mh8-4-dal>&TA|QUa78 zdzGi?fJEcIfw6??*ql!bQpv{*zSKl|^ch zh^b4*mDYdm=P$%~lW(my5~JUoIN4xjI13;o)$qL^s9KjItCzU_hhW^-{RI>g0H8=@ zGR$v8fLl7wMSZ)L!J?n^okkjb%zD1fgsuuvJG4}X+Mx-S|N43bp0Gk)vAC%lFSKR~ z^+SE~7`OxzxJ0q!UnJDk2DE?YaD^0nM1#7A(5KECP|iElk2KX&iR2;b0xHP@mI3_` zzAW$&(BNfE3|rR81}ehKe*gyI03d_Q?6)Oy#cG%HyyfnJJqRxVGX&8yZ4z4uw~bUD zgyCjAsQETI1L#m1IF6J%%Q`$rwE>kForRv%_9M2sGCZ<&-@j2YJ=^M?k<)j;Avel9 zeGXmxe&yBo`xuBP4y2w53ImKzW%1gbG>b?1-oTDV2^TX^X?cf-nm1v6*Su)j*jQR1 z;SzAq*S`z!wZnK5`DYD7poHsa4^%=;F#taK$L7D15GZ#r?tXTIT4czSYl85Z zR{FCYg(m?TWdhtL28MwRPVfghRk4(6#|EE?%@?3x1m+zg6Cx0W9P%3Slg zxI}VmKn0+)8swZl6N0J-V46P_y!pKU8~8nr9sot|GANasIlcreLH|W=58%p*pMr^% zx&}`LzRU$SKrimM?X5+BpvJ)GJZ#(Rrv}eNw=aZSbPq2Bi)JNY{trF)4X~elDvStz zI2YXV_?KtDrk5!ua`sF6VOlO7G{FFYtB}o(h*<*Ze*IdJz(yvu(uytoIMDXeH@!Uh z$v1m{W*}ENl{9^{k!ldpb6z|$dYcN>5Qh~&C_;_bc)+{Z76j^TGw}6!Xbx(G3oNk@ z7!o?sF+zulToon(+F>299f&H*5Hun36({sia_2SGm9 z;Avaeko6)Y4rCuaS{=TVfc+aW1K-I0=mK1y9JclQV`S5b9l`d!^B)a~E-3S;Lg3%u` z(x5-rXJ$ahDc?F6DFl=6iG`q#ynJG$Z?m1TseHizVQlH4qMY|K@8Wwef0=l+G7DI} zRR&`^pLt*D&z2_3IUt!*{WfR62Z^SAq6cu_gonLMqg8$}iG!>vV+BQqjDxrviNgda zY7QK;lK}$fZwgq#gKtXoQl|iT+qPFtMdKbsQ$5b?#B;wJ6RB9J*!=k|K=htiug%qC zL@Fio%BzBk@dJhu5TCvbdZIQGU{46wDPv^?&q-h}mRd+)V!2-%KMWb0 z7vM=(&joZcTwR#)ypt-+NKhbD)m{hnexE}iC3jc*0o+zPf9?DHA%u|6=#C=!8oYo@ z+V=jru#LDZL^_h*h0_R!e%lg!(IgX8=mmp;l2Iv#$NwRov{7mMu<)p%+0$E|y*RH| z^fK_0d@3N5#!iGg$=KHT7#USx)i7Os%dR%%lDG<{|BL14$^h5cj*cLB&!)<4|KkHk zwVA^$;kvTs9kRI}Sbl{|wiAk8Cn0J3rXuCW` zWD4=#ne=;{&Hm}<7mt5W`spKQpuHj|!jGUawt=TI#7_+X=a&c9m*TjtR?Q!22if&0VMJ*>0~t4G{PhY`BoxF{H4Xqsp3f!_Sb!Ah zRyP8R96PH6uuxPSXa}?WL^VHwFyq|bKfUIU#U0i_yEGmmIxiH3J%nRVpG$}N*{dcm zZ#o(cYJc@{h3Sy$S>Q2FI+6v(jEP;qZFW%crI5RtOiQW@^B@)NRht9BI@xd(G-cIAr3f|9`^`%+o8LA*s6+eN)!ad&@$n^M$sYKd4*DRq?(Bcsdo2z3I4W zQMwc|0XQ#8Egi1%TInv|HW@ey6^6VnM^6+>Z{CuDS3|GUwmV|BOcO0SHpX6Z)53N* z;W%`MLAQ88fkg>&HQJ(fqYcml0L)!RQ}7L?*e7MLVxZwu;rx#8j|F)OX@p~l`^YTa z?1ApSko<&AX?~<4-|rGIbI7++S@vbcL$l5SH@QJDIr{g}=RY=q#Zv(<3L6PleVlNl z`<1sj#C0w*!cGIsmObnHnKzHUs``!Os%!y|D5=Y$y)#QM;|hOuRoQ1;!9>9GV!f^+ zUu?1%j?6vk0^^=c%Va2J-qk_S>*86i%qL1reiLKB4MJB<-plo(J=iElxKyL33ONaO z(aa-Q|IK}E_gBp&bXS-WN!_pEs(;R51a0)s2xDIR+a2F)LUaz9WAGM>U1LpzY^xl|=R)fO?@R|>mGbF^ z@%k8BO+Z5pxj-wBHdk5Cm#hUcqYWJu>8>JB1pa*G5d{REE?-Q`JT8mRN#G&AcYS~U zO<&`4{wTexAPUybfLNK_UU!>c&9C6}5n&JMP(APireK70fdY#hsx{A1aZSA#?!c#PDi^B{mHo!u zsWkKRzGXrf+X4D)>1N#{&sjk|oAVCeh~@`eUQ&)m)=PggPLrUiBcMXZXqPN6M{O*m zj87%Cr8)(r1jW~QMkS`~=C6GTYR+P?j3$Qo5^Ei!$vOdK>A?B~*^<1jtB_SzgqY2V zuw^VRGvO<{AnL1*bTpng$W0d)sIo0aNb%&%muR|+R0fcG{^RvNA{2$vtq$H@%64>% z$Kd^z?cDH(!tk!zyloc(J1q@UF9Q*M2sYTK7)n1J1X*pd+ zg`}QB(v#c$oPF@Cx`c-vpQ$MKBKPA$G2Hly3ok=wAafQMgn1sIIjX=NW&gI#*Dkx; z8?mxa@Zp3ozKcCDT*4r%+Gg@QU@m?5aH;Cg%?6f~)-@y25%;KLW{DR35Wq&M-Cia^ zeZ@|R%I^C16~KnF!!j06BF;`4MQr~%7<{0@wyW@iAKPL({|juT;Vem+T6dvPx|5Pu_rrORRis7lajfO3;Zswv?!N>fUj;46kS-Wm^H^#HW z>0&zN&tFf3T@fppjpq`S!83PV0idnJ2N8_UK`J}I;s*I*Xm;oM%Z>r6$l8MO@utV! z*GO2E%-Ex8zs7R9v2|tiRcx1ZQ|_%s9={KmWfx@Lg@AYKejXTgnz6sRAxwz)kL+tl zvzz1MFiBc&9bXY&8O$edI>3VHhrW&RxyPZ@%2?{>5SP?2HkA`(g>niMrLyVGE3Hzi z0YZ|`ghqe5v*T84uriL(J(KHnkamoknIUy(j;fr@2{wDzchD)${j7yAGQ35NM}sSj2$r@>cn(Uz|SKNG;raSZcaMGZc(!GBVbilFa{G?_li z4)2N_wx!rkyTDQ(FN#nSV|k8A{ZF456Rk|?{qj*SI;NRV7gS84X{O1dqh34mxW`FP z2J&%}#X%p^r*1jBqKP&~4sBY05L9m;N;#oCD9zy{>06F@nR5s~ev5mhm&~%sjPBM3 z^CNW9o<1Y3%*-e&8^6+J<+x+7t>7i_5zZApnOx{s*`kl20>DqKYFmsej974VD<3{v z%T0o!0vX(U#7<8F!b-niF#5&I2k|EgiaA!6eXHwO$GSI*<^zbKv{y@;>0N3{bUQH7 znW?`b{2vfrU|Vta-L!izCu41d9Sz&LFZ+ob>UF5F%Ux`K#}<)uzSu~2YwqNa@@n1; z?qfW1$77Q7q8N$WBUjtI_xg`I51e=-5b!yh*cg5NBNoX~HuO#PSpJk%F2MStBpodQ`#7-lR^>P=5!VqcQOYYpWA4~riY1MrUTf=7_rRBq`ZH*AD4 zEA)BkR;mT*4LIwb=e_aeE3&XsIZz^+MbpzQy)%wsf%uB4iOh(_kriypG1_RN2l>=3 zR{mYne|4SfYC>`oJ$y|fx2TMRa>6JcdQvAf9N(P2n8-g1BSGhG(JM3cdWSM+ zsjC)_yFFP{ySkLMq_uM9{?pLBwG%^LM;D`$RdU2<*O;j3@5W^WLm|OC%}1oCqGll3-=2>@(OelA%nBD*<-p z(y@Wd;V)9U@{t^0{Hr+R$f~BNtgwDJ^kO>X^0|*06J?&ZO2RamDyBSERMoE5leJA{ zW5lsI-Sm+amLwg5ppEXnMQ6Vr7FTn0YVo#(twZ@p!}_3m?g zs;+XEQ?sGeGu?Jsva&hGa;Ja3q0iUwK(DSc*qdu#wdd9gA#Hbp+l0_gN>Dnqd@E`w zW}qrBHTgy1D;mD9cTb@13MSBOvGwen+`o_))DM;gbU`S*ooT&l0kfbegvNK+YF4@- zo9vXjq5Gv-FLzv|U~rrqt%m+uqZyzuYh8TxxTD+s`0`QGhY|@VD5T zO!R>x!2*Wo!|6$=k;&%$-rAvmtyz9fzNa)CA}}xSpOV{Any*JJEeBV~Z15JE>)M*qHy|hC#GWj46c9$2qh~qj#>Ee*oo! ze^`85sNc@8gV?TdnE~)FVv5UNa|=b&2-_ zCRyO_#KF}KjIORUv>3KlY}RN;JX3L{j$$)F{4V2MN3 zl?3C{GeZ)5W~*Aa*FkyW7A#mfhgB&>-U{UpHZ=#!f@KUi?MtJT^>0o#&_DK5f|stt zB01=s_T~)ysx<}8t@!l%S>gq%-;YWG@FKUANVnen6-y6kl0*_FF!989;?t#!BHT9#sL05W`@?g&Ns zuE19EX2eetQaU!d^v)g)f98i1oSS%Un2va1JroW zv=fxox;v}fP^xxz1(yccB?Y;YCD&+G1;dQ%0?Ez02|4_3i>K0{b;G(5>OU8Br%j08 zWnVL{%ufcgW~H({O#}PcYZIdc0=s%kaLg}6iH*n`4Gl5&m}BWXBFX-}_+B{j$73>2 zn4^!~cV2Wjy%HKXj;mjVi^AU7R_lyL;3eOUx1{#%(&{-R+<^H+kb8=gUi^q!T)84@ z1kXPS$vuvwCvc)p!2YqR@vg@?yv|(A{kU{U`Bl{ww zugKWmvZr&mr6*}98O7kWLT6!78|A{S4+-@hkS->(H0p@&h%7!g${;VdIws`L4V~1( zFfWUT8ytb6aBfUKZ6~V6I)O?nAoTzfvA8xPrFcN=C(C!Q{cnB zip3TD39RjBOt6%Zrs1(th4YwRyco>^>PkK^@M1HF-r%AHVJf-l z0U6V-gqm?ickj>ngaxe9DVmGpV2n04&0I!it&s$xg{9K#x>T`1Lf|(KD&TJ9L!YKipZyz*9L zFBu|GfC{Z#=QETzvS>fm9-!m?kr@EO47x@|QtF_x8l*>5Ppwx(IV@l9G2)cp#PBHb zTz#0}|7RVGJ4nroWhitsAcU)zp!+ZAUWAJW;@pSlZL){#Cc#9zc`YvRWc3Nd(Wxp8 z4El1(vHcl7EtwgbgFWPtq%ao5<#!X%k{}mTq+ANW6>CqQFX^%>sjflrMA%(aU|_^+ zK2BA6v+tGm7VmVp2@%e}(nH?Jm5Dj$3xpNT+3^^a+oBiMX2=3o*~ytYEu(!iL$|v5 zO(Zz0&*hRi<>796J&Z|UBB?#QK#op&@7>NAt(%l+?KE$o^g3NKeFTnrf5xw=#DHF= z-IKm`MmG_L;Zri`+Tmla$>?yM9dvzZLOdwdba7wey@IkwFE%ZQ+|hX>;=_m1neCm5 z$w_av@15GJ7ETw!d7RZ8*>tu8QVmpDk>Otu1%dj4t34V;n0?fzVRrtl&UzX&kE{CW z^yk|UFu-2h5v3C1xX|76earofoiS;4!sbhr=pAheCdD$tU*tTFINoc2-%I(ft11M8 zN5N5=#~(S~5eQzqD~ZMVw35%NdaJtIXcx5Jw)Cz5=X@b60gPhhb@DeC(Vhc>I1aRy z<*>`S?y$LipQr{dK_Q>FP}tX>)9Y$83ghR4?;ah0i$q2J&?As9>>3e2Jvx^=b(Pha z=yVLC8n{R7=FV3oVSS(1q#iCr@#dGCCc@T*YYfTpJNkmNzhA{ehtFWV`0fTvmikuq z+6jW03yiMCZZNvkj3L{05#DA>a5q!({W`6{@3@}^G2HE-w5BRRG$CtnTpq|q0@eyF z^G9xs7|=Zlp}WOj;0%_z6N_Y53`sBYxSCj_l5>Pq@b%hhfY2;vlAtATU?+qDgf5>zzED?B4n1q*>K7!+p z^p7i?8842y$Ex}@U;vLMnoAN?-J?Bdth&YHE{o@ay~gD0ocamZ?o@X6Z7rAtL7?yR zv!a%4u;jPvjf?iGnMK;&*eQDSc0RIlvpGzcUl(w1k&>&*3{)uVMWRI~lj0&{bB4yY ztWR6FDxU5|qT+|l3xygu;uiN8V*GhWLyT|yUb=NU={^erwkv1*Sj0m2FTz#e2nNaKnxFBY&#pfB4_p*{f zZII8s=JL4XtoirC#KTMiWw>vY+epio;m6BbigFtONF?sL`iMcVn4nsjGz%aN^e2V` zzw`lREROc2qo_3mphM)LSUaQzwOCSn25kfXK^M_PSk6V1L@hkHDMfc4Pmo>XO^ypY z(nZ3R-AR(enqps7Do0>!gMpC-Y4^^`Et^EKqtO)MN4 zq)`)YXYg=ZFl7A?A~V+jH7%7eRTha#ul_~3p1pYI8|i&up^$}NXKHK36e`Nlp>v0> z$~EBIr9R(2Ah{|;!Cz`d*W}+Pk0aC46cJXdaGRfHuV?iZPcUf7&VlR zkD78Qki%D2;5+`l9@`x+mpP$5sU2rb=SlBy47nwvGU;tNurBYjHxp!9J!LciD&kc6i*3GW57 zJP)@OM?^SkNMth@cp2A>+5?18M138Ww{DuL0O?M!nmO z^-N~v%Sn^WZzl|HiacN}WDsO{puPqb0@l5ey-#OO$82cO0CYTfxtC)5S6jF4S=0( zDz->XpT%13spuDnz&gY~f!eTPs((+%Qn>Ggn3rX zxV=A6*#q^U`uWnv#O5zKV+bm1cFg(XFg}2r`Zvk{{96t5M`rxF+n!;fyNM14)gs#W!=L;j(jF|l7ya%V+lX}E>LT)BdX-WGt!zhVS782rFraN{-5`eJ30qNmVzhQ|C;|u?Twq~PD^e2^?mZTC7x@& z^>^5V_fq*U#iL_WpE#OsO_b0joO<=%iKVK=Aq8+qBy^D! zJ7n$TrKnI8dE zlt6wd-@8l zRADP}HrD3e-(mq^xLoG=OBN%a1S1%1R90qe(3!!czEn!ire6C{UT2bBCQiGhEQ^USO5q4|M7o8og@pev<-p znJUP92=??W4D8`w2J472mBmB_r9GFP#Q3!=@qBox8_O7HwcVY_HTZq*`B5Ig+ilbM zH5EJvwi7rh$3zPxpCeU0n%$@Ae>CKDp3-^aXF4+@2`p)UX*F3YmtMp$uulI5q0rFF zyXQLvPYbYr8Udt@ArL#G_p00^yT(%BY}!?MAX6JWUwQ_>lZsw;UFmfcTPo$PJA0>Dm1 zaP3o)OV?TZGNHrojkBaD3Z$QbD(AmN=y~Z3AH#q_dIi{Yl{A27y3W@$?v`u@c1wTQ zvz@Pd{ms-?h*WvO8ckKpwgU6}igWD|fBn`9>*1Pw4@J7GA7>G1PI=C>h2NoiMa3WZ zQPa=tt`yq|KJ^?%iv`d0PCuIkrop+#0m16b$ouhxR1zE9Z5~8!b)*QN7^7;pFMt5I zWnew005~}*SYcl0kdk!X=R@-H@F##D_F$A4$KtjLRK0op$`^9pnw=QblF7emU*{H= zt9&sn3wi4H@pm91jeh$PK+0bCCSSNPRNxhHuwh8$G;D$0P%fZ(^iXZgE&%$CsYVgi z3_SQbyP6&43P^p(^>5p)_|o!HsH3;Qp5`%7ihrU? z>v%&0zP`PCQ)9I(!zU8#S$sjJfs%5-td4cL@sSfEfK@XTsbGm-Z2ywTU3rK6+Yxvb zR9#8B5-9sPqVLAD?*MII-3A;Z8UFsx*<=Hk9?(V3^7muCIr1v?S?Dq(%vG6$0y-|I zkE^7dK&GQ`WQQVK-P-3RaFj-F?t{k3e!owx z$AFPi)1}6z>un!G0MS#HWC8Np27r^DZ=_)moe|Z};Nz!jAFtS&Aml(&JpHil72>2! z)*ky6!AqK>?v)$P*H^KRz(#Z;QFnLYRXzRB=K&E!0l*hecL7^0d;_p(kT=qxAhURQ$W`IaZ-Q(Hj}r<Rf&T0{yg2J++c|gcrm?dmpv6vdgVVd-n0k+B^3kR}b7N9IbRGK{=g$o7E4J>X})^xRH@x{5(ufloxj01*8an_*1va2xPRu$N+k5b=&E zlMjARANW5bi3-D|Iax=~X2$goadK*-@gKZafE~ew5Ahz%Mn^Dk;1FSM*Z!NW0A(_} z1X{tWy-GzoMS!C9%?uiKnM&A=fwiGl&%mFwZGq<@f&lNn?MEfWavT15apg zN$3y=mmf4ZDb|47aO+X2CB>lNdt5G|*(l{BV%9y2AV6v&Ix?iQ2b!_p(EQ ztHy&pA7Eas3hb|39nhD7?we0>r@s18EXVQQwG;Ym-dGiO!5ZngSW}emhWHxp%HkJI zKo66TU1J`JNxBE(-p`y}K1EKHC<+@PUH8a3ynBzAng2XmA3SYsY=eu$VuGPGkQc^6 zH=aRq>xgFf+f+l8N9QAeStO4mVnn{o11wC>%5icM)WA2#s#6vUt@A&)ndB_h%z660 zjRju1*8O3!?&9mhSpO%h6#{VoyQ;5aJM?+aHt291eq22Fe1XN(g9M{-8%SMKy@9MbUKYmWOSW|*y>#5Dh9XSwqKKVUFX8`>mq-ug4$c1 zZEj<7kHjA3HCmaTg$sQPW)@#&ZiF;K?XBl$AbJ}BopI49uC;et8KVQs19>x(ZLS&k zuEJG7dTSaHZ@-?vE_g6|?~=M|c$p!=6aU`7kBxC;oWb>%Ug+I|pd=NKWsPj485u!J5aS4o z{|aAZbN>dM4X3EYyjusz&KPyqoAgy(Dl}JB3BF{!EA*SKJmVWPl`|qdfYS~-nF&wG zc^VD9?n@-6JgDmt;JFC*cgRO#04Wb&+4bv zXD&w-u0dT8X!om+M`0hLleyttA$DvJ?|a0vL)?@=yya8NJ0n5T5)yDX&$@P<@Yt`M z(vPX0Dv5~K$e(lmh;8kmo3QRhAnC6k;mAhP5<>A=u0|Y9jm-kE?oY+3yvb?iHg94 z{O%=g)MRa|yL({*4mfr@6$QQ@?fOsl*jMa2HRF1aYxfrW0sN z!6kGDu2C-`2CSX_KQ3`Z9OrZjFuU-%u`fV4=ZDJmZh;R}E0jhIfjs7fzqe8`9?c}; z=^hpsJb5XJEVmEHCeHuzOT=;X5WYCIXxOG3+=E99RJ=2T}6 z-!XK&x!RmX$R^RhJf%0y>gP1yHU|tnn$i>ld-;!9imHhQK8GE%l>hnkNz0YKRHHBl z_{E#Vmsj`Jcr~rNPUlbwqzQ$)W-iGxtbYCoo!tCFUCPitQu6!{(-u|S{i^%E#M7X} zQF#8(!ug{7+WWDx%%#KibbFsxrCBLo6s{7%;-kNJaPLtROIW>+b(3p>uvNckJ zobz})bYp%H&VxN0&}T}5JwVbZCf4V=LzsHhZmC(`&Ca=@{puEUE)8%<3TyS}hG=bh zWqWphpy7=1A<^V=o4(KAm2J01A37a`>qdNs$D1pR@iG6j@Ke4#oy}@l!I=q^{@56L zJE!O!Dt5bnq)R9ri356pB6g9%L!^z*HrN)oU5Q4N9UyPJMH;8|efnM4bZWIf7CQId z4=kj$H$>LCaI{W6FpnwutY2*#&laz7wBMN3dlO8T70dO_`(TX4wh5GkmED$_T_9;T< zrOz13A}(n5A(X;hHb_L52-zLa?<1r1Wc%j)%@|Fu&&LKT0XgUs^`+U|d@fZp@v0(T zXpvzzR_rU-245ZiMQNDT+gs1TwxYhsOSTp;K5E#S{``px9bF`)na<_FxC+g$%ZAQ9 zPYR8N#A+C|YW`tb)ko_E;Yl<0vm2-N?F4w5LA+XbL>e(M6~YV^q(z9SGKLXC6JZht zm^|4w$cgRzdjlr`lIUkvH#*3iA2Hi0bk5o5nEJ-zAw-;!ep$ARy-#Xg2<1ioF>%cnZ%9EEkRr3@`_Ado2$)Clrud5B|vy&qJ! z5n9}MP-H<{v>WCu2j4s%d;8>#?Z{^n+J&1>&^fhuXzT{ZEBf> z=rXs4<}=cWhiV)@gjA>YigQxZPR@;(CC3bHwJjEZOdN=uoHi$CIN%z0-`!^Th z&+Z5oi|ag>@CE?!A{kMMOqR$2MtXw-x$csX+zXcHhhM2WoW#VyL`{*-m~llbA?I7g z!)p_!S0~Q%KJC3D?xJ|1tB#hzOL+|l1iAJo}{T z?gO8vxkDJrtOgd?OPj1Ep-%#^PmDz%LC5&H`7(r9aIHMz_g;nj%d{~|sbsaXOW;*# z8qz{ZR`wuIh6KNK)Yy{z=yXb-7)2|;cKi61`fB?og|}*5Z@vqw(od#}S*@>TZtF0H z8s^-gZl2e)%2Z(}ZE7b2y~+q9kHPQ33ol*i-ia=z?Nz-JR7%ie{A~P$>*Q~lxzM7o zR?%7s3T*3yHU$P$KM7hgWUP`M0}w6=l5B?n)XQax>U|aYt?ij6cT4$Ob1NBIPuk$>D;^d=-l)Y zIO}d{BTz!W5vDoxOo@^ZSevbLD9{ErDr;r1qX@zZHyHaSP9ViSC`j?RPaU7^-;6IB z$zCr|)tJ*jXP#=fF3uyHSIbv0K7ogF2p)4d=^GvHej^H6c-8G;tb;rupZS$;_q7NL zQUQPGWw45ma4CM)2BB&*+L_$-s=yTFk$5u6%c3-QPW1LQwQfkwv6sZU1mE-caWcef z{pf@ViH-}kvMZ?6ZScja9uK8U;f^ITU0G%{=ngJ{q)C=T`3K5IX4JlK-^$8W)8I5n@QnJ z6jKgOLM<}B^)0N#hVRXVvWBW@rZI*w4pkvUS;BU}yuLI``V?>@c{SO!&&*Hss4&55 zuD=2s&~PntEsq#^@xa!5%Fa1ulnu_!wsQdQC8X??m`g@Gp=ikk=& zhX&yc$ll;%a0z@JKylBy+kc&R5m3N^oEcu2u{AGg*A$#3bV_0WCvsVSj z$0aEl)~Ud3s#omi)@DiJEW>wIb_xP%6j;( z&+lI&vH_m# zfNtXJj1OXUxmpz7)kCBB)E3<>v}h6iggy4m{0yq^r(A#QTg~S;QXv@(d7+<47Se1X zg%Ox`&e_*<%u0)F9;@2nM4GzQT7!U&K<0N0zVpK7*~Veh7oYlECd+U7HG7Vw!CW6q zHMZKh146a??Mrg!0pA9Li&zpX_xKak@l$-7zDrMc>{b4?G-ydDp((q}Dz)YKFn4Wy zEhm}0?8e!UD%*N*p&T2m>ZK3UbZe zI_Njyo+DSh`=zf63p8z?7$~4`!~B<7|tx7@Pto+^)H}#*0NW0uD0T#BeBCW zz)sTjOhdm{jCYx98A6*MNOqDT=1{n_lG!tp7#PZDIOk5KyWJF@BaZ{7U;=?Mdqi5# z@r6&pP&LRDCR*kDRamRo1-{-e_W&0H{nD+}6_iO{^IFxEA0Xv=UUZL$WD}Fu`Zm z@TZRM1d|Cpz8hm#mhaonQ)eqK6@hi}EgnIXpF<#F8-X&FI#?E7XY`$yXe=7Nc`QN0 z{6>fxnOGr)t9*buJDS?S<<|4Sa67sf-}@|>O`O*+s zosZB|cV|WPN~o^-syknTaqLw~Cc%7LmH1PPcO6qM?8?o|d9b18%bCTpzQ@n<{4^G! z8=Z;uauG!JFzLD3I1nz@mbgA20+d0?HpXBjzbwcq4N%^ert@50Cmy4dp z#)|2TL&NiSa0aTlfmoYhAob{(dU=LhO$HW7U|X{qJ2$PeoV_Ks2qY{^?hPra5}%cV zqh{)!Eu8$0D7m~f^g(=@`O6qmC@0v0O9={AV2?!F+2HGapeRopRJ+#7 z=^nFG%l0L`HWD|O)*Y2!$!Dau*#CE(i|tw88rr0#SozSmLV8c0lY{p+y8U+Eh3d>V z`#?IybV=%jx^rbF0Kj>9MvXYjw{&1+rc}wK4iD_&lmT565ap7?K>)T2r|N}n#dh<4 zkR4qmu#vkMjKDG)+mW%BdmKa#J}!Vr?($=C6KKJaUluE59cKSVPyJ;kjNuKRVpJ@l&rQjft4hSFsuf+~y*$10 z=uWwvEzgz~C?7l*vl1=1af&jq`o$aARgIqhv%DB*ySzb3l)#5QeL_j>)XTIZjFnR) zx&ur>M?BXB&{fzQmNpcOiSgF~jHBk&{E!ec%x~ZsUh*vd90`Vh5jx%Nu3V_L(Vd?L zEl;|2%EMjLRIjq&*GEuzpQ&Ek5u6bpde1rSm-wOkowH^<;+^2H6(S?D$Ew7dM-W$% zU+{2`Rcn3g-LTbtiR93ALt-QBfRvPIo-9RSG7%4v?*=ARLQe(=&c5AcqF<0INY@P!hr1Cpo9jJUkjzJ&$FLn zjVphV65Hy6o89yz zFK29>jx1XaZ##Zg`lpBDy7dGIH{-|V0?gm22HSFTagy@E=qet%z62|Ngw@98cC?i- zQnb@k_Gj7=hkBGzz0F`nK~^kIQBWZd0Dn8hM=tAi=nAOnI!nYr6yri*k>Y@i$UDr7 zCJsMNK5lBt=QciD{3bu9JHc&JJrSnsW>ncnx^3MObYAcmvm*xKN~5(i8(Z%=4q^9z z_f(K*ZpWF~`#|ITf}Gc~ca;|M{oAUtv-=w;tzt-~D*wBtxmMb-Nxw0;dnWv9Mt(A( zX^YyJ*I8e%xXQt_^eK}d*1iSIwG1}+b<53$va7{7R*C8$M&bLjcUBVZyN*`=QF*~c zyRFNwyevT(uoLfoxJv-<()hSb*uYmsjO5nx;3LMqkRc3N3=j3sYvwYiJ`29Xs#Te* zHjPi8&xNaOI3Mf;phspT-e6R5gwXAe*UkwB+*CItqx(BKNS`(Sogm*wiX}r9%Z6VxyOx;zt&Z9*1Am(12mw^hYD0Ts`}Ut#(5U2P;g*aMdsUb=N>o znEaQ$1}kPpoWJXB_uI6ui@&NUycgayN@`A8Vt&Q~H%MDCmegTYh@K9bM;6A#PT2kK zGDDiS#_AGlnJL+?T<$4{?_HKLLiNja-@X2G?ZUy%MttwHZoAIxo9Czle_I28Upz#r zjnwSAtkQac6pKLF;~zkvC&X;r$Rbk*dLzi=_`X8mEREIQ(dp76f$hX2pyf8%>SC22 zubc@h>Ya%*26%*+JboXAYP}oq*1|dv6}7I|5~gU1LtO4Jz8Hc3V01%G>RpWhhaw(vBv^^hpf&$wzcl}}`>d~Fx z9$BCsh%U8DDTo!C?kBWu^$j7gygErzVXA3;NV{E¶NM%+d8IdLX1kW2aNF*EOI?nX8}qZtO%$0vk~tMecD3 zKmmsA&y`7a4!-@Ed8R7;O9M~D9_E_W+|=^D&+c{gD2VDYB)Po3gTgH4M0Ehv!6aHV4;cf5<&=)7*_zYDD*n>FQ3$Vb_W;zSpj7f8fXEc0( z#`~dO8BZtoKgLL%?j(8Gs0?6F8w1Iu)qi+HUF3s*hy(+;13IF(?gQc?u9vvb3e10g zhpWyZ&i{u9IIDU0)wcDkX3Ht?uQ^0rJ{+OL)o|{EsQfy2A))s@{xGZglFe-$}q{~ zrY)Xs|ABA(k!CoR3SB*Lt{Eh)va%3m3;;m(%}w<~X38m2eex2MNtpGfZpy_$7TYRA z*sE-+OZdR&DQciuTdH~L54+gUJbwBpS;&$EW#50W|Fw6(D8>BVUcg*i$^BntPxo4F z6m`eDO>~SlAEkUX7L*KT?xB>Kh?tYvTzA~Ti3>$P+ZKm)-NlI#AWr`}C+M_C510lH z?0l2$@xnfl3^D`GB!+k)vsDKqnj(XoL+E<892YS+YL)x;2_Yo*PqLJZI&t#tz<-h@ zv5n`G(kD6Yhqh1`V*^XbGtVxZPlc@5PyVR~6w6*bIMTAp&e0znpas#iS_pYGXAJTt zTD~_6`$4hcK3x&8naU2+C0kS{B2t8~xhf+2*rs%AXP98C?yzGVjhxVt_bRT>% zv0HY-#_LD|q7!F>fbb;Hjr>gZIF&MZZd0HqoR}j8rge*BLc&MVeCeyy6SF%|n|MYq z%QOinm~3wM8q)7ZhO5u?km85nifBBC7_S#40@^m&qpttgl$U;?7Hx+8hE<<6lRiYO zyRRSlf^GP&V^tD*Z0XvH7UPdSa;$27H3^{_W%5t7dNgyMG;U|(v*ZFcf10OaU9K_KjUr0Q+3vp*xg{#(s+UNMwMxMVTxn0{I^8Y6?es!W$t+ z(ybvC*5??6Fd*6%{k0#d0_5!a!p;*Bz1&h0gM#SHZx?#ZRDO{6l1MQw7PlNuzOE4v zm8W#eE>CwZ3E<>&4XX3$S}b%nE1g8-g@JF+qj}F$G#1LG#*N}p_)sR~7fe&86MI2b z^o676p418Gqc|WZ6H<^+CD&Z#?ar8Z1_sXc7mJ%UIZl>W#s&k@6C@M$x>izLj25pc z5d2Jfic`_%6^nW8Ri*e?i?TZ=$DTrjqX)O8kFU%Qb@L#=vt@BGtI$g7Ki`f6eL9iG z);)Bj^Hn56OZwbkm{kaMvL7U@{q8L5pRmzK2|=kY(%E-aU61R4Nn*Gp4**#X=t?{* zCV}aB1hGtRdd$e-!;=Ld)ziyu{rcVatNH0VV8A&m zUAawBPUW;5RK~qZQT^PJf8wGeU>F@yPfX9k9d94lNN9|Ur!o&Twu`>8u-Y-gS;kB*@^w7)}|!obm2yFn)evgKjB%e^!23I5?KN&PgCw z^4nl%_K9XH`UmJUEkE2V5@Ugd*zbiQdWpi;d_A|_)g%*MTxOYj#R&UhEz5&TKP>g3TIE{%>U*_%rJ@R7gl2t2W3?M3(n}PM^hX&whEcdu7^5R21Kx}DG0iUh^ z&@a%*e6GiWYABV;gyC^)xB8T8F~i;A?B6>2=qwT|Jc-bVnp9_Lvx?@ibDpdx=QVOlwMcZf2OcudqD=l z?=G;fxkD6QlenNKX;Jlmbe%Gn;Hq99Nh# zXzIR!B_~Wd55V1tNg%%9=w{1B4;h}0#c=-W3g4l}`UXS_a%CqHq?9<7+Q3~!3XmiX zRnW=fdB^xzrXl=NZ1Pqw@Sp|sYmJszrJ-Po1B>PvidThJc3+E(-Kqf)!$1&72>Gf4 zJ|K6?W&c|_TEW#CAS0tN-l@Xjp(a?~&7Kr^_4C2J>Os%73n2iADKC@nyJ};C_iPu( zhlc-b6fo(60z^&_?IrVFu5J60fVSe_bcc_eHt-c0?t{QaulZphHl%}>E;``RPc^SK zX)Nay#U}zRV|O>-=$@+V?5x~Gxli4PbJq!vlimgz2xx*0%;6{bUVUodT5Ki;#g3lu zAQWF2$kAq|M?R<+`!B~gf0{e$_!6Y8G#iPJwEt*V)a;=v$TIcb{jusX9ln3-lWY^u{d!wq zjZmQHwI^GnoNM}3YyLEXn<&B4vD@0N8UHUd1#}H$0lH1YpPi1y0Zo-!e7l+v#8v|$ zSNWTUJ)8$}yiV?e9q}okqw5DjK@MweKkX9y`+;G@MKf@%)wq#+HyETLjqkT$)g1aj zE+wPabO^s_MqjyESBvFk zC?gcpt{Ye*wBazWyoTwJUS*HbK7c+6IRmB6BB1jWz{k!U_ikD31F1yrES*fpJS}K~ z&;NrdE4{2M?IV(Dhv_8c^VPZUfQ0MU0^T5J@cpii#Nl_~CFOn2M*98o>j1!NLyx9= zhU8s2fZYAO|JQ}ZwG@s_k!o`;%Dz!8q?dVEgNmpD)Fb$cv-q9wa_CUlVTbv35XCh9 z^#wQwR}|DJO)YE9z2885lQYPRN*BP#(M!m}I+n1s`Hw(2R5d21_o$`I4oJ`(g&bBd zOQ1jsyWkck@lZf_&em<5?1`aKIqkEnS zcMb{0zM}igF4cRwt+nrm)dX!g(nE@lu_!5 z)NX6Rfz5De7)*qYv3Dk!6qTI&D!tIQAu9z;;lf){&yy);x~QFFc)IH8(>gh?!0Rsm z`^*6lF+k4;F?d{`MGsg+MKeh4CQBe6o6-1B+$cMA8_27F3G^VhaY>Y;r`1Tj`>NA$ zBkp!J-rmi(v!G95Ul#|$3tCeok&<&SKa{7j!!B~=ftu-i|1TpwV8T^+mY&C|Nf&YxWXC~0KXVYKc zwQdcY{J2i0{5l~a9MqdGQ$zX=aPi7cwtyT`dnG|dBZ7-l`i*DsLjFw;OO??gC*HI( zUy3>N&K&hx^{B#7RFL?ts8sNFiv-s#XSIIfZh3LN^?MR{?^Gk-sXvF0gmNDP2h}#) z8BWf6DTFAN9l@=7<-UBM&U}IrduQSK3cGaA4`mnMzfn1Nee|LW5YeJ8X~ow{*y1zs zS>1Pqd=iV=2v96X07iQpXx#dMOwLQhcmau~;pX(3=&m-aM?*!tGM65J?Zd^M^UbLx z?gAC7aP^Su|+7?9t=TYCW0&tpmn#r%d= zzb)M%CsWX-T{R16yiSukdWxDZXOuD93hOWjd5}(W6>xeEVl7>WHb5cu3-t%&aOlJc zyK$ZRFeiMtnBQ(_~=7B~HkS|^7bnum(JfL%LJ17dc8Iw}1-A`XKNR>-@qQ zynt5N;|rA{nUucyqonDUGY7G*L>W(##qYe$R|u`Mv51<$nHLd@U}dcO1)L6A49K}7 zZ>0E7f{n!JG|OgOJ~YQP-X-V>uw4#I(D$^A%-fv2Obw}<=ZwCms(4?c@*0I!m|HIE zH#K^y7j$PzIPSJ${;h9l)i6sTrx6polOUJ?&7Ol$+w(p#pWQfO^^ZRBhDkgw*9##{K#?;tKA^T*pN){U^r9SlBk1+`kXW{V%Ac$o zzV8nm6Cm>(JBURN$7Hf7ifzPt?oedkTnTRIzQ#x?3&DFa-st(bw8B*?{YH{-N9Sh6 zK#LocRE$Q4VBeq!Wb5k)`EDM?&UNfbe433}sattzl@8<0-x*me;FL5w6!!%06M;*D z{50OCK`Co94Z0eY8D@wi^THy?7W}5pO5K&2SRy zQ6K*>-uceocjdF8=0fV(G7?u$zM60GtbHUmvP5>+Q8e82h|$dOw4R^ye>;RTHlA(c8|M91ZOU;=vvKrLU*q zelfUdGD1>3Uxav!NHlGncvkXn3^EvMKzIa}qQ|19fabO#;xd=FHQz}`Z=p8+fR2bV z+bKF-SWrXM41Q!pMLgpqQM9(++LQpnbJl5wct(3Z#G#;6blC3rhkZ4!8je# zwQpoG#+Ndzyc9irQwi`YF~rGpgsbsyH8Y?@euWNB6sP-n&%ZPoU>^gA%e6B&3U|Y7 zXpejaoN0v`okT4#Pd^Mcvc@iDY!hHr83OSbKlyBwUzjr9XC(5=UXM7SVhM`3;lx|S z$q-U1DlY=kCE93ddBS{cSdBnZ7DCiBn)uFH9JI#!6-B(%q4pw`zwvGqfw;_HPk~TP z{oJn83JR=R{@u;F+Msb!29x^jFHDU`)?U5=h1Ph7F3M5|ke3dr3CwD5KvG@V6`v>v z1_FN7beUIHIv?aG3FAv-&1Z^v(z1nJC(RaM(ex5`J@|ED?`$eVA z%_ULpJbCpJ&VuYbze`@-u>e(iXe;XgU-ycZxA|cB@O^Qc7aGxxkH$GY9mSFll z4ZIAD0)r2aNLF@Y3gnzT)%lTEQas^N8z}Z-Mg>XCDWr)*9ADH$x`>(k^OquzW%M+3 zgZDvWjI;S^^^UJQpIKrF;9RzM{qG6YHzZx7635tijo8)cEm7I1xqW6~bKa137L}~L z!<_xvS$?nflGLco3)RTux3-3E)CeC~1>0>GEB5I|cZbnOHtC#s9iRZcCWq?#HQ(Wy z+36*R@5_y21?$wuv0u0_8oFCX+2wj?t8kJarvTOf%pX8~HgdJ~RZ#5`ljMCln#I6s z4PK;8<(xRR&Q2et1>ZCvjfFNXM2uy3x_!^wZwS;ur&;+5ghwpizQE$0f*^?4u*cP9 zq@i|rlfw}m`bd(@gk>XQlJUv!?kVYqrUYX)J`DL>BbgTo9cq-&S0JPyoOvUj&~|T` z*#^ZKewP24b924rGlQbiyIV^SKmW}6IsNnR-_Y=%>n-h1*iBVf)2>n_XqHBt3#JRr z%BQ;im{rJ4F84*?&~fjvZjaLwT5?`8Yxm^#^~SgcXvk@v_!!VotwhKCw{-8_ZCuORdC*W8walc#Qb`rZg$r%h9}4>g&4 zkfDO;)=?hV1{#q7p_gBu71b1`q&|PH!`D2=kf?r=3a@j4^ZGukC@&A`4G8A!{94o4 zxa@C?vP`9=wBuY8R0Ui!aOJd68tIZY<}N}u;Bw&2Qag*hJGXIVs53UbF*L8KNeSj3 z<0K1VSW>Zi6ayNbV&#LuE1%!)k6~iFAuTPf&R$ehls){z>MkNrFSUt9M&4rDz~s(v zq$3%Mg}Qv-4ITom{s)9L^hn+1_0h3cvM((mkfl5lwqo$=c$_?j)ceqa$Nddi+(5FY zSmit8aS>-s>gdqWtmf0}s{sqm6y{C%gL^OUVMweM5CM{7-RH=_?;R>|Bl5=$B>*4W z+~Qa7f#)6+MaC4zjszjlP(GYx7T^nA(0^qot!F&08r(;P_5Fx z65TN*K2~#H_@PfnYPIw3A4A_k=n;qn@lFl4wmW1C*Uq{e1X(D;o=|+IL|qYPgo{q! zJJ>2!`vsMp;l1{O!IAX!ce9@@;RA{znNzkR3Ql2$BTEH?Y-s|sZumfw+&)mBWo&>O z;}O3dx0W6|`N*v<6i-8d!|M|ZHL*@te+X)K;kRgqZ4F6llTGt)*j7)5eowv~=S31= zVN1c9H9pORkUDyd{3IYN7o8=f1F|&HN)Y9TX*Subi1>wxZ#Dq<|ERiYl+Ua|*A=yhI79l1d zf4kqMRJ3Sg+2pv6O0X{$_DJ5C9PK|2TdHBvx7$3*#LPU^N?o5}j3*;@h~GE{&bqi1 zy<*t5`5fw6jVnbdkv6(tzdrsPVPZ1JC7nVw ziPaJ;sH#%n`+@G$cTF&s*OH+gK)#&|RF1&0A^_amR@Ry7H+UF1V@B3XUk;VaM>?xViX z#Ncy=IKrDKw|rlc-RYEhDz$S#;q-LQ7Ak=_J-D;eWRfG=$LCI;Bce4u&>xXV*4X+{ zPFN2Lg-K;E&)jB(VL%Ah_OC)PS-ftM%!<2nn`|+(7G(T`_W^Xv8R)socm@Zd4FQ>13o=d)t>G#aI|b0Tg&mT6Uo73$sa9On7y zS=d{>DyI{GQ6fVku&1K^8eohX?GeG_VG$s+%5tDxsbKx5p@G4sUrX)4QABRRU90;@Dc|jGK9VU`TKv1|QsPJ>ek^w`&mFe)P<;RcR#h zQqcowOyiSUfe#)E=i!PNHnFv}ZNGH4EhjcM_Iz_oi;0Yk3}ZCrk@J%z^Lb~FYkMR9 z?SIEUeY$zVC!Gu}tR}g&>muZ@&b}U9oAnM452tL`5;qXJA9|LTmwiT+Ok>I{cRPuL zMWgi#YvbeNygKxlK(wuV!awV|drS z%|aDqEQs&~_@A1(I+d%ANxji-z0{vPiAItM{;)qB}N;>pjQzENZ=VsRXB)`NL zo12?8;5b6hB-UD*R0&ypuz=g(4mdtZ$e;+o(mQwl?CtHH!07cj*wkjo+@16E_V)I0 zaan3l|9KRTgYx6RKbO)xHndRox9Xl(?M43-6%)HGbHBG-DHzN)g7xLv&Icmmcz*wh? zSFbjgEBoz0V5C##Q*>R literal 0 HcmV?d00001 diff --git a/control/predicted_path_checker/images/Z_axis_filtering.png b/control/predicted_path_checker/images/Z_axis_filtering.png new file mode 100644 index 0000000000000000000000000000000000000000..0c064aecae42e81f470ea19efb7422c412173beb GIT binary patch literal 22632 zcmeHu2|ShU);B^MVVg@bY-4QmEb|mH53xzYHqY}sWXP~HR%Q}XnQbJQGG!}7C{#ou z86q-d`mS9(PtS9nbIv!M_x;}Uy0oK+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 autoware::motion::control::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 autoware::motion::control::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 000000000000..02ade624d630 --- /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 autoware::motion::control::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 autoware::motion::control::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 000000000000..e3c3b5cccfb8 --- /dev/null +++ b/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp @@ -0,0 +1,178 @@ +// 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 +#include + +namespace autoware::motion::control::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; + double filtering_distance_threshold; + bool use_object_prediction; +}; + +enum class State { + DRIVE = 0, + EMERGENCY = 1, + STOP = 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_stop_state_; + + // Client + component_interface_utils::Client::SharedPtr cli_set_stop_; + + // 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::IsStopped::Message::ConstSharedPtr is_stopped_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_stop_{false}; + bool is_stopped_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 onIsStopped(const control_interface::IsStopped::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); + + void filterObstacles( + const Pose & ego_pose, const TrajectoryPoints & traj, const double dist_threshold, + const bool use_prediction, PredictedObjects & filtered_objects); + + // Parameters + CollisionCheckerParam collision_checker_param_; + NodeParam node_param_; + + // Diagnostic Updater + diagnostic_updater::Updater updater_; +}; +} // namespace autoware::motion::control::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 000000000000..75e90e624a17 --- /dev/null +++ b/control/predicted_path_checker/include/predicted_path_checker/utils.hpp @@ -0,0 +1,104 @@ +// 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 +#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 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); + +double getNearestPointAndDistanceForPredictedObject( + 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); + +Polygon2d convertObjToPolygon(const PredictedObject & obj); + +double calcObstacleMaxLength(const autoware_auto_perception_msgs::msg::Shape & shape); + +void getCurrentObjectPose( + PredictedObject & predicted_object, const rclcpp::Time & obj_base_time, + const rclcpp::Time & current_time); + +bool isFrontObstacle(const Pose & ego_pose, const geometry_msgs::msg::Point & obstacle_pos); +} // 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 000000000000..a35c11b80c1f --- /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 000000000000..35f971907696 --- /dev/null +++ b/control/predicted_path_checker/package.xml @@ -0,0 +1,47 @@ + + + + predicted_path_checker + 1.0.0 + The predicted_path_checker package + + Berkay Karaman + Apache 2.0 + Berkay Karaman + + 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 + eigen + + + 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 000000000000..5e8d96805b83 --- /dev/null +++ b/control/predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp @@ -0,0 +1,231 @@ +// 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 autoware::motion::control::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 = p_front.position.z; + const auto z_max = + p_front.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; + } + double min_norm_collision_norm = 0.0; + bool is_init = false; + size_t nearest_collision_object_index = 0; + geometry_msgs::msg::Point nearest_collision_point; + + for (size_t i = 0; i < dynamic_objects->objects.size(); ++i) { + const auto & obj = dynamic_objects->objects.at(i); + if (param_.enable_z_axis_obstacle_filtering) { + if (!utils::intersectsInZAxis(obj, z_min, z_max)) { + continue; + } + } + const auto object_polygon = utils::convertObjToPolygon(obj); + if (object_polygon.outer().empty()) { + // unsupported type + continue; + } + + const auto found_collision_points = + bg::intersects(one_step_move_vehicle_polygon2d, object_polygon); + + if (found_collision_points) { + 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); + } + } + geometry_msgs::msg::Point nearest_collision_point_tmp; + + double norm = utils::getNearestPointAndDistanceForPredictedObject( + collision_point_array, base_pose, &nearest_collision_point_tmp); + if (norm < min_norm_collision_norm || !is_init) { + min_norm_collision_norm = norm; + nearest_collision_point = nearest_collision_point_tmp; + is_init = true; + nearest_collision_object_index = i; + } + } + } + if (is_init) { + const auto & obj = dynamic_objects->objects.at(nearest_collision_object_index); + const auto obstacle_polygon = utils::convertObjToPolygon(obj); + if (param_.enable_z_axis_obstacle_filtering) { + debug_ptr_->pushPolyhedron(obstacle_polygon, z_min, z_max, PolygonType::Collision); + } else { + debug_ptr_->pushPolygon( + obstacle_polygon, obj.kinematics.initial_pose_with_covariance.pose.position.z, + PolygonType::Collision); + } + return boost::make_optional(std::make_pair(nearest_collision_point, obj)); + } + return boost::none; +} +} // namespace autoware::motion::control::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 000000000000..3fb7b69d531c --- /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 +#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 autoware::motion::control::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 autoware::motion::control::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 000000000000..0cf2548d6974 --- /dev/null +++ b/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp @@ -0,0 +1,585 @@ +// 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 + +namespace autoware::motion::control::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_stop_, group_cli_); + adaptor.init_sub(sub_stop_state_, this, &PredictedPathCheckerNode::onIsStopped); + 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); + node_param_.filtering_distance_threshold = declare_parameter("filtering_distance_threshold", 1.5); + node_param_.use_object_prediction = declare_parameter("use_object_prediction", true); + + // 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::onIsStopped( + const control_interface::IsStopped::Message::ConstSharedPtr msg) +{ + is_stopped_ptr_ = msg; + + is_stopped_by_node_ = + is_stopped_ptr_->data && + std::find( + is_stopped_ptr_->requested_sources.begin(), is_stopped_ptr_->requested_sources.end(), + "predicted_path_checker") != is_stopped_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_stopped_ptr_) { + RCLCPP_INFO_THROTTLE( + this->get_logger(), *this->get_clock(), 5000 /* ms */, "waiting for is_stopped msg..."); + return false; + } + + if (!cli_set_stop_->service_is_ready()) { + RCLCPP_INFO_THROTTLE( + this->get_logger(), *this->get_clock(), 5000 /* ms */, "waiting for stop 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)); + + // Filter the objects + + PredictedObjects filtered_objects; + filterObstacles( + current_pose_.get()->pose, predicted_trajectory_array, node_param_.filtering_distance_threshold, + node_param_.use_object_prediction, filtered_objects); + + PredictedObjects::ConstSharedPtr filtered_obj_ptr = + std::make_shared(filtered_objects); + + // Check collision + + const auto collision_checker_output = + collision_checker_->checkTrajectoryForCollision(predicted_trajectory_array, filtered_obj_ptr); + + if (!collision_checker_output) { + // There is no need to stop + if (is_stopped_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_stopped_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 stop + if (!is_stopped_by_node_) { + sendRequest(true); + } + current_state_ = State::STOP; + 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_stopped_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::STOP) { + 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_stop_ && cli_set_stop_->service_is_ready()) { + const auto req = std::make_shared(); + req->stop = make_stop_vehicle; + req->request_source = "predicted_path_checker"; + is_calling_set_stop_ = true; + cli_set_stop_->async_send_request(req, [this](auto) { is_calling_set_stop_ = 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(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); +} + +void PredictedPathCheckerNode::filterObstacles( + const Pose & ego_pose, const TrajectoryPoints & traj, const double dist_threshold, + const bool use_prediction, PredictedObjects & filtered_objects) +{ + filtered_objects.header.frame_id = object_ptr_.get()->header.frame_id; + filtered_objects.header.stamp = this->now(); + + for (auto & object : object_ptr_.get()->objects) { + // Check is it in front of ego vehicle + if (!utils::isFrontObstacle( + ego_pose, object.kinematics.initial_pose_with_covariance.pose.position)) { + continue; + } + + // Check is it near to trajectory + const double max_length = utils::calcObstacleMaxLength(object.shape); + const size_t seg_idx = motion_utils::findNearestSegmentIndex( + traj, object.kinematics.initial_pose_with_covariance.pose.position); + const auto p_front = tier4_autoware_utils::getPoint(traj.at(seg_idx)); + const auto p_back = tier4_autoware_utils::getPoint(traj.at(seg_idx + 1)); + const auto & p_target = object.kinematics.initial_pose_with_covariance.pose.position; + const Eigen::Vector3d segment_vec{p_back.x - p_front.x, p_back.y - p_front.y, 0.0}; + const Eigen::Vector3d target_vec{p_target.x - p_front.x, p_target.y - p_front.y, 0.0}; + + if (seg_idx == traj.size() - 2) { + // Calculate longitudinal offset + const auto longitudinal_dist = std::abs(segment_vec.dot(target_vec) / segment_vec.norm()); + if ( + longitudinal_dist - max_length - vehicle_info_.max_longitudinal_offset_m - dist_threshold > + 0.0) { + continue; + } + } + const auto lateral_dist = std::abs(segment_vec.cross(target_vec)(2) / segment_vec.norm()); + if (lateral_dist - max_length - vehicle_info_.max_lateral_offset_m - dist_threshold > 0.0) { + continue; + } + PredictedObject filtered_object = object; + if (use_prediction) { + utils::getCurrentObjectPose(filtered_object, object_ptr_.get()->header.stamp, this->now()); + } + filtered_objects.objects.push_back(filtered_object); + } +} + +} // namespace autoware::motion::control::predicted_path_checker + +#include +RCLCPP_COMPONENTS_REGISTER_NODE( + autoware::motion::control::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 000000000000..9cb095e908d4 --- /dev/null +++ b/control/predicted_path_checker/src/predicted_path_checker_node/utils.cpp @@ -0,0 +1,429 @@ +// 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" + +#include +#include +#include + +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; +} + +double getNearestPointAndDistanceForPredictedObject( + 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; + } + } + return min_norm; +} + +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); +} + +Polygon2d convertObjToPolygon(const PredictedObject & obj) +{ + Polygon2d object_polygon{}; + if (obj.shape.type == autoware_auto_perception_msgs::msg::Shape::CYLINDER) { + object_polygon = utils::convertCylindricalObjectToGeometryPolygon( + obj.kinematics.initial_pose_with_covariance.pose, obj.shape); + } 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; + object_polygon = utils::convertBoundingBoxObjectToGeometryPolygon( + obj.kinematics.initial_pose_with_covariance.pose, length_m, length_m, width_m); + } else if (obj.shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON) { + object_polygon = utils::convertPolygonObjectToGeometryPolygon( + obj.kinematics.initial_pose_with_covariance.pose, obj.shape); + } else { + throw std::runtime_error("Unsupported shape type"); + } + return object_polygon; +} + +bool isFrontObstacle(const Pose & ego_pose, const geometry_msgs::msg::Point & obstacle_pos) +{ + const auto yaw = tier4_autoware_utils::getRPY(ego_pose).z; + const Eigen::Vector2d base_pose_vec(std::cos(yaw), std::sin(yaw)); + const Eigen::Vector2d obstacle_vec( + obstacle_pos.x - ego_pose.position.x, obstacle_pos.y - ego_pose.position.y); + + return base_pose_vec.dot(obstacle_vec) >= 0; +} + +double calcObstacleMaxLength(const autoware_auto_perception_msgs::msg::Shape & shape) +{ + if (shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { + return std::hypot(shape.dimensions.x / 2.0, shape.dimensions.y / 2.0); + } else if (shape.type == autoware_auto_perception_msgs::msg::Shape::CYLINDER) { + return shape.dimensions.x / 2.0; + } else if (shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON) { + double max_length_to_point = 0.0; + for (const auto rel_point : shape.footprint.points) { + const double length_to_point = std::hypot(rel_point.x, rel_point.y); + if (max_length_to_point < length_to_point) { + max_length_to_point = length_to_point; + } + } + return max_length_to_point; + } + + throw std::logic_error("The shape type is not supported in obstacle_cruise_planner."); +} + +void getCurrentObjectPose( + PredictedObject & predicted_object, const rclcpp::Time & obj_base_time, + const rclcpp::Time & current_time) +{ + const double yaw = tier4_autoware_utils::getRPY( + predicted_object.kinematics.initial_pose_with_covariance.pose.orientation) + .z; + const double vx = predicted_object.kinematics.initial_twist_with_covariance.twist.linear.x; + const double ax = predicted_object.kinematics.initial_acceleration_with_covariance.accel.linear.x; + + const double dt = (current_time - obj_base_time).seconds(); + const double ds = vx * dt + 0.5 * ax * dt * dt; + const double delta_yaw = + predicted_object.kinematics.initial_twist_with_covariance.twist.angular.z * dt; + geometry_msgs::msg::Transform transform; + transform.translation = tier4_autoware_utils::createTranslation(ds, 0.0, 0.0); + transform.rotation = tier4_autoware_utils::createQuaternionFromRPY(0.0, 0.0, yaw); + + tf2::Transform tf_pose; + tf2::Transform tf_offset; + tf2::fromMsg(transform, tf_offset); + tf2::fromMsg(predicted_object.kinematics.initial_pose_with_covariance.pose, tf_pose); + tf2::toMsg(tf_pose * tf_offset, predicted_object.kinematics.initial_pose_with_covariance.pose); + predicted_object.kinematics.initial_twist_with_covariance.twist.linear.x += ax * dt; + predicted_object.kinematics.initial_pose_with_covariance.pose.orientation = + tier4_autoware_utils::createQuaternionFromRPY( + 0.0, 0.0, tier4_autoware_utils::normalizeRadian(yaw + delta_yaw)); +} + +} // namespace utils diff --git a/launch/tier4_control_launch/launch/control.launch.py b/launch/tier4_control_launch/launch/control.launch.py index 375819f8e757..af5b82349f18 100644 --- a/launch/tier4_control_launch/launch/control.launch.py +++ b/launch/tier4_control_launch/launch/control.launch.py @@ -63,6 +63,8 @@ def launch_setup(context, *args, **kwargs): obstacle_collision_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"] with open(LaunchConfiguration("aeb_param_path").perform(context), "r") as f: aeb_param = yaml.safe_load(f)["/**"]["ros__parameters"] + with open(LaunchConfiguration("predicted_path_checker_param_path").perform(context), "r") as f: + predicted_path_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"] controller_component = ComposableNode( package="trajectory_follower_node", @@ -176,6 +178,34 @@ def launch_setup(context, *args, **kwargs): target_container="/control/control_container", ) + # autonomous emergency braking + predicted_path_checker = ComposableNode( + package="predicted_path_checker", + plugin="autoware::motion::control::predicted_path_checker::PredictedPathCheckerNode", + name="predicted_path_checker", + remappings=[ + ("~/input/objects", "/perception/object_recognition/objects"), + ("~/input/reference_trajectory", "/planning/scenario_planning/trajectory"), + ("~/input/current_accel", "/localization/acceleration"), + ("~/input/odometry", "/localization/kinematic_state"), + ( + "~/input/predicted_trajectory", + "/control/trajectory_follower/lateral/predicted_trajectory", + ), + ], + parameters=[ + vehicle_info_param, + predicted_path_checker_param, + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + + predicted_path_checker_loader = LoadComposableNodes( + condition=IfCondition(LaunchConfiguration("enable_predicted_path_checker")), + composable_node_descriptions=[predicted_path_checker], + target_container="/control/control_container", + ) + # vehicle cmd gate vehicle_cmd_gate_component = ComposableNode( package="vehicle_cmd_gate", @@ -338,6 +368,7 @@ def launch_setup(context, *args, **kwargs): external_cmd_converter_loader, obstacle_collision_checker_loader, autonomous_emergency_braking_loader, + predicted_path_checker_loader, ] ) @@ -372,6 +403,7 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg("obstacle_collision_checker_param_path") add_launch_arg("external_cmd_selector_param_path") add_launch_arg("aeb_param_path") + add_launch_arg("predicted_path_checker_param_path") add_launch_arg("enable_autonomous_emergency_braking") add_launch_arg("check_external_emergency_heartbeat")