From b85f13ac3969e59cceef4e202d5da652fbc75df6 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Thu, 1 Feb 2024 17:03:51 +0900 Subject: [PATCH 01/13] chore(twist2accel): rework parameters (#6266) * Added twist2accel.param.yaml Signed-off-by: Shintaro SAKODA * Added twist2accel.schema.json Signed-off-by: Shintaro SAKODA * Fixed README.md and description Signed-off-by: Shintaro SAKODA * style(pre-commit): autofix * Removed default parameters Signed-off-by: Shintaro SAKODA --------- Signed-off-by: Shintaro SAKODA Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../pose_twist_fusion_filter.launch.xml | 2 +- localization/twist2accel/CMakeLists.txt | 1 + localization/twist2accel/README.md | 5 +-- .../twist2accel/config/twist2accel.param.yaml | 4 +++ .../twist2accel/launch/twist2accel.launch.xml | 7 ++-- .../schema/twist2accel.schema.json | 36 +++++++++++++++++++ localization/twist2accel/src/twist2accel.cpp | 4 +-- 7 files changed, 48 insertions(+), 11 deletions(-) create mode 100644 localization/twist2accel/config/twist2accel.param.yaml create mode 100644 localization/twist2accel/schema/twist2accel.schema.json diff --git a/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml index 23a1201a84958..bdea584bd58ae 100644 --- a/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml +++ b/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml @@ -27,10 +27,10 @@ - + diff --git a/localization/twist2accel/CMakeLists.txt b/localization/twist2accel/CMakeLists.txt index 93b9546be0a36..59f23eacb2fb3 100644 --- a/localization/twist2accel/CMakeLists.txt +++ b/localization/twist2accel/CMakeLists.txt @@ -13,4 +13,5 @@ ament_target_dependencies(twist2accel) ament_auto_package( INSTALL_TO_SHARE launch + config ) diff --git a/localization/twist2accel/README.md b/localization/twist2accel/README.md index ec73c34052f99..5a540dca895d4 100644 --- a/localization/twist2accel/README.md +++ b/localization/twist2accel/README.md @@ -21,10 +21,7 @@ This package is responsible for estimating acceleration using the output of `ekf ## Parameters -| Name | Type | Description | -| -------------------- | ------ | ------------------------------------------------------------------------- | -| `use_odom` | bool | use odometry if true, else use twist input (default: true) | -| `accel_lowpass_gain` | double | lowpass gain for lowpass filter in estimating acceleration (default: 0.9) | +{{ json_to_markdown("localization/twist2accel/schema/twist2accel.schema.json") }} ## Future work diff --git a/localization/twist2accel/config/twist2accel.param.yaml b/localization/twist2accel/config/twist2accel.param.yaml new file mode 100644 index 0000000000000..e58e029248253 --- /dev/null +++ b/localization/twist2accel/config/twist2accel.param.yaml @@ -0,0 +1,4 @@ +/**: + ros__parameters: + use_odom: true + accel_lowpass_gain: 0.9 diff --git a/localization/twist2accel/launch/twist2accel.launch.xml b/localization/twist2accel/launch/twist2accel.launch.xml index 47b8a95d13a08..c4c9a3ed50bfc 100644 --- a/localization/twist2accel/launch/twist2accel.launch.xml +++ b/localization/twist2accel/launch/twist2accel.launch.xml @@ -1,6 +1,6 @@ - - + + @@ -8,7 +8,6 @@ - - + diff --git a/localization/twist2accel/schema/twist2accel.schema.json b/localization/twist2accel/schema/twist2accel.schema.json new file mode 100644 index 0000000000000..6b3c2bd094166 --- /dev/null +++ b/localization/twist2accel/schema/twist2accel.schema.json @@ -0,0 +1,36 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for twist2accel Nodes", + "type": "object", + "definitions": { + "twist2accel": { + "type": "object", + "properties": { + "use_odom": { + "type": "boolean", + "default": true, + "description": "use odometry if true, else use twist input." + }, + "accel_lowpass_gain": { + "type": "number", + "default": 0.9, + "minimum": 0.0, + "description": "lowpass gain for lowpass filter in estimating acceleration." + } + }, + "required": ["use_odom", "accel_lowpass_gain"] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/twist2accel" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/localization/twist2accel/src/twist2accel.cpp b/localization/twist2accel/src/twist2accel.cpp index a8a7d46f57056..68019f27e95fe 100644 --- a/localization/twist2accel/src/twist2accel.cpp +++ b/localization/twist2accel/src/twist2accel.cpp @@ -35,8 +35,8 @@ Twist2Accel::Twist2Accel(const std::string & node_name, const rclcpp::NodeOption pub_accel_ = create_publisher("output/accel", 1); prev_twist_ptr_ = nullptr; - accel_lowpass_gain_ = declare_parameter("accel_lowpass_gain", 0.5); - use_odom_ = declare_parameter("use_odom", true); + accel_lowpass_gain_ = declare_parameter("accel_lowpass_gain"); + use_odom_ = declare_parameter("use_odom"); lpf_alx_ptr_ = std::make_shared(accel_lowpass_gain_); lpf_aly_ptr_ = std::make_shared(accel_lowpass_gain_); From 7686fa069fd044d59bfb9f02f094a411ed666c39 Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Thu, 1 Feb 2024 17:09:52 +0900 Subject: [PATCH 02/13] chore(tier4_map_launch): add maintainer (#6284) Signed-off-by: Yamato Ando --- launch/tier4_map_launch/package.xml | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/launch/tier4_map_launch/package.xml b/launch/tier4_map_launch/package.xml index f75a181bfb659..8fb41076204a8 100644 --- a/launch/tier4_map_launch/package.xml +++ b/launch/tier4_map_launch/package.xml @@ -8,6 +8,11 @@ Ryu Yamamoto Koji Minoda Kento Yabuuchi + Yamato Ando + NGUYEN Viet Anh + Taiki Yamada + Shintaro Sakoda + Masahiro Sakamoto Apache License 2.0 ament_cmake_auto From ee25365a1ad389e3decadbbab6faadf7aa054e3b Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 1 Feb 2024 17:23:20 +0900 Subject: [PATCH 03/13] feat(intersection_occlusion)!: react RTC disapproval and stop even if occlusion detection is OFF (#6279) Signed-off-by: Mamoru Sobue --- .../src/scene_intersection.cpp | 16 +++++++--------- 1 file changed, 7 insertions(+), 9 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 3f6136673a44a..3cf243b7893fc 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -735,9 +735,7 @@ void reactRTCApprovalByDecisionResult( path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); } } - if ( - !rtc_occlusion_approved && decision_result.occlusion_stopline_idx && - planner_param.occlusion.enable) { + if (!rtc_occlusion_approved && decision_result.occlusion_stopline_idx) { const auto occlusion_stopline_idx = decision_result.occlusion_stopline_idx.value(); planning_utils::setVelocityFromIndex(occlusion_stopline_idx, 0.0, path); debug_data->occlusion_stop_wall_pose = @@ -814,7 +812,7 @@ void reactRTCApprovalByDecisionResult( path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); } } - if (!rtc_occlusion_approved && planner_param.occlusion.enable) { + if (!rtc_occlusion_approved) { const auto stopline_idx = decision_result.occlusion_stopline_idx; planning_utils::setVelocityFromIndex(stopline_idx, 0.0, path); debug_data->occlusion_stop_wall_pose = @@ -857,7 +855,7 @@ void reactRTCApprovalByDecisionResult( path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); } } - if (!rtc_occlusion_approved && planner_param.occlusion.enable) { + if (!rtc_occlusion_approved) { if (planner_param.occlusion.creep_during_peeking.enable) { const size_t occlusion_peeking_stopline = decision_result.occlusion_stopline_idx; const size_t closest_idx = decision_result.closest_idx; @@ -895,7 +893,7 @@ void reactRTCApprovalByDecisionResult( "PeekingTowardOcclusion, approval = (default: %d, occlusion: %d)", rtc_default_approved, rtc_occlusion_approved); // NOTE: creep_velocity should be inserted first at closest_idx if !rtc_default_approved - if (!rtc_occlusion_approved && planner_param.occlusion.enable) { + if (!rtc_occlusion_approved) { const size_t occlusion_peeking_stopline = decision_result.temporal_stop_before_attention_required ? decision_result.first_attention_stopline_idx @@ -965,7 +963,7 @@ void reactRTCApprovalByDecisionResult( path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); } } - if (!rtc_occlusion_approved && planner_param.occlusion.enable) { + if (!rtc_occlusion_approved) { const auto stopline_idx = decision_result.temporal_stop_before_attention_required ? decision_result.first_attention_stopline_idx : decision_result.occlusion_stopline_idx; @@ -1066,7 +1064,7 @@ void reactRTCApprovalByDecisionResult( path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); } } - if (!rtc_occlusion_approved && planner_param.occlusion.enable) { + if (!rtc_occlusion_approved) { const auto stopline_idx = decision_result.occlusion_stopline_idx; planning_utils::setVelocityFromIndex(stopline_idx, 0.0, path); debug_data->occlusion_stop_wall_pose = @@ -1110,7 +1108,7 @@ void reactRTCApprovalByDecisionResult( path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); } } - if (!rtc_occlusion_approved && planner_param.occlusion.enable) { + if (!rtc_occlusion_approved) { const auto stopline_idx = decision_result.occlusion_stopline_idx; planning_utils::setVelocityFromIndex(stopline_idx, 0.0, path); debug_data->occlusion_stop_wall_pose = From 60009363f0f7dcf2ebbc0049f0661e9e802c2d91 Mon Sep 17 00:00:00 2001 From: Berkay Karaman Date: Thu, 1 Feb 2024 11:28:14 +0300 Subject: [PATCH 04/13] feat(pointcloud_preprocessor): add pipeline latency time debug information for pointcloud pipeline (#6056) --- sensing/pointcloud_preprocessor/README.md | 40 +++++++++++++++++- .../pointcloud_preprocess_pipeline.drawio.png | Bin 0 -> 60904 bytes .../concatenate_and_time_sync_nodelet.cpp | 14 ++++++ .../crop_box_filter_nodelet.cpp | 10 ++++- .../distortion_corrector.cpp | 10 +++++ .../ring_outlier_filter_nodelet.cpp | 8 ++++ 6 files changed, 80 insertions(+), 2 deletions(-) create mode 100644 sensing/pointcloud_preprocessor/docs/image/pointcloud_preprocess_pipeline.drawio.png diff --git a/sensing/pointcloud_preprocessor/README.md b/sensing/pointcloud_preprocessor/README.md index 91ef34f4cae72..5c6402efdf23d 100644 --- a/sensing/pointcloud_preprocessor/README.md +++ b/sensing/pointcloud_preprocessor/README.md @@ -56,7 +56,45 @@ Detail description of each filter's algorithm is in the following links. ## Assumptions / Known limits -`pointcloud_preprocessor::Filter` is implemented based on pcl_perception [1] because of [this issue](https://github.com/ros-perception/perception_pcl/issues/9). +`pointcloud_preprocessor::Filter` is implemented based on pcl_perception [1] because +of [this issue](https://github.com/ros-perception/perception_pcl/issues/9). + +## Measuring the performance + +In Autoware, point cloud data from each LiDAR sensor undergoes preprocessing in the sensing pipeline before being input +into the perception pipeline. The preprocessing stages are illustrated in the diagram below: + +![pointcloud_preprocess_pipeline.drawio.png](docs%2Fimage%2Fpointcloud_preprocess_pipeline.drawio.png) + +Each stage in the pipeline incurs a processing delay. Mostly, we've used `ros2 topic delay /topic_name` to measure +the time between the message header and the current time. This approach works well for small-sized messages. However, +when dealing with large point cloud messages, this method introduces an additional delay. This is primarily because +accessing these large point cloud messages externally impacts the pipeline's performance. + +Our sensing/perception nodes are designed to run within composable node containers, leveraging intra-process +communication. External subscriptions to these messages (like using ros2 topic delay or rviz2) impose extra delays and +can even slow down the pipeline by subscribing externally. Therefore, these measurements will not be accurate. + +To mitigate this issue, we've adopted a method where each node in the pipeline reports its pipeline latency time. +This approach ensures the integrity of intra-process communication and provides a more accurate measure of delays in the +pipeline. + +### Benchmarking The Pipeline + +The nodes within the pipeline report the pipeline latency time, indicating the duration from the sensor driver's pointcloud +output to the node's output. This data is crucial for assessing the pipeline's health and efficiency. + +When running Autoware, you can monitor the pipeline latency times for each node in the pipeline by subscribing to the +following ROS 2 topics: + +- `/sensing/lidar/LidarX/crop_box_filter_self/debug/pipeline_latency_ms` +- `/sensing/lidar/LidarX/crop_box_filter_mirror/debug/pipeline_latency_ms` +- `/sensing/lidar/LidarX/distortion_corrector/debug/pipeline_latency_ms` +- `/sensing/lidar/LidarX/ring_outlier_filter/debug/pipeline_latency_ms` +- `/sensing/lidar/concatenate_data_synchronizer/debug/sensing/lidar/LidarX/pointcloud/pipeline_latency_ms` + +These topics provide the pipeline latency times, giving insights into the delays at various stages of the pipeline +from the sensor output of LidarX to each subsequent node. ## (Optional) Error detection and handling diff --git a/sensing/pointcloud_preprocessor/docs/image/pointcloud_preprocess_pipeline.drawio.png b/sensing/pointcloud_preprocessor/docs/image/pointcloud_preprocess_pipeline.drawio.png new file mode 100644 index 0000000000000000000000000000000000000000..e690d0179afa643889a3a994630022f3e0c60f52 GIT binary patch literal 60904 zcmeEv1wfTswm;wzID{Z=Q63PKZb^xQARS6~H`3jWA_!6v(xC`QN=Qhkw19L-D2Q~! z0si|4+;L{^n|uFn-kUdfX1sVW-#+`>vDVrverxS>L*->}<6>RJLP0^nm6Q-uL_tA= zqM)3i!bArx`roKYQBZhG9N?-BRxZY7mPRNv?4rlN(Xg?Y+SohLu#3^KvFX{`G8vlb znb_%B*)v%iIe;ecxs{EfnX#FX;c*`}7B&t>7FI@9R%Mo(H0;8h9N=Fp984@cJnF~& z^-PScPX?5+aWk{D)T3b&=VW35L(!?SveK}NfZwFetQ}pze_eREbhy9}$TmACFcd2r zD-#Pnc)D$5U||E^WMg4v0Y9vuN!-lN$k+zFCjO(>@pMKGdM3w9Q+9G49{ zHFFi0Vq|2uJ?`UVWM^+?V|}s%HYQdkR_^0Z99(UUj+;$vY)mYTkge=+8Wv$N9rA}= z^n@Vb!CKGiq^~^KBO_Q5l00T7gfW(PxO-Q|N<`f09*>@atfac3nA=~Db~>h&%WXS7 zTT>YuLnBKtgrUpv5?DFd!KBDR4PB30xH-WSvcbgebe@xGkqt^_ZYK+3J$cW>(ag}u z{$#Y{HyvzjEFH{j|Gd$_#@gD*;Dk#jBkI}N**O1sH)9*ilii*4u>~9dv(b?aN(Op> za6cr7g^A~QR%E-1nW2N}aXSy^$pVq>5=Lewrl)fQ<{rOcrFYu-q`}@)&(OyCWL#vQ zpZRi3$y0jT+1P;beq!6tAD?!zauGGMM3VcIk|*;3ar*y%_ZNED{UYpt&v16i3Q}C^ z!mg5TmPT@_=2AR%l5&h}H;*afq-W`PLf_*Cdk5E3g4@|RS{wd2n?P1YoK4LfjFfEk z43OQOfrx=NQwJ+c@N|6ckfH<*gM-nj#2pW4tM{jE{Mgywrsba~dfUjx%E-aa6%6bA zCvI~hJ0Pbr{fW~&r;OG+kuj5B-bHr(JzM~NPMG+&*N0SYf5GctCGZIo|BSv|mOzq3 zjBS7lV`H&DJz!k-9gz|y!cN0>`YZU&1lc5QW~gTe`ij|^0m_137{OmK^6^0WpyjyV zX$#oI@#v?`$ld>UISQ1yrKpXijopu9!fvQ%#A9p#7G>{XXJcXX(|3q|*Ig$T>r6M=*li;xb`17kG z#fAI>K0zuJGhhRREzL}jHrBxgsdxSnf_5q~CxZ5iRQ)7r9H)JL)B>2&l3KpR*^r~{(tHtZG&XN51nsrU^5J-$$i;yM@bD|9@TAG!#?kJFDFVHI zRRIHaiqw7%dUhtj+x#)wulD0W_WRp9AE{8l>VW3|$tKwuS?W0ewftub{pV3HC)@uU z>g9LXA5l9STYaQc4BTT&haVP5$;i_9|3-`aa~dF4u0N~=V&ytMBL7xu;m2|R9ctl+ z%KX<;3n$zEA6E-9W+1}*#l86V^F!HA{nDS@gI`>RpWTB~m*JnsQk=pS|6ny>4MMx0 z+ymqz(m(j&5+EP`>v54B( z*#YF|PkP`#5h@!S$7ww9$I}dKC)VO0s~L`+lK+ty;KafC%@dA{6#f;1fRp|IeMel; z%-RGTZaGH>OS2y#z-cV-9~6oOX_bKJ`~ph;@y_@Orv8UL;wNyxZyxa<@$kQ%5oi1D zBmSE(BHMofBT8D^Iy!)p|1+HU-#zn4buO)^4^mQph7swVz5y ze1wRd5dc2*^nc_gkUpX<665@V_H&BRaEgJJW4rMy8HkgF)XB@B+eyU!b7taKp`jmV zpkZTdY=4?|{q2Ov z>99Z2BEO(se|tgfqCa~7$d3G0&)=6s`L!g~|4b4E7<{l=7C<8wCMKqTYe0+r^gNtM z>1l-e$FpUue|TedqM3fvnt@V>e@Tb+wASG7^H~1_TmPc5e=!GtdCLF5xb>;N`s4bn zzt?GH{TGc(kJT3_7x}sRu_Yap==z?;rPA|2VC`Be%r*FB*&< ztE<2FSpNr7{-t>BG?x3zQ~pQBluyFaKkg|%*}!l5=>Mvq^0D^%dr$d)Q03qD(f`1( zGV32bb#wwf{pKk@j#&RT+;s}3{gLX&*iN9!Kdheq-&eoChv|P}{a?VdY^QZ&C#W0u z>GLUGdn|b;ZvoE|KtsQEm*8}=|69=ZnDBqEefY8Q(;8+`8*2kS2P12}fA`t~w$oyQ z6RF|)l{4!cyeh}@QL@APNovR-roLNPIjG%uY$YL1%h`EQh56( zk{%z1gp6ApJ;H|ELOJ>IJHHbG_j5wU#`Hls`5Agz*5_GfvG6;CU_~l{rnvb;K{tJ16lNk_UC}Ms(uP@&FT`CcgJeh9g26*R=&Xf9=EA}#Sy-6`{1*(E8{#iOTlL&Y~c64_|uI|}P|W7$07 z9wwH}i@#UO!Yz3-efwN@SF?S0i+~B8!jz%n2yNToLkpE$ooz0MnMrN8Rm26O50Cwa zofhTj6|?NCv6>1;a+62`Bv@MTsD;sl`ek$@6~;tchE2p^rIxBPm;su*Si#{Es>Lo` zn-|y=`VPJnq&h9!=sf||%LsRk zka*J`efe5iD?0s52@bs(lq$~!-h3USo|!=2RgN0|X@jY(;4df_|Z2 z!0?5qxR@Uw=cNu9zx!59y4WtlKc6SM$hu#D*mXm_s7}CjE&kiR!zgmW8fNWm3U9bDGIJ}+ULQh!P_Dx`9p(c2h6(+Sd!h`O^B6w(Th);Fl2}{-|4NnKvWo5^`e6ydiBt)lzMHoi*780dPE7Wgga4ZYgq+s8NUc+nR*GZY^ zwUbDhlhQ&n(9IVvYRdBBt+jDT?<;SJIL#gQved8a zQQ1&Uv2jJ!TM&fJ-VvSn+Aif8bja=5pfYw{D9ldjOTl@o6yHR`s0)mrVC4 zuI6dfDJYlS6IDooiy#UK!nR@y#)F z+hpQH4T83^y^mhQ$MzqUb5}{}UgdQ}U^1$gv@sEIz0`Vn&?vN^e0k6s$EvDf%UQOq zq<&7or3N3WHNutM6HTgEtT+pgQo0raA%u$VIixqQXZJ*0Re|qQ2zXFxzpE|d#A}v1 zl0I8Pla*MYfeC=`&d3rU$vB!+x8aY!z7N>SH@k7 z<(|jd2~22!Xc|+ErbJC|q-A+W_x&{MTuuqJp&RylBGs!XTXzD|Sl ze_a}q32KL}Q1I-_=X)5L7nD^fbgU&l3lVwS(v>Zw!jMU_`8;4a>B&<(g?x?+0TPqR zm}QqrG0VQMppKb-FB06UlS|pZHp{5mZnk^v5rx9`mP~U5E{T2t?^fF2{i$zjyi+Qq zFY&NMVPw-7QIx)^-@sN*8RK$k##zz;lXWs)a+3J)0^#kfPR}6hDETxoS*wUc_TocI zwXnYQ&q-e<$^_`*B_DjwSO$&_X%5);`5fhn%_vvo~nlK z(?>eRF6YY36h)=E5$a`3M%@t6Whz3yD{uNLoz6z-*|x*T&O^IW1v0AcO7+xM9}QRB zvZHOd5@l<8WSy_f%Ut%YJ3L$VvM}E{9byf#<+0tkH6s~@Pl_wdZX=u`8sHm2CYTc6 z*w*gIErmdwYdPJ&@mO6G$5t;nsN`ynY8)F8qzm5JBulP54|KUug;*nx)!o&iL#_F~ z%{U?|5l9YamA&01n}=@Cuf(&hJ=!HuKRBXwdBgl{ys*KtNUnZ3851=8io~TO88b1=^w6@Tng1v_y-5*8U zjoVtNHEvGVZ__)w2zT3DgJ0xMr|`@?(COvU5~KBX#<#^vwOSiS8KsqT=N zk^KE#H4abb7%|i%Uh(L>l30n$n-pi|7n=NWFLi2R=afDaFlx@UX+_od679Z%k<@M6 zxR;l)s7YqF{b6$a3g>5*q{Q-X(q`<2X?3OF8)xo|=0-bBWiq-`E5Vcx@+imp&neqE zk&8T@p>M8&jxTm+h@#BiP!`d^UVYk29NLm)!lhInGEbh+(C0o<0qY7lI{tNtrpdpyS-2F3QI zMU4IR^-2~;1dDol@{@YBxdj^ni>YVycV8+@Xp3h{=xWpuHVxg)GCp%(5oV&hW_%cH z-fts&#r>SG1Pc`o6#?v)W0`GFva}yx2g`K=5k8}iSV`6D=>Q(XW~bF>^=Ddu9X369 z*(-|&FP@s=vVPR#CVN>xg0Iwb4A|G6bEdCv5tH-F4&EEO06hYZb z0}OcOoV}~Qlxq)PlOhGtEFmEBTE%Mk13ayp9=ea5KB}R~6db+mI9SYfUM^+4b@bGF zQmKDO<-<)z2^Sr9IlR(EULVDr4!Ysl?=fYES82Uhn$kicOz+&Y)=gwY>h2ZZzEXvk z9zHy@LbH}hxE>(7??|Fi`Du~g>9*G)`V@2XRu;F7Ha6>u1fMj_CT&Utwz8GA2CpMsPxW{;G~J44 z78Z*&<0|Q8HX1tVK$7V~5E$_{}D?t88cQW2GIUv562PRX5a&ofZY)-}GaknM*L6<)aa zQF9Sz=QH7#Fr6unRqd&J!#7vU&nP7&zxwk1zE)_!R>wjZar=UE@~iNGiEmt4OvB|& zBeQe_jl8cPl9KlK-qT*!V=E`_u{4-{{JO7d)kdF_iy3noh*D1Hyd#B}pSJ!R9dhc1 z3QwG$h_^%Y!9A~4T8-$1<7}8=hD|gKyS&&cGFb|3U@X>*Xp{7Q4M{zS11 zj3?#Qmr#kh?sW1igVpTu67d`+W##FWl}b_gpWa)gT420e@v_ra-7I+FY)n@Z_0UCz$b~CPxH=Bv`)aARTP!^H2u#oxz@$p0^%)vPiaV-c4r77f>|UnxjwGKkSHTsc2%il_TAM^9bMmg9V>ex zC>5T3&kcedRb}l;RRunU&ikLKz3XXYs-)Ax0+35ELl^Y5o~s;Eer4G#KVMyt(Q_{xp0jfo;`A!_gtMd7d00_5C0OMFvJs zw&&N-y4;ol&PCgpsbOJ;K&cpF>NL9qkByEBNz?AR`K@b{UFBQzAMfN#%;k7qbc)>y zRUILb(4cL2B7wOG)P&`({!p2~s9AHL-{NqMUKze%FX;Dj@KE#asiLE^y)LI zm^?ZX_F=&dG$2_9jR6{v8a3F;a3;mNNna;vs8}60Zl-CEK?uW4R=CN0msRWc1c{1U zJEq9+G9nNVyNeOLh!u}{8;#7c@%)>!cil@QCJVYBS{z6}-AbuQ4cY5jd>V7Dmz(3( zezvIV;-HCl9e!Pl8vqDcy#P^m@~qMPAABQc`y^;X0=2luK){zo+pcLHTp#YwP7^Ag z?2b3U=8OBVVb!<#d|gWtW|Zy&pcEip`A_R9Gpd3glyyCYi@dw`bv~GWI{4#UTCLe; z?A77d*WdrGS5(AA)+cWC2648P+AEERoUMm@Bi@sdQM?9zS$h;xK?}nqCUdHwCozi$ z9JV5v6IX`!wm_py^}BQ;uXh1YOveOsQ(-YV%3m)@Ma=IZnvKxmYnO9(o?H2TXLm?v zy23Q3l)n9pit|by=g3m71_Ggo-JAWg@5z*~U9KJVKQtGm3ZD8v$Y28%FdQIf7 zJlu8TD3)9m40V2+M4se+r5w&<2?3~F$50wux z@-w=jOuQYyVDP|hXYAn)XA98IWI`bjC_JO#zDrw&ga7eO9B1!;V)dm$21Z$Yxin0UsU+ z{ECQ>LR(VCx0l5c7uQ+;`eUR@R<1+xQ1q{Pi1fCV4v@6O1JU?jL<{~%y|IZT7e5Ho z|3bp>ko)WZF)99UPC5klgRpBG=r32z$JDyW6q*%22#PRQyA^a{P(BhR9O7MtUw1fT zHQj|3rJIyCp*AV|_UqeeG*tW*L9`H^<#jceax!Wv{&{z^F*3uNzWb(Jn5Gc?x;b<= zfMw351-|k_LBHSt!C%ovcHh);DZLE3=eoNlgYKigrf+lzZz1-|_8o=z#r&)dD^dM% z_E0cgm{FSwxA&O%)z3xYllRru$l|bRFWuspD1=ga9Sk2-QIJy$bF+>52%~$VKx*Pp zrUu+SNy!<5B{1>6X=`6YzrgHFnYcUvR^qkjHHL>5_3Y9G>v~FmK@_xcDU{WP+Bevb zVntyA7>>+^g#HiW`0zWnEx-!voa&Z>gC)8j;&AIm3R9qiN!PCV!m%e!ZIK0ez7w-9cH%Z(Yc_|VV7R~%1aSWvKYE4(Rlinkfxe*yzMtCG$Bm)w*v-u-Y@ILgY@;a#6$&D^q=*hV4u(x6MAw|GF9=5+RFKRPhlV&|uB@Cnc^tJo4 zD;OCcy5<&rF_w~`Z^gfsIKscZ%wix{*dKjkv0~z5%fn0bW*;;Az>2S{7EvA??k^M3 z+#ynbWe62;-+FK-mO*m5^-)f)LWW{bIy}#Fe@nU2R!=YP=u@`Lr6^+6*LGR&$S(8P z`cR8MFfEK@helBQ9@)-*AXeD!c*;$$m?_bht8f(y3oBizK32@S1D|ern9-iV-rJeX*IZ&X@kVQKS{hyG($Ri6DRZt`iE*jJyyBfm zN?(^H&_EsiOqF7L_6w!g5g{~0XJQ_3KWvw6hVm`*#^<-e;c*m4uXO6XYF(&aNlZHI zeJaqHe`@n4?aq_y3W*$MrYn;TX<-l&+$Cdz$}5Nk?{9s14hx?c^HmB{D4RuQ`tp=S zd{(gcfpjzgJMg8$Y&ea}^x_1a=3<5~3l;?Y&h%!!Nf_dW+x zn1a5g2Ce5<$5>3eDOVY+M#{5z9lv#dA1cYS7sM3&V74H;SjMK zDBs}Vub(^`{M3I3j@VP*4gzwUL4}dPp!O=HPsjvwM};%o*Pt~58imj2WOAg zEe0W?&Rn(AB7xD4HVILN_(LpO0v^JT`FC$zSIT}sS7Fvmdnbvf_??~YK0tJtQq~c> z>rTr>bMgGHuT%%{6D8h7Qu*hGkF=3uN52im69sbF>iPO+h)z>s;igRpq?!MsU1Xko znqU0-*9E{#ml1~?dV&UKr)g6v?zD+<8%><1Uv(KBqGTGJ_JV&Yz46AQr@ zX;#8W>Ik6_@?wc9GU*~;wM^35oeF0*Jvuzl4+|)~Y5yf855tgvXkkWh^m5ZOjR<1z z9!4-AaVizY1(LG}i_rv$5W;KcHkT)K5R31kt}0hKm{qxL=Ho+?^1phoHP?OIRjJIO z_O%iVCy@zxQdoDWJ~+b(;a}FNaaje+grgQxU`oMOtfAV`^;3b&Bsd8Duk+X%v}ty; zAN1WCobJc^z+3mXmzzuOtG&sVc}kn|5RMjpjs(WvQBPWUce3m}kX=VR3hQ%I+jY`t zQv=StH^uz)-}JG+vvo_+i9k$!d1lDUVmBi(_5F+-_6k}$IP(NH?lXapxT02O-V+w< zcCXr%+xDz3*Q`XA;4`4`WHitpfHT(J7RNkB0@bvs^Ewc#b`d};yfT?gSVOA^PHe*` zSf*@pB9KlP8!-^u45!6mXpimIceM{uSA$K@n4DA1Tp@zk&-G*kt7a5i4zW#Xk-Dyb z$+8@Jh15qs_&#y;2}bGVnG**j;fs`jKTfJy{qy~s?)7N8Q%#}z>ORgFZLw06j`+_u zQ2RL(+a|2dwuQ$a0S#v4fap9Bx zdD;q_2EViVdwxgG;UtWHi`J7`1ez4#zBBKm!#8njFdwr+8OU}<&l)#dO@1|uT0!jE z-#0!Je$C5z{7SLa2p15@y-H?ojMe>#CG@7k_0^b^ zUbSsHhokBt5brI)lq)Cs!A44yD4(TY(xa0xC}L>5LDpzHm0J z5Z8}XXrnO2#he4<^owE}QGo=j10nEqfwe_JH3F-8az9Xo147+!V>I*LRRBWI;+3L9 zHo!RFfNy{gojX$n)s5@{=GMoD4Oo;9m5nzpqD4&-TPr?~A~Wn;!%#ni<_5;u>=scA zfo!0TL0H})?d`2w7l64o()>(}>npK>#huqLfx~9Ld!_&tRRE0RW}3zzhPLNp4g7qE zt8Z~BpWy&|&GvF7EXXBL!nFIDuS)$!oVaWfPt>=8!e!=1;a?%BsnmcPUCD&B((;80 zM;1{7Apt-*>9KnzE^Yx`+uNHXcd%HzT0=QW2&OQ9U2N1A3*4{nYe|wm5-gYsQ;TGV zu*Lv-{Gxc^kmye`d7YQOZwUbXkW=_(?+&7lPi5$pQQo}*^^Nr|p=zbkX|_0K zo$Lv({f9tzh)YJ(I+}mop773h6t_RE1;}AH>4fZSY|Qo08-0kGY7Ykn%w1E+dV>k= zGjZKG{C(9Y>S#(|P7oD^5XgXay`|RMU7PJIHn_dt%kQ=ka)?-$<8@twZ7vKvvisV( z_$j(Gp4DGf7qPccX#M1?2=R4geEpd?9k2Tfhn|6&q40(ok&9_g)*cPZn^G1#jGbc#$*x`rUkwmG-Vwp`0$k zeQDC(?wvr6sZc8|T!k827XfdV=EA8Z%!)4{FuR3!%+Al8?*eEEc6!vy%;C;Uqg0*v zD`h}0Bnr55X;nFd62K%Vv#EDzc2-*{!t0#B^-0zsT&h0rZ7xjNFt7lY(H{ypeIMMI zek2s8i~trfS0akq$q%@PIrK`|-6It?@Gx(nI~|S=J)>UPe9R0Ln5AHgwq2cqPnk@X zddJWy&}o!g_Ep|D2)oFcU(~Uv1zd%WWWE9IfdY*Rv2rl*AwG3TA<(PPG>7datvjiL zweM_8&3apA9sJp&>bJ0nuZv|##gX9LR4M@u(A0eV`K#i59aN{8!9g` zQ;8W=SPORFY8yxy;SAR?(mo205WDy*lP;{YNG&Q6kx?^;_7Ko)NjLRk%3h>X~b z+a(qT3Q5(ly^2@cd~_Zo!uNAhz0!d-J|AbKQ0%yHZ}rvZIP^M5C6iawid2gNY^Cju z_`{1+XWu*WyRHS$$|Q>2pK3af=97aqdLD|n%pkAIWB4H^)Mv zt67a4*(+0Iz+FjnLAMs#uLS#^GTH}$LwNZ*`?^CjSclo(#{5)so8v1=-Kcs7RY*}S z=6UMwq?`5-ZZD?8<@Plo-6EQ+*zs_J5!>cKoe%9PfzWU)615txK%L2sL{363Ra@I+ zhRdo&s}pLJMJ&4I4Cs%p@QDKhMvP|L97Zf6|KJk0?2ER^H3pH&#rKbCGJxq15v*_Y z-#-&hNCIKtTAyvZ?R|7mu|lz*vS1k1u>DHs^*Q54rJL<>si}bv*~=Mt3f?r{@G9_< zwaEi8re6-I3%C_yN?n6~VI(ntNvmow^~>sX>y%L^vkwSP6n)XoHa+X88{cU*s@@s6 ziT91)c3rA5L1MBD9kCG2>~((4Pt>btJ=}-6bspVo=x(8Qa+UKklNdw?fgPhWo^&M_ z1Q0Ay^;1Tz5m%;+h*>7uqW-zR~BQ%hRDll4B1Pjir~&T@#WZe{nPpa+lDV3F`n%2Dbfi^fP5 zme+gd#o@b{*E=Dr*yCG`U-#8=SJD+pVn>-elU9atnBJ0_pzZK`Zb`*5sEIw@eJhdF z@VSh^<9_Ot>ZD+!$iqcj&vH^BIsg0KboXAwzoX+Zuy76vJi1ylHPCo_BR?MyxDp$v zMzK)ZMvKV%0Gd{6LrBGWe_mtOA)f=I(z8L69+zv?NIZhqcc+OqGpm{a=bZy#(eG5u zGx@5#Fp@Vc062nS(r9(Lmj{?_4-m^qZq6W;%KVwb?4$g`rviUhKb>^MLd?<9_2_zL zF0Y}RZ$bvi>RfhRHA4e{uci7TQzA+v6=9(GBPr{0NkVA)v1PuO5cEL zCk1oPjH0)OpT((Tz`(r-(@tk#YI#Iq!#s74RNF?e#^pX0hb5^A-XN2S?cVk>^Y^ul zkj1IMgzwm1=p-VD#}zX0p%1pPdJ}Ivolxtkb3Jy~(kE3r zP4X0JjdE{)AG%87!>e5rADdIC>cL}hgOy>7i&%Sg!RgGw3rb+Wf<<8xK6E`|F1T!Z z1(HPqDOP-xbu4TqotM97HQF!p*LBic077}w^ID(90bV(_2{;g?z-N_z&kJ(q9D&o} z5jHaqP)smEpgO4tLjWV2K9+R-YhT^sD@H*FkO|X>p4>q}P*2D4bajj{b+)spn2_d- zt5L2TO;kI}g|M`S54fyc7N`JTeBIz~vsv}%=SHvTGF<+S>F-lzMEuDOjom}dR#+W! zHMlVYzP4Z9m4EWr`8L{mQ?$tdZ{&*wP{|^;E3y|mKddO@Fz?K?LxnC0)n&+kc6YgM z2Et(Kw$Bd=nu;7olz~Yb!QChUX%vFX=YBD1l~)NYK?(tVGA?{^54Zx&4h@qH{`Br! z-(}%`(^I$JFf&BeGn07ju3*=fyF@I1=7c7}C(n9Qu|sPjAL*DzkmgM78a4Hv>tutL zbDkOHI&^HG6)`5*8DKG?GYo~umhdf6ex{FyNj~=Ic53~K$q2;9I;B(h9)fzduWtGr zb|UVp7R(a_(|Y z#SXbP?0v%7L%zbZYNe)8s$G)|(JZ!;w~Ae2k2c!%^W}LfVLBC;=1k6lj3LkE zKb?=;uoZ(f&6`J6)0|l4;ok38Q93LLT#BESNc)jT>AJh}rF7J<57v4_20t|`Bf`BKmi}kxStnzK3XY=N2BEd+rCQn&c zSI31bTZ|>Mo3tLuypDJJ-ftJ(GQ5OPG+AvSl~Y;qp5_EexB;9ZN?Xm62K}Ic6kFp! zoizsX%V*DF)2Do!%)3BBTodv3z6|;{hL;z~^BSi!)WTDgGosl*L+}tDQ$U#%nndzN z8ZGD5?%5V*gTu`Z<{MrYR%SybCQ(zrE?Hq;-Bn@B`FL|0U&za2HGC69vHG(@%+EkB zhu=iI#8~D|98)qr0YWNX2T`ow{A$^{sKb3-g!@fg1^Qasqmrv!s0Jfr_0$15N;^an z2^&=Oxvpd?G%#9`HSPe^}QHCI}xTo z9Kc#pKTqP0NdH=AzvWB%#BSfU0DJ%8z_S%JrKK}Tq52K=7a-a`@5AX_YcWmWgDMEQ z@v(X(!qM%)bK4jpkWl|fyaYes@Jk;%nDSb%l?*$#1RYuaxXzLDuAiSiwg((A(N%d^_=yENu^jGCCQyb(!>w*B0Ab~QYP6n{-BfD~>gUhgD} zHt`nC|7+K7b35}e38Q)lJwa>vYN6?fmzQk+I_29g<5-DFr&VTiue3F0hc~LvY&C}? za*d7GaNX76q3)$&_{iG$_U^|#5}u2Gy>eIBa;4)YEW zYoxJbc_$G7Rie~o1+igsy_Pa4$@#Nsy9uo;Hz!c|@Y`92zAE z|EE+IBYdU(AV;?VGfcZ7shO>*le2i|R!O&a7Tl204DeS%m?@_K!Y>bCbrr1%&~pVB zNmO*1m9Jq)Ah=Mw_LT-GC!luxJ{W~|<_xZS>mn#HHU{8#qU1ol6*8~UH1>miEDb~c zq|Dlbi~tJ^T^g&t*1#qW3b^BCKzz!j*Y#Z#=F-AAsCC@;^Ns~X4FbKThX!GQ`RtV8 zmq!5C#GxLmfDSqTW9dP!hm_%zP`Y*>pFm_7-RM+uJp{rn9C#N8$xun!odF2|j^-)l z$f|}@hSGz6cR{~Z-FF-aidahCKA?Z@ZK*fHB{8Z}@D#j1CV^_2LtlxaszrRL@mAAHMS%(c-lp-VRJ7{=ZR$V9 zi8W>fLL-Mhj`%fNQ30*qlMXpW-m&2Dn);mcYXE`lDrG!1XZe#Q5Eyi}9_x7#fT7&4Vf*_Na z)oRPWv{w8(`9sz2Un#C9a0~S3lHQWha6Z31TIm$%)gI?N?08Ayt~uAv2ZJ#dkEGEvTj5^JZ*hZgW8;hR<8Ud?ZV#`RIBY z9iL5$SR$v<3)=R>XXD8lVO!f2tV0Fk(5Oig+Cs+6+kiu3$n3=STU6wwgtXWVnke~& zfvMr!kJGy==cTkB7l#H&tJ%rNet%6@7n{=cq>yEEuKNK=M>4f`d)`OGXO7QfyQf@x z13DU;+XmqxhKmN$Ahnu-2KUN5-1=DujN0H~zJit4V_BD5M8BI&mt^g|YuNRhTb zd**n<4DrB7Iak$;O5E%E@3C6oZ48N<;!~(r)Wp5AkX5PkGUc zb%RuhS$p?*qNgv8;JkWGxydILUnO&yyPZ*RGr0FZGEUA5S$g4IkFomsCw~7o!Thx8QzT6!8 zj?^sG;n#G|YSYcNvwg3G@2VHiKRXEA6WL!g@U@i8(`+_R$MxvXl^4VG`=-vP!I>}K z#!Zf2*O#oN2Z{jm;-Uu*_qoJO>%?3>>%W^13eCXyI8!WY`gVzZ3!XagQagR>b+2Mh zifEpBL68W{!D=L4Tuz&eL22p(2Dqq#zqZ7NJUHANfvq7rT~pvL3cGc~(i%-v+SB>#zE@S)+{t-ahZEa5QN|d;LtJHa z1b18iQicz;SFy}`F=Rio@ENW$q}WV6^|>blqp!q(oeKSOA+ANN5}}nq{kYPRY41f; zhp(v`9QKm(MQm^PoclkCwr9z>cMTo!VaG9EI?A*PX6lVwC8#8Vz9bO@vPM&u7lb_= zD`7$!ey)?8rNXy%xVOQ6uTC8rMM)Jx%$0^brw?VgdDDSZGP6=gtxT?{r@I2XI1iiA>TUJi=a6tuAb+zXZ%9;br7mSreg*qeJ1C$JvBw%br&BZj zxgr%?=`v$UgZ;so+p=ZKFy$LMA&Ta`_+xvIu*$Sap#J+HyQ+x^TruGnMNk1G^>tu7 zKP@-{rSsfOr%C|2ImX$WUPrnXKmx9(C8=r-X5KXc`77t^M4eH7yyg}cFIV8N`86!4 zFo$oRDIdcXiaiJnl1sAKMk#DhdCAB>!wFru$9$eTZD4X$InPZ%A!vYFnf|Fxn}b+d z-ul4D{H*m{$LR^v*)O6oY>sXUUuMHe^<~5)JDk3bzn$xEi&HL_xVOq*Gg$1DMZjUO zD*hp%+DEDD(%9JK_c+Y(gpOg3_WX|E#jjE<*90T!DT^)KoAe4h z)WiGH7HX->A%}TSIYw5u_Bf(ZhsAZm`LWks674I;g}=u>Pv^+Bs=|hrnd`t zHweOyc&_5#Tr=sb(ZVY}h+3G)T(pkQT9lqN3#+i12phwdOXbfdS#(z_?@GPun8~G=T!d6rQfl;`ntyiK>_DBZ{6!_ZXkbRg~(qd)&F28eLyE zv->JEfK`b!TflOV(FiO>3OZhAJq^qc>K=Udaudf>+3$|8BX8*;QcZ+z$;r3mcj4*1Z+ zQ4HlrpcoTc3&LrNCS;;v@#(-kwv}+^^b*wbp8T-*txaL{6gKf&WythvypZU4!H@A) zxRFjU%V$>9evAu`C~&y3(DFkem2f81{%KMGlhz^YnggJZpt*wYToAg*GI+c_pKq(! zpyG`X8GB(8k`u~%My~EO*j^R$qu4lpPvlwvNFAN0<)?kNM>)Of|5-c)A~bg<|A)ZK zVgj5;pN!U8vswf=Z&`It*1&r$RCqvEOc(6*f{g+%8K!op;)am(7s!(jsiF651VlVM z)&SC+r;_uf6x`NYR2sON>#+O5dPFhr86eZ07d6F<<8NqDS1&mgDhYUjML)QRbpM0& zr^b`L^E7)brzB?8>$o!@I@i*l4(DWll})9T)tfn!FiMO?1xND^_Y<0K*GX>AOP(UT zYRs@s-XzwRkH{3m=W5>Z8NyJ%RJivF_N?w>msKg23{MkB;c-4xmUEs;=dc zgUXtho^!7tVt!I$m<9o3dE#d@tAt7=~x5G*Ncb>=m_KYsuOUXMIXK@yLKOh2I=2-O= zovgyBRNgcy=WEi05%Wb99Z0v)5w*w0n42$k62 zR|Xj?dqmL28GsIb$%iH8XCbclWU>(5JCoR@P^*O@!3BtPsO^!-9?;VcbM@q_l5@!# z+#k;`Mz=*>^%fUx=^#)G$_U<4Y<~RO^e}%hhG+h0*=4ZYj1g(yH1H5IAp3(=UJX22 zkGeGUX=F9%U<&!_B{w0EkR`c_tf~vGu62!c-QQyLM69+pU1?aIO2$QX^d{!J;za&h z{L(>1gdT!{zGw z&8R!YFkM%vo1Hoq zzV;&m8d-60pA>(A;2!f+InN;3Or88s=W$%5ru#zQ=9xY3jNuX`xi2z}yfva!n5LYe z4a!{GQvA@agGip*>urgSew8qqC%|xg$bz7PWmbbeFC7r?P^-X20C=wx4@@pW{JSBY zYH7@YED3>9D_#c8Fh>)p)C{e-`6+iG=K4S`^9S9k22G)cs+&mOu$*tQ89YD(mCyJ6 z=h2ZM!MNZ%iCdGsw8|8Q9v9!7#S7jkL$Twzm*$25IpQ>XNhP(FSo-Un!vR=l7~R0N1;c)7@V*7phVOwj)d-|3lk2hyV`b>oppn z0i{7ML}nczvEncI>{w+7AT?2AKq~~Shu@236fBkpM}06?0&kw_C=54hDE%A$t_VW0)T4jB&{^b4{E zBDFZ>BB!@9XwBK$$6+yeniyU+uHe^W%W-c7mwZsZV0{i`|bs4v5 z8$2fQpg{Z`3JB?uOFX?NUT5qZU&WTP>A<1dcshNi4w@eg&wI@+J0WKf|+BW z;@jQ<%G#+FX%f7VCV|708Wcbw@AB?_FX@^C=>(!{vX|Ws5jSgH*MpWO>TJ4st-*UN z(EzKLu4=JFUbDWo6a?a%o@b$;en=@*&~vW;xr&n%s9Va6xWcEXtNToNp%Ro!)=L9r z&OU#!1o!kl#Vcvst;yzaQYZT;YIr&*5O~jq#|NxAEi%o4IpAX!0y(o{SpobM)N}}8 zM4fmfJQ9V7_Exoorm6%;eo$F*KlhWc zB~(^z{$cG5{k$J;fMO|70vk|<`8Xcg57;UTVzcc9U+^_F;LAsl@m-AJ6ex>B)^J^9 zH^y0wIm3hx?kFIuIJ;DU@8XeOC1J{~R~V2J0DS_*F^$xk{gP&d4k`(?J^-2LIF zB)_{PCQ_2`O2bbtohzX`leCz*Mwvm)ZevaeV*WyIS7{xM9|4r-p@aG`DZFu){hHZE zq_)Girt?*f(-&zZ;zPn>>24!0TY=Ev&NGto&_Mg_ZXa?hv!evQ?15R;hUwdQ^cEj@ z(mo|{-X>41_P_>TP>?jqV!GkL`%|b0zJ4U*=|JJf-I5$Sn+E;ZQZ3-;5nu{xhF(KP zLN%hG?h^yV4PM3+qn|CP^%g%g6OqYBgWIuU@H??tl{!rsz1Jc>f}23}Y9C6cXf7!5 z`PaAKsDU>!-(8S@BSItS(iC4jEgzw|Yc{&_WfTvuq*@0~tIeVf=18KHv){GHNNql_vC}=c45ViwSw1T!aqR44A(4STuzgNR_W#xb)%=REY+&D75&!gYL{o-nJ;G z$VofkCCuR&SmdYI-Xj#>%6TI7rKjVP3jOO?Pt(y?SBV+a@5EQz&7%>&PY9#!P?G^) zH9;`H3wy7m5cq*}ew+5_N}8p6k8DCk(4M1(sEO>Aj3!AX`M1W4d8&D9TgCz&wyAs0 zc$s5-TxJvIF5(yJ+QhH8;iP3I)>b#d!?m(nO_im6qtFI#=<%_3eLseK5tZ}8Xa zq*>)!drHXf=ynv06qw~>Y-;(j6)_Nz|o&f=5U@vqT`E5qT z=8`%DQ1E3rFFj%OSP!4R>7%*uRN`F>4TjPCl<+l+`CagRHUE#jw~nf+d)I~qQP?7a z8w8Wwq?AZ^!zM&px{;8OMj8PLsSQYjG)PK!2}rjf4bt6R-`wbP&htCtci!=SV|?cu z?-=j%pYFZaT9divyyLp=`ce;%F#;Jcb$I(dNR4p@s&?T@*|D;u~{-^;H9^!3L zC>3O(c{wM>Szu2o{eVqj9Je<;8wWBm#?rTNt|z|0d-hOl1!XQW@oUX4dqR|YAt7jb4@Ns(fTNwM=R%C_Xh$i1OPk%V^~ zj_Y+6LS6@;pn={e&OD0!9kDbamlx|Aub$SPZMj?bF^NhH}s1uhD~LP{HIZo#y%_6;xLhqvY#Mn+}{P z4i>b?0QnKyuhV^YbQ+9doW+@vVhlWeUQLS6ChAc=ygk=Bole*z=(pl=u7O=ZKsr-D zQiYW5af$}Z@FkzwyO}7%*Ze(pNCAZ0AL(3=^Y75D^rhAH1l;)KtWoI@)Q;CKb(c4Y zA4|;!M;<>(gEe&e%?vIk)|kQv!q6?JlKws8Ch@`7txeiL3LV-$O9yY^y_bePK0kf- z)<>kr8x#tuPAV$}18m@e5{WRMfF=vHPqi@UQFC+l0cEH9MtEnb^r}%$P}g9kJW*v% zjjy9L>TC3V!&ch%-Htq`({!7alMe0WGmSA%U-=}p11+$YG%-UN?VFX_V|dDH2sLdY z=oHmS2nl)K@$+!8;_B9Kj}{nmu=EXGU*p*iX3f3JZ+}rC@;nml#?$9HZpvmnP3oh? zhjHh1MV2Fl+cKkeOH3{g7(66Hr%h(U2t!}W#hR3VHuJNw`?@r}hGPBbXEx6h?u^Uq z2;g`;U+Lf?$)(|+Ht&n1KL3Wx8yWyye#x20WyXEOnBi4|5VqrwY*qh@^TpCng;N$< z<>lN<*V5pTaJ&)&C{VSzyLNFeVDTkrCvB<=x0tHjULDujOjK04QCOf&vq|EW)HDTZ-Ny7 zZTD;TmR7a3qk%eP2+lmF&P*vyZ+MGI!f?OZb-(ZxpZ3_qmfnb#(NR-{9rjlH+VW_l zkS5Tp+J}-r-(eBTM0^>>HE^I4j3_)VkrKlL9l3P5s+_^9Y!`t_=Dfnx@)-mMnzarj zL&D*MZ|paCK5EuD!wmxT@AZ5Ocw(wdBk&yGA~mi8lYPIsZvv~^)vq9GBuDyN&ZzTG z*IG2|U)Q5iQLAM85c9$mD5L^{j3=M}3oWAncqGQ4`2a(}vrw1BL&)0|aF&nB&=39N zQQ=`3LqoUM@P9Rc#vNoM+@TQ>f54(l3ci`s%UkR7T?}V8iYP+OxIRn6g#8~!(65g)5SABD#@ zlBdm`8O%EzkTb~yhFJ0Y&uzc5H*W*@P1hvZIql&fKQ5%2KSZRlvrVt~2~^rQ-ceaZ=kBdh8hQbK^MB=L*5Is)p&RYy8;-`GPC0_&WhML&? z5WW2`=Q(a30Q-(9(0}qs7R;k|wTACBU$}__9(ws)k&NMZ76UWYJ+^Slb@7 zaldaR)k!&kETLm>$kyqEWdi5>{=r;M11PIl-o$*(dt@126r)x1jy%ZjVsAj^{rPe9 zK^Gcf>z-!9WJVdGOb2*d4kzm6n|!E~#K3PP94aBnp9brx(M_P=cQaI^v9xQI%B6+2 z$*JIjOcZXXc3Qt9wTwqHv$=y-m3UO1G>gw!n|fv2diD`v#iNv?|rB?SfnR3&ihdL!kILbqd)+d~7-RG53$w4f>k4qi22{!HsGtkY%q0rQ=f%y$9% z*d4>Lq7emNCP(zO-5ogN=pr_zRp$^MvxgCeuxV4fmdTnKisi45{% zfz7}c3yBqfRdvo@VxpjNwwN?)=;wBEV6AgPKZZS6sb>*Mnsk=Wk}17dd+_P2c)8s? zl@oMqPYcSka^}?}G+1^!Un?LbClfEmqDYB=n-*)v)*X z3JuEoy+W0Nxg3x4^TKkYPbozyX$t=a_*QEBbgyEgE^~>DTxH7$c;;{_)(`Vu(kO9< z?X&1soS*cXRWB<8aYynG^*Qd;2LM+Qo&qn&?Xvo+4+Cu5vI4H(PagmFGv zr!ZidS2n}0tb%Kzt0j8+qmKeMov>=>ZBMK80GaDzG8sCt5Y$Cy@J>$;~wDBi$ zPl)yI-b~DGi3R&m*^TY$J@1|3fysR?hKuYacM7RX~8Dn#*H?;4@;D0vU5??0Zpo);-T%14~Gz1H5?eY{i=tg0({TEb2(r= z%olX}LuoNVTBd#QK-B_W5)c!*sz^F0?Ap^9it7i>YMlx+TB2t0LN7vX9e{2h*6Nh^ zFW0*aKR0dyYUmixzJqMq3@ps-oH1says5gU zFU7_f3@UH}fZ7TX2fr+Dutde~y`+N)^c!51$PnQBdk8fse!S$<@I8v?PqTRdI=kuB zyD^bW)^AQlixkO!?A;2*W_v((#em%3%`g8Svc>;Bukyd*t>1wT$}P}*!{~v6RrqwA zler56WfIk|qYRSy7|HaUB&?7MG?KlG@ay5bj7#8kSy40-)f2dec0mR(k!(ufF8^K; z{GX_ORpuSQng4sH0kDbxZ~*^MGynfI=KdG<>>q08A8H1)nO=20{73u2KSbtVZS4Q- zmj741C*Qu1P*M2;nIKUipWAmYi?NuBUiYK}0UF%PqW@K2i16CauUDbb$m_&DAPz(g zgcA0Epam$8#hR#doBC`!4*E&7DF9_3Z4)>GlB5=yanQ7bk}QA=+NsldT~0vYlfO2M z-(dDvEx;$B<0Jlr%PzIPp8x&OTP_TD_h=BG81}OmKKe_MOFw#gtpRAOtSum$#(}0! zm;s?3Q0$ii?I0|7^H2tGAUCH+%ta_b=?8@3u^X}-1cgfKuXd0j*?YpCcU~pk1N9o$ zWD$_D{JZ*hVJO}Ya0)^IB_#OMTnY3MQDheQgHjGa%Aj37T%M?6vt1d4nBIjwL;lVm z{Enu7WB5AI)z5w@`J23HLKd{Woo!(T3JSld(bWM9G>H_*NXSRlbO_sq_L?_pLS!Jg zG`RPBiL2VXgvM?IiHnEsi{xcruHqEVP&QvLL&aSQ2f3)1q4ljCWAJ$aQ4zz*K?;0O zfNrr9Ra<%${-2yJ7c&btUh1g;$oj_MDa-wgsIR*6CsHa|5?wwD#rhnlQ^1Dq`iuEQ`%B+Ps!x0w zp90+>;nx=ounOfs1e?40_;6p0I;{OUNO=lN>cjrZ_##FX1YP)A|jEi_P;1qxr1zJh|!WRMzv z1_P5#Ov2Up`;%{BgLJ1PFYI@%&Izh;;|Dp35%%yxEu|M5zqfETdGTV2KEaTz9GcUx&_#eE0(D~lLKViPY*ZxKWnZVk1g2l&GiXMM6iz<{T+c-VT~0N>*7zl0||^+DqTO3e;^5 zl6+9S93(6BPL_X_9`pbRa{{&3i6M_7d*imVWoDIFs{(1ZY9QK0@o`P&X=GCr7iv#_iQCM8004EFA;eDd<^m1A_2`oZ4O_vLomd z_@vcJY*FLoy`7954R4L3r2x|SajM0uB)1blbJc=W zBL9BuO*ud)$${nw^YxgQy_FHg%lX!LvZpVuYsJZCz9h{!H|QqSnH`;1E&Y{KD*EfG zlaSC0HmPBJx=|)bnYnrj=0w`Iw5HIV! zBW0>Ml@=|R!C)aq^;X|DO*qeuh}@TozF7E>;XL(ZZ?}!xN))uA1#q?cR)$lJ?|Jg$ z48KM;)he|qY>ko(ZqxJJMQ3?Sk)+@RAh$!d3h$5Mh4bTt5K<&i zq@Z%@#2=g2Q2i?HjVrRAv-duUM`h%yEKSx@$5&qTCy-1#IZmL+ zM7|ku3$2xi68H6r*+)g53jp%9Ulkt2!(8j*VKD(c;{Ci4B8fhtVf=E&vT z81_B5sj=B#ag|-8+^DEA;O6n;>lgFgrZ?VUM-wlc#T!7G4BB1*)%`mQ6Ult3=?DY2 zB&AV1Nqh(>b}X>4Exu<%8CGz5g!NUk!7ld|x7eCL`^ll6KOP4V94c|O5Vd_+0#xyz z)t*fh(}1}#eIbK9`{Ewb3B4_&c`wChM$nkkma?u!3>vbXciJ)(b|ZBKapqbhrY;6= z6q2X)^C_mYj?#Y!Ax#3Z|D%8`x%G<$a(VjV8xk$ZNS+!1XhG&uFrOnJbb8YpIpkh` z*A&Wnx88D4y4BbYnjHrGrO}(+Kyus5q0>kX+$e8o@R99En$5lXzq0f#9g3vv(n>y8 zPcL2NMo=W))ZsjqZaXLuTUYiZeU1tWrH~M8wn|Hq;XMyWih#?eh-BnG8a5icN7?&P zn7ygK9BMt!P4oYx0emZmay11p4W&uPh9m(}{O*;-ZH^&TTl5mQ zd@A*g9u4V5EMfSdF8eL5^$*oR&nF#^t?aLF8s6_MqI<$o9;sRPP6RHW+Sg5DB-tzx zL9nnfQ6sefplT0;Fv=26 z%nj@b0VyaHHZZEx0fngx&Q42}1?P6hjNQhRq8?tcok`0SX0!9+aoHXE8!HXouc{2a z=W2IM+SaRYFcGqjQARsx8(BY+`A!z{acZj@W9&Nv;EbEae2o3WFx zgAQAFsb3cOo*k@`s4%;g?y@%9c8@_{i%lhGx@+-xIfnhx>lTac%ublqDRM#hq5H6w zJ$nP!KJ#&6{mJVZisrqG0vEsic5Q1>zcEu_gAKoPH44{!feaqYniFQv=0=8Wl=iy- zUF-AX*3T(N*|OXMsLPAwO~?g`=rn^G4&W^v&t6hEqUuPZ&K}Mkleg{;9Bc=`sP=df zTMWWs&!|+W%9t%(z00h57i@l&ZhtFb%F$vw-0dD-sA)Lg9Sc}!I|{vS5V7>Ja-Hs0L8ME7nm@cmdkE^ho3j5-{W7kbK#G>2O+w#>7fAh`>Eob_B68Iry zLvJFI&MW< zEeZW)(B9FWX3=_|QZJOe<5(_xGQ~?@plM%W+8wlQ*T4jB+;u=EZ z6cpFL8a=c#+S%6M9~$P&HV%`VjGA@DF*uQKBAwv5PTQnd_^VQfTG~_X59&7CY39$Yw>KxhIwtR98P*8po=UcU zJkFjQ(j}j;GDJ~ItGXr0yJ+3>jj}U5DEDDosSImdV+2vhgV%90pOz<%;gph$LcC{d zl!tY=ljcV{n`LsPMud*(!`hBVUqAJ+@@m%kubpl?Df^Iu%IHILmk${ZoufBG(9DwU znla^}_v=1t!ARV5%3wG?BY z)Yvbj)hZKezt{0p(ey{8(t4GcUbGtC_aH()S53|&SdJwVe%C{Vh>}ES$_n~&s>+^m zWi2aSmh-4L$2;~JW=`W{SPY#G1Lw}RKOZ4*Shp=#|2FbKF!KFxhsu&QCI$xG2wO@z z)sJU|MEzv}PEON>R3DBnw=etTME@If_1D)b&@$J}-C*Ss*p)cv_$iPJTlg|}ae&UCW$-Qhz_N6WL;w81MUL2>VsZFlcSrmE_b?t@sDx+M_oj)9 ziEZIuU+wm-j1^8bRrdSLIqcRlogQmid^Jk+6!&D6t@`Cn4f!|~ZV_sd_@p#gYY12c zc3>5nwC)gwK)vZBeFD`azi*t&BtNPkXEa=STruIO<=F;{8oPF=oOO@xboOuxo<*wM z9Ic)Yoa#1jAuSBNKPcJx@PkNpS)AOp6;4lWd>YYGE$nmB zM2>(5m{adQ?DBpn!ksYp)rU?_RSwte-yOlP<`v>BenUkOwmng%Re@l1JHA)HY_jO5v%&UsZw`1Uvb80)IfzSc8=Z@vdV38UDj z@pG)yZa!fc-@B+G-;u06V{7yED@vYEXJ^o1Le+Ln)0(E`-J^jlcuxKbeYmmilbzqS z+VWh*Zz1ptmo1)6VyV%#k@WFJmBqM}n7)(Fp7w)NXFhvrPse0Z9g2oB$hXA<2mLOCNODuSs?H+qE%4SJ||wPNYBKhYr`>?&2PGkVGuHLhD7 zx+tcdybpY=bEJB6Zv$paXigemiEX+1RBey5qS;ZRLH|)_N<>Y9IeC6h42_KK8u>5> zCUImnhnS`grJ2or|NeIKLcXOrxWKfX*H6uD(- z0h`e;2j`c4kb2DWvNPYw`fiuiOzLN-;8c~++G#ECKu_J7iV>igzar2OnTE#hJ~yDaKhO+6m^`l4EFZ2 z8!KK{!KfbVs(ZJ_aTGlUqHB4hQhFrUJT9TyXQQ?h#E@I(9xy6?h1(6V6pXN!I2h5_ zX4yb_gTe=}-_gN?WuKvieI%6<6d=||{WulkK?Z5KE(Y~{y_Rv4;sIYV6(&j*2BYix z3dphk{jKz&p6Ed^w4R?bSW--`MzZ**c6Y(Ee-HtQ;FIfMvNG>`!bR^=BoX5wYQZ-x{G#~@@!;Bf2lu`sqBC5fnD{1kED zHdS^DfxleBh6$h~>tawm5Q*~gyU?lgpNUIP?Z-_%WlYh4m;}$;z#RCWFeZ1CFXkZQKIdlFX7{G}T6m|^^ z5qXI!aUa7=9C!lKH^GV|5JG|YFZYq|n%e7_r9VT4Xt_TP)AVk56!a#l4)C`=BBM?` z;-2}m-n(5}YJl5YKi$6Nt==>$MHyOECAew0BD>7CYCRV0^4AuuAqi&H8 zJ~qupMk!mviSSP^WDqY8J-7_MRodgeW#8?5KHuMw7s52Z8JWSkkH{G*ta7tB*}9HQ zKbedMnQydHe{k50H()Y75gs{cqd1 zZ%NYn?JP@!lbkLzV)%Y=Nc;-s3+fo^dIU0sK3cb_>r5v7Zw@W=KJZaS#|2oYd{0#P z?7V{GQdJT`pmm?REV5kQKa!eZ#Ci^~uEy4JHk>ZmtxnLM*;Yh8g~jG*{(V?$1F=)K z7UAvqOND@5rK^guxXMnY9+*Yx8PT8o9X&e=P@vQV_m90XnT zB&@;t(Tw*4i-e{W$+7SA`^xF<3lnwi91or+AaWcvc2r)+r}1m)H>^HSbqToHKR=Sx zUjSbfepYwSp|qP!>m8$;D+sQ6{f);n!0gcJ~}?11DQ9;<)PbU=CP;0jbAiEOEhf25&9c zgy}1B(;32RCq`S9ooYic>8oFv47v!9^6tJVCUE6&;D5(EAvdX2q)uOX#AH04Toap= zDL0!GhE~6(ub4u+s zSY=U*s4}k_y65*E{h&k7b~E^*OJ9)lkPxwC_uhB_w)jb?aSY4)bqy7RG$CD;-J8gc z{Bl)7m*l`fhXPsV7k-|Rl99aM=E9_j+DxBQbX1q|AplGjz49CfF3uvDeVx(uL0!f! zng|qcDGYwZ&_o!o+8PrfY0!KUzu`tn4&kuUB*uDJX0y59si$4ssoU(>UZjW<@njKMxUHyCwm-^k-AFG+q&aDR*Xb! zhEqpB+hTiIFyE4R3xQReLB+&<3p$6c^RiTP@~FC47gb&*$w}weMe33H{Dn0mshZ@+ z`@JO5`zKOTji@mrs{silj)MhSQ=w&Ve{Ri-iKuyffAl7 zL^`@LYFMg|5T8Z*yV*xUzG${_%Nd5-dc?Eu7z~Dv35Nc{xst@Q;MF!0Q@=`a6rEF$ zKDo}$Qww+-*JhAhzU+)0wdR+&;?;iTlYJuwA`Y1s)wM_Om!^U_5}oKB_8r?K8WC&@ z;@K@F27O#=Fqzu3wgbbWn~L+X`3L1pp>h-r`LH*~4mE?-`Q=ZEl{LcHMty!f#h3i> z32Qzc%SnCtS+ti)$s_U8ydLT}+e;sQsKQ%S0x2~BH~E3h5&%QvT^fjm#g%U@^IaYX z@7jD5+i^Ij+0YBQ?z!v4_g5`|m=s(I`tjPh!qE_nJPDwOx~}t5&c}hmE=qHwZ+61N zjM?AHCR5{8OlT)$mS^ae=%1c!aOFjs?#zX4Gju6OdWm2fcE|@0OP6kVKjpJa%wa@m z553~<-=qFv4TZmKHr8M?1D2Ko7!L*n&e3O?O#}|gc#WR*alHzx+-ChipS*$gHgnw| znOdWi;AXc>`$FI<)Bqa9mFQZ#{Drp75Zc+;+%J+Bj(Q^?4n`2lIh5}rwxY~H*>i`G z(sqUIg&efhtx|=M%08gVvd@BI=KY}({QblE`S-a~l0oVOFsIrFaEEHe?=S;O7D{SF z$isIBn~#cNSNrPWjdAmrQDh-rmx7N+^J8}h>rK0aB`-SYq=zS z?*3BQl=Ct#YBYRHGMYU75k6 zWBl2#<68jp*zP!zHgO<<+zPvc*wXSv;(jv#BwFC9tJvh<0>E0SNJJr9$H-zF8QrLz zE&fA78~P=oxiO1_av8Qbs%wy{Zhew;u3(~1mYS&wg`E=!o<%pUbmrGX%!@)Yi>;;> zHAF7sz1$u;gl}_Hvug+Km@v6YEg~9RxH>lL&L2j2)l9k4*>eWmt>O%(owRmiIn46% zvQX#VzT4X1!r2iH`IeS8uyMvVLAx5a)|mQLX#BSL`<7hbo8NxY6!Id!0=N)3y|nLP zX9R0s3@kWSp)`^i8`tN)F04CCdire-)DoqBupZMrKh2&WT{X9KjSmi2y(cN2kCK90 zV@;fu=WPFDY{N7<@bTK^vRK8+XmuWA6yBxd;%n*Rjwl@$gO=j$!p#pgJ8s>>q*aG5 znw7Q=q%@Fp%Q4E84u5jYw4~hxwB5btEZ7y+1WGVC_0N+b3TXP$f*|r}$csVX%*`;l>ZO>T9?jbcy*ZCDVn8PNxVnb~iIQnt zm>hLyT=46!%{&}0!HUmquEu)X;2+2tk=j57kQHMb$IK6S3}7sQ>%~{-%Gdp;h|l$O zSvVG*E+Qv~D@&6%8CM^gQ>!+*(9C=>&BM%WIl?wQh2dU$$!y+j3V_|0_^5Tc=zkU1 zOl456gOC#C7lh=_+U1Cb*yn8&*!j@Ny*|LK(5r3_$2cIoFf>~74|h9}2#~{OhrT2- zi2ECKq=C9k1+j^@M@8a54Nh9%>l}kFw=bi+d+fF; z&t9ffB9o}-oejEG-t&eDi_;-#-P+}lEg`vgbj1va^{|gFO~0~5wr#3BwpTC53z4|g z#pzxu4>Fdf6!)w+ilkSYNv$8Tn#0?LudsHlRCvCuwy6jMQB1-}HO#m(e0cw%;aeDh zXaoA1MFxJ!0%JNULx&vvbPYooogetqxCNkxBQ~fuz)XdF67jlY&1HB z&1T_JhtqmEgrkA!#2x)TosuvC4@C(Q(&hGWifFandBh8zn+Y~mNp{VMLgR1feI~4H zKR0VFbUMBhwc{+3y-+KA6HdDr&k&LQBVy=@6DN@y=NO$S6D~4>i;e4f6>L+BGx9}) zElVjwK%%SU*CtpqO8ow_qNyUl&|WwRj$YAjZ2-kV6;6!ynxlvYaJVJ!;Gk3xXSDl8 zkIbjI3i@!FC(knFE5a2r6@+M%^H*KT8gq20T!w3yoEtkcVa^p!8E5;8i91F`ta9VW zF>@jWT3_t7QA7(}5Rk3j0g;_!WZ8}ZrxV&pzG zA#h)-=TcYiZ}OCB1ObwhCR`Xvmbc7;Y2cwk&VnSglQIrdD@;+iM36&<2*u=5{JyhIF>+;0o&xWr9Uy^Q`EZ+&ka{ zH<$Uy0ENek1j}y1AQW#(oc!BuyDP6-o01gfI-g1dClMy)Wb3DH(`H~!fdcPc6(e1~ zE8YXl!4Ixr-9Rr`lLUPOGGP-IfjcZ@wQP_DUl*17^vIl+)>Mf;A{|>fbj9{zdrdd) zovOMcDTP_RMc%iYXN+8624|K=c%d_Terx92 z+aHDxF;OtiB9Rd6bCmxEvz1BW1l!@?VXXiw{s;d32Z#T+YvUgr{(qbhd6^`50~{6_ zn5aSZNDQseu#4uyohSY&_yY=jXyEiua!~1fP=sl49R?(BQ0T9yESxQIcdZyg0omKA zx6qKr32AZ#`RmD0U=3tc{sR0S*TC-ptLQF{f#CpihdH2$Jj0;EL0a~!I0pqK7+e?p znd&CW4OHaCSEh=1I`kT1`Yv8G@n`;P;NmOWhK9xs<%e>6Cf`TH!$1-*p-5xs?k)zd z6MKpG-W?SMdGTN4x(46E@Ylt8N$d^`;}s`|ib@C}2Kd@PgZ;l|X2pH#!LetlKn|%N zoWA>j=UuTdED4+($Yi^su>2!Cve;sZ&=tV9*N}@h^Y`MN#zXsfKWhEs^X?G0i(|@@ zx`nAbM7+1T031w=T%xajFHy@|sES_{Lgzao6BUvHK3%BYfcjJ58Y;?Nu(<1gFK!P! z4Bryli$eXjUpmBBmK4g)o$~R=I=!?ezvEKW;PU0J}_vv$y1M~Ok_5nd_kk=)N4H!pdKsD z$;YK&0y2>dmmtnEf}vau@-qCV)GFOve9bO)t`}JfwDRJA0Z{()^77iqjL#c!12rEL zE-uaR)xrd9(=76(HGm>rWl4=8UJvA3+UrB*Q_Ri)e(ZQ2VT{ZQm^PXnoc~&RC|1Gz?hL*>?&SNJyFe>pby5icv4Y*5Ap#pz zib|DxgfxqzFM4nqzC1H=5f#iVS1K095I<69mP<)WfFJq%~nWgCVaC=B6igh3ALH zB-^+;@Y`Z{4LOJ+PoBVik2?*%J0NZQ9tg9qiYhRKpoTA=P`>|Ojb}ESq;;p&^m%$K zC;)8xgWX2nN;41VcC-kQ4Koz$h`tg0?WRqnJ?mO1Nc6bj(8^*L^%kl4SqbkE-ibol zFB9?#>9v(j8fBIsLmM`H5lZ+Zw!?p4t5qaYePN?$E|8=D%Ud&*0^JmSOD0SRd4psu zK!m5zwbPXlnL{I<$meGb3`$dwEXYSbnRN%Quor%{{hOqSZ^PNQmv34>tNr!G zG!5QyN3LjtOqV{DZLy91TT4%fKlWe{VaKFJ-6t-KnwBm!JbQD@xG4D2XkONvk=@w1 zuxBY%J)j&kZHq-^qEk4lYJ&p~0|TH4Eth-njS?<6m1m|uup!j9Lk$;989l5lBlih( z;(%*HhGF`a=I|&nJb4p&2?S24hwYfF%}V!!T>CLfBFP_B7D7;6Uh9!(gh-EGyOFy^;K__2BRIXTs4t@I1J9IXfdce5toEsmO8*{m@Rh(d>NGeol2!>AS}{ zUwk-RJWCo5Z!GpB(|5Ss*l28)VReDA(2TpvQRu9%%y?I;Lym4I+wgwmmT!UX;M9j~d0a2w3o?Gwd0P!d>$(8j0yMC0r|_;v_pv%*XK z?#+TyTXuI!lDJ@J20d2`3W!{i!v0F`=nw@)4R0J*wkzfG`*7vDRea0MR=+dpzGOJ8 zOI&98$y1w}V9u^cK~k8WWSXdB)pP!1oRW|xoQ7DXXg*{?#@3F=0|2$z`rXb6)h7#8 zg{F%K!U(XXgih>20Wl*n*6otI^d!yTYtj8}5z4TTXL{*NWFes$j|iQTjM) zZTi%ots`HK?Z~q`$d?oUA1@~q&H9?;RNQJUrB0dkS5{1PqD;lj@J%>lFh4+qr8-Mx z1|#oD;!6lEZhvEyIsD|p=gQzx$vc16uSI6qm+W}!m+|7=4orqhSlb~ib&w*Ano&k7 z$BNMOY`>S`ilLGnpfp%3ScH~z(M~d3M2{cNYEnB(K3ndyNDY7biQwPvepRTh`K!kp z4%(MJ8|HavPC-rMT)>mDiF|pV3KED;e|jD+@UFKO(f(LXUqvWBgR=%_ zvB{G2MR`bgUB3TmdP5KI1nELR@bE$x1ArH;>b$iF4)!CfQqR_p^)Gg?tb{xSlUU6T zKDIG^Ru(&6+D#P7C4ghxV~dDK#_R0lf0i;oEkaw9&sk>sQL4>|(|m;v1MJZmDyOq94hZ;N56vRNAHIUfT)K;kmt$yHgl z>|%i54a}((=VD`DWV!n3VQaHf4P+knBEZJDknxYaScU9?dSxv#NUf#pt7v2{hWBT! zH<3aDO{ShkGsQpE%jlB+s=2#bWpb=G4=B(b{qG4I1Oyo`940GRzN+BYl}Q8sw?7j$ z*XroOY&71l@tpCpBys|?_}In;Z_mn= z{)`!KQt^2C=Ruojmd4jqsrVX&Tlf`S)Yb{b&N-jn zsMigd#ZvErntJtU$NfNi@=Ixvan>koxPe`J>E>upjZrM-#R3*ltHdJi(89NuqMBbO zTw;->pbA;CGOnlVAp@m4JBMx;WRh`u%tRhB`~AZ9=PmsuWAkUbMQt*tt|6zAQ!qA; zb)#v0b=UKKf(N{xKRnvpZzgI*RH{_G8O1dmmx{&%dnCx1;52*m4YK?fcyCd{OqHJV+cvN;oMT&ycA)D| zB=^PA+_6AF{%|$$i5iO){Z6d@OndMIX6DE{dsjL9?r0Js*Ml(U!!G6iw29fB@LkNh zExNKQH#RM2TF}S=xJN8%`8>hmgw`0Zu1CWhWug+Tw_l%o-Nh|B|6Wm`T$x=kS9Kx! zfLAB|DMVwGmp)YMGQBfHja34Pqz)=ame*ZGa%n}!ahS#3CgOWuNxTzSkzcO$dHhcS z{Ugem7%xDgm!IaoDtlgO_e~$qM4@~lBH!vz$&OrS1P@j7A%b$rqpk2o@g z(fE@^-~_<%>Xw-(e`tLVgY8-OFK^PiN#f^^#AF8caQ}E!Yh(U2>PFCAc+^?Dnp}Sy zo-nI*1MP1fc=$ZW>WAunn&Rn3UtO%)jqh<|1fhG*bJz=}AGOv;md6F7C>LLR88$S=SZo;%7WF%qlyrt};?+`Q zOT|=B^$pxw7#LWfzPY>V)_$bZ{g&aAbQN~RD#nX&G_nU2v3;iXOTy~y_%+>aqTF-s zL7`q2br*7m4DT2gE<~WZqTl~DXeP#o8@)`a*0-W}p4Ey;)UU}_rVYiO)L7OWA1gB= z=HtrRk6fUYQLuY;x$y#DJ3Z%B-ScZxJLV#m1fg;%5$H(X$j9zVumtX z#Cy+wliC35VEA@gYVlX)ct!nUr|k^fmd!OY*}CUkEV^!u4AAO;X75nz&foWnJ+?KU ze6-cx_(K*RRiqzZHO)W`r*hd0I`lrV6&9$|c)4K43SAiE}v^={u43uTgoAo|;w!trHo`)7|JQGrcIN`b3;>oj7&X zT~H{pTSa?v|mmJeMKj-W}9K9QwqLXJB`Jao$~;SPIsEk+A2lWe zdgt;YmV2I-pPS7Zf6?{aa%6$_LhWoL!>W%w(h-4X-H^YWBU^r2`$g`&K{SZbd7XFT z)#40Af1BfA?|3C6Q-7rp_Tf2JqQw-=Y{DjkQ{A~lOxZH2w5mrZ=ngp`B!j7TvM)hBxvmDT2c|R7io4*C$XX z6rl222cPYsX8aiQr$|jLieZjI{RH>SSCyZ`Zd7PIWHnyrrQpnQV>?V!fFzm|hvDpI zbp_!gUpgnC9W3~yRk-7H2GLLgC6KIT=*SfD2z5scwJQZ<^P-W;vOqJsGA=xX64O-Pt+7gHHZV1{LvdCIEztx_RMG zgvjb+yn0{C%R-U)&H(EFLGiA8C|YT;v^M`hvhnFP4o*{KaH{eC58wqw_B!k?FMK1E zl)sINBaVdvBVpOQC<9HHAms<(^FJW(Kk)fK%K-Af$D$a)Jg`u4Fh0~bdSj+p&9~1e zh|=M>yMH9&n^e8^I_|Ac+)VKX(d(kpP-d{%FoNBq@uILBXQica3P9?hZN1sciV=4c zRlL#I{Y3;$K{)u#_Z%E^Mn=D=#b9kXSA zjJg7zWt)oT#qW#@?pAea#Dm5RzKmh^yWznMa%1u9@vS8M{C*%6Lqjm)h(86lE$$C{ zjE*KJ1HR=EBIPHR1`I;Kg1r^^`W`TNibp>mpc;dj4LLXoC-dab0hhdL`$~k?PX)dW zw4?oS!{a`f&u9F41Q@9XV8p5$8bMg77vQrC2ib?H#tGosg{r9QUhc2K9KTk;^Wr}N z&}nM0>jD+YG?;*CZ>RxrND#PSIkSjE0V5TRbQ;g&8X6P~g`EUclw+X4JgiYr!4$Eh zga5+7-xPNr2SA$j9M@35b#d1Li_(r(J`uu1Cc#f!gF_q^qWLan*6Tm$Iet#$Bj3MR zz#*}uLA9tmFCENLkr(}Vp9Jd>Yq&2=Dwb7RwalCjNIrdX+NePH1vlgbjA81x7mFbz zmZTmZA3SddwbJC#Oa=(h6R84LFgcKai9n{>K}39a7y&^O4;Yhvb-t+#@PsR_p-91bnz8LHAT8=Xj* z>j(wmJ=_4(LWF}xC$%pw%zkjYdzc_a(FQXuThA$K_4+-#A1aDZ8UgjuRl#~ks$*3R zP%gIfRV7}PO?QuqtK(kr&m`tqMqcfW?+LGn?B97(LSNAkXpV_6WM;Wy1pSoG0p9Rc zCg3;4H*tbsxj>g)Q4l-w3QwE+RXUahSew0p_Vuw4`?~1hUIlfN&F+Pi6PNx7c~gXs ze%H+G=AW63Ki*w+2Y^e6Y3f@>`3$`T&|1nB0~eP?_VXjcm}ks5ErFUlk-E$|c33m` zxOcS4Z}|y**+3fEWD;XAlc@B=B-PhO@xP50f9mv(%y)P?7Y-y>5!`+Q)De@2Py7av z+}TDAzwxvbUR3TDZx6@Jbwj?vOc*jyq~XzqM5=E=Y~RUY9*PPbZGkts{pqSFwGT5D zIGQh=k?lZgj6XLo?FVJ1_@UOz>0EK3&L>1@Ok^lso}H|5v5tMOTWA`itxCp$P_1~Y z6**W`ns4m4_0d%Ffje%yPe~^y(o$MpMb*%k$uH9ZHc4sEja?Ef3h8J=G#<>z(f;BF zG%6hLd&HYf-@&8UyTQ1C26?G{s6|Y>xZ;=e#B^N`axf6e-z)~NnX~Fy)$tA=o>|?3 zQ0{G*q1K7UHJ;62Pm52f1z|ECvBy)oD1|qj^Q|LTSpDsYsJ4a84m;nKAt^b0->Jy6 zZ2e`(-6i^S-dm7Oqp+F+w@^$fb!=%q(THFq$Sn(6j)h`@jkDIifTAQ-asp12iykEyACwriGOC?Z~6AZO&=;`4XxpOnqHF0@8XoN-gl7bzw^Q%NwDyr_M z*guiQ&2lo5XD$*0x2@EwoB!gSXB`)!PsZ6#Nm7)n8%I0ujup!A zvCNmZU9JU=X<0`2fE)XBai=LBjU{6^ue|0UygC3a?Z#+cQgH>wU^5-N3UbDl#|%63 zhFIS3z&x02I0u?;>$1`D=YnB? zeYGTu&`yeV{P_F6!#ED_yvr4Hqk}Lt!ia6c@cNm`1ruc2Zsq!p24R5aut=DU)$DP* zXt+GA3!m_@AUl_2660?P_G8!Z1mIdNi#zl z3Bm?M$jOGz89+IJ!%n(rS$csyJ2eT>sGA{#sgF;HYee%yk?K=R#mQY^Hc)?eH(^4zAVlS+rpb% zKr@+CuVQM&dW4)Nw^H3<eEwEvdV<%VX5 z2N7Z)qrrIDK~xA!=%(74*{?1rAMG$m=X9L`~47t46HdygH zwX1#|FcO3#cEqJM;P~P}TrxhYd|387rBV*e9(AAROO=0}A^==xK>(rM`JX%e-@N(; jO!ch%!7~|@h052YwEJ?U9&d{}WWYt( + std::chrono::nanoseconds( + (this->get_clock()->now() - e.second->header.stamp).nanoseconds())) + .count(); + debug_publisher_->publish( + "debug" + e.first + "/pipeline_latency_ms", pipeline_latency_ms); + } + } + } + // publish concatenated pointcloud if (concat_cloud_ptr) { auto output = std::make_unique(*concat_cloud_ptr); diff --git a/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp index 20d1f5c8b3d6d..cfbeffee9982c 100644 --- a/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp @@ -65,7 +65,7 @@ CropBoxFilterComponent::CropBoxFilterComponent(const rclcpp::NodeOptions & optio using tier4_autoware_utils::DebugPublisher; using tier4_autoware_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); - debug_publisher_ = std::make_unique(this, "crop_box_filter"); + debug_publisher_ = std::make_unique(this, this->get_name()); stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); } @@ -195,6 +195,14 @@ void CropBoxFilterComponent::faster_filter( "debug/cyclic_time_ms", cyclic_time_ms); debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); + + auto pipeline_latency_ms = + std::chrono::duration( + std::chrono::nanoseconds((this->get_clock()->now() - input->header.stamp).nanoseconds())) + .count(); + + debug_publisher_->publish( + "debug/pipeline_latency_ms", pipeline_latency_ms); } } diff --git a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp b/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp index dd38b85a2b56d..d1d91ed7ec439 100644 --- a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp +++ b/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp @@ -128,6 +128,16 @@ void DistortionCorrectorComponent::onPointCloud(PointCloud2::UniquePtr points_ms undistortPointCloud(tf2_base_link_to_sensor, *points_msg); + if (debug_publisher_) { + auto pipeline_latency_ms = + std::chrono::duration( + std::chrono::nanoseconds( + (this->get_clock()->now() - points_msg->header.stamp).nanoseconds())) + .count(); + debug_publisher_->publish( + "debug/pipeline_latency_ms", pipeline_latency_ms); + } + undistorted_points_pub_->publish(std::move(points_msg)); // add processing time for debug diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp index d2570b9c4d786..d968b06a0dc61 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp @@ -204,6 +204,14 @@ void RingOutlierFilterComponent::faster_filter( "debug/cyclic_time_ms", cyclic_time_ms); debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); + + auto pipeline_latency_ms = + std::chrono::duration( + std::chrono::nanoseconds((this->get_clock()->now() - input->header.stamp).nanoseconds())) + .count(); + + debug_publisher_->publish( + "debug/pipeline_latency_ms", pipeline_latency_ms); } } From 9687a49ea7e4e141bf93d82422484e7e156cd747 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 1 Feb 2024 17:43:00 +0900 Subject: [PATCH 05/13] ci(build-and-test-differential): add df -h (#6283) * ci(build-and-test-differential): add df -h Signed-off-by: kminoda * ci: update yaml format Signed-off-by: kminoda --------- Signed-off-by: kminoda --- .github/workflows/build-and-test-differential.yaml | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index f25c2fe07aab5..e3711d413cb68 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -36,6 +36,9 @@ jobs: with: fetch-depth: 0 + - name: Check disk space before build + run: df -h + - name: Remove exec_depend uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1 @@ -69,6 +72,9 @@ jobs: verbose: true flags: differential + - name: Check disk space after build + run: df -h + clang-tidy-differential: runs-on: ubuntu-latest container: ghcr.io/autowarefoundation/autoware-universe:humble-latest-cuda From 742f44a5e647807d164740dd1185066ed363b6fb Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 1 Feb 2024 17:43:47 +0900 Subject: [PATCH 06/13] feat(detection): add container option (#6228) * feat(lidar_centerpoint,image_projection_based_fusion): add pointcloud_container option Signed-off-by: kminoda * revert lidar_perception_model Signed-off-by: kminoda * style(pre-commit): autofix * fix: add options Signed-off-by: kminoda * fix: fix default param Signed-off-by: kminoda * update node name Signed-off-by: kminoda * fix: fix IfCondition Signed-off-by: kminoda * fix pointpainting namespace Signed-off-by: kminoda * fix: fix launch args Signed-off-by: kminoda * fix(euclidean_cluster): do not launch individual container when use_pointcloud_container is true Signed-off-by: kminoda * fix(euclidean_cluster): fix launch condition Signed-off-by: kminoda * fix(euclidean_cluster): fix launch condition Signed-off-by: kminoda * Update perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> Co-authored-by: Kenzo Lobos Tsunekawa --- .../detector/camera_lidar_detector.launch.xml | 3 + .../detector/lidar_dnn_detector.launch.xml | 3 + .../detector/lidar_rule_detector.launch.xml | 3 + .../launch/euclidean_cluster.launch.py | 13 ++++- .../launch/euclidean_cluster.launch.xml | 5 ++ ...xel_grid_based_euclidean_cluster.launch.py | 13 ++++- ...el_grid_based_euclidean_cluster.launch.xml | 5 ++ .../launch/pointpainting_fusion.launch.xml | 51 ++++++++++++++++- .../detection_class_remapper.param.yaml | 6 +- .../launch/lidar_centerpoint.launch.xml | 57 +++++++++++++------ 10 files changed, 135 insertions(+), 24 deletions(-) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml index 1c9201a9af8b3..2232feb6d7c67 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml @@ -85,6 +85,9 @@ + + + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml index 1a97659b357d8..5b5fabd4dd886 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml @@ -22,6 +22,9 @@ + + + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_rule_detector.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_rule_detector.launch.xml index ce34640bd3179..cec0c3bc05aac 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_rule_detector.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_rule_detector.launch.xml @@ -26,6 +26,9 @@ + + + diff --git a/perception/euclidean_cluster/launch/euclidean_cluster.launch.py b/perception/euclidean_cluster/launch/euclidean_cluster.launch.py index 66c25396a656e..b8d4f61a9cf28 100644 --- a/perception/euclidean_cluster/launch/euclidean_cluster.launch.py +++ b/perception/euclidean_cluster/launch/euclidean_cluster.launch.py @@ -76,6 +76,13 @@ def load_composable_node_param(param_path): executable="component_container", composable_node_descriptions=[], output="screen", + condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), + ) + + target_container = ( + LaunchConfiguration("pointcloud_container_name") + if IfCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context) + else container ) use_low_height_pointcloud_loader = LoadComposableNodes( @@ -83,13 +90,13 @@ def load_composable_node_param(param_path): low_height_cropbox_filter_component, use_low_height_euclidean_component, ], - target_container=container, + target_container=target_container, condition=IfCondition(LaunchConfiguration("use_low_height_cropbox")), ) disuse_low_height_pointcloud_loader = LoadComposableNodes( composable_node_descriptions=[disuse_low_height_euclidean_component], - target_container=container, + target_container=target_container, condition=UnlessCondition(LaunchConfiguration("use_low_height_cropbox")), ) @@ -106,6 +113,8 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("input_map", "/map/pointcloud_map"), add_launch_arg("output_clusters", "clusters"), add_launch_arg("use_low_height_cropbox", "false"), + add_launch_arg("use_pointcloud_container", "false"), + add_launch_arg("pointcloud_container_name", "pointcloud_container"), add_launch_arg( "euclidean_param_path", [ diff --git a/perception/euclidean_cluster/launch/euclidean_cluster.launch.xml b/perception/euclidean_cluster/launch/euclidean_cluster.launch.xml index fd1ea82befae0..f4deeccf7b76c 100644 --- a/perception/euclidean_cluster/launch/euclidean_cluster.launch.xml +++ b/perception/euclidean_cluster/launch/euclidean_cluster.launch.xml @@ -5,6 +5,8 @@ + + @@ -12,5 +14,8 @@ + + + diff --git a/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py b/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py index 00bcd4422bd3c..607e1bf30ccaa 100644 --- a/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py +++ b/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py @@ -77,6 +77,13 @@ def load_composable_node_param(param_path): executable="component_container", composable_node_descriptions=[], output="screen", + condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), + ) + + target_container = ( + LaunchConfiguration("pointcloud_container_name") + if IfCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context) + else container ) use_low_height_pointcloud_loader = LoadComposableNodes( @@ -84,13 +91,13 @@ def load_composable_node_param(param_path): low_height_cropbox_filter_component, use_low_height_euclidean_component, ], - target_container=container, + target_container=target_container, condition=IfCondition(LaunchConfiguration("use_low_height_cropbox")), ) disuse_low_height_pointcloud_loader = LoadComposableNodes( composable_node_descriptions=[disuse_low_height_euclidean_component], - target_container=container, + target_container=target_container, condition=UnlessCondition(LaunchConfiguration("use_low_height_cropbox")), ) return [ @@ -110,6 +117,8 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("input_map", "/map/pointcloud_map"), add_launch_arg("output_clusters", "clusters"), add_launch_arg("use_low_height_cropbox", "false"), + add_launch_arg("use_pointcloud_container", "false"), + add_launch_arg("pointcloud_container_name", "pointcloud_container"), add_launch_arg( "voxel_grid_based_euclidean_param_path", [ diff --git a/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.xml b/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.xml index b6a426dabfd12..3a7c685d8f449 100644 --- a/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.xml +++ b/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.xml @@ -5,6 +5,8 @@ + + @@ -12,5 +14,8 @@ + + + diff --git a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml index 33781461fa1cc..db13d73e37fa7 100644 --- a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml @@ -26,6 +26,9 @@ + + + @@ -38,7 +41,53 @@ - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception/lidar_centerpoint/config/detection_class_remapper.param.yaml b/perception/lidar_centerpoint/config/detection_class_remapper.param.yaml index ed378ffa44a70..baea087c96bca 100644 --- a/perception/lidar_centerpoint/config/detection_class_remapper.param.yaml +++ b/perception/lidar_centerpoint/config/detection_class_remapper.param.yaml @@ -29,9 +29,9 @@ max_area_matrix: #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN [ 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #UNKNOWN - 0.000, 0.000, 36.000, 0.000, inf, 0.000, 0.000, 0.000, #CAR - 0.000, 0.000, 0.000, 0.000, inf, 0.000, 0.000, 0.000, #TRUCK - 0.000, 0.000, 0.000, 0.000, inf, 0.000, 0.000, 0.000, #BUS + 0.000, 0.000, 36.000, 0.000, 999.999, 0.000, 0.000, 0.000, #CAR + 0.000, 0.000, 0.000, 0.000, 999.999, 0.000, 0.000, 0.000, #TRUCK + 0.000, 0.000, 0.000, 0.000, 999.999, 0.000, 0.000, 0.000, #BUS 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #TRAILER 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #MOTORBIKE 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #BICYCLE diff --git a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml index a7f181ab78ac6..1210875770510 100644 --- a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml +++ b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml @@ -11,20 +11,45 @@ - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From a1d4df191ea28a4e6db280c56a8b12ccf1cd7b4e Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 1 Feb 2024 18:26:36 +0900 Subject: [PATCH 07/13] docs(start_planner): show typical usecase of start planner and limitaion (#6264) * Add start planner module and related images * Update geometric pull out path generation in shoulder lane * Update README.md with additional path generation feature Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../README.md | 69 ++++++++++++++++-- .../images/freespace_pull_out.png | Bin 0 -> 533509 bytes .../images/geometric_pull_out_path.drawio.svg | 48 ++++++++++++ ...ometric_pull_out_path_with_back.drawio.svg | 57 +++++++++++++++ .../images/shift_pull_out_path.drawio.svg | 41 +++++++++++ ...ft_pull_out_path_from_road_lane.drawio.svg | 31 ++++++++ .../shift_pull_out_path_with_back.drawio.svg | 47 ++++++++++++ .../start_from_road_shoulder.drawio.svg | 35 --------- .../images/start_from_road_side.drawio.svg | 34 --------- .../images/start_planner_example.png | Bin 0 -> 247330 bytes 10 files changed, 285 insertions(+), 77 deletions(-) create mode 100644 planning/behavior_path_start_planner_module/images/freespace_pull_out.png create mode 100644 planning/behavior_path_start_planner_module/images/geometric_pull_out_path.drawio.svg create mode 100644 planning/behavior_path_start_planner_module/images/geometric_pull_out_path_with_back.drawio.svg create mode 100644 planning/behavior_path_start_planner_module/images/shift_pull_out_path.drawio.svg create mode 100644 planning/behavior_path_start_planner_module/images/shift_pull_out_path_from_road_lane.drawio.svg create mode 100644 planning/behavior_path_start_planner_module/images/shift_pull_out_path_with_back.drawio.svg delete mode 100644 planning/behavior_path_start_planner_module/images/start_from_road_shoulder.drawio.svg delete mode 100644 planning/behavior_path_start_planner_module/images/start_from_road_side.drawio.svg create mode 100644 planning/behavior_path_start_planner_module/images/start_planner_example.png diff --git a/planning/behavior_path_start_planner_module/README.md b/planning/behavior_path_start_planner_module/README.md index b26864eb450d5..5280f9c2ad020 100644 --- a/planning/behavior_path_start_planner_module/README.md +++ b/planning/behavior_path_start_planner_module/README.md @@ -2,24 +2,77 @@ ## Purpose / Role -The Start Planner module is designed to generate a path from the current ego position to the driving lane, avoiding static obstacles and stopping in response to dynamic obstacles when a collision is detected. +This module generates and plans a path for safely merging from the shoulder lane or side of road lane into the center of the road lane. -Use cases include: +Specifically, it includes the following features: -- pull out from the side of the road lane to centerline. +- Plan the path to automatically start from the shoulder lane or side of road lane to center of road lane. +- When parked vehicles are present on the shoulder lane, the module generates a path that allows for starting with a gap of a specified margin. +- If a collision with other traffic participants is detected while traveling on the generated path, it will stop as much as possible.
- ![case1](images/start_from_road_side.drawio.svg){width=1000} -
pull out from side of the road lane
+ ![start_planner_module](images/start_planner_example.png){width=1100}
-- pull out from the shoulder lane to the road lane centerline. +## Use Cases + +Give an typical example of how path generation is executed. Showing example of path generation starts from shoulder lane, but also from side of road lane can be generated. + +
+ ![shift_pull_out_from_road_lane](images/shift_pull_out_path_from_road_lane.drawio.svg){width=1100} +
+ +### **Use Case 1: Shift pull out** + +In the shoulder lane, when there are no parked vehicles ahead and the shoulder lane is sufficiently long, a forward shift pull out path (a clothoid curve with consistent jerk) is generated. + +
+ ![shift_pull_out](images/shift_pull_out_path.drawio.svg){width=1100} +
+ +### **Use Case 2: Geometric pull out** + +In the shoulder lane, when there are objects in front and the lane is not sufficiently long behind, a geometric pull out path is generated. + +
+ ![geometric_pull_out](images/geometric_pull_out_path.drawio.svg){width=1100} +
+ +### **Use Case 3: Backward and shift pull out** + +In the shoulder lane, when there are parked vehicles ahead and the lane is sufficiently long behind, a path that involves reversing before generating a forward shift pull out path is created. + +
+ ![shift_pull_out_with_back](images/shift_pull_out_path_with_back.drawio.svg){width=1100} +
+ +### **Use Case 4: Backward and geometric pull out** + +In the shoulder lane, when there is an object ahead and not enough space to reverse sufficiently, a path that involves reversing before making an geometric pull out is generated.
- ![case2](images/start_from_road_shoulder.drawio.svg){width=1000} -
pull out from the shoulder lane
+ ![geometric_pull_out_with_back](images/geometric_pull_out_path_with_back.drawio.svg){width=1100}
+### **Use Case 5: Freespace pull out** + +If the map is annotated with the information that a free space path can be generated in situations where both shift and geometric pull out paths are impossible to create, a path based on the free space algorithm will be generated. + +
+ ![freespace_path](images/freespace_pull_out.png){width=1100} +
+ +**As a note, the patterns for generating these paths are based on default parameters, but as will be explained in the following sections, it is possible to control aspects such as making paths that involve reversing more likely to be generated, or making geometric paths more likely to be generated, by changing the path generation policy or adjusting the margin around static objects.** + +## Limitations + +Here are some notable limitations: + +- If parked vehicles exist in front of, behind, or on both sides of the shoulder, and it's not possible to maintain a specified distance from them, a stopping path will be generated, leading to a potential deadlock. +- In the default settings of the behavior_path_planner, an avoidance module operates in a later stage and attempts to avoid objects. However, it is not guaranteed that the start_planner module will output a path that can successfully navigate around obstacles. This means that if an unavoidable path is generated, it could result in a deadlock. +- The performance of safety check relies on the accuracy of the predicted paths generated by the map_based_prediction node. It's important to note that, currently, predicted paths that consider acceleration are not generated, and paths for low-speed objects may not be accurately produced, which requires caution. +- Given the current specifications of the rule-based algorithms, there is a trade-off between the safety of a path and its naturalness to humans. While it's possible to adjust parameters to manage this trade-off, improvements are necessary to better reconcile these aspects. + ## Design ```plantuml diff --git a/planning/behavior_path_start_planner_module/images/freespace_pull_out.png b/planning/behavior_path_start_planner_module/images/freespace_pull_out.png new file mode 100644 index 0000000000000000000000000000000000000000..86b95379f9bc1a3b07446a2cc911d94555544db2 GIT binary patch literal 533509 zcmZU*1ymF4`#wGcMJz@rpwfsNN+T&4BSvh(Mo0>R2)uMRBFI3>QPN6mjC>Ig2|+v;tSU0){fvgPxv` z`J2OsYge59YDv@aOn!bNPsgbgVibvJ^_T77uxtHv#ICAsF-Q65(c8Zv61TB~QLA5* zq?{-2Lm-HjrKRGKy0rTGdQoBFG$K0H^3kJvotB!r8wI;8D}zTUOZ#0m_}w^cRG~9< z`uyg7h?DW=_&e_L#)+uN2yWKV(NS(>9KV5Oxs8Pda`wY&%1E0|U;i32lGi6+gLEym zE%klhcF^kbAaC{b+WV;AJyV(=Tn0<>XC6Hot4fjC4x{0+wVH}v_O_nxl`Eg_vUR!! zBX@FDIr$7-v9=!Yb-#}G9sYjn)Kf+!U?JydgZDlIEBljnwjz~r;@vQNrC zm|ihtmNVaSAWu}KUw&~sGs@3$_a~vNRIYn%ZnEdcj(){*MZ=wrwJ*O|N`kYvEvz=H zcwdr#eEEe(oxs$aZ7wrTch0(OGu`R=+4z?%=N1!F@_4mMaa+VVKm&h0qNsCSbuRME zh{J>K0;Acrv9QJ0$-C$7ynR50J$?GLn(wS2(^&Y^MQ&ys5dwJ=pOVs5_u?X2U*S3x zW!6fk(_rjZa9KTL4C+6({oi(q!iO)89LIj`IhA$ObtY%U`Cri;=UlAk#wD|J&L-K> zP~ot1zf{vFgwx)J5L>#fWwyW0%MA~0pZ7fKEmN`T?dXW{T}At{{VgnRhNU?;%Ic|Q z-ScvyN4txCr)@NGMfJV6PakO$4ueZlCiJv0f!}#`=KJn3+(XLUgG62p)VTAR>$5T2 z2|ox_y`+GQ%htKBoBv2xSNCnD+|lfGXB*qEKEGBrzFxshIk_<)C8<a>;U#?*mdDS}cQj7OiqDFXv)Y^CuPx0- zc*$8q5pFb)-#O#s7K|_C!@|OnsR_9KL$yGNQu*PsZzUhc*0&*7sv))varbM{T1PrZ zM+p-GvfVR96-}aB3ig7Y>SZsxOBViU=g;{5^T!&^2^aq!+t*gS>3E06!#VXq?=kqe z8NzH?=E8*wqLPxZM#+$u)T~2kedCyE1vEIlsHi9e7WQb_H5}D%MNqG!pJ#x4bgY+> z<%-4YG@RT!EOD)+BTo>B&J+|EoS16OKm>D|HZ!a~-S(H!Jhh2&- zbrvyD;&j8o#d9_*&kX8}$FXXSX*~+~$xl$1X9HXCnycOkCPGlz8`m!23C(R@TvqSA zbXtfCHyuNToASa{Q-_eOj3~bC@_4C{r8O|zS<|)v*)VuZr}ty~b6L4VFfM;xL&JAr zY`pFz~3PWF8 zeMcbdgV^RYp*gG(Gy3GyxMvM4l+>FX1Uz^yu>eoHS zNX|;5Z1=-v8H1+Fs?hzle+#w1Kq?gwoeA2|7*jd>(VfrfPk2KLm1uSAFjkXn?&T}3 zYKRfnUWQT8?5tYMa|yLK;ELv&1i5g+8{Jtnb2j~|r?ggo=2`1-+~aP+r0C*0idI2N_~=tpmF$40%!AAe}I zWF5wwMy_L&+;%IB*pj5R!5o#f6`B|t**x1I^rC4(R;0qu62QShXr3O-N_cR^JO?SH zu+$FMd9u8H`!fBxoMlUZQg7;c^RzaQ$6f7B82_$2hsQLVsi9D;LD(eTPn;=7{h}XT zVcVNcGDpHuT2abu)ZRGIaGz06Dj$v$9ERQd0gbUggD*BRn%`bmu-=FsJUOuKlhM8Q zpbldrw>!H00Po#fBbxnJs9@%_bdvBR7ENItDi8eb7z;VeUr~k%0y8yiFn@S3%nYM4 z)!B$MLEcOdjSyUuVdRmR=Qqpt_2sSf%V^}vkr)OWgqav~PLyEX z%%V|FCpM2Y?6}APF;RjrZ~ptrqZ-U*LnEz?y0}iyi%x5gQz9Eg;j>Wmk=u9Ui7N5W zU?#A=t?X$Ck%g!$Ak4l-_%*!}HMg_D_LiFfYCigDjL$rlgiYYr)7L+j!!i`B%*#5PLuj*5#0Nz z8Ok(6)zIi1o$HqW{1ZA3cpvz3!vUO0f~t#6UVWX7h4T`={9|J?F}pK9i|(zr2z$`0 zy%Bf?T_W9=t%=}SuYUYZ;@mxA#OhAaEyF9}1-Y%ef&}zB6pfrNm=|R-mM_%7mgqX4 zF@2@bS+>6J4l*Fu)aSnm}e|;== zQMV6KnZG{JC&wuD&8J?atV+e|vTW@q!8{4iQRd_wN0pK$^ z(JOO&!F9knMQ5}=Pp{O;%`HoxpZMw1oo+dC35l$`Z|t_(GBY#j2jrgLee+t|$h&03 z6`BArWW+(zduzVIm`%Ccrms9RLT*RLye*}3V`C%Ou}&gLLa}DK{*tYZ&+`G_-EG?N z(G0y(n=89xVdDMYB7By(T4Qbsxzj*6Z9F`5@u=M43eVLi#e(#Ny?viUy}^E)`(pPa z=m;d`5nU$|#N6A8X~onn6v)Fx-l5!iOO6RLJY{;M?l7C#0SmeqC($rC4vDQVRGQ&c zuXA=zW!U;dqOen|m0xOcp0}U`G7LLyVvs0ZU!0s#h00xe5$jNvJK0?zZonGYh|vP^ z!wO&;_Zl!2gG#sgTC?2YW0cu^WXt_~Eb;;Z%UcqXHI;8GP7}PTEGItS(X*jQxinja zzYKnMPgHSB<}aNVPU~^oNF4T+3jRD%b*&cTk}4vX_Wbox__M_2G>e!ex2A_OXksLM zyx(#tlH5qRnFD@RKpyyosuD|W~d)PHh;tPly9 z`2M|}LI}$5^I5-YfT+Kzp`9wD)HVD`Js@2TY?B9Ew{`6G#xFjW8Cg}nO^or;`=vO0 z?;GDX3!BKfoXvI?H1ZSrjWBKFWu%^rS-o=gZyt^mkR&>hfDO>HKf00%RY4x?HM`P( zoB)DQ?%{%$&VN2Q^~EWBBERZ*%eclL01%95_p-NbUmwX!riE|OczfpXV*31wUx(K@<}sC?R>rI7BYq74JRhsZ9i_x0`(+T1 zek+-v0HBvX&de`wojG7+ApOMsQuS3ta;lpm;4ABNW+f&F6%@$72?!pfz=SQEqKh$_ zv&e*T*S%!4Juh`@x5 z8VgaK0wq!pQ~1r!9TpeV13w+jg9(t2_mE*(y{fqNbpc=Kx9>lS5+)vvYX2U2JQ2+e zavfZJp_~{+40VHl8As*m7Yl5nX3@Q6h_49(SP~!43~F7Gse8d^iHlr~FO$3BG0GU3n2fgAs0?)a#Psa! zZiF%0aY*f_gADZZCjjU3DpI-)tCL2%x}~-QT|GUzUlge+=X|>y5T)c4iM)gCL&uZ& z6`uGtyPz6<@AJK$zMp3|BW3KjH=NI&JJ)0AyF2LZz1|sjg!N?!$RQf3-a7)6e3GIX zapJ@Ylzu8(^JHRyFNTY#5IxRjc0Yn_W7;J9oYTWc%zBMUQxa{z+wfUR za*Z3Nsp-toE~%)vG&x2qN?c68e=SKu&dp%jds1(}a--rN8XY0Kvo;(Veodm(rmr33 zx9GMpF)68Rw(Y-)!BR%A05`pPQ2*WbIumg&$F3*U2#_h1at(L37QL>&VR!erN7jjb zqS>40XH_P=@_vnw?j=i-`wPyu0iLQD@!^!_iK2_n9$PosX4(W$QCZyXZ`<2!CZewl z_v$>*>jc=fr8kKTU05cz&{2w+wuYT<3tjyn@9SxJ%G-@I2r=pf z%P=F}H_xG$c+9NzGBv&r4RIPrDC&%lrF2@wjDnO^>!zT@*suudrrX&<2WiTbGwrC~ z@7fz_4jVl7kz|L;KbnY6BtXoAx}`+B`qxU^O)0tg@UAYog+EpPrU)Y!4ozNY=O&wO z!IV{yP*_tN4xa1QG*cO2DZ}G@@jmm@=g_;zWU3p;R|;YP9WRO71b8zA4_|%zVxw$O ze2CQ50;*-v520Wp6R-X+;l>ByXdwRdakwUni4Kr4_`f-u8&10HA>-e__8&rsLvP=< z1#3e)TTu$BJ8!m07?-Ui1;$J_IKRDO1+=rK#^22E+t-cq_o#H?E_S+{wHFrHuBMT< z`9{_KPLe`KBE!;G`N>(J!pQK4sxlXL)Ym`H?u370pxjjmOye3OE(^lW4(fI;W_8JJ zVF}daMz39hLP=Q}X*q0}zO9r@!r)!!vAtR=B}2vSwpN?hOp848lk=yn%s^S&n#7M> zuwl_;nvd>Vx4y_M|1#09X&P}!fS?Y9laWRD=E=C&SWb~Ugv5turX8iwRwcUE)0hOH zXyE=yXs=Mly{$d!6v#uYVryA4ec4Lo}#OKIky$Cw|DDFPta*uKn$joWv+F zMB>h!vZ{ln;Zap5XMKOrcNmX@QY9}pZvtd^MX2$&`Dg=LrZKlqTibtJdZH6IqopE3 z)1<;cc*}OpI@4viXQmp+FcL|w>c%MwjDdT>`43pVN_()gm+LI+cC|Y7KAZH@Ltr7a zNrGII9gy1{5jZM~w__$hpCYK2=<=GI{ZC%H!lvD>wIV5$l4GD$Qto23yXGSi^(}NU zJsAi8>vnj7*GD|Xw-T~Udu_$vU~(9r-KpBC#e9F+Wr5Z5O=VA+NOCtx>DYFC2(nm9 zOX$M7m);orJcFN(aru6%%$WUVwrbVw4 ze}Oqfed7A#aBGnNu5@ekhRn%@R6Z0Gd zg2acDt8A=l$4-l6ICyNa50f%b$u#(jp!S!$gHB(tlDb$K^*qL>7PB*H%A#31K%sA( zjqq2Tv3s-xa%T?^)}TP@q`NUqCbaBK^n41ID@_RaQ`|lamUX28ZK3w9FK^;kMKk6r6UC0N#NRe>Ubn&AL$aMF}Z9sUa!Vu6{q5OZ#70+Ke% zmvFvc1D6|_q=Jb$KUeWW;M*X6@TQkE0-4pRgxo_&m`@9qbTRfuhQ~z=bD0pLwceSj znleDIquxCFM^lF9gUkR}>00={TnyocQX;hhmS)m}^^`hAYzh5AN{;bCQ9d0bV}>(9 zm|a9O&&bJ0@oIHxNz*XLOEK~nq-EL=)uCt}%w_G32UkSqv38Ybh%J=Q^*{LB4CEUu zJ4hdpS3qjDz!(<@zsR=vOj5AX-uP*3Hh>J{+tjt!9XCI&a>wi3)DQ{eUOiT$3L!=e zF^%J|1-7}ldE@u9^Wg$HSh%jfzKlIHo(phY9I<9_X;oGL=nivd4t7duZ>Q>0eHYu7 zzlvA=bXo`EvaHbtm(|Ag%Js3Jg~@LJWCd*Ql&6I`Z#sJSw~TXBI0mtg+Rg)9@SKn1 zW7S)M!-dSDkBUP`xjwSWP{U1_v@Px8lMP$(XHa4HUaVvxj)obg6D+8IKRX^hA%5PMa8yp-= zXm(v)Dc*L{E1m5-H<*x4%-P3&K#~knF|EqO0+VML74-PK>9x1%FEBQTpTBiv}N8(gEMB@>dR6u z356+HT5qQhmw1JBs{p+#rVH2ff&!Lm-sQVu8f9U`-pgp-y&4KGq=|65qW-n5 z&C0?e*a9ojWy$$+VC?hOme-zq=CynLW2JCMGYL!#f?|KQkDPOCARdZGL7IyaRltH0 z2@m>h$-};`x^?0=7gpw*Wcff%&4Et1o6SB1du9aHteD5K3R=SA6; zwl+5OvVBoa-mivxUI8VPJ(sEsA%Vc7-IoU;0Rey{B>=H5S#9qG;(>8XaV3jkQD<$OOuyoCMC40(I4O0(~4a9XG z=)vlN6wK&X?2vG?vo%4s6n{ZIkQwze5Us#8;v}8(OX=-d(z|!FR@GJQ3}$r?e#}P? zQlwJ{{c+H|bH0R@>_gwjk^Dz)rUA_oV2;yvieMPciAR?47;N|W*ar=gsJujy-n=m* z1_1Rb#lxMD1Kgv%)}p6lqQ_FvYNJ>AE`sr~1kVF>vM>{UdeT)DiVQn4f|4sL@ixNK z35CH!0blP$VEL?a)YPLd&SRO##H0?(l6PrWoLVi)JGQneZF=8-pZ69Hqrp33&2yLk z8PjJ^Q3h(3stgr3^Z@s6JAecQl0-1W5;$V}u&kPMpkDqJ6;4nw+jM-_t(UiIH6}Dv z*>1ZBd$c>094SQJ4pKal2#EO$H+TyPqeac(Z!Shj$A3q^CK?Rbg1TMxvdT$u_2k61 zTl3fjaOkJ*94s~RAFxzBcZ&rEHN>DEcm;)Q2O8Ct&)39z>(MqqGry4*(nN_UwE)W1 z8CjkN@>oP+aq%Cf4{J|@F@qun9hR<~k%^nj4o9Iw&9H1MvG|q=bHH=E->}u(lcB0* zI$Yca054q8HMK+sx@8=kW-vODgt6&JwYCIk)#IVxD4B*IDs12HQh%1ES?w{%=|;(z zfkgRgsNK>sGVax7`WrFI@_4UP306pb;X^M#uWCA8XEN@DO>1ENqMsYw9Y^$g#c^;= z{SXK$cAqpU>n0=vSN1hU+tWZ&t;IA_mIygmB4moP#Pav5 ziI$m$1wpLpA3(ASsVP_ixs=<&dYcRMtv6g`)b+2dKk_Dv zLNvE%vOqgjhkWr4Q2b({$)6%Du%M1y_v&BpAgE_5=EV4Djh&juR)Tni9^PC(7s{|{ z8l((9?R*`>)!*MgE1?oCd2(@Z_+a!OZo4afLg0^1uIJ&D-!v6i(a01G=EJ z!UshQWbMs;_%)!g$o*nlc>__3=SC$u44EUG-6!sww<0FB-3`I5m7$#XDooxs(}?af z47o8L;p?z9o0zDWYEOJMvGaKoWM$iOHQxC^`{XDF176M0Ms> zv`mx@IFj&gV2%J(w)GhkD4*`$KDb7HuPMwDK%3uf{VJ~q^z`&Ro0Flj7U%-~G2?wShXJ?>OvHdvvF>OK#d#@m|y$AnZ}# z%Il0Ak?GS1<;?bZ8qr6((MHf0_TfL09aYnn2`=~4Ov>E=p+0JI9K*%M<*~5@I}F34 z@(8Mr=u8ddSX*+bK6%x2J9uZwO)?;zMzIvC$3k^uC@bNYZA1o4f=uxqOw98 z9lj07j z>Z@iXGUe{~$lExxV`4&QdR6+%Wr-vVo6mw?^Dn);Nf9?FvyS|kz7y9~(`jPa_!zc* z&c`dn=;zhIL`=%pz){F393I8{Ytb|S)THW*VXnOjSak!k`JCfKGy{N=C(FI%2IFxZ zcFJ!fh%FdmZ*P@)>6>7v;QI&U?wM`juqI!h=P31fikLI?)BV(LF+D22EO>nFT=0b< z*vDgsGz2FCKzbVR>&+?7Yz_5|`jKa};aRtQP|3o_OUm2A6JvZfmt)?A3pEaQ{MYVI zCZHZrcIm4yN)RC?{E#Ka7vw>&h!_4LS=^g`ggt|e!#VkA0|_2dUJM>IJ5CP4Uf(+$ zREY%)nkQ(T?Kz5rPgrf7@d1Gya0MMNd20-`Uhy3cESmVwutwSE8-Jq)#``~e=G$1E zOCKtqX`(iL#r-E42KqHT^-WbDtP*=u$l)c|XxJW}`5vGuduET4ut(L8y2z^fq^AXslZq}(j2C?#eJ#NL(2 zUSna2Rwf$lc-Yvz&VTy!uL97WlksWHXy%>=F1coAW?E_ zZ8&q$6c|L3vvk!s7dDyf@B@Qb=?F!oi`T))9X-4mb97L~NJAGgfqVQ@dJw>A^4gC# z3W|9JFDwy^9UZXG=?$|dHr$e*l(f$_(u=7XDYN7N1!!r}XlH0`fYQsz`)RA!pWher z59;Zi=wtLiju4=kkLJk2Wp{FO!g>lHY8=0U5|e$$(552_1DUAc0TrfpzljR@sDi-W zE^n!lY%YdHoH?ufsO+9uQJ(FkOx%R(U{KS_*irA6lH~|cJzVbJnW-5iCUq^9 zF=`=z1q5$&018j#Y)UDZ^o0aVmNa;K=0!$2PB~;(SuRJg=`wEncg27Tz!74$Bz{N94#%<-ZECj(U|naC&t)lI6RV(lNSSS zhfE`2JBXzDZ)(1{EWb6r7-cEnnaYs_S%O+gL9&>)4b>I({oXoZeBtTTTCm(^Vb?71 zRNbmZ%jM;oI*l2Q)|$DH9t#dh{E$>?HqN6adY>|g;Db_d8=5ILC zb=#%a`3WPj(_3pW`X@yo_#+VpM?quyq^eSP7cRat){GQV?B!i*`TBJnbYrA<%rD1l zuap_f$_+80{Kd@Ov;K3x~6TykBD9Ztu#xFabUc9(wpZbli zA@a*tKuT3qRLY&k@qqIV&Z|=a4)guOs$Ekku2s4ggS&N@y4lOYu0Jv9i7wsJA&+(a zzHQ*`-PZYQQ)ca?IP)cUy<O@OMBr-x?ihs)iOdzC<^*qe4#f&x0Tv73spG^mpu`+JY)W)*{JSWak0a8m93J}Z zO0ezUKNiDgsU)qN8o}`Rqp6@n@*%7D%VbYMfugM2g0lGjcJEc~<{w%Gl|j+`J4ZcF zi~KcF+*>AXg@+?e7%?wV5ie!N3oAr3%^LK!xyo@%CJ8&zf9Dw~^9XjMDLkaxkXleR z(y~@q07&`${T@NhnH?~+2a(Xuhbw8Qh-$_}F;BxEd#*+&HgJWEGmU`rjNvn^h&zC) z-ciTUu+sYzJwvu2$13`L>7=xhzi}{{IqHip zSIS*(&>G*9+acp1xPU^B>3=Z<${Qa97IYm{0n_?CEqzNj@5G``-ql-Fpi`Jk!q|hO z<}sFf0UZvoPXdYVEq&Z-J(B5wl4eYM#zx;(<4m%Q4tUZb0AlJ)*TUf-Af33`u6%v) z%L0>Ql@oxug42^Q8+^J2$yAQ_4TqdyXcLTU{-_yYBPdQFtI|iPi z0+}`HZn28eqRPguzE=4>DK8WFaZeVX*R85>jo9&56WuS;As@jWIz0z_c!`oDqgE%2 zT{yD~UzYN~oXLa?z_cIV$zR&sH!_a7C35eY+yZW@KenOtrZO?nFpLeey2`ij_{2^d z4JRTU6y{~ms7xM&9X(_1pz|ESRa(By_6uraG*)ym^FQoQQ%|=xUSqYw@>tNs>(yfB z7!RQjA^=)CJ%kRig zwf*0l;1@@ec@)a{I^6=Z&x{+2Nv%B2YDUr_!xuG~5<8lri~_x{z1fSH5#?%1!~I=% z=bjz9XnI(Mj%arc&Jld6Pc?nv(FDV%Xld1SO9hFMf();*pByRv=C6bgj)`3ffmISA zsI7C|u-cefS{@aRyfME1!eF|4*R-NlpwY!ecw_1OJdjv>K`@47C2?M_Aw{LJ;EQwm zm>MQY7z8F+s6R-s71Yb=oJlk&jjBZ!DEbZGA$UP*6cB-;_6h%oHkm37C&(66^(Udu ze#lPlJL$1AWaLXT1KXrZl1{BQH7lgd&BLhg+ zpQE~#p=yDAQ@Ct>e(4jg$zCU>T0aBpPolW3i_7ad)o=7)DsRgKUj6UD@Ic73@35qZ zN^q+UsoDhDRUj>eSRrCY?Xth`ckU#AO$HMyzr$rhK2J{Fq&R_q@ARdwtOcD5!c6wL zO_wems!m0}Y86LhAHVhr?^GE(JJVNz2d3$AWSuK3~7g#Qh4HP%a{R zEe1v0)P8jAr#3ffcwg+F39ooxdt6KRiZq5W!~y5f ztcVH*;zw|d9jNcty;AJpCn~AOwh%Hg4*%_9XJD7Ef_E7gqM-=yDPEBN~_MgwjCArnIsbcr0-}_Mi9lZ<8!cO)o->0>tt0h1)1y z9Ub-`FJ4~D7v@P(=J*eE+0*V83tBfBnYU$ls-;3v?j>NbEO~71xYgs*{I<)}wL){j ziCJhwp}jAfHb-1;WIRQh&tJ&g_2EcSKE?G)_)ud7#5_>rDURk% znb-Q;t5>fk@SFEwS9Qp)#e{+aSEXMSDsQgbW8j3>kRH1XM)z&xT-(M=lR)jP;b#9r z$T>UtArD;rTrX_T3lPoVgW&n;d*O_@O)vG3-EWana>G{W9~_Y`{K=kK44hOiSK8f3 za6+xA(za!U2n$S~%4UKrl7+RL;S1nhH6dAh6?w_>bo-x!=N^RS=^9v3)=60;w4_9< ze%^_tQJ$yisi$#}tqtKm^CYJv5zm!7D?3CwZgOMa8w`OsftIdMQQ}P=IFy1<|dLf}Lfl|#d(FcCy9k1~SXNE`qTN2?d_H<1hNb##M%AQ4@3589~*)&a=9( z@OBJ}N_g)c_8~+8^ys)t^hf?u-OYBJpWJo;_nCQ;J-v8{Zf9O30cg-1|0TfN61c2y z!CGX3R<{-q1~Q9-Fy0>|&zh!2O=v7EURcX!4(U21$E{qp=YJ zF`YZ^Sw;|;0fZ3vEr8|0Xa{yr!ps=>4Ehtc-;FrmsXd;t059~VoHiup-#t-AFsH_{~xS?K<^-^ zq(O0S)I(H5Dh@_x{Ky-3w6c56kGydY-nI0T;tN0R(5J8Kd?}lG5Zlpz8VJIQ6|*t+ ztq*`>A1G8)@T6f+-dp9{J75FZ|F?ma`;AtAZh{&W$Mj%yAz^m?MPDtb)lpE!!RR7N zVvUUpVm>3tSnr#RI9}g|ki5!~780j5tDR%lG}&mLOQ&{H{8Lh=sPqsCci3}*_^olJ z)l4N8fk{KHHVmI*kh-95eS~n{M4h+VxV*Jj7=q@SjIw2e+kE5;W}-*1WQ7ScGpGt3RH~pOsjTQ(~;QCO$7Ea z#RgPzxkiA%+U54woyBGUR;91aAWsrkm5?!_L;3XC0u?SX{!BXKR|k&zt7a z2%sP%FfdSOdnh$naEF4{ANXhZ=;IX_)$*>kFo!OpX~slarM^2o@k$LQdLa(9HwXm0 z#fdo+Ct%c7TN^Oq436mpnV>^9e^(y+eI{kmx}8;>2SzEsQ&%bX5wL7^@X9CH+dB*< zLifht2l(c6Q?XX)L)hO&G$n+Gy|1P$`~c27?kfc&zkd9A0hdEy>7J^l?^~2}v~t7(F^`cE9l+9cc{r)a#F@3+VA9;# z=uREhYnK~zi7p;WG!Td(i2nRT$Qe6AQ2U@yR+Qkewnk1~>Z5#2SQg1d7;m)G@foaPN{dL3yM2T`@yaYfNI%>tE6 ziOkb8RP#FX5dhW`c)UmSD=NeN@vJ1~v4}sr9cdX8H>7tAbuTy5=cK@>H6;Mt~}Ut z%SpL`Z-0Gn2?YDm+n^vqn9PMCX8e?A0cfcXWPGs3SAtUbv7$}x*n+(k1|I8mp0?`%!1z`Jn|*)EJHze78A{8q`2Bk(<*evfO*5Z-MChdoJHU(A9av+V%?zr2`pBFA z1VJ&*myVUMvnp?vF&1~!VGeospol-r@j6f0c|uFee6;-lm_qw=T(-!e9zr$QQF&Ja zs9i-K1{;<Su~GSib>PHSMB!uEgC{g?hvVdk~#~LaTdI$+DCuA{PACXzsP$9h)hi} ztZPY3*WkqrAWr_F;D-5MEY;LisHH0zev2pInj!AiD{mr`C`_uDO&r51?d= zLeXjtEr~Hc3i{B}MGl*%y2Mb&FJMT9I=d!X)7v9;*|Md*UWOT_Nk+yh2pO~En8U7w z-){ee{PFY0XEk-=qu*pN29582Ow~#RbR|$uO=;H+TRnZwm(oP2&ln zj~Ze@#b?53kWHJ6opw#2vn3`XlI|rt`|DA_x_AnK@AM4r`Nur;P4qHQa~vZ{)Q;Oj|`wCs^QB}F9f_t*u^NMe~<%b0`0_x7&Jttv-GG=>LjuL{b34TJBrss?m9h=K;S=tZmtFEwDGC4MrHA6(@lOZ0gp*!1 zzT^@*-uJm54J4c!fL+324HF#%>M~QezjRg`Rj~vBm1Vv6n_UjQ0Kt^Ww9Wn?YLJvP zOo;<)JZcA;;h*``&t8WA>656z=r?4)?D?&b=Hh?L$|QkZw|P!YxofOm=zP=$}^B6q7*6NeA0C#Ty{xC1S4I z5UPvmZyW%K#*{y!K&Evz>eb6|j0EG@-}<%dKdI!ylB#^eB*43Rg^guF|H@)7n{q~y zTN94JeMqI(8ey+`wzn(r4C4=*a>;H@TSXu?zUAJB*IrFa@OF%~z#K8|>40`EB^Q_1 zgGiqMMjZ=Z-&8yJr%D_JHo~KPw(#$mYAf5(3*Z@v?!EYc?vhT1Y!_Kub;GhBI16lE zAS+tPY`-*RX9Dl5k%a&(%Rv;#p>I<`y3#JImjIoq{GGDI$eSYbS2uaCfJZbsWZu2| zW!!`1naiTg zR}Rf+qnu(Y+%)x#|3J%cSC8&%j1c$=^sT-!I6o7kIwiLHK%9UY>*U zT(sH<2ULt3C=D|)!AQpXh^~xL#R!5Q6R0h)4rO89HTpj&)n4-b9^pN75_Fn577p{6F>VZ;qUY6YCqtkjkclW}})iW>o@5 z;gBacLMe99PvDGIKzLa=-`LBLoGDWPbvB0CcC$J=HLd0PV!3ZU@TU9ohJ!m#D-$_S zEs$3GRWv!{10h*eT3G9z?tZzZ`n8s$x(=4144!%p43YMq_a{rch9A;i)=O*sZQQVu zPtoyl0Ec!!`uMG6Td-)hZgPkCJc2X(qQI8q2>|O>PwvB$&;4VM%s6}ApndUT1?V75 zIFIKrf|f=TcxCpp|9iRsn}xIUa_tBLJFY>({zKeVYCPk!HG1{v%QUv4;?Hia^`h{` zjrEcQVamhv-E+cqpb=f3z;L0sSj}-!CdEW-U&ip0JK#}B5=bzW;l!3zB*5Vr-9YrM zTVJa=|BjDO6*>$nLOVa*sVDDk7a($!D^Z(JH6sy-N%h(Y9&V#k=K*@rjqBGh7Z|H7 zvWUrL*z-IXcD!jK)LJkHG$}lujnm@-I$nG6(0u0hS*L+F_+is?Hn0~yr?MacZ#0*< z-7m?y!^92m``*my@Bc@8FW~@8jyv(TAZuSN0#zb6Ey|ggXxB9LU^{+dSqhYSSU4ln zQuk$StPaN$i^L4B5}#H8VKsC_XP@WXzR$~noB2RI{`~>)rk+P61)n<1=;qbeN56%m zYKYemXv1djE2qz#3oE`t!DJoPM5zSP&R^1LRs9^xE9Wd0$4!0&F_e24^!#Xf;wmu3 z6)aFtLsHoLp#&!R`z=wtZoZOZ2zd1%74-*FtDI93+1~63`nT~o_;LHwBs`Ow3&Ve4 z@KJ9sEphw9#J56$f$2~6CYr@-yWmuoUo^GDR|8$(1V)B)#E^?&NZ?E4AQNP2i%D^l z>mHs#;R3%3kf*Cm`JtfDtZA0S#uu&IIZ)l1zo z$$rQ@W}4LcA;T+NzX5YtK+MHz3NCwXKjnt1mVBCZQ}$rKf6K`CbgpWchy*6TgnB_|?~gire)2ba`bB{Zpu<`dfhgAI33^Z6 z@C5uTsS=PHsz5WFvHtjR%tvmY5AqR0uru>DWf9qWTF@|qtUt?387>4icjjwUP~N~WG1o!& z;jq!RXpCwX)6<{wdeevpeJ38+8hGkOjkO{twm0MiC{8hF>liU_R%Ot*5dRcCSogxf zdY0f=^WX!&^*?kdXTFxbc=6aWtc!^*d7w_$-Q6+%{!&C4_^A^UJDF?8W$o!3EU@-8 zbm&?j`R_~MeIi}+NX}O@wulXmkKj6|LKFf;jD zvn4$4*R>pd{>k6J%eXDfUD3ZPD)1iM%YXZ~Jw4jzw&&)WgZRT)UD`#hvkSy|k@@Mc zd%8pv*xXBTJ5%`QCr&2vpO;D!=1L1WQT-W~)9{wQ^EYqP&_cpHU2^Ha|GqviyY_KG zs(=gr3|fC(K;W0`&7O;YTtni3XOU)6zj15CXlKOuK%F~;9jDit;PLKA>g!<`Eaix1 z4hgLlm7-gR4jaTgnnQH_DX5<#&9?=haV%U-Qm!+M230bdci&`v|K1z?D_1KgyUVia zafE-|J+ehob8=;#v15_Dux6fCQROtSvy#n_5pOBWNrqv7rvS512MNeHtiCAx1x&vqwC*mtwk z*YnFkD)n30Po>lZ{|gE-JXCD=oiE9iBy5<9jR&tavgHwOAp_7#`D{CL)!*x0_&#>; zd!`t%)M(D8g5TIY**PG`j+B!4^7r>g*_rotGk3{mnPi^kU%K0JeILT#rZGG^dsaD< z{B?jA2~2NzsSv`MMD)cEQW-iA)lyxjYDf(cY?H0Y(j1px-r~%Ds0n8rSzP}J-YDdC zy+_WU7N}t;5zGU=j=uiX?og%Yud+Su&ysq*QZgQjOMFol+dh{sSAKi(%v``%i`mS>qa$iOCNxzp`rP^RPIhZ| zgMv<~tr|0`E-x)zi)#EkH+TQ!$**#cWa3n>riTh^j7~Oue{=49#LgpeXZZie)K`Z^ z-92v;52%132+|-SsdTqWO9;CQ3J6Gdm$V|OfHX)-ExQOvtb~NLv^3HkOLxP2FuuQc z|Ma@l^Eqeco_p?@Gbd(6LtQ=HlTXsqaZB&oHSP#sk(TT5>f6It?%eM6SB=ZQ$_~5* zhQ?*39p7;^+}Xq9o0BNTgO7vW1g6g+?J_EZl@)54(GB>wL&0FAs~?pJ4x~rhZuM7V zzSc~loSs(L4hkkEiFW~Eog?OA11DU~Qp z)9*5a58VrPb97?t=VHI9?Iv`87J$qtJLKHwyghv0#cDa$?ZB<95`{4DQGKn&l66t* zn@S~?^LowS)5|MPL;l*eYomT&i&7`R&0fEpi5dk}g^B+D{3r+j)Jls?!sfWteoY$Sb<2%+yo!4E)b*G3LQ$G?__1!UA zcp=Vt)|Wk4#)=U2X7t3G?E#(gi$n1j+vk33=!^ba8kMdyH0GYI z#0xEhDSx#{1L(^&n61qN>l{zrp0rJ6fVMkS^x{R^#Y(g^G#20njoYEygY-s3J%oyu zQZkJNr9CB1tiHd0z%Kl;AN;9j)h<+bOxJUJHZVIY&w73!L_SCzp+7a$9y2yNDXN1X zyG}2bRLiZwh_yFe~2PWCfZT}3AiMlRLM#Djo z%-%j7To%zJ(*Qx?cPHiK#1i6@V;o+>-rBFUp`lImfT4bo%30t+x~+wm`*VPKYX51s zm~gJlyW|%XsM69Y_Mjz4r&fFGXCeklIai)0Cnt*uI>;xfXj!j5(V6n_FnVC%=U3Mv z-xAwphT3;|qC3`=?|gb1IRs4S006=gdUJEQbg4(J34;9#Gdw&3Q4ZIp)}My2L0WVbexBHKXLpz9xefKZ6lZ&pr3IpaFt>pIl5t;;FqsQJS5!WbG6R{n69Y zQ$S1tIrHhIOKVokc)YFin(n=|FFVW_k^SS^Ov}v=_kxPwBJ`EhRroa+hxMDgCOB4xz%OV ztl2OA0NiQ_N2j1q!GFAg9BWI7EK1iApafz&P+nG+4LSx}S4^A!-b9W1{06bKs?g7M zJ$KyteP-vw*m-->1+CawcISD4GvQ060PPD-TB+kKp^I|s)&$`oby;&7IDdfAv?x7 zA6YC2O}u4IKl{ZbLd8t1e(P75VFiJFK-PSTs8KHk#q_o(j~;H6;(yoy-dyV6>F>se z5UaNo-^cg2altB!kVJBLjo9@qH6_Z{3t#lVX_Wz_l>BXa7jYwGjSu~|ZF z*vt>>q8cFqh0qnnx&!2)w>)E18hyXEI;(cxo+moo=D zpsB8h3K7!>7asL2}-#t2j0Z{_Rz9yf3vS4`O1*xVm$Fs<0~I`^7IJk8sxa-rn< zTK=`z2ESim``Ekbwxi|>j6mGqmh!XRBqPa-mXaN^x^&+#IH?*cp#gzD5zMr5VTbFN z@xGsdBIF}7R$G@dwLd<0a6%Kit?PfH8ZyvT>)U(+{dwk?6bAqM{n_@%QoGz+H0R8V zpZHJTAX3xMh`&F@fz(Kd6(z7-w5HG8>?z*vIV?1y74Wtq$AL2PS)^18!Jb&k;+#8Y z8{Dx*l$Uv*;i&%}Ujcs_OVq3cJg&+zu?BIV7ultilJ4RDf5?+97Ghfb_YwagYy z-^SnLv|c~L246JWCi2ymf0mv>;LfPK4ZZ(Milb_&7Wvk#Q{~OpmanBp@^>XDn-(~# z35|-`#>S#1tZnTIc+u$$)8g~X9?GqIsPqOz%bu<*%+?k8QP~=*U8slY(7B_|ElACx zXd8ZCLzFj#!>Sbz=168i5z)9t9&k(Jp>fBn|NH(T(#SdNAeKa`c{b$a=U|eH}?E;|D6Y;8ed$~ zS6hNcLuQ_ak!6Y`l^_cVWv+DWJWBOflKO9$9(qgBgZ3yWi@a3A_f^{FCE9z*6EB&Z zf<26Gc62*iEV9MSBuy02)2H8!bBXHkxE?e&*On11RuV^OESx-bewn9Z@5k2MZ7-C$u=`$AdS zINEYLvUXnT-@3<7Cee~dw`)Al)POmn%e;X@|h+-dGogVXV_Vq za^yO{9;MCBDOP@QF>4(cFstu&hNwzd#e~{_T4K3H=cH=1DvbIfnf;**u+n_UAR87E zDE_-v4}|0xqmU2dVwjL-+IdzrTw%o>0|TUBl4Hb~Z?LN6$WV_o{X(4qdm0JxpPvGH z$q-2)H>eZ(=3E16c?%~sJQE$LUL&zs`23ti{WTT`@rpWXC^xg1qUdZoZbK?VD4$d# z?xJ+evj!N{FAu9G>H5wAN|o}2!7ieZX8QGSYA=(}G{@fYgI$M8%);$<#;*}uj*seZ z70bQ{d%;Fw#LQFTm11D|Vd3zYlA4k!p@;ZM(~rfHXYsHQfk){DhN%4Pg)xGzKT(!A;a=VDE~95|55 zf`+ib{x^s|86<^59DVvQA}()d3-QZ%16NhL8Is|zEPJ9*fMWL-o~j*k2e|4XanX9Y z))nQe_B@$mP!9|Ol@e;5Ns25ky*)E?;$>3Oc3w`YGrhIfs<>uTQso%n!cx2`2D#0e zm@1{<#Hw~b%Ea4-rmn}}Jnd%IE$FWgU1q<=C!02RZ&TqH$BZ&iy(_8o0aKo6KZ-TF z9FgkwnraQ(e<*i4E$p|Efc1PzdXxg;{K8>S^oF$+8=Y9&{ZwR7RP9-o)i4?=h$m{5 zPxg~EQkJG=sc2|-XVkg~CXri6&x8b{ywdzGj>8gQr&6o0R&o;D67n+Y8dD$gUT27# zW&dj$E0j~_7dZY*0SGGvGz>4BDm+U^bg^)&GKl`*DZ1PPkMwD1$nMRPQRsu3ki3*K zU=B$h?F)QKA4Tdr=PiZGH@7X;CwvqRFyB7L@9g$|Kd<(7Fg!WCueZdSLM2e0N8B}D zmhTaBRd|m%$yVUu#2tUjj~#&&zBHuFN51sbA?(hAW3 znMQWL6%IsP`k2YT5C;-Bl$CKyF^(Ql{#EOGcA-?X5pE~pBjoLEXr=> zuzx|S&Oq&5oWs$e6@rW@POUG>1x2PEfIP1zaC)m{9f*iKf=@9bXM4^&xa-EF#<)N$ z{K?4*YtE{nn&-`-%>NM+u|f|T`k#XUK@=({0%edM%*t$}4Lk?6h`r_BnEkxNNv|g} z5c-wjKgLozpqqR$eNgZkU>GG`q@RH-?4(Ca#NM|3`?}Md(v&Qe=7Y?TR(nxpsW8g{GAACXiBor)5?i@FW#hETtk!YIoeW9J8 zRui0E_I_D|l=#BY0(&a?g(|*6c_xSSt4+++Onqt)O}v=WHtkRB>Ln~U^2oBMvTpZC<_y~SReCzQDa zMXgwKYPX-YpMAOKEP;cUC!2j(CNx;#CJR-2k<9U*TyPRzI@@u|wa67F`vv+UHM01m z*|wViD2#p`Ppn2nsPKxr5;i&%e?7+RJ!(WA3X)vs7j%q{lA#!Dk7;8m=H2?pRG}(d zsrRv9nGX!}_`*SxqdmV%$3UZ#N1={cF+uq#ivjDxaYw7rLHcW8D}muheWyx-5h zJ5z?ro><*j&QKoC3tI4UkQ5uyCxS<+cr(T~0$$zYOY1*v?uSjFIB~=o?RRD^=?mDS z3fSO}J0W;f;(a}@tRdVaK8asxxs$$kOsvB>U(nLbTyUgafLQ}&(me25FzYp)` z5#tLS<`3)GitgC_5)*Ojoit-o7*s;ONYB9}Xr+zc#M#o#ZD)Q*-6-GUOiaJ$x^Y%8 z#SN8N-gAnehg|6laS!xDf(Z#)w2RH17hYltljSqhEK%OPm>Rax6 z$gsA;@Zc#$wARoX0ywEE%I@diC-aF*8=vjCeOUH1no4`FN z6p|&>4EbwyCF;jjkmDugEY{7w;TzsNn{zj~B`)5p+F4Wj4-DE1mSsW+vX$r9etO0V z}-g@?btrp{i)T#k4@>8R1H2 zz}Ip8ZN)klvr^mgU#bOk{llE$bVSRs`y7Fg^M$+C(1{2*sS0ZNF3n@@Rl$)i3t8g9 z+c_P2je9=gasBamr0Su67#%^PSp%Fk-TLg{Fp$1wQutc_gC!_lHb;R1CSGZuXT?pK<(`QD^|CZ=Jj>fR43U=wIHOu%^Ff;QuX+#nm?Q0dVZ%@Uz$c? zd5_nprtgO*OgKKDRBgZ9Y$&gaQjPs1y4v@>A5wBrzgGWb`_&pVypaB8meBz2my(jc z(kXSaf9n!ae02o9*nZdu*Mhxhf8A;=%5%9DeAF$`@kv8CiT)C^ep&tXXzMC_M6{cO zmBfP2!Riqh?3iK21FP!1bArylTI!q?Z9g1^2;dCQJCmZIF5UhZNYP@pm6@o8^0KwM zB?7QRKaW%!hL=xB0%K31q6z=3;VPCECd+7JW3#uXdhv3AXj`2-a>aV!?q^RFWaWgI zpyzNMTBDcsKY;1O-5*Lb^g9{|UtYP(5l9bj(K8XI<9l@}&Fh24nuMe?3d}NkEwO&C z+xDA1ZIb>jad6+dg;GE0JiT$mnbK=c{g_t6($=a@1(&XnaML<7t?vs`0*OV12R8a4(szbiZ1rLwFp!xd$L3fcPUR*d8)mtjLXMt)iA<9gwk%$n!G!1)64qCBS1} zoK`;lhn$a#`di2MW7NI3(~Z(jy)Zhv>6s*Sj^q_e^G)o}$#gf#8RHa9-W^RHOJn?) z@(s_wMAL6fw){xAxOMr9obB(4YTw6G zx)d|E968om<962TW^c(ub&^NzpGK~%2FVX2Sz20)ckZlGub$dHo*9__VOC zliIQLHkWQZTGPl>vOe@oCfeMdR`7eY*pj}f8_7Y(9ba|K(I$O?@;UtEuUv%yowVQH zAT+P6XaZfJx{_FXAm&J5mdjbU5UqTQe|et>5p*}RZxm|U=&fP^Cu>B8Zadyt#P?I9 z#=jFm64`7lo23D!Nq2x&h@-88;2Q6|K1_q7X71_TlPyoq&zFLq3^K{tmrc){7uw^( zIG;r+zD+RjtzY>r z8mMu5EePg*l7t?UkL=Nn)@%gx=6~AC(ieecgD=U^-G=^2+6?QV>;Rzp)b@vRr7C=$ z079>H4Cp0_k;8EM5l4aQI^6iADyvV!rytUf!5pKM*~>QL;L)Qq2qs}~xDF2uk!tOK z0%Kv#%*`>kPS1{NE+!lbHNtXFbcN^AeZ>Lm04wj0^6lBtw96mMDGM0N zt;!z)>kOa+W{>2f?H{I%Yhd>`VQkwuUkFp!PZfI=mXyTWilK#{PYM$qbMBGU-rl`! z90<#>Vu*W#sPA84I!6|$VpboFT4V3(STTcvv(G6LH_M50RuwXs&OH$mPyQG0g5F0| zu1fDSB8=|htcmLPoURRH64I!Up{ke%mo?)Q^G9jbVR*SZ=dS$(U^ktf>LjDn%!YE& zN;&7JOdQK&Oy^}nC<7MkF%7WNo2Ujv{&3+}7my>x4IxwVU0jjzp~aySAieviVMq!e46tP& zh+vkH`qJ!Om%@SeDXoXVJ;_w!u287}7^S+4T-tjfVvB7xpXY#9iS z(A)`2EggNP%W+Qe?-(T~2;pdUgM2I(0>f*9C1SAEkrr8rPa#$z)q8zUR8&=AH$Sy& z#|F9DBGUp|ECTWbxTsq;r<8O+2gP5M(p2D_iOFPTN0KUGe)}{4#_RaEFd{VLGKoA$ zR8X8JY&YRRjhMimD#YSgc`FYn5WVRyyDP7LZg8B0az~Z zfeywm!rJ8x|?Y2BfRh5jX!m~4u1rbg) zdTlEv^8g%13nbFe@V|#7`+o@C5oy7*5B4S=O-%MevaiP_*x_5i{H|kxYMh41pd?6* zl2$0Od@pM|PIyz0@G}aT0+^&mmDpf}1u|tQFX%}PhD9QXn$Q}#q8(%6;LxGGlutUc zIe#;op!iI7L{4%PlpRjPIkYmjFIH@IuQC6YI%Rg@h0+ubBnN=ab(@fR{fIlQvFibpf2cYD=R&%A?^tYl_%ZFFMOc^Z7X0Ov-<)+ zWE&}(l3&oi`tU*78ZuZ=U~P-k1z7aZT`L&384&}=IJuzs4gkO9jj<%rVwwEll$D$$ z2vlHL{_e?Y(QpkHfjhg#y)zUh$x%#Kj%w&{|G6iVQ-7n`kslgJiSMw1qYz6@Rte@ zNYM5QSD@uICq$fz=-}5Na?Sn-?HT!^O@kD8l7aZAqFOw*G?J+L4B%udOW-I+iGLp@ zSdb*p=AuJQh9j-0%@!0e?j#^L#w$y`Qt2=DiNr5N%*@Q5B^o&BiCm$>2ellfCXyOo zHqD3p){uR>Yk8jFrGp79(z<~@MKI&Er0-`>>)k#onEOBLd%fTm&;zgAA$a2(lC2C2 zlL9;&BLXisEQN$ibiq+^vy6(GP*Y-XeLQ?>YlUX8Y{#7722gi~a!NbDt3zFn;jmX^58Y3e_M_ zt4V6^Uw_1nh*(~=U+OVfOIAce>u?})YT|tAn1frEtzu($n;?_sb!q^>!1?lJgX54? zPp1ctu2&O+_kA_>8dymvSP317VRg!!uxmGwVKW0@kj3f2k^w+~!9qa5$BEc7k>-Gp zg05)EV8OreUR+$vJJ9o(73}_1oQrz>$pTqNI-GqKR7e@w4TWQ?9OrPSs}+$SfBIcg znR&b(UzF6;uEY7cdkaAa4}{3!<((+73FzrX1JQ@)t{9Jxsp7wnpl^MRfUjtH*EG-JScLeEF)Rw}J-vsA}+0v@y3GPGTnsfkvIQ z!CRfi-uLUlPNl^J(|J%h_&UM@)tg@fXim#3Dt@f3*%$;v7D%?=f}AEB6oB^GGQ~tB zgHi06RzS!6odNRQs@CUGJ>PE$ZI2vZJyb-JY?d0Z9+mrI`;RZy)L!=u`-D6F;~5iB z&3PN~BfM?Y2CSO?n=abHg+=u&*{<-$b31W=7@Cqu)=-1IW#I?((8R{tjC!)FwHVw1pz?lboY0FDx8Z#2#H*=@clcA_oOx*TjbSt9nNWI zL#bSUez?jX(BPbu?ls3DjawslMMc{HaeWLxbCYGEGI4@+;5zR`a zMfhKaweln^*K_sk_}yblr9r-9X+P-E>la7XUtW5=!z_So3g>lzmu7_vytZifIMd8p?Y}selOC{@5=SwR8?aQN8jFGQ{JL?C^ z8%IUAjw>HYkRA2bt)YF&jbB?IUT@|&S*MVTQajm6@I#?Tp#pd2;^?dU78C?LSXd1K z|A!2|l~1ou?!VsobX<3tu91S~I8v0j6H$ zr7e<9PUc#cV9^PXbF{RyJTE?Ok^{H|4yoPX;8F%@384px@=a@ISl7I;6c)Co z@CBapVzx2(;`dP}>%8RTIcL6p>a%&X(Hal-Gw*3*n<8J5+A)3GV#Fxsuao6)F*$Vd z+ru>8ycESqTaYgB^14=hoHTXKa3{`hd~0~bZQn2Qnb!FcQebk_Z>+0Tx8^-OC8O7W zwKpqx!b60S79jRj`7U@U7s*+u+8kZ3XubihR%0S24M(Z;)0b`bup?y6 zD6RcIcB8}0cH*g2x^fPucj1YN;@S3Pa$QPHhG-BdT)`lHJHk zL#z@9>JrH4wT5?}C3jcfPaR`s4f}q}I)quf;(L}>4_+@H3m;qG_+dM&$==Q3U0W&h z#Bs<03~i$1((^!~d3}IhL#t5E3ww2aFy6z{bntE>oO5; zq9F1AllO1l$O&uRWRDd~?DIfUJQ2N@fj)FV=8^Z9Tize+B=!!PX;|QMsML#i7G?!= zn~^gz_r3Am@pq@$znmyo&1mpVR zwCX!2$0Kzw4YH8rZC7b#g#MLn{;XdrKZm>ac3R8|Yslf(vp)%S#( zS5Qz8S_G85-$vNyES6bR1+;N3fjpLf+1YVwUBVwRSTj^rE$aSsO6EV5_ zoa%|7*MIb+Mu>;NRB_pVuUeK6eRuUaFmTv#F27y<1McLu=r)rRw{WY(tCSDrvpkScsbJbSx zR@Cc`1*(c?c(}rU7V7!ZZ1GlW1T7NNRiDZFx0CE-k-)($ z3X}UHxi}?!&Bm7)5%ki8E=wcQ@FIh%f5uFFBgIqB$c02P~$ zXVw1S((}(QX5QugGuWFEvl_3qH_y51dwdHvdc9LaQg9!na0F@g_d`a$22L4(=TJfY z-FYHa{c;zH8TYb+NA+-yp2+MzP9ymrZD+!0OsG=Nx2G;R%@e%>L?n=XenKJ8DODhE zdQ41)JF*@MQiH))z%0zbh__~!@RfsNztGm!TjC7a950fAw0(+&1Wpe|eOzN1SdKLs z(R}dVAHkdLKV;_QF8sP}QQrsT)c+X^nLc;oqQlw#9ND$`jsX z&Wp@u9-q*?J~_j|2Q)?6Ro;X4Gf>`WJY0os=?lL?^2iBJzksUvW$rV~r0rMo(kD`% zTDRNowrcW>*FzBx!{BDVJ4L~ZORCvZ^ShuL>D}BxNS|gbAyGf*KDoA&MRorwI?{uq zvb>);E2D7oJ57xNfYwz75^JDgf%^~{!$dhngW?B8FCM}e)0UshUb*LPkF>$QQ^AFR z{h!36fE}estmBN!@W1LHt>Ci49!%V~=r<4t$yrLo>H1o`2O@POU?+ky6RSg-1aNf0 z3(@+fruj6*_D#PXT%F^O!7nS&U?76VQCCjIeboLhKRG~#42Qi+@VT+r5;^#WFHdN|Wa95cWn<$&X|-1(a0fcC%gi>puuROGe=6(>>mbxt8-4O6}?2iGrI$NKpw zp*R(0SDNItEC=LnSnCB$C+}p&;PT7D*!lrL?72RDuXRCSydNU6#VI8H!a3!=>Uv-XFNO+UVwVQb99T5> z^~=CQ>eLU6oca;+>=j=z;+40ay#q6i&M6{}Zwl5!8W7k&LF7BH1vbXa2+AAO!oO;k^O2r*hLpX1O@iI#(A+{(N2;FVxc+y7cnM8EjH%SF=G z0Tov!U$gJy6+aS2l`zA&GsKoP{MNPTR9&rKAi=HB-*nI48T-mi5DHV+h8#Wx4_-sF z=%n;kzJ**>CupEd3VS|hbL4K)S|Wo$1cM0!VQfFU?;?yC#)4m*_>kkp(MSow{U^jQ zaZ6ieoniq0&m2^WBBch=VzB(*U3)K$j523U@mxI>td$G$$v?4Yj`oBS|5H{)Z^7w% zwI9S{(blo9Yg4I{VZ;9hQbBL(eJo_31M=6H9o(uOT0WeEb~KWKJxCNw(w(!J4X$94 zUQuR-^)v=^+SuERo>nR~J3pyjdgk z8GHfgZPss^c0$MCz9CYNSLO90 z7IJMFYo+a7c5BavL)Dkbm|u1)_{ThE54UX3Ne$*-y!SS{9FCWh>d#f}q^mbJPimi> zkv+RfXey2LoVsJ@OLJyAyU}iMf=Mxw=oaKpX3FQD&XkmVRN(P=N|z~xfVGI{BY zA<^Mib?Q7`gb55NY6DRoe>4D5=a=>~nOY)K6I2Ie3NVh^dBW=5jTmVKPYGWMIyvZi zCW_s1u(Oi@e-|GQ9`uZ971}I#RZ=g|m&G{|{Vd0zU>EtX7XY*bdZPX(YE$*CS|I;X zs(Urs57NT^=35V@^wEp?iTteJsMN>;*vG!|s7B5W=TP;k$e4bsX^QZDo%-uuNtQy} zDN8-i_jcoN5{48NCA<=CWM`||H@Gfw(vBv4qI#-X8{48p7Q64Ph6)Ie)3a`*nKXqt zxh>t~Vm83!xP&KFzuY0eZD8D=(rCUuUEF_KXiaIi6Lifc*`JIl#b5?8Z$R8#VEA*S z=lKJWic{UlZQpm60TelV7cB>gi&*B=6d9BNt_v#WE#oIY4f!>XOF-Yj&nVwP3*fR~ zs72$iQggE5HmSHF1ZZFmHYeJhzQ6|J@M-NLYFK}6f7oF2;Bnj?_W!J2F!fBdw}<&k z#;%wt{?q-@=w@P{oZ{GssTf}kI`voS=VDh>Xki+0v@byz<&@kpKO{9?BT;@fl(t$< zViAWQ*pif#WG9ly_x_Q_uTVoP6QLhRp*JKRa`%qu%5KUPmkdT~Bb!aDw$#I?eK$Dg z)uqBaOnG;@%ZoS81dC5K`l1FlTx}B))|>rgyl2RZTM2n>>$gr?JP3g6%FF zTs<(5LVHAP%N{j!N~1^CxOd1b9Mm_{t(bMX53 z-|RpWCJcCcvnF0nwgJdA?02Zk+iV})KCdCysp@(pvrlcf<>8W7S=X}kHU7}I+Rf|I zb)&AiY>Ii>@#UBy5Ge)iODniwM~G@zE;uSJFnXnC8Nsei?>S!cUJWJ z%a;x+DW!>7_C%W6J8NW|cG#;Cg7S9fUVXaaHj^WFFYbofdMMKQriJ5QVi!(Ru)eP| z8QO(leSSIb_Qm-XLHR?WJ>DVgC*zUntR%?|I5hn6mGh^!{Px6Nx4CvI-ELgP8e^IL zXxi*|XAEmt>&>^-))8fu9hV(xXGWibEuT}pqli<7$YcsS@_5^=((hBurnsWf-jSh$ zM7(seZLLox&xA4RuBoY#r0Pw-oF>qk>@qr0c)KR}UL|7OGkz`WzE;Wns@^o6>zw3b ztK=eX|M%|EK(!uIL-YG3`OodDFZk)aT@GcW)A!4m5;=w=el%9%z=qLr0f zAL(%nx;y43mCgO=X_x`g1&Uwzb6sJJg-E)vJSyjZ8c=rHpDK)Js^a6YPZPC0>H5s6 zYNcPlwk-c(%O}$QHOg^DA65(A%yc__*^XKBr+muG%d4@y1IRvjq3}@#o(ql9su-E( zzv_ce6|pLNeDp&o=xtDb2rG5N=D6#+Tg0K?n)1u*6p;Fho5DwFQSPS~8<8)9UfZu` zwGZoF{z{9~y&==-9~{~r_>(=oeGdPW7n^R#Z`4S_^!rg84`j*Q;Z&7`(=j@7wn_b* zNt0EoE%ua9!RS(0+*)bla+(ftMiH5I{Gbn#K3%a1Q>(l*=-i_UJtfZ6V|3f&=Mj9& z7Hh~w(^!|fFd=SUQODml0~&GUXVtIMfQ_DQ?tW~?^hC;TyYTXr)?;%K$rG+%pTlR9 zQtgrSQaw>e;u0}OLUtubYB*ao+eYxukG9H;w{*7Z7;e+dIZeaNCftj)XH7P8zmx`E zrWhyU)Vvr?42jY^I>&_TB?NHcXC5dPpYC;{O=Rr0;T;53JZ4*#!l?t zp35)*Mzs7ySQkH{PUwRZW$6BZm^%PT&^9YN|Cfr@x{$;2LkYDAB#azKJ)#O2v!Wcu;G zB>hPi(Sdh0cLSdxS~1%2=y5b}@{c<-Zgs(wThPlE^wxWi8{NTM?~g+!Cd}r{^Rvq# z4y%6mcH8{gcOVJdD(85?dY5U%w;@f!5m9N?AydgFLR*-*=5MaO?kQdqRp3}KO(QU8 za!=whdcQ5jP_XqH2sMmMg`iQX7lcNWnV^;;ss!FVbH&44GI~g&LK5k;X3AHeL=)K%8iM z_?NUfC{t;2rXWeJd_7JZCFy(AdiZ$tpYeiw`!wk%1MrY$BOSO?MV~{C&UKfQJxkwR zVLu4NQ=I0d$2~8cmD9_O6kR_o{VR`R1ftl}i+p-xjo72!fUXkav$bJDZ*kBHC3w_F ze+LWMVPM0Sh8Ng!Be)Uc$XnlIi`9#ZTQaSO2M^+$yHe;yYQX!Jy7307Lv-s|;=98e!NxXkbDxU}Dse3p(!bm`!Re4rZmq$noWI6Q z*P^JP`E8i;)vh1I!b!TvUK^ZJeEZ3Jd%t9&$LXzZl{dnh4QH^DUj^(hST4?v(a?wT zRi57-5A~wR=laZ~-+9|Nm$jVYxi5~*R`(Il8Q15xa=!fU;!2)vr!y?3F~|D8wKvBe zOE7a`Xz4AE^sqi>B$6~wOr31ls`_ES^uyMynE$|TKE5Mq&E{L1*8>R%7qAOErgt;A z{A=|*H=U?o%|>BtN8S2LeWpdg6vJ8`)lB9zN5}6Ntg;hD6V&=Wg@;!U_m^V)xS3mz z<%e>6Z^fZ><8ko_QM*~9YdT?YPoSQ2-pnIOxcD^}DQEKZ*H=}cd1=Nh7%2D%W0%^#R`M^z=_PYc3h)5l0QqNyxnuaV#cD>y|wehE3C{qHU?47Q_3!6 z{PO((8=dBSjTD{EJH3<&Lauk-%;jEX`Ut&tIVsDRG<-Z*cJ~v4%P5&C6PZ7B#e`-* z6Y7a_iJU`0RLnPL7=uy9FE^i2#NZbC<2Ul~s9aef>Rr3(C7(T_| ze*Dh%TV$WV)%+8`kmJ;;k#Afu1>Qs}mUwimGI2akY;6u1K{~U8OUh4m`l$0?RG(bz zrq%~^8t_hy-=CB+8?`#vK0E3Uyd;gr>x#i6V`NhoQjpqgprAA#pk|H22()r#x|Z;Yf%x2doR~C z1)Q~xRMIxI$W1zx&OA5la*xJ2ef*i$`tYb)lh^A_h+z1`_!J_#_ivAWI)^GyzoRLa zGHKFTdT|NgdM@5+K55EP{(h|c<uKB>eQdkc-MKEYN!4JH5}2u`6Ep`f#g!W*q8$#Nsrc7M>C zb%}I_a0bm}e!+?>=Upd&RGxaQM>83Y<8EY7>)~oKDsU|sjrqO(ywIH5WAyCHnpYU@ zFvZL`_J${SiDftOmpPSFy6D!%(eC@={~ceTmyQ;)E^+xB*YN5jrwHyBlZkZP==`6cCp*Uy$KDHhw-4xgwOx)^)SYZzewy7U zQyT=1hOUQduuub1b#nqRXx3y^K{5@@XOYw@@IsBiHwQ4Q>t z^1=-W%^YiJsK=WwRM$jD`&?e1D^lGD4FPe}ebkG{pY$mzzOHuG(R=C`uh-xRn}jtD`$F_}w12zOs%DJ|1@7?{ zj+>fyimh=9Y6QsJ4fg)cKdw!CZ?UlUa2q8nc^A_1*xWA<4cB<~x`ZKdYJO?fuVm@q z1(O{XT)_cnJll??^0s6fYMOga*ga82;;#L-SIeTRqk@lG1RK7d-r7w%JbHVqP4n@I zVWmX1^P#10>@iK${C}Hves4;TZ@w=PKE-U=SyeHkztw4L_#C%CzAeZnF_yULi*2sv zVa2WUCoCnA2R;S1nDH;3wL4K7QcQE)=dt;0_u)OuVITy>|jwc=VQ zH|Cxy4@?a+PVv%uKBP7_Zu0QhYUZkOAz-YWRBe!lGN_+5*vl5FFM#u<*hkeG0^0+f zglSrg9ISLJAV;-K_>;#o(Jy4q7?9E&c_@ShxV|2qd6rr(Iy4c^f*YV3e~`YG~S=H=u|ZwctJ7&wj9 z%LRiC5YMdZB=_n`zfd28u(S0!ob?vd?UZ`IOH8KC^Jcqweo3E@z(C{wSP3DCUM1VV zln4x41%qr!BP|h*=0b)tLtESW)1oAmyi&Zo!z#_2&aKW7wC>k=MtJb;N2YdP7<#S! z2bbS4`Y37_N!Q%DltgGheLzLwwm=rwJP>*O?2N-$>HF6ktn$Z*)4J)x!?_U(=Jz-B zV2|ER#66g6yX0FT0A>h9e#wsO$~}Awd3v36#~7|eb0VNyYnge$+WSx%2eKevbS|{A zwJFY(p&YEfcft@NqQle+JqD5`=r7jx-BKQ-U%mSZU9D<3zkTiTkh&m=3R!aukiC%( zSM@C*d4D-ntkb`0k%@M@Dx3K0^Y?x5oPi1(D4>S&+I1Hkjxqgl znq3hH`nt{*c;N?;ZJONw$JALzRoO0W9FPWSDd`3&0V!$e+QbIw2I=k;De3N#X4Bmv zEhQaNo9^!BdwkD1-#KgX53WbocI|oY` z8}hvyG(7S0nY@9pCXPhhpXa3MHXgF%pcBYhxMUpFFpzP>$AhQ0@`>r*TjaHOL_0vU zvx+8AaF|qYG2%i1T;vaA!95{1ZPcyQ5q)dj{!ztYU3lY4TxxglyjAE8RCtCg?dmHK*MEp~P{tLN#&V^Q2G# zCDwm$llMvpT4w;;umk$f_v6^wwc~aEJNWN+RQg6{t0C!q&jYkAsC#HSi~3GB!M9@4 z!Mo$(#h<9h;3!r93s9xn(DiemSWl7!qZS&RFiq~F4LD??8#lc!{DR@IIWCZwCraj_ z=wx$wg7y9j%KZDnwo+gl>F7L-f&EFBz-P=S0gzWmz;I%)?8%?E22HwU+uI%k?okf?8H;zYV^V$*v2M7dh?K@oym6*3U$VG%WLl-Z-xU&t z3c_34!uw{Cex}TKiZ@+oie5WEwSDB!nb-LI2g16yrJ^=w8&hSL{y;Jma#k8K(yFnXvEAM~CBQzm+Q1_Jag=don`O?ajq{u*b=3DO zR2GgK7wv?-HstP$;~fg9c{{1E+J0iC}Sj8wGCoL1kPh_Af8qc2Po*Y}0KI1A#0pUR z{~$w?vf^qb%YT8L{7gJW8BQQyvdnnow{(pJP<4oB-lN6`7N!ps6W?WF7yeV;L+tGf zCpdFI46DZbVIZ47@Q%E^s=;pYHM5`4@FPt)>E$p z)p5_G!C~jR{dtjz+j`0@KmF3p=>pdB(suuEK1TxKfyY>u$J)G<6?Sozhjq@eVuFhi zfdoVe|Fcm`4#ae<% zmBc}+pvwo~B`d&wqr{WXBndwHC)u5}4G#|=`Tg4wnC6P$rtHLZF6r?tYn*E& zdzStNGP%9uHg|_Z_%yMAC-30Z#8`|g0ukvVB{BJi@g2`E69Mnd*6*h7Rqt=}AA}wD zPNUBdYD~yXGHYlKJwp4dSt?~v=ZnR&mw1tI ze|e;8S%u>2*`@|z^Wd8C;-+2O=#%g>cSHM)FlJ;nDyNSj{$h>h%N}*E8={F=Zt&>X zqYz{qyZ_|z2R*FX*>m*c9-G@!heXED2Ai5c`%_$`|f^D3QdQgLJR48yg$99)QCj7!?b-DvW(1iE81+VZl!xQ|JHm3rc4* zL>7ek?IF6qJiTpNZUD|=r1w3bl{yx|G`1F>?2%jVzDhoGE;VqANId|#o|JwqnT++$ z>ir<^7Z;l@+~v+Cx4j#la`yqwO1L{ytLHo-7A4#G;V}6uTS($|w$o_mNjpQpmH6h8 zQmE?ZiK0E7bEbpUYkl8<&IVuXMf=(f;vNp2r8=R(ypQyQ5>D)v#*2t&OL#BBUMFv; zHC>?=zB?_atkj&;?Tm}2EiEmr<}EVi;$e=PmR=MV6tCI4N4VzW%t+bUTIHBst27L9 zeCB6{g)G8a1aDU24NvZlPuN`i_hyOY1r27&jH(?`$zKmU|GH$xj;?ULxwhbfZs;5-7y&@X zit!4WRJ5#Ok?r~xS<-{tkOV8;3hj*kr&%A%Kg6(J_)=)6ikt5ehWOKB;O|{f!%@7` zXdeP&0##Whb$ZzDo8Dm*mf>EbZeGFWALOOJrpvW+>U0f`TLReAAi6R9` zB(EQob1Q>zimoLsN!EQ7h6jrn1!Y=jOJ zHs5@0U^mrdO&wwK-+zD!{NgKZxrX7%7lxjZ$8q)s&Nmi&XDn2$tf_!|z}d*abcv|9{y>!g9Cpav5`)V}kp&NtXr2&O!TfjcPuQ^LYQ?E($u3{# z5qOJ%_dsPa`;}C>_W0J1VNyRUITmhX4r2BDllcwvy6;w^Q`nvb=84lzk>9?#UmsR- zN;{bG=31i^c)Q0#%lvVIf)8)q^o;x6F}qWu@AhX^LM>9S=7^Vo6KtQG1M$agW>@MT zwfAQnKA(}K1*hcLN&6Xju!1GoiKymra~r@pT&lh0#~GLB`9I*9g4XRFNZj=E8RxY! zT7)@!TFE;uG#>6~Cf#I=g1X`{O(99V^#q}^-|L|VGyqf>!lH~&<^X5LmXykiW$`x> zvO4M@qvkT;j+0!A{w&&(?UuI^|B8dG&U=9ZN10GlK8eQvumGxIy4CT#S2RLVR1?Ut z=7Aalt`rtv?LqKdh3-KdWVTV&dQ@+CvRr@1!i)_^?aKo_DJ_WcUs1t;HxPJa!uZ4I zO`NH}p){=`Bi;ZJ?5kIAL0oBaxu{A3&u_J-~O0;WGo61`cWvs0NObv4KX;wmE3e|E_lKZnr53Y#_M7g zS}JC9NFvdJN`i=yNl)Po^S&J+5MJAHXgxDd+A7}3!dCz#EFAa(1(7ivIW>rs5nd(@ zY`JU`cy+Wd`7B>?NjEqDiUK?Ekt($y`fM557KEc6h>b{rFgfYKgyUD>pYGC?jQlh1 zwe#L8T4n+#h)Ot8BRz9AuosV8of1Tg6f^^0&;nAHQ>uo$70Y9l)Ufo%V4c zoJbv!8zWP|76Q_&ople^DAfV3fYzj9txjzVFq4g}1J>o$)q4&BF^G;zG&UDcbgc(KnGLb?Wa6TjPDzMSqsyJQr|ig{<&o1`hU zQB=FuNvgG>Fh4VVNS8T&DHNuyDkGfN;BVNTdaM9>n}c2I zFEM;-{nf1Z{m|A*c1EGix(j@?d)|)m6jZ$}(N&zM-*`J#b}^^;noJ7kKU=$Vg+wD6 zV5a`4qI0d#t20tBhg9xVRGms(;3?E_hYRWsAkSh?O3B7FNZCq$$?=W4`-#9bL1|6> zOp0umq)c}qoY75k@pt(9>-WKsTQ5YgYRxO| zK@>ApEL1;k@LmbZfXDHQ5g#68Xs3Smi)#Vbi#z!K{+`$EI0NSduQiu;!G=~*Ffuw% znrre|m+>=(c&_CHqYMBZ2R%Rg{$NxEwn#WOF9o}XMIO?;qK%h{8{AaYO|#|H+V}@Y z=jFYfj!KU!`p*Fq_Q|NS28^bQGzFGXMeTDi;VHO-2^?ofC#8h%TGvSyaUSor^$EBS z*B5m5A0qMyn*77|%9=%fv~8t6YR+Es$z&s6>4Q_SmOi=G2hc`8l8Mu@jrW}KxIbg1 zq6A0@UuK=z)onchdU|Fhbhaz-u8Y#T(?hM(+KUrTJFtnosTXOD&FJpK?^$1QyC+sX znNNuOSRq=}zg*5F1PqO&lVKmYJ&eBs8z*r@m$WIrpi>CQbUKC5I>nV_nM{!H7@u&q z?LN~IE1b#Y#!hj%TNRlj9%{QcNGWZP!;uNW&7FDZKcmm|!oZGFhbe@@xX9D2s;P%Q zt?I8&Cp*AEw84@?>@ZmyHh4u^(x;@+L*5o4FWX%dfs!B)Tj~fq1k4s}s8p&}43@15 zxw?i{ znz4%u(ZJp;S;)#QL7?!3mq{G!#JFjot|eWmG(&QDSs8Oxn?R@N_eriu=ay`FvlNpW z0^K=AJjZEEwfsZH1#B_u#C=n9bMz1*k}nADcJ@8ha|dc+eF7>;+}}-~TTIv)eVlcn zH;zA0`!?*cCh-^?EE@?0u>_}Lxe+LMP?cL_i@99smCM<7kRGU&N!2ww${Ey7Nbb3# zU(FDYjJt_nL%%C7L#d6J01W<4x{IY#Oxjwc>!V#UBf9z=c~u?$Ejx zx8u@*r0BpYuh3$*C2H28X5hw0U~KVR?AsMGB|G{n-KjHg%sH3EMP8?E^jEK5EwwsD zA6mK|y>Gw{?R8mxJ-`qMEMq$$EJ!%=SvsbI>l@4iLORHk#ZzPUgkq{#t4vs`Em0mo zC+oKEHj6Sdfjig-)Pi33dBuGr@*3L8xObBu`M&}DYF*hBqWDdeRspyjV@LBLSIDr1 z7PcN7%S0Zg0RqlgDV&v4NX(Te;Mt)rn;Ydo$TGzhg&swyp1zpfCbtc4cpvheM2Tlc zNz&>X-mzqGM!Ep9P9dcj;bcE99ZUs#YVGd}-&?t_KYQsYN{_C37tl|__#}IWVdKc$ zf?iW zuZE9S$G(ocenlLK`2LA3%>^42u2j!qAVGv(JB_M&*lK5Vt(PlwD={uFAQ+g*8?G$O zX8~VmF|n9V8BZiB+q|(EUbsgSZxI|q&#n;eEhGn-mM=y{44{c`N5_cDwIIGZUhcgi zS9}J3;}8%~Y}Ye(aES73561c?O(V&_JaBpnpS4rn(z2viS??Dx(^%E>N?xL3b><5S zn|HQ35W+LzrkcPoY1sm?Iftto%-BKnjTQ_mKIS81YX#nVEU{0r{yTRj?@ZN)OfS15 zUk{wLVDuTm4*cne&{R!ZxOb7s;YGb}{nvdP^%Gv>31^UhLdH6wcwyMxIkcqq$TPI0 ze&j#{giCrdzu5MML}F;#b7+Q$`1&%|=A~Fe4_kg&c)y*u*_vM2)RQwmZct(NyjUIR z>SC#`adZ@d3Nr4t{J!1gCCF};romY|a)X-fKjT#_W`gtE>j}jy% z%?Oz-VP<7@w7Vw@TA#J34vYVrVe}goD%a1;7V`T&3jmr=m1Bn6c}TD|)_=D0f~z)N zWaQJU z6WQM|{5EE7`&4kl$K>xjl z6Qjh!@4vm#v`Y&Lt7Qp3puMJ^dCGQuWP@@JX(F_{w)6zzSQ_ z&+fGCp*~7!8>rX)20!gmx(Q9ZEfO0os_MJfyUj>+Y~ko&P=B-BFSb}7j{J5aTSVdE zlJ_G;!`8V_phy4qCTEmeA~uKqOQhv z-%WVJa@&8elKuGJ)tY2LHfIr`%>bmzS{pZiHibv;8|it1*0ctjKMuJOka}JcrgVKd z*u7$=V9a_R*c^ML>zK&c#qN+B3whzGe(<|1#taagnwlCISCTVNGqpav)Z%L&MG5N8 zpL&81pse{LaSZL0t6yL?{6dI0V;M9!=yZ9F5i`mfJN5+@IfNP=J%Xyh#MU-#YwPY> z987@)PvhegkU!-EF5Pm?uGaXrvf{t(iB`HqMDjB#3Wr|q{P`wkk{%1$SQD0{=ubA* zH~GTswKa#ZKDgRiRh=gLL<9D~9S`29DOwj%)rLtf|D9&MZM*k=FRWgXhJO>gK-n}E zl8>(O+-f&GZ1v5!vKb3RaleC!msml4&W$wrO}#Fa<@6(|4Ho-H_5^Qz{UEd z2CA8@7QqnDc170gJoQSOMSW)c1Dsujsm;T^S^=-UKZP;i@|w09c^VSRscb_E&Y!Kq zKFN?hh)th|?p!Kiwt<1c4=Z8q^=T0Fg%Q^n*UGfWMs{m-%1m&q$JUv?Dhea|ynBYA ziWzOOfe{aFw?&bLWbH7u7TpA~>3Qm4gw0moP%VS`?+Zp3|HttTm$$sO?HNswcxoz|Fa;l3FU2i8wug0m!dx{p!dj{(zva;5n1|D$B2OoUA#_$A`m zVh)e<+5W$9cFJMHJPA$s0z+XX55T zzwcb%b|XnVZHUEDZC>irK-Hq={oTNwdS1y>Z zF5d`2+WgtL0uye>AWSj0xOMOU$Jk_eq`V?Rhb1Px}6 ze=r+yy4~ffV}J{d8WZWxkM#@SNfZyl^TP{fT0x(S8a2F_&B&=7!awz;cR% zoGE$Fr_T1&cx#5Y_QzZi1^Rt8UHN?HnW+AGEY9}@vntH33YF)(&@EjDcH!&`(bD*8 zT868;cpeb30^#AD3BwY>Ap?yzV|h z%|NWn%S#~W&+nMuy$iQ-7`hNBnL$NEs|Eh4^)tMr4^lZXQd3-1v4lBFDFp?5NhjW7 zr%!fRI_XW!mi(%!jVK}1V5Y4GLaIPXW_zZj#u5wM(zMCgO{br~p z1~`XTkpvvtf&cf#@WF|A-Zp6fabBTlX}U|jQ>L6`FP3m0?JH~Gy@ zHyED+K8fc|uq=*^jIwh!URix&z*|3r)MfyqM(*xBtQT#Q+>T|O?$%8O#x~k9S2nIQ z7cu3IGKG2)hd;X?p9AxpJ!(q-un1E}p+~cG@dk?2(Ux9}WenKPw|PD3%1`yOqkBWY z_!?&M_?>T8^i$%5+Fv!70#nhKA+6rGXCc#;AMz9O;~4dt?%~?^^!oezi^1>k!h$kC zs*%Vg@Yeg0ND!;hL+^gOwb(YAlvvGGxD0|176r?lheY8&{?j{^E9I4*xDv4yt znX;4(wv9>Iy$-793IEPG#j52n#F8v?@)?8HZ>w7;y|w8(=GzH)65~fw=TNeq9Fv`$ zHN-1kgib%8Zm^wbu2`a|9^ACj$_ompi&`AMOBnEdGs=kFd1V(m;)A*N(cPbGYeGNA zexHXS>zSo&-DYIy@cM1iS8K)2d(ZEulbA9-kCp6};S}(Zo1B}hk7QHT$tc4(D#*@v zRlPwmII6RJx_(v)S(b{-z3rwrD>zZe21ER>S-#QB8|fw0*7FbnuY-LucDnp=$Rmz} z9fAdvX6tv}TD{yo?6d?PqqE8}T-xQSPqw{H)DN|v*!Vy}Qei5_pYVNqcMUWkRL<~2 zw9^A9KIeh@{M6N=1hd?|iCru5E7$i82WCyMh z(e-1$AG0@%HObE(;qKnvnk9JdYYtI&%0K>o`DAd#ul`K!O&vk7Kk)kX@x4QpK9CH6 znP{zBt4m8~UiWm@Ff%1`)N8r)IL^8J+Nm|+=;_^%(Net`Gy&CuWrbQrP0j_PjowS; zDbo{2;vxsaAR~SX>`@jND*!VYEtZ>PY)^NbcqPaNRXF;L<4GnZ6ENU8k{(z`7g|`I zCp6}n&xpyWhHZ?9Chl70^g@m%JVnTpzS}o4%;02`N#)`kBvpc979z!G>f3c?!F~IS zc<=0RquZpp+Rps^2mz}DqyPY4>HNHsNCWO`Lo?S$8eC$`#1?YkObgY;919iT)#$zB z+zFM;YkOE}6-e{Fx85P=4K<-(9qe%DS|m( zYX79)5)CY20QOlhBoC+4Y187$0QU~ISXEt{I5RPItTekI=O_}n_xK8u?%bIV`P^bN zyg~R`wS#;Q4WQa42FR7mg&q$xhj*HIT%rvqq(LM$zwvVX+)Bkfrw9S`u)svrp<2)bgNE};a z$%LEPCwPv@I(a%yvTrWQ z4(apRPN-ott)eq}4DudM=L2~)Di3xIpEjP>Gm4@~!UE?@U>dd*6}xF>NWmD5m@K-5 z@vmb?ycTDB2^dg{dp8Vxp?(oGm2QvKwpl9evI+b|CfZpusN!E9^u0;5&NIofo$t>o zT|6>uQqFsvBzTDOCBkqYq8^2!!Slnf#%BViuPC=>==A)k$Xp+#?u%XsW=4h+20Gxx z43dga*d7HVr)#IZvif+a;KO+SzJcSJIFXwY@IMy$sL-HAz}pJB5&}7IYZG3X2A*&Y z{DMA-5Bb)#v^3(LjTWVe$TnM~MJC`3RAY-7Xu_g@8o2NV&T%o3dadKM6iY=K8Ipmn z2Aljq5sI&c7J#aP^T&#m%#_SiWWb}t3#%JO^~{oM*UQr?cRrGn%UVEdu`L@^#nI)F zriuG&%}m8k4mgll)-y#)zQ+2iezeoZy2=ZR2N);j*3sDf{N1gM;bH;reK-Ec4KQQB zS|8_)Grf$+zx;kP*nHt1v_nq>jLJ8JsHRL*~ovl>E+0qh|&- zsxpDWHQiu(MQe0=?oj1a+NyhB?F=}P`;qyG>=fvdxWMZ`qA4ko2rdbT=q0= ziPeTaMwqoffypbqAFtk6Zu7yE-5ZroLJJeF$N;5p^e5vdE+S>8c<=DUIF-q$a!2;9 zO@(^LDCB;zsoS8xr5C))x!;HD-M6CX2>|8{ za|lgK?vF)0nPrYxK<#Fwx}r#7_3w^6c8G|Yl-8A$CLd+Y`Ge4n<_Ge)OlFMs4ca~I ziBA)20X`TF|AoS3Ka)9WJmKU3(~`K8m3x<7euvN9;6~U%i+fhMMVf{>)^10)F7iZD zI+sEZ7mIgilqmvCHJ!AJ@NXbo9lUksx^4u~dn_xh(&!qNDezF^<*#GpuMIRsoptr) znzc*~4U@cmO~@NAc4Z4~2fm2TGYE|U=mTBqRM z#qnVQZr~4p&<y+4>+_GCFC}B=LI6!7vw`89E=AA$_1`AozOg9=tH!RV`#=DJXo~ zm9Ep-(VTI^fb-^uc*(#jAQ)~tUgonK<)`v18>2g%$uGh$Mt%#*FT4>mNTXAcElJOZ zzybSwy`l8@k%qf(JEtR}qd0lle*yK(8LdPo>K%L1#&?vcBDlmYIhF07PeikZDq?g; zsS1`Zohl3oktdkn>>hFOsX2JhD`o%#3pTHh7DL*kKu80WktOkpGJj`~U*6ojQb;WU zGsO;Xao2fi?aHey$o{`oO)rMbkM7E8OD~$M^8dPF9b#7N3<-!U&|k3HxFQD22jZ+rq*_(n=vuEz#J6qgKyZHu!-o^eO^`{TURw7Zz0NP8Oy zQ|@MP%PYPOzh7gPj{*i~4yD*Z(%VGM{6!I}ai6!!nz`SD$ydB<^l}ZY3`wv>l38Ip zztQPZ`I1S&L(EZDLLX6ARSB?<;e{pU*{JeE#Fgf9+uq*2(bId{sKD`O5g4T*iBzc* z8lbm@0}(UNesga@Y)VP=h}ehIE5@Yf#xUnyGi(zWM6ID-?U&<%v*^^fce ztlf3yaa=lqk%Xd^QxRyo-H=&cQcfSC6-UN5Z&p=Oq$$Ujm@>vuq9pSq%hhRtn>(7G z5l`J=*=#5h>ze_)JYW@<|M5|n0@Awg+v(+OTp##(`%?#}0Ezsqe6p}1Z>EKXr`)HG z&pfn5HEE$C1FEH;UZ7m>har>eNj!7~se=Rn4^X;brWsmQ78VxL z`R4Nt=_2$5#UdHHc-`UnL7G96b8%$RkU>3~5bqjk|`fQZ{CvuHTogqE9aD?bg ze?u38#Kb}f$OqleO1V^Utv}36SUOE#dY`yyK6R6;5WbMWbQ!6-E|jv*gxb-bmcgfK zi`JsOeJf4AHZy(%*Fn~cneUcR)Mmhj3@F8`m7P$~%a`4hDuT&8NvHEJOJ>8{*CZ^{ zir?U7D>C%tzT@EJN3)@e;GCAWY1})}u#>h8(XWlEPUY%gzECOi3@5JZl)4j9<=)7bz6?TVU%aCrm;>z^F}*lUx+8UWe4-Y_`DxPL{`ON^9V73~ha3>)LWN zztl0?YJNenH_vBPJ@N7Xb*R4~E(yW#CL3j?{1D%OWwHb4^yHz_F;(IRwK$$<7pK$& z@BJno#82dWMt>bi4`d$X5#T;OicQPQBrmy1!nFKYtnp>=s}Mo7d5Y)&yUH;-6s6js?&4Wk~oXtSYDA>CX5 zRW5gX6qLlP#+=wf6Ii61v0$?>?Ml)hUY|p{ycnBaFK86HFN0t7_mn+*EFd6!`{%y8 zNf%fU&JtRZqD`B%|EFG@79KfA_MY@jlIg_aq8#Alnb`(!C7MC@op#btnoIwv>5NIt zIdk|B6&4n8U&bmHEpDBrS>!9oPyO}v)~k7k|Co-i0#LuWSh_GbaK*5r!}-G)=NY?K zgdEKSl_ds3DsHU2#-e2ZXIS6!-yqjS#SdJ(y{kVdRAkL|zAz>x&imo)9voN+Bl3I- zRh9bmE^??kyQBzWIyxR~^4*<5T@dZ}^r=nP$%XB|eyl7P*PtFLd^?X;}uv z&)BK`3S4`&yR=vip)nX0W@iq@8AgXYkb!i1FKb}x<_yBU-=nb6R{F_@0<;$r=y!@X z#O`uKFv0thi)oH*1Sn?P+2fPZ#aFs{ zv2AS|oxNz6tCEuAZTzv#ouYOoZaO=>>%8254srZNz5~URv$NWH*H?2c?C7|2E}A+S zrq0edFk=Uby%vSCHnd6~bU&U7Ik!W>5{cA8n1k^RUkis`H#u0?IIk10xY!V zT?1ZY*6AuSY%<`b4XOdN`8IUh#SiaaCfbhpO={(UGUMi^2jFV}U7oxT)CCN9URzbN zm-X(?lV~=EvZ1P&9tm}jqxo|2nLCJdS-n>s+AuTf$yc)MnvA2?qe+=L z-y*)C=N>ow&q-|9nlCU92nPDF<{3d?7nklNNCq782{?Vt4Zdr&_dh-gWbHU?kEC9o zJKGV9tFDrhk(rtJ2B!WAspQ!MSlO{GyX5PGM@7H{mnjtf1X1ZuWVP#DPB^79))uDo z-kUP#`t`*w|931cm~Leqw+V&W^rM3t>#x6;vjryc$K$z)&}Yifz= z@gIef$$OV9b=SDDC~YF~|E6GB()?2e{6UbOXPhG0OQ2vAAaC~7fZd%LFu8%6_77k5 z$)dl0gRvd4%C6OwSljlPnKb6wqI8e={$jGcc&$PCrIzz`B}24tYIiCWFs^VsZLp!T zlhPSIa{N~K-X{;`JVaPC(5|u2Sk ze9k9=vk47rc#nf}o-Q{AJ#P$sM|c993$K3|iNNx6D~DQuEcSDFqf>t+%IG zOB`Y?(t?0jcOT#!?j+Oery4FWd(Z=7ASeSIj>`4uxxWSH`POMlP&xD&uwNoX% z6`0A%mTqAY!=`(0i6@^mTb=hi;m!P)x}>PS#p5BKsv_$6a(wW;i-d@+^pR zl*|DK#RAbQ?`om;d=E;gk#V54&C9*zh|T!q$|wqa4;bk^NreUnn@L5Q84J;WBUL6> zD_e2~zkuvhZrs6rpj2{kTr5FokR-#L8AB2|Tj-FhEXaC)I>|x*G5?yW9yL}eaLo6<7B37zJ?S&@-^!GXx>IT3 zw;Wdw!LKXMYs%dl!rr1&6fExIellY)&VyXV(4w?4U zkE-`YxwsPvWij8&;Y(eUF_S|Gpg);Gszi@)k(&r6W3|Z8uHxUuWz5F(W0iyAnDnOw z@N-V7`YF_nj<_)NDg`)|VoMVDWN1#9#mgS0?TUiSU!S3pw`5!M9*5a4Zt$4`iMNpL z_vJ@kCifrnS6*HP&cXa_eQbpxtOq)h*AjDc3dmK7?%`a|;cTm-*Y}{^ib9{tPl&tA zadmt!M=gf5(^M%O4nQ!WZx`HiwcRngW^R5xZu<4VHZ4YfTA~XmR0io=(D@Tl#__y- z-wm)UPdxnir`8n6=9`-zMn+wv%m4?UKNFTFQj&D+0!s`ice6(TiuAjY@}~-~Hk2Gg zP5iXNHC_xLE_tuD_5^S#x&5eN+O@3OrozhJ$*|JKZB^-JPXWC;14F!7d^>^fm>F6SH{6vLxa1y;P_wefpIJ z_-8d9#K0IreeH2U276K0p%_)FlNK9?qx;c+niza|0MkMNgGO0 zcAVf)p`dkhK8%7pE!w+=o(vDtDADuj4l3Giz}gR)o>eJWQc#??;#WcYdTE%xNdrTv z8+h^+ovIBnw)q6-mro#pv_E_Lpt7s~`t3WexG{>y`wG^gxg}H}7WD2Z*Md5MGvP`A z2^n6fWo_fF!+s8X&Lr1akX!MkPEM>ZMmyJ)eWn5NXgQ^2cpyPX^sK{@`W_kN?Mv|a zFSZG3fdEqB09;a}O8@O7#>kgf-4}kJe%Rx#&7f2~JC~2~-LKq1v3y^(ucZBoF;`3- zpG*e~s#<4EXoNxeQTX($P0$N|ea9FaTE!ecA2IA)Mn)9Mm`NzRp$Q>f zs5mP0h7sTC=s~Uk4p5RB%w0o6R2@)3IYQK+_X<`lF7y*l_-<3*6*F zg@IVRE&dj1(+3|&imDq-+~5)`4r~ln=UxNHYJw2)+b`@vScHvV9G+rOBy|Sl<)K=xC7Mz+BT%uG$&C}?Kc^DqoX~TCxcl@pTr(*r0*0y1 zKZYq`gIqcjUKr4qBlQpmfMU_q${+kn<9r`vxQGkrXFiqd8GmSO-&}2B-I7h!YM*^p zWGWCh{|0Qw!5FTy*FjorAR;2lsjS4*wW8DZc`g`pyLy9;2z1hGz=ng`ZyCe-sQ$*5 z5v1u);bNUim30xLIYODpoTKhsv-cVYpg?&mdXUKdem-^!L`nk6av*8N5r^lchOreEIr6^f`R4W0hd6>5&#&V{ z+8RM0bwf3~8&Oy~{MDL*-ja2{##|R4FsJ!#ME_fb#1DaI8uYm0M-}t%qdiM+45#A7 zVAyy(Lq)spTOn`a#~UV~K;gmbT3>+6rUlxR}2o$;4Nz{Pw6(|u$ShfJm=6e1$vT#DNFhUra@fh&Z zQCt^kU)(!FcI-$l?b#y?iJK~hQ)|C`m&`3ID>Fzl^U}^Vw;~`!hEFTZ+0%M>sQ3r( zIcP~o1*MI%&kbpRB#rARwD_wP0fXN1ia2}eF|e<%Pht3;F^XVJ-zUr7#OXi_IRCQM zH9I%5Bxj7C?(UQ16J-lpOn}W;1;!4xFAjTn-mcW}e^J+em2U$?{u^?}qYetm`{I8g zw28Pu^cd;hMjNLkKoe1b1UOhKBMgiP%e)O?x9VIsnew-etT?Rt%`e> z(8zf}#g+=@DuP$6B-SWvt_{`a@&TrmuFxpM0Xk%sCuGqZ885aNOFHE>!|7xr7_@z(Y`UNTL)5N?4PTsz=g6Ix_ zG8QyS6w8*O8JA~IAyZo_vVf;Yh|bB&E6Yw;I8m(3nv5le71~QkE*x%12;g8U3}p>- zqgyozvK~00c(}MbO>QTMz_rUrnR*BSK>amvBO^o zg_EdpFrcr!!l*p)2MLq5B(#?RR-64X05F=SxB5YHta;DT=6(j;02eY`ma@L8ZV3Xp3Vf{$%@tV^mB0{@pBGmDLJ%3Sz@{%A~hM`##xJLQe#5WnpK58V=gEQR0d5G(OKS zDHSvokZwPZ*spn_5@TVxo_&clWgXQbvMOZ!o$t%{h}$CvTq*>NFNfqu_bCNtN+4ay zTUPZmjP7z5W=;nxYH8|k%BiA_7syc2$}bZKnj=H6mXv}e$KEWRVj;h}W}-)qoSgTQ zu{fW@vdskY@3Ya}m3v;W7jcOJLVg;JK+f07AI!7@M3V!6aLHr4iqhtJ8AX zy`YYuXC3iF9d_?MpGVfjgzAw`T4tt^g+&zbL4c2&^ky^R8YOS3@T^DhS`=Duul zy|@{CE{Hws?k{;aiM%dwfaA2W)a>+6wjMt!BbT>t^3?py=CdaUW0Si7{8WhI8wco8 zN``;yQu@E3a6Z%CT$e3vNdO_|e>3)|jQAKp2K=QfrFvvy3tiJ0OnlV)5Sim($qihPp?QNvLw`^xq8g2_z)~9Ma_0g&=?jXwJy*qGM z&p2JjL}BTiIp(apq>k7Zi0tJX>d~iheR*rHNEE|6q0H2y-~IX;JNuq9Vo0*9mxp>Y z`>yB*(sJENZ*#!r8ic@>|?~XJg z1LaSxkVo1pm`UWXCzNf7hiZyg#IBEAL7Xqh`e;V{!_)T_Yucd${DlGHQ(U{umgKDg&zqG8 z?4BOnqe;Jx6IG_IzpfJi{4O3R-Et`yTUcaS)_0GO6aIZ8jAXo_)XCb0hK9j?eSD8m zD(}+Fu)-C~-RTcX% z5dU|NC9;_+haUk+_N_c#CyUNuzv*w_8A^l8UB=1_6qeuV6>Z8>e{JGZ1epiUER6K{ zd}X06QP)3EtqhxKWK@T)bfWf4eFw_^gi&6AYH*eX|I89+Qm_(a%)$s|0tRQl=k_-g z$l#7Fi<|?T%r&JZT_ZaW)6~R6)Q*?arwJ|vzyz(>u}$SiusUha3g7Y4D3svH>UFjD zh7Pc!e^bYTPhg@Y84#`TazK^p4x~2ZNF9k1lLs=du8~(+d^hOSJ=6ed99BS8v4c|u zcbV@gO{-dF^0~?3K=Pq>yLTSG+8lkr1^B~Jhxzpnjt&;FhnDI-ih^PQFIH>g0kpyh z3T8|Ls948E=85yN?SI>8KB64bz}FwE;>>)y)Ct}6!ka3@{b4UBO01+d)e0vlJ6xci>ed}u9~XBMs7b2g5S5BX^MTJSxiGmpIv5xfYD{{vE)H{fOlSmEREi zKhg&h_qRSzEA}vfh){v<0AIbTI5Q9F0uJ)8Ox{auCgWi6fg3}b{SL^PKM}54gf
eh{^VZT+218{2OP^@{RA~#>vTk^S+0kwo;smO1XMU zR>x=nlAF20whUwJ3I>&_6l*pTF@eP1fnsr2wZEXC=ldun0 zvVN$Sp7y`>Tb_~HI`;!vTynzXSH654xwESzOoR@d51`bv;%ujFa_*CTXxU)pqdWH={T1}aK`?n@ZGxq7%Y&@XG1i_z{wKOKigv|; zO6hd*jMeSOgq7bW9KcS=!OpL6J0)Ebf+ANlBCv5tG860G*-_Y{`rPgwjlFz`pjaBg>u-BV!0Q6f| zlg{z|fl~Q@^n-a_AS8(yVW5!&3aowo+n)&3`9te*5Yj0Fg9}ldb%lG|`3YTRAqyuq zqO~SaQG+*j*qt{;37H&`)3jlsP82?Y3AuxUzzYZHGmi8+iB7S?ng&-7TcxMf* z5@1bAp}t;Q3{+pC1B&Y6CUHxNP@rlcX0#g4-fe|dHWu@ID_l1)7aH+1)vwKNKpUWi zr(eOVL!tKa-8aZ%FRxWNi_P>3IW7_4pS2i!w&lx}Q|a4I8?CzMSLn#{*^7&^t)6WH zfn>~PH*fX^at)QVA*%KE`()A6lb`B(VXh*nns9!-p8|^my=jTdbrnPQ2NdoV!{@(ZTp{T6cmy|WjsO*wLWtVNtjD4raq3*Vg&GLSYB z;%?fs!dF7U83!u?1n?9B|9NpW5=_P{azVQ(=FY>4heThXo`d@v4}lq~<@f0C(kl-P zad6EJ{b}+PEHi6s1l#zfDXq%HG8r;naYOM`9Z+0vCl4O1?OqhU(eWSBVOpl2x~|3>obqkW;2~lB^^M8a z&!>4$Jh1B6o{fHhulq=?4m^tB$dry#gKiJMQV$zS|LL74_4;3RJ#YM=|Kc0MIG5*s z?&m8E$dEHS2p5O!b$~AeP9Lg-H7lQCAP%Sfh&U%+NqU~B>{dR548~-%`E>j} z#^s-SosNAzyeR(O*N;!nUvDE89&yhfIjwj){8adTz2^we>qe@ce(pGfP}lc)%*L93?jMGNqzZIOh6jjZ29j%LhFTIc3K9L?9&)E%c1rw{y-rbNzcyBGOMH5dUMWpI|j+b+Eq&IawI`+C|=} z6DM&Lw#~nzvP)s9zREiLiT#wk{*jxIa44-HZzxBuMHpd0m1v%!tBi7+yKfjQ#%t(u zU~N;o0}n8n7>+B6jfaV6QifM#d%DR|IUD#@pQqc}tf>#pk}uR;#Vh$WKM%~{mc^;O z7~6G$Hx0~x|N45lwgEEP-NNCc!q&R96Lb;A+I69LUvpK8HH^B96~=ZXx{rJl_Z96u zjBwjntPrc?eu723%RaIqNbnKKc<*-2%JVX9z6(v) zC@kz#Augw;6EmE0DZ){(ByjV+Sb?>SelGd?33L%~71Ka;23I$yAK>ici(-fGc*zpt z7I!!FQUp@6A-Bnr(8#YA;^W|M23?3!3RbU$5ckhTK=gAPm=E zFzHbFh_71PF{i$IuAxud5VZ}!KsJWTCgd2gNfSGW&w(rt7M}nG0MW(bGeB z9gW(6-e2!0Zzz)iA9ozPus$q|>)bijN!#!#RxbQR5sXb-MPl`5iUDP3UJLmonCHaT zv|nSKaJEy*frI_26HaGwyhjd+O3|M_eabA$7+h=%K#`|269*0Y3%h*Od0~4z3X&9M zLj{ZPQ34$GXC~YzkV^0Vi@Tf{K7D6`0`lG8vvT86{7W|7>M~%}cu;4I`tFe`W#B9}~tkU8FWHO4wx)F@1Yt%$| zH5@#gYS?`2G+V|oBSwxGJdPK0CsihkqBf_O6;`~EA)Tu4l%!J#jYd8by7eM8*L2K; zaeFgQuyQ}xBCr4bqso#VOd3-YLh93;hCMNle@TVG!jWn`wITeP-^4eEWx0i^i>(Z~ zG44JBGs*)CEnEt8SS+&US|;UMzg2}mlug}cu{^I{5FN1s=Q?2G0JGG%NjDk!o$ax2 zF>+`(!NN(3pW0i3?c~XuFx0fz?>vS=*|RWQm5HGufAKj1Xz7B?1&kh{Jr*Cjl&je0 z>?$dljeZEnz^auz9i=nsGc}O9;zfbW)$=vJZ8l(R{QP>;{5m1~wXD_#`MJ|3y%lz< zu9Ba97!y!~@R1~34zrV_G1*|Mj2U-!b#gkDti^eA=@a5!d37=clQXOW9rJ(3mIOjFntFV{b3#13qe+Sk_ql-5^r zm@pAA7A6~PwL6s)B>}r$${!-GZIevCy)o+Mwc&Ls<@nMFDs|uT35!Y53Ai+l!ab))dF|&pMY3hOa1?WPD!lJ z=I(r+%wOO+HDIfgP*}5MW6Jpi1X7SJvtH^VAr_w-K+}0j7c$Ijka~(cCl+JQq|3C) zE%(w$Dim zE-{{P_|CopaRG+h&u4j3LklTRL)n<*YEbzn-ffQz7S!KyaEzp~vh_|& zm`dqPaqGPkm)LW^@wr|E6Rs6_Zi!Y{ufH7_ai&5LUnO|bVTq}0y8P!pe1GRHTECHl zN*nR_OjXk@Nuswr3899osb6^g=lalsYW{_O@m^L)w({zq#>en%d8FBD1#ZY+Jgh|G za3rHf-V0{geoHEx(ZPf-zu6I2w}%toVx4VrK$^eBi0&0&*D6EUR%{+xQbJN9x_nY8 z7Wb8HrYgh=2$}Na8v!bIV*}He7WdawwtI9MjHBW4Mbs=UVnk!(EH?1bPh(j%4W%LQ zJw~+UBd(Ti_m}4~K&%6%sN6j~=!4ae`+*eTDx_m5KvTd!J~bdDF780Ve}En=X44~N zN*7*aHP;laD7_Y?V`VZ>0>^H6+Zh7tUtsa*9QDiLHW{RS=lJ{nEIkKEO^2jo| z?k_nY6KJQNN8ET4BgJz1ckK;;j7WvM$|uu1b`xcwIC*gA@U+S5OU|2;Y^|j6g8|kz z#%ffBzL3Ibz1jYPfqCQ#TpVo#5miqt9JjuGp9v{&CV2me;a>DBixL;OSN$%7$%Y(O z0sU^+{f&8vpGx$nR~tyRyFwc9$bWhBj(fcXHcP?kYje-4X)vDv^rh@8qa!;K@SS)A z%ga-PLOdI6H&}TmSeZN})^Z`HPur5{)_$Bgusu2dvM7D?-z;igHt1TXQ2=II%SP$M zzm|K@@GBW3If}+&1C&gQCDR4)rE6VXwGf4n1U#IT>c{JctOULOBFK_A4J34PuxvP3 zw#1H``tzx49(ZOYkVwr~)0lLrR_%y&w|8De!vY1t5hbQnzTXFsat* z7?p+E9#yAK;}AJ?IJ};*(U+bc88j4KPaTgT2Ri8+pFtY5gDpg@q`*lo57vu#Yn^!; z*#o`d_DAkzR0?JQ`>B>>+`N`+X-UU6@#(MEwna32fo%-!OB9nT3W@|zs3 z?T`!6z_WW&X3GjLro5JrYu+c zr^Ski%R8g$=~(=}a%Ai(E12X9-6BcZz4`%Ff(A1k!u;BqZq~myu%3z(eM# zT06Dn-+aC@@grqnO zjDD*S+mxaVS|oL`oze>w#5XSuoNA05NsH0j)IhZLn0@%DqjnJ@d4|!m;cb%(Tw}Td zw`_}0qxyXiYE%=%jg*07IQ5v47%@*TDB&L|fenm|R7}u8y3|d)b?8uhKVCMdqq6yq z!#aS%!ouRjIoKJ7m`JDNJEZ~*S0CV}ZCwo=#MsC=OutGEo;qND?)wul#K?R@;&Ue& zcv*84PD*kzHny8)N2U%yiJavpw8 zj99U^v$DB-G5Pr#pAJ+FX0G!5R8?_6(A}euuDqVdeI1f6W5z$if+!kG*eFJ>%c-dK zfoUW-Z-t0N<(e)R`1zl!j8_4vUTjYdrKP2%Zvz0Rg^+u7t@aY%e)pB$|_JXJD z5SBMX&6$vIZ&@yMe1en5YbmMG7Y&%=S!S$jGeo5`1zf3)kzPzUg810b`TQqGqjiNK z4;th~C!AAW;hol_A{r)5C1@KTBvOphE~VrDaZFU@#286L$Jm}>kx zRTH5Tb!2=*GE+X#2?^MI`@F70M1ba%jPqG~k}NcJFi-{ZA!P5N#n)|C12m=K{lbZtYKXspQIoFN zM_Aduf8K^o{+#XGKaSMNy{_u;9CC7CJ|oC{#!Wxp2oq4@Mw1#c&u)|}=6Hg`uY+Z9 z(yeiAJ(~AU@WS;dhrY-rghz@^PSfhqG^@tbc(yAkeb?N}+-FEVDin~DM-K~sDr?sJ zQI>{tsMhoE%tza8qt5D5vYOrU75{H1ko95NX|T5CZFI%m(UCT})DUWfRdj=9r*kD* z>}8P22CkwRrzJaFKE-OXfpi)G`|&NM{mXp6us{K*+ym&7><1bMLl9tC33LSH@zs-~ z9?N&p0sw)6;-6w2uki{$Y;JCjC>@c?MC-Ul!NJ-3nV@J=X8-J^{Tsjfv5Ix$WeO<# z`#ysNY}ZP^7pDPvl(=8Uv|lh3kcD`0Qmpw*<9}yj(cfiy5!Kdtw*d(0*wYFAkS{Z? zHoh6K#nX4VB14U{TPW0&IwA;4j%?SLpdnAbC@2Rl&EVa(y2`SuB^f7F1=An7GrSXO zS!T0)H#?E0D#&1Z-qYN$_k8kWkRm{-5cPAeF_@lh%o|-L2*-{O<*Dkwo$WE27V z4!R(~)pc?heW^@=%XFAn9UpGOiP`xu6vn91fmVA}7FrTZ^FQ9Oc~|YC0uRF>eGy4Pv)ho3^jZ}2ZiQik8^A98mmW_eQzr}@NDZ2^0DH@=pmf| zU7qeZ`7+2V&$>-~dw?ytEsetr9#(&)=SE_bnV{70y*fkYXHEwXPY~(+nmwN^7)u#x5 zuUpuM!lE`ubX3}p;pIFSsb+r(c@BUwSMi{$^2@6QIQt8U9IC3SnM}xHO1%4|fc%TR zvg;8>EAxMm_}+IPY$Ap&5<=P9X+?KLw2?o^K5$-WcyuzR;UV1%ep*)T{{+N3g`_(# zmhb#Z?bg%ObG=Cg5iaJcc6@)+~I@*@?7)ESRDb4w|l=k@smF}o9jM4bi)4g)?G{iZoK+M(S! zO~}hX*^W0rFfiZ{+|PuXTnUFS+$CQB5`Rc)Z3$u0&xoezW;(P|y(3GIXv>&?H>Q|E735-|q`Dv~S#h(4w-v?1H^xi8~Z=Fu?gL z_&hJ9ozHJg;wdFW`YqihRbxlA3nct*Ck>=V_!cfv>d_n@kD&f&1NZRN5*>Q%1yY@Q zr`Z`{x5K*hJNNAFkI;(mcXHAdVXcgCveT<4M?FP!i@GMBE)|l+ikJL=lItq8v4s%W z46;amztf^s4mqsuoGyxprZywUGQ)7m&&Ok-_58MJZlvRYC}v|~3y;1H^|LpWWp7J3 zclFJiHxLL|5RMX;yU=L38tIyqzJith2PIGa0x0~3k4}z`-`r=e>}&Vizv2EV50%Cw zTw2|qX4>z=!^G-X)L$A$E151GP0qm5Iwj6{n<8Bx4%+3U-$s_XPuh=(AFVYF9R9(N zZ~nK@_=|%#xW(e@r`>SqGs@`KNiu|<=FgVtF^l1} z-x;08KpGvT_*wK+ziL_j7;(A#PLzq98jgydB ziA7R#s^O2oPN=AG9Y(CqoPys{HGvQd*-230seGFbSQKPJ!Fv+P3k4_H>RJ@J_a*qef}0+i!~mFwmLbIR6j+C zK&0$ri;}&*5)M3xi6~%*KRBP`=MIa)%^-_!FqjX@7 zj^(~BaO~@*q43#xz)$nXy;h316D~ZWX<=)A3Py1H&@qD)0~p75`Le-aeL-WYE%Ax` zspc>z0T)vqW1*|le?F6>s(Bix8v;3b4`L3)@yiGOV>Ke`Y$|El-3Dl>jFYGDv3!32 z)j)NT4Qv)T*epWY5iL@$9%WhQ$QK6g3>dX_d!353YA8(vWt-b(g&6WC9bY;z_gg8r zFP5PIs#jp-B_ZLi5MIL zvTBVV4f4_FS70PId#(~Kgif6<>5gNv-aWhbnaKJ_Q59;yVl%uMJ#DY9>6zCN8#dff~`SCi_CMHM; z$ldEsJtiMNjikXN)i+;do>4cXu#W@XIb&>XTB>R9n?hNe8&k@<_{l43T%vX z@853$L_l&c+V;J20HY%dmud9tbW4WGJ4d7^Awb=I8oYS2okN6=#H;)IQ=#w9PZ8ef ze%=L(y{pcgx-blzCfu`X>(hv}RjMug&6%+n5E=P&L zZsn*^-Gr^B6?&cST)mOaui$~o%-29HwP$1U;Z6-LF~$v&pjxc@Wsk*k2S* z{IA6gTz}=E%pLLpjGmu%fiI;~%H7Rq1F0iGEH&h~akp zXo+~e5pMPQIH!)%;M?uc&K#`hM_$ zw)grJN_>AmuHY=A!k@x0KlW+wg$i7y|BAPs4fr1i^d9=R#HtA(G0IzaWT_C0n9%hm zw$bV#tN%oR7CrdY1&*h!kF%;RHDFw*hb-K~B%)QoPP3NDoURa)Mvce1`bZr)?IkLc zwASU{eU3#zi`n#}Zu6Ih3lWX7H3*!3P%sWw*A9xT<0t&DlL7MW`lwg*+ag7;+j zaR3CK!ocK;6kbt=k5qXL)r}jt723Rgs9*4|V%7}ol-L@&NZgjatopzWrQU(BUl|0F zB_T_b9gCZdiOt1pm z*%JXFRolv8_lKYRxawsEZW2s}gVkh3LHjHAw|klz0!&bA{{G$6YKj$-uDdHne3xxA z@hQpGTPj@9$E8QE6-ks>q@6>@cA1%@n3ty8`BYENaL~ za_Uy{f|5h73{3Jy%RxneeN;J}y~Y-z zal;ez7^E{^?@67?$c@#>4WT~Q-E-n*3#@OrEpPC=ft)XIJ1B4n5n?yPOtl7}wY7F9 zBmE_>UpJAo@nK=2wuvu?l%53$|9lD zYQ92DP}ktA?bNrAbD8!3PbP9s0;l1D)l*Zvew!1PY)xp!fwFgUj1MqbWsbzQWc@;> z#P;hUqDpuEhthsgh)Mw{B)Vk7;f6Y>{6hX~Ld^RNv%=P0OMbb@W zI1S@13dSN!LXZmD93){0!vdUn-q4<(dLDilRpMzn)B(P-U*Iq+5JG`?Q?P2R^r5H+ z+*Evr&@It0T2#PKdBrk-JBG1`V9E3;7FF@LGBuRTt_hy?%}PYYDvD)&5=i;v&7Dd? zG+V*=7uv`$r4~*FF_Xm_&Pd#HqcaNoXeqV`@vrtuX|XOlg%;)B3O*V%3xF;;kp4hl=e4->TMz4!#YeI6t+uE@^;J~8Ykv_*Dbpx{A<_8b z$Nni+ax$RrFG2vmYzzIqI`b{kjTB!Xl5K8QO~?f|+ITPYl|u|=vMIwmzsdsu__Gs3 z@p2)l%dsmgPxl2C#8!(?0Pg4V-uMOkvZ$JW7F^=q+b$@8_Oz`uv#T_ldTD>N#=x-t>Kd0tR?7Dk(peAdY7_$Dhgd@KqGQ<-pJVKBdb1_j5) zBNvBcb_-Q*1ut8UEp7}vF$`R(dbo;#ybLlz?yh^UvC4rFLYvQ~o$-T1)1lVACc5;z z0=>?kYD)BD$lWW8tGZc6Ijm_E5Z)qu3{4K8|LwTSB7-)+kbx_A?sS`4-e7v zVbTdY;%I2D22vbte;oBzPnr<^(NXkuA{R;n z9$|{~%?zY7@#;D91ik!cHKk=)v!x)Nz`o`wm0f@Tb3n{BhL$6@eX8Yt&EUqu-3Mw^ z&r3HP)CeJ*`b@C$|0}<`AeFbFpf2(8;3e+|dJrF=?j`Tk2a9U5NbRe-twa&?GN+&Z zp^xLYUoNvfS}k1RyAi|=dIoP?)6wIlxWuq`a47hqsjhYq4(|O`rN@C`Njkzt6qP0fPaAA_=Lb4UrOTaC}@ojB0fd6{#?Y#za3Pitvm}EXRFe{!m5)6`FnL+|yuHrV{ z95BD;e=_30L%O2C6Bs=vInAC2ah{1uoG`B9{msu`4wWDBK4OAQ?sf1sUPv*$yYN3R zz`k4hmwR9KhG?=jsErArlmzdIu?wi;dx1APd!OUa!!d`Z&%EVLcHRFRv^3WFObV8B zsYtC$@TNWhb|k(qcM7R*$i)*#9m=F-U%fmS(X1as6C+68)#eY>WPc6Fh2$`70NET; zy5V*eC_e*dK(AQE(0^1lU69oU&2oC$`IpQkqQ<7r;V;!;CIn|(CjZyRwzAfrdT@CAZl z$@KuD8`$JF&o#jyxcip9CM^prj3yuVA4)oR&baAiQHHmkeiM2&c3CgW{JGF29cDqi zKwE!NjUOIPF4?8$4(x^Wv!uUn{G_{}T!~n%@m4U}Tv4*HxWT1Wk{?a(E9-X;Z4j7$ z{LpZ88u=DWhGmHf0?by@G%1TuKzYyz| zOeZQGhnRUU=(qnW{?{Q1bq9IIx(wqK@y7FIy}s+sSss=Dc1EuWJyoLbAsQro>5|O) zk_pEGL}PP!Q4z)f;m%c5kBkCnkTUH|^Q{UkaS=1(7ht95cJP8}krbNr1sM-e4VaD0 zo(t)UN)J-?-_%5m-SE)yGqTi>Wc!VmivUpf+SQHJJazj0`}cAx6AuHq&u*68Nz0{z zeB58_KCk@DC>|Tg*diuCWYEs5-b0mFYk1n){;2>iuQM^DdI>U4~A z(e{#rEONuu36OBCx%hv9QkhVUem*xhH!znBjKDlD!m;BAa7b7LcsRAtdCfoj^YeV# z%#LPa8MkLa(faB|-cayo(3AwVe5PWld4CDE3TP0a6}9IyBm+)`*E_p@1Kt-m!T`>z zlP0&vIQJJ)*+Zur``VUux4boy-EgzHLhR-Bp-rFR=Wp>P3l?V8R1k&W0R8ntI!vcC z$U)$G``%K<6{|8 zF0l!*a*W}0w`GyKIk&08;aEB&AVabmUToM9;RGotU(~lv4ACoSVE5sY?-Pj-OiqlR z(qr(FijOm{TXg5zodj{KLgAExj5|1 z+e;B*P9qGS1 z0yIZQ@Ir$B4we+h4a`1dzttGPf>T-aZ%oO=7glLZxp^OS>?P%JU99;0{QUnODP^+J zl*}~R1ee?2r1~icHTx8H_?7y~i<6R5KguDEqW8kdp<=?LM`77JL??*R2UTXJFTUCt zZ>gezsFMX+C9jtP$1=(rn4IEeKmi)1x{e&$z}*@E-`C_|zqYdNSwj5Vzd#HzJiQ%g z=A(AE@`r7uIsKzi&>D@$;vE#!)#~(fG-kIxB!6;LNa(VSKPD(pYWP9qF`Zfz@@Ode z)qkgl6$)cLwN~k(CR)KTqH@4yX>%ahI{&pP@Ms%An)Xy+hm(rxTrvkO6I)W^J#fbY z$#^6&P4NzW5#)DV5um^gqKQQtx>-8iE*fxptUqyp@f~m)K&2=xRqR_~$oC)oAMU)+ zZVZa}RwLq?Z=EGi^|J*R&e^zFn{z;F2HdN!yvQJDtDscBA2=}x*xG;meQ!;P?Z=Nj znS?M-2we_fG&<+VyIkbh6_nbKrTc4i*|L))*Z|{!9A;2^_*Oy@h~3+Ft41WHd_d?w z==!*B)e8AgPtyDz@>6{${8=~+1g)7HF}r2ci>t2jWC=HwBP$V21=<%-`DffQ3SM(T>@>rni;)G@~NC-!@p%XUQS|u9ZHV~^r zK!F~kDpV2#&|$j^qTTKoav&gR#L3DBPXUg!06=6jklMA4NphfIE4bJ9~O3z;|8PEsBF4}8tcu`$Vrrt48h^C;z+ zosZ+Fw8acXq?`H#ITNlHF_iJwRdkhcVDxZ+qkwM6d8?tcS|IOe;GFdGh|N)$V&%E6 zuFC}siPYZ<@AOcTwcVWN*7DGyF7V|~QW!pO0?X}@jJft(S(bk`yP{7VGOIkSYr3TCQk15^iV+Dr)oO`7}-73Rxdo} zG+P|7+oDs48C=+C4-}z>%f@zr+Q}w`OOG%Q)Jr+lC+2WW&D~*y+}H)!CJ_MS`d>En z=4yTDb_6I>y1*`QEm@?E5e!k{k2UuKK* zkXxJ|Q$v9?cbbQe{5t;o`QRF@N{54w214<8D|1WI6_LoDO%OSbv>I@d4^67nKsb$N zUL(omh>`AKwjq4IJdc09Gp-Xbm3K2D5Xjt87P#^Uq&e_8uT1<3SH+EvKM7S&=07cL zdTH!n7${A*KoejopY0AJOOXKN6TI0aMe$L3CZvQxmJwAe1k|z%o%iqS<-H|Z^<(gr zrCx4vB0sS{|3JUqrr#v7^XvO5Fx;=EuPjdx50qIRr9i}bAYdu7S_74#*&4`mWVaid z!kaiC25AKD8VDpWWQz+TnMssEcY^W|1{?*Yzub5*hH?_CGhQugr@R`c8Tm-94eG)h z{3jt#91L1&?$bhS>yD(t_n|6~6C8$OC`z*z{M|IHcaP2-dOq#q)a~UHPb`9f-;)YB z{NTsZz5yIy1Xa3OeSMcHj-N+qnM4zTvmHsa(T4O{0b8q%pc@GhIJhYlkgtJ*f1!5K zvr!smf_;*HxzYQF`~+&LKHNx;V>BXhVsz=L$yiGIRm-F1fpB|ARUqczO@mw)mfyk(7A&#-rZ~gb_lYx~tc>Mu0x9j(T}u zs+BT?4uiEzyF%_sU>-PYs!_e1$G|`$5a^5P$3l;VfdMB@U3!Lp`}nJ2iztj$ynZYD zHqy%HCe`WA00v4(cGdXnfW3P~hIcg*{nZ=cUZO}{tA3Hwx9>bHv8F4EUHe;XupZ`# zlgtg=hyzQuZybq;GJ`C9Q4SMQMK_CbjaL(xi8sf#LPCJ>I+LRkRG;qxzZsfpUgGU~ zch;CiQ!~=_IP^OxApb(YszRDj0RKf|7{ywF7MBz|adgmOG_pf5Su7@ zAd^sq5>w4KQ%oJ`GJ{K#zN9C>vC!^+sJ>=1e*#LOwZAi>_1mg!^Mcns8f393%3ezp zSqhYlNHMfgs__Pal=<1YOQEtzKSb5|Pq1+i-bAA0S8>Pm_>g)5B|bDmzEDx@ieNg; z`@3W*n5!&9E(8y1(NfYQZpi!hJ8>GDFwj(4kYNyn+8&Dl&SjzZK!!!+-OAM<+emUl z1O)_${B0~n5Xp4zv)S_M10T#qoU74g>zwbAA}Cb_Z(C+TK?f~N{|BELczVO(iP(-% z+Ug}f5a=I&ZvEFtCoCc|<^937a+vQlrI1*Rqx64TjvVhUA>-q8g=JosH_-3qPyFXU zL({r>6>y=x1tI&lqS6_NwwdxDzr7W$-i(}oV|poS{tl*JOUPbJm?cU9A8?TS!~MUJ zrKpyv#{}20TICoufoRi9D0g}Irk_vs=$}AMz!~0_mq!KMpuBZf@m*136Kij1>M?XQ z{1wP~Kiog%G#*wZVX{Fe2GIblf}u|UXXiJ)UgQMW>uM$_tc*^ixq?FjL_e}J^iq7h zpuJK6ZS=|aaK&tl)rh=@ToZ3)X#7=ol_GivY{~jJd4;(2{1X2bPy}QsT9je5ERFB9 zcdb%-#IQ^JkC&1d^@KG3qJN-oa@9 z-~kW&9c3LOR;o{qlol5JugfOX<+HAw!G69+8y%xLwLLefbwn-i#8cGB<7jqEF{kn}3(cLK6g$C!Z+`r~IAtWCbxY`7+}`$zos(0sW6g7dYunBatA?h? zq;IvI^lYN~i;F_cKJK2S4i18k5zzm9BWxpj<~v%|ATu*5Z_JlW&30LTxN}!q?nTg2 z!_`vdxb;3IB|qz5QfU1zU(S!Xdfop|RQJ)#M-8E7fMpaE?+w3*}Sf z5Cm*BQ1}42Vj&=RktJH6<6O^6zp1!Ale>;-+*$Ybi%Ry0LC$6Uf(2qOsSik z@&35}LSR#QSWC~sa!OKGR`x8Myb$|`cAtBATQ)X$)O?&LJebufQfIQlp8j?_Vq-XO z-uNknvBi_)Z8g_zXzJrH_o74xKPUEkTW zzZ>3o6QvyeMYwr(ZE~{7%=8lbXnn|uYD)%)?ORi+Yu6%IS8=y(Q?*+8x@pvWPFt@? z3JX(ma{Kb7XbZB(u|5rPcV`BTgGfFIkjS2>(V@_`&YcvA9f=DIkJ5F8Pev9ey|SDN zWshSEJvv>4VQg}(Y;lxUJqv+n)!Ry^3-lR_Wm1ABUP{H_!vrs5<>Yiuic(&eSth@$ zb-*)LfqVG6(hbvLWphiC&3%FOGANvLnLvKxxN^g4U0z(gig@h?w=I!XCK|qE!ULm_ z1paD4ygrbf$g6wpZ#j7&_iv5UuK5vJ+dDd@w)ZH!n+N#b{eZ+pWu-nL7CPbEUY3O| zQf1#xo!=yRPq%VN$;l-c{<<)|%Bi0h>Nv5)3`V|Q3j0IdT3}%N^V|``dWKC4ShV&8 zgFlCRD|SIaEWlL7!oot1`<9qQ{<8{?6B7K?3hcC=os4TkJ$VA*Vc>ZGetG5~*^6Jy zX{uqDm%PM^fspcYO}#K8sqjdiY^d&L$K zc!@oS>PjM(8VewBdh_=Eb_-w(i%h2U6E*@fvQ}>>1WTiViR3V?a2n1;H_r%(uJA*)p znC$E#X_=RLIiYGMHt^1)o8%*G|JRX|vzbuv=n4Sd^?;p$XLFkgC&dBx^6+>YT0s22 zw$56&g#V7S7D0juS>jDxOYJTR@&&Bsm41P5&?sQDO4t7d_$go$4+mPR3^2xm+H_lO4NEbM%SZjI{=DhRGSjDE=B&YO{?)7tiJ+xug+{vSof=*(X5 zbxT92Py(tr1m~^A8mQ%MB!SBe0&pYawy343!sOm4xH)i#qxeSa=*k$8$d>jXUMtLN^ChAi}_z$ z!+B?he1wm)8c-5{ko5Ioa)0?Ztlp$1of~%7$mP3Q&>dj$iH=6lfzr7q@7OK3^uy(E zGkZARZ5PW)E*^>o&zNh#4+@7_@zdRVVlQj_%j&^C_OGXXG!3TV`Pgppcz9o;3<>Nt59?kZP=GZzzh)F&vBFrEf2#f`?t<^ znW-&P5uyzI7ZOK;&%hQ7R%lh(ESNKF+o4YBwfWRszXuzc%9cM3z=v98Y z>PR&c$0&%Hs_9r6okGm3o72PX@G-?pzXtD9mmli?~Mlw zRjDC9xIwY2eJik;Y+v_Nk*9wO1k0$QMVFlrtsEd~c$%qE$u{&Q9xoAG6(4X(B?@n$ z`gegYgT`DJuuQqe=dx5p@_eCtb}RdKp^4DD$OqCiiM}U17x@DYC+XGdx7DTsiwV&< z+^K%8OYGve^DFDLVU&($5$K;MVt{l>S7)*ROUF*T0EGiwrEvtbFk z_A>L`XMz9ORX@4FOL|d&UxOxsoEHm&rh;}X)ZE_IkZM$E2~bf4){v6RiWU>R1ByJXsNv%JUuDkR~Utd z!lHf+Tnz_a8P6*4XBXn)F#JG4yeFe8%%UrNpC5&40~XMFT``nmrA{~w3wfxJ&3Rra zJfELKIzyKE2`8(1)3>A(5BJWtw+kofW8S=fcn*brK5FtJ72ksql?K1&(u?*6za|hd zKJi6?Eg({QoYoi5s$4smMO9^Jj{ zm;$>tcZqpFrp9|}0Uy?5*caBa!F0yz=5Y(_u$wES@Z zZPcxW|638TlU_vuz;-wWY)w#zLV3oU63*o{Pk9SWZZ($gI<$^zCRKwS!@5hSs>%Qu z6?upJa0i$CMWH(lw`ht?FFkdZHD7&8MG+*v{=6Aqm(MTql;;{n)ks`rCGzoYH!Tbt z!V0Jz9b@7QAb9||qtT*K;lw5fnzJVnbXeV@;8%sBs5w`a%OFZJ$u^sr_RZ!anM|Vo zL=xMLi`wZ>63?z%0uDY~Jdb^z>jEci*sGBheg%&97~I^Dn-75E3fI5dlwaAR1E=cj zz&7Iq??K6VCgk{GEE!6ACw~?Fi-gQZTNHkZOacZJwY!~BC?6WaiDyD~cV`u)Gw9~# z6G5(~WLe1S+{yVaCoxI%I%ENvxx_95d>WHuAI{8gmAupB zu$9l+&J{TY0S3nCktKD7kCA)ZLua4-W*{J~R`9GBu}yN& zZvJ7pkRI&{$7os90exs8HJ145L;SHK`X$5z82$%AH+ltJmFhyew(%Ga;cWk=Oco|y z?uI7@YSs!s{kRFZ6yVP=zL4<=$aL5Szd-I|X&p_C1y%X)-@hd@(aiD35R1xWI_}-N z*2hrar2$u6wl0laeOp%tF4jC#{)2Kg@5n1j_}-f!cZT;>ha!M=zcLa7ABd}3YRk^f zN!E)oJA=sI%4-6zDkmb{mdYRykbvd0&VwTh8M+WiaJ?Of4Yh(=a>)q}3bLw$;z~_6 z^XLGI+La5%At-SOW`-DA@Dsu*;nVV6?(!U=rk9KzrCl7i2Vtq*)K>%+w;|2)%>4#@ z9(ll)Gyu_n*A?`UbsBviA_81rCXf7L-}@`xGagH64{1WY!F5c6HFDm}R3-pLe6eP% ztE;3aFOJmF*C)-+k$57UpMrNY*BF?bfj)LdfrlN!47vZwkDSJ-H8Dkh-79@h;J^nD zv>be1Zc4@CBEJS40SDwzi21^f7y?kUkr5YnFE2`n`$_}-kjV?X>uVP2vHSN$Q4wVN zqIdqW&@4^=OUo-)2Zz{R@6|(?8t*}4fMZxv&JVaJQzWx4YhhBf3fERa{TRu28faFI z=kuTqz7k6wQaCL{udd4ThgQZpqire)fm&rL+tv&$(@vvNeuv%vjX) z84z*0$-??sAOjiyL=(3=qs�+XQ=_&oWx3T01*MKi?AvTZ)F)VlHPzfZF!nt~O7G z_iY%fTEX==ad!qpj-|=<{#Z^uzpKEZc~d#lT;;Ud`Nn0#*}eP3ffKH>1R?&0t`psfL^ow3ruFJ;< zxvl+D^F&cvg+^8^FtbbSAYhtiR@twdJFf(}b=J1rOzNsXkP|+7j}4oj{r{+X3!tjE z?+g5bl!SzUbP583gp_obQgUgemF_S|$xB|4QbOP&aOnnVX#|n(mM-b8|GB>3cmDtX z3^Q-$J?Hu1oU`{@d+oK)0mWG!6gR*WC_EG)At9*f1WE&-HY*3FKz{fX-v*{Q=B^J- z+FBQRijA)!xoTV}#^70KA>>8iqDU&+r4H`8yQh|m2XSyyzoc9S^ ztioh8Nxs{OhUgguuobrWTw6H@-3%K?Vw&2MNJ;!9!2q#i;qH$9Dc%q8(!p>#OkBKsC=Krsgu4Txa-}Xlgi1V|jU%pZv)TC3jgLKo@JnW)SXTkl$^4m>b*o#$|Wz zmG{*?nZ11wZok*U4~%G<_c%cKT6A48(FG@^!#wz>CD63mSKr{g-7Wqr{)hpG6^OQ| z67;P*`55CPS5{((X+UHoMo^H8eaW2E$=H_H=}&CaE_nKr_eJ)CqCkRmt=%?GJvL1q z>*>kue)E)p%Ch6}1&9<$0O8Q_E0eZjkK6X-FYRd`qjJGD5B7pe$99f6bEDH6>9?EpG-RJ_ssII^(huc@{F@@sC2W0a$d@cHa$S-e>A}W83@au4@7F1viyCFP%#M`aIr({5mE*T%*hp8mK zZa3Ei;00}%vlqP6UGn{DO5fgPBTUXSgYDd!4XAG_>V(>J4{X-I6Bw&Wq2815x%TS9T1#g##EA|I&9g z>+c^(gElVL=ak2e-JVQ6chmmkL;AE(i=6;bmbYFrWvB&GPdl&z9Ull0rkf!ssI@vsxk#Xx=J9Y-4 zOZm zLkqM48pG!wMMQLgSTA$pAk(Y>64ie9mn)7*YtHCd>&oR1%&qJUl3^UTPjxSV)@O|B zK9l`d6^|r=6Q7KlFgY$D`vB;zCy6}qlO$|}a1g-J*;xmme%R$JNVc{4PS|_u6?uN{ zV}*cPI0R@XKoFR%Zwc?W;QPW5eovStx-r3n6=*Rat-ccraTn2c^(q-B%pJZP_tR+c zb0`Et2d5S^ygAk6B$v*y_DTC`3CMq7-4IgW53?GnH@6_3xKwqQ+_p~WU7*V)S=5AFFIdz^!|%HkVX1~wK~X8ZyH>CA1;VX zTd(t~g`dX_qpYihpoBC?GZ@Amd7y@7G_FX9yoD|AEj~*XJ!J!j0&T%7C|OH_wr|I^ zb;p&QDZgLxmIj#BLnNK{Re;w-P7VVCH10h&F>-Fuego6sn)AR1uK-GGsH6fI7y(?A z?Vg$E36EOp8559>TfrrL;EKy;DNgdDcj;+qv=jD!Zu{pNF=|}a-Ur;iVf~76caJ>) zp`;uySAV53IHZ=R^7XIHTeiA@A-Z>;vl?>iUc9?UUFJ39(qEw{uQ*cWeJEmHQ1ii# zX8LJk*pe$kmsRE_xdFo2L4L#iS6ix-6C#lr(k5;(@*wH%w}${`_6fc&3= zT|&u=LGAXXHDde_ka>DmfNb`VDOMAtzJ?DT69Y0V$|Rj#k6g|Vv^k#`EAWflQ~spE zkr4Busr7W;FVL#LNl_xbApP)S%W1J{d`?Q(`{g615lIU1bAKqQJWhbWy7Px`YzPCWC%Ok8X)^%r9Z}K#{moH{o)v_RzsfuUSn0rDC2+L@Z{2%+d(RK& z8vnrL8XbG{Czbcpq*vl=AJcERaT+VI=H)y{Rh6grr^F+@4^Kbe?A{u-?V}V;=$ZGY zzh(C|3!8MQkq{R zT80t+f)!I+n+R8)=jqeXurM3%)7iKWZVBX4RP^cX>b?g~Wu?x<9p=OvN5r_nVhRdO zpVP$QhilxX_M9QyO=r6CDx*r8B0fRa*RLX@qopgAHdQ_a>DiOy=S$`J{CI+c-r1Gw zy#Gi0#ful2P!7fvafMnV1vXLzPQkFBKPkcAmcDmlq{j;CyHx51o z2@ke@tc(+Vup-!KzQ$W9xy{-+%)!iojL2$1G?XP27YT14sladELdGn_w6&#c3rmB; z*GVe}Mz-x!!QPmU3a;=Y`mHq#bAMBP9^zcBp00YRF5Jh~oIOA$#{F674LaD45U?G? zdcmZHrJArAbFlI~Pr&$py6**&uKoEVLgKW~+XldN6Nn1Ng>OJK1%R{p-2Mx~^V35H z3QM5WlIeWJiIPA{k8lmH3;Ui__=Tbt$8HPz+b}yPr;)4J+D?s=sku4syw9mX)7hV= z+q;i=M5z_UBtnCOS-{cn94&BK*mI^|TH*z_&+>%UTkGCsy$%lo} zE!|2OpqgW5CXR1DZ`LSmUo>nAT=zS(8m_7(c(Jkbmo=t;jVmzGK9k8+oqF&AJ{EW& z&)$nuR%^~|TyW)$T>2bCwVI8^`EQcXLq~^)3+)cD&7A?&ZyfBsEJ?iC+RrpE~p{F7y?irZz9?@)J*slkOdE>7!gINcXs(tLyK)UaP|@eXCci0x*(M@YDLw2{8` z@gbKz)Zrsl*TjVI>KeDX+o33!`0wb5fOV}gf;USqcj7((bp*U&V%#{@b#g-Z-TOTy zNH7Fosy0d0K|^6QHjvS%@d68~-Lkr>MH=xQ@}s>STyxG#iu-JPr?I_2*X#JuvNm9? z-w*r;Qr1WPi!-&)01|;G26GnT1&8*AvL8>(-Jq2hj-+Q@-Cj%HIWr7OyhTT1eo?#s znNKBG3kZ2&O+{FItT$(BZKf?KlMfP25+7Sp4O&@_iU{aTIbEBJkNo}-|E3|8a$+HV z&ah7XZ4_gEjjRyyVaHzm((RNx-E@vfNfKCAHEGN&$DmqkVe1kXraqehtq-&JG+n*{ zPd*wx3P|V&WV9flvq71RsKyDV0BUydFiavOryDOCK72O2dqaGAd3X8n88Y9kU}1Tg z6kMNOU6an3rY4YDQJ(^y)Rqwz3#Y$5^ZRjh#93V}2b9HZW+eJKv>>iwf0)O#LIBIFheb@rr zYb6Rs);d^uB_x8SO!30n)nuJjNacV1N^OJtdEcMh=A{$AumTe+6Xu^TC2t;`-Ly%z z3DrX8m(dkGmM#tMzW8E>N2X~Gj(#6EJ4y!`Ul%b;e$*Dua^nfDzRG#1%N1K7g5 z*WAEs;;NUA6L5{2yraRI%`=dM$rQ3UF~@42dHXIO>VyA#4zWQv6Sy>2D)I5&h zR`B+EsX-!}3P{?Fbm@v^pSyaK43SW^F=k~67y_n}9qC#-;@*^>e@yJR=!_98Q)c77 zy1dNqdz7^m^N`;6_EJ$P`%_N8)`in8`p5L^5(=MP$*<3NM%^8%HHe>?Tj%>#xyhx+ zzTb-Xciwn*($>4z`z$iye$0rR@Tre2?0n^TYH2Jl zlGSty?q}VPgAD8gz(c}dA@|z=KVGK12w{idztA*vk)zkNOGTYyrENZbdGP3D6sZGL0fcF5!w?vn{DfpSaCuUBQd~ehG@2D2@`ZPFu%wC# zg|77rm6h!~G>-PX04Vi{=BDP>vi7#n^X>hKSyjCdBw)Clz4)4g8fIX@i}E=B>im+` z%B2Mdb54ZCydl2*aPV!+p(>NXRErYpU1i66>aFm>UfhK|gf?Rq5z5%0A#ou~xu2$yrP4pmqDl>? zmkeP#bKXvu=KBt_xW(@=|NcQhTS4PDlg@{aVSiXLCZn*rbZYUA@F{y=5Kwxt8(&JJ18sX?f&{E5)b?Sb=34`2Bte$&M!9E9Fi92T2h7MY!HIE+x@dr+DC*HiDmp8(B^}`A7OW^OIHM_u{Q!=e8 zcDmaUFbTw%aBz+=0**D< zn>79Xoy%P zeo1I#F}2DOKecg8BSAY`)Z(Dv+GT$D&6%Rk(kp7C^%T-nGh_0JX@a0Ry3h|-tAn0M z!!>&C^_}MvbgvXNY4Sp9FytSk4vpmnXY?SeU*y&Kprr;ON#oo&st%7#`okar$7>8< z3yM|AuOsBw0w}7@s!^+AEDK!fhQT*g@8k5P+RFkT31W+W9GxlBB z1MX^YknO&^t_WZRGSbk|flLJGwV7-A#YPRME<^aooQ#p18;PL}e5Tl8?Faw~N|vM` zT-XxAC#I))#s30GZEL#&wAZn*Z%kRR@!%I8l;fYaE0KMZJQ_Iu31qe8q$JYY#!X6OwY5_v zoBa!PO%$_VD&#@Ik_n55wAai_wEX(@3?c>o4d}^|)(VoSw}PeTNC?XrfHS0G_!Oc) z|0o5TN=ti}*Gk#2Qh87&v|e2?f%>@V@^8uq!vx*3;Bc%o^5la{A0qiJr(RzE6>&Qamj`^mWuJW! z)a@0#1!e&-FF{HPlp$v3EIqyNLHqm40C!*t z7Qjw$zMxJj9~mXj7|xWF+mEVF)6~r0zQxXd=_Cn#10sPcBpD<0oPqq($-xtrRi_nuIzBP!&2@&`#1RkN9Ej=!y4 zJj_Mt7&eE)J>lHYW9q`%)jP*PIGgnwenW?GJNR`bFp*_mZ)d{ ze3mFTe~^06vz0T=nE#J7T~MM((})fzSsn2(AnE<}^GB=)R0V<$R5=ogL&;$wKL<5Q z6cvBw?0_?z#BG8J0flRP?`WAEXtIL*zqp4J&;pj!HY@IA&B|L0E4@F|lm`beD>i;V zrN=nvGMU7Y(F&Su%dsi~^YchOPSdxiES_&o1h3wcVW0s-27c&hINWYA4@_}?@(QU-bywmi~a&Y$1K<05!)o{^8R;g}KDjrcz=lI86 z!NawJk-rRc{X1r=>+!zF9I7w!xKpA%gS(wOrF0(4t5ECx>iZn@T@Ko&^=9e9KMuR( zRexw4ukR1#!+4j}^q14cw1laZTH1FE%NZClmWlc$KO%Kb6WWQ{0x;4Ig1#jeVG}_y zeOa*e!x3!qMC`kU?G+z-iyd$wBQ$%SXROsm=z488ryzsJq?XTqa%u$)*zj zX<>=v#z45W#(Nfs?A$ORDj0&0!b5NvQj!;yaU3!URUI50Kz^r1l?z2KxT=7^5)|0} zV8?*4kw+k*RFdulShB)?zG&fyg^ma=HkIT0^w7`}4Nh{Rh$zr&BK^5saPh3Z{w@t& zQ>&p<5lAkecmTC1#q(@$3CY$);tM+7&(KREb# z%tJ}zhIi32nGpSAlte*8`vp4_Ao-s^C@HSACg}%CSRgdXgxWgptg}>WXi9=Y;r9Av z{z8MsrOzO`26{{i28mnM0OCY&D=zx0Y<4P!G5l=kPw^JspE z-ne>;qdi2FArlOdkI9e;LiVVlmBx|f#l-V5paEq5vdZoW)0&QNc(icQO@P#2AT;rr z>qsDYz#Y9YTv$9;adjCp{9Pj2h`B~M2flq|=&Vwb!pM;UDqmFLcKs1WiA3&4uVy(~ z0PRLVjroEi8DS;_`my82UiUveT-+Fzv;Zj}{N?q+=-Q!~t1IpU?kAvPSiIbAF2eQz z=b9-+91tMLPTO>i^P zLW)z9%#$SX(ZdNF`%Hu{Q!k&Krm1zlx_FG`Orqtmk*beex<1G+2-o`=d~~`N^CF{k z&*m|PZl0aRGj%@iXUy-rO&=PTf%YT(!Wsvd)TXk2p({-V4#SU!g_OdOA^G2?`dQj) z4N7s3w=NS%pwcp9LSZl`nyi(^P26`niqpK~O1hSJ~UkM}ab>-=tgrXg0%4ded=Or3wo zkm$lse~c0aNGRL3x5a=Tvp^SHSa{+N z1Nb)`JJWu_Wn~neZ{O}6tdQekI#nrF;Ta;kdn<|3X+v@v>{OvHn;I2i!IQA`(dxcrZ>}rJ8upDbruL**Y|9 zi)wR!w@DE((Q6+aFHlu7>`#B|;?cI!IK8W1t$JJ+W(5%1!5O#ore3o-h!S~v!G0w( zE5wFMOCkSZ^s+Qc2#U3%=~HZMt!8IBMFoO@AbCf>?};u2Ev?-ID-Qaf{r6XW^H=bg zmCexX1Qp8LBlTNCz*9ga_wM4TA17F0ZC>d6|pSCqgeT zQIwqYd{}&Z{MJ7<7N^)qztiNZgSO%Dw>l`ZiNhkzfs*W68##adw|QZm?XG^YlqQv7 z9LQ*(YYn!r*2uB0$v88nOK4u~Bilu3sWau%r!L=KDg&!eSQvYdj2R8R)gJfl0UQ`F z96snYhH*icS@QFN-37q+%$?@QY2RAj5ex<)w1>a%eBmif`DR+aTbXrbUs>Ui&n6#x zs4AuLT8^V+L3akz5$`3b{yZs$cBkbcwvvp;wu9Tm^U>?VjM_96yP_e53mf%h=q0Ep za-l|IH&n4N(KA(WIpoCX8$ZtOZNbP)0IV=(ObKV>FhM{24eHVE>R#)7|3=kjG&}xs zdZgUrK1o_yQrD5q|L}Wr{ya56TTV^l`iQveC^lOfUv1-G)ybH6x?Z*3|~s7 z|JF^#qwF$?Kw07V zEI22;gG5j$-NQ**PCVx4x4rb+!;)8+uK}~=NGQCm1F+H&p$hPzb(c_zR34dcK%J{A zSElEmFX#s;%;$)PKRr8{el#&NIl71_jdM`?mM>BTX0jFp7z0wnM)v!yk6+n!f$vs)Erk1flhbr0LMYm*& z(I5|m`2VA}8JxkI#DO?$wVhS6a{4%#Oc)ILWEd-)9|pxdP-;iTjb}qjb>2=I*YM7W z2sivcSSR2@fxFn-7<7UW%0P1O%oA#$svC>EpV-@SgdbVJfXnjjKV-qWNX)b33j?>{ zA-f(U%3Ul!}p*R7`kz3cz^Wlp3GVqbzNkq4m&w zIJfx`gb)sOOt#RIk94;1|8-L4AAj^89rcP{Is+1_TJPf$w}WCc0+2{V@f9Dr9+2+M^>@#-yh`_0u_NV(1lQmpNWbF(8}e*_q~$CEvAs(-d>ve4Rk{!@;*f} z6^)%Q+1o%?2QA16xqljET%5hacCF(lK0M7YG;t^JlwvR5n%N0c4+Zee6Djk6QiZN@+3ybt44`*m8Atj0_VD?b##Rh5_kj{Xj*`l;kIwz5hOM=_v z@-XlL2yh@5P!&(wY<&uXvuts@j?!q{yhLJs@O7kJNAq`Q9savQkmgGtM~>9QE$R492|IXQW%PWeQ}xk>Nx^-{Kca1cX?C>bOH+5}L!0;IL@;9u+_; z|63@m)H~8*{_|hy2&Au}0j9>FxHKPxn909^KiqvmEWi~jAYX>u8zfd|q9$BrE(^qW zeWzyJpX}`_qHHP_!njYQFqf(HqChIEF?{*Fabg%Tu4l63%=Qa)UO_IpmQ(n1o`LM6XumFCnbS4Co?R@wcT?0OUp>(IE3q4s29LOYH zH#Qh67BE{(Q28MEaiz71xOV<{pQy*UGa`Xj$rd3E4rnY+^T)se0hleNtHUgFg6uD= zW~9(dkC%@fv~-!IF(IOd43LnmRd76O*Z9d}xuD<7tZhpRF`+ZGu`Y8Z{K1JQPxK%yi4xbnu8Z%u68uveH^vUp=&)^z=lt4`eph4bBZK_jC|ny#X*>J}O0!3z2dAg#q&OOyq>36OiZ0Kt)uX%8d;KDuS;8#$NTRQYkx0hw0K(UUa9ij6 zA@{k_5kGKlKV~hU^WEr^X5&DWVn#?hd+Gtwn3wP2f10AWI$+04?e`5+Iw$+o5&^a{ z6Gs9go<^a!{__)ie$1a!eR&QleP{;}w$t&$XTrl<^mLULUu3gQI*)9&12n0r`%&xZ znVOzNhxa~o+<0wST&;z@DWnk9R_50W0=G$xi4zeM@Swum3>Dr0DVY3=+;*0ajLL&; zg?ae}-qA(&d>3aD3Q2-8Jh($r5mL?0Os2Z_jLt%A>|Ilvz>UY%da(`x1mHGt<7`%7KNM5E@8_1uA4X^tsF z-=2P{;B-SCO@EfipfYyGRVzY)^1K~9^h19Hz#KZP+^G^>Rj4*fX-y+T2~T%|xU`n# z0dK8s8z3dtpPW@SeJf-(nM(RE&L?G70tCqii-T2)eQLg-<+rpCj4bHm<$V`rU1}&f z@yf=d-gyP_%yGvS4UUPNuJX}gJy7Oj)p9<4f;gNZov-5~OF~!piximb}EN9LMxx2Nk#YKjRQb)JI2YzXLX4aAS<;A_tQ=R&F;z{VCax`rV{! zL=q!M^bs?Yh&akwgXPc5e>`cG4#XO9lvwlEh4TS%Z3}t+i3{$xvS8aiu(F@&+AU}3 z5>n7*kE`>D`J-#?6yxHx26}Ak7e9n$cx*wxl@ER&8=hIiXUqpGI5*SylpvyCxfwIJ zZd6eI@A1-SiN5R0UBkbICVqeN6T(AMZjM`i;MKM)Ku?bV|Az)bQL9*mYT_UyI>AQ& zTg5ffWDfG@6EogpjhMu-Yh}Utjj8BB7})d!IWniJG`wDO7ABEFM?R%D7PVf1OIMYp zyve_|S*>5C))5hs_^5zL8(ZPrCNt0a9H;lE`b@g8obS@9ehARls@Wm$c2B&lY*U6r zg~hCUJ+NZ6r22Z%vH-P6^uwNIPqwFQlCSC$z`=BxzM*;(rKQGY@I>+aKd`g1?rHtVwvgF>VYqQoo%bL6 z85+BE+O@Ab{t$>T=>pn68Wz{y3TZKufkEB!2I~8?oWs!?eh-HtA?_aE(#a9%KN!e} zV=+-1eGw$V4{lcL7$AL*I}H?S5dE;JpAIN2dV`mMXP-%h50D9kGui^_NPAS*n%X`A3i?*PNzvrTpsqqlUSuokx>V2Tu)iRq?b1OM_mRVp(MS zw8QCz=y{ewdj~DeE``bNS}cdqzd+O5u~nOYMn`vdze=i@S9pbMW7({&q@EIi4v~gH z6Hq-o1r%bwr%^nNO#+AUUzm?5g8-MwB$~G}GR4!rMKRMNdFV{kPhom!vW%RU+mGM; z22Pf?ZgJ3pHOKQl#gnR;Ade7D-wR?NeAO?8Ne{g__5I51>{H6|4pZet;#?%GVMmAH zIM(mpjJSINRk&pK$@0Q+mttBjrWvS9HA|9YeEeJ3cQ>{F-P^OE1gz!EsPz+rWt}7G zo#p6bMRn+Z*a80iALDBpvyk15<;}9pvIL zjrO=8S+Rqt9dq2x_hEiz%91r!$m^U0hIrq4Pp9jtV|dp9B0Fk5rC&n+TjgRYa&alg zA^)I~Dj7YsP0Y$8-h5AgxF1+uKo``h)(MrSJSgvx43$r9Oc-`jq%agV=}U4SPfjNdcs^jEaF1FXj(B4M)b_*Bp(Q=}#5 z33?HJ;K26F{7d(PduFJhR}@Z$Utj_-`pd&FFK3Lh3Q45bcsrTnC3t}(1&A}&{M6@g zlV3?GtunQ|47^3ugH~h|e5kOmFsX4B7g~H+@0Bv!^~6ZK{_R+E(1T3dY3R3xMelS* ze9dQ7sz1HZm+A9wXCqK0Vo~vIuiaez^;ht`?8QY~6NTX_D{${QH6Dko2vDRlWn37T z$3&-o_vz2P8Q3BsQ@kJ^~S-tzrZS(D>qvmz=kezGDO zvu768DMRU7M-w{g@(hU7O)Wr}d%N9=1DRNrk^8zhlG;wraSFbW7Nn(6Y&Skf^&VBTv_^eX ztD!&Nbh$F1XT(rnf77!ld6eO?E)$n7X;2 zj~|o2S{3btKq)Q$w`D3J6;B}O$o|*UK&erX5ZZ3q=q=_)-rSV;P*~(~4~6KoC?(1X z)Qqm7pl7|QtJbG%pXmyugtV4{5of)K{O?|Bo#&-P!U%5khi^Eia(+!^Z_7Z{z=Abb z*M(HiI>g0CY`qR*?B7flbkL%-!Lms3X~%>2m292x8W!dD)56f{E()7j9PLvK zJ{z`2Z9RTv@Twwf#JOtxUJn3rt(5o^y~0-T7EiJnHoArn7aGmH(%9d5zxk8vkdm~P zr34}}2v#1<+7!i)N6;8CC9Dq2eacp9{Lv1^^wf;CELCw%Jt4LnG)S)Jgs? zaH6LB6na|By=oNBDd7$t@#(J)<0mE1`~z0kWa+yiZT-0^3e;acGEz(m09s{<{U*K4(aYkJb8RmB13)E^W8fWBy5MfAZPlB@Y z8jiwt!9j&Xt|w2*Ux#0WKSXOWP4|10ifjYxi;!+dF^*xGY&H&WiMs)P*r#o<%)G@i za;^P{=T-BvuXwC>Q-8vmbPO^gryC`D`U$R&3j<85uEQ3%zGb`odXUcaa*{{#xBX78 z!~A9&H|;p+nLi&p?&$5Sh!=J!cB8RO7r_)DbyW-Tvo6;oa?g%DhexLFnxGX-E_#q32mwzpPDCZ2UOw$37(_?zO%p zILyukxBX1za25|%I@Y^Ib)87VHu*vK6No|fyY^_v5HHBlw_p{+whXFDRJkMtJOrK& zKS=Rr2d&P4mlK=AmrVuK;(nu5!H6`&-mPc3fYtK>CaLs)$a*L1NojBoovc>dN(&-#dbmnm)!i)R!!)!&RS~clRNOzOEU^=t%d7fn zOW@dQqT{z6bz1X&=I$*QP^&*>lgc)vYeC99TpA_{Nci<$myqb)$C~9^8W3lF?U<)Mv&HZ*+S1;s7 znGaVVp>^Yq4nU#LT3vq*2)?c+ziylb-&<3YmKJY;UrZE}>M#Qv=)hx$!mf zWa|N*Tg3Md=RH!<8+X(?3%(47QqIsRwvVy%9kyW8g9*Yf8{@X#gp8ubIGWmis~~qD zJTbGhY?r+igu%KEQ5ZrCu;838u)@OdStkWexybxq(Ql4pj#XG~B^5&? zO|4NmhMXMJuwJ0CCB-;0az$Dg3s$N=E1F%N%h~d*Qz$qst5d|TwMoer^AJLm(55O3 z)gGUxH~j!TYHFPkuRy>vO9|z&U)rElh0W%hg+M~i5)}G)az|Z|f}DikmNeox81}O` z6nR8}U}7pUJ0vBJMN>Q+%=j1AMM3D5o@Dh)lQQyhft`TUa+1G>^#q&QWCGrKR;UUp zH52MVY=9%GV^cXt+Xhko!%+urwz95Id-@AAe}2cRVctJF<+bleJ}p)_eci!g*-jbB zemSaA-;;UZ44kwg{}Ay zDljp@(1}kSqLhVcNs+@03OMBbp`WtABrcApxuJN0s^^V=fc&Hx^*>sF%vG&Q{47Gj z0@h{4b!r$4`Ola+5mH>qAPuZ2E;@4jL^DmNHeH{p+(m-jMP6ST^;GRrof`W0s9LLh z3@CpYf`4gBb_~bXwVe5yKpnt$Ozb25olv^v&qPJ!!PENC$rBw}Xi-quQCID`loIve zBV$>pxUD^c&$wa~l2Bceu$ScPRe)A_4}Ks@gei8U?`LO-QY-!fXM@A8{bJ`a8Rsu9 zb1$m`i8(?fRu}}o<6W~f{c!GoJ&6BO1HMFzA}B1)_>-OVM6}w>j$-&p`yxESl|&LhKO+3_lI}c*4G~37rsPMh zKXttyP%b*As+61H^+(sc4itt3}-_yqDLD1^o_zP@T2Y2s7&x^!$%(1toWd z1iuPkv~71@5VX2U@3gr1SaudyIa-C9yw$vX$0(U^%usLHIBztbm; zVr6ZW?qX?LphvyXLF+|yMH$PJ1=SU|_JppnHITv#9h|z@nswR?tZ+1IDF??3s@b0o z#|>9!oo)v}74vScr_4SFXgQ{sZU+!T)Aq|1}@{&O-gxL2>c>Ut+!~N$rlF4IT17hBbN4WxYCOWI7`t zDc~J@aL^&m6**nl`yu#lMZS#>l^fLlFE<#`UV^M}uQ2+83}l60C}F}k>c=V3W+Je3 zp)vz_9Rg$qg5ZBu2tq{EpG%7$2bIG0`Ke^ZBJpweH%*c}&8t0yEHI{dd({1AhocXk&ebQlseYx;t!6I?$vG;d z`i#}*RWo1VQwYM^nqeyEzv8u@;!P>lxRA9OpNJ?R+)o`914%q0#$})oif>GaYI9Io zVMYH-X~C$z*7$QKTU0lze7pd_r^zaip(Rstj}or?~3iGHZT~_2|tQNsj36Jck}T=8Io|jQwBQI+;BauL-evk=~hysX+gx zR6jcA)&INz)Z<+PcQ#y%=)aWVnxK0ZY3#md`G5P`NO4s5`j{D<0|6J6fC~IhpaX!? z?WwO2_r{&}yk{8y4iPIjMCv7|-w1*2v_6$%d&2sW_8OzSA|&JY6w=b8q#`IRRpDG2 ziIr=aaWhmyEuK4_q@5H4gmKnw3r$EhX&fZMvtLa>Ic??imxJE(=4(c#9c`*1lAM6WWF!BeHIZM<%OP>1o_Cn++0ETGZhag`+fp(A3EFr*u{oO+nsxHXbyGLt1h{QL9UR-|uo&iGCmZy*6W8uV0WfCdi_4 zrdR5e!r^B_n}1NA1;t$|`+WG($D9I%^a1#gy~WUG+q2`I9@X9@a5?!Ytw?6@0iA^R z#8!4p=tR^OkW7a<5{RmPM=)~8qd|Rt$;drHne2Q(MM`A}YLUsU+<%dQgNh3zsFx*n z>;e9TLl#;*C~LU83Cxlj?}9G(4>4hjnYq83zC~Z1JnRe5p7;#MBc>lwMOWx~>AY%< z=n;?$X6C$C4EYif9G5=*IOp0wi3?O;6CUGoEOhY;W z5h5^>`2vbJ3dJPhc9>N?w*qm^#~{4N$3A7 z+1Ctrp*GlT2N3AjZ_v;w^3WT9i`#ca9PNNGvHr62?!0)1LwJ<2Gtr zzP?@iP0RV@33xOK{EBx_vVqm0HU9ot;mVD9*~nYztiC?0YO_*P9{-h3EEVl3$*1D-Mjz~biqk5B5 zGvF}EY6W3G=5yrUR5;2TtsS_kaN5oB{GDc9 z2+}=hW#Q4^04uc_tiCDQfT8Nzb8*oQx2Ah{=?hkGZLMQuwKiU00UqNsE++5`Xrnqy z6)*EDH!Q}JgCau~YY}6>MzORNkUSC0eQuB`-3nOOdz3+VnSIK-sjQ4QB*)sc%ptsc zE+aJO2;5FMv=MLN@6W|4#}7kAky?MYwlj)yl~!wj(NFD7#v~&OCAp6;2AoSL-$`6o zdqy1uww+XbEip;buSgIad>L|X;q0<2w?RI1AiR196n{d$b{)ul%fS#;goE1gC54}4 z9j#HtJ32y!g-r8nu61e3K`SdUayN-?=Kq_@%cLD%1D?D-cFBSavLBj;BT8OHV%}$^ zLH3>MBrtBhP=w@p0z z{B5Cp7B8p)z!iz~_t1zlER{hJcGIK@T1BoaD>x1$3*m8u() zRl@HvyN(1Zz!lyTb>Q2V6Hg2lw*rm|1GIFQWx}u$0E+>=fBsYy+J7Ag1)Y*rYJi;| zS(K%Cx&eMBm{AR`ksBgm)_S$HuW|RT37v2JkSOuRV&_wM{kUZ+JnhPOO{R+2r!y&B z%U`J(W!;NxNpTcnQWn0es{LYYg-eV?<6ZES)Yt#@0q=`$%w3wm0eb5 zcCtfAk`)q??Cib%_ebC7|ND<~I_G)L>6{Ml*XwnU>%Q*mYOk@K9A3PBz5D&6#>&%P zs!;(_`~T6)a^=b;v)}z}_DY}K<1>`+OdEV9^Ke3l%PzMYY`bSs6FDfkr@68&41-@!%MLl2O znD)X>N-x8%rnL4pvJi3;>^mCx+>pPoy)w97r`MR?^%kPU+tVXyl8r*sDG}kvEJr2E zYN|fP-hiKe`BKaumRI{p5wGX}ym3{u$7L+vP!qfz-~T3fg9ubvEDmXqhAjv&vyFNZ zN&nwktWeFGTa%L4@ZHH*eY>1r+W`D_6+Lr|(<{`qPvyK}fiSkV{dBVB@J2khe9r>Z zZ&j~D zeRX2c!Fgc(xPbXry`;c9sFcTW;~U)GZJw7m5dzd?NlQMMjT%&l|APFYqpvT=mH@L! zELiW3Sap^&@_FnaS!KV5i*-rI(2)KU6|Q7OWz_TP zFvt&U@5B8(JBUS;0p4<+=u6-xbusd~U)16Ct?{ zPh}r?Uuh0%Z@wW^6)I9^T@@8jwSVI%M{_uFLpS6{cXUW8ZkGRdezZo7J8w6Ju_7Md z6%Y9zXhcV}MRkLj8A3p)Y}@vF5OC|XCA=PXt=+h8uhD>ri+~qT-Tieb!{b%@NP~l{ zMAx8~M>ox*Q19n+ht*Pq1&@P!UnXxb0|?HdMiMJgOE*8}64ARvC8)~8Ua;`<@sz`u zO>O^ok!xcU`M>{MZYS~EtM#mPnmfXUELqu91?AbT=%xE_zUdeR2<(_0?fm)kD}S=a z+1DeQU+xKX0aVJbu{>t)!*7)l^WTVZNAur^(Ju^o0dZkJYg;=zJO)41z*lbA`2_|> z2-MP#p8XF!gGG72SM8UM{0xbRh)HUCf$>J6xHaL!2pe8nb`S0BHRfu@f)K0nK^e$b z4sv=oy2XX5VGy;z_S9UoR}GF_sqv*jU&0;YrOCW378{KJrJFs+9piHAhd&;||=TI56J|^>jC|L;@v|R7rsbN6%G`fm^W;?>03~{|9v{2lG z?b}Za2>=LG3oR@LsABm#fXv9g|C27+FHQ`0nh6Rv5Umt234RPk<%cc$PcJ!aM<#^f zj+Fq=WUpcNzP3nPp@+Jz;r3`zPhmpd3F;q792CnOC^G0{j!66jSw<-4a1ffHD#jO+ z&SBg!TYbIvD~6RWB~K##9op@>+?Q*wvZK>m_P6+z{0ZDj=CLGwFg4Qm@cpR7?$5P- zuE~5vnBS^SC@q8n?(^ohg%{7^|HfJ62v)mxOJRxVmr?{)7UdmO)*NO)m6>BZIYnTB z6_$5sZT(ahbs{F#y|l1CE7$SaK2GyiZ8`+zg54QjXw7Y1+H|dZjV5REaeD0$pVlg& z6DY7xhG2aiQ8@G3zSmx-$K0s4{wZbmSh2mv6+$SY*Cv{^GcUa*PD=nFv&&xl_y^V^ z#!NQz3{s|j{RZ9O7|-1zvM#gAnCWn{Bk}I#bt?Q%af8dtw?VB$q!F0``!>zjuegUn zwIV&ICp>(cA>x>4Ge^ip0@M;T32mR6Mq7UAK#&{(-Db%Dcz)PL~#-l*0`LMWQ4^mYGbq~ zQZN{ueesq|OYJ!;OwLnE=#xh_OP_C5&DEB!lt5M;6D)DP%{x06eAq(&E24P_7%df7 zbH)hihCDqy`uQxyY@MiqLNgco8me^_?Im3$h)@&ADwPZKP=7xc3hA?w&HVm=_9q5oW^R0pTUjj zP$+%sRXx`^L4?X7<4-=1&JT+uHG~~j7DU8KO5Pmfi7@wIm}>?sx#}00p&*n3NPmiM zdQA+8-unlBsrDKf6-`y4v||q|`0BpL5Bkv!jnUH8$Sa^4`-Nzl@1X+J?^u?3cp*8$ z=H+jcx(71hKd!(X4IzCfe%}F!>D0_qG{{%d@%Z>njk>*qAc&&~=@ z>jt-m#T$GCz6vtrasc<-o^S)bc@Jig+-r(77uuiBg0=liG!8MsF;jM9>{2+vF_R;|Bw8BYr?|9OGi2} z6U;33LX#cgL_SSqTM;NYb?%4?eggtt*h`TnMrc{kk|TLhZKJ#A-ydzielde)F#H~F zs9Qt>Yk?dYs<5UxURw@_!Ntq#`jMH0fOXBU^a{5oL|qS^<9MhVEna1bdE2i>qu)AO zpPm$E8L!3`-dJXrLc6Y_Ay7Qa(Ku&-^^A0BBBHsl6W+4jt7~#2@Yh$6)A8HuyEb68&&-XqY2Ek2xq3Q46so=MeJYE%q>b+3$ALYcn^Y0}q1pd?xT4`vn!?0sfdG3og!@~lF!<#n3iyt_!`2QV3~hXr0wsL@_ap*_UZG+?WdpgJ^)RM=3=5Ud>i#ka9reuD3$-6L#Bpx zq`k&zCp77|?xKF`=*fMV?3;?c5Ks$hL}AWV-nYwm|F+P4#}du+4}84?UL_+mtU`c+ z1}Fn3(?h0WA|Rmg*cH*bb+aR)8PGg&;obp7hA_KpiSZ-5NokZo9?RIB zBAT9Cp1)!BzN`HQGXN8nKL+^yK-+~luiKa=^^xxTkJ9+U6}Tug8xov%B5Y=~UXkJS zi%>!$l5Qj9u6Aya4aPxt`(I1AaBrnhk-qjc^T|b@Tff;{()X}`80I?WN-8O7IjPAzUL$|gnP#Y4UCndjCL4-f zcd~t#pqfoU5GD=p>q(i#qoEY!?Sz|zW(=<(97=T|R#YmgRUZ6`3roDQgTBmyFf<@4 znE98`d{s>ztoeNf8tCuQkd}DoAdc@}j$oC=V5c)p11YLhPrI+(9a!h^_JCl6@*hmrtTjV;-YF(eGLt zn|~5v!Hd3na=tp%<4Wt9DROXKu#)tnY#>>iJfpmQE$dtBz9EnC!OJag_Di)Jrg^%- z^5;66>5+hAOMuKN!~2~a9s|)>B0*%h$Mfr)@2&L9PhS3h&{J*xh@w-T4AiopeQY-W zLl=l~#n_aka{Ew@j}@)q1e;VpE;h6LjK(K{#LbF6&+{ckv4@?tD53haHjzqEAx6P) z*qq0Ue!q~aX8(dU5#N%cc*(TrEZWz0!ey~cw{m+J8Q7riN;8H?p+W`SBqzk` z!kaORc?xT~g{vO4!EN4R8LGAF?w<}M%zS7E7j5>Nh>iQmGQL>V37yRGD%Av7tx1~~ zi|49YiTqVuR?FC9 z6fIASv}5m7ZD$B$xKB{L^$;hh6dq^OCf<;KsXPgKCyoa(FYbW}?u2E)2b& z179ztKGM^hU%(mxA1a%hWwAz8&)E73|D{kjT-2`-(dfBuYH5juxTE3L42W1EO5Fzf z%V2$;u`So9W+!PwlW%Akq_7Gi6!7k74D)79*-{N&HXa%yP7_#WwH74IJNdYrjwOv| ztCp@hIw^zA<#K@byM*X|5T(;ikx7QC@nb&Dyc2N(q&ump;J78rwb`iOJw{>UBEsUP z&vg1kIAWG)Z}+_Z{Pj|X)B4W>{EzAxdUXy$O|eY*Hqk*5zVbRa;o;j>ZERv@9yCeti_S03HZn~5ACM?&>j=1G5;oFA%gqWYmz;7 zOK`T9zFJZt9r2LM$UeQd%HH;sv-0$YkX;m7px3LSJH?*xBkSntb)FvYhc}VYknDp; z;Epg^Z30OKQ663HFGZ=`FOcMg!gdCI9qMR70-A_H66Ey02#1H{aO7G}gyw%2k+r5ZLjg@2C=i&Wd8e9 zM*mTYV#_-B_W_~=sz+Xu+5QqnqV_8GqZ@N8M(EOh*2M<5wBK45b=lJnIC}WBC>++f z^omqQzkbRa^Ib%k$D`vG@Sw$cc%D|!{zPl#_se@8dn*+O;{uU3 z$@l&z#oNznIjV?NuRkFV7QmCvut?0JPg}N>FsdScIbMrk-XvnQ^3_QzjajtYKTDtT zoPd<$?9~;JUfQ%-KlOaejv`+`#MJ%ZCh-kyFDKSnN)%!)c+SA=T__gty_aoh)sAQS``{$3&xw?0v1GS-zjUFA<9v7DvKEl2$ z2$l`_&7^}mPcO<|O;moz9)e~OS|Jz{L`>LtR;J_-ikHHRwH6W>pJ74}+HR^4*#o~4~2 zo?B|o^+)P9>719?YjupS*9kY=CVgA0(%%%=*YJqJZQ0|M$=q6=cyD=<$eMoThrr9> z*Dr$42fAws*xbBzbVK{QV?F39uvBkEncTh<5W=arG=6B)2M~}Jq=sN?+V6{i&!y&}18_GMbsvy@- z1$%J{Jc@w1XLv%ej3$OJu4+0-hIC!KP%t|EYJ&%+NK`!oEvgE79#L%^xwDJE4?lxI zX{Xh?^})zh%&0R$7+z*zzWyTKyIzuakhaE~OPYqxX|JJl`8d5aM?OS@tuCx-QOisJ zZhft(K(5;KS;-uB^nU8v^y=xNd7@EcYufl)|ESfE+MaHamy}NDyFJNH5Iy}R4;K?& z+G{+nrY`YlD{}JMITyqxP-UF4Vhj^+FP{e|`NN8{a4+an6)wTcWeJ3MbD>*SmJrp6 z@2cKXV~6qzz{XmbbrTPtke%PuEOXfx=X*2f8g0Enm6j`W(0?0~p~=AejhG!Kvjzdn z(S!|U?($tct*XhL$@H~psk6|GCwv@$- z|1qvi%k`?1T0|l39O=a(Lk1qIJRbyqFS|TbX!XRqVA-O-hE^p}xz~)JCz|b!5RD8^ zvK_T4RTou@|Nkxz1vFIHSyQ7MZ}-W#usE~s9BW8__YS*6=mX!C-|Of`2(Ix_^%C2M zVRM4i$2Io0N7!Sd%@Pf2qIsA59cX{Ew{+PzUY#FfRh)n4FuK;_%sv|xl5n07!E)3^ z1UDyBwQKj9a#W)He_VisEn|v1W+wLbNu?T^1>n&6$!hqBv&rSw{@G!9bggTr*kPM)r2$O%A5I1i=$?p#y_vN#aw>8nS%Y!(shG@uz z3@z372kXLa=9k~1Ew+Oq?k|lr6r2;Y5UpVlfqZ*U2c6P;Cj5V#TtjHeYFJLz(RPll zz6yb6)#I#7Sm^I0kMXFvO69A-%bP&ZhuD)j0caYV#mQgKbAeWJlCS>y3n zP~}dDC2n*|PUf?UKUd9Etc^xb5U6?D7&%Ac7k!+%Hn}P?w>B~`mCv8QbIINc;`Db=xMj>Ws5f|fxu0z3H z7n6?~T%-L_Da;9AvgL%Xufq#j0g|iNNTSK0yRa>rifHzakz`rMJl(DuS#U16NCJp3 zihmi5YOVP)dLSsy=kA8+ z{A@s#LW*qjwNh4yneL~kS}vmd3aXUQhBXSgQxP7ZgyTN|K~t~D!tR}mE{`PD_#&F} zP`S!6L?>J%F_&Tr&L(%PR`p97;!t%S#R5i^IN)G+Fp?p{auoQbLuIYjrhoyUuj8c_ z&!R=&YW+rJAi?<;^U;mdp?#PgDy>+++`75jmpN0wG@mwVT@;@H?5UfYf zg+s!khw((AFkJLBJJHMt_|dGUs?~4O5hC(PEo3`Cp7Ij{A4g7>qqF6J1F4ugySjkuc3=0Y-yr?hCQ5XpPwloh z=OUUnM|x74K{3QA?PtKsC_yb9K_LIm*S`xfUa!^G^3uGv3o@xhNw;ZQiU zz*(~&)7gX2mG+t%(>arggsvHb57i}ZqS z(S_iw&@$X_@emZNurM@V^894mgg4y!w<4)=ouH7sdA`Ar!W@-g?!B+~@J0$}T;mF* zP)X{ze_DGY|DCq6E3RV3d{PCHVZPw<)6bdWQ_p|d{rE|Y-D^Htv46xVk;$UpxM#6F zC!F~8^>t^u66sY;t<=FvPy+uKz}XD`u(2SvS*^9)Mc}r6!Yq0YxA<{hZhZR&8Ip46t0resJ0O#rzk3o)c%NCnhQKzg-x$>eSJ#`l z@7^buclIexRIpgIT&fDncIw}H*=^pSl}55nNu4{+_eMzK0oT_*of%!&*q$-a)KNDB76ejXaiNG~P1wp^Iupuo~K_iT@L zQ0~3wx(29P@qbcu|1K^smtZ`6M^oC5mi&&UkTO&gMks)Ut>37 zq8?)HrdxR6%eow`dI!?;-KL%K0f-U4GP`0zZ&u`;imrq}eiS;f*~@iFUikEStfJ10 zKIPlghtstlVMGBQLxzZ)Fjn4)DK#3=PpGp>q*C7TN_%5kYw_yYU|oQs%8i4M%4+=QK( zZ+z&QP@eB9TxU`Y%P$=B-_9a0IaikXi1WdEmvf8}if!ARZ{5Q+K1bCz@3M_Z^1Z<` zmP!9q+190@ZCdEx8chUaguLJpjDUD*1wd}3irVrYypr~DDYgrv6cXSSluWE zmIwuwOZGXYPLYeN5GqU#R;_5xj#w~9Ey#IG2t4muIe910`Q80vuOXBvZj(Oo-D{$1)3D>QQHI;p^VLhO@%9T}p;BU| zSL4IKb8*xQp}r|phs0W#aMV=r4TGSvQ@!^uhQa+Lk;k_tc6U(c*7P+b%>crR5ZC#9 zz=Ms^M%)M5jE=Q3Qj=Nl2cwYwPg0Rp1?o|*!{{2DUoL69|2n}F95ww)!lS(X{uRDn zN7S9nfFkbAI*sRRX8|}`g;)lu_HKrNh~3>=_R66n+-p#~k%O#-LoRRe=UcV- zN@emjCW39S{zA0xD0-GddPu>b`A1M!k+x)J&~#j4CtN^&XK* z!;}N~2hO}LZ>HIM5uxz111KEvsUAUuQ1UEC`&X+&ckU(*5vwA?e%ntM*ykd~dc7HLizf9L<^SiPhlBxPOx!DI+N!Ig38td6H;k zHlyU2K2dg#d04`76!YT5&*VGS?fik&13Ww#3I89-9a(y%3VW$jl#s~ksAz6Jk^Xab zdJM58Iz`(Ek1G3G?shN}r+BPVCus+OXaN5IOI^>b&Bq@HcESi-E_%X1%o5_%e(oT) zON0L8SB2}S=xTT!rfKXp7Kzp00=4BAf)+2ozD97qE0xT@a%*m#Z4Nb0FiLmd5#Y0M zTlynFSL;cTN^@r`OTJt?k1`_YjR_=&l@ z{qU8H3OF4*fBRR5XH4j2^23UE@368QvA{MAN9^2WW$fw26K5G4w<<&ruN1 zQB5Gk05|$*y^EQ?8|NESocJbe`11ZgntUj8)S)QL6}gB5*C}JDdl{D*9;wQ{Ot7Mv zqkJYu{g`zb9rfm(STCQxr8(Q{pf}W{n+NubYBim3S)Nf4$5j8WlifQgFCOLQr937ogxa;u$)Lx z5DjRmbDdFEUS}sZQ^$Wid^UdiFc{l#U^GqzximaAt;A053r(e#f^*%R@(kz#akTh8 z3$<;gY)NYX!%-)Y8GRp400Zr-P%RRWTQO2ehlhvOP1W$U;}t>s`#@Fu^@2FxttsFHS|$&R-U~I+%Q~+{E#1 zKoEz4wLK-zzU9I#AsGF=C3(_hog+RcZpwj1IxN+smbv zXc1l?T#&4(iH9j!ZNrIpV`WpVp#Gd=!}+4;&iA#Lm&YGXkHLKdtwh^y$X>t92ApM4 z7Y`~nNh2Kcn;9DQ9&7d`r3UhnS=~{TYQ)bz1mz~0)aX{ee?pziW6%k%BzHig@6R7R zb|vZ;tZge9Z5g*1ezk`(f_I`}(-97IMXo1@0|7G3@vYw;U_UI=51;zmdgf21r^gFU zPT;u>MyRvBNp;!m79fy}J!lQ;<2bqO?el46nBAZQ2o7=J#0WEDj2|BwVv>^j*eUS5 z_EsC0pWLq)r_<5V0sAAVj$7*=qTF=5e*WZ9y0+cLMe|BK+Fedglb?|3e?o1Af?YFY zuqCF#XJ)+&JQA<1-#sYU^WDE38Ac0%lqLrDJW-KIxgdvwoD(#tm8z;QBa@%!6y3Ui z+aX=xQ@#~(Y{@KpE&f~X@cW`?*y-GtWcbbv6o**N1tnSc9>%F)s`HGa$%IU02Klg| z8_fu>##ApgN1Dorkhhv}J$*b8>(YaTd@$qGyMbxgu@=?7{OM|VK0ecHuN|zt+A^lB z^sb&q{z|*0-)6uIEwHLQ|&|THyB1)N4b>w&!LW^~nB9!L+b`|)p zd=Kr!Jb%bnV~1$$y-?tjKCwF}|v!i)-TVPXdC% zYFUzP^L=(8VDb#?Ri@zr#rM3P-Si^C=P_~L75MpKTpr}_##TB)@nm#LMLu{}MKSn) zmljDc%FuYh3f5uDYK^n|1I$$VU2qvdy7sd&;>HcT3LP$ZvOXsp9iDOXtU@XwtoOtu zo_EY`nt0!Qs=i42qKAc!zH4AlCP&Z=8bahk7t?<*2aPaR0V1rx8hxtSk9Mrw=rRI| zqzUN1;{mRTg{dA5!IL??Mnuxk((mo0!f4g@2z(V}IV{p5HuhII9Sr`S-bhR1WP-!s zdKWf4D4`^OS+f&eC26_4jymza2VG|}urDZ-LVMA#-6u)oWHv~V6Dk6{yhD6EU9{OY{F5g<5w~Mh|aoc@tj#cu>0=gPJVZjnl3zx zX5rx3h$xOU&aMpmslVN>8r5DB{_#sB4pQqW&wBfuU(m+iTZ;5N+4{A20a>^M9RKIhk@_aY$8XS0 zHJr_V8+yK&H|Xlj^mN~$yzYl(3gxGSd*18|8FF}d{dXju@Nv?`q+nh9t}sF!+YSCg z>=)L8EnO26yMhcuD;YBE)sag!M74EBzjjyFCj7Ryqd+BALBKo0$*UZkmNa!s;qOqv z;>QmO^q@zqr2N>y*eKVk76l3V4!9}xZX8dc4!?v@dP7P`H0QPbM;L-HT!D7eA|W$~ zOBIuA5D36&W+hkyk9cCW=ywf*;M;zCpKjxG)RTQ1QcShxFI+TlVCupB5zIt_&Tqgv`w(KI%xM zk9nbvqbeNs7Bng&l@yf(SFdYLt51$mDw=ql@weYvXC%=JVt>gm*m$Y#I&RN{;9{LP zm1B}9Lxn9T91%SVZ9PK5f_tClO1L%q9acKeuF@~;(^5!8!jO+N8W@wPgc7a2#xLHq z)`w5qIuRxJlQC67mh;*jfmHkCRR@KM{_1ajKBKdO_XC#@prm~0ODKKq;Ps6pCG|uBl+m3M zF$P+i_IbZNkyVjxL#-i_42l4ZwjY902$G76O&uL6!KsWsmWXG}ZCC8%k&h0l z$#fIhGCAc{K@C`pBbFuXC|;pMF^z+2j6CTGQ72kbQUV)jLS5oEIp5ajTvM?}Hd(j1 z>j2YwQpzucxl?Yhlq{hyZ5luxTxe=}MxOZMYU=Rg?W-8snr^a^`qDgeA!bTlq4NtV zdvwx?oRkp;nPPJHWPa~X#t~7*DShdZWB=1V0fxe_$l7<)L+z_<1cEmzzA zp34j)S9VHP*V#`RPJ#!x%js_r+Z&0IbAd_b^+v7Ejfs|G`OZ>QUzpI?=O#*d<0bT; zzIqj2tdxSYI@A8kRjlAe&9WJ-RM?(^8$<%+C%a1urVxWcaK121^y*C)PBpmjC_}q?Py^B3k5VnvwQE5 zDU#Iu<}+EQ0MpX6e5Q1jJazWgH3~lAdGLt@!ybuB?p@HkkBE3;^#iq9;CaSsievsD zHGf}FLf$M2irl~7p}Y8YeBPrX^mjto0mz?&2aDCAy|Ydm-YN^)*SVum@jEp%|7cvq zLi5v;nUoi^sW=^iS7Zb#zk6hvI^$A%Qv?^b3SJ58BYuUBNWYD@uZ&^iP0{laB9N@p zac*2TbNU`j@@~5+N9$UY@q~|)#0%d1%VIl!*l%;aX?buX_r)sG=?B+{Vv9kR`(?WD z+?``uqr;Knx~rn2yK1YH^0pr1cQ!0442Tfg;qJ>V%S4|87Y0B3Y6{f|jE#!TvN zZ49YNLH5_OzxpIWGbiqD!;cTCHkbW}FjSKbqd<~WJI~D&IK9o0GGN2iF;Tq=A6kOF!wlMtr}>ENYzhD> zGWh|eJ#|bMaPc-xaW*&h%x8?u$k5=>Lw;^#jKs}v;*V(W*@^DY?5tiugjW)O+oBWF z!eC`g-pti>Yd7U)Y;Fn5$Z|+|)kYO4aF%OH*D*$L`{|qT*PpFNwsnnbl4epSFcHcs z-As=niRIte+LfRuLDmSZ_7A0xupg+XJ>jOWX_)qD&Aqj(ngG{)g=)TR=V1@9( zd;9342qh0!>rx4ZuROAtwhc8a$j`b2z1~<^6G7HMY)6L}DE4bp)=x}4c?P{ofBFg( z;#g${Z_hL73D;-S9nXxwNqBVc3I+)@F~KN*j2gPmhnz{-#Wbuv=rS{Sbsb-e-6Pvj zrw~VU1?5GR6nRZS;Z6Bo?pKXyM?Jwey<>3IIybHXnw`;EvLNiEt|KrT|6TO(Y zysCzJ;`XHb$=#;PMtR+_4E&#lE=@h3wcAT^O`J9^Ej0)q5Dl>wdan38dP$_QQ4iJC z@YO#Z8R-*~P-di)B!pR9l-ELr=j`S|wvBFSC~o0Xv(LH(AUY4`^5Q&3%`s3qobNfF zdm4a6AhbqYyyY{$I?1uoiKD~fRSUpbnNRQvn3J@Ekz<|?m#N*#b?Y>6JF-1~Tl^$f zzOPV#Sv`auZd5Hj;hnee8~{Id#s_X+ob6}#D;LR#ANK8jIEZ?9cx?PPmWV}-B}y+6 zlUvLu7t(jH9^dL3SlQh;RJ(%Oa}Bf1;V`bS*RZ;V%gI{w)TJlrfe9`R2DYWj-6NH> zhzC7r=`0}+dI(jnK&HRE;6~wC`!elSXNiSUQS&`Si5UHCL7SLM`PRC?a>#?VD=Jmn zCa+&qCGAq=BgS$L!@~Bpw61-+8^um}b>nD1X0qr#fjafRjYw^|5%7eLMNn^`d$v|3 zHS`IJrZKhgWrl)3r^{YBE7kl#SGz26ECZ3xwYeoB0)d{_kB@xNX?* zg}<^Jb1;TpK(B6;3A^>rpQ!g{*ugpkE~#&;&2XUHDDE9|z8nqxyIcpq>cup=ON%W- z=2v#3(E)X4ZoJ38i3SRK+a8c&*mH?cKrQ2ZuEAAB03I#0G!eZi__G^99^D8CHK%6c zFzMYLq*^st-n2@c=1P36EvkA^g84mzgKT>!?g}3EXGip-Pc6&BUmrN*j%#Mu#un>j z%RJ3j`YMDbau>HPD%Pa3_`A1rWmFZVx_84DT|Ys|wAHCl zuZ4Lk>%~hri2iIkq(3`3tqU>uib1^qL!PwgjJ&<~)Z=4cO7%p$er;R);N~%WI=L3a z#lRdNk)y+fjyPM&I>P~Q-|OVS2TT{x&bE@n0ZIuTAHVrj_AOvvV7lhDZAn>fc>2_H z`t%0M@@11v< znh0)_*Z)wDi-6hq$I;RIWVnYDr|*0*w6td3R8f5$_(QL)J%q!H%xyItG_KUq6;XP` zr5%xrkmnd{Hxv>B43(Lt%oz{H^3z^7Rh)1^m{K7Tv_1cWV7vi>fy9HB3W;Z%<)WMi z6InJCJpzACR>Sk9(8*f3#rCbcDO2%5R&2rMzSJ(JXwOcyKI?xE>wM5qsQ0WE)ug#TFG7B@csbVtao4Osz~OqRTXq_ z1S5>@YlMTHQ8%2#UP1q~`)tf&XS&}lDf_;KuRUjyj6mwse4B_)LP%N|0J)^)%V?2< z0RX#FgM)q+>m#SrBLW!7T+z@NLUmu6Qs?xu8}z;N3EU-uf>j$&tQh<5p-RLyj%DL~LPf_PUFyDj$4`J+-109s5cbs*l|70*CNNcf)=%4e5;YhCoX zHREv$fryH7t@k^|Lg2i4fzZ;bsIJCtIX5hoDf}kpPA=+jg749IsocnM_Heu4`!vxQ z?61F@T&oy=46!e=Gk8g4-ld3U;sMh=3V=_@aJ}iSUYqe~M8VQfegm*FsYZ+e<(e2B zp>)fgW(CiUa%7yPOsLyr3ryz!?7!8WHzTC-6bcWtxYr4kHp0+J3x>c+#r*2~Dnt^M za~)19s6R85kxDYZU-AP`4g~&=)vt5NYSKh_RH%Dvp{j^x9$-8li^tTeU~(kDzHkBn38bMIH}dHrKUu%L@~QExc&HMMILC&D zOg^aCHbS8T05w@gzVIRr%9xmC-Wh=1jG-w{zq;f`1AmHpk0NDIjD|sL+OZ4m2!ioP z|K5vvo#S*DC`Y297*m9(ZCHS>;%?@~M$o`qhaCS)$C4X3Ybiu_&&l(NO}o&-bTU~S z2h!7Y`P+JTZvjK@#Mc7(w=aVP)Vd^KSnxT`IZzeZUuBjATsKpdtGBYA5?vv!| zgh9GWEUlQ}v{y;hyv8-};>cWoLLk6#i*zt4>^z4v$HiHvv{|@V$U!qg%$xtwx#xU# z&W%Q=22neow~#Jr#g<7UZxVsQe{Q5M3 zcHiYEPCak+O_w|YQ^MX|Vy7~>9K84t^-9}Ri zZOh97+7Hh`QN^r0Am(XD{QC-h(D)ZgN8#nJuG;tqV_Y+D>}hTr#Hw-ya3W{oCiFumG-zI{ws~h;HgI#l|I(WF=(`QOKxPyr zps5*ck7Fcpb*i>Vp>g)==Oe3|&E|Hp*Pyx0<%uX=LlzkLJbn^gMsR@ zd)FeFS3NFc%pTa4O*w#T8Cb#+c9ZFsJ>aI(=OhQW)|GZ-Fk|~lMi5v^7ifURrTYSQ zI12$9 z;Fw!f3}duT$@DO@U!yUt^n;-X)DOXot(H}D6E(CjCyG<*iIDr5tyA)W0VWXfpXhlE z-Uq*ZIIU2r1LFq@O|4LvS}ZSHz}Su)#(sKwQZg^q&R)r!R#p%{e!>t^2XV6p;6pwN z8Svl3di$`A0|>n|Kp2QnMKO(3mw%(X2yj$!hee2gyJ&U6>oF`pVcq+Ge3F-w#O}TC za22<8Cx7&@f=C?nR1J^sHdu$Vb5z{?c0DaQ(wkCXi%zZxKb99)rcnPQIR;+h3-Ya5 zOuEiLh{V}+l@aKz=zP>CkvTDs}%MnH|dyG@K4Uo!GyVOi!@t;0t~OiIAPIH0_hNC4`f@94@{Gsd z!;Dk?0@y_BU#{7LXd?t7#?+9`=!X`9z24*aen%xY3PJ2U$Sy{IN6pLAw0rw;Ennv8 zVe%)d-P3;3d$PNd8UC|63`kblch)JXr}SxT!=rDDNd=Y=-?q58Y9%C^oz}47DRaFK zGdIQ2)+-Y!E?-IY$-qD{ugguQQLoikO444#QmnbWW?L+umoA1+V&qL#7=U{IPh+Ld zzV3hk#;q$Py(`!5y=z^-Yh9BhOxDsZz)*aFku_j6CNS@&n!`_W0~_GHOJEkou!?T**UCEfxku(s`Xm2?`J`d?jE}#AO=Elb1iIcbiJJ}Y@ey^kEJ=oz! z01>*?ur0^lJCc-@6I$xJ32LJ<#q=EH_ajz!&vw1T3JS{sXA-}Ps#j`g-eLkKNRpAk zb)BiNr`GJ`gCWu6TA`yj0m_kaH_aZi;)@oKgstv8X`U^1=^|5crA_)b4EAEph&>~HPa&?$Ar)7|uOc4NNh7>D_iPvMJ0xFBwC7-z0q(WNlCcdC6=y+#{wJeBSp9mqsHUeJ$XLCI)huL z;=)mI%J6TLoL~EJCaRwJhnEsJSo{OhU#l_?l(fxHCh}>VeT`ffER?gTMd;oCmarVV z!In{X(h1Y}t_QCk$0(-Qh{brYr zwXV$?1*l)rRbwL%f8Y#b+*6u!|PjhLU z`aVA1_Rz>r7)A0WfI+Qz(UiP7oND3NfBp9^E{ewRlDf4yTjrH`^9j3k(&u=cQ;kbb zR>+RajvOf&)UneKaWN?kTYM=yPd2S{9t;9TqRt~;vAeoJ%=+eKe=0$<9AiCB&x4QE z`-n3Hv-8TtWl{@vA~%u5)&k|F)^rK`DU;g@d!EDVM0=Bd`Fa6E2?q118v z&)gpZS!-+>SB7BS@x12&iotr==@pj$T&#Kh^)~1W$Nvoe*p*kc@@F%u`%1pl{`7nI z5QcCpXuvDKpQXk?*%=cocfSJj$1DJe=x8K?xC;lZPsJU2(f4A%UN#Y zk?h_FE`bmY%3xZqF}@nrw=sMnHWmdHAsG&W!bXw9{q^GdntaW_W5u5CqNkQKLRzvs zb9W@?ZZ{L4XXB_dF(+@1*spK46rE1}RW`F(<8^vZL_%bwAh{wha$BS6p<~n6yVx0G zf)u<>!5s~;r%fxLUY|(+#O!&{UVSSpwc)DQsgIMGhP%(R2h{hI={we@x{nOFztTI9J|JpJ^Gp5 zKf>7P6;IZ9E7Yz^6ALLmz|r<0q_~d;-dti&M_z_|?g{H>iuKO-9!Nr6_`N0Uv?+VZ z`_4m868$r*uNd`B#}&5(*pnZt3*(>*MLeK}(59{T_v5Fg&ZKoGlg+!G?R1qZ7?y`~8{hc`*VGaAzD~T_O-c_>34bCws zoBUE=6$Y1wtIZj3^v#$TOiGhxG z4j|5`>XnF#{ekpBV}c_y7y7idFX`G$_fZ!|rP-Mf1tb^Ss$bNZ;+G&8st#CQ;zF65 z3)qV00?C@01~a1?wQ=Gkp7A(`StH~5Yv8#bb^gWleX9#BK&woQ4tB}g_`6cgZ-0$i zycy-WwmgX)c4}O2uM7ZU@23my0fI(WqhMi=p3!SF{jbL|qYl}J1A^ebX~wPhq`Ad- zs=G?bXayQq8MtGZ5S1)wME;3v&Gx;@Rhxd$s%3rJ814*>TROILqwm0{`@iUV51=Nr zu4_2bL8M6ssi7nyMFEix287T_f{64cARr(e>Agu2M7s14K&mK66%a)cDWQsVX(B~> z(eFgx=YOAhXa1SY<<8u>Gq7{c-fOS5_CCC0nJS5M*5}8M+_>6DbI7aObhj3C5S~E^ zz?l8TqT?ITlurJ!KYnxMtE+ppM$HnN9q+Am0s@s3I;9HB-}^7K35b3 zMV6?bSO9<0+lAgF)_F%8E8g+lHuGppnZ5@*F3$3o_8G9Wgu0FBPXN9{ zEcfblFwXR*nE@jkq!12_*b@;bCs9l}MH!&DK>QF3LH3bIyo0)NwiCslWOY65R zkz>QNX$I|GTDdO@rf+-(zm$#ETNb^?f65GwdXB(jPieLuT^ePPe<}tlV(XFY2 zBO;8zPG6>IU-5wj92^9Bi<0{ujR zX&o_S=LSHBEGasAFMZQS*0NK+Y?UfOyaG+g_)5RtF|HzyxixB%Q{nHa5-GGr#;jGl z(deZ$l;Qr=Eylwd;fn#`D8U-OI-gOO>=^0fI;05NY2}b6R8;l zdFR(D5DX5RZb17L1zS66zAqAZU3#ys|7nB?;}(bpg9~ypq`;Cc_&1n;(c6>rAE+7W z24CO5{%*jRyZxIE7g&(Os2vcJ*#yw4)JQRTmM0M|h4+H7#psp~_tX0Yu+DLH%mssT z9O-H$?OeDNVqdJtw9$HF=#_CzYls8N=?aDpQakB@flnoClDefCBX)#itgWbUa3EEV z=Q{eHJ($f6OoWZmBg#z=6tTF7O3n@d19q(FdRi)&^Xew+w@CMAvjZw0eOb{wv?*4oNGD)4BO=3=XLwE+f89n_gG7@4u2O?*&letLj7YMGT1()v zg_S$gn+J>R%Eaj2^_5O`X>%|`l)DTn}( zz_!T?GDg{~8z^@p4t91gmm+P!-uppl>|d+DbAjx=$-ru2kT!n5p(A+|biqWbr7&su z;)UR`hgbMQ2EJ7#tX}(W>Qr)HRN^L`c57stdNfo#x_Q)~n!8b_&d ziEP_`(*@+o8sqZ-OVvzz2s4-Izt`b!2|V9a$Y_m+QDxkrjkbp0$8sqN9xp!G3WD~!=Yn2fEM!mr+gucY-P-l_ z;R8y49*t}9vC9z#_z6413@X5Sl`o9+I?|2$xwIQ?W9NW#^|rEIS{w