From ad4e9b211cbfe1d64565ed07559cd841aaadc398 Mon Sep 17 00:00:00 2001 From: Shahrukh <82996646+smartSRA@users.noreply.github.com> Date: Fri, 7 Jun 2024 15:58:24 +0200 Subject: [PATCH] feat: New tracking T169 MSE UI, enhance and new Rviz plugins (#48) * feat: New tracking T169 MSE UI, enhance and new Rviz plugins - Introduced a new UI DRVEGRD 169 MSE with integrated object tracking capabilities. - Added RViz plugins for decoding targets, objects, and header information. - Improved the command configurator for better usability and functionality. - Added a new ROS 2 parameter 'pub_type' to manage the desired publication type. - Created new custom message definitions to output radar header information. - Update documentation. --- .github/workflows/dockerbuild.yml | 2 +- CHANGELOG.md | 89 +- Readme.md | 63 +- smart_extract.sh | 2 +- smart_rviz_plugin/CMakeLists.txt | 8 +- .../config/images/recorder_rviz.png | Bin 180236 -> 578151 bytes smart_rviz_plugin/config/rviz/recorder.rviz | 145 +- .../smart_rviz_plugin/smart_download.hpp | 42 +- .../smart_rviz_plugin/smart_recorder.hpp | 145 +- .../smart_rviz_plugin/smart_services.hpp | 99 +- .../smart_rviz_plugin/smart_status.hpp | 127 ++ smart_rviz_plugin/package.xml | 2 +- smart_rviz_plugin/plugins_description.xml | 8 +- smart_rviz_plugin/src/smart_download.cpp | 25 +- smart_rviz_plugin/src/smart_recorder.cpp | 466 +++++- smart_rviz_plugin/src/smart_services.cpp | 289 +++- smart_rviz_plugin/src/smart_status.cpp | 236 +++ umrr_ros2_driver/CMakeLists.txt | 24 +- .../smartmicro_radar_node.hpp | 561 +++++--- umrr_ros2_driver/package.xml | 3 +- .../param/radar.params.template.yaml | 23 +- .../src/smartmicro_radar_node.cpp | 1267 +++++++++++++---- .../test/radar_node_test.launch.py | 8 +- umrr_ros2_msgs/CMakeLists.txt | 10 + umrr_ros2_msgs/msg/CanObjectHeader.msg | 9 + umrr_ros2_msgs/msg/CanTargetHeader.msg | 7 + umrr_ros2_msgs/msg/PortObjectHeader.msg | 12 + umrr_ros2_msgs/msg/PortTargetHeader.msg | 17 + umrr_ros2_msgs/package.xml | 2 +- 29 files changed, 2937 insertions(+), 754 deletions(-) create mode 100644 smart_rviz_plugin/include/smart_rviz_plugin/smart_status.hpp create mode 100644 smart_rviz_plugin/src/smart_status.cpp create mode 100644 umrr_ros2_msgs/msg/CanObjectHeader.msg create mode 100644 umrr_ros2_msgs/msg/CanTargetHeader.msg create mode 100644 umrr_ros2_msgs/msg/PortObjectHeader.msg create mode 100644 umrr_ros2_msgs/msg/PortTargetHeader.msg diff --git a/.github/workflows/dockerbuild.yml b/.github/workflows/dockerbuild.yml index 45bd366..2bd920c 100644 --- a/.github/workflows/dockerbuild.yml +++ b/.github/workflows/dockerbuild.yml @@ -21,7 +21,7 @@ jobs: run: docker build . -t umrr-ros:latest - name: Building the driver with the docker container - run: docker run --rm -v`pwd`:/code umrr-ros colcon build + run: docker run --rm -v`pwd`:/code umrr-ros colcon build --packages-skip smart_rviz_plugin - name: Running the unit/integration tests via the docker container and exit run: docker-compose up diff --git a/CHANGELOG.md b/CHANGELOG.md index ee8dcb9..f6de3e3 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -3,51 +3,108 @@ All notable changes to this project will be documented in this file. This projec ## v1.0.0 - 2021-11-01 -This is the first official versioned release of the `smartmicro_ros2_radars`. It provides a ros2 node that is wrapped around `Smart Access C++ API v3.3.15`, interfacing with smartmicro automotive radars and publishing the incoming data as point cloud. +### Initial Release +- **smartmicro_ros2_radars**: First official versioned release. +- **ROS 2 Node**: Wrapped around `Smart Access C++ API v3.3.15`. +- **Functionality**: Interfaces with smartmicro automotive radars and publishes incoming data as point cloud. ## v2.0.0 - 2022-05-05 -This major release of the driver includes multi-user interfaces. The driver now supports and publishes data from UMRR96 and UMRR11. -A new test approach has been implemented which simulates the sensors and interfaces with the node hence making the tests more robust. -Requires new sensor firmware, if using UMRR11-T132: V5.1.4 and if using UMRR96-T153: V5.2.4. +### Major Update +- **Multi-User Interface**: Supports and publishes data from UMRR96 and UMRR11. +- **Testing Enhancements**: Implemented a new test approach simulating sensors and interfacing with the node. +- **New Sensor Firmware Requirement For**: + - UMRR11-T132: V5.1.4 + - UMRR96-T153: V5.2.4 -## v2.1.0 - 2022-06-02 +# v2.1.0 - 2022-06-02 -This minor release of the driver offer ros2 services to communicate with the sensor. The driver now supports mode changes for UMRR96 and UMRR11. -This release also offers the possibility of configuring the ip addresses of the sensor using ros2 services. The tests are further extended to include ros2 services check. Requires new sensor firmware, if using UMRR11-T132: V5.1.4 and if using UMRR96-T153: V5.2.4. +### Minor Update +- **ROS 2 Services**: Added services to communicate with the sensor. +- **Mode Changes**: Supports mode changes for UMRR96 and UMRR11. +- **IP Configuration**: Allows configuring sensor IP addresses via ROS 2 services. +- **Extended Testing**: Includes ROS 2 services check. +- **New Sensor Firmware Requirement For**: + - UMRR11-T132: V5.1.4 + - UMRR96-T153: V5.2.4 ## v3.0.0 - 2022-09-23 -Major release includes the new smartmicro sensor DRVEGRD 169. The driver offers mode changes and configuration of the DRVEGRD 169 along with publishing the radar targets as point cloud data. The callbacks for datastream now require a clientID. +### Major Update +- **New Sensor Support**: Added support for smartmicro sensor DRVEGRD 169. +- **Functionality**: Mode changes and configuration for DRVEGRD 169, publishes radar targets as point cloud data. +- **Callback Changes**: Data stream callbacks now require a clientID. ## v3.1.0 - 2022-10-19 -This release includes the new smartmicro sensor DRVEGRD 152. The driver offers mode changes and configuration of the DRVEGRD 152 along with publishing the radar targets as point cloud data. The callbacks for datastream now require a clientID. +### Minor Update +- **New Sensor Support**: Added support for smartmicro sensor DRVEGRD 152. +- **Functionality**: Mode changes and configuration for DRVEGRD 152, publishes radar targets as point cloud data. +- **Callback Changes**: Data stream callbacks now require a clientID. ## v3.2.0 - 2022-11-11 -This minor release introduces signal-to-noise field in the point clouds and also fixes the max number of sensors that could be connected at once. +### Minor Update +- **Point Cloud Enhancement**: Introduced signal-to-noise field. +- **Bug Fixes**: Fixed the max number of sensors that could be connected simultaneously. ## v3.2.1 - 2022-12-16 -This release fixes the offset which causes anomaly in point clouds from DRVEGRD 152 sensor. It also fixes the timestamp calculation bug which causes rviz to crash and updates the simulator source files. +### Patch Update +- **Bug Fixes**: + - Fixed offset causing anomalies in point clouds from DRVEGRD 152 sensor. + - Fixed timestamp calculation bug causing RViz to crash. +- **Updates**: Updated simulator source files. ## v4.0.0 - 2023-02-06 -This release includes the new DRVEGRD 169 user-interface. The release includes new modes for DRVEGRD 169 and also introduces an additional ros2 service to save configurations. Previously used model 'UMRR9F' in radar parameters has been divided into two versions, the 'UMRR9F_V1_1_1' and 'UMRR9F_V2_0_0'. +### Major Update +- **New UI**: Added user-interface for DRVEGRD 169. +- **New Modes**: Introduced new modes for DRVEGRD 169. +- **New Service**: Added ROS 2 service to save configurations. +- **Model Update**: 'UMRR9F' radar parameter model split into 'UMRR9F_V1_1_1' and 'UMRR9F_V2_0_0'. ## v4.1.0 - 2023-08-21 -This release includes the new DRVEGRD 171 and DRVEGRD 152 user-interface. The release includes a complete list of all params and commands for all sensors which are accessed using the ros2 services. +### Minor Update +- **New UI**: Added user-interfaces for DRVEGRD 171 and DRVEGRD 152. +- **Parameter List**: Complete list of all parameters and commands for all sensors accessible via ROS 2 services. ## v5.0.0 - 2023-09-22 -This release includes CAN communication for all the provided sensor types and sensors interfaces. The params are now extended to include the params/setting for the connected adapters along with the sensor params. +### Major Update +- **CAN Communication**: Enabled for all provided sensor types and interfaces. +- **Parameter Expansion**: Extended parameters to include settings for connected adapters along with sensor parameters. ## v6.0.0 - 2023-12-20 -This release includes features for downloading sensor firmware on to the sensors. It also provides custom RVIZ plugins to log the target list data, record and save it. It has a plugin to send instructions to the sensors and also it is possible to dowload the firmware too. This release also includes a python GUI to send custom CAN messages. The radar param templates have now been merged into one param file. The pointcloud has been extended to also include the polar coordinates. Additionally, the release also includes new user interface for sensor A4 T171. +### Major Update +- **Firmware Download**: Added features for downloading sensor firmware onto the sensors. +- **RViz Plugins**: + - Log target list data, record, and save it. + - Send instructions to the sensors. +- **Python GUI**: Added a GUI to send custom CAN messages. +- **Parameter Templates**: Merged radar parameter templates into one file. +- **Point Cloud Enhancement**: Added polar coordinates. +- **New UI**: Added user-interface for sensor A4 T171. ## v6.1.0 - 2024-01-26 -This release includes the new user interfaces for DRVEGRD 169 and DRVEGRD 152. This releaase also fixes some issues with the smart record plugin and offers now azimuth and elevation angles in degrees. +### Minor Update +- **New UIs**: Added user interfaces for DRVEGRD 169 and DRVEGRD 152. +- **Bug Fixes**: + - Fixed issues with the smart record plugin. + - Added azimuth and elevation angles in degrees. + +## v7.0.0 - 2024-06-07 + +### New Features +- **User Interface for DRVEGRD 169**: Introduced a new UI with integrated object tracking capabilities. +- **RViz Plugins**: Added plugins to RViz for decoding targets, objects, and header information. +- **Enhanced Command Configurator**: Improved the command configurator for better usability and functionality. +- **New ROS 2 Parameter - `pub_type`**: Added the `pub_type` parameter to manage the desired publication type. +- **New message definitions**: + - CanObjectHeader.msg includes object status for sensors connected over CAN. + - CanTargetHeader.msg includes target status for sensors connected over CAN. + - PortObjectHeader.msg includes object status for sensors connected over ethernet. + - PortTargetHeader.msg includes target status for sensors connected over ethernet. diff --git a/Readme.md b/Readme.md index cc9ac88..8c2f121 100644 --- a/Readme.md +++ b/Readme.md @@ -38,39 +38,36 @@ python custom_can_sender.py - ROS2 foxy ### UMRR radars and Smart Access API version -A [smartmicro](https://www.smartmicro.com/automotive-radar) UMRR96, UMRR11, DRVEGRD 171, DRVEGRD 152 or DRVEGRD 169 radar are +A [smartmicro](https://www.smartmicro.com/automotive-radar) UMRR96, UMRR11, DRVEGRD 171, DRVEGRD 152, DRVEGRD 169 or DRVEGRD 169 MSE radar are required to run this node. This code is bundled with a version of Smart Access API. Please make sure the version used to publish the data is compatible with this version: -- Date of release: `January 26, 2023` -- Smart Access Automotive version: `v3.7.0` -- User interface version: `UMRR96 Type 153 AUTOMOTIVE v1.2.2` -- User interface version: `UMRR11 Type 132 AUTOMOTIVE v1.1.2` -- User interface version: `UMRR9F Type 169 AUTOMOTIVE v1.1.1` -- User interface version: `UMRR9F Type 169 AUTOMOTIVE v2.0.0` -- User interface version: `UMRR9F Type 169 AUTOMOTIVE v2.1.1` -- User interface version: `UMRR9F Type 169 AUTOMOTIVE v2.2.1` -- User interface version: `UMRR9F Type 169 AUTOMOTIVE v2.5.0` -- User interface version: `UMRR9D Type 152 AUTOMOTIVE v1.0.3` -- User interface version: `UMRR9D Type 152 AUTOMOTIVE v1.2.2` -- User interface version: `UMRR9D Type 152 AUTOMOTIVE v1.5.0` -- User interface version: `UMRRA4 Type 171 AUTOMOTIVE v1.0.1` -- User interface version: `UMRRA4 Type 171 AUTOMOTIVE v1.3.0` - -### Sensor Firmwares -This ROS2 driver release is compatible with the following sensor firmwares: -- UMRR11 Type 132: V5.1.4 -- UMRR96 Type 153: V5.2.4 -- UMRR9D Type 152: V2.1.0 -- UMRR9D Type 152: V2.5.0 -- UMRR9D Type 152: V2.7.0 -- UMRR9F Type 169: V1.3.0 -- UMRR9F Type 169: V2.0.2 -- UMRR9F Type 169: V2.2.0 -- UMRR9F Type 169: V2.4.0 -- UMRRA4 Type 171: V1.0.0 -- UMRRA4 Type 171: V1.2.1 -- UMRRA4 Type 171: V1.3.0 +- Date of release: `June 07, 2024` +- Smart Access Automotive version: `v3.8.0` + +For each sensor user interface there is a corressponding sensor firmware. The following list all the possible combinations. + +| **User Interface Version** | **Sensor Firmware Version** | +|--------------------------------------------------|-------------------------------------| +| UMRR96 Type 153 AUTOMOTIVE v1.2.1 | UMRR96 Type 153: V5.2.4 | +| UMRR96 Type 153 AUTOMOTIVE v1.2.2 | UMRR96 Type 153: V5.2.4 | +| UMRR11 Type 132 AUTOMOTIVE v1.1.1 | UMRR11 Type 132: V5.1.4 | +| UMRR11 Type 132 AUTOMOTIVE v1.1.2 | UMRR11 Type 132: V5.1.4 | +| UMRR9F Type 169 AUTOMOTIVE v1.1.1 | UMRR9F Type 169: V1.3.0 | +| UMRR9F Type 169 AUTOMOTIVE v2.0.0 | UMRR9F Type 169: V2.0.1 | +| UMRR9F Type 169 AUTOMOTIVE v2.1.1 | UMRR9F Type 169: V2.0.1 | +| UMRR9F Type 169 AUTOMOTIVE v2.2.0 | UMRR9F Type 169: V2.2.0 | +| UMRR9F Type 169 AUTOMOTIVE v2.2.1 | UMRR9F Type 169: V2.2.0 | +| UMRR9F Type 169 AUTOMOTIVE v2.4.1 | UMRR9F Type 169: V2.4.0 | +| UMRR9D Type 152 AUTOMOTIVE v1.0.2 | UMRR9D Type 152: V2.1.0 | +| UMRR9D Type 152 AUTOMOTIVE v1.0.3 | UMRR9D Type 152: V2.5.0 | +| UMRR9D Type 152 AUTOMOTIVE v1.2.2 | UMRR9D Type 152: V2.5.0 | +| UMRR9D Type 152 AUTOMOTIVE v1.4.1 | UMRR9D Type 152: V2.7.0 | +| UMRRA4 Type 171 AUTOMOTIVE v1.0.0 | UMRRA4 Type 171: V1.0.0 | +| UMRRA4 Type 171 AUTOMOTIVE v1.0.1 | UMRRA4 Type 171: V1.0.0 | +| UMRRA4 Type 171 AUTOMOTIVE v1.2.1 | UMRRA4 Type 171: V1.2.1 | +| UMRR11 Type 132 MSE v1.1.1 | UMRR11 Type 132-MSE: V6.1.2 | +| UMRR9F Type 169 MSE v1.0.0 | UMRR9F Type 169-MSE: V1.1.0 | ### Point cloud message wrapper library To add targets to the point cloud in a safe and quick fashion a @@ -116,8 +113,8 @@ For more details, see the [`radar.sensor.example.yaml`](umrr_ros2_driver/param/r For the setting up the ***sensors***: - `link_type`: the type of hardware connection - `model`: the model of the sensor being used - - can: 'umrra4_can_v1_0_1', 'umrr96_can', 'umrr11_can', 'umrr9d_can_v1_0_3', 'umrr9d_can_v1_2_2', 'umrr9f_can_v2_1_1', 'umrr9f_can_v2_2_1' - - port: 'umrra4_v1_0_1', 'umrr96', 'umrr11', 'umrr9d_v1_0_3', 'umrr9d_v1_2_2', 'umrr9f_v1_1_1', 'umrr9f_v2_1_1', 'umrr9f_v2_2_1', + - can: 'umrr9f_can_mse_v1_0_0', 'umrra4_can_v1_0_1', 'umrr96_can_v1_2_2', 'umrr11_can_v1_1_2', 'umrr9d_can_v1_0_3', 'umrr9d_can_v1_2_2', 'umrr9f_can_v2_1_1', 'umrr9f_can_v2_2_1' + - port: 'umrr9f_mse_v1_0_0', 'umrra4_v1_0_1', 'umrr96_v1_2_2', 'umrr11_v1_1_2', 'umrr9d_v1_0_3', 'umrr9d_v1_2_2', 'umrr9f_v1_1_1', 'umrr9f_v2_1_1', 'umrr9f_v2_2_1' - `dev_id`: adapter id to which sensor is connected. ***The adapter and sensor should have the same dev_id*** - `id`: the client_id of the sensor/source, ***must be a _unique_ integer and non-zero***. - `ip`: the ***_unique_*** ip address of the sensor or of the source acting as a sensor, required only for sensors using _ethernet_. @@ -234,7 +231,7 @@ docker build . -t umrr-ros:latest Building the driver with the docker container ```bash -docker run --rm -v`pwd`:/code umrr-ros colcon build +docker run --rm -v`pwd`:/code umrr-ros colcon build --packages-skip smart_rviz_plugin ``` Running the unit and integration tests via the docker compose diff --git a/smart_extract.sh b/smart_extract.sh index 1af7f6e..108c42a 100755 --- a/smart_extract.sh +++ b/smart_extract.sh @@ -1,7 +1,7 @@ #!/bin/bash set -e -smart_pack=SmartAccessAutomotive_3_7_0.tgz +smart_pack=SmartAccessAutomotive_3_8_0.tgz URL_smartbinaries=https://www.smartmicro.com/fileadmin/media/Downloads/Automotive_Radar/Software/${smart_pack} cat << EOF diff --git a/smart_rviz_plugin/CMakeLists.txt b/smart_rviz_plugin/CMakeLists.txt index 3e20bc9..50e5cf8 100644 --- a/smart_rviz_plugin/CMakeLists.txt +++ b/smart_rviz_plugin/CMakeLists.txt @@ -23,7 +23,8 @@ find_package(rviz_rendering REQUIRED) find_package(Qt5 REQUIRED COMPONENTS Widgets Test) find_package(pluginlib REQUIRED) find_package(rclcpp REQUIRED) - +find_package(OpenCV REQUIRED) +find_package(cv_bridge REQUIRED) set(CMAKE_AUTOMOC ON) @@ -31,12 +32,14 @@ set(smart_rviz_plugin_SRCS src/smart_recorder.cpp src/smart_services.cpp src/smart_download.cpp + src/smart_status.cpp ) set(smart_rviz_plugin_HDRS include/smart_rviz_plugin/smart_recorder.hpp include/smart_rviz_plugin/smart_services.hpp include/smart_rviz_plugin/smart_download.hpp + include/smart_rviz_plugin/smart_status.hpp ) add_library(smart_rviz_plugin SHARED @@ -54,6 +57,8 @@ set(dependencies rviz_ogre_vendor rviz_rendering std_msgs + OpenCV + cv_bridge ) ament_target_dependencies(smart_rviz_plugin @@ -64,6 +69,7 @@ target_include_directories(smart_rviz_plugin PUBLIC $ $ ${Qt5Widgets_INCLUDE_DIRS} + ${OpenCV_INCLUDE_DIRS} ) diff --git a/smart_rviz_plugin/config/images/recorder_rviz.png b/smart_rviz_plugin/config/images/recorder_rviz.png index dd45f9159ddb9e0d71660fb4e6fde8f7e5cca783..3f73ca377d5ba57d1ee859ced4c00e2e6f2fc607 100644 GIT binary patch literal 578151 zcmbrmbyQqUvo8!GIDrt{3GPnNfe0?ag1fuB4(<}%AwY06@P<5hynux^F~raL=grC{RIXFi3SM)dc@)f zoecEjwc}^WZ%9z`LNW@4{w8n|RdZ6ZHF0v)cQA%AwXwA}W_C1mFgCVvG_!R&hwBuA zfgy*H6#4YcE#qX>)d^dfXb^OMR`C7%M-SM~NP%&`1p=e5*FG`%D#HH^ef5gsmA{j@ zRJCtVE;+>l4)*toDN%kY+xN(U39Ife629L_U%&GPW;;4?ET%R)?vJ;-+Kw-pk|`A{ z=A()Hji{Cv`}_KgTuJ`MB=VX~yVXTD6)5^QE(aJ#7uAn{;}CgAcdz<42C5MGi^|Zy zkOVr&%pYibW(>CcLU6n0vqd%p{~{X6Xyv(&6WrF47C(1VF)D1lJ&Iw=;qaTt%X9J9 z+3;W53w=5k4BS{xf8wb45ERk4S1$Z6S3N3pl_|S3(D{+Y(DMTC$+cE{W1rggYO@je z7F-#VT<@@zF3P0Qk*dW0@{o@C7joaJ!G0ood2}mrZ{0r2T8bfCRS^%ckMBg!rh2-} zCg#gtb@zG0QgI{;{_NxC?zVBZ85RTl6s}q%{pf>r?>686G9uH5JTVzj!)i;(k_eeB zZQa~I6JNe#$$hKymyTn_2U(5_Q|y_i!v}kx;zZGxl^7P#Wptb}Uf@0r64NPngJ6}f zdyger>2@E(d3hkt9h{Hl)hV8WVH)7F%=8Uy5gesROH6io%xI!=4MK$5S z+yEwK9QC<3`PKqhO0><3kYm4zJHRlHuf{}h^(eXEdo~$3LOEym3U$F}@phv$G4e~! z?X|TM%vIE?)iM^M@97LJnuS)-_m9F}Z4e|T^#~S26_BY@9G2~=$);nbxniwgKO6*f zb2-3TMEu5cT(5WW-bj_bsbl|(m`jDEgfE#7{1>ESwv3oNQG=hF0s)q->&6nt4A>Lr z5iz>t)FoVd;6&P?B2hA$ zP_K@)dt5rP-2y;r-5#65Ay4361p4bG@$uKwVoP^%qwhq5pi}u<#zIj1fI=g1KPSS$JxqS6tPND4ikZ2yj0!KS3i!Y{k z%DF0V&~|OsY_;M&=`Bd>*^pAVGOKGFD0a2mm{;_jF{g=0fOfLs)CqmBTqfNHZivh? zv{Hr1L@#~257Ojs<5xVWvpnu4(izQqnfFC>NoYDcw}M@Zw++LQr7;AvJd=JP@!Y+* zKfVn}L*~qXotrr5>;v(Fw-ve~+Fx7m(qwLv1i02D)^?T|+ypaXdzaB`qcj_YKSXE? zdv(v4c5V*}3mK1v4)6H%-BD8f&lHEX3bnRR_j96c{3Z~9Uy(}=2?5xRfP<*gQlK-g zy3)3%h$qNa$S1f59j5o-TOD##LC4rK(IZ=9tm9m1vg9Ptr*DPZw3=@=N0HtWX4L1@ zZ9C7!6(jsuOk#RT=H3fOlXfmozoNC(VV-m}BQ?tIH5+|(#>8u+}GeZ%zKCfZLsQiES3qN@I9-v!_eWhEd?e|mpQ9^He$krb-%v=j^03W z-ytd2DN``nF9-|0MtgO%$t5#|(-HqlkG<_uJ%74`8-;AG7`;a<#`RNi7s?bb&yntge+ zPh8v%)Msn8=HMG)?_T`D15Nvq8Uq-$zgKT(K#Zzb?9WpG+2@R&Ap#TM>Vv;F{ssnJ%AgsfgdV@Y*X-cQ0}8 z8F#kb4}DjumIC`#V4v8|Gpm~`P~(y0+-3kWU}`D%5#(2g*3#Wv%k$1Pp+JnlbMC1o ze%WM;pvRH$$`+Q=VMtgP+^@y=4p~YW(ODyrG&=xZ@_DN&3cBN|Xa|f&C zZsm4iXrpM=8Ca@Jx_UkGJh61)to6w#QtkQak~unMbb*gIexB$1yRoe8ej9K1ny;`n zwAWDp$eU^L&haTSbi2(0oYCkVhbjX~d`*Nzc2DqzaRa6^;2n{kfODjh3ZrVWkmzDQ zeN5w3%P2Pywgh#>{Cg{;`0TaMop-uF&I%ffm#Y!I9|ZdiMIEj-dVHsSqM^Z*Vl%I90v)+dZKwrPcSK4PBT*4jelD#z+$J7_12YzfR6I%xhCd9Da+* zxRv7@Lk3AZp7uy|5Dfo_c)b13AsEp$Ma_mwgMFv^4_K=y9#mv8H(pVy40sf*^9v1T zTvsl}TkmiMm}o+|-{l34(a0=dt~jGq)(?wcuJo8B_q^61pG7it6w(-7kl3xTbhGV# zwWfK=k(o4}x45I+w%o2pQ_Cp)k%p6|tHVoojZg-KLg2PQT`zS>UD@EzZP#WPUk ze=qx=hWqKR4$Mf<2JAU!@j?ZggJ!dJ2Xl;MOFT@(qm5`SI(cKi3f~%l4-mfTuBUhy zU&RYN^8?8QeJ8Gt-SYHVx}tx4&*dGkHQMaz-pS<6%2IZq#m02?J!H11$&)1c3^3#a zUGaAS@FkzWPUCCs!sfrj{fidC$(~%us;8xFW_xVWF&;6xKD-}iic~(b48M6uutl9P zxondIyWg~W;hD-ok?nFOi&C%K?+F<@9>WYP-{fZ0 z3d0+IxL91aY{oSl7-IZhQ$EP%c=Az7@G@9Z@7A*a#MY~b&6w~Ucmp7_ZG|1r!bU^R zYdb#G8lv$M_^LNt(JiChnx*@kB~r-{*2)B5yjq99si|@~9;B9Wm6$vBE7{Fh{)-o> z?6dh_q!CLz;dHvhP1(x${>9k-#4DdrcKufGq@j{PjW<0v`ETohXZQq1<-b^=2vtbc z$cf+C*;y+8*;2jbopvfBbFFi5hVpp`J)^b5@{9EHUwlER5zlnJ<$UBQanZ*53j+Mh z-(u4ptyJ`9oWI;BW^Bkv#wyO+zp}h`*&ojwIphD^s6vtS!lRCCOiKPvhtW{n zqV`{9;w~XGIXNk&BDd6NOU7ffLe9qawpM*8fDAr;Y@k@F(9YRe8K&wl()b0O@iu;L z_kr+>hGTadabS{>z5F<)Dy~vvdX0eKaI#Q+Qt>yng$h#LB{uK~3KG{YM$TGz|GtUk zQY%*(HR0Uc-28tI{*3YOi%bzxL4jVjnpX5UQ4f>9N%2K?`2Qv5|NrY*eN+4a0ISt{ zM_~F!`Cc9Nj*Js5`L#& zXGc&aNT3_HI`}Q%poXq@qAIb_GIdkin@!?4ekx!5_s5hfakP`$Vn)JQfK#KBp1r2fA}-V2J7W1=)a7$?NVLX z&;7|fq_AhZl@4CJNqByxWhbiWgFy!k54LspRyG?AJ1z^1^UM9A)(9FnA;}U z4W-G@Z?Wmyh;KV@LQX2O{@s#xU|fcDCDL|z7zu!|#KgoGAW(BH^Wy%W@ul;`xL@tT z{_X?hv3hwa=A)5*y~t{2t{hR#d0m zbuh@TGMLtREAnsB_MX=0 z(GUNMr6iMQF3VVG^1pdxdFiz`*ghg7y0_S0B<5LzxjkDQc>-U7?(Pb;njLl~va=i4 zebOP1cc!khB2=gqX%(C^J}A_gOI0i;l)?j@@vF+i;7EyRYn_QbEPF|vI{VAa25j`x z!G{aP&aV;eRUzk{%e{#w8n1-(UKV{!0fP+_b2V31Rxa~Y;$d2M?DMR;QWIoiT|jm9#bu2`niYVwN}kb#!jbYA;u@+(8WEJ{n$ z+KZ5Qqtnv7Go|YZG*;D6gj)2t)EC~DH;x0FojnBWl|tK(vz=J4nf~?pe_2<2{W4di zKskFlDnWRWzPq8jtlPHSOjSQ%Juwq9P!9C@RRvqS=)~MA)KAhMOz(|fy)_}@eek4j zvDU_?RQT2SXr?%lOgL+AEPeanK%&uRb)m)>RkOh=N3+p}mzVck3$9?C&W zKeVwFatgXGnHcRY77R-7WXsJUg7xmC7U6K9U3besLz z35{rLt-n7*U@?}5_vw()saTyDC?|KBSR~t+n%?B)*(6q8sLO79+0wMJbrdc4kxsw- zfz5tbr)N5i&D!+-hxFSlcdcKiTjA+)(B76VpE9y}v62V)FuwFT@VoDQWhdLE=kqT= zoTWU&D-c?X;uA24YcuOvtfYJY{*&91@PSw5hi4u3K$c!rM}}5By%+h0+g1@|%hKo> zx>zzf9v-h((n_t{Y)K^Hk}rKghQjMdD?956m0YVof5b%fy<2BNnT=%VG4&l+9`~_u z#o154mQOb$cbk~=iVyaKOCwNO+yNj~#jIet7~@^PU!&z3rz=QE$T@C8$udR>&*!5A z|7u&8Fa6_eXOK{5EiJ8*Wp(3fH6(QO0+FzHWtxrAbLETTOFwJHY{KFS)qA!AtK zz33fJ#P;$2w8HYkq!jbzd&Pl?8=JOlZIPiX_QGNaF82ZsbSQ<857K>oZiqT)b7v(DhQu0}UYOoM*HRw0MqPrl9d({o%#&EG2WPHFlg2`D3gEu+aO9woL7|I1 zZo1RjU|p6diTIkyA$-wxd}9Hmbmwdn+v6uFY-YBl%jYWe%*xJ|V*Ucld6I0mijCT5 z(6?&fJo5@g08fS;A?kuG_4(nB*OhQ=OBK+3f9j;;eq%0%yV~2cSD_cRF^t2gpEt)| z(2#mi3aqx>M!~(Q9IUC_yXx=xid`eE6NX=*-4bniMep^YNH8f~m9O~<%S6^px;DOa zfvcRQBIYMMT375+o{+xLSSw&Sp%jLi8NvLkc%v(HdOzJ=J$W<79T4dL=%;c$?y7-5 z5Ww;{`3n;g{nN6v#L3f!fiise{oWSx?TbSok;#ZK5TgZB6n7I9=*{|WJcNz60;sE;{_RLR(f49_l)slH4<%LBJ)Of>v=S4xAmBdqxwVDYEw^s zO5F8}8=-aER%nx5=sBKDj%%K7bH^d42ZH((YgYvqMELn~{EcxPE`(>CV6hVc``-fL z*pnoRtMh0QfvVbC>FUfZsFh+76MNC7VE<6em--VG#0Wivnok#0I~^(}v1ogkdJe@= zzeYqXR4=f%rc`Qe%=MYA3B+anbjT3p?s9~YA)8iBZ-a+*j7!POo3a&ESUrJ)&%;}H ziIZjXPHa&Tr)YWCScSAD)voPSa9!?Dwso*Xk>=;?{8DG*O)?b&*YO|Tr{M_9~RM@|PU59cb*^w0%0?kg~8e zHMvb1i+-CsJBH;%3t-l4_}yTwSs<7FwN#~?PVpxaOb{ww0n~U#Gx*}6k>wgzXm%X3 z_zTBOnR0|iBhVsYU>$Y?0WtYao-(*A(C0zTcF(3Yj%vH6`(`!5y~CW~Ra^T7vsP?H z1cqT0B-jVOJ-#mX)4ezeh(+)_nE~uJzreomms0~DH@ADmA{j=LQ^{2AIS(hyFEl4q zb_;|)S{%Wq%iQ_)S6{CQ0U?V3X#;V=$Gy57rys0mXKSyMZ2Lne{|>O z+f9wPw}K^|iZ$?cUFDv_zx`aE!dj@ZH@G!)Q}s&Jwbd1}LChQRm^OQ+xB56*iRxBh zjuXCr*R#q=mj4L+^!hDuPe2D)!;%l@1r<=xI96xt9Yi4H;BJ;p2dwuBx|aIL6wDp0 zo-C#~->gwGn7*RH=DIAlM(|8EMrtW_hm7T3v*GNs>dYmn;=rl%ezu5ICE|g(g~M!# z&`0MM+r={Ya;v7++(?FJ^FTM;Lb()ErIJ8fSEEm00&n|zc=zcY9Kjg8J?;FZL+K^< zwaXwQki7&$$J12H_*6Xwgi>zr%2J{nk(L->#|=9fa(@60P8dE93xUr0&br3anb+&= zWu9{wczAePf`lCBKck9pw9m%*)P2al0&QTcNVCMOdGNHfF6GU-?vM$pINK|J>G0*P zQlfP;QbWBhG?A-cuc6-N2Fjez%*-50W+j7(j*h;+zh9}f#z(NRu`y4wT;c6L%Tz@o z_z;0ieGku z#%mico#>Q|y`d~NYwkN2wxX$dGTW132;Yu!YeP+|jwt$aUOfxCb=Y{w!f=N~C8sFd zBGSy-`!{`II+%_KvX>>`GDqsqq~Nn;3{EEK3e=1TF?n}TxTM&FT!%&Ch25ahbgp;| zX^IRDja-&Yy~S*bfGdl5G;xmYdIt=XZb!yyt1GAXgOkll)2F+$)v$<&JiTszNvRr# z8wXzZV;R$h*;tvhN4SYG%Scp&ebq4&cP()fbiN7SMi%>igim{PAEIoe8|AzXAD0wq zJTvuIXQ~C)gpzKEbaFf(M{2=V2A)Q`uP$HNdoHw5CZT-kvE!y#WUC>8d{EIFjhy|~ zus+h0EC$-Spg7U_ozW&4KPv|LRl|)(f4d@G$NF82hOHJ4CkwyVe+~SL$cwBZjmbX6+a~$d$W13Z!n^a`VSA6u)?? zs+rM%pn+u$=f}9c$kx3b!wvG*j8*Cd`&LH3gaQ`uEc(8iJ70k8sl4u9iAA1`Stj1H zRVti?+#HahFR!>QP{%yL+%XDtAhEH4lYKXx8pV389h!h_@!kOj`B48VD4t zHGe>DyZA;bWd+Q%h#ndqKWH92HTEcs9*wl_EduA!?-F&eclTSW*81e zW4?Xc)f0qj@9f+^IT`D6y0p5?^nnos0)_FV$)=3rGMNNOXA8@v!*6xLcrq@(tnkwkP7JuDSqFOUOYQ^(@+{@XMvA(!o&;-d?PR!tiLFZ-yvgTJ+TP#qa z>(z9uKbog4I=7>?@zsfb+jEbt;O!LSD8Y%`b&@(-`b;uCH*hzK4Y6zx_tI(bu+KGp zbSey1OG7v-$2+T^cE>X~smj4(WZ#OT(X{*0Wrs&QQCq`<@08n1oP!3FW-ncE18faZyd;qm-nB*{-Ek zgP9+~#eD3ayq84u5hX%}oPUg4>ay2M+OY9$Ckv|&H86Exq)(@7z6<9whzWA-UklH1^fq@%Hi>O zhWsa5$}fxa=Va8$HM31_4+oi@dC&KNe)cuv5~G~HpQlO9oRLjxmnvk#89A_hr`kRD zl9`9Grl^*l@cEuPOUEIBsOb<3PCF;W@ST<}3{EkQwq+5i^E8>8o#XDAv!3qMm0RSO zdHib6)VXFX+a><1rPgga{AVmjokPj=&=sq+RiwL}8~*n6?C95QMw2oY{OcPN-0=i} zA3Wd@$giq*$N|Fr8L`a;9%kq-IOBEuL~l(w*> z)Om+5@brK5>)9i6X>UFln=B;!!FE9)DAc-nlJPdu)Yeu`UjBFH$Do;p?X9gTrYrP# z#vsOdnz97=l0+Jp`IyLOcb>`2w0P96oj_N4_HZ1DC;ZMED$Ditk86d=oE6fNOdl7k zP4A0AiX8&?6gbjwDIf;rbPZ*c705-WqbMQm0G85H`u1^Jt;qy^nX?ph(xaEgz$<)d zk-SEdA~cBou0Eep2qPMSGct$q9SG{jE7NXGYIDEhFrT85N@9{+?|{yb*KLk}{CAVX zE($an+=7A=qbckGBgw4O1+qk9F{GJx-|aIQ=dE^_)gsa5gvKMIZ9zjLZw@y-L+{p~ zQz-zzTy?+01?|>R93p(x4!twP{bHV7MjFB05ac2yj_5Cm1DxmSIc=(~u*zjvV4q`I zelB~O=dL@eCbc-)qX&bQnn>`7!NJp{7lPm(+PA#E5hD8M9u1!`^RLrduICdTdq{(M zne<8>YW#jw&B)dZ!SXOA@-7Q8UKcZ8ZwEeNBEoQH<y4vs z1;j2NcMpLe?f%Alg9+Xe>IiN2il6HZ&OFQ;r*PB+9o9l{{_)X`$H>n17*teT*dahC z@t093ivI_(h1nfWq*SfY;RcvuGhk?QtNXW?Vsi*>f{2=#v0laTA-5!V< zlB%;eQ9y0OTYX;stoKq0_KqVP+4qVr?^Rs$ZYFT|MX2{jT31bWM{S()^l-jy7fzPd zX$N0sCKsg{jT$A4kGt%?Qk^xjX zOwCedv#91m8lG3`x}`LXBa!b>U$hCMtPM2Wl@oq9m%}L=u1P+cnmLkI>pZBd){9c} z*bY8n0>2X&bbbFD?OV#IA1l#i|2!?hHwy9`=T{|DWj;|<-M?<3F7_l01M!El;R_Sw z>-*9xd$$L}Qu7L@EM@SBR*Q|?$Ha#jy7Lh5*N|UE*r`fv-03saOrY5Hrw4A_Os`0u zxi^JTt;iM$oAsH;hczy6n{vWo;^;^{Z3cnU1DozXcLHd5xtnc?8blEsd6y}pcm`UV zkE%MmrB4&p1p&4XoaI9i9L86MUYE4Ar=gYC7QRycbOT$FZ&{$fE1K4hnpic8_4G^~^SX9DWiP z|DfHoG#ti(BlWXgtlIeZUBP@$cLkgC63$n_oLAAUNt0H0wpw+{6uKrhwBpx~;*7vm z+!OUyuJ^Av-aI>}6>5s5o$mbtEZR&PIFw3fZvxy#Va?>R)*TbgA>$nA*KT|u2$wTK zIT_O@=YyGC(q=!lN=mOqJrZH!=t7Uw8IM%IF+w@5QRa%wwLu=o!P-3!a=R0hH$2#Sy*6J zir4rrQNhM^!3yylHDMODj8upCOOxb!M2*LFhf*gJ2>FID;9KOXMqc0Q}BJuRnHp zf$vXhC(e>g+sEsVH_`@!w3I!k8S4;G*Vo0DOU|oy&Jo&{%JFYQE;k6hgD>y{ntD5H zg)4XgrS5+EdN4FEM>BL@5wo3S-Ags>%#59*k+v>&rS`I4z3xZ~KQB*}eNSy7dE~|S zjy@NFznDBFs_w_KtQY|!5e09r3K^%2rodo{g?n~Vp0ReM@`uxB+wA`eGRx4C5m76( zXB_XUk}Dz-`@BrB(=*S*T3uLS*K6{9>BOuyAJoBx|^ zrd^0Df`aXw)dQ>gP*c^H69D#Db|)bCylfeMAvDIB>IMEdvk8|Hw3xr%V4ty68x!iq zT?~!IPt=K!jj0>lUF!C&;ZbpSy8PfoL`6Y&>p(0*!eJ;#iG+gE!dY3a(@qEk0>5VP ze##Pb=e65_F&)q7o}Eqf_4RGNGx7C9&UUe_@se-uLyM*%_72w%Tm5y8_`|BPq-mwY zwACO``Nn9V1CSBH+T8&FZhmW~F(!%fGz@(g)442u4zboP7l31^H`ZDuwDN9Yg?PB; zxODG)!bdQvB|uX$Xf2#0oO}Wwiil09k5mp;zCBM%zh6+(SmjXET4w9o*^a3^WJs>m zU`OLjX$ReWz{K<+NoURoczmJpSf*oeTYnQ++uy$pycJZ*`*`F{-d>%ZNwO=ndgqlf z*|zJ(cxsy13ft}p54!)sb_BUc^M1Jb`Gs2dL=udK^}yu1KfUuj7_S`RZ1KtEq14`Y?rQ*2qsW%SieA(%z=o^s)6G-jv`>uWc+_H(9Kb6_L$$C}Y z2WLx>stEc-@ZOpC+9{E`C)o$$nh%XIsrYbw_uev=bE#2ds#oso zhKF|mOIZ}H#hw**tow`oFBxHVgR?BJEbX}18;=cED#U9%N9iF#L_5fIk>dRt8A~1S zXCbgSmRqFXC~kaW6b73hsbW+0q!>iSYWbc{8@BW8s=0vAcm7RD~|(eRjjd7k;~5 z;IpxEm6C7tP%yv0KsFr-13J5^R_e@@C^PmqLo>*ok0F@dH%I|1EY0kxsK4uN4Ncmf z_*tzU;akT?%nprv5|)EjL@+T^@nO6G0PdT1;d zw#pUDVpwMWZ9Fg_k7S{2g|BCg)YEFg3fWn%(S}Efp2GucJIgEfoH5dPDcl3wfwwmV zE^DW>Zi$w*7BWU;>(yPD?c*^qVluBs>bb{F>e+%v=2|-9n`1lW;i!z(o5esm$5|Nl zxN2{}v7I*IhfQzBX}0Y6;t!hZ@b)Cvw^6IogDux=99Uh=Oyjn!F&@E%s_EkHjutw* zKo`LN0RiCKW!pn&GM11!&F+Flsu>06Y>b@L(X){rycq^JA!gv1-{aqp1_Igt^axdQ zN2q*EL^w`nv)y~W#G>)B(pZOaxSlm>(5m{Qmf#!{ z8lcxi@AkN_Z9<3K+`&nSh4ob}-@%#obRpU};7zZIyi+Hh?n7IMt_|76=;!xhRLiu^ zKaK}=+G<=dwNZ^JqJG+kwR=wJF<{H&d|M_5Ny8wh_6;q*S@(VACO}J?vZ=eU_cNASdV)kvLpbHp5p~5{Wao09 z`3+#3!7>=o-Pb#o!e#nO8KS?wLMjNPs^v*kdVu7qRw&t`TS4B>dhZI{jcuGbExlRx z9$)?-VH}kCIqf)Ph2GNKGz6Y#uC4<()IsqjS+=me600H$jQlGZ4-v~Z@f#lR(Bo$h z85gyaE|XS3?@ta>quR!hndbd-k1xW7Uf&rzGeckN^+wJuDwG46!2iAm`~{K5tN= zvBfGzjWqeze5*yD)KA?VDKN{;)>eQs3A0qa6SnwHWju?h%wM!*d-@Y(IEOVq*>JnG zcms2jsEPTHrR=t!Qj{tc{8#GD)z^b`&O3*AR`;hz1;CRa;zd^^%~|`lndT3qG@-33 zFtpRfj~2qM(C|V7E#P#@=T>)EywuOzTw{?Gjm#e~-Ci1E(-(@V7fmj$4up*u@x8{V z8j%}I6J_^y^;c@3MWRO`Lf7qTG*eztY)?S8LMB+^u+V(`zQvopI?P&F{*A@q+zq7Yeq70Zs)3+nDNAo!+84TovhsAU_N=AQeEUjRYI@r<&cY5_iqA*i!m;Ym|iE)1z+uc z$@qX*;8-p5nofwK{Zy=0aQ+UTz0u6!2jNKgX#aTJ>;r)o#DsTZlxOng>h4gT0$d~k z$zWXX?9LcNpUGT|dn)eWrt(4l2(F=@$Aabv!gl#^$|M_+xy{$j@VS?mx8eg<@t=IN zgNCS6g1t?D|1f0EDqczNKOUIcBcRR5MEj~6(-my_aK4|K@VsI`kz9)Dl{kDqUUW`SxCp$Uc`t{Sziim8R%L)Z96@h>QF-X1XKwLK z0(sWIpeObR<}W>^GCkT(4%dU2H5dYFr_Fgrn@pY8K2R*QZK_)Jdn#UzYxHy_sZ?2& z9ET(k=+gFEHz`(qgC7RdR^|oyPEp$fS`*8m)mXh)|HeZ*XwEHdFu8Pz^-LD(TgGY*(KM=ZIvb0z>k~=jcMW<)u3Jk`L!m zgo7W~kDW@jLs!`M`Q9m~L^Dg}BWc00d1Ak(o8as4Jclb;V%W|;CIpJFK#ZD{#%K=} z59s&a5QptHt0XuzI)KAD6Vp|Gn3*Y*MF<qN>xzyRKrIAKk zs&Ktw{Kj*#T>^E@tweYaPe5^edbnSjC9u9+%53p%nJtUKFayTXuF#-y%s^e~R&4op zIkYZQjR{w!LQAsK2g2+9z||j)(>pyK-_`XoiCI(3%#5x-0&l`&GpWak;J1Hsd&pGj zuh$RC&RZ8X^C{lBf|R)PU6=w4uIFF!skaYrA{i-Ll_|5qgr=j$2WrBB15qe!$L*MH zibix%a3sww=dV6I!Bmk#;#?aw>C}7h27k4m2wC>m%MX+5KXSmOOu3Sf=vqqF=E1o& zNYZkEY;872@y}m4Bsv9LcBcl*z!?#_U0x}Gnx)R`rNIgoP;Yh{0xc_ z%IL14C(!f`w0hbr5MxT}%fAzF%VGd0~ScaBL zGhd3h6O^86z;k<;u|+n zqonQ8E2qLgzrZ?{=pH0AaP37V8B2fwlzbn-)q=_XivHgLn#lySDp@OPJDdmwd@|nN~MQAKvMoCV0}}4VD)A ztPxY7el-&Sw0|J;yd%-w2ERaa31SF~VQST3KW^7N&lNmp>GHWtl{GaXDtIKfb5k1i z^|vLs!n2B{8VnW@A`%o7eEZLkSn^N_BuRGwS znm0HxO zR-ta|I=$kwsO-KWU838gglsaCm9q@H-ue6>4b6PDUpeN9MZLp#83<$)9Qb6z(x~ev z+N>ElyAS%np6{sO5p?X4q8*oB0<6-i&0L>r+C1f=@6iTZUeEaRofm06EDN}m=p^r5 z>eMUZ@bf4a2%z4%mp%t7r)_g;kpbs4brD4wwfFojxM~WPlrP=&(97Lhj?$Ucxej|L zZcYa)Er%27)B&}{dW!=np&azCcN5&8%I=4Q@?`Ga7VYRWf`ocIB4dvXt{%#PBt2g` zZ`r6cP!dA)y;da`eubtAp1bjA;V|E-5_1M2K7P?yC-!V0G8R>T#cM&Irx_8T&-WZN zM7idy^gLwSuQTA%Mx&eY{CCb`mY~-5gh7KO{?RFhNBpR#Ep6v?2jyVR4>;zJu^J5w zIZiZ)iHD$QjT7R$>iD~&*=w<|>^mo8?xRQBM4$V|v`Y^n?MN4e28RHyPIb}519qL> zyN(=I9m|}dLx+;RUt1PBa{{yLw(uy}-^Wa*e@ezDP>Q1)k0i+=Vvx>2_ZBEalM92W z&r)$R!!rhPDl7QKIoW8xN4E14bL`;SYj-Gb81X&zHQ{vT8%M?n*)7t7oro(X24xsl z3`^4HM$2n@_YUJXx*x2}5M`V7V>Jti8FcDXIMVZrq!H_$^2`aJ&$$<;j8(b`Z7r5A zjy%Ydj4$P9?S&5pUy&Ver`Fz#PhFwZ7Ag%0Qh#fgHWbAp`&oRRJ*%mEqY#f_`zvEy zse>=PB<*fHsI(0J(R>o6R4g(pM?X_oA!SI3Px@v?H8YKl-21aybyoor`lmwVhx6&ggL?$j<oIjPHGE(onA|rc-ibh;-#;f1#54y>fI7b;uILorL;p{iN z5PY&SG8m*DuK!&Npu$;`pE>dgb`ijBaWp3&3O zar`waCco(D=t!PX($Ps!ODD~QVbR8U-s2_BTFiEMKYpv!X{WO8v{~g33JH;p z)6&+)!gzk=X25AODi6Ngtv8(@y*au`VHA7?{|>x*cAZ*D? z2CSPtFCU-z@m%?EETy;w20RSR6JkQSyg)s)km4UC5kQLcGN8MAr@;993g*mWGFKGZ zz(1J&{JbDD(ieFD;9%u1 z)yFReAW&iL|Cg99+M3%RSb*3kF8a z4C$YDSo|kty*u7M**QEchQ^xEjG(m2v7xh{QO)ux3L08MVWH`NiTFP+gOLlP=i-`i z%OHs%6Rvk#U4=>arUUA?_uva+&p%U2vn*6LQ}7f zvjCoop8sJf|IJI43Psq|9{wr2|2`=JR~CX!B6Z6CpY5(tl9O-bOpplsJP|~{hOra2 z;DQm<-kTx)Pu4$2eANQ~eeAwm{uiwOdd+t+HK>9mEOVWGUc?~Rjjasz#kp2}z5lQi z7#K;X=O_2oCi^d+K7ATmnwXzgWnp0%j-wt?A|!zEC42)Trz$nKNEHNR)s32IV*OyY zJu6X`z>uOv4z+FKwZa!gZtz4-=tz0CpgTtVrIGc7e zn|pOk2yjnC*9mh!qWtsjl>dv!nVamlgP}vC?`0z`oh?z8{!^R#f%Nii%)<77@RFc) zphvw;QJOMCu~gK9#bkc=fQ)*fq5gp34H#y5{lR5p#6nQ7m}QBq5*3C%fG{(yXtFDU zJpb4#cXRz-^m?K;`CFAy7Z&z39ZBY@ZY8iuqLsC|L@)8dV(Ld)xN%4RcKZC`-P;kv z>(tBKfC)M_y3g!liVY3NOS`BoxTmF4WBf&igDw^dopGJ%?-3VFFEx8KjthUyMrQAEet*$cvFfpc4)YV+!s#ei z3~r(ms<62b5;`ADfc<7TaTzYo&E0hV$ULbn-_5Ufjhbs#QDdtg82d4b+;Y>Ig;x6W z&eQ!MkO>uY)sAB38f0eX_|`If4oo&!a`&jo?R|+b`%o6fk@D{JKP=PtrER$zUb1FA zaw?zR(b;|P^CE?fgndj1xc0QqIrs)4U;$#d^EQ;`Meh*sG@*>ton6tCn&;fWA`ne+8D3PN7cc0Ls1Pp{FjH$_vRa{kdqu?MGfE6`IP(8Y`G)UtM-jA? zc_UWYGQ8{MnXaA2=^AwVWUp1o8hjKS`<38H^B7`YIV=}<(yg)B8LqOH_48Gwd3T0t z0^_7}+_t0q9Dlj8t~`i4%52Q&wA%qdd&SV z&fYVusjX`lMp03uh)Qo8rB~@v0xBZXYY2p!@18e*}o3sp|W8H&g6s0*ume$K%SV>P* zacMwj&rSvqi18~FBo*rAO)b4{ek*KII-%Y@#M8Eu)5xaOk8!%aTcuz!kr6m9VmWBf z*y61{M2jx+j?3_Da+WZ!l7<+26&A>8ZIb=hM8qE)nNZ3eJ*xM$v7Kg-enUpvNa@4& zHg@gL6AXGi`QiEx4p?I#V1Vm=c>QkufoS# zp>n6&a9P(gr61XR_I+AEvs2DJ<@S|5d2lQ_ewjZvC^Df!|mo1&dRF2#bhp`N za5L~u8~6U$vTV565I?zcz_-1bHRp!JA7e$IEA8PifNJ$h_2cQ^b`^SNFs~X)~Io?22bRvqGgwUH125y;|Xrkv;{@o4wIVhc2rdW@^#P{-M4@&ffc@IAnj- zX+T*hsIZ8;dE2~!igiiFSg3#Gv?+7n#|koGM_>TLM2u^hNg{m9eIYO2B850A zR;J`IRXw(jnvp`Tz(uJhm;C@YJ8+qz9Dm>Ot|BCT|A1Hj8eZremhB|0C?vt{ZXCus z_k2^v-h#4vSDV!PP+_4DWE3H}83zOCSmK&lIFjP^zd!ZR)W|6uov`||t<)>&rG6pq zOVQ+U>S;(JiuXd=o@cW*tnD9UlNguQ`vR1RL-_LLt|oLNRZ71{&6da4HySH9blXjS z^R+usM&?71*~vQzz5GdcxFPkijHg2e32T2TYLcFqC&_@Hf=xa(Gv)QE#hPtFl0QPu z5BTlosS3^(P(8f8X<3nr*R?|nk)|nJ>Sg>X&8|6QB)mnT?uk=~g3k?tbTd7w?)@QI z9~6c1w3}1*C(8F$`9U_Io($1h$Hi#pnQY=;@3pGP{Dd`&hAcFT1T3sSZ%?n%?JL=s z!A55rkBD5$W;JI91tpvR2=hs9=c42+wpJ4*Ty8k+_mZ=Q#f@X#7tTd(RQN7a@bj$1 z;slskS9y8~2d7L(?xvgQQ)%X`eHMyx z@{Q`HIF?%mCO~tgMX!cwQ|19JX>7fdZ|>f6o9qBSM3g8yilXWPVGjm*{;6^P$Unks z9LJ*qv-hK*H&3g~5EY~ce7(8OCPR&tsF?_Vg+tpL)*d-l0rHQ>4msjr`>9{%MWV&+ zhum`od07wf>F+BO^8Io6vvgUF7>`d|hBzYxbG1CZyRk+QnXkJO=|*_oM57$N zd9!76EFEvyXlBbE@K@fCdp^=?CBhs}cL}4PPFUf!2%Sg0R>jaF+P>cCZJA+Iv_JCk z950o;eCL+Z``S>-fl>zjrqj7BKl4OI2_K($p1*2j((5H2w2SdLH@S998NN)=TEAld1OFsfJP1 zPQ5)7uCy^PZ8Ton)^Yeqjzg!cV=pQZC{FS6ja+v z@vN7^>1Li$x?EQ9n=}{yr1482`Nh4_!NM38Z-!AesJ`2mk@vM;6#C+VM}GU9Pm0o( zOrzgkbmd!1Y`j|Fth<)^6er_sqju6B`JTsN^bJZ^~6bmjG}9*v}{V^Kt7uiy9D*+CEwmR2TF6=b(PsY}^0cPRMdEPBGNz&FpH%NK8)V`5>zNYi50HtSJ z@5J>!DnyjkUw%=>SZEG68hNVlG{uRLP=En);!`lng*S>jl44!YG7|iPPYO%Km(rg! zcwem-RnQ0V69sbZ=-RTJI=XAVe;-h6QOS^AEa{8Oz8#f07J_q)d+Aas{ZLFNlbjB| ziEKGR&vvHN{81S6Mn|iKXB0Y~3d@=y^eX283+6)hoYK!0b4u-P)h;oGGs{grQs zm`#_nP@`&tr2+@E1Jhpna(!vw9NRc;dh>@kL~)A~hszTpuaKd%h-gDp-_l{T6ie+| zOiQNx+)&1(ero*sR|AO-dQ={|-l~SvE5p#q`@$j?ptm`+6iaGF5w zigA7YA@t8N`P2DWwl=z1k0tP?LY+)z5oNdVcC$H+YlhU^YT@lNhKy74<=gErN~IVe zTd$n-y|^%^sjd7`(R#?pb`!Ye#AeW>?p2N_<9Nb$W|7^&+cytl%>uTk`+Bb+%est` z%=uOgW{z&L67Nveu(dCPeP|Sc>%8!rC6&VxDjTH&waQ7zTs9n4U*5(V%`mY=be{80 zmJ1^C$OLcyd9}4j2-QLG9*ukGc9ayE@;lp~q9#M(eKAM_qNp^WCx-$fiL@6i!~&(3 zxktVHC&2_M6{Qu3nmP3x-kue7ufr9OgYGg{G|kv1nk7-RRO^+LD<>@ZzSyYUXacA> zt6Az?>S8BgA(`_oMnp-zS%+jCULn06g6pE*r*B11g?gE)^gnrqPbO-2yN)tBc&b_? zv+6&rMs6{gpZpF_2E?rBF?UY+Ulo0V?S3^RE~Z6T>ea)*tUfh zxm_%4sx3Kx3G~o{DGzBm`xv=c2UbqRxlE)U%bGdNZzI(1 zh|;~UjxVkx@7NUf%xlnAq1WNzrRGqmdnvIqi=-DyRjEiBP&a(L>fC1_Pw5OcYw>tT z{n$tWJGuw+8&!wd_Klh5$}o)>M?iFecqb1i`dhTuM~|^MmZD^aO>lBSPilI~8NKEzC~^c{V1Nh*hjeESSxQH=fC- zjhJj6H1&U@aMbe4tn6J$lJkwKh5EDExLqdiOJX-o>SMMZqI44nhO|yxCDsZq{?zh- zG`^C|2mZ?fd9>@c)rxQfns1F7TO^%?l9AP+y-?2}z|B5wLJ>e}{a(y=i{evq7I~VOmx$ zv#f!$0WZdIrB1x-cAA35%7%Jw*>D!X6NDA1eJA#SFxTC$q-i>hx|EmGH)Ej^2CkQG z`y$U=JeF_o6T53I&jJ%JDWHbV)o{4+Z}=}pXHm?Q&G%xCz2X&MU(cZLn|@1&iNNku zy?<((-w*$|d9=PDNls%}$3i&FX~lK;DV6&7cAixhg&A@uYEC-JC1kl<_Kq%R_+&hV zhUBiZg#U7uq;&B!Z7uz?CmZA|Wg3S)Yvx}RZYT3lAX zCiEBg8N6sov-PvVO!~#2NT=mg=sHort*D>sWFYE8K{}y#VqvNn` z%TM*YWwHX+z13J^X@Z&Ci`(TIEHhyR9$)uRY7V+OpMR3=Nfn@D z4!E&kWlG<+H;^IS*9qvMu>r)VQ}A0xV9zQa2bwQk!UKSpeG_;tv9S%pcX5u+yEzmk zX*9L%Cylf)l}&I~G38(vPuNGQyZX_Uk_zWT6p-cc#-{01%>5<02zX<|?gHv&OaO|R+>>}`G+Ow`@AUF#-0i;e zvEPy{kb$o99Z%0nIMu1c3;He>O-a{Prw6iFX*_Y*C zGs~FfoQPUQEz-$B$KW6WBI|+)@b!JX#=?{k{A;(3e0Acq=t-Ym!4KoU1kKV(DTd5w+VF-d6MNm82<*_2nw^_qSYf^J};h_cccRFi|$5lSuM9R<0(7-5%KIADF} zr?OupK!`2~@Uy4`+wY7m+kyRBa|eLRJ%=&3hzV-&8j$>NhmjSCUwhsvgRV_ec>X&7 zM6IbPWL{Wk4=A%<9d6k^8j>UaF0!_j@_NPuQm`oCuGs*WFiUu>|5fY(FK!1l8eHKg z3X;XugO_Z>Vmf=}4;GVw1uh@WojqNs*=xAzUX(^8fT;3{S37mPLK zLG(7jgVb)6aFv_Z$WoK4jq}usT63MDXLrqLVtJe4qL3iz+ZI+s@XV@@>!kWVD7YbP zaR*rviDDJZO)DMYxpLA~31m%o1Kzq7dYK>9np#~EJ#q;~!Rys$PDNWlPB`@tkS1LHTh8TCX-xP}O zqVr{)Y6^@LGqsD!+^@)Y2LL6Sk%|(>8!iyJ^&1agm`+doP@ynd&1D86@{V$s) zOMb-G578fGchx6Z2W)xVFO_6w7(ivDfI~(8x&L$zpvrMSPhf`2z0ZcvW#HN%{^!2Og^XJ)SV; zDyH~vSeD?6f`t1)8XmcR%D|9TjP>^RUfbF6y?y((mKV({_$)rNSeW!CHkjZ`E_8bH2KJqf^pAY( zyku%_f?s=En@$N>l(y@+bK5_9_aKYs)O>?4G13Oj93D~8CU>p%Sfc2j5> z7zQk#69~kwP5d3NV8g}z3-c$qK9Bx8X7}4qHMaeK9LLnh9I34~{vD_3( z)Hd~*kvrMFCKvUcgzU?>8D|Nqp-}y0u|T?=gxCHP6+e}U$(aNaHTbNOwE>e0DlRKDr+_q5EsO*F1 zdj*L;S6}ma=L+R4-#j%x)k*Z02bSA=oqAPPDnT{nZV|jEMnMRof0+gP;YqE^j}vsR zn%+0n*|aS3B!4q%c|j70tut1h%G4aH1^{{bv3}(;TtokeM|wDUzrNuT-qbh+dGZ*& zotN%T8|i|kx=PxRy4utHWvLjexZSrFKl9?`sFI@4XO*rHcjF6k=`w|n)}~bCMNKC7 zkwMPK$`WAhsSwRC&X>FZKb{*&Za;s}Dfnz_+K+Bovg%3-`#2VK+AyIrRQsh=LQdXX zj8l$F$Wt|3(tNLm`=?GbwSPDd zQI*rBZXo4;*3dejqlB7?S^VbKmnyd2OgE;>;QW2{5A!u?dKP6fFB8h$T{(noyU;C9$bui@YaO}RH0Lky`Op z>IUBVpz4upG_o z+iY(2p@v8Gm7i;Q@hTqMcGLUpNVz`voZ!Bh5bAjq{NJd4!T98)b<>pJ zb{w_Ctp74+x!?$|A@2zwLxyA>Y&?L2W#lqDro)ag1Z@Zl$Xs#U?r z@2NLdr_g zIb>Jd^6mR`z%71g%WYT`%zjYoa_(7WGMX4w4|hy>+;_Oiqb^Qe=ZPtNpFSmGeNH)Z zz`R-FJbQL&0|)UocuPwsaQVq280+3DlrAwUp9EIco8gg`nTkHh_m&pLQe!5kkR_7| zYrBhrRLIjlZUJ%ub3Q#)qi%<>nJvsFzZT4wrtAO_%9$D!EbUWSq>-SO;`T!Fbl94> zriydlZwkkcdQ|8bNfKDRT_yy5X!Cp0pzzmC<(Ub+1Ejt%jz?j4y`pY?cR7#uu1(?j z+Csgl`o7~Wf(#6ShqO5CO$$~ZDv5PAePQe27La!iXyEXHAtEwF#wxX z9JyFr75sL7;-H*w;<*1|pLSXLJ(qr7=PheSiB(?eZm${q+?C_DI~@*1D{+8(?SlrhdWDb`8nX{m17>#u%w4`iBkcvM^dwMk*Uk}yN}g%1AR)6Uo3UZo3On1% zy}>K7_E5vPpP11=L|@h=t$=-o@d;DLemIqDQ6UHv)Zg;jplP&Ap4u0j&34#a?B8lr zg+V&&}qRhTy|HM@MvUx z-!$_k0=DDr|uis zmJ@{hzjHv2+LSR_37Z3QZ}`s8bBN{Ns^&Y=`aI2WE*R!aFbxhls!g07@k(YF;f9|^ z7;7G8EKKBE$kcTYKbeiRnKgLgGLnPXxDhen6HaBLrJJ{k<`zvY`7Z1W+$8Vof!rum z26_Kn5HuHYTBRf9*}nSyvQFr6QX)u3mBPIg*lASe7}d=%m9NTS{*)#g8m3S*4KT5c zT;Ru5)y6ZH>Oc3@Eg6+Vx_d%PcH&GX8>}lmd<=kYN4NPxrlwL|J>h1ULxh>?Pfzlm z=g#x4){jKE`x=JjQxdx3rhQ$JQJl!)gpG8Vz!y0mixQ)l{o3CL%P z%R8sOK1lkTuZtPuZ)8t;*_4-M=%$?WBvmqt-12<2N+QePpy5b3sE22f`h?WTTlEU1fW_H@w{UW9psEfnEX?T zW{a`g%{G~5j*-z+^4LuFNW)@h+PR%nMrWi@j$-|ca^^%CT<}TP*4$9h1b|-r^ZQT* zKbeZ{X@vyfM$>yz+%~8Q6e}6+9n^-K|CvXR1D1*bfWpd3CaD5_5}_kYsYyHCEtPQj z!}`7q_N5gH$>wFL5{y);@qvMfgcdZsD}fMP=bhRX>IT|GF$n=YsXOA<#@!pD*(b8e z%SQTS^KPrA7DjhQf1IYQaHuyfGf|Q7o?qWcR;&xvow8ZN<>sqfy-Ik5jkjx4JTF8I_`L44Hz7dgn?yvJC_h&m%?Fq))uYb%&?ZD)_y($Z4G zOJp>y|Lm=a<=9m<&sMOzPK}wd`I%c>k=MO--bD?p#laL1(}bOuKJ~{uyAmZ4aH(e(}LK~!-RPC3Avx5|x zHS?m}+!MUI47o+E(n|p+44q0VFK-oE})9q%I~5y(TWVu zaB@cLPJSCaK`#HOwX@$j$se95GIm_=`NI!#XEyHzy+Nj&PjDFcujn2{*a;@NS!*rb z>2iY4~6y0W4WbMzR%gX$1ztW%VCyu+9HhHBCGGPFa230{p zD#|TP!aHD$TljWS8JWW3xci&#W=e`|W$Lm%a8)s}_*=?! zJIT}Tk49nNHC0r8xbYhlg(YV12K->^flB}_uf!7FKP5Ds)6zh6&fqNW z^ge>mNn3W91}&;5|^_Ah)0P?%(GK`o-NlV@1(7R^eFI2tA z-*U6FgJ07pLbMCw;7u}m2@9F$Hmn=v?d0mu%9mW%Sa4y``>8|4KA2hQPoTqYg0M-5;UN_qEK(x` zt?NY!$Dx2wP|I6dAri$i<&=dU0Ke29-Wp=&Z9Nq&*-W--KdlP-@98zuc5P8*BbfA} zqUg+;`FZJh7K1N+6OfYT@iQ)IoL;t?O}oN^PL75y6zaic(+b&<^o<*O$KlxMSaTIJ zec8N2J)EbKVUHRxd!Hqj zfN>Gu)KO-Y%R-=;C1mW4a-3~9!s(KQ7B@JNy@jUZ_L;RMHWX9B2B}Y#{)N%r!rhfn zs78aa2lSqnV`AwwY|Vv$&&{)Iy}8e@Q#@<>%?R5~gxmb9h_re+Y9_%hOO~r1LsF&} zU_9G|b522b^qTv4dzeQ!S&3fZD)-Nq>3frg=2qWrO_o*fF7y zlvke_jgW2YmCwGDokXGn!oXF_nY^+Mw+N@~?}lFr^^Vs3f=v48uN$_xcwm+IXlKA5 zWiVB_&XcuO6+qpZJ@|A*%C$6Ky_njrIo_-xcORW^bGcj$pC~}k znY#j2j_#Ttqhq+v7FGLnD$A~rk-Ouu%I1c#9-!QgD=}8fq8!7ANbSv_W+iH$*BD)a z@#0&9lzY|cOI5v`ajclSyd8a5aC6I6R?<$D?s*!OkxZ4Ujax?2;9lXhlpbv?uaLof zeAzn#^On z5qkVmA&7PLN-d&zN-2}Myr<>er>3zs<Q3CCw@9Cb$ z$j4GNYWnX~kMC9L19My*M28>2O_Bu0EYp3*F9T(5EVNCMA2T}S`qIw5VQgvqDeXE3 z`OTAT-h5U@mg%VF8C*-=rno$+XR>e0fN|~^Ye1XPJpFIz=eL}BPxNaR78ZQ&E9l!W zs8CBDj|4?w@7{>elXw_+mVi*d-S02ZL8ggR5q>?lU3nUeGm$oB8D&lRZVA{mZ%fO{ z#;}_4E$IG<+6arC-b-MnZ~6Nh8?>LKv}@c3Vle;5?>I@jN-i^B1dERZOjfU{v#0`H@E|x`CM-FLr#r$H3tXse&!VeS&PMkP5rz>(EZr+)x z$Q6>DU%;s`2eGurssmbRa!!#;W5I;5!Xea{<8b%xTy6f+X2fKV0BHN>ww!A}zy7#H zzmsy`hsuR?bU@eIR#A8c`%HT&*MLQjQIhLQ=5FkqGIv_P_aW4YtKeB(3HWr_F+E%? zenB(VkaFaNPt`_Jj~R;qhFPji1VBv+ycU*R9I;NPy?(E6?kq-AAe3{ssmBU1n|*7= zKci`AgA`#=nG<|rna12(oy4=lhT&vof6v4M{7mfS?)5#hIklC1pSps2bh(h@vOVlC z1Ve`oGEK|5{KZeM2?K6UOLu&~fQCGS18Wd{4aQSh%%9MYmT7&PQiESebodH114S>P zdM?-tc0PS@ z?UNcmw8L5R<`h}?F~|%3=%5AC3V?NDzi{ka!-3Dg?rCtY_vbuTeEZJyn` zP>rkhhJjEWXLQakf$Tm_uM?kxUFx;FE+&GK?G>J>*mKYM6oA*le169k#tN}n z%6A4IWClPzJ47APf8L5ZywH+Wu+W?d+DHCXlw)rw{ZqAQ3i7eulWx4I%1|ZN*0QR= zK((n}$Ph<5yAvVCUw<_Im=Ahx&PZaMlg5`dr&lg{p%&YtNEaMfsaX!v*K$JXT}(P?^&0 z{hh7BlI1=fc(bI)5ck}S&uo=j%bR_&a~0RvNKDVUzUf}Q%Mp2cO+$fs^0(tQefBzP zffDaYgrxVM5Yu>IWN+=;j1K(11){#!9)W>@Y!{6U4GlqLjBq@mj!X^(+d_^E^GqZ@ zE%kX2irhNCEz!)(N$V@%$fjw`v{(%RF133e#sR23pXf}jfgM3bT!&+_qD2XH{6@rp zY2_xFQ{JJ6lB+nV_eFknzu)$Bo{gmQUT*0eDKzg7apQMm%U+t*%A?9PD|c5Ib`t%TlW|*F)IZtNzt?# zaHT;5zy;*I5kz;qPQ<J!W8Sb8*3ME0h8vcd-C)n1H+?pE){X!VTMD2`YcgQCxZbb`d(*92zA#)4f z2dH7Kn_wz3M;zkjaPK4#oR>k90yDWIlZ@-;^;!GO5hI~!+6nJ2vcbb>fIUgfELIJQ zOnuxUPL$x~{Izf4vL;J>_e`hvY{{l~c6Qn{lt5AQ6y>finf`f>6pwNhlVfU9P+Z6uE^T_+zyH;6ln_KZ;6U@$-xw(b%l zXV-DvalVU2Hsn+Dg{Oy5)psL85j1E1-zr=uzVT@zMU?lXJFjJQ*Ws$+HRgEY^~xHN zb2GJ5<0hj_-6$iid5@g>`gkAtes=x|sfc^rOZ(PpR*iywR_OdVA!3rzMz$Ov@BVf5 ze}mJF1S;%tl5Tqicrct%+T$o=Gn87Ol#Efb$Lz|%dxrA6W4zzy<*fET2VXM4Xna$B z^fy9Sv~E?T?uUll5cPHKVC$viO8PMj~Z zYAXq{|5*?SqOx!;F2u&(qeDIYcEjYx8WU#@O=#>7^O~aKU$p!0J%|{v~ z6R+Y#_V{4EMoo}O z_U6`5+owbV*DJHxbe}yIDN(qivJbA8z-M%igH*sa!O^-rC}O@~RA=@Pq^o=Nl6PRW%Ux{p;7dQ za_8!8(rj*vwj821Juk7|IU_ff?n}#>Iz|M+eo_sExxr5#-@kL45n#C!>pv_gb z@#!N+)kT-*VQ1`Boh(}qCkK_o=QN&QT(;9y8P^7M63Jw}k>h!hW_b`@c)dLxbLgl4 zR!aS@#wF*L9HiQ~qv}$@10B}4^*bC2Lw#u1>)LkIjfxD3mWe;85X-aM zm`v>i_oRKD6Sx1QGvBjWs#@8!5<^a25+f{bkLoE{L8T4t<5`3M-id%qJO2?ib<&1= zVqzlxm_S^-26V*2>N#}JVJ&=TIC?VAB>Tf`cwv;o=jB6<6_PTr>}FRObIyg7pEJ(l zPJ&6c{S=U?v)bgFhu%-2yP2kc1g=4w`e(HKe%+~qSCzu0G+!B)*q73Mic>MNDOkqt zW>Oz5Q$iEdx}obL+477(VRT9)Hmb)RJ>KaJMEpu53X^3kIv*UAW^Bf&6HlHY$Kx0Z z$A1aw^7yV~+LRXnAE)H6m8qsb1N$~O#qb<+Gg&vE6m%#AQIytXsURx!d>YbsYfcK_ zlW!Tfi-tdTc(9wpK8CYgw|=TpODNbW`gB-AKQC7Bk~XT`Zj(<$UgpDx?(5!UkJrKJ zO`;zLezioDQv?8R&!Ld_f9VY-?23;THS3ujp9F??-N!zdENS^tt|1%LydG>$h5b-r z|HNl`v5HdE?%Ryx4sQ%ZpJ8x!Iy@7e(CU`owQw>G57-BHAAEiYk7AOKw(J|P&G1M8 zT~kcnH3?cFwBE;r&`;rW`?Z3=>%96myDX71x?HB2ie94p9<}-(UN*)hczJ3z#<(A3 zPR2HuIU8g=dUKy8;9ox>Qz_Y;C)?w}cv5!9?J+ij>+9>Sg$D7^Y-z`qk8X{guL;X) zb+GB9fPl%nkmJc8;6}kCnx(Vtjvon`g1ZqL-kSU0t=a?j!^B~Zqh&9hmLG#wb^1Io z(Iz%)OL`#4-FvZ)JIs`FxNlEKcIsTN7&IX)W1CQlWX!M`Zjg2SN7qnP*P&{zV_DR+ z>@sP+YHEA!;nL5u;7%>O)GK5Cz&8MPVd+|#=Pg&?lneg+WKU#lKQwT29L{DM2MuNi zd$j>}cNU0>X&N$G-Y+d}A7It|mdaPuKAL#FbV`X!Iu$un|9(${IemG85>Wpo`>9a! zpjw#v2j@QU-bzhBo-0MSo1=x4!6zipQ``NauGR0yj|gce3SYq|!5=bd$YVY_DhfWJ zglo5%iYApUwY^&A6)v_Ad6&=0?@A+650G^+?43oxXuxoW<%Y>hj$J}ZD?ZoMuI zSg3tXLqMfdO!>uaNf7svb~u$(xY@TSzUwQvWM{SdGp*(De8=<%_2~+`SlUQjnU?`K zoxS7gyOrud8;wqLmfc8(<-~HKyIRa?g-}?;%5VGzGzCRH(d6_oSIHEUXKuOn<*oCc zm45Ms1sxq7KOuX+s+Fcz6DRd6#^;__q>#(JjiuA3f#O zJGvBQO%-aA8O!`AccjlL6ClQh5Wu>|!`Y2Z3usMhT3&8{`k7(cZ+t-mm@DqGE)o*X ze?-93*avJ6gWX^y#-WKNVlrNJk*fpcpR0W(64S}U#>CA8;&vsoHJ@*Z6*CPsGj?yX z?CZ~SR}K#($?>mttx8Zde(z5q0N3!VjZIPXr}!t&k7pjK`WNUoKC>elHr-r`(I<;c zDB^*N+eqypjG=n znGcgffQ?)xi^Ayd%&rOjHKbeW>Uq|$@Pxn0S6tn}QlB(dnUDUG4)fP)+!n)W(@Cb8 zTBKIQLyp8U%OsVoywAw=|0flJKi5O5tgQU^=3971${sw4{9((DOk!f4nk9>|R;V+y z9>EnHc+8)59`T{Ee`)hD26xt3TZFmX4`u2ce5lT7g}wcN7rwrnXzh(w2~AL{koJ@wB2p9_w@eboQMzstcTQo`Gxs6{E+)8_dMfI5*x%<#rA4#^yY6uGZhyyb zecNhbR+gm_4mXWqAQz0L>*N{P$Z?o)Jf`U4xP396n8ZL%!IWH4(j_Cov{Ej3+|<2! zaU3V6bL80BDJ(0qc<^*D?z2gwaVC_}ns8e9Djh1D-#_VWc_Xq|3SuC)1T}gS|4A-0 zR+0{YXTQ5ir6Je+mObl&fgL)m%0=?;seiC`Ff>GK{^nq2G7mmBV4xwnCmhMOD%fYs zoGL_le}wj8vu&xPz_Zl2RwYeLHcz=WcR_dcU9VOKr(n`cKcK_AB{N)u;b}uM)(moU zp}bjFJf&G>s=qgOEn~z?Ywvie^c1ou5MHbso-H57j=Ruyzh>?zTAufMl({NV(7XHE zxU(lGn1V)!5{qo9gS`0cqey)_c9&ae^f5pmIu&w^Gh(6{NOKR8GQ^70MHmU*M%f6Z zyKhXTrV8HWvEdPcFpLUzRkegguuzTY8GK3zyNn&r{PKlh(Q~(C?dEVahX|iFHIoJt zAjc+u5X0T=G(cnpkiBBt>+!x4=TT^FjC}dhYsH{i#s_4q7&4=Eh(_mTR26G~HN9ML zbonZM;Pc0K@h*O$3+VX}3#7x%5W}IlPDr8$-2= z<~*u#aonjDbVH+^avnL>z|c+i_TEJb@yv=7Lr1_dz8G_+4F1XClYc}6shC>H#X)JZ zPpb6{_jxrb$FFSWOGCzA?k+hRmw(CVd4vaVhekEkM?3)RYPR*?RiJiInmp{SB0L{A zYEeMXb?EBwWiX2?crh40)Tq~F&Oan)V^isWztv1jvNs{5oXQ{L^g`4 z035$gm1b@D+L3(T$1QFXdOIe(722ONa$dlAE)Aj}A;-f{&_z$7GhK?@B9WA<`F5B8yIy-i4iKCOf zRAufp6scD)-}sqNVg|WPUI?h+w<0ZCOdf5eR`fG33}ReuVA(I!op@r&0YY5@vpak2 z0@%el(9rzF2g|GX@{S#yJ6c6$%~MXyClA$)-BZVzR*}GyB9p|njG>p)Qp?+*gtK;C zG)QN*Vxq^nm=>8#*D3Aj=F$l>6u#n@eqBE}P%OS%msHq;Enf1ZHcD7LDck??XsyWc zr)P_?&gg>qTna$C4<7FFMow;~5$c>T>wdU6Xi=ElZ?v&=@yT}D<*w@Y!cnmC&yps#W^L3^UZD$Z{mM zH2j%zWV6&XK~*s@J(&$2HyB)ok?YjG<)Dq%z`Swg`kT^!Ox zH;|MwNs;cImCY{e$8vd5N%uTQ@FRIdp^V00(VUqHCnuPcCgS^Q;(nxRO%!z1-qRMi za(ZuM>(@xWk7?Tz>I|z90xHTYK|c?ly)kiZ$E<)bc4&tAyzwtS*)ONvDHS%C(i=lY zLme_U$=H2@#JhfKgi{RC)PM4Pu7dw%AO2@S2uVsVDd8g|B2)3jirDY?(Gn6G+d#(D z>;Fn>kR5?7fL##WS`!OYa?^Kx!A(&fnEDCsqUX3Z!$qrWzH?$wKDh2#?HpG}K*r{u z#ihEd>E!wxFHKEYwpOU`lf_TUQ~KTu6?9&N^qRfhx1KpT;sPT1cQ;0Q8nEdLH=mFxpTm6u}>~8htmPMsjFt%g0IILg8SoI{i=clf{;X zyKZULz=UsSlHug!j+&Y9vnr<KjILb0F%@QI#Ljlp<{JM!13bmQNkPgBJ=qs*+l^(P^g!m`uHl7u z${Ga!a^aEpXJ;%(*`$Eg5LJ5WC@|GAS)8USI?D$SH4})=B0J|4l`k%hif2T=+EW94 zWnQG962B~yc_j^e!deSJ?zyt|^pjz+25V?Hd4FO~50S0zFYmsaLmp~ML?ussNlqyF zh8TL>@c3)v%sgr8g#p82Rbn9F+~+0Si+;(voLhMM`4O0-!{mZnuGwnj33mb8$pn+w zVaxZ|j?cCwNvk-)Ue`PB`7yzOd8yuNQ6AdSWxB)`yDSF^zMq?@vrAs$I^~$F!R^T| z!rd(?=@WF@JD{d8&2vh?6nU}5p!zxIWbIuepMA||H|tU9ttuYQQVl^4X8k?z@5kU{ zL&J%LE`K*vPXl|&qHW}O`>O52%M3M4q>%Huk|&kgeZO$ohOZ7u2d@m^TzpHs---?> z#7P4kL63(Y(s{uf0r6tK4>GC2Q7N@H1L4-fi>6pF(k;Xe`w%5~&YaKZ0071^9TD=gKC?XJr8LQ5SS z(Iz7iIdUSceM^-8+smZ-J58f^7X0J(h%Yl(O3Ho)`$l0WjxfEv*WUu?dY<`&Dd(U1ujkNm~6#z`JQ)r%gw_U(Zj zn5+41zw~=&bp+SDRi=Y}6;~!r+4z(!U2>@NLQLm{R6P}HW3bTInTZLL_gyqFV`DW;(?Ovdpyi-M5CD}Oc=}$Gikut(g+6{rBgpLOHWmb zsx-&A##iL%U11-Ea!k@I-+w;PG>xeGeLJCNx)$bLnD68;OhqOyG3JH?=hrBa(2G7@ zZ`)JcQ}YCW0kVX8SkJg^(7;UVwdc(II*z=0)DH9~EW1+b8uv4f3dEdf zyK*}WoO=7B)>?28)I0T)79mvUCOWg23*HZVJnc^W)hFoJVOXgP&Qt7D(#g+*Kc+v< zk#hf=+X1k&+@xN(b4*fD9_ay<`O5>zJE_o-gK&nu?>tbU5sMXXr2J(!7_H9q%dPts znFC;;srwx-BY;z@kSFJgB-_Ecr9*>~G}5(;q5^S8n?vBks(@_8i?)yiXWwfcM7w;Z zOJ?pp3|(f0br`cYyMQTr5y%^I$7{GPewVoXuhy0}R*(Qu>Hc*F)}1+LO5zW&k^9g` zDs*`;ec=8`Wq#XFM;DW+@9VvX)}QT8MP+^WdulHYreB^@XX_}VUe^85giBH?*8wPw z64=<7?JVrN^9GVsjO){p%1j@ZjlbO^R1kFfEEQ_NF*)~{Ag8R9;|>BV%lNN*IfkYRB#eGl?E1*ReY1okc7p;^MR^f&79@&%}&`gq)?? zb!NET@hi*Z3qA>^wy1}d>=jai+Hi>e3qht8PL7<0ywKqHnIwEE{wz{LA&Rw`kK#VO z6A~H!WagP!tL*2fU)EWqaf?^yF0-r&FDd4w>kdZ>X1)I?oJ9U1r!{8f z`(<`^7s{o%?07N46YVxKL&N=JWKE@OeSYMK1fNXNcf-4hc6+ z^|;4ecEkEj$>-LSBDG0eVM$KWtHHyMnRQqMUn#R)PiyjT@f8~Kb3H&i z2S;wHQ#5WryW{<4_e%g%B+iEj!!$eM-OEnpI^f}Q>*?@Dc-rw@ATPlw%ivPUt0W+F ztLBQpL|3);wwPhzdvu@N|3}zc2gTJb@4_S`NU#tjI0Se1L4rF3cXxNU;O_43?he77 z!C@FAxV!tE_ndogom=1U)VFK?+A~vo?X`M!_j+2M2lrcc!Ht8c5}0Ys5@2W2jRd_p z)+v9PYy+32`u)D$n5r!NpkgQZ@-csa`y2MuN6J>E!y(v!v0Y9(hJyMJSFAYwE232I zwkNtt%@|J&-naAwE+^3q56UVc{mYv71Gu$a{Zlp9>?d`z>ZbO@T#53cLxkyKlU8BjD zcfEWzp=r)XPi>m$rSUQ|^$v9-yRP`MG3W6zE58uMS_)2{l?nK5`+L&IwFeWKSv-Zd zjypQ)+trbLj1sr|28V+Q8x+b%?yK9QXe#G{9+{v0N0Hh+!5if4q|+L^0vDYB37L1M zq5kluTr;*te)>_?AT!ZLi)Fj96D^-7&KJ|TG^2rX5*UIlka5=Ya79ibE_#+Y*13 zlFw}6!}6l@0|7FQz2)U)_mUj4X_0Z&cmgtAX)Su6(Rz+Y!(Aid_+UVl?J~DPWhE}g zlD)h+uo|yiZ#?)yE$L+%h3On;W#uyW0}M#nw>a`ES5W-GwDHU2eoEVn3tS;Byh~~| ziY8^%XcIr33Ej@{FogBuzUL2xZx+@no^x|;iVc=u-!|}e&$2qO=JUB8K4#yIkJ5NO zlKp>S>wgT!7RJ3KENW-C)ymatRdd*T0<~qF>(^}+SSI=cZzYUO$(g%?8c6fWFo(Id zm;<$91j7_(eXHP%Vyi>7X58%*S3@t%-LS^^hUxC9W3lbYjvp=V-^J13O3{msZ}i$t zS{1jv=ZwYd8J(22G_fbhI-b0|U+8s9sK9>pyv4QE!-bgB?@I2)s7pQ<@m@BJwdxF3dWopnBpPUv^CL8g~0hcm9`wnq{~p z+K~AEnP0@WeuzWIiLsoaaF>1)MAjvaVY(xp6`WM3af$Y>6(Ld;&sdQ3(p07>JZ`H> z??9$ANHXd1D=Y?)M9Wqv&BD0u$px@vdnm7LUCg9-xNq1zys_#=YlygsLQvpbF08DJ z?`gaCw^?9t)Gg8)V4FvE^#K~NCx`L7x_@dNhtXttV`v$!kHF9R(c+U@<=)tB#(}af zZMIvj(8?<_4vF+hfqnI4t^Daj-W>H}CD&+d{4U%^Q#LQE%KYP%;SqO{S2Fh!q2R`m z6n3X2eg~mTZbJh3HV{Pd#!s=dGJ~h~z0cZOo$t92<1wC)JuW018fM1I1x0YtdT+z^ zS&^~K%F^?MPBB{X63*aPj6&s`!S^4q1@IOIuRB_y{C(|z$A5VdRe2NIZ$A|bAdUU1 z$Rs=V?xjEgrZE{R>0*PfV(NGR6*$jx?(|b#=vGS{Xt*0_dBTzAG7d@-pHjZ4cJwQ zRZtM7%%-NUQQVcRLRVM+Y0Ds#-Q<0>hVqN|(~bU0qq$bQ6Fd|@KflNQSyVoy+-rwU zb2Z1T5`k+VQpURo)gw9G%Pc#s$1zd*1Y(H=n=jAxpMr{>dU{U0iuk6|t@s%c`K{x` zaOT!!882)3U=tbdRDdtJc0l!9b2Z@<=2yojxh;ir%Y0<06N{O~Vth^Cr$m=ExtZM9 zV1ViS;QL$>A`^wGBe^kP$y(I8W6cVGHBq*Qqr{6(voTonq)i_RSSVsBQ4~{raaK(~ zfsHG^nS-7w=Dx~Y)l&4zP+#u^(%Z~Y_Z;>JWot4JV6gZgp@ zn|>Ab7P@m1zxjALwtz{Lr=%yOWRS|I>!EQU#VMWNFZnilx>#QVj~H0zdTm3Gn`?FT z#y*dIMV94yZ?YTuqy%p++F!4;eAM6ObH{oH-NMus=Dc^BrINmzwV~f*YE6yq&`V68 zI0sg-UyV(XZE|?HNxq@jI5}hZpOvPdQUBbO8VTgfPS&mHZ=H|2i3+we^=2#54)U6? zvqqwv$`u$CIrzd_T(MtKAg1^<}r4;M8}GkIVLQSY%1lm3QD@t7=&qbA7rS0!kC%6ReWhsu@!tINAzps#}$ zl0b$T3dW|6A8FhT(Y_Boc0rF`}0uz0I8 zK0Sm40+-YKEZ#pjs=|2^V$G0+bX(Y2vjksOpfKC@zn8k3U`!q*{{!DVr^sE|9x}ia zsAEUaMz{E-O$w?8e?WV#FPf7s{-mrgr$l>MI zx=hYIZ9@Zw{gu&L{KVMlY#%@MF_{gPrEQ;~v%&2v+x=v*K+5{fDL7!r#|0bKoub~s znJi}Lr|^KG(zk#K3|KsT^!aJ={P?|J^SYG;9GPJ>_l}o7h%k-I%W7W(U;;MN2x_qr z1K*ev^mC>Rk1s8Shbr{+Bal4crYT6hqS}TQenGdxkWnQsi2378)eRP4T~5LvYrBhQ zqB=FRn{EG@)MG8+#g36Tu^Lw){do`VtJNt?TlBc!XS~(;NTof?cKSedmPmaXb_FJz zdN+hBS@r5R?!_A0NFn*tOUH=r<@VR~j)27_oesLxEuLx(-=EN> zglncF>J(et>0#+2^FQ+x5w%`_0_;f4=L|BA1E`$MC~Ao z@9vBJyOrVW#U(AsI~^Q@l&hw1X#6Ksx38Ts_zKu$#_BQ%M;SZV20Za_bZy1KwX9^N zuCuQ@G`KJbi-M-Ds+-yr^D8PMdwsq)oh_7r>U@8DR@2~{?3Ik$P9taFBX=hfch0F^Ac3;^)Uk(vp}dY+Q>N%}K8cxkr;%7fji( z0W7{&`0DS;rqpEeWZ6zJ z6pogroZ%@e1z*N@!HdjS;j-i%dxyaSB_!%3mvL6l%0nhes{qfhbFNl}H>wGbKF`R> zuQ*YQqY?Sa)Vbwt6@Ze;@~FShRH%rrW_a!e^*&-(u_1 zgGP_sJ?kzg1x~q>;MSbb!92~Q6e?u8mfdT+vOy9F>h;bP<0yPE;LeA{(q7FwD%I&? zFhaFXv=+E6&^s??Mw9dJu5Q%(B*EkeQHeAI<$qCS|3VFTw969A2l3bc?EP#0b3@~~ zK}nL0QDttSD3sNurNLUHLW`2g%1uayD1hgz!gUmh&KqX>~OP8;vG&$GIZk#t(HEXXt1T|(q1VPj%8dd zhgukm2L2v>Rla_rYT)vN0X8>)EDpy@5>#qUAFW(g_DZx~R}$Nrf*jeKmr3u{_186? z(AFKh4OUP(mT%T{3>sbBFzJO(hZd=Bja)j@BNLj7&Ke5u@sA=+kE6dyr*X#oedTB7 z@B95PSj6=Y8U2sBI?%Q3wg?#1aaqZlR+D05JRbilj6+xJcuStEgZohmL;H*>tB4*t0@U1+3a$g|B7JM{RBH5QTT+fT`7eh-wU1xYzmb^j<{YgS zyUke))hM|e@8c_bXjFE=v(!d1GN3^Ih|;n&s8c3tFjGXG+%#-td8pi5nG&| z=g)=}4_o3`J(IXY6a4WAVhN0w^=Ax@$CKJn)ZroDv%}-2HC-7MNXa_RkM5zTnJ zE?8|>Oei6AlZZI1l#jO!1}=q`D~aoMcwg50oQqg(TPXeGZS*pak&PdLLNdt#3W0w7 zYleD#fKkF&%-dqeA66c-!C`1rgx>6HMRG^hRS`2jFVrhB9BV3y&ZILQ9QyO+H%`h!EuW4OPJz-gj*5_)$)!WH4&RXQde$d9AJ~DQ|8X4=r@aVDam}@<+qgQ6a z0#c3pqfUS`?>QeTWles%VoO=~^n%fB8mzSByHD~7<=nAm^ZnD^=v^wyne3Vx+6rBf z_aVouhl1-g&k?euNB_v=IY8c6Q71gbPVVI@wzbTYZ9T0%+O;^flxFTuumwBgAlY8Z z(M}$2xzQAqbti%3woCsp=zk7Gb!sqol+0di&FR2jj>#)y1oRRei-mrtPv(z5YqC8| zp;yd~8mY&MQdDn`(v{^vgYdXn?TELvl+<6IA~HXd zHRO)%Q@}~h5vE1SAMLfz*)22kQD!RNL?Z=dpqScUZ>HH8FE|mr2LoA@vE40^wmQ0s zMagK=PHjc`jhQI^eA&pAr$vwqiw}D~woDJUDiNphoh7AczRKIo1+h-t{9?AWbzNLP zeKSInLflPxJ~RwtCF-FGv;J5!#F3sKfSMt-%$A& z=%762tG$xi^yyM80OX_&0hH;e?gpTtXfH}v(@>KDOm+tjPff?b;D2DhxsU#pXaQ^s zPAFz0e}6!iAt)$og{LoU(w4?47tOu@f&{^_Sdq5svBWwW%~@PyqX#zg&9WeV zYeHd1MkCmJ+9MXjNv(AkxlmT+^Y#4@;Nqp~l@RQ=H!0d5lbmS;By-OL+D{SV9&|cE zU-a^*A08eJ%$JAD6z>^TuEfJ!+1B@N$^ckZW4{`I$2T)%r!r7;BOv_R4vk<-|BjoQ zK9ofqbh>$A{?=JpB2oU+z{IzP?U4DS(TIqrzD8)Py5p}iGA!9_Ex!ckydguQ3 z&z`zV<>t2y6ud#7BB)0#yjuBu_^u0FfJ^pIMPu6Y`H>5&OT+QpSQwiqAzWs*-F?$sf9GUWag|M_S87zob2h1JE>HeeSZpxgz~D_iu|T<^ zZz8=e9@yg@a7&m%v7K3n)A;WcqcS7@$x1FmbQvR~^61E(zH-||yQq&h);c)&I9fO@ zMcoh-W-4%8f01WD7ZxlFF6h-YFKse?u^l-R3{pp~ zSyol6_1>0?oYbD!eTogXCaO4EuIBTsSvXYQTT{7uZuJc4JXwVu%+_7;7CUCDwRumn zMY`nFqnY1_UI-=@Gc?BT;QQ{wN+>$p4elfJr*JJpCwAN_12F9lL!!xLy%=I3GB*E= zd!V}w?Gw({6}7b<&{WcsCjcWy;%0#;f3Qu=`3%NsUPq=-sUxeAlPJH>n*56bK+E-% zg>aKiND~ss9LHU*m+$8^7J(KaN&mUu#mpEw()e zrl8iqV7`d;fHy0XQ#gDPy*rckJ(rtP1jI@vlD6A@Fph>x$LPX?Q5}pbika z2L7FV&rkG-NcJ%&g!M}2%=rM1I zA@5F$S5;D$r<0uPEJJbJpUjoIK5ncy4rw40&Us2`Ej(QabYLlmhU(B@tuh`?Udx$n z22Ar~77>J9o7z8p?f!lN(EtXGB#>M=cc$PE2=(tZG*~2{DQe?6*zNT*H#{*&_(uQl3A)(~68v4D+{x{KxcK`0rtB%O@ilqX zH7ycV;&~v)L}9M{WxbP+Oxv)n)0PD=#Y60yV(z6j$gEFzAMM5Gg71r%Emwl$`wd+U zc{pTv8Py>bTs@h})QwbKIM$jmx z&5{|ZuJfwY`GR+;vpt=_0#6uMON7kx`(XK#TKADUC0Rzzmm$p`UQ9&k@zp8=>s-B4 zlRb6|zXAyygB6F_>$=KV&dRB&Ay5dnAAN^soq-!KwXKb4zr*^@4FAqb+MFBW>eS9p z%RlKFLKL&!swm0cS}Elj>2tY_6e{v9oP-*|aw*7#S|-<(nPFUse9$$J_UGsuL##Ah zehkT7LV9knI4O4h8ezM$y|ASZAgsNldy_?rj zxehvpOp(ENruS#e0aIp+6|W>|;nE&0onoe0&UwR;{B!s5n*~~&3c*B=Mf+;Zq60RD zKpkLfIxW?DBTfrePp!1V51PA&=kECph5vE_dI@PVpCcE0{tOEXQ3N3+t2jS&@O$3h z01!q6&zZ@uTS1Sn_Z#piD86U6#mG2y0&gG5@BoNDKyL5>3G8A?ZO3jRnduu`kv%! zoF2QbBIQ~GnUA@krILYF*G1T4nzJMOH_QUPgchRR6|bR4CTRF+17?;AcdIg97bJvA z(d)@}YueOrVKcLsu-{!@D%f-VTd@6Z!a3G@9;1EvaQd&hq|&;^aZujV6WNCn`Wd?u z|8?$_LC=YPkH)7lt!Gi`U0ILoB-kxe?k5}`_|%584cfdA+ewcy zMbJHO1uNNy`qh8`ghH~3I3@vs020J+Yt$@8p=IP1Ei>~j#oYn+ zLszKT0SGi}6dG|K;SKo^2T0oN5MDeOOkKMVz20uWxYVdgM@DfNYs46>9Qd))80qAg z<7Hg$#@7u*r30 UljY8AQsv;pM5-GU680F7r<_wObP(GsC2s>pbj9xnsVu;@wac zgt!n9QTjrs&krgTX>_~{a^KXaD zIBto;Ov&3TW1NG8(P(xsJnOqi=LsW;+-bz^mniw0wF)hih;dS>78p%e-75fZ)wCA0 zDu>)|htLvdojrzX(;K3>yx>RQ9CD#g9M!9P_T)gPnFGAh^JBkBsh-q&lf_kg7Z*`w zWpt6alC}Thl|k^_J#-NPW#!DQES47tQ!o}0L}#Q*`1=NZCAMTZ;z@hL!@u@q)U>sr z0+)R54j(&qIEsFCCvDnL6EY$nHe56Kk>YzGp1r?Ri8tyIIlrR^{{H-k3%sn+{L1>Q zi%8y5S2(092AW-h-KAP^KinUjP=A5~Y#hDVP8q?ZER3>^C>E~k%Do>EUMN-`TBF|+ zR03E6V3L6~+IwSXT8uOgOEWWZ5Zc^tU%&nqy~YXTLHI9rUl1-KQj`SJcCmkE=2C=1 zLnDEt z%VBrMw>GxXPxxO4^4;V>Cy{7$EFqu%`Al3@P*=&dqHNt+;C zT+{c*3qoaO`2}f(tuH?YEQvez+m}fF>i%orC9UQwM zn@Kf{R0!=~1wl19yCNJv|5K`TVAw3?-KcB+hwUKl2G>+nWL&L_aLFw-_CmvdMZ$k| zt@|*FJo-ZOpU;UUx3sm<`5zXT2qg~_@?7DmG>jL|gXuieHRS&)1()B-HJXml&W$-V zqyBln0bfY1phjrrE-7v?MBc-*)%P}nk#J2qm;^&J0lsfMZ*Ol5?bw2y4o0VNaV+&N zfg{-J0KuKeO8g%VqKnaAxkxOLW9xzV04M_%19*CVY{w&&}4tjaxXbf(_g6 z3uKuKywUjhz+u|Hz}#w)72Oa9%b zZV83bR<=4=S+>(%b$4d8C=!P`jL^43y3ktR!s#t_H0QpsGJt%+CoWT)DLD^Kwf0>Q zOXL3A{P7c$Zsd_PJU}LxE$u|8Ax53Y)?&b1MeflboBw2IxoKFf^+_R5LQd4@5;f{t z)5sG5b;GgD<_=e|Z@q0)8t!>m+{xneMJQv3VlA0!m;WUwE-L+cA%_p~{Z+2Jv^3y* zH_XHua^yV<^K*j!1RP&q6DP&XanIlZRnBa8>BP}H_rJCzC}F1GHyZ=eyGKb`L>@g- zblb5)74Anihlu53ZWz}L;TxykCuEel&z}Y|jn^vm=snQ?(8wfKNDj0uc&$_rvY_z(R3s|k zRwfV=&9gv2Wi9=_kg4zy-uXij8Z;@}vhu-HZJhE<3212~%Ns%c#S-xmVMm0?v*S~+ z6vE-`fv;7}ZHamcpWE7c|B<@4nG;j=hTwWZDdwL)MW3}x-+NB6#$5B>51_W*wfgf% z*UEgk<2Tsv@?K;!6xhiP17}5OVw*D89 z>JQf~Bzv5?O^8M}`ZQxr9ua)eDa+j+#96r7h6}w#P8SMa->u^jW#E2HB&>zJ?<5x# zkeC9q$%u%cqR6*Hz>pnt{Kt&d;cS%)4}XroX@a#Oz?aOs{VOm=v;bl%)LjLQ68?Yp z#{av8KorNKp(PBr9?a{@LnY^kMtAEOYAIAQc^$sr%E_$^r^;D$Hu^%dUsEryk*vm& z203mxU1x0z(TNYX?LQT{v!wHjDw|4r39M)HMn5fv*&Z|0=KG?+Fz^j{FF7P$BJV2= zv7ucu;uTb*|S#A$MgM-^no@5U1>*D>AF4A6kuwpMYb61#VfP^;Z%vG@c^?ZMZ3u%z!d z$>}d1rM(Mzi6Q1@^wNr1#Mm%AqiAs7pN5kxM#fVmtao*z;Cmzaeee0m=xVN%PTpP1 zrg!HeYEz9hSSaK{9R&ie&+OI;kTojHQ9D2Q=_hOy3^uO(D!lA#;C-{lLY)cTaW>Q6k1S~7$&&4i-g0x| z_g^mbMVeL9KR1X`j($7s{W;$sB7B&zn1`$>M&a;;NhUK~v!v)r+0rH&8J$!$-&VCQf+N^rRhCLb{J zCc)C_PsFa^9sJ6SsWwsaj|C=VD+%B^-{`-LOnG_f#Npj`x$MiYVSU*sm#>;EH!i~j^~po+z%ZckqAuh z85xL?PlXOna!t=w9vV{`sPJY8ej`bNEeeY%@zsML=V!E&Q^KT`e?4*b46asn|=_4Z|aV zu;1Y!g!9#$e2F1eLB%iK%SY?o2~4A-Go*>9#S}4GAs5#n&*9)bj1Kc|%cFVTedLR- z;(oKljwzP|lxvap4(D03_2hwWm|H&hvhL@J=Nxx?~DHu$xw($ z>Y!e}*Sd~6k=Hy&eD`jjoZUvFC0xrv!OWc4?Q!kBe&WbQH-FbY;=jL-DDmnda@aJl zE-3L}h~=7nxLHvxi}DH&kVbqbT&8kNR8S3>SvWOKyU&Wz&$-Izj^!I4(WVq%Q~48p5>bhcaK zOSK0_YVUc?pQElIY0F*xMd(l2OE`?KfGwcijS(&PJGGL7r1PitZ%So)A(vC|(HpUk z^#54+OI@d(5mZ__I>%Ry(C@t`!>nToHo_VfeRCh_sG02!-O{i$fOY&QtZ~UI7_?UxtLzh69wJ5z@16LYyy?g`1 z{icp*jioai-zAlkGsuOhiRj?Ee-Dd5JMP~hd0@;3WQl2YG})V&c;?;bJ?CPs(K1GaA21f zv9iwLS=la7dayH@#lD5KlN{)BCYzRAD2}FbUp$xcwBLPL>5Ni-BlmGKd9s_LyJO9k zaNoiEP^H;%FC3?QDl2qrZyV|gp1|Nx#U2AQxK#xTV)Kj;Dcap%ISY>byxHo(($qIb z6dZ9C{LE<9wx82(8kb1Eb>S?J;wrp6o+7&%p{g>OzrKyRd|5I8_c) zqp_tcU0HkvT0b zq39O#ZDh2y=x&GhI3Om5qlm{EF`RI)cOa_|!|UR*?5BWhLE(7L2w}w48=}{VG!qb% zVff?n9^rgxZhj5%TC0omj(7L^zCygR{?{xRmhjwR$KgeNSG*P|4`WM6*x6ODPm_E= zY|+=!G%z#&2`%9h`?b{#U$&Pc8wKGvX%_S$@Gxx7m(O;uqkOoe$wu^>Q86(nyN-bH zscBmQ%4d(={>jCUii&8`leD$=(sFkON#;y$@Du^@Gde+Ev)9}wN?cvraBq$s3lMZ| z>wMf4JFkuY%&dH*@pP^KUL#tOH{SNpP@()TOPX|E5^>RBwfgqa{jz<2A~ltH@QJ~B zrbyMb9-~UQ;R6Ea6%UswlbnE0?_v_ln^;3WNc`L=AgGMW1e2Z9bRtSMsyR}_F(`)m z>!}*405OoM-AeR?ZjzCWX>fiO2ezdW{mNYU90cq3t^Bz*bg4v*xs;0Uk$KC?FsvvG z7ZmY4V>0lCzEc&bQ}r|wstzb(x&d_Y44BtyR_6M|i8u@z$=P5CFLPD?3h`3Q=30{u4cetlU zUG$V-`RTrRtsRc})2MPBpp8c#qxXafD2`r7?YG04s$aoYlYDOHDrBdr{`?XIA$_V^onojo<( zv}9NwzxR?K=Cob*uZ$jzL;JFxjYW7^8Mew@wc8GzRF#X6y4wNMsAr3B{#j35v!9H= zy$(yv8Qx=*O1l!Ty6Clk8r3y0>4Bz1q?f^kT` zDKLIlKj}ov?A*=8(v@S69|(C`LmkF^;SdkMVhejVLHsfEbVPx=UR~H7L1l6_xqPvS zf@$e+_kqj>^e*{AyakoTl1g^a0b*VM`Eheii74K%e=L^H&~b4X0jWgx`Dh6o)B`KQ zf;nQRpegnxNbtT`i5SX1cfO6^{Fj62ph0w?ajtyH%FD}FT9z>s9pDg~R2m?UUnT<`f}x^J4oq-5554FdO zKkD=)FkiEe_h{Zc$Gk4>)+19~x-W8yaKeFxLtj;cWGoO`mohgq6ivPpX`(ioG)d=s zA^7Jary?-_g5|*N==I58-*$N!&a?I3D+#Q$ z+T#T>Tp1e^ox_n3B{dKmo$Y(y&tG?w7=%74DT8U+YiN6fU^o6n9CKR#Wu-2?HA1U9NFwE({-0U?_h zEVqlu?f)ki0MG*Q9t+^jc%l^vqwFTMzvQ%I*ZuPOJCnp>m5L`^tPw@I^>yfRW}%Gx zjyZ1X^F_6M_RU^gr>|4e+;K`mkp$t|qYJI&UL^|6Pe}u_Pg6>VF-Hq9tj*K6p#UEHB(meup|2#x zC+~OZrncP%={5AH-aL#d-usHvhV%qFQyU#Bb>(XocT=Uo4YDEf|2QfN!hmvBtJDU+ zCF&2G10OMUE&4}@gM9`P>UZ7nlyclX_TdRxAf-E=O{a=IT0vRbBYh3}aAW(Qra*nM z^-=bcXE4b_EK=dEO=s=0A_rj8PDGVW^)7@3o?Xg*fA{AH?hrE7fq3w&*z$TdMuazHdWFjgSb*TLZczW zEp7xS(bPHw3VGg1q^E-Y5(@Z-;hSU>@Y)PXTfgCtB!0C-Ca~<~xAwOGsen`WoT;3s ziKJkpkUC5^3VXBd@x}6VB1)=|F)`_JZ{%YMZADl>@LK5z)+VIAu-1t|gvWddD@jOA z)2Bv-LqS>c;M)ugf+jafm4s5a@u<@3EBH-Md$>K^z7F**l6E3aRI+wF5fwM!*ih(P zos>+z3nWxij->ujPbB10nJ?tBwrh}oNLrklCi%6mAASi_&kajooRN(~DBolBNZzq+ zACz21M(p;u^*NXL!12?^I4|$#cvV7eyN0ECwK0pI=T61)?_W^$0}%!uDfxJ4d5+Rj zU*n>vAx!hAaiju+8Eajoix0Y5%s#rmG<;igERb*ad)Th#e z2I0C!Y(se{K9CH}aGNBGf09#a87f&L7ez)YeA`QIB@Y-UZ5kICHR$ol9&waPbw6Qg zR^GQW@wQ|ha$BM9_IdFS%Q`qGlg29HIQ^R>5AU%c&9Hdt`|%2o6|1;Rl}ws#cq5bycPgXNvTegaGA@ll$-2 zCbC?E81Km|xf-y1qsq=Pa`?X)WPL)jA`LHvk1G@+PPp(9v(=EE0Ctw#an@1i~W-=21wV{m5qegxOO);JlM7K!^~E&9X}C3tP`j9|WK z?=Yf`gOBtz6;8&S^;bD-QtNdeyn;~|UQ=5O85A>=jJ!s7@J47Bd40cxYf7d0az=JW zWf;_(BaQE!mjH?RE0K6-2-TvGg&#($-D%vdG^6&480tKLJjoj0mI+z0XL$m>9k&ztFt=?g20^Gs_KD==%fJ45aK7No;>n2y;kS<5_h!2vgCSq8N zToJGYwc4TXgJTK;M`KVh9&L%GbfezTU|&Gqq*SZjlJzcm;_1Tfrns862u4RL8HKMV zTH!)%d``50ggdbq`=_~|4#Vmy4>YhG=M>A0h)oq-6yIp1c(UdfvYZq!Y;`{8^(Ca{ z3t#};u=}MEYd`INokNkVHtV8RAHQJ)MeQ@0~y!;SlV(^ojG&qxC=UYTO%&#&x zdS*_Lfw^%=gsHv7eQN)uYTV^4%|?!){J94D_(^0{6^nZKQZXu=^mLj7_`~683r()D^50*5f%zqW^EAKnI@{wPr7;lF`uW z9gf+1FUjn4EQyMAW2)Fe3{Oj`N_>`BV9DnK_VulZX8bSI{xvnm;=jLxw5{swC&YWp zvr^q}Fyhh=`v~f+g@ron+w=_0qXImU!@Hnn4_I8-bGIN6U zjm@J9#F&nd)+Qbm$FWumdE8kz4XjUv_qLF*>YmkCy#_RmMOFu793yt#@{yf1?_pw8 zuG2P%9ZxFz_*W4ZWZ_U+V)8_SR$D<}z4PRdFLcB8*YakWPT@--X{#$4t2Qob>Y(i- z_0%zFm!TRo1NJIx{Q{t)CD$5`QlT3Giq=VGU1L3k_XmEDD$dDAqylrrHX?#4b~TV` zuHIyKWd|+?AF#`EvA< zjVikzUkoz8Cvyo)_YB4O-T{IsuchyVk58X%m6(~)8KN_!Ss1?2o?0=6zxDWaXKqcx zo48hs_C_KvFSo~589@ngY>?bg%mwkT4=yL~jwVeZTLL&7RLw@`(FnJy-3lzF=r`oP zeif9hH{Z96l$*edQg`crxQNM!m~1=>fE0h#EfzTx3WlH-GRDwqXxU&-gG&frH8S-J^EDelK!LT z?PJjSDu^>uR0m{N*VOw%$cNfBbF$2JYjrjji)4b_Rq=L*u#Xuwbx=6m;e( zUCaAz^w^N)P>qWp8_%lNc{EtHAN9n&EIfnn?!zFLj)89S-Ww>Eioo%`u6R)dfZ5WD z+rEOJKtb(dE~?}HX-O_i@mX(!li8THV?%S3*Mm**$fTEcs?BKG^M-KF&lBy609%-iSZ%L4Hehrq4OC4&KV5Mb220kT?`o2!v zgM-JRd)XYg^26guGW0Ys(y?*@U0s!xv0`5nSXA`+>& zH&$ogKbRS!8p3%A;=&mj~J@kgW4EpIo^(BFAQJ z2KXEAn|4kY$*dOYnHDO7lo}vN0_&Rz*bVxJf3<_w=vI7wgmSD&k<@Hb!l{lw z5X;{D$Y|r%HIZ#x#l*DK9Sf;^s9@zXF5Tj}wqPM6_cL|V5?p*#^SjUkPT4_}x*c>0$XyX#F=|Yfcp3A~S!WwXE+S?KS613os|9w-i~_uaS1*p#9J#{ z4O~j~>=fP|+FsvpqK5r``)h7X>SI?aW~9HISA7w%kD)TIsvQA@HlX4RzYy6F!3kzQ zD7v^(SXI&1Ho8*i7DZ3+z3P~H=jSBP?+Q09JMM%eJ!L*;S0XUC!W+Z*+#@P4Y|)`k%gCv&f2HpVmV35F+pIKNDW|&DKo7dJ zzQe%OIH<}|^eVAZa$AR{t!UcAbcOx1C_q0}R}xLS43t}yUb?dlu}`d@|UG@waS#s{gu^o z_VCTICM~MlC(T5ViQThE${+->u}c#sUUQ-4iXBY!b=3WC^-5<>{vx@MM_%E~#W0QE z!?=9*Dv|OW6e(Z{CS@7CX&c+OZ`ativ7}udZir8vKdh=_=Y z$RCC{*>6f=QHnt`Ixu+_kLC?8!|@Z(v(e2)n_~727%ERFYctD&cIZ z;O(s=>|NBCL%Ywg=)k`OWQdxbO89(;0aY3>=Z-0Ps@0>dhrpx5TbSRq3dbL8V&9l@ z*hmCE@9d3#yVZo{@uzv8d^jjS@ZkDaOsx&foa!T2c5LF{?JQKP*PPlmQocSo#O6&S zsJ#JO6*2vN0fVspRE}b*w-5o*b2H&?K`p(yz}ryKf8Qn(t-*psnm0S^`UT>X1tl zspU6{bE>TP)NX^n$tzB6TgiZ$N4c@$5cB+9kP^n}5p`%f^EFwjG@?gqSEQexa`U+< z7RH9%sStLX{p zI6%)odb(JVlp_54blMF)NNCJ@@j}y)^zU{IL6UnVnnz zA>imGW*=Nbt1NO*-eyL_dJMbnM7f5YX_C>D?=Nq1+tdsz0~^(f$46Pe<20tl>Jd=Q z71PKdF6`LK{C3{Vms;ZCRRzChKJffFTXxN%Z9`)+o*qMqm)yG^!nXxq0Tja++8{PpOsO=EUg-vUi((DqiR-a=jC>o#C%1iG07%lbhHPWJJlnHHqqHNxC{#BqdRzP-x7Os(Q_)4nDMA z`wF|lHE7Z<9ig}Pv1Ljtj-Gzbo*lg@VBPU>d$(f7akmoB;X*&rJ!L2zBsMP-$()|83>yZuVqy4N|(GUMyAspP_kNn0U zgj`_F?6n-VFGBS?Rmfn9qHaZ1~h_MRtqN+&Q|HeGe4i zs?RCD@#tX?Dp@+xyNN!W$WI`bM+I@B2N8vxWZmZH2#!tZ(liT+S(Vg2J2{+W96Pg= zS;uNKvb3@u<36WGpo{6S&=kumQ0CU^*qs;LI)J$+-iJol~9jIO`r>%c4_L~%= ze%pRzw+`pcovTRA>|*?wZ)g9ZdW{L(v?)Qo*1bp{d6S*1=hLy;Ln2RZqK!ui*EOhk z_wX@a1v#GXuD_^rk^egSwqK%=IQuc_e+sTun@ZQtWyv4d5|5uSGPyiTbE@e2OmD=x z=Re7p11wwr92>u}G{}$+Y3rH{-LsKp>z>l2t4B z`3h&p2vEj5xsunXx3KNlNAlFDLn{vpR3C4$Z}STJR9TM1%$=f@D$=N|G4IZAW81$y zsIPG2!u)F3{=}dUdFGn*Y3CJnti+g{x#fU*B%%Ud!%yyEPxUCirPlh-C^ zSsCD}(LPpkf6a1^N918(YcFhaxzM8E97Y5#g z)h8aF*u}0X&A1V~iPJMGVIu)h@Mu|cDt6t$d%FTut>2bR=Ha}*b%gDE0|_tLn_k`t z`-Vwd*ZlyKJhbatnaQnouyxaU#*{9Lu>pAqyE={9)rN91G#$nL8dJ^9n2?|=?BBM7 zRc2Kf-o7XnX>34`KJlVLz7?>ayP8ucAE7LjLv0HJUrrt6ioz1#ils0E1ij*M08(6h zI@7(9dz5X*mu#9=tgn{T z<;2ksYxYV*PR0xJVFR$Vm8OQWGpDPRmB#k!COGGbaXanNrJjfR$; zy{KEiDh|exyt{RXUF#Fjk)G{BLv$nrA7f~hdQ7_xnafqDxxW*Vug^KRdk0%qIMZlc zQ*tF#bSR&*wzUuKwtOR7wT5&Ju;BIab*vj%pQ|6Xb8KQ+4d3_2{JM^kB4+qs<~!$4 zT_w`go6<#oamn?t5JHU2G1n+!!*2h}zemE6Whq7xt${X*d#5@3PD+-RC2>o{G5KLS z%L+88;mqn)3z>QRFQ%2ZM#5K4&0fSAg);#GzB+AA@%A*cJ2YnOWlO5g8$~VqpK#I* zyl0V=A>`;-1_Zt(Pyb`guAMGHzgNF>GP2jMPoa^6**IebgDbWtvmBI9S2J_t8;lBc zrEV@6$lNGW%}wiA6;B>cLMjpPEK{ATh2r+5q__t3O(${2uYot#`}Q$={x#|kDS#;g z?{>~&#a#i9ZUK}K$DE{je$NRlL_|cA6Ei;Z(YX#|CJ&~KbTS2MJ&Bo&N#yrJd?z9z zA|krc`{Q4+ApLbLy@oKY-5&hs&1bp92H$CuX`WGH@UxAcEzr`tAB*NzRe!t^&i$n= zsM>8KeFoRUcUfKRB@tYh(ueuCO{p~P2BS83!U;Dx|T5Cb)b;lW7A}Ro_ z>|O-FV*NN6xQjPU|H4%geO`@orD3!CeP>NfVJyota71l3wcf<=asC9qnaC+sF-DGR zgqy?=8&P+L%W}|c(tLVGcQ$=I#@{vSGJR4HX4E>);Jk8BK44Mb@tjo@W$3=03@Q}W zQ>pA9NXznVS=Dzm0X{SFF}chB{SOgx_GM|{Fbc@EuBTHv+B1hn{~VP+i*h}gHBGJS z(8dfZRfSpa8?ofnLaLcX9rw<=35EXJMd0SUbRC!r85%m(oKZB5B5FsAu&YezG>&sZ zF@`T3L~#p4%U1ohBfJS@(9nH+&fba52PWZdCjkV89_Wd8y(J78x{>ND1F(N}guPe7 zaA`h=&9i*seuSBj{c39`=6?Wk3bmci^k%k507Zw%_?8;Z^$JrszNtA;eH>q@-K`jP zmab>r`Qa2VW28Q9T>W;V^_S(s`=!**)|ulmwxnTCG0#9w@!l(0 zsgb`vmD*Cc@kZ8de?o^IS&*XT{|ExIyqy@`b_-1w{7a)E$MJ32j`nSvQYE)t9H(1< zUoM=pll$?%hneWG?Ff@AL``}jbS+Pd;;q;)btMD+dg3Y5H(dya#}8)nD@STCJj${r z8Pxd-<@CUkRGAy)+oi1U2N1%EO}lt&T#^CR(;*QA1ciQe?C((jrM-G5A-zWMY|AuO z+)`kaw-|*i;mf{J^b34}bHFl=EUrt`_Z8o0|4&t_j2}b)|J7kvr}UIAn-%G~bDX*n ziC3g{1yt7yg74<2Z}P}l!5B$DbBo*;8C|U86*PASF0H^>L`NmR1U9iM^?g$Fc*7RwZAuE z4$FGxMJ5O_pO3`mIXb45jYeZ;sAF0xUU}7}aF@g67`mH7y*#5n)C+ITsIujluyrj* zCRe4FrDn@VD;A{{ql#%4yO*a;_s(c`uLy!N>Nt5`I{j~LOk7Rzcs{jC^kLVcjXbZ{ znT*lLL|$U$$}32VkEKyA8G_W4hRsSdw)bY1?fD0vy0$Tc^rK^9MLNu8wmK$8=oS9) zslfQaCF~jLOMtBe;oW)$58TPS^i5fLa322Y)Ool(f)eGY#oB#z*Ni~S|4Hh)P9p}B zP%O@}P;qj~w{qpyE#4{1;3nvq2h}4M_Z`j2klb|JwvTaT)z2j209~@zW_7e}B#^(P zw(_LYjyiA32W*=(lBebxyCmimYSJ5j&!`UqwBuBuXS}GSFJ&y3v-`kdUiHeZp0M~k zrw*RxyGd~>mbC^!&?_FNRs;6Mo6xOCK@Hmw5R}?6IQXhp+`uEIzL2J?!QXS$@h1e{ ztZPQGHrrXU>Kg5bYg|unEk&0T*=am}POL^B&ZTClesMJVdumBLHWQ5rg^TCMXz>B= z+;~D{t-Q$f&BHHh=~qeXKAT}al%6qc(96cZ9UMjPRgbZ*Hj6{6TdU)2DxS`%LVg7eP#Y_3$i2)S$jg2rX zAFgHD;ZU;mXi6zl0Zja9R%H9lIS`jE7dyppn;}Y=+LL$ zV`wa5?Z%=)ALh-9)zQJ8rKr6`TSo@83-#7fB$uc4WY%>FrAF*ya6=B(001BWNkln92gImqro1uzFt{6*nfrRckK8k_r;rn#<( z2z8VeEKQ(go5rjz22YuiP55reA5q^&&(> zL`2darlm)7;6T*h5eHK@FCro$A|fI`gWgSag(CjUn<9o{Li%hOFylUvm||mPj8dU6 zIItxsR8hyMlqeJmb?`<;=EkGw{O=xy?Ow~C4>bv}xX8xM_YpF7q)$^1qzXmU02rAk zEqXOz`q6*cwBZW<^5nrcSRCIR3CvuRx&!5Kt-=p;S4OlpS}xQ(M>5ON6)de%O)}K`6y6E87C^G0);}YJZmrd53a+iMuDtfcZJ?L z3nF>6jg1!~u&>*bPWen?uj5*aKCPy(ZNhfepBPIyZyTJPj8LB2%j$zI$>!_M4=09G zsck%3BhhhpUAi_ZfVY=DvsORl@!JR#QA;6WQ>q;K?*U| z9Z@^+2aQiD#p)b_x)@cO!?sm{4|fFUnX&t^NpLU9LABN-d|~ zz76dAP=^3>2b|2{^szv;-YZ7kEM|ISLm9`$B{4ro%{wfp6tTa1RG_?vjLR<`^E6z6 zwH&~V66K0u^1of&zyFcQk`72f>)s4}H2)z|Ups35LHUsFQ%3XLTuJ!14?Mqlk^{%@ z5^PhJQ6uW(tcvzOqEQg?=`-Ob=_yj!8Oik*JpUMp!WrJ~-^tl9GrT)?qL5jvJz{2w zr34V7?pKkJjjK_Gf8oRjc)tAH_^PM+by z7X==s`lh?U&b_aZWa&n?y6GU=H$;M&g(;v?-;1tylw7_a5PFmiyWe13q90Y9RVWlH zQ0Z64rgr_8`r1hi)bCtzj}4;-a@#~n__y~wy>^mgmtPWQmX9u@+LBH9%DxRd2$JRJ z@4nS>7NTv-l!BeRQ*~}@c5c|llfOEXy?i-bC;!WdFrvDUP03k+VQ99^O9A ziJ)G1y1<7MN4chSp;`Hypok=B*9MM$v!G(Fa>!pl<*7P{HbqL3NxGQxXYLSIu>dli zno9`XwywOhi{1B>I5g}+t85zesmcrsb4hG^X;j@Lpyb)orW9JLd2R_t>1!~)Uscj+ zlxL}J$EiWu)Q+C0?Nt?Yg!yB_aS$T-_VE>W&mH3EwYL}*=*5`7JP{NM6rY3nCP25bs@>D+zI`Uca@C~EKV#@sDMJEn8Br6z6KP&M(dD_I zLa9(i)yS97Ie8}eGk z9n`11yM;|x6r^k7Pr>l#JdLi1GL@vL{bDwsKgWxRLh27_v~ESI>3>GmOor$x`dLI? zn@WuWQ{$XlVwRm|1G`e%R>KEY#QJOs#gEI2{~BptI|-s+`$Z9_T$Yiu^DO?}@58|1 zotag3JKeIX?F+Si3DL(0d_KFBvHu)|$PhjUJ>=4ngIstikhR5Fx)+ls@J__K=XW95 zwWE5$##M*-?%sk1rHrGlBQHikoy;tmvzArodoil0QM|*1cRT6ZaUl;~8nJw46Vj{O z8u4R9y4(AX<$TC%bb!Z?pAfF_i1LAC*(p=XnTdBFa_@OKifl5Ju?7<787NfhPwtfJ z>nOC^#c>QMftZ7PRs0GL|RhR)T?{N z))h%z*MUmwdBks>2^LmZNz?idVzOUc;vV5{}1764Xu9t!T%PLOG^q+#sW%EB*uym1^Q;x`ln$ZV;@{uml3er~+?Y(#==Z5zZo^wW<8ko^p@?G(l8cnojv>BEEaBXk+K$18 zA}Bt5A%jbptIL-7_W5i5F&QVr)2dCI4xeu&FjyJC?CBN zsgj#(R&!C6oBnlktNUCm@oiWgr%mfvx$ZtKdZ<6f(rN3u>N0)xC_zy7oksU}NfDA< zqq?6*d=e~&A`R@9N}>2gvgtz*{i={f(5jPFVFZ8tj?B6c#WKq|^6EJ+BNSN463|Tat!TA3 zRQisg@ik3QN2O|bu`@7GmJ`y;$`hz|1X6Sr}nU4(|c1oidF2i7itsl4eND6OW0A zh-j7pX?r3<5fKp)kv|J@<=+%U`E&)nM;##~eSY$W-eAk%0n{x0KlSX&`lIc1#Jm}4 zdI}bBLUQ>r_n#>cGC$(MOC?4X@{!9Z?o7AFIrEWSuH^K+hlC3S$<=Nw-43*5#y?fa zx4bml);-O(<{bSwA7(41#fIfK*@4-T@1ViZ5Tjq7uxaf(8<6Y^cPM?*(|E)Xb~YZ#?7D^7SgZ!k+jgdH-NHD> zAD0$=@o4G9o9#0upE1{zU~6xORQSr5FDe8#^<2r;wpdFABEEk|AqW_29-mAr75piP z+KEfV%{la*eigab7^b(6T8+o>C!?=+^6>QDVujeLcWEd66}#CbbJ~l^|hmZr;5kyo;i-)NRUb;2r97g>dl4){qfCc8k4_>XM31D zcnr%A-XthQ2~rbGO_Zp}ic%pU2uhwmet}ZvPR{JsaqThMmW1fpg>~4t5X|MJ!x%bq zE9ahkCPD>rGgD*{;HXr_92e~mMXv%Bg(W%s`!V0YHxuq1B5>g}rY@a9o6466+OvsH zIgRx9P@VeeZLN(`umt3>^~#7(a{Hnr=&)YndGpnlHEXB=8Ii^Ebm#%9(yX2_23Uma=I z=`X5!T7dEy4<3C1t32fOkj8yR7P-imSg@V!Hb+i>rDZKCrw*SZ!mb(>iy9*c3Z6ZDN~G!w+q)KGd%S!~aee<0r63?p zNOK9?pDtThJb%h_r5w+k*)Wb%ro<^!)Dx)-fD{+Mp^R_ji3|Zn$Y);OJHw7O8|hoo zn`{5>WQLzh)T&Eq(2q--+R+oW4Jcn9Vd3~AAdw=K2&e>8^8dArC8PYwu3kL>b92lk z0;(@x_@WXp{bBFC6#IgW7`C(#1K(X|@2YuBp0Sp(0q3|eZ$C>Lrq}V&gQ$t$i8QaB z7<-6*4yF|9J)7S9D>Hs*f7X^?tp4C5+WwUKw^3~5@!AGPUcDIK;shO+_NLsi`FIDk zrbEXTRLp9D1W-JA$Wx_~kIR~pcUk=G%AMZvQ7PcAYatNg+Bq1etLS@?XKl#XzpLXa z1y$sCK0d$2@lC5)-L4$hZw9h`SZS;!I-cDxyoNuKG_RdRF`)et{TyYUw4E`WJr(*f zuIGFzZ7QnXA6r*M9it-n{7NRA2Z=nA+O<<4*Z8nU@&oTD>#gFmm zj%i8k9I%rLTn+w;N+S+yZDWm82;tjz6@nnuFfHv^lvev$yS)+TaU~E}li1_zC`0%j z%ol}#U<44t(ZFrIGAqxZ8tGzJZ+EOlqlz}{+q;%+FB|cf`hyqUF)ay>E{;f5_X++I z6~B0T?-3DFHwqSTjysu6)O${QQY8Dv(%MVveA99-JQD<*`DJ zXQ2XEYF|h59cbTwGUz^OwWH3Pi7zv6ZltA-6~?0NJzkvZyPokPOIv*XD`2tn2)hn` zph-gqA}{V{e~>Z7`}mPgU0(k<9;aC(>v*o(??U-j|G0rncl-%sC!B31sJ;gCRViRC z1;ezYuSONWpO$nz4~?U~e-0*6kYHhD0YY+WNn`&n+Pvtq8R$dl8N=4g#$|80{~#E_ zvLc1E%MvNK^^eEtnBIZpi7)?15C45qPCJJAD$#^qnoQ>j=P@cbk-1&-X!!E+?eo|A z%VTYVAJ|x8^;JUsHxfr@9Hc6~eg1+{5Ta}{@-l(zZzCxoW7Q4XNq2hGpy4 zbGyrcs8vf7u=RL#8T#r`&}s?^2qe8m6YS3d{mP+G1N)^k?IVeOv^ZH$F5Rf}Y*cU< zClB=@N4y6eU50D>3kJM9(~{Jx?85T3yV>)s8(lmE9_-!2JxMP5)y%109bU=X6SEmI zViCKqyx?1;07hn*qJW$V6dE=ZPcyN%5_?aAfWm+=G!g@JWKg?MUmb-$;Qn(Z@^XdA zZxYw;5-tzazo}mH=t&4d_zC_llbgS_Uxmb!cOMl9f{p<}F(*q}9T^lejPsn5S4Vnd zUXK+)^?v?%i$-h=ZItkSv%0MLqDpwbHqwlAKN?Q=csnFGmF>=)vhnxmMn;~Y7l{~} zROuvGYOJOnXR(j^qfR<^_(&c4Gg4L5sP2XnpA=eP^mO4WEnLA(a3UX^a!EuT7d4>c)oiRXMO~5epWsVp4~V%%9tpWt&Ff z?eOdQl**)l3YBK8T5c58At$Ir?T93d;sHzgPv)YeI3p&vBYQ$0r2hiCw39HJ)@n?) z=F2!!{y6KFEMUR1x%Awzh&fH?vt?Fo+<$qJMHx~lpi&X1o5#qAsA|W6&L5GKMPneN z>eVLN`nF~BoohT-Y8Y_jRVFuX!Ndn{RBZbX!-{)g!za!x9K!7LvB@M72?)xc80;hP zc2jp6^xlTDU?ciX^(B|H3E@w+GJe=5Li9e544dqgXg}GT%6S`6q1QpC&N)h}Srrrh z$X(l)Q)|npP$%XOtbnCJPnrzYvaZ*~>eVk_@Wq8t0?4 zR+7r)Y*@AL0LQ;HBFmwpyw6w--%1q;$uyBQht3mLMaqHW zU$87&nNm@U&_(H7>PpR#Q)!l6dlZcXlMMMtvg%JFi5hIFccCJ|!m}(jYZceXLo2$p zD2RWlfvldinyyuP5ii>!B5Gm>hzWc;+@Hz;i+FhDK4G$0&B@%ek<~)NrCS%d7S@uA ziA}7ng|SmUYWAE<#fn*|S#dNwCoSemy%7}FH%cUGLgaVBG(X*^_hMI-2@D^!iGc}y7cJs1yCfo_gM`~Jx@0BG+={7xZ>N0! z3H1Hncyc9h&WxRRa%o&Cj0ok@`07+2f1PW0z99PGsDZ<{M>*HsVr(jI91&EklaWPD2QpsN+n1E zg+lo=SNTyUkjkP~Xo@lE-~$Bie2eni9y({UrL*=Sk~6H^{FK&RGbgf2tpu4&h6Eud zo~%$PL1Khl{u56tsq4BQBJkzX1@0lz znKHc%S$}eLlD_@r5{U%RUa>xDkVxgoBoL|5#~6Ng9h)90h)@oru>G+32L)|l{ng&& zDV&HZ;?-sP>rvb!XE`KE!G5Vf9R1&&8Kvr0!*%5V=vejlr!YiEzyAa&zkB{fL_|bHL^KiWEfJBlO}t57 zMMOkIL{bP9Z+7>hTH}9lnRK6B?OepZC<72z{!I~71g#&)$bG@2Z@z%RWo@t(#xi2l z2|8~a%*c9Wm|4Y6Z^Ml@qi4*H58S{19+gpEJlv!R#vWvGldIzYcyxzH3K{Mm>5&Tpl1y32EK~5{+6}%59$3Ys zRB->=O~NF$WXa+XGo!J@(vwOZCQzwOZ;p*?Mw4mt7`3b!WqW0hKWlD`-6yUQjiyEH zU)qT^(hAz=HT3cPM-a6Wjf&Un{$}DS1^EX|q(e^mFFX@{wId~irw2yLqg=o79#s(y zhfMW`8#msfGRcQ$`q-JTO*53C#fUOA>v4(MZ37swW;k=2`7x$s0yE`CWhah}YtNJ$ zn@{5X9jy}qP3;IV=Sj>R-zn9&26=eKt z4l74{VFExT_NON>=X~`0m6ASdCgiGPT)FZVWf6@5Z5lQcHAqPN+F_j8xu5q&6_~zu z4lUJAknrv!t4D6)PK^D;pOs!WGBQ^2qkz$VPCa_a2c<7=`ucLF>B;CQL-j$xwL%q2 znGNu~);>--K>t2${_xpa7&HLVCQmPhJT_o|Y{i8ZI zwd=ps*G_7XfGubvaVAS|J{~eMZ9Jcb0h9tbmmuARxspQ+i~=X}(z&rg9Zm-R-G( zb;6JAMECtkGiJdYj((_EJv24dR_rAe%Jx?Km|^ zo7&M69p$QRg^|qdewrFnCeeMGFS`d8jG9Qoq!d*u*s^}xc9v`zgm)v?LVovGb+P;JUcrnp2z?N|GRhO|+1 zwkRH>p7JBX8Mopq(Qor7Vz zO6XZcJ&^3=&1M95-xBmeiQptlusxMlNb}k;i1_Unm)Hi2hW$wKXgP^NTf7-Eehd#0 zz*>l@E8;f01O!Ye)O#L(AFs%eMco-$`4AH;B=q5?Soi!cB&&85*VwS(7OM2VbZlA- zTP-)w_6!HbO)cZbztd`GI3X=L|2R`ftZ$d85(npR$6Nt ztR+gGz78T%h+Q2mUOGXJkr46{pfS zt|S0vFEuP*LJ+X+-DFqT%%$&`o-fwFp^`0!1wTQjg__k&)$89M^U^1 z9RFTPuk;XluhKh6?=>_53spcA6a^Ip1nEUUQ4~-FRQORt@4ZO^NbkK9Y6v0y?&kLg z38Y-YT}aRSd7gd5yV>2j%f2^dXJ=mJ|J6Aa%Bp??^Zif6xsI)kB}-#84aQOe*M;%M z|M+FqeaO}Uuey#Xr7X^a^|7R)eNS(8%}brlnmUvfeb|;<-QlONtxKOzODjcoc!qvW}bGS;q>Wr zkG;yfnd{ShJ^s~osG|QCM*DA6T32^hG)6z}_!&?xx@hkc@dSB*2K=zvP^4fJevD|EBegizGyZ^Y%2f9E*qV%Ha}``g*q>_Ufve=&E}8ZOoiW7TObmA~&uaqWxq zKHR;LL&0u%&0fN^){#@d7>jW6x2fzfzWUB>Y-~V95Ef=aIcQ>?D&}X=S~G^m(m1lV zU1(_>*?HjUuElWWJeMLA6<>~wH1m59JB~Ct$e-5%{(Fi|(Z)0@X?}(lv)4}SHbxS~ zkyU+$(NCDnaU_HgLI@#*5Xm7k_YVt^p@sW#;J3kiIBE^oLT$-q?q0D-&>OFi^Whb1F_z}NC+bYsarX20s7DaPw2|p~nL|9bP(DTfnwt{=w;umAX0GHm`DoJOMLg&VwxnGpTm09}VAj!~mq`t`RxoAZd6Z{s+Sf9( zZlg^uYIki(alMI$_a7snBT|bB*v^FUTL>u7gRuk4VRl@X)m|4n8nQO>qP}Z5duL5! z_mfvQ${y{Q%It#?WNFlaMzQbO0op7TdDp7~Hl~L>cr1}4qG-s{=zFGh&ri_a34Hs% z+b@1sb$awD!h?f}fAV$>*&4N@zDpPfejdYyd)BSequ1*|1rr>SaKl2c(}4;kATaV) z?$c|WzZV)Sm67}V_i`>mgJW(_+@saLUtgE2Nb_d7;r3Fd{&}9*M}EoTbmeK&x-gnM zOPKKMaf0GYmx7+}UCp+~cGPU!oLmXDOr(rWhwQ24)q-5cQ~Wt~4R@o$Pz7>$=1ev} zv!|+8OY%kj-CY~BqoM0lw#*!X_xY?eX;B$lY^l_$Il1nwWBj;v+;(a}+lEmOiD<~t zpgC3T!`T1p6t+K1-m5}as3mPG*z$D4R3`6zlE}dlVO(FefQ^18Y>Sm3_82)K;^#n> zp+7OGtm61jU-H|zh!-zwve0U9Kg!zrv-z7|OxWc|M65l-ANlb(956lP@`Xon-@m?> zf3F$P=J3SBiq%&nCPdm|PsPDg_^{{`?%WNFc0DG(jS`mzr;;7%RLcbw^neG?6}qC$ zXjV+e(+xBD>Cm$`9!QroaRotV7x4GqP&CfPCb9kE001BWNkl zqepb1g!TzrS8V600@O2hO!$sf5A*TC#9`EovxI5V(`GME`Mg>Jc6+nsQ36+-&I8X} zI*eCOawf42ZS|1ND|hkSp)Mbd|2EF|G3?ukeA37T!)b3;pR;BuJ1rjd8}XKHFuUf? z6>H z4G-7;#y?lWU%g=rCpqXUJ~me>olRJMJ{^)`IL&)g+7h z<3N`qH@WmC?w&f$qt_M<*7X}$B-6)|iD&1Q@Oifp>;*s(5grkvjg^x9aUu;##P6%|@}CTwc>;Z{ubKQofw&W9 zCpjBRRV;_S;SB3mpMNzr#tiGqt9S(MVa28g=qvW%`|sk`XTKRgl-3?_Yu!qG6E1{f zu{0ieSw06n3*^O5bjrr4MZZI7@V->q5WBu$<=@V>GTl0t#B_WyqsIP^vo>|;*1o{Y z0f0Ka9*r^(92Ay7y+cRN+_}&h&U4~yLJ z7^H!`r0q=zA>N$g$^NNyu3VPJ!**a-syNQF+;5`D%D>4jlp{ZmV(DE+>i#g2HrZc& zm)iXAF=pUjG@dw*5pzCZ)8G;o{XvvcC=`KfKc;%aRWz%fADf5A*|OmvcWkRNV&pq` zXcS7>Qt7iv^xg60XjRzBQx zLEJvPj%7DBHG3_rB0jc@aMl+G5;wY}@vdNz*+% z?7aL-#QKeQrT({L>A0yU%g24sx)yV2Tc|P3OHX3rqK|0#tOJcp<-lGW#uXob6op>> zw&v>0n9-{_`sEUO)jmO^mUStfRZGyl|L~27Hmh{(8J(3aRa-P6$8vARwCli`w$&-% zqQ~^qmrDksT|YVsmMVswVK;LJeumrl?`d-M6Y70;mOPbeP^oxs-1HInUpvh1{TK0f zsK8hK8sey4o%i*1IeXq7I-YlS^kvELM$}l}j0WZN;A9Bk_SrM!{B%8&o7e-Ern9BW z;K}se_8zmxwxGtg7BsD#7l&|vF7CO3iF^rk+$2Zc?>W0yZR3euE!sBE8S_|1%gWf) zF8@+Lc2Yxp@fw$Nqi>neaWDN=^rzk>Z(3H*MacObtlxJN`x@Udp+|uiv%mwmG@x^f zY^+**h-bNbF`>F0N-1oswx&g{dHjA@k)umz8oRyvzBT!~Gxn=hv>!X4cWWJ{QPY|f z&8jE(!6i-xHsrUzKBA~DzIs;tpU>>It}V)klZLXP!vucqRFi|vTTr8*3#Ml`IC#bY zHm}N@s2G2I;19-*-iTHi2!48xt0(?t|A~8qIagxnuuhS2p8D5uYRH_iW1)E33)od; z@Z>(MZabS9BmSntvR>rZf^GRP`18lBbRE2cX&o!ExI!&zl=Q@zARb&jf$y;(y#9BT zDOqRpev@B#RJbZNDik57vzE{Y7dW`vhwDLEs5i1VmGxG%{Us(+MW&CP*!B77UxPz6 zhK_%awOtl)^JN+=Zlk=cyYTAT3)%Dq&3_4?TJ;j-c80*~2k>4UfNhyNRLcrVSC)?_ z_Gd%4SxjqFgWb&i366? za>kig{ZuM?oh#-(x+1-p^!W-Jjs1gff9=ZVA!V?MlQ$`Q(u(AZoiGlqT*GzpGoaO5 z=*@iRx)RN4Ui1g1?^wZ>$L;9gH=8m4y9K!#;&6N(Kc0A%R-3Cf?{}?=Q?z`)$aC!W zepERUwW*lbYV5T7igfQ+i-q5;;G>3jSl75b9*&CV=OQ1%h`M$(d1%s1Ma~JBhtc&yNO?a<7$&fM? z&G(7LT>1&66xyP_7|~-fU4NfUy9WQ!u2E@RpPy&<`W;*~Liwm;Xgw)e+!eKAF<sQF)0ce@S_jCvEIRUMPl(c#r>vvvHoM&{MMW zaC%g-i`7pxmJh4BTi9Rpf?bXG=~{d~Q#bEKm%lIXH*$IT8MK!6$2r%bS#4)F?HohOJ!ev&k4n-Qlz<9dU0J`VCA@P zIO|{{Jm?9x&mHFAv70>CJ@KbY6I*sJ?g$rVc^UH`h&*{rEUmA0@CJD##I&NZ$f zSEpeNT5y0#zjvd-g|;-Sn3M2p|FUuOe?*Y?WNbk)Nr~7oSzA{rU4RV} zr{fcBN7+09terU{T3TC5w&_pvB5|)z^ZmH7u9sLBiHepsTkF1bnYxn&liSenXe;Uz zc0(6-58q1$u#48FPN2N{qLBH%&Pg-O_t$R^FG2YSSfi|3$LJP2};6 zcegP8+lOR{UA*h^)AI9=csrY!`hrz|I~^sven9mfhp~B!hO8Y%(k7SY<>$##w*@tw zcd+TpmUQ)LK}Am|bcVa^x@&}7QGa6{rJFV;|IFX`^TYN$ZCe@l;Om^AJ^%dJA#VH1 z(lInD{_7@Y9EDolE_}z`(l~OV@sO{mzx69te$snDWzlJ-9x3KZwFmR0adtfe( z+Ky!O@`HS_`eW*zSxU3IrO0U)#*=HOxLI}_E5E5?rY|G<2aK7&H;yA~`V6C;JEi*p zGjknI2qAxOHnOHhB_%tX;!jdm&5F8hkkY8@}#Q30Dn(0e#NA=+|%LkFAdg zQFdg>SB6G|=P}~T8dx_sqY!DFE=in&S(MZQ0WU+ zY|78HiNCUP^FJIkxKg0q7QE48ovy#j|8}`u{S5Z(6z| zlTwJ(Vc^<@D}*Z(kB_Wi&JlBI?5JOS5WT87TYjBd6gxH)?e#aCJ$_=sj3w;+-vUA$ z^H8qMH%uEoh~@=fR6A6d8=f9dSiNKx-p?Y?Ip?HE<@cC4Y&h@dv1Ta;kr`;Rwd9*G z>agLf)lB+r0L@2KWbogAVH`D;rF;J3r?m!j4lZQLk(WwuSEZms)SfmJ>-9I=^3P`K z&r8_0W284eJ++ry{H&Tiaz2^;quX4|su1R8a?(Mx)`iZr^(WQ@f$bs){JS)TeF+RM*=YD zoXFx)kXo%M&7x|XX!`P}lHKX3Mt490QdHM5qBW=1h#3jZF?5XhC3bq!W z$)s5;*z5f#+ahdm%UzTT&2uLCY7&l>hTy%e7&9mThWFm({JtR!t%Ex`^Hrlo{o3S> zJfX%VKc$Q1=E1pD{Bq2ILW`|aRy+!ppn1Q6bnDxbrbQf+ICmm5aIEn;-?UxMhij%Y zV^?QpG;#)PDbi&QJ1ewd?k@{jv*#$APwgT??@EsR#i{k)do(KuTK9H*`SlZ4Y}wD@ zjfZ&@WWv@h7e%UcW5kDp8PKw*`2kA_ozHU37{>mw ziH(2z60Wt!HJc}88@8iyX~)Q4c^xGN%x2d8ubJ$!QCw(xVuYmclQw7DcmKvyIXK~*8&Q6C|tYp-FJJu9^LPb{#WDFsXAxNT5ImL z_MUUU2~dYD$6dHT@e#z}%9JvG#%;GWUA~6es$LrdiLQXo`L9L>erWF=YukZ!FhVHc z0*R)xs+C>9x#k>k(ap{}@!RI!6btAI)P3q>p0A;v{s%aF#0O*y2t7-bdy7VE)r z*|Ii@a4;jv>H(Y+T;6Y~)MomA;iRd5n)C=IyB4ziWsvAQKc0e+87>gVv)VfzipUK} z9LW?J`k3oc9G;7s>)^8(?DDUP%bGoOnvAVl3ZExH$2@bGD>lJoDHhc?wuj3Kn6%xw zW*v-NNsbC%>fGJVSCauE7+UbJsDSElzqjyu3%;Fk_ky=)eDkCQK_kf2;%L(!0nz(q*?dAsiKV=0u=xMmDcm zV|wUgcOdLqmqYr-Ad4C|2Xe0o__<0=f~KK**ZGjk{W&wl^cMelaCD9X-B(d2hHvn7 zr*zVTQyLU#r#%zv^g`{O=60`I`#pi@X4@Suq=S*RnB^-!c`46oUurOzA~>8J@|lG1 zpjU_3yx@fxHU=JpygtqI#+O}ax34e7b)rja5{ZAl!-aiqh!fVzT9YX@Q7uAauf;VQUgmA0YY-biyQCBb}&& z!_C%0isU;sTpvIB@aI`KOXQQ;zM08kZ7y!a|M%YE*VhpDconZGshj>q}Lh5rKSEx1R4ske$0=(;kse_ z6qdOYD`rS-&CmgVyQOjNLO`V7dlaI)4fcL`!hG8K@WMrG>|8L$M;+cLHzI}a!ed40 zvwptZ+NpBV5H=!2WODe#gK_iK&NA5#oex*hvB7COc?Gg~iCvPEr=Xfa56g@s_XZ}b zoKz>QATY8tslv~}APwSZ7vXk6-0(xcu7mU|TOkcP-(ggOfJIQBoS5nM8Bn+6p&ysG zf_tRiQ&RtPfx9NQz98dRj%r6(AmT>%nSotL#wSJ|ke(qm8$d&9+DOtOabk=vi5Ih%@69*n%?SY)!rN5w@V5pcFO6ehoXM?upW*bm zs5fIg1mgzd=)CVC$ci1FH#k)t!_6~A@X{d*B5T0X*UXH}6^(TO(x3@Qh zN;6csk%C%ZABZWCjY@V32fX32b9p2#@Z%11tLlr=9HUoy&LQ zsnWMxr-f~$QkDujQ+b_tF#3jrt-Whpcsy>D^#12xLzj9kyIkVMbK!J2@U(09z%niL znt!f$J{~924}7;0-|{>y*-A~}gLp||z0nEj?vyNo-CVd@Di1l)U=#0w_2WA@*8Xgf zJSTGbTzZ=1qD7^TnZSXWe)Z|2D}_8C0eEUtl8~$YokE5TUrVx+Awu+f_(0SeO4aq4 zcdk_%l0SWHRyf8Dc3JYDF=$AJD{tK8Nfv7)^eLzUC1B8WfK8G8?|JK&>1IkLX>{V6 z)mPn}i0N*DJ;k;Tx2e~SVa{SBM5J-Sm+*cluhAW?-tNXO{fhWw0n)I`wKpHrO7kA7 z)f@$7Ql3rL>0qMAj|Q)mAsaYTq0PKRr#hTY*4qP|Y-Lj)^l-1y@3v(n=sUtG5A`Qw z=kgj5iJQ~@Jhu#=LD*%U;TEHsOEh&#n~5SnIP>xbrl zt~Dd`d2N@?YF~D6YV5_akHFyLs<{iMK94??$TH5jp|cqHpvlw#l2DU@$SMJ{Bw8p% z_Dq%ic=w5A{Vs*1B)gRGjF@qh_z;9cjg6T*?&np-pkM+>XN8`vkUZ|W#zQynWAy4D zPN@dmXP1cKC z8>YSY@~NJTwSZ!#xcnAOvhUKrTeIPp`j2$qbI(~wE0>wYCSS?t|Du2RQzvk;C!hL(SVMrM&B%q;TJ(e@mk z^8p&Q(1k*~b7t<@{IfoyZ-|m4z6MLdSIs-AFS#(}G0}Egf5t;T;yH8gei3;P`>x6C zj9LM<@V5{10=T0~R~ZhIyd2{KXqYoXL#+rj>Z01@g}Vh2vii#|x)XR14;2Xq^LYW0 z45-@;O7ukIlDDoY9y5NVaYg!$Wx$A4Zdvu{_+R z9)O|qz@@z`Hb=V?`|AO{On}e%Kq351Y_VLEt$%_#P{L!YO)$?o|k$w{V$IuemqiW+i}ZHbdl0B&?XVT$O!Xw)$B z|M`-EKo~x0`Tq8{;qA>p6h8H13Pgh3CGyy0GMa=bR3!6({GVFl41NUh>&?}b z)Et~zm7Z*oTqb%$6>4hge~TGs|KHF3=j}A)x5YjkKiuD=qN2vGEdP~7+eo4RtBscw zW_OjnLqX>c52&GmhW{$ru06UP0+IjwZ(>{jmkQTRdLLsjm53HK!fjYSMf@A24J%|Q zZ-2qcfBIRVghMTQF)D7l?8{+>ANx!H+m|4b_Fa14dv#xl|NO*%{jr2z?N!x(d;}}K z=3iwi$nE)DR~P^JUdTOdJPIJwQNpoI zy{b^TNUkIk2{3T~&nW(I@bvf(`e^^^0;jEyg1%xJb9Ebdd^)wQKZ?TqVj#)VtRNhZ zng|&Defs8Qt9YTZe;QC_;1DH3lUV$(-us`LLM#LE`47u_atwqq5f9vrW zil=s@yB3sw!Fb&0UFItP;E^}8Pa^>-)3X$41phO%+jj%A01=%hVgV@#@#T|cPx;d1 z^*u?Kw?@qNa;Clg`1c@JVD**K(6Jl)W6fPrCp&E-f*GHej=<>5326CVP%cN<^vX!L zD{jf^wD>7rrBCEBsd*`EbK)%3d+j$t7GvWQuW8izA_Jluc^bKS?W=Vb9qEUF`#r>?S~HeJerOirp@ zaa1x@3cnK#TqEIpHZ*nYOIri&j5d#S3#OpD5_x3jv?UiNKD>!m!n}3#3pZ_o?fluz zDGyvY@qDt29brK$H5e3Z*bJw{+`}R;4_X_#xdSh$lH!G=Y2(G8#y>?TVWBUDyEa*i za6BxTV#_WE{EsypYWQC+cYmV}OK$lYBNKBmiZYscWz=HjF0>gf+cVe>V>sL50$od` zy6KUZcue!`qZt26QcNvo_0I67Cs30K)Z{RJt_hJxH~`Ic>)9fo-cyt0I!T;BLe19g z1YItd8~ABxqrOxNangF(!%Q+~ms;}TRgQa+D|-KhS9JKyJS4!&m$m_a)S0AZ5DV2c$|a9ax#1^YG;*bTl2vyOFeY|W!;*A{ z8&~!mKlDz{K&OdQ@0jXGt4nW@Dpdhdt*NEUwm&Q;pT zN)-Nb^PX2)GsX4YqVj9JsP$4a015o0D3+bJC}k*Ag?gwDiJ;cCl!H_vN>kLni>Q@$ zul_NxGNy|HDWF)6FWm z7x>SHp8%!kx@RdD;4^U$3C;V8`H_25lgZ;IA+aPu)6queS6jD^#_lnS-x!=oX6ks z^x^k`H!n1Wb&Q#)CEqVk)(Y2?hW@=5fVK1Zg+=H|@LN2SExgqVKOD=3PEUwl@6ydu zAeDMK7ltk)JfK}TM)tQ$9vXpbrECmSYrN2={%a~1UX>qH-I&|^Q>TtET#@Q;o0*<3 z%cUj4O);H$<-NMDZ!gqFe2?}A+RdiMygM4a7-`hex}&ZWvh154^jhL6|8U8f7${L@EaU&z*Ng07 zd1s#bz4m1kXkYO7!M-u$*X}S#?s`@n3fjLr9c}J+BIYRga>jHj`!cEKz(#^dj%Q7{ zKD4KqaK&*nTdHlhVWshDP-P_Z@KOKTS}4tmuw$9yxA0hqGTE8K*0#}e@1zr(iefJ* zWtSwjzPu8K{e5WajoB+NK!u!A92^}V-*VzSp)=!s`OEe_KwKc;N6Nu0?s0z zxA=HJJGqZ%{q=F9Q#A<7E*r!?StIT~ykWyoR)BRK@X&Q&{02Cs$y$KVd(w$X+pm!j z?>lAPB$0@{ivics&E=kAx}SUVk!}X?Iqz>s$4&0)>hfG~^Z=V;p`%|pBD9`V1hWqn z5wPnMzWhNIFP0xtfj3zUwv*6BWdN3rWFMLzQcanjoD@b51c`9oy^XAQ@ zWp%HDSKLc|-YZFp)=F$x7j{|1ys?bsy;sF8Slm-2KK~TqROv-0qyTLVE^Z8HEiv@e zzPXKAOkl|ZApnvH_}!To=)z(Mu{@O+o(;lyiLZ|eHs3mx6RkN$3I|kNhA)n8E_|}f zgdfXG_aCS7pSgweQ}UxSp)4g>GG}%@)EVv~=-q|oO2Zlm5*G?m)4bS9MLa5_Umq)J zvsH`OZ=qESYIzbC3V-8yji3SnK@v_%l&C}{h zZt!;JTnfUK+gJq@{Mef!l!+rob0%bqe_Nkul|jqPz)?o-mT1lPez&-xoG;?brj1vU zO8qdm!6Ze8Z^L+#br+9arI{fYns3DDIu_oX^ZBMKm*1LwWFYT%X{>sY^8;+j`c}=1 z=JZ~e`h_A#XHuDCCA$KW`H!Odmd8>CrZ(J-934zDxc)H0_-w7E1yzg8qhcDf-;5gZ zSK2e89_BZteT$t(qRoM2Q2LmPygr&7V_f&UX9KHX)pU9-lf@rNtyuc=quc)&;wh{4 znT8H_1cSx{GE>!wGxU52KG7gV0Qn>oaWiU#Z=~3k>9F+b=$h6op2c#N!Rjep-^p*# zUQf2vG|&0rsTk>1QPEIIe&I&x!P!&QcFqCIU>7$?f>v^6^7AQ9()vHP_aZg2RO77U ze*;1Zl<-nA()reWzE~QlS9Eo!RYWA(FE^yfQCgch)7+?va4t^e0I_UKZH!R-0mK}mr8aZ}ElSP49*r|M&Rz>!DB-S@dXr>D6rWnal_ z0j*|edNsmRm(o8unY2?QJ^_>RstwjQsyC8m%AAvS&HX;6;xt%}Dp6I3zv~}QN|i!l z=Kko(swh%N&FuQgGjzo(R5=(6)#>FCAaE%Oz#uDR((WsGRz#Ev-b!TL0;cWC@btKn zXRNMAAgE=&1c=IE_(Xes-oMDd|L_u|_PYAavs?Ak?MXyv(cgsX-bXz!z=za1$CHaE~LT>s;1;Y@H{zOYhLy{W0hb% znAyPuOf`Y~uBXM}6q%|`Nrm>w5=Os59IF&-&cOR%u-ARN?_c)TQPa%$IsS6nI{4Kc zZ}AobXOYaRovj06ZV-a-+i3Wup&`=I7JWzNQT6D22fgD3U$4^_LXd3b2K#S1t+1;~ zML=y9%I9jYx|^#T zQ)nC!PWW_neWnPN{zun(2_qqrSRvGy#0Zjyg9JEMq=LCJhG%vmpQ&^n>YKTHPX_AA zx6zfZw;vP4es!LcxRv@mJ?HCJxnZ4?>DGH!KQ3W@hzFg4Qn($+lue&Ue$78|yBRRC z@$T(4-u-A7)an*6Lf@SqX{UK-a#rWB+)b-Oca-D|%v1G{I&pj1hAMb=OTA}c#Bjro z`4L{_PYbj$dK&@WKTI+Z-0ws2pVJ#G%|QhYV1F?Xd}g+0X>xKg+Ui=>xByqt1G@rh zI3fwMSTnlpMBAV+yi;my_?R!vi1r}9}Y2E~{9H<-G9 zoV0@MZ*Cnu%5(-Ta#A}B=%acU#O^A&idj*e*^AP2b%FmbXL@iv+?v=>dV6V6C)YYkH#uasOz6RkOd$Nm%k{(R*i%y zu&^Ezexgn_w_t!$UD6E`=zkBo-;k+Cy>rE+)BL16B&b&I!_ggnxuEB&&kAUpSWRGl zx=7k};iQolX*F`trEfK}&ScH>LrT2&b~bbD*Pf4GLc>iqIVJ4xop;jkodlSE@5(Ry z&iopag>G1XL6NiuoW{;oQN%|SSF1U)>>C9OuCztO!?;<_myw_dgx7;)SN{#`@+AEo zpw*&;P{}$ZAOMf*!!s1Kg^q(;gy4=ug!rXlvz2g*Cwzz>Yr54q8F(JfxJw;tDSQ95b2oRxB-_s;4|qed`U+TF!& z$4Vn?_-C2|UsO8bppx}utD}s)?SE=!*XJAhpER3Y=D3eDM(X&`yuz~OO`BB6ya^>S zw}&&_wRahqAh5T$|I^*U04Ano z)-&|fRnGuECVfYnjuT%qxs!)7*CQ2LUa#9!{LQH=&bV*=qdwjB2*Q+ooiDpCl`xbZ zPhUCFY&o>B!#WHAfa?T} zuF$-+UhAV<1V+)kDqnDV*h8F)BJ<9_vv?j19U zAu!FwwyoW8<=$LGs{UBr+)BmByd-ivORd_rgd7Xm;cBqw=8QH)db|W3t(RwBAQO)v zZJx3S%{1B1y_a3ny@u{}+cmi;uPQ$IaceJ}&jg7#4#m{g_yYdp-4E_}5tTb09{l7e zXX}GF4hiS9+&}h{k{zSGSZ(J$vZ$T;NoQ(B2BYD+R_~ZCoHkSG_P)4hiWBiWQ++sF zqf|IDCd-q$T>{`>d;me62{2z-OPZ}&6AmlZ!<-6bkH7EIkasKo`g|rdX#Zk{$FsV1 zq8Q$~-nn~j^a|%{oPM_6J(*9LTqHggoIL?0k3uNcwYtWpl_eMIOu4}sgG<^eLvW8D zqb+NyRkXIpClyyKKqZ1c!@Xbh6`3KJZIB!5Wgue!4x1W@mMk##(>sAgn5f2CoGJbtH)taYvJFekVl%Q_k@<-Td4af>gJ2VUECyd*R96VBFZVYP^)oloyaD-Xld*; z(To@G+FlVNYPu%<>u_`}mAYyP-{n%9PIVff6xw=x-55BZZIZ{vOPhQtuA1Er9H$e09N-R5(m{e{ z_1zYslFJzCtLZ2?BA86JYz=XH3$A}MMcdCjzOV&u)YIHX63%+g6u%(Ki3r?Sd-h!3 zY@Bdge?=jb1T8Molj$hJ=8;Rq#fF?#IN_9y1`a(UjK>&8Brs z{OR$XoSTwiTwW;o*c*r$t>2Sv`{fxYTVQV(eBoZXYA+}E6w6{}#e6wQnoyVA#w~2D z_cy!OmnRNb1%2(&Q{EK)_yFdneaRdA7&t;kNaiGI9;k!}^PN8+D^d&-qU;;c{pWaL zOEEV$kalWm#R$7>tg)^M>LxID>Yfb3kd*y8mVA87GUG<7@AepAPrj6RHku<>5Y`$~ z@u88`vkyk+(R$~&^ft*?gmk8!DUUo`tJNsC)V)weM}|fTNgWSHld-d77C3YZo<%Rcr)3XRfM$(Tfbhr@ z^Pw9F=adco=~A0HIwU{S5ghKq@6f!P9kkZjAC2oO(hwwyA0eX%fnd~F)%s|I$kfgPbv(z9>?Z<#fXO9o&?=Zj;b zwoTFi;!_QEL521Smy)ne)>5QS#tWqou(&^eUiUI`KU#aHVK7j_kdxzZq2P;C;pBFn zzi0|)wcvyE`!)U=!2CXjE7osap@(Da>8 zlpgGYLJG;$i6x+e;OXV5MIHgqAo%(nTQFmk_=zd#A}i8~P_(GlHc+U!ugmWg zR3rJ_fm*z!fqVw*-#I&vcAX{qZL*??pr6W=rHRwj)vVdkO5^ED_D3>}w)|4=>v&7= z0tpO(TME`?>^X&X!njpegHx9T>?$UG3ohQu!#oRNfI zJ>+)c<9$Uc7r(O<&}4Zb4sIZjQOxwbVK(89sN+#D7n6L!i_R7p{cc3aKVRmfM}Kf@ z`8MR&?oLQHyR2Zdc|PVL^oT9hR8|eT>Yj#1@XY7!jaQj^Q6oc%3^e$`G&e|zW7H?ABuh9(j^Ord}xM+Mm z4bT-`lr|n=w4r}1sOnW^wDCLs8eg^hxtG~gkUAK_des$L)$t2LlCSs!4qxYE^jw)= z`wEvpc-l_!l@%2aE#_0!!7()tFBZ=*;Avj>q}5a;-U;djVRHL=og{JzP$$eMn9Uhq zg}3ARu-UfNLk}a%FTPt7a;Po?*|$@I04SGP+u#krEfY59H|1t45}#d+p;Z> zOgrhWOvZnn?Lf+7S~M-4gvwgyn@FQMSKPiOZdY!?9z9Qc zN4{?svv)2&e*pf*^1&9kcYC_J=8G!vG5n&)ckR-P_68bo)~<*qq~zsA$+R;*dDQPZPw`4|mWg^OAr(nCwRb$c<`=9m+MKCK zXsOWZPD9(io|PLRhY`x~fZ*Bby7i892K|5AJq}_pwzkN-_mfz7)an^5?Vjsng*5x3 zZNKqsZFPD9vDj5XSxckcMV_?mmC|Z?{ugvsnhswQ=qq5s4m@6UgDh$9Fbj(pg^_E# z=T*Nf$1Ol-If4g}Y}cB*$75ONXzir?Xo#cvBUbMEjasSl9{AHTbnF*?!6TB8^!)7p zvD42;6*)aSpmlxP4BN}$O-CrvOzd2z>yOCCvd{O#eJt}RbS28=i|V@X?Pauxir z+-4}?+v<3YyAqy3OPeWxCHR`KS4nzbt}%LZaW5DEu$Em>7~L3Zh%bT*<>~@tvw3F8 z*zOD&1YACT{(Rp2&EES7PuAg17FOH3DtqV4HAg(bGKA@p95gSj!)9qetQc&n|J-AE zo=E?AXtd$k9B#Mj`eP+^$h*Yr*>1@l8S5njml&(b`$iaW*!MQ3}Y5klCd|mEs zP*A4bBM)i{#gMT|NnYa+cVgx?nMBfZ^pG_<9f-2l0Sn0Lpg%qx)4UCnaaykp1wXue z$&(+qqGZWd4dqI{LTTmO8DNWmWK49=2AkDC`vccuaa>x4j}2Zqzg{$6dUrg+xpbwE zZjRV4?S2toWqLDwdbZtZ?}&78k~d&pH+d>F3WPZ~bC3G4GnyRZ{cxpNygRAGDzeGf zN)=SU^WH z7vW7fSeo7jP;+U`em~oYS!U*ZgrMBw{_$B1>=s38)>7ktYhH>wyyyy1!!eCdJ*L_UOx1YGH(-)|UQ#|ATOnp6b@YB#bq^_h;PS*Lg{On?;Z*m_ zy{mko?b=u|?G`~6XON5hIN{pA>JjT+vbtmLz6@3qH1PGezpt#G<{+`!bpK~w01Oto zjKuX`I44Sj6}A|*E1*t&8(E|~{E6>q+EL863s&}t=6NCSqa1RU$}ub6`6-*Zp<5OY z2-`tAYZ2W-)bOvdilqFtRu#wpvR0{Zh_!AlJHmTa0r#%`ZLC+?F@S8z8fy%6cOi)Z*O8Cl=TSPQBS&|#Ua1*dw4%aw0b|6ZALZ4%>$CS4v8`>;%GY1ejY?_s|mY2pU({xM|Q;iBJ*wX z+4*%91w$+{I4~O5CgOD+pVj3QQ?EtkH!hF zGDkSuet!b$Lji_dAN4)&s^3G#gk3U~J~CH^Ze4s8RxgU6ZwZQQWgBzD(VHU{NtH00(>);b*QBEO3H9TFW= zs(veJp#q~9%3ztH-Woy1kXk*XkLl}Z-u+ordX~Lozlxw&5s?YP4w-hrIXB*mAv1xY zh9o{ap6u9oAwizpP>hon;0nWRDIwRuHWG8d*y??35u$I5H`XhT)`dkU1IUU@kJ^ycluPu_4!St{VQ z8%`i4>yUIlX-9RnW?dJ&-SfzlJkeN7j&n`Q(g?__!@!Fa!BOh+qzIfxC*;%Or&Xbd zaTR)d$m*V|lrqjO`E-BIjE&f+Ql+D2nuCt}x0>0Pf@-?Vy=7hWK96+EKL}4eBeNbN ze;Y}i+i7kx(nga+$UDZMOb9O?Tz)v=N6=!_Q}CTK{FniPW3`e~IAdgklf%{Qtc>*uT4Ev;(S8-x!>G^?-^dpWtN+0IoVP+$9KqBA~y z*Dw2EC#qjP*Z48&XxD76rc9^R>f_x~01iV{okamZ8t%7t7Z!{rS8Gr?3wDRL%H9q5 zP!h6imP-yX49Zl1(1l+5hf#Ut9Z81g?0@?bg)t##3X@>&q~Q%If4qJgglfR7y!c!> zja)Fg8ahzmY~AG3ollJREmVzzY|n@c}yagJ)HJnOz}y4b7huXt@LOm-HoE7 z$gOfM*I2-OM77nErpo1{g&xJ#YpD_wmB+jW3phe70;alz`{#1+5r!EarHz`D+5Cs9 z^h2e~lLItH9Os=cnsFyue~LxRwr)T%=;#i=h+AFEMoi@K{J4|OOR@Tp{Ji&&_mg|W z1k8ItQw(?omD9gxEx)Fg`yNczY?G)F*iPJvcCneAkrm$R51;76)=qgLBGsByYkC>V zIwtJyD*P;#j2`JUjmrZ8;t4uh+3>vL$agn?3WUdQqGF=nAo0$-r%N?<)oiUne^5cP zwb|&I52e;2P>61TGR(9ElSqAjjIR+#Vf$S^7D{i(x}iB48{LuW#gF>5hE=>?PStYS z)9iQnrSnaO?4ZKdJ<);OB~Kmg@q)_jgAAt44ID%G5lb)(gqVlsRhJ`*;caYt5IOz< zxYn8ABo(v#}ln6?JzT5_nJJ9p`eJ1&2PK|UvkHYJD%NnEeHUg1b|KxcTX0Z_=_*9 ze91|TMcZvo&1s$dNUNsQ_Jf9|E@eGieCZDje&2p~em3oD_xF#|Vs>10i8H2=E1+d4 zPOsyp`OUcTX-6-|-z#_Fx;QfkwyV$7PRc6(F?j&o1+tZrZ3y1I_@pzLKMeZ`=FjHQ zQP`NEX>5%ic{uO;rIz*=uL19l;P~#Xbb?uW#DDJvIErV1s=P%wS@MjGg+*X*uCZbB z(_+Y<%y^H$XiTpL+4^TGl3toT7Tz{2bH%?~qDP7{e6vbXl_ru*_{TT++$(wqrD?^R zqloWeeOn_0t?wo00ISWx4P|!!glddONEA%TeVsHEaYsB7ZL|e5H)?I~z2KgtANB>G zG$i$LocF`}=uEL#8nyx;oS%9!_oO&-IGyqO^+nvaTAQcMn76D-xb#=hFu}4da_8iW z_!$V6IJG-c|9iDDqfB?gR#f^F8-5D^9-prOagEAdEqgft@3^u=X33R$JNQo5H~X59 zucD-6q44U&f-R zs-37pe%oif@KHpM<+AfL6iMuQ*PCRDw1E_6-L-X;C3>c5G?*+lPyRmL1MiTL3`P8EcpAQ%>AKeemgz7 zPc}oRiSVS@F2~InkS^4Y7oa`{cCRAA<7-0kmS5HCShB_}xC>3XKirCLx4f3~|0_S4 zKA7;!@qLg(P3Dj3$niB_VJ0P~V6pm&lkQy;HVvNxGqo23YW2(&k+q|N?PN5eh{X7i zXw>W!pLflLHr{!wF6jn0{@-r(PL6$O0aH^`)NTVDMO4yz z`Sy3Hu=3(SX3&N{0l!T@sWK<4Krfo}m}H$|OYfJYlakn4G<>Oq{M;i(Dvg5t(E5nEji?F`&HQI#UecY7kO!|%^=*^wi`5a7~WCI$isqoemLfTLA zmB~boXu&b7zcS+y6*G&m0g^}#2xAT(JzPf{{c5DC8RYd2$$G1iS;LIaL;ydsStch6 zLvdZK#@VIbzwkCrTKJzoJX{lXWNvCWzDKQ%XX)5?fT&He`2qi+V00Nw+oj+400+(# zUs8M^01yJSz@inNh`{u;B;Z?jYFAUW`3O$ufm#rvqMzfbTZ_-2NSY(@RFj|Iqqv;U zsv>U#5o0I)wvPqolO(L76pEtX^|t9i(;=#-99{3vNm|9LNf=Cd&u|xnMW^m2I3Zsx zvi2g6B|Ai`g)F$Y)@qJJ+@vO%Z?#(M2iFsLV#xIJ!%!8)$|P91Z`ON*smI*e?YzK- z@uF$;U5=#tTBGN-Na7}#?bzAGc(z~`iX%hW=$%SnfF}>bQnY-IVc0oyGJUtUg#h!q zKyOwQ{ype-s+*_xw{)4->Lhi=?a}Drxq8Q1%0yGt%|2%=k+Le=xtd z;$^LobCBbpmrtY9)~LVwl$F?NsxWSh#svbU%kAu%#Hgnaj`g?bT0CFElrLAsfu}x& z_dQVw^B;=>u>ZJP;~HT<$2d{H89xn-pR}2it+oMc-5mwmA+$h*S2Jg`c;0ufI%!Y( zxhAvl#ttn5ohEFW&4VQJF)<~HVN?D%nG26rGEPXyt=TZWn?{ksd=>R`NO! z$8sQ(Un~^c3AE0?+oVu|Gtfsr#byl(`2+gn9)g--FP4FIm@T~ z`{ca7JPS6aOw~F`PI{d$7_hQ4mJvx{_SMC<+`dl#Kl2=~D^Kfte{I>K$QjWU+;w4?me$T!1 zaQug~as>gytXlY;4vk(Bo}kc#(PQy0d#V@#i}k}@`D3}aJ8yYLhENQ!SBFL|_oF1U!GvP4B@fYZ zrvkMacfc~AkZNgiIPQbihCR$;5{l8ugqQnbc7IF&?UgyPNRf)>&=0~-*v4>^BAGuX`wDOW$!THafIEUuk|SSEckldS-^-kHQmsCeQ4oe{M$ z>dd2*m7!Mxx#H#L`Kgn33K7QWT%(1T`!1B~@sxoKbMVL7lS+sLd6&AfRF>`HBF zLm)AY06ttZ<+h4>9&Pvv#dS`QU_OoE}6xS^l{uN#6Mh#M>2lHj!M0 zd~sLeq|@R=T$YEO3cs)uFc~s6EhO3l`yGL2d<4x0hviNkSs$^dn+-`5zTR~0c_Sfo zktC?<6A0ewv+bT-+`Cri5q!nFbP3%&ItIrvqn)^*69Ucf+M17KaH}1m1w}H(=gU#N z0H&apcF`vkD4dOFv(M$NLr;XWh64lBRYHb4MA)T1O>rd^Afki0X1{oCQmVKDiNg0M zdWKAUnu*fBo>e;HGg%!e)hDop!JdFT9j3h)!h2@^21{=dNJ2*%@Wcr&g(W{!=T; zeJCw%9(zNbTA`wU(DT)(FsCj;&vt53h6(Rs@zP3~ydMfMU^~j z@Az^abw0Q$2SAxMER)~%`v;g2!Zm+}`t+1MyKk)#{utEt6E$EYS^`n-e9GtnChqop zu&+R$<=}JvkY2F-UZkl#=o$?L*~o6NFM@`Wqw^tgei??@_|dWxj~TyAnwAyYx-XU{ zd$z-p)+H?=S^D>RU0C~8){Pgm=i663^~w8=4=0ODye3~ja)l&DXTt1+tO>3*#{i~& ztDCg?c8mW4XZWOA%;=PEoMcwqM_Q6k!#*Z_&HAt+Y5@a(lTE^)>W*`W`1^ z!~QAI5a-287p=0PwrAw|6}&u#l593CItU=Ht?gEiEIyjtE5)LTortO~qvioLVj#dI zkQr5;aBFk16-cY|2P5X{Dl$p=K#ts`udsIMLqDsl=6dVtuUR+oxZN{v=&G~T)*}2s zCCXw*@Tq&8wn~TgI?%1m4Yh+lI(2sOC$tyFNXrluxp@w;%=!)sfGL z+1Stf$#WH~KY`z0z9@F^aI|kNq;@&jOA+mRSnB8xQYYfGon|oY;`w~d#B5rwyA~hd z1daxIbg@;a@n?zi?&s?6k3?E@gzrkbvDJ&v7#_~zQXlIJu~;nd(nE+DOh?D^?VAUo zwLiBr{H%jsRDmwmtVbTsJO@uMP|{~!5QPLNRX>%%^AjwtMY=u6Iaefbdh0Xb(wq*D>2E;n0VTCiSrNNOk(B&|aD(bfH`D!qKIE;h1gAv|vU z`4{7f(aR*;L;bDAy$uJksq|1s&kt8`wPaHa#yFlF7UG7>Ztr8nkjd6q3R2h;RaDm$ zA>_c#*t}0c?Z3TIkXvY!{t!O(yqxga6TFpo>K9gga&;$)|*y5P-3#|8+$qVFo)1=yN zv_JG&#p$-WZk?ZJ7h_p3Rr|vr;Ze|54W(P}Ph^HMx{=wjLXc6P;xd{f!T-kx?nHb* z;A)E#b(0;i(0uy$^xpYO1KmJ-;KkL|V^unYuf3|;<#^$x$de*>`v}FLtutE`=-a!d zy2^b&sd~1Od2ux?Qu(W(QcB$7fM;ZpO({yX}X;>x-PaT zUvo%^xFac%H@)H@oEQ@O=VD!+3Q0`U6i8u}EV3&;reOTn;A&zl@d;qa&RJ+Y8bcuQ_Tn;}G`MFzzecBK23T zF$tlBjxyd@#zs9a(ou`dErHuc&2i%1mtI)n20|mfCi&EAU*e)F7(> zcA%zEL{kePFvC1NN{^sDwiTb5rwMP>z`WU@uMe#L-AR9-i5EBik!ZAI1rD<-2~w>n zBDJm1JOl*IkSxt;^LQ-;wpo;WAScyjB3ATe;;zP5w9sN!J+A&q8`*2i{TIr zc)3fLM6&CZH_n%Z%6xf$@yTZ9M&G!QBcPe-buNdqgc*$R(tOjWM5lknTU<2ILz2kcjgOs`$G0-Wp$}F3@$?O znw_eVXE1<3XO%{42T0{xv8>@lv~L3 zxIXmYWX)(2TlEuUPgal7ZFQlM*jUXDbigP=y7GNTV*aBuT^r19gn*XCkUYEmY@Eo#GBHPH}=0 z+%32}1ot380-W@HzxSRq?)Ux9z59=hojo%4UMp+Qxt`~lbFC>_CKr-g1Qe!4f5?h< zUw%eCYpC>hSM&er&|^u)yR}&MV~oBRqx^k^IgD>Z{Xtf?c{ZG7F%P}cdz4VHl1SWm z_%uGj40m?Y=JVwO_UdCT2{6^ocvGty{q#;{Ufpjf!JY0d9+A=#csd00uwmR~Ot{_M zfoO<1Ut;`%MLqKrvy`_)+7lD=PYp$sFSP{?Nps+5hD>JBD>Yvj<6DI@*`rI5H-iW0 zZB$0Kw}0&iz2la*Xj9J=kmP8VTl<=_?@0Sac58v&l5`7+pk|h$4|>;~U4>%KIR}qI z<`I*f4-rr`JD?>|!A+Lcb5<+mfyY)YEw`B)eBJyZq()`l-*>4%W@Vl=pl+QEH2+5V zN+{rJto*2P`(s-~fs7sSt*0k)1l`MbLNy%)kiBi)G^0v zDZ<%lI-A)u_`EF#Z0UNyEj3`i+2dUb^C|l;X;)>Exc=2(@2qC!?F`;BJy3w(>Zye1 z)&yuHQckIau2(m?`mux3PJ6A3Yj!kxek{zE^ZC4pOw!PsrKedAdljY{)h{I0K_)Gu zgI^Dh4QJhI;4)CpP#Th5icc`$Pp!K{e1vdRhA&w zG9x^{1p0bB7uAQ$%RuCwWGyybVohte>S(#E2+-A%pjA_EFu9ql)9xEL73yBSQM4_0 zT%G+6vE$X@By5oQ6tS{`dEfdk|NbA2xH+|ez~8|q#T+QEl z7Ct)8=oy7P5BaoS?F#3I(cnk2J-QCZ3)E+uJVU6)UIOi;I9TqWEcoIZ)7UFkH|u9QJh-1(eNS#E(HEn~m0~sDKk>z5-028s(dIWElAn6D&rXE$ zn?BZY=-^|ruz+KDoel{OUEo=b;<}{*0_BNZ(9T?V6FIjk@HP4_g=~Pk@7`~^Zz<>pUU zcPd6ZsOwjo;+7;5Z8>izAwb_UJI+*@t5;R|4p>^X#}Z4P$Y02|@BOOeE6?m}2YcTU z;1d4s3?f{|FQBmh;((T_%oK!^GI=;9%A= z=9_k6N3KSoJ5GNYzVh~n%vUZ0E@R&3yiBp^R&WnPKh8oKS*fhE0;451LJb<~>}8YP zXlom_`@GUXaUqe>YL~ zoOlLQVRsprn4&b+T%$8 z>%xe~-Cg|j%aBqgR>GGnI9>jzb1X7&S*4DBZ8ZvkKHEGR24kTz)&+}O8S0R-)Pd6_ z?6+z~FJlk=*v6zmLQixa`6T~?as9m%ryjM?fX;=@3z*2DMBmoQAWE_0q+TV;{2+Al zVXj}K+xBhT4OhW0osWh(ybs`9qKsR9eOh6PDcDrz?>DwgvH2@CL}hj=h&}w~2WMJ& z1*koTHQ}6_=G9Kn@izej67e@Sf!2bPMYRU)cIzq?uV}Myo7gD*IDDWeCuvg?wQiJ| z&*ZW_JX5Q5n+Iq~Orlr>PjKgBDtC8{)g~Jr(woF(U$+4aY1RbdEA!kQUH=O39sh>_ zU$u)6;FpRsw+vCg|3`#Z=j9Z5J(k^pZmy6XJwzs@bo+2(LpB>lr|&zw3)K47tnFrW zh<*RnX+*pe1eRN9ixg?VbdqwjsekN!x?b%*N{EG98VfOu+(3pEwJz-8)rah}i@{Wa zLBz|C#(e!{3V19x_}Kn&|BqbH&iNW}NBjeZRvRcDPs1-(D3`Vzzit-brM5J+?0k#! z_MD6I-=&!U+b7hD9aB7^aL(y1p!MJSBWF54UlGPJ-SJKzwa@Elg!Tw}_r`TDF~I70 zt@jkHCFPnr#HvkxFg%W@m;d5Q7!KPdS> zoG}PR9?(98&to9;MmgKLL?tir^9m0C*vOV3zx99Xjo@;G-UxeJZPL;C92K+c1XYCB zvx-)g*qii7huMcEERt=E5eMM{LQClzgOGoZdasyS)Zv>zRgpea4F@8OofWk`=MEK|*jsa(aa_SZ@ zB9t-GuBJXD4ZipOps80XAP0Pq?(uSyM`o)K&gP<_Nc+`rB+|Na8Ff~~XzpA+E`JK? zr*4~_&|x4XcWVGgb77rH>idqKhxSJE~O*Fe6bjcWE> zvV=XdhtV`fWm*_o$k?s_AH=pR4C-GqM}KE7JK_e)ZD^Z5JE2AYun$g`4=i4Tzu)Fc zZ*+n%FWiq6NU!b<^I|$wj;9!6)sNdLd3~kO|IFh@5fE!*vR&`zcumn$rAEXqN#e3@ zxEkh1?f(7_zNdc~SQ~dAeoTl<;@81@8V?yuCG8()BE17Vzqe(u{LV>`jM`7_^scWP zR7uL!CLcQPtVM+4tri~d$NS4;Ql(70F&m>z{^oq@ZR4|`hrTMaLeO1(o^~ux|iylmMaFO{6=K2?Bt|79i{x@g-oW!6ncoA6K>*(YWY3FQaM8O|& zt8K>V8~hG+F5jczt90k2R=u7%2!zcj~?6PQ+o(GIt7GGQm z#%r62a!@{$k z*4zD7Co&nYYoo3jid5pi^tLrs3_)+bsTK5O@gtIkI!3Ve86IM!dpQ1C)BPE$9~=I? zuFZ5S{_>KDGa*gfk1pr4>iBgKF=$7_BMS!r@pxALRbP za8xR`Jt&0hGkBAH+UdUSCCr=ToHPh`c6KVu5x7Gh_mXtiT( zvwMurd)w_aIfZ(YI>Fm3!?)WWudffi8qGpYLVg$$?pY`ENg^I=x7H>y!L-oiY@T}& z0UG@7Ch=C&$5L|XYO+OK1o0d^1IquWsi@crJlr2u(OmzjX$Y6A zRd2uch`1>vZNABQH*)nQpqBw!`A`2;JszgK1Y}zkF`9oLptw?FI(!C$`5{m(TUwAC z8lPC+@&CoaBY^PB2zQ8nvn0|n+|=`8sEnT!1Ah_V8JU)QM)ke)Ydpp@ZgS|{Di zt*doV`LmHX@zB_5Q5STtE_E;ss-Ht$LpWb?YI^c3Inj@aOb@XnlkS3Ae+DNFbSS7u zo;$dH@*~X~?t%j)!3Y$&{N*4t?3bz8-Y~Ea-mqSSnogA zF(6iQ{nMUP9radf`#zwCMppJIivJ<*CDCKqE zwyyI{uDI@32$WhiB0^3Wx3y|7U0#p=lV42U=dT#}IoD-=lMlvAwDrC-F|V3Hj_z)q z-7uCHg7Ri_SJH>*E9MDv(Vbb;VjQ_Xs!;PUF&RLN>^8uMr&U7VCIcTQx0O8naE9vB zcftm{lLt6}rP1K8Dy)+2im&T~D~L#q+Pq#1G|ifUkBi!*sT60p?4SDYn-%`rMfSUH zcD;*zQE7tf-+FN)`PW|pylS{1mI5ixh*w`XJ^P9VD(Eq>{UxE$oFiNq>pTX2@Bcv2 zW~~zwTc3)^&83QF0yx3OuFA6c{5|jOtL>Iv!&k^tp12bZQ`Wmj>1vYx$N`_RogC>8 z4=wlQ!07_7qQZ$x432ut#;Mo{ zz#cI;3p(~tFZ)_LB!ec{63N5VUN99y9dx|r+v82%r+v&S!L3$=j`QX|U7;aHO)*0Z^Sr+9*^JVYWEOjec;FHnd z+%W&iaj1Q!sTzd#Y-H)_ytM)s;i%(wyTNHPNgge8GB4UzdqA_A9+yrdZZ_PeuYCFn z>cyNP!;>7Me&nCQ_Qtb4gYcURH|(6IPpQ_7oZBq&hkwP{^R znA?`~)yS5lCr;hF#DSAd9J_s6Qi5C?6DDuW&8OE3teQ1(*xT%I`$)1D>T{`mJ@I~i z{0)cuYFT;vMenV(;cnAqnQVpblY@|K+Yx@w^UAENMkEvKib}dE8IzFf=iP!%&XZYW zSlAaAKKoVfZ0>U1mRYn{uOd=UNS;_JjH8xrDjnIJ^w!1t$~;T3fC9l2M*GnpECZt? zBk_qQ7NUp6{7mJRJr}B^z%{zuzBYTdsiO?hv!y2_j_4~h!vh-z9Fq;2mO4P`5zIwv zOvXK%RADP3F196#!j;+40m#o~i&jQ{@OC(8#O-MQO{L3hyA+{h=BQMSzkM{W;hPHu zKlAU3cD$Jw*gV*p6bS+zO%u!AodehV*wox$3EnOErBz7L!psNgttd4pXc5t%I&L^K zKJ{?FcJ!~Clf(h%*T5rqs5AeKKZo;(_m;(aw3 z16GL%t$sL0mkZt>yMV# ztT9yjdY+RUkZBkp8hz>t*D%iDiuN3c?@y5?(Tk3dxqkKs$85BaE#d@-bF#2ZaD>^CsM`TdR1yjWM= zrcRs#Q`}1b3vsXY595Lq5INdB0fB+kh4+2c9JHA9>~a;Sge!cy90BCs_@c;;@l`otW3&lDk}GaUgDaf<28ix>mK1P^dz3 z)Okf?o+iyuL3tw81^U>1`{O=}Xhn#aOwa`_XHkutQ^-JLGKEV^8hkiDvB&EZ>v-C9 zx{F)bLK3Cmi{D)W(b&3qNHOrz+hj1yA?s$3y6?-CvI`M#CCb}cXNzKM3(E{40>YL7 z^9nc!yI@J4W*5rmel>k);9{pTIFR0BqA|(Gg`YL|P|c^LGxs!h$0x|m{T(5L*+o3S zG*?{^fhzf)8+tlr)yJPPw91m0Jq*zvO)p|R2Yh|=-_3h33x`%6dyM!pnAa_qB z2y6pywc)t$0+l>DGSx^(5Y(C2NX?;$29as>Oj6hLJCnfdotSzgYVZcbfcb>#8bAjw z_xP9N1uA-7{ihsp%~I-G5X72yM4A<*PqP;-^!r1K^Zc!?mYZJ+sS?#>OPg-6ldsuP z3fPfj=$pph8Sa8&NMZg&l3B!*%4^te`aGu5!Wj^GO@XrRYmb4UrrVS4??P2coZv;s zce=CQTIsjFUPum!WO@O5;N`PlK-7hgnKLfMA&763lsBMjs^nv(!^OsqMMrYC=ZaL* z?d)t9p-2f2(=&(ul1RC}5z;Zd3Xorx{~{PiKoz&^mp?AO@EJA6(QNjKYZKT%VN zz+Whvs;4x2|H5BkH#(6bp>A`yvj&Uq=qismaN$$J=LxW5Zuu2ev#eVilMAIP8T? z7oTe9*xmA+dJaAqvr*va=kyN0ZML0$${0>5e1L8IWd;%(%ghX=5(&Nb^R7Jn3&J1^ zoS4)@FH=WSKVx&Ysj4UI*7n{AgA@bL2jJ#n!4D5uWeK@RRqwzON@0fT#c#;z)y0ol?KECfoZSP~kaq~e#;XC@;# zTc#J@XlTC;saBb1E*VT_(ImY+UTy=Bv|s;EfFQ5S~$ ze`diXDugcMF|5ZtKz*;X=8WwD;Ue44^Np^V?UnP6L-B!fN~>N7&|aB^SWzLAa(%iB zTFH7Ld2x33z=WHP{3>CEGBMB#$1ob<_0?ksOR-hl%FUJg<8K5-3SCW>*B9lH%oTAm zx0C=utAb-Cd0q?L?(Cy2EHob!QSW$$Uz_KFJ&oAz?K8e;H?r^N(r^~BeED5#cJk1a z(q4Y9NDrl=y@baO^!})}y@j*+h4`&yx$77)#9EyWSijf1QlJ96&ImylBgg9Ix$OTk z3hNHvQ0)fW)Me0_OVr(`w>7($-9|#a=TnZZH0UN%?!cQRom8+-X#y1lf6ne@ABf-= zV&0HnUJ?9xjcfPKYZFh)+*7Wy_X9JLQ{3oi-$atE!0Sr`8TjMy6Pg>#=QJuin*7x_ z0G@?LuYK`+EvVtaFdZUtY1%-m1Q?Z1qyR0lYrNnC1`-!}#Q` zA!bF|u8lE%3=Huo-K_+TWQ*U6`OdlirK8a0G*Iz_r8!hbUm`_8%;Bz@@5N`0RZd#F zL1N$s_92^l&9(|ixYzZG4F*PzsSsyIMKq(*Wx3o94UDEl`V}0ix|<*%v;Z{uaEc0{ zPiP<@XP8WApDkj(6S9I036+tEq}#fSpb>JUP^wODkh&&_tnNGvijC7YgmXE!8!S$Q zd7ViS8XBV1Cu}inZA6roGF4QNONd~u|f78 zibFThFz(x>N8j4VbqW!YlQVqDXu(dvmad=;^5cuy3S_(;{5h16pUrSSs^(wgy2N32 zQTO3=j(B-dEJ5+`9i_7sTRgzL@Z0gpi0EsspE`T?A_LhpMmfvMQ=X<@ZXDY#nT*$% z6timw&(FSmO1D8q-)jxA_6+A+<|4<`gjjk_WbN@-dg3PxOuaq@x5o+*iO2Z#|Jv_& zWPnm0M+(s0NMMQZrunKo_4Phci!$%yNi$;j5!6;VzEol-jKbq|%)L%uG}Y$rsK@jg2byQ>`uGAE{pPc73C z_M-($WgHJlvMzm|AD_T6pM#h%YeZvj%{tT3e9irZq0?yDf3$V~C6QU$+gruBS{DNE zz2U`>)blR_V3Y98pDnP@uEO&6>7!-t4FHGkl}d6kuK4%u#^!%G})I7>Hc+=!Q`I zUhfF69mDU(=tLM<236<3AR1E7uGUdn!(V*HV{lFGl)iY z=1UrVU-ba5*(MIzqBWbjrj?0@(+&DlN4LX&g@zq$9 zJ@?Pc86-teE*WAD+bCZqT94hBw$~VGP;1Gx%9o7wPq6~if~JM2DrxQkW}u9O%-f;y zvnfEPPbobYJuj6{CbG=GI8W^9I~uDb^WF1pIEKf}U65PT7T;d*0LBIB;?sG{e{q|! zAnEGoBR6IIhKG0KZe5=~XJ_t*mlYvaq|9Jf918H+hWMWHs?Z~uR3=MfA>+r63d8KFOSx~5w}u;M9m+&FP5A{gv! zEC1G}DK%=-buG`hKl%IE6F$*o>T{+dv-)2)E06G-6bwm{+5+*VzLzFg+vCm1%(rW* zR5>)uOIOGmy5hrZ^Ss{TLM;c4^ zd9P%bX@pZ-9^JB4Z0322EF5VB%dEN6s%L7O(8-S$em{C*vc9V`3+sPR4BD32OWJ~q zT9eEj)78*BMurjF^tJ3b;F~s$M9Z4J_ z*^pAQyv9Fr(U*QXt(HW4#lbEhv<0^i?_EG9zzhfs*o^vYHMkfc6B+6Ba3`rivDzDw zlgw4ukKn^ zIJHi$ftD(iX*NaPE)}Zq$xmya;@5DKjV;^I^E+E`iTSn%*_kprI3G))+_v;L-<)xp zbS*60#u-7PBDr3_)dT-cAYTa2YvpR=X=3@AdO@*8C3a0d^i<=v1;bw00^R;bAT@@! zz7?gbaeN10GCD)yI|7A(r3pZZSA~|7| z%s0ctTN%H6$tv*n1mhIdlMFj5(k`voqrZ{x@7hVHpfpkEvhN|N(auOoF^383U~KmG z-gWQDjU(D~TKgK4;g^4U1V6@|C=F*EEr8U2I`GDTv->JLeQQrOLg}M6=%HOAvDadS zH#&3S2vv6gc+Fmwc3y>L;zXrh#1J*FoDLQjHTb@db;-7O&2DS*t@Z<;D==T=W_N>= zdM9+u@x9;Dd6fN0FnX0Qd&sL^6vwI~jd~W_PfoZUx(6-{aw`=0)ef-t5s5B6ZYOB{ zc1w=T+Nm#Cm1c3H(Q`fr%h<1i!^Qj2IGi@Dg6wk`G(Qo$K88`nOt`@}9{c7iKgeEL zcBCR>k%Q5!#VcO*5`s)9m!uQvJAzRG%S_j%eGRI)lC<^uni6ZPrA_G-M9#cEvgO?P z&&uva^DNTXC@QAhq6TwfwiL%gMwWTAJVnhq))Nj^J}7w!>MN{>NB$0W4AV#vuq9eO zTtsjG08_Kw^)+32GyrLPk1FC0OD|!QFI4iWO?UnzXo{!W5=tyvNGESyRPLhRlusY% z{P{}MkUd|HxatdJ8+YJ5I`ZbWkv=wij^*c|BT0#!gcNz!?X3p<(st z@YCT$fuk#jVNlR(sKo>ZIvpV{t6hboXe@8hkZh75fC9eu-|~ezAe#}9=uzVapE1Mk zveo`8HECu_5C9O#a^?>cU*pcTiXCm_xygQ)$Mlm~3m*aQ?qs|dI5sv90tV42ZzhHq zXi{HyKn@}z8QS)3~(>5bi+&^gsaoJV=*%97XC33!Kv)Q0ZZ-m7H zTE3Wm)}xJWGAk8`K^CtVhhJ24Gx4B2OIX0-+kJnOtYh-kKHN22YF*@Hp|jjuvF!l_ z4kU0sP`%hP0~a#in_>5BT~nr1EI{6wFKdlfO$f=T*<&YVu{xcQetge|NXbKXI)(!( z3KYbLXsUHg7RK0%Oyxy|lmaG%b}tO?xXSJgxsgKT@|5eHfu2Cd)6H@iU@?iC}j~={$to61wrOaE|8PLxCdwL$c4SbL4Bqk zk<1!)0kh`!g`*fgGE}X!b>d^-duXWF$2j)hw)te6ix?_d3P?VW>uGybzQpxAdtcy| zZ8U$flmz)o}b{Vb3$;sq} zWEOGF8d!D>4CVQ!k39s>m0siFEli|(^t|^eCCYpxPx7RdUT4D)~e4uPufWLy#A95@P%>RWtC$qhvgaY;S~XEubpQt zayI?ASs%T%+GH9j7Hqsy4l-!^RXY5sRR)Pd$h^URx0dDnmmRXuR7pJ3hF3!kJOjiBey5_EacQ{|&T!zVCkpbL<*IO%gV}xf zWZDkY-pS<#nDb_|*(xSGM-mD=u$2vZoP-HKFheX>f>S`YnTyp4&euU*#nD>Xrm+?} zoj&t1Wd^r~fjZIYN<%+T}XgbB{WZ9Y!rO+QgiexS`O1f~| zeYtWuf|Z208XW0Mt0wH|{xXK5!H|%UP9ITe()cB+M_W0^)F9uwV_ivpz|9R?cNqV-azE_WZAsvB0_b|$i{^tT2ZWam_UkD$2k0^O z#x1%;VR35h;yNfx;pHf;p^4Fa3L`!YR=mWAQe#$K~U5*3*F zuFn1R)`nJY83Q{Q;SJc5+3B*O!j@-NPe>cF>~&BR2RlT#I{Y1y-u6_W<{rDx8w%Co zRM5MR(I1oBCVrfw!uOyLjD2%MiJ*&>ns3EMwg)ripJe7{yxTs!9y`dgOcE*?=7^ge z#>M5ODlhSoL<6|x7g&@8G)kP9!&a*ZD?`uwv&F()06&y_-{#=uyjIatoJ{Yqie@Ei z#4r5L!H3vV@$5dD5YX=#rVk4?xMov8Kek|0tU(2Zc0UnH->-_jRt9i0?Oy%z*UtU4 zHSR2(?WC|v#`V}M`*W1EYgGi**hQJ-S6gWD^(_#!@OlsFD1XSN}}I7 zDe-onma9$?Ql^UYnujEXdOtTSqmOamG(#R}lpJ6|N+?pFj?rcW4yu6bZb(M--W2)P zIC0pke+gV@V5NAtL83k^Qv6jp-IwO$=MelX0{nT zG$o8A-R2#scpciOT{ULH`Mln%<&iFu_D|)EU98CY(9Ao64)$EVIun)-3{f+xr^o0A zLv#rw|18=2YbWr@=eEyd2?L7Ui7dRw}iStbZn5)_Y}NZF>C~+&E*j9FinQa!*MSmDy8NnG*hpdEq# z+Yw@kR22ib9bFfrT1s74oU&pM*+T8x^;{P>Hv6Nl1B|Xy{O-oxSaavxCT8`sMUrHQ zL3S`jHlEHD4aWb-5fjz4sg%W1Xf}J7DbKeNE5YPMXEn zg~RD{;Asa?Et1bGhUVmLNGO+vEj4V(oz*$H?aQg@{}?G4`bpnRNC3E?tES*W;e*K; z_JPrszpCZBTwXA2jz|^C!_#xdr27w4vu2}f3|6?Z#_CrrpJABo66gb$(t}ZKt>Rb( zHYCWAq)(sbugGv$*}ms}%9G-b0C0bhR^Vg5Px__T%?P>RENP=2i!oU~^gI~=cKxo= z;DjnH3vW31NCQ4AXK9n_FXj|hvTfX9*t1tFZg`OmI4%|I%1%_-J?q;*_6CaF*kS&@ z-v#dZM_7 z*Iijese-U7Y?r!n)G!1tAYB2A3p8~#xK3O&VAhwvNz*x^uPE`M-#;i$??A2c@SECE ziPV4UG~C$k=14TB{8nZNRaeCafRsV{)8|fEe^Zr&&FI9^qex|_a{}dV9awjbc;r&g z&aXO6Fd$t8csk9!c~sGQLzpRQ>^_6HLGBiqEB#TY*RSIW(d0>X{63h1wZVLF|CB%KqfO%Jrh`)KjRKK&=lEu>CP2?PBhte}l|>l@V2a zwq5rAhjo*iIjZ}T>7#%%MuOiPy%8Hven+}GA~^R*W*DfgK;90rY6 zSvGw6u$Ruqigov`N0OM7XfpT;*SX+rmegKs=?r(*Xw9NUFT(Q4lV7wFF5P<(dqe3| zt!)Z49l21|n9Y{T3HG?^`GT3Bp%Co0$+Y;AREzorzwnDKD60-NEJz2^{d%>nht@Id zn}yrLcQ&Q3e*Q-|#E|9mXuy`vIy4S5Qz`m4#q4irPI+k+@Aw5#rI`vm|-WmAF%$_G-7`MGwIhvAokE_Wv zCJ_*aQP<4%0lvK0nn(fD`oQH)lT{OOj=rqw{Uh-!WH5U(?wHhf|f8M={8(oq(OKXMK?z^+5MxKNB)Ca9m8b=R0%lAdZ zQlmnF&UR)#%V)ng#y6&QF9dV=N(V}2dC(i-7?JAaeMMkAQ44Q#bxOo@g{@*%pU|h> zN$rlm`ABEKi&_1*y-(Dn<^kw`{KwvZ{1i)l>UFx#5$S8w=dHOK=Mj#$g4`Dvmz?ICkODZ*}l-+saqfV-sZr;nw*uO|xfTYEJ6wmd&s0(G}OVx{e>i}PI=`yM`Stv}l1UYSV z;PV~{ic4fyL>+4j9z3d()P;#>lB@q*er`IO2S1;){aYvf8xzr>3ibBABpK_!Uof7(q?lDN4mWi%H9U3=^^}DC~YDN3;3}t#yq-ZipF>7$b*jYJUxo)78`lFqL5{zbt@qTWomc8*5KJ8zT&Pdo z0teqmNV_%~#)i>MHWC!k`sp5sip8LpitQxmmtOcTNYD{#!_m)x21366?e?F@PiaI& ze9#4XnZU)PEsd8s^^d{Dy+21Sr}~Pmdo(bc&aTm%<`8$elUzMYa4@ z$*B|A8h$-N91#Np)$icF)U2^7QL-Ouw#BVG2%V)uGZW z^}e$SZ7+I41ui)6y)huD;=i#@-fmIC_wi+2Fy z0~ko}lE@BSCLvkFYcdTqm_CDn%i7p;qa~*or-S4B!%k&~Gk-<%&g6LDPC82sKt&_g zK=>(B#0#l~B{QcedS{p4zNL*n^^T0`CquPUzGEPld4+L9FmNAeXcOV(d%nSaq7^)n z4EkOiAE`;=tb7H=34IW&_vMKgr00rn`DQ5?MJgG4!tx=T<2p1=IAXGDAA|YHl+1Zf zhklYpL;!=&q@$P;b6@!_MRaofbPq&4+VM~`d*3$1w=ROHT|Ai}<80zm2J?^WZl?{E z&pBh_z$MAtpJe(5 zcI)p&wXeyhsJ#Kd``+Wr5lfYp9b6_C`BTFjUW}0)E=*%;_dkKFYTJXnB4@lKp*_L>l z;R^Z9OBtYf-0tSNq*P-PE~a=kolZL*nUu_j+)49RIggUgE>~@4Gw?}ffQD}<11^xCl&YL0U#L;!>l6?;M2jxPH=tth6>PLN^aCAMUF-@FZQItsf z1?DZ#mp#Oo@eXOD&}F8PrK7&HPTW+nW9sBZ?*WxIRQ(td`Pi-sn1Xtmd^R$A9T1>q zG~Jgoz;T3B$ePi2*1OSII3_cJ5=bQAjb`h#*7P(3rYre582MH{UB%co%3E{JhGszHOCGN@TE)z?(iPU6Jx091%G!vWU1UFpXi{p8z>G`Ffi~w(T>6bOTsXSI@ z)|c2}j_$@$kH7d^s8=88`?ByP{bFeCaoVyG+pCBaLS+t>nVI#{B9MXW#85Uro3+vE z!*zYHmq6*c&Xm2z&EscjdnvCE?;9_~E}ZL1)Ge5ecR*4PzmlgJQqlRGU(&nl_OCbX zUB1~Rj?xfCF}|2ZwNEdT5gO1iVFD&{zZ(tDC=%+N(*tY_@n!XRg* z6O*I=M}9wZ_4V6j+B3A69N0KKIu9jy`^878)rq+eyt+vEY zC&ZEh?(bbthv)QuFzfEk&|TB4v`i-Fn$J0TKZ419H5?NgUg0;lh_?tBt9rJo=8&2_ zCn{{ttDB-Ez8Rs+EW=c;@b?Y1jD%md!59cb^8ccxZW8_0AY^T$xHp`81 zYUNr2t`!478`#N;!md!9c^Wh(%sJ6rA~O#}y-B)F_Gb6PX&ApWK)Od@NQerowED&| z=D&UtuXrm(bL)1xD*x@<>+PYW$g8_-5wFeGWKu+-a-4K-!~%kda{czlAKBD{@4Q5V zviyp8@-KfH*J`??vRU=7EpmH5Sy;7lhaXlln?KzQxf4iW3)RJ+chgl{EWLRlZqw*d z*e_--8u9(OGwjVM0Q_R((DVHBJq3f<)rX5EX|_favHn^qTEOXAMcIupX;LnA)ciGX zZ#tL`wzsCa!em}1qi?ud&v_rY&x|NB8w%F#KS+*SW>d@c?Oz2=6yl{Bu~JzJbr!iY zolRWLX*S$b5A|s1b0sgy?kDc5@_xS!5RcTOGmaXyr5dX+pR5XJzS(92uT*Vr#$m6G zJVFN6!YH{yzIFEpIr@;>Vt_jBSqL0VtX6Ik&dPqkp}nC|X>~sycJ1Q&Dqknbwp6=s zi$bH|Su>SuO;Uj*eyj$QH~Y+MfK&`V+s1-1Fh+qk=gk!5^m*hXT~`bc()}Y!zd2)S z4hw`R@q4YU&t5l+9s;8nt67VAHU5T|OOUrYWZw1;&g&_9u92Uc3M^-d<%xMF6>v;@UCTLQCRP;m0anWjHjt&meTeCO_asnoKeA`sCH}s3N2x4-$Ouo;t4TBLrJl14F` zjErhFJ|OhNx}MBbc@*mH@tX)(KbjxhPQ>2W)FhUa4(_?!F}sdt48(|obAVpV(Cg&( z^=D|#Q~PDE`2@;xk*NGS{UpdLHbhWoB&tX~4>fyEJO&;MYM+IA#+V3uSLIJ(?hJ6y^qMzH_3ht*>wh~$T81_cYZ3=r@Nw5Pyk0JF;D*2(Ju`c- z(k7CP<-3kG?8y*%SwuT@RTI|3=IcIYsqY8?UbZHFXZ64`1!%>WJpg|QZc}G$RBKx4 zDBNdlyms@hEfKwSD>aAx#78#?6eqY8--;5(?kXqpElhmsRyjupBFr({z}dvMrD2h4 zL<1p-b5g!0vW5mX9FfL+_EfaHRS;52Rna%HIfB6;}_45K;X7ei9BN4m5iW^+U z-9$CmLi}k7o}cE*$-f!@mE_?2K4pQ{R<4@^ec_~8pks&Wn=U+@;=r=Z{)8&NNC%_N ze%j&wnvZr6*hSLmxI5wf6Hd4l6cY#jJE8S7|E>KUUWn`RzdC$rX%pdD( zFcWl2q!Ug&J-UyXEb+?7gLuibD1|6JNdzW##{H`fLni+`7F)oa3U|}W$66hySJBJl zxXy1iBTr100w0nGyyV~*mKOrAVx*StygBQUHf^1poG+@47VG&A_xJ-^H^|CcA2Omp z?T~_?T)&_pjy~bn5x?t9yRpCZCxw#^k?i=_TS7psa|`4gaqUOZ3$qbet9u~@{cS`p z{zgq7Ql+-P&i|i|Kj*Ir5@AY^=!M|$CVMoo<_0I?-kC5hhHsfq7Xj!eO^dLu5>hkM zxQ9CRdj(kY``Z{Z3A#;(T3^z>c8G{O-i5Sfd?w+7KzChUA9AINr8S=J1vfSeHsP}w z?#Y*xM!Y?|vpIf7k%k8TQ%$Q%__H^yS)+w*yD3xizc%K?+p>$5^atC7*W7f*5 zKmVxANMO`dhhkT$#hLcBiPCc@NnhXbDHh%S7scsk&8wysCo7N&@nV7+5&Y1>kvwlt z01%Y@K6^*r8KSE4U6AXSn+*S92y49&zi~%^7bO$-FZm~q1?#CTu-HK)PisQOPRe@V zV*>84`csr+w0^`CPU^+eeRnk;*_^%FF-g>n5+jC8W&Uv*XUz1*=mgt-{oQ~%S>Vjy?d zRb#}aBDB0vv)E?SYQJFc|2@X6+ZWyO;SdoWGdQgPd5D zLTXzyuwqWMYNN@!8V6jFUP9d=kRG$vy7XcR+TSXDjXBZJWs>xiD52S|e658YYsEb? znB;`49WCWj29!_1-#2IXatT9_8~tXjht%UMDxF1ESKoAUBH#DRz6~wD@k_ciOe4!Ld$z7` z^5)}5_ONNbQ!JfGG*P$a+M*Jys^r!6jvK3MZetb8cPCsHe(H+i&Hhf&bWbY@@r?VG zcc3PGPC=w{`2K+B^6jRh|3(luY<}H1mvSXJTNd-Jc0FoMk*3Dq0c-L zAu2*(6Lei~L1@wVIp1k4Jr{(&)$yIpX4W+@SVW(6p{|L)srwgbw#b?@2R zk6V0>8^pd$x zK@t|0ZN1h>pUf7eEXs7D=^5EtURALWC3GwlC9zA=n_)C5tcO%(%z~;VJ_7JSD^?wy z<8UnH-~ivy>?w72Ao-s2>ue2#J;|*Kc#--Z_soSG{OOmxGe+4mvIHk@AUY1UkCd47 zaOU(!g(w8D=HK5Sd%lz7y?bJTnGq z!Nx!ngtyB~T9xa(=0Eqpk$$FhfPCX0p%9Zv?r*Xt5&RDp08L!HE*WoCw^)>JyB65x zZQ^iN)Mg!*1e@RdvCJ1&sAkwYm)6SceW$Lz6+F*U&=*4v*{flbz_dD z2g3j&H!~Jhd1gZYa!*K63EBSTN^g!o!^TZE|ejs&qpt+07YbJ6dXbLuplM zf|wA;vlX3txN|L@brU`0a8qf0)Os$^{} z2aoZP!yiwvW2ul}9*WHSg<@@<0*MN^sY@nqT|E2+y@+fus~w^8c7zjMxP-!g419y!q$&sD|IA>I-$HI*|8md86h!b#65xTI_5^gK=#5kFS^jmGqm4?R zvhrS(e}xC8wft9-IWl7wapF%qa%4g>-9t8!pKP1`Zvqm?kHQ^{q!gwC;Y+D?9WOOe zgYY+*3;vaEPd_zofz&imEwva<6+Na87I7I&WXnN1VxTpy3%dTd%>JKqxhkmbveRe71ru{#V~_O&f4T03KL~^oWQ!t|>F6zKAK87M?6r9J z#Wp>6_4FBn5|>0~_+HEQTotQ^=#k1DY)7h2cT67g#|#rw0K`)t$j}m%e%hy5z3$(V z?TPK2O`6@idarTC`mJd$;!oD2f2dmQz818~Q3-8eM@4nMx^d0Ap8sc}`gw~Gdf zvW_+(?k~9h&K)vnRfqE=GkM)>5Z_PfI|3f=cnoomWIDNT`ct_GY>A#TkxkcEM9}0- z7`w3zd3v6}e{j7N;|yzc#oR#p<#IqenlHBN?!i3A63UT*1oHBDNJnX&ME5Ob0V@?i zl8gQ_QQx$x=f|R-)CP9P?m#w)rR9lPXTD?6;+@D`JGkeupnB~D66Wv%&JvdA^%n`G z7PEkMUEC^e>D1EC0k{6?^Q|>)RGdkjCGJI-uPVP(SIE_eg{RVL-yF~FiEyk{^O{M| zfi550mmp?md0b1PO zdIx%SUk%pE-pd6nqhIujJNQcIkR zOU_oizRg>V6+`?ps<+P8If|S-t--JNMPX?rm&+0Nn``tG%!?DDK1|~0E>>phv26+k zE{9GQ&V+2gco)l+T{tAe=_ymax|Je}E-+4yaFWh+k$I(yI-S?g)Z70tn?avE1yJsV zE}3@UoiHVQU7yI2|6H}&5q97?lRK+^Wm!_c|XMox1=E||s`hf8Od{7Qn3=up@ zJ$*M916pAr2L24rP=pMvrcoN3L1X$;rue0(#0$ylqUws;l=xiIhI+nIiQba8$Kvc3ekMX~?(-Lc7 zpZI+{7z8_T&&-1~!WYQ>*52EWxH+L7S;0;8uQ4a>XEKVv>uT}l3D-o)mOD>bZ`RRs zq{|IdIaR}dpiYETsCr-TWd%lZevm=Jk^1| zuY`R_yTVF;{=JKFL_q1x3wy}+d?t!{#p^O+W>q;WV~6uo+CbNX;T_LX;{iv=>Ii&k z_EG;m+~TBi>knm|VY&cyIps%s=~-2t5_5*-Srb~{grr@qnWVJ4nF`olJMS_mW7xAt zjqAw!SH1npZ=}N+(!N?Y<=!XF4C$JV3~fMZ+qFH{(z{yIwGxW>vWY;=Dk+DH0zy{O zxj;iGqOX-SqR#;?1zdnjWj=}e`Dnk0vzE9fkv;8iX?S5E+81BS3r;6#{|7XK8|4UQ zw+(dz*5naZAySo#uvFh;Gs0+Pqx82ty6_&cdETBlB6#P@C^k;>-i%NIq|2X@D#h5` z{bVfjfm7t*4CmJXi$|Yl2z50446Dz$#uc8UeiWPucD)!{@|&B9)xjC~0lMo>f2hUl zr;Ma(ZYAzch0^}sXS%Q0=5rGAek$*+YP1A@YW_!M^Xh>7##2ICFXJJ(x9xAQ46S7l zIOwxu^Miw9a(8Gnr1NXa%7!D8GI9r?aDBLS-SFvcbUg@1TG4pQj(*v&atKGPh}jR> z9{`i}VdVC<*pY;8XY1WEB5QTwx-ndj_6Vrfc>4-xlZZXmA|A@pn(-Vf|*gVPDb!s``kdlyelIHncA|rmiFf3j-R9T1x#Ms7zF3Xq;jijs; zy@B}Z1FX1@j!67uHvF82oJ7n5H|J2+m!uB6lM}1Saj$no1}Ch$Z^6C@FZHVpO;2kf zWw;3`Yhb@<-KR=9i_Sxx4w5rX6H=C*g3L72>WeB8gD;GvL9|qxp;A;4L8+h)Hxd+> zE|y{~PS1MVZimk9Q&Xkx>Og?LzUeKbb~Atg?8orgqAEk*9P3ZQ#3`qCI2MBfQvFIP z5ZII_qjewM)9~Ub{E?&pYXPfyjEWS0rV&SuYW_OwrHcz2?tdTn2=j|AqaW?n(w z17m*-oXh)mw!KXrxWtLoNo8i^T@<}$b;Tp}=)ktm_ZO-rf<6s8Oo|}AT*R7z5g^Iv z9Ck~>Y!3NjZ%XF+MqLse*N%rh250%o%hyasEG{0IMfMp)LG*+Uj}04Ab1G0ud1-t* zpmQ$k)ysY90Rq@_=jw?0U=gb!?~>-V6Dw}L2St+ZD&$Wd5$l15)P{(@Ul~5~?)e?M z9H`lkAT675;2H7}4ZmE2ue-KVe%xFO$pRhr`^g%LthhFQU%) z+L*JW1d^1V{wvWK*`tb!FtR|riW10Kx*{s_its&LeDE_QyM0ir&Q9NNLxGaiH+2>% zh6t@i^Nys4BhO~w5fLS}IS$T>|EgZI=xEzC{+#O2SD#^2FYEn-3_-bUaSzip;vRSI z6l|~#tAOjtT_F6!U)YLZ$9eLYUQIpkK+EFuS!rGnq>PuCaX7%;Sa@1S-r{i?D%3c` z534uQa+>BeXgJp?n~8Yj@fDDWC5IoW_f$9TVG)qjzvf0gdg=46n(;vt>6T&k+NFY| z;ns%VFD{&^>-y;7S74YT-bRa|B-IN z)%8AwA7>+QMr#e(kvc~+1;d_)V-)(Jw{C z!Gb+K73PZ9bmLKp4~@|RLI^D<(B`nlqZF0a5N?nydM0UuFP$#C?%VNv0`rz%hP*c) zkEYySa~hf~{V@!wCz#z6VSzp8WUsOqBeL_D&Qm=xkt+FOPOF$Buy^4X;+x2B0+KRe zYT6+3BCHdV)NZz?o=7uyv@z$Q3&!qTF`c`ly+CYYW9&brSIt4|6OMtfZ3n3{W}Yl& zS@?_v@WE*>ymHtLXdvYdQ__e1FPUJ~TwrM@(d!qD$~P$xACI*4koctVpL|%9<;jXK zZY$jPK3V})tsWHoSy)zn9mMNaX8^JurA3b+iV}T9L}iWPiZ_`TMMNz{e*I|*-X3bp zTiiv&k5Ud!9U-~Ap08%?XSoWX-|V?{SZsDw9T_{6BJsQXy#!2i^V}PV9R*79+yVRF z^N{`8yo;V1pkCg@A0Qe#8b~v zS3fz`z>9%5e~Xl;Fk_OlsD*_TF=ui11cQ9#Ww|S*tdTNf^dFv^XzttW%5z>~$rNI} z5yjnu>Th$lj;%jMM4{5ZUj7f(3Paz&;mMJV%JxQ-c%)E|+qN{Z1M_TROk9rPojZ4q z@avw~p?W%8pWY_eVeXP(9J zRJAcjijd87`{^oE6{gBe!?q>@w^vthx&I>FM9R^=Dp%uq?NLWk&W=Q7HTNJaGUNnE5So65pctikfZG{r2$g( zi!^qKAbSr;=eFJn>`3;@nFdovu0kE49L}jRV-nA?MYZ7yQix{@ExLT`31<=!8KrXZ zf767Xbs<)PdfK?j@?MPCAEA=DDN{VOg%o50<4aMQoqTuDGkB|Lxk3VJQluG3yy)<; z6!%S6wV90zkU*KK0Jfu5vnC%u`Y+|osSKHIraPNip3^)i(DTJ8ZlZ6yELRZJ`-<-z z8N{<{CVQ%)6NoVko;E8!_dU8JFX~*A$`oT?y;IbviSZxN;b#<+hS+i5dHkEVojx` zc;*oU`;m*kec0T1DxeX5qSPNQuX^tt-I}&q(z$yx z$Cv8!NQfL9zi+xgsX+-9vC>eX5)BxR4YO*G#L^6Q7bQ=i9)%xeY-DPXTq7Y(zo7a(F5CXxbq*rgMQZF^Jn zrpU{PgHEkCGd|K#q>D#yo1d@lY(&^6>b)*p%;dCH`|6WOh))|B+7%Z#- zE^N>7x57kZ-^);sgKyT8%0z4f*>|LzfC=-^Q`>VJcZ=U$$>Jw@i&XW=kqs?ed=xmHPM z_by`Ji6*343%Y(FsuH=%J{NqP#=17^lUXAxJ3YH9g0~Ku8O})NzEIy{zWB{Fd@y?U z7AGdC9oY^zvy)f=TR`-}O}6$&jZY;;h&;l|nCjj%^|zBx`DEHJ5dD0AW>xJ2qymOv znN9E5_N7RL+7#55Z&hQf_gNVX#zj`Qru6L|MfmpDhA%lW_k>O%9|+!I@LIEimH6-R zFo%nG(wW>>EJ*r0dgkMGFByY*2U8ohYFt9t4oBQ51%47mL%(r_(?t}dp7K0`cTX+} zHGHA&WkgCqMqd@J>W@(*3Er;vFpChP1utTG)UGo6hXpTXp#xwDKQi=cx3f0(!1^kO z$|gpm%JNU)C@QrSU-3c`O|xqw3OQ>Vi&IT} z7z!P;-Q^Vxen;&s5hY?l;VYK6dKn_3(*IAP1bvP+Xu@p3p_Um997efV`f+SLglOHg z>U31HB8+y}nWnQxd+lh@HD=i?@IZ3BbqAB#;tdIOF8(L_wy5f(xX*mZdwZ#aMYgDn z^gcX`akN`|CAN$b;Bl1`qZ(e9ZnHuFKBW5aKy8E6B}CWV6bmGTw+%B1OIt%a`lzE` z#X4ysjbLbL;ih^fbHz2!x4tUEJyP6TB?YY94J>Yo`Sc=?kd3WPP{!{u4?#uMn~x2) zxE{@m-%JcF9WF!ONs$TE!hDueT{7xJeZ5&mE3I)GYf5CF-qG;0>UESV;?9p7{co&D zf}!%(9hp49IVPI0qpnRW1p0?Q*iuV#ki zoivvm*{0B3QQn{r5!UBDp`J$!(-Y!VU#C>qZ#8nkJ5(25H4KDaBjpz3gS@2mF+Vq} zWmBEUz_6f6rv+%PkGkM%bfiQN*R_7)%Dc{{tgHNQ*5RiD0$kQ-+FoQX1+I}#Qr&Eo z@}skoYj%~2uPEpaImwC3Oiv<;Cv7eWgIX685EcWibTqab$hsQ194TP@&wZ z9+qkx3MgDa0`E4@dOX~OSHcl~G|D5!a}Ss&uie^T&bI}flrb(9S(AM35pA!R%4ByN zVI}P-H{UtdcsaCZeSVx<`6G}#d2!JpEX{Ut(XsapD=%+5p(I;??nLXPAS(2zw@6wE z%PJZ-YJnJVasKQo@O%G6ST)xMQl2qX1U*~a^ zoh%yV1Sq)XtHRWPv|8pl75G_%+iyDv5FS57Nj$l%TpLB5>*~hts;*%X$k2 zU^hD!$>*28GvxOzhw6+5DZ~dI(Cbg~oay17QjV>Ti zCpg!K4H9@G@-9o5OohH%Tj3Nkr)cTEA^w+UKf)(o4x3m;((Hp?ELe<-yr~#@hpW(f z12`%E(=#esMKWoHipTH3GU+c?f+1aI@CQk`TZsK%4L5Y0#BT0f_m-E<@l2bAF>>UW zOl2RD1onsJHLsP32-At>wR0Xq(xzfcZ31Q@F__zXJf=C0(qHyr-)$UAdWlz><=g2! ztSJx3zj({4HJ}~kDE(UL89PIxRgDTlZixK;2Md8?e`fIg2EDr~jkiK-GQ%eR?uwcN z@UUl$JU$V<<$@;+r7tqq`cBfcA2%ohYjoNJ$HXg)Kce$?{4MS2x4M^RhuoZ=R@MH9 zh1ko!t0!Nb{*iQmW6_za%__PON(K1EbY-C3;VC)oaC9?sa5D?<$~#)DckTJxduo@z>tifyp z$+tEkH2pO(th#zEM1b7*|M&DA`SL@t zXcJN|=6x5{X5o0K$d_+a_As5{>G)%zh{re~bx);~=g_(p3}o|3VM;&@Xai>*dzfJR zs`ECT))lfon9{T-(C~~Y-@6ZvNHG6eaQ{3*SoW1s3xyIrDxSbI0QGKI7K9_DEQbx2 zTj6{O{W6s187(|J1!MfTB^>OJdCxjWFq?i?_1=_okC?yGiA$X<GlnSuPvVqK zc>9|L7UIzRootk_&2%MED>3HTc1Pj8U?bjAm7dYEtU4gEOgL^(+Tn2#(5A8)@e+#` zz11rdbLPG;mF6)z`nQPLD=I1~;HZY6@!B`t&s5I5>2jgY{W2*s!^{K^E05IS+firA zg@8@Z<;>G}*i4!#^;Guao#`VHH>XkzjE4qo-V-q?SCBUEmi)3=$fu{~|3fW(` z#Ys9k+__wg0s7~db4A6MBAb+b6ZA3s`|^=0k2Q{6{jKC1JytTRv&y$b&hE^^(jyrt z_1!g`C^mK1C->mTLHzgmvhz4^*D3DuTrbLI68Cn(&X@l*G+%j*W6B9l3+Nai6XPwa z+$ion*cn!87Wv$@;7p6Ab;!LRb_Z&#A4D*l8x0^>lv zoKYEb8U2(!M}|E|Gh*6{$LZw?q&bypj<@ao-v>cn_cGRSPy5aJtTjhh8&N=;Rd*YcMl3{mQ^w{ zgT-1o0-80tC0Zp$O?Q558Xm=0yYlV)EE+|Gal?U2Pq2jfiwKMQ-$*77X%(YsbAgD5 z?~>@$)33mtR#E%*p^*!IglTwucvBWtJ&JWxLMUBfp3g~jE;cTSmyYwG z5M~sEl&(-m7VTzl-Y?b-y}~okS9QLjx}I|z!)P8wh*ZL29d+z%YJXplx)p1%Obd1& z>ghAWmT{*@xtkd{zz?0i-Kbn;pr=C`2TLC8SI(>%O)0u_LKBS=slRy}sBy}m2DqLWmr3IM?~Y69$EjHDYpr7X)ienRf62E1PTIg;BHXOv?oKwOcV5 zCT1HPuHSyB#kA46Lo=?cJ2$w|+w6<+rvNye>iI(fb`fUKAVT-jMNT(qA#fpWQ~)M} z?7i}4MnWVO%EC?IqzhDu-&eDqP;PZNxuN6DuF0D^EaGRCHw-%O<>Sgk4Ua^7A$N6^ zKEob9HxF-peGSkA;+VGHB`E!(Tc|*`f}~DgzOnY;xoX4I3w14%!FONd=2v_&_du$ahuFJ0M+~&CYnhdlPe0 z-8aO~Y_* zdrb~+GQZ2+hi2_yJb88%k^QOV!=cjUQyz`TyxKaHC~|-ngb6m@@(t$el0H7OH5i4l zwh8esLF|9vM^4FOh}&Ok8gTo;IYEzjN&(~(Zwqe5?m}32bL@o3J$Ht8f~VRzi_=Bj zVvQ6%U|aH6?$h(9imS{j29;~^ke4qAr0);cC>o+HZuvTvLo9^xCZsb{W|T5_0n=c8qY_Oda^nI z_+F^?>om5$Qm#@Qe$|5*=w$BKQWoCUbq8DGVKwkcr=}wz8 zOG-z?^;#=ORbel{D@jl87{D&Gx842m`O z7T=Mo3s7tCE3My$?Wz-0#?cUR$I;50Eb1*eIK%198xLQXjHh$-mTf4#U*z}nH8muw zzM)RLcRDvHpt{&yO#hST96dnMmU{d`K4}O=KtOX5-*YwLohU%DS@A$jebz;+ktsN{ z0c?Bf}U7T_JaI=7WjST0~Kn3XEX{ zH$qAqP(!i&Z~4p#GZH2kM1%h7eFk2S*jR9%H=bT_y!H4nlK_#-W^{Fval+!ZCcc$C zljXa6F=Ij><^$M=qfJ$x-LCJ+gkT22og6J1;^JPfIaek<^l6V|U$;BsD|V%r9X@*H zpSacnE1iW>%FFV35*73gj**l+%K>50%ZI&?)}W3EC7=U*C4-`h@t0A>y&xc6Ws}cb zUNy4#n4~W1e5K~J<`wFr&m&2GmwSC$Ti&w=BDRRnt=a?CI5!TJX2155#kEI^Y^wch z1B4} z&Z08MH@^BaQs>KVA~$T7Y+xq(Q_hA|Q|sCiQ|4H;Gl&OaVm1|zgH5%E3|ILrN^oaa zegus9h(EG>)>*_YCTV*vlZErxHuvPtdp7>jP1Rsc54w1HS$07d^Yc(rrHAzVwTTro&8za8&oSQSr0bhbMSk zjYc*y#*v;+?BfqH4t<*Sy70*n-%ka7Fi!s_^)ZqJ3sHh(bKv-3xVyE@Tv< zhjsg*qj;tZnZIy0SwdBrRZ5OfEKaUTw8q2f>lq6;pQSY0>Pr5Td*O8tQv75m7*x#9 z&Ym$ijiw4vs3IUDn2iv;qTos4d>UvBI`t4eYF_{TH>B9UWk?=;Y?%<$$b$cJ&)D{w z{l#w1gIWn}S3)|a2DCQy=#Nl}c9ygePZCVk59U?Ppr5|`a9(OS+F~uMGs&i$nwEB5 z2ozOl5e|l&bYG$MWJU07J5A@kqnlEH=mBCFq-geskP<^d_~5VwLG;KntiD z<@0dAt_V^;9>|Us>!1;J`S5FiQM%Tc(S#r24|F3E@1MvPsG7Dw0$3RoPB)*59bGS- zhgCkV6~<{F0cosL#&das@|zkTh-H+u+WX6E(G*9>CWp+oVX=nS2V;~`331LoJ14IM z20pU|3748NtA`1>?n`M|B|#&D`juc_Uw-TJQTI>DAwdS10CL{^;B!8rN5QxWV>a~K zDhQ9;+Lv@pzHH;n@-%Wp4lAi}Dk)+yoZq>|V4*#k2%EIF*PqNElJ}VN#*x=T+Tc_E z8ny_ zF={U`+_=Bfv-YQ?Qc69UZ&aP74inq9RxSZpwBb{>$`_Fm;pE4Kc3GacWFUSn&pm(~ zg8z$?@OK8vZma2#&#i^Z310nNX(D|Ft^9nUKiu50#F`TOb9^i&y35lfke5?q;?r1R z4qv)0_uCTljY5!8TU%N2l_4C}ld?UZ?% z8qrUkqrMw;?9f~;e?>-xsXx+%O6(P(+A+jO?c2r|nVu0|h9f3k{>cMWj<)1qz_JFK zj=rU<*#$KVf@G$&=qptsnnqh~QHI=m?n3h_4*~phIpp}P@uruav}HeuN7+O1+Wfx- zs~(WRL0q=eDiV63AODnN{DUy#(0H=2&9>$TKyz)n%vQ|`Ry?^PJmXh^?c8TPH>T;- zC3UFO-yF@>9RoQy4ZhEhCqhbyIIT0&QK!Uu#7vrP^lY)@_f!yKl$xj$IiFh;bjXrpI(W&Y&CVx zaOjt)bs;Jax^fu(z7vt0_}v!=5wn7Ek5*?g{K6|tw#J)rybKQJ@+uV`%Vg|%)+5xSgKHRLJHi!?n7BfEuMt;$24ij@hpWh6HJFY=GWMh zTV*}jtPgy@JsR0uD;EUIjWC=?@_#*+i5BjXr5%YHfmaw^9yi38Bh6Mjs#EJ%<&Pfy zf4BZ3*dUAF`W*Kzx1~1aW-xN~X5=~Qv@%iR3?Nm7UhGAAqce`!Tv`@JcU8;)-;V>? z+Deae-$m6gNz5%pYp7$}!u|W+A9nm$NVt$n32@ z?m5kDf2a;GCm^}v&kBp7qx^r6$#rDrR)b%;vPjL643xT$oPGpKSRU2jjANv%_RMtW zdEg_tPmx7z;@5uQ6pyJ}wU6p%!fV9Qui6dMLXBhK(AHp#xVM@T99n6;r1RKflW!E& zUJX_RME-@*VQxWEUa*v{e?~%gDQ5$UW9)nVY8{-n+*9>u48FoD(u(Tb<0mC? zn%uE6?mJI=i6U0h#(c}qPWg)Exz&r^WLrrWL%5lid!6`eu;9DM&%mU+2fy|@ zeXm2PM7E~=?I#b*%~~4XkX}_**mpa#x1UqgN(H#&t}enX6C zJEac29M7F&v0l5^VWR}O7FgW|^WAe9o;+`>?+FEyH|!W>uxDTfOr@mC=@+n+I6sU8 z2b`ahe)?W_NzS&`)oLHxpW(-M5DkpLO(U|~bSo#w+;djn+c61B{_Ri2I?UgX{F*DzC;3hcTDlS}W?#LwO6*@;_qW4qgWxg!O%#8AgYCegqS=hZn0sD7d zHu$ZcrvreU$94XNC?Ki%-vQxS33=+5L&=mS$m!shZs(@o{UvW|4t7lXx4#S-IHtWy zGBX>{OydZ;%2^4LKAX%D_&Xxx=<4hrJ+{|s+b1W&a4G%3822GQD=)nCZfFOWnUV8F6bPMegY~JPe*7G^+#M^ ztPmUG~=x?{>ctM$0t2M)-Z9DMS9 zxq;(b%cisdS^kBnb#;LfdM8!3U1q7*_bb^9`v9T2WbUibif&U9E=w9+9KF@ZrHIek zFm=R%C05Z!1nEnWs#q?6nX|hi$0mo*!I4k@DE*P;FrQ=*9`((Z zvKvb&6t%LOA9}-x+>0*L`?34AwvVWATqtl7sYI~o6mLCEZ^o<<7v%xZF$JH<@<3md zg!(KML0Vc2%{J;njx8X=BeCFM^E_6?$h;f zK_-w6YBt65y&eiIy@e>uVe<1Zb=gG3Ib~kX(J0XTWEJ-LZcXG%&yj`7(PcCBjmMK( zx)t??^_PB4CBOyEfDWO-Zm*2-V``-vD^vGTV*tWO^LA`?wkN}T=*IZ9dXmk~Xd@$=mHv0K}QCY2U-X+LlMnvF=GD!C-5Ltc zVCCC8w^qIt@#r1MUb8>n!SU?+vHd#!)}7VY`~C+?x!KOS>&(sl7`ff+JF|C1Vj*Bc z^-7|lrg_@&H2JraZX!kVkx`8j5&h{6q5znNTx=b)zXhN9C;<+XA<%WAT6<`UpQ|{& z9*?JtH}uvg_D?v#J&r48MZk07K8lCe_xg5Kxz)FW>pMZf-JL@YqH|_U54SD0fJwI$ z9`3TMTCWmtw{h;C6Qz0fPU_qqIDWs79NF7`9xA*2+I*MW7E?dJ8g}PZdSl}N7>lP-J|IuDUh&g+>qf&EA=-B9$SY>?RLByhL zasJuumV%*NhlW){cUP%C5W8q9bZ*TR)5-qQYkJu+dwlgcUX@H}!nVu5_CK24WTiZR zj%H1Wj%s3SrA0B&GIkC-GtAhP&ooOi_aUb0J|F0dz-wT3fW6F2fIVQR2sH*u|P zA7ji`=$2&P)y{K0xl2%1q9T*Rpd*3kCJA0aQTb0GfzH_+B=hXTfl~_6Id=lI8InI9 zhmEte5vJ|YVib-Qc$*;qs=K->bEx#QC5+QOBD1Cjr zm_SCbQ0~>PHd1|{#8^eByNgq?P^?vgDl-c<#(f|UxUy7HN)bws=d&dW!bxYUS0fry ztzSkDz$20S`7~duv|ego@pygzSr6N@XH&lFvs|57!CyAR z;qVCESuB*Q4_Z4b3u|MHYnI*KWZ+cUh})E(bQW6^ zqc&}%+WsJBLi9p}av8$xWI(v~TvEI$!?Y8+G5ghxHbz%X&01yEaU*DhQNg|{RcErd)$1->bW*s(V zZ|SThIN^b(#(PKOTD)=3i8>aU-oBi2Djiw;hJMGUDo3z6EJ?l~+(!FP(L0bZiqzyK zG%3ktcxr*yELKe+zjR(c{>gFc-G8NVN`n_9e7kIFUz?wo%eSRb>V>x#+Ik%&aM z^6nj3TaXfyE7x9z^frcs16yybn~8LGDh56P_FMUTt^{V>fQu1}=1|f^U)eWrKElP{ z=T+?b0VQ(O<&VtqZO1v+f0bOwR3cS<-)<47!$q)mXH7=aP~6D2dn`##cD+_T=S~4* zzh=}j&bK!z&9l0=b`LTQ{;S*Lw|qQW1wd_83G^+m2)Q$FrZ79{!;_|HEpO`ByNvu# zJPQj+hJ;!T9ZBIs)`JMbOOV}roV}wBPVFVX%9z*JbDiK37 z4LWoM!dpmt2<8jP1@727D>9kZSN|%ItVPhyGp!fM8~3_diJ-x$d=v5o=A5-!>L2|h z?qGUj^$-DqJiE1u6qX6Y#evRSPy&mD9o`9l63gAuA=ylTbjUZO=4V)6WF4jz)E3aw z5G&hag6_T20-m7oH@Om0m+4YZj{q+RoFVMCm#wf!Eq;XhO27Yh_~8vo&&K_^o%W4lk!hpj>X6#+>7e>pV82|?obln}c0bXx z$&Y5b9cB$31I7yPQ zHuHa>_TMj1l?NQ8O*b1zL4syU_=1W|eLRc3EZ1eM9AKA*t7+q#4_z659D zzJQgHqEEM*NXJPequ`^9i#>OW`bYSih$`(c`4hE#kD`JN_aI~MOb`Dl>NFZ&q)_^G zTWYfT27~ivZu-U|{JHQ#5cf6@h&OvsLBeBk>RHMBIVAJBU#|@h8XkM3q2taW;v*Cv ze6bQUyt(mYyu6!#Lk|DtF|C12uKK`Uab_kkb|N*ngJMkzbrU_<0lQFUCD67R}H@RlCKndwqMVE>;fjpJB7_%%sVjX zIzRo@jM9*QVzNgGL5zrt{Ri9oXDr-veJpi|i3PH*9OueIKI9DPV55(@f*9r|zwh0Ku8+5Y1TLd3BTt(O*!f>1BIk5%G->utED5n8#2n~)ToL-DGS z&QwmX7m+hU2bV+V0vu~yz7M6HUcSD*49W#k8E!SEqxi(UcBI9w;_D{D!or9I>)w^>k+uPd#Pu*DF)c%)tGbHe{#qE6`Ne73^-e-kX+?l{2yBf&zT#6N#PN82R{GbN6Y>(hsS z^925DDVAWus|F~!_bNDG*R9EeZl|dx2)u& zmF8~5kA@N;%#!utJ@v1dvF`uij?b5;O%MbN)m4b+)PXq1^BA91Pi}9zQ2*L+h>^C5 ztZ)3xh4eq1{9nsBvhUmxPKrw5KSh8Dlc4#-nQqSJx2m7f(0OQ#xcS(?-PW;3lA32p zs{&cMO}R`>g2#k`Pw9JUOK;+b@!*?k*_!TTtF`dAqXN6YxkJ%G3a|mzbL!DsZNI}W za|kg92S*yqw#OeQf<%z?{TQYsI>U$YVv7KQS-7I!FATz@J@3RQ4zRXVnl@(B1e9!Z~? zh$yb&6ve32TgGx@laCW%<3Vu)yd|GZJV0r9!x%*7PN0 zksO&P43E~1oeLPl#e&di7K)KH9zgX{3vu*F6fMzW%0y zK=VNtUB+BmVsk*xgyBl~+k(!=0Vrmm!<;*QfQVqXK`*|W@O5g;6-QN5F_QT z4_!h&A^3@N(LSOB&xzwYo%;|X*<%)!Fxf`r79_e zi@d6(ct~OiKS0w@pbZC%E4bJCyQKhE`o(6u?d;iklvE$K|50A8r=8?K7Qd;YL-);_ zL3T)3LVftlG6$q)>zDDtqJmeb>0H2LueMBFR*;Dj957RF*W>0#o|)z|zN_sfS4yVQ8<)DTdmnqL zP*7CY)6bMqld@&W5jQdT>xl5?jBGVVZ6*raggWdJ>dSLeCKJhSKCF?C*|}Umwb7F; zmp+~9e!Xt`u)B`u;C6~4uE)Uh2q*utFXM9GK)grp3TcihY@jQ$SYU@LHPHBWeg06I z+cPmYu5xGU{gH^HXaGZSaWeDm9GwHdDt1}dLQ+JLvyE<3#&hEtG|-p8-!EbBE`spm zdETpILyxunOURxm)Qe(r{errDH!?@F@nUR=Jpj0u^*G+7uRHp)sFJAmiuQPENhZ=HhYcjJi=n$zY5F1GU zbA~Z^rnaALUcWB3<;OPo8=sIrJ(ZeP$&X5!#LfzxrS{-L1afR5>%r!XNbIb}NvY>a zpNPv1U|BY|-S58khVNuF%ryRQ$JXmlfQ4zA5E@{9O=iZ(!US2aE=ZP(IuD1v zsCO9|*6vBS@Gi9MA5(`$wA&o2W_lS%#dpY2Ezh#o`wzdoUjX!6?X2ACt5y?^d^HqR zsISpBURGT157@pdxmD0z-ewZ})a+m_w1u$za;W9qyV~0-lG_KNo*I)}x8|mVYcEn( z1<$vq1E0D3DMb8{qckQO3QGfm&bm!!Jy`zzp&jz~(;XXI0yZjfnq;#r(4t^5u4lOd73M=8^S z%#Db*V;sN5oX@q)Z(JeT$!8Ic%&`Vf*PQ9f?S;^#z#d3W3O$V~zm(7ktG^F%p?uSe zZb9PO&_RWGq}J^vTi~OA_LHGeL!ET_ncqj6c9vri$eb1#tG@(7ZtAb%ia0?FY#_LrR?4s9`t-}csODXCeQkcd-J-q)q9_w;8+j1Gk|$$ z@~7EbdF#m#KY|=M@JgG{;|c$(LRP`J-k-V?9$5WxC4JK2hnDqPGuYv+JN=}y2qsK# zquDEp%csNRIvtR**p6jPaI)$1Pb(4(F$-TNwr*!2nh*E zDOp<>m@_Sn8Qqr|5tXQe;k@4jtZT=f8Os)dc(kDfpQs065Xj=^!_U)$;iY@Fz@4DV z$g$9AlB+f@UMD^pj?WSNwu^njjryr(vobaaE&FUc9j^vXc_SI zObAK1WE&%Y717jv%y~SJAdP7MZ-2PbF{X29KQnz7ZYT}uOYx^+B7AvG0!fs&Ns0f# zTa-~h$dWn4$kgV|vvSuRv98KVWJenw+aaYyRUSX=;P0P{O~`K;(+#D-Ic|gp*X9H@ z8@i2HUY@^s{`wONqYx&y0k#g$MN$`uNu(;#MWj&eMAdG8v+qAlSozxqRj}Y6^;=k+ z7OIBYC>S^BxG+{6?jV|aFuLV)1+I#a5E2^QF^RhU_y}A>Lqj2Wy%L~x$$^1qmhZNJ zBMhEYyIa2+9M0dW)b=2{)uQhbnsuh9wEZgFy9+n{q-~CmqoM_Rs0_M2Qe$%d*+U~y zUZ5Zml?8~{AjCzq`UqI94i_WK8U49{wyjozBQiG0ks@gY>|?tLKuLcgkG^@*>d|-W z_d#b#Do$JZ-Fd5Tf)TJLb@hfDn|H~^l-^xOUxEz@KRx+jUjVwtfiV6I4CgQ&;5l7T zrj($!kteLz&e&q9AXst=9HEe?i{YI14!BRptzDKSzy49l2;?`IqQ_cl=*DUvA$ZC5 z{ScVQKaOEvA0J!Ze1bbdh9x8<5~_<3>jsZnk+@cLP@P+OF&yPh{kd)>i$w?Q%VKS1~&W?0v~B!#4fUwt5tHmL`Kfne2nZ22q$5o#gMa;Xg$Fq!OD}r$xD8* z1&pl(?joxjISRT*!~=MUpY=}By?qx_W@gveT6x&aRwHQP@C#rSrZ8}?{mg^h?;(QX zGac_3Egh9-)@Oq@1IUngU zqqgVh6Ug6<4FhH^z4pOc;l%Tz(4&(>PK?P-5F}uQ^U>s$1f2b6o%ELQX4p~p@Fk&h zOu-4JvDEmsVpbzsO=hYBNC91H`O4i7zEMff8MVlgwP{n68X^8Ret!yxqtfyNNheZU zrxl+RX8ggk^w7Q47Zk;>>C};B>Or%`VvXuMxVdt7XEav4?MW!c^6GYD)NEVkk*`$y z7x9k?3!vZ5%jBaeJNfN7Gaci>j>uK#YK7#9px0#OBVzjkx|W%v1E~lQKq$L*jiXB+ zEMjp-rjjC=eJB67heY~6?;SOgXYk^iCH`#jV!7?d4Rm6`49{L}5i*g=s1S(R?vpE# zH`8<|H5YC4dpihNeC16#UriTUka5}$!fbFtp2rdrT=oRnpn)oZt~!p2q))qGxpNmw z2kuk{C$By(2S1Y3=LPNz8TSHh8t|l35(C3dn@d5%40jS(7Ys)r{XC&IkIf!P-lEf! zB`YB&=;7$Hh(em}q5RO(9g~1jxZ}~6?32F&cYNyUf^qdKYL9^IqC4R+b>={Ql ztuA}y5*XINB9;}u8yupgZ^0QQ1JUTHD(k;wOy=r`Nth=?xV4YBbc#Myo(pEE&Wfd>9+jNf!nVs2 zNo$22(ckUR)k@RFee8&7QbHRAP`(*Nw;+f_P=#cz{F4F2dYBSQ%2ks!m z6Xij{^e_qFF;6%e<)6f9J%U2}C>U<){|qXH8<%c<=!ejJWio^?l1e=koNPF2_#DW&}7P)=~R+?}xgYLFuAp&EMLk1IqZiO{z zsi-EOwa>Us-n^|l1f*9;29h(O)YJ%&IY9mTcqeZyAg}QJ?3QIJ(0mGK+vV+U&vAeT znF3whX-Wt2Y5WN>(EYPwo0y_+LFR+Hg0l?-A3wrs6eN;K=Uk8EqeE>)#CSU)u0Xan ze!mo8aWyFT^4zyiotYD)QBt3^IKJLaJDp7bHP|6^Y%g3%u#>3UxBU*h?;#LNaDw#k zEcAP>^?hM@Yp^#Yk&*^|(?$r`?QOjOZU=myZGM{FijsX*E+3WySZ&#%;MVs{@)nO( z5BzqgP|J2Mt@TX z+uII*YV&#;oDYollN*!$G7`n11&y-jX88jqses5;+58i~x|2C_M?)f3Gk@BK(%5U}7cf$z?0rPxWVHBmZs4+$~7q^9~2MP{a;&NVxbOmB5w?TJzgVWQ|TD_m-U%zk26SBnh zp0b$FbT9=3c%#A2UF)5;&lQ5z%f|3Zmr@RN>p@ivhlXZTEo2QRzA&e@7yh&5S zA!yQXuMIBptJ8YduGWT<2f}gSzMdOHRas&IP}!H4=YUJ=sq;sISXeKjrh?t|6YB~3 zU?<{S4}2fYD}^hNCTCHm;jeTA^N0C6vp`j=0c7XGmANYug-dIQt~zR){9keQ=D#Yb z%3KBhkh+#5BGIc6GNO79T-gxr!mEV#AGdB8WOY{CO42zt3oSn5z)pVoQ@MncA4{?q z>jd#jel$GMHYjzrj~+f1cYjY!ZR14FdP}t{;AVv7fi3VfQk^1l@&FOT zq0mg!8pB3{Mi<9RrIKkkJ2M9XLhJYdcUHa4E~rHt%+HLn8vjAu&o(K2HHdMl0CtiA zhJ^2JrNuFf_$DU?5u@*fy#dv8f#{w0iKPtahG7oo-jY0XM9-q*oy57a}dXvp#t*)!d;5Uwkl|RSaqO zc2X{s3o{R{YshSf2Vh+!o42UrNq;xG(B(aL-YKJ)=iDmUhyD(6C;!ZI0vZ!)&em$G z)omYB)qZacFdZ0V=GP3H+l;4}ci_<(twVrcRbNr0kEyFX^*3I^e6)n`^#W?kN1Ggv z5HH%NcB1c#m;_)9yozh=Z%=|@`nR^9X{kRswUFW_36d}WBKNFGP(0r*FlfE^;qesN z6HqYK3h5|0sqS!k>2r5nFTGkJ^m{6DMqu$vxfhRTeX1ZwEPo==L9P(#>*tSo!qC;iJqyj+$bV?OyqO?bA>LhRY8A=vy6y(s0`Xv@gv9%E~IEzyy6 z0kwH}(+{_9VB8*K3lUU!Vq_SirP4b55kKp^z^DG5i-l^qD0!&EHAZJB*Rc)sU|-dO zbDwp>Gci{w{au5tTEOace?@BhPcrrFD{18bz-YTlb-&mXdt%X5vhUtn>6=1jxrKmbTMYB5+o6z=0K-t zEc~#EYgO3ZlN~^;QVdZezp8X)%e>mwGK06KqD#vtcdL3YH&=-x8MD@-apf7!NRviQ zmJ94d{$97~&6X^r6Fua7heuniG%)Fbl4^Dbwh*L~37?5~T(Us#0~74#uadwWU+@hdog?+Z~($NX4n38x9qaC8>z@Aa$4d(iu`=_Yo}8Ut)d@57Nl!1%@+L5u%`?h>6q>1t6q}O+bf6rWlkP`?Y~I5` z350mkb0MQ=9&;b4iiKpXp!9+4qF#4rKCzy3t??I)|Af((t-=bTrY!Ex@QpA;JV75a z%KqN}=!>BaB6?}TYLyR*@^k=4gY=K6HdB9Z3yVEq|nJ1YX9odgYs&}D9Y z<19y{nl=-r7VAs^5jfi~Md4B4U+_9@{tgT5y3*hbo3ThNRGRdgN^$<3bj1Z(EXsy> zL!^M#I<_?ZX18v_pBuw>BLC$%z}nlP<2H0KHecfx{KEFqMC!;o`%`6J`tubj6MYwv zdok=4#wS;=eCF(5H9NU&f*T<9P0dDpx}&=wKoa|I^9 z0c${c$M|XMj0ShfXZcP!jdOP+sfWRa+dcJl)~3WVX24{vuWT7i{3}I7ykN9$8UjbqKkJo!oNup28jYzgje`%WF=<8?rI6$j;rpIx@7HCw#%<7 z4z=kUW-1!V#1E2lLH5sEVDcS{%(ut<2@`m3dJ}jjT&dDn;8CwwQ(dcRE8q(+h3diS zcd2X_xA$kK_nJ5CRp1{{bY%nXB=}P_iW+;1UJ**FvghMLA-IQM%e?vtpVn!Y<@SMp zgZ-6kr(kmYnTgTKH@PmGlU(3!=ts%HERLZmZ7VrMg5x^_GDl0gr;5ngC<_hgloXrf*SD&?wN48BX| zk_n~$uCT|T1QSYY+V3HNL>PCSD7pFE@PsOY3qUvixNr|CDAB4O9F5VgO{LM5iUW9y z{=TO-RK9e{m@1Uyd2ITmJWdWPQ0k?rlWYGRiiE?*ud#K7IXxfQS~qv`;RLJ4Cn4QX zxllzAd&h$$m+fQ>zOJ9auszuj>BeY*rEuT?<$wDd=>Bfl@M}u8{V)_HT3%iq`KTiA zC_0*R87C_1AYjA(>8o#kE5E^D%u_yrR91oZXN@0*jOO{b7`YFQ&jn)R z;nA>C(#L#}YoT=uzg}|fhhT{SsH>*Kr6GP2| z#Gv|ddsa%t&i?c%9P6$C_T5jbEhOLC`}@Emcrh!U?>vx5YP|HVQvO$5t)_#K1(7kc zi&&w@)sL79NjIjG`ZuD{;&)LUMu+O^XX24&a;+LEe(2^GjuV9BZIPYpKsLggnGlKtUbpf1Uo`+>5p}&4nXuib5BvcV%;4T|YC;e`Ct*3}E~^Ujj003_*y;t~8Cay+BT9PP=THG-f}{ ztqxFNF@;tc#4YSe6u)GNo+etqx;xJoOkrU$e&Xr2SZLI$)W~#JL4<2eSnujjx^rq= z^nMW4M#*z_V5$s0}k8qK&->&?A6F5so}_lg?M^kL8#JQUI6gU533$vD*nO^gxP!uAArNuSLB?$m&Mj8gGb&Av4(Wk7>OSU? ztbFnpgtTwp(&QgolCFRnNt>0Jd`3;zRf%QV&c6wuPa|Efv_atvJ|bdv-dO+ATy75V zS;(c;rOl+aUO4m7n&(e~-*0~^qT_YKs{o$v6yh%Z`Pvckq6w2FzW5ib4o?SW>#dRg)meuTl29Lc0v7egb9@5FWc3!&iQBf_c}RrhV_1M1C! z@9!S?M zG4vMbajoH*z+=36o+kX#k?WKkxCa4DZuE1fkidubiR@!lFe69G$Cl#dO2_{JsaZ9^ z#td~@T`1>CM%azHcN?C^4x0-jEQL?h5Yp(y5BI6|~c0b(iGhUB&`aJoonNa|z z&YiIfsWzG2{IYMx2DV?wD3+dh^ftL_vBtv-p@Zem9}5E^onWKA33r+qb#uhwjw|kG z%%?)pgO03~h!kNwvg&`Dbm*C3M6UG{%G7n>`Ks~#dxM0AoaKm0YYp=JRtUf0PN^Sb zSch^Jq8vzTo7i<(k`Xb9ti9w4KqBBBzLlcD}>V}+_;J` zSbmT{M~CvNkT%_4JvUO)4&s?+6?W2>?zOh|w?s0oqI$m3-BF%;;9o|jGO|Ze<3m<$ zzzJK)D^e*vVnc7Wx@#*!n7{S6^*<-BNlbTpodPHikxLEW)bJ+G>cMjx)teqL^jmd0UF(S(^@(;Ts^=ly}^MSvq3v$1X^Z)9;ZHg|D zjm5$Ad`>U?hn<6Fn10`<|2c~LI0U_i4Wpu1(P4h~OBLlS$0)T4(c`{XQg*Amv!Mrz zMyWhLY|z+VC{LA1i9BS&w3c*j24%3zVj`To#1BId|Pt<*qF zPZsGd9=%i~>oe`xDeRuv`f+ryRS&g=Am76ceV!A?HR>$3p;M-op&#%lb%G$Dlyo!!I! z@;>EMgL2pN=Ho?hQ=w5+10S7iRJu7*nJejN8#?>3$cp{x&7~g~VB(ECVcT+3+=#OMX0rLssx6Cf(tpHbO6qmYUBP=4EZStC7e2b?K<`fHO1@g5KN_FY- z9zUuho40IuC`2M7jo#>c#wN!aztzcf&u9SYyk_!BpnaqAhv>U~VOtw?gV)=a)z?f;U^oJrwL_2NpO!%%E; z#yd3yG9hWgC6Di95j`(n9&N->zEUWPPFN`4JlrC~@KF?iDVcV5>E&A{F{ zB)F-Apom3kz4SZz}^Z#Kq4p%-`&w`j&aX3$XD?X zA6c4>59eppiPoY)45?y%enD1wtF9v_IA@Qj$&SqUEy%O96tNli1vCEw%gV7ZIIw^H z$=xx?k?Fo&XsBaoSnU?ElKm^{B8juA2xNS0Nq4H}mVrnOi+Tbh*{p9d-R9nSG7or? zU36q23kl;h8blq4N>jh#!#^2386_U{Xd)g&hkWmU!^gI3_OI3i+fiH`SF#RpH@xVc&m+}0^ z=3%tBv^bM9`EVTVd9sf~CP>fBV>+9XGZRb3_9!B`MqEw_0!~F(#QdNC+0bcr#MbZE z_F`!$Tfwh4dg}NOI}*da$gEV*4k~&nT_Wp^`$jg4`6VI<@ z^)ka~i~*C&t!-PpPq(~OrxHA&0m4NmA2`(V5?8o6E@&o$=D%ue6MF=GlFFL4-5Yy>To2R=4O#sKo`_< zCs(i+>OzMcm^ryINfs?;$u7cE*8Q2hb<@rd#<~(5JSP~b&nZ);XEq}DTPk%&2ZkRk zxmyT_*;~3c(VqCsVmjTeM`!~U_YsoOLi;chU`gSO=94F;RuM0fn!QmaS0%*PfvTu+i@^$H%V?-sndtsAS1-Mu6VpJ!i# zG2N}W6{RI3x2SDJO6;WyS--_?a@|=evrB0KO@yi}*~%*(%yUb>Ib)?e@6#MwsrWz> zjAaD9@n~GRW#WqFo2QH?7%YuafCS27X6Bj#Q_AtJ!9f zmySNgou-13*{pWk_all+g|+(T{SB{3n_H(_uRwa^pik3Fvk zp0jXESMvmS-(DE64~Xk}lkEKcFE`QOg!H%hJV zlQK)n#bk@S>|2`Xr&32_I!?c}UZd=8qQAOXWBeRj1}lTP-TzGcVA#dcpChhNv8;;LOj3rqMIu+5T2bEW+ zrm!Q}L`5vw02dGJn4qn(vM5yBX4Jzp`)%$5;q&2s^1y~=Q*mrwS>?yeu- z8%|pyx?caJdAvN!_+C9&%4bwa;*=pOyM8l<7ofShXqjZgKWta)xCucZ;t{lJF=tAL-bWLHqL~daZxw3sFktUKnOP<_fP<*qQA|2wf7XzXN$Bd-D%I+-z=P@nK;p1Y?5( zimnJB-mQY-I^VxC^7dx10pu@t_Xj!;FQrXK7m`f_^LY(l;FhNQh=KDMi2x0#iP!E0 zsqO-zU^}CU2yPv@nV8bGu!BM@&sVQ%i_FQr9<@_O3Y}tEJP8+~ZH&j0wpL{qQW%h} zf|~8%DQ&nO1{8EQQL_v<58;Z}&ax@>-0wpkCo=9`@u>3sESw4qM*SLws%Jet=Te4e z?Wp1Yr6cCq3q{lZl_fFfT-LkQJIX~(V|N9V!=J9(w!Z(y>hej~tTdY}wfeZSl1z7% zi1~OwifV(JmX1m%6dsjaY`c#h`^DkX&j8;rlEr@B;lM1Husc;DjvDf~u@UdV^q z-aM)V`;3|HT%e9@cZE1Hb@zLyjCg(A@~1zt54^Q*$rQPWa{g{VT4jGot+SM)R>g!| z;`ysHCr(GOJuAul2{f*iFgs#jhJ~}oR}I4_Aj|nU_FBq}MXo#=x76Zx$zi|BCz>Kn zb>otR`?RC!RklcUOxblbhV^5PdhTr!uICxkoi|$%jDqX-7`f~RM5cbz?3(q$P}@M* zD|%1*EBepg9ZiZ;vusz53q88$UiJh>hg{%KR*RYz5?pPy9j|6JJXeA7^HR>m6Xl@l z5H6a=H=Dj)xSl(MH|=%~z6#cF{rocP62oJe8zW7SxWzk3vQnza0J@&|3MHp9Ko zhe)fApHYZWg(sV?>Ut$(wKEA5&2Cf6lIxqc*WV5**4Xz=;A=0 zr8=sODXH_02b$&WwnpUE=}%wrj;QwnLeLa)7x>zInYE)JRKD>H7!{RC%sU_c3CyBv z$h7-zJ^dY_v;Kz~2=|sOzioMei%#48u|I%9I@GWF%eL#)V|L{7=KpeaRDye*2pt$i zdGzbc<{E=JRZ^MD&2YocVWJBTS`$WI^`ngiQ}i=3wO=yaBuew1xY~Y?Y2%n6Wg**$ zcC4uN+49WT(r&P6Uz~f&{AU$0NmI3#FMod;S+jR;Gr|Mgm_6)@S9B_67mZw< zxIzkoVJC8}ev#U4M$%7>F}<9~_y;;_+ukDv2%Wlrj zXV)mY^1f(Qo!+<*FU)fevuP|00f+apdsAG0Y@|V{VVGsmE(`t{5KGSZERRVfw>4eY z4rM;=$B*xkZ~i>UeI-p32vvQG!YflxuW;14)^g%1a6Fsx=`tcUZdNlhN#t^L$M>~l zfrnHMmRt#K3Cz;?rao1a@n=BcPdQ17#eB)w_J}0!i8T-ks6pZOmm3}OCE1G~efiZp z<+7I^|Is@T!KC5@>%ydq_W9v!{XUzgWpp!iMziVYJ?v4wU|c^ksvpGJqL*Z`@VCht zkRtdf>!OkFlwrZwdUOu3IDXanv~_}P)&o>y+;)3{10{6*ia3#DPv zW`8se5oda68}7d`L0Cb>PX1@x)YL;Vd^=+Kxgqms)P?8AlnD{kX|pE*VS$z4>`>;r zo8elNXYSu=kzG);ddT9vv&wY3TtW2>(upLq$;6kVdm6{frJh1rcXkILiiT4|p8Z0} zE3#pw=6A11d7N%HKOABkZ)qQ!Cb-;S_fI(P{>GGDVloM1PM(YlKToV@H`Y}v!*i8g zL~g_TaObp!T8BXfETD-eI>!BNykCK5%N7&ck2WRHPR=z{J`}7z$MfS{8$2Pt(t`7% zipW`|Y>V(7fqlQKll)P@cMuhcZa#r)cKxwF+4)eG&p-HrCm;r1Pt+v>452mGf}P}V z>w9w3u=W=FSA8;lMnbf0NK{1EhShyvID@bX=K|7S)XtOP?xj5r+y`kA@j0P#cIk-M z$eMMmL>L2Ggn#_8nWOGP1fT4oRRA-Nrj)+>*3>QXJiZEO!64vee&&8K6F4vO~r= zEL5k`FkBo#!u7LBTt$2qK=<}X*-u#5w}i?R*19VO*{b6)?d*tNIFQ}`8tUw^r$l)p6^@j#t*iGCbUYV$Ca@pv4s z{Jit0gKK0ebcrOBQ23N_SMKR|P}7fXriILGU{s!WF1@1TrZd8;lMURoXSKhp?1a@j zZu#)6zV3?~34c`eo_6nf@AYHiHswM=YlNq||7i|@AQ*Y|c*IgLsuaO1d@vsKR7wAS z2b4Jhh}(_;+}^DL?a&S3fw>jYXSK#>P_AR0R2M9}0HHlSHyhW!R(j0zUE{r^xiKxz zbhhGI6Xw~NF8y~#-z87}sEPHLDhx4FtuL@+b0Uf7wT+juVrOxF1ecirxQyrvgl6xd@MYzoM)zhdtWN zCj2}=pk9H_{w#0LJnjEAi;-20mYKV@((;p=mkDoAGrFQkLqJ$oEiKq}n$s8PEM!_$6f?z3){r-Xr^Te{)I%%xE8j{U&P+)E@Btyt+IxR z(J$8}5jp%YXWtxSqyvs5Ee}KQhgi4qDkL8LAs$6i_Ju= zK@37kK-W+H?uJn&S9o<*k^!K3lAN#ixnQWcTi*(|^JFJM#d-?wf;-Ll+K8y}Pz**h zkJi`g35}R4hQg~T+TUsRvghRsJ;y*|cvYt#Po!>^$6C8-$o+yaWa+GIam@$1Z?i>PMiOZ!V8vD719g?6~GFkUouas$3 zs441hRAT11pttDg8$&Ec4P+Ct6Tav`P1mU1C13x;>^O6EXj43U#s-O6Ry{Dybv-BJ zK=)mRR^KCnw05I51()^E?giL7&wc}DG8 zuU>`Q^tO{@>mKL+IxTXho$Hq&rph_pUbPM9tt&Kol{cW+cBf~F1cgYUU_v=XhS}?4iB5hflQd$b-ZH+Mz`r?TbV}N_ z|AB<(_zY5wOvGmR>RAt?C*d;*O&S&yRy!`$-Gp|x%u=*kU_55|kb~qF;2q+7>orS_ zZznXuZ7oxmT%lNu6yQ;;3>+FriJ7Za^uAiy#XIs2Y(mF6)peD88C7ivyyUM~eB=$8 z(A&zI`<1X)r&1zHCE$CBWRGB0o|=nwoGaznC5 zXW6HHMJH+v&o#QzJG1;1ARiYuWr9h?OU@@W{Qm0vHQdTSqbKOnLm$#;=GL6BH-Uv} zFRs-=b*ni8Lb_ywF0r~;-6rJiq)LCGSqNOI5x8}FNaNgTi|HSPS+dN^XU9==g!kDgGmq#WJA#f~R zrAlFj%@FhcbykM0*M#mGPf@(~6Y{-i2hWB-mQM52kH-E#%Dy_FjlJ8pEiIG+1xj%* zUfdm8w0M!?9;8Tc*A|LfafhNQ?(XjHE(uUHI0OQ`^nCBT_r7~i&wFqF2$RVqBh2jC zzqQw1i<&6z{#)CS()w{_sR`Hn{=y^3=bA64qM1e=I@ogokg z(WpX}Vz&n4v@Pk>c4pSQCKk0bhey^V$sG`5zCwCK|=MCc;*=;qlrVhWgm$i8E|!m?nSC*gu{PFDdPQmd&N)97PrSMbZC zRc6Ji3ump%F_XPU;@x|QMojm#XJo@6aFnftpj z{O_iI#&(F}nZej39JMEA4xW)y*BZq^`wW(XVdhcQVXqY1B9eKpovB3Cr^(NiPZZ|5 zkb}gf8?&=}Ba&8~-M(S7CJ6z%0xv(8?Xy7=(*a@z`fL=;Gu^$qV+qCLB@-ST)y z$~l{|9df?uA(U6Q^tqQEmB1Oxo+s;?;d{7~$6eN=1iC#DxpL58MbjjwJ;~oyT5_i8(ago{&?}$M zTfW$N21Rc|Pz_4IiTRg*S-RFqXVA^3AD}JWhWB6<(>&7Y_8`XI2R^aOGrmya8(D4F zYNIHop^E&Nf%`LVsB?6xj}OweR3AmXi?QlM}c<|mk zWPwivhU0Tw)Sg6R8?(!P`&O%VvH417n%#_pi!4H^v}n0;vu{F}SgX;ER$PY}aQG9W znDpbD=8ceB5Wo9C&6e_@?cDZfj1%)Hyeg1qjnBK2RKWuZ^q1C-S&+ z?iG}p7DP{7bWvMQn6F~ol09kge&Y~-Gr7NIZRO;m;y{>4p*#0pz8JrMB_mKV%TKj! z&$Sp7HN6mY7JN%l3BG)bhGDd4WW&k?Tg_?raW%`uYslDaHd&+%(yaMI6J!=MfcHjh?xfxZbKE5&(j!p3H3#qQ<`3{IRMe}*cFxNAIUj1>8ga*C+NuUuHcbisUoVtF+l?~~d11mPo z!=I$f5IuHQJ=TcP`hl{bv8x?AlyE-y7xTPH?^C`6x2Sl%u7zuu_TGiEmc^>ok;?GJiKp*9l6rIpSYRxjt53`Wh~#d>6TY+?|oNy{&46f zq~87QS@}{9?Q0!7CkpLOyEJ)3sZSNsI5@;;JtjM=j{!cl1@_=i7pe;UXsZOP7HYD?_Mh{~~T+8DS;Etz=a*1_MYn%b{#^#X>1?;^uT* z;-gnYLKy=5y`q)HyC z3pJN}7wdXsJ5F@KZ>$VXrKvv!miu*_$lQBtcYyeOMnlC{4@{IbvRS$NHe0T}wW$1Z zyaW6eI0}W=ND4-G+I-%TLZ?wbZ1QYuraZyn=`6fb zjV<-_1@0cY-Fue`3Cf6nts^ z1Khk7UbKtdceBXHorja|)9|jNbx4cr2Nwf?nE-Khk$=+oo7?{PB6nZ`Cl^8*B{qlm zV&8+~V$R)*y99^E6E9dJ>c{pp&F8gZJ_DQOo*817_HR~FN-8N&_?*_cW*eVnQy=lK z8$PDu`$9pCRV6)RK1hMU_WV(V^N{U7?@_D61XX_O11m*pgN$V?X`|juTWV7G&ObU* z&PV)*Z@ov!by1)sv@@;O_(_m-My>%csJ4jTH0fb%cz? z`eL|>_XoNy9FtpH$k#OFP~VNWIVQEON$ufrGwdRAn0ekSjat6hY^$L+xz#4wCU^4e z##N4&(;7(%$PJ9#x%wf&w%%Rz2EK9)VuAE?FLCK?L9&>wOgPSSeu9uj;k+TtH!R zhIfzp=|Ae3RPc-&5=cZw-awDB*+s&(peS3}_xta&=pQgyQ_}`B!?P~}ZH7s8V;zR} zm2)&{b*=Ap`J95$$%_rG(;)=#`bK<*r|k!yQU+nF;2q5Xm0g@m zQtlo`Je-0sjr?zYYs-Zykq3C~_5PV_z=K+>StWwO8-g=uCXuw>bjH|G!3O-uc72@>nZ=Zf+SwqO(4?}(Ifm98Z1#edpT;s>h}xmza^zY zv|4_v^U^E7QAV3@bY?8ku92Ote)BNq0$o*TaM+3wK#$gl+>89M`SU24`u}AnZ7;{3g8!E$xIl2H1~cI5Xb|8z(qyKeYox<_3L(*gZsDmXT0STzmF8O`D{cd3(xq#qTc((fl!O?6(?X3)e7zej9bd z%>mZBcXU~aTH~tauxR6(i+|69XU$=A&i4x z2Ac3>ZaU-j9$Oe%?bBf@CpyvQD{Lw}avH9Ixt$*LH)a00rP2thbQFRr{qc{FKlmDZ z>Bwe8_-MUb%ZQ&2t4y}yylEt9+rXi!G(SE`ThhT?lp~~2bSElfJL54{Z>>@MKxzq+ z$k(X2-iLE#mTQCU{sH3oO#AB!)RyM3UH{c=sR?TnJ0+PxuH=4=T1vgZF_W>8Q0xcHI-QmZ>z(d7TwFub7ja+4vKBW=Je1gTCLwAYg4RwJ( z;sT6*YX4#Hk1A>UOvHU=@NR8iB*7t=#Vo?>ay0o|xR`&=2tLc~RI#1qWU1OrYfmry z?b8yG1D%{jW%A>LWg*9;vwMA^6c#H=jWL)tt9NuYO_=CT?koRP9qGx&!_O|O4&6D1 z?v~a4vM-ht6d#&W0}Koh!);!Mc%EQ|wz00U0$Q9|mYh_L=@zVGT`Di{XZB`W1gpCu zp%{tQ^>GS&ZiuUcIxFsv+NovCUBP*M^FI#dlP_6c;;v=y#y2pfa0Ik9M&%bzg+;OE zzh012Ms8;_mRXI6z)22Gq{6|RouTj&qw*qSH{V=;pLI(1jww@E{L<0)*yeWP0G(l2 zkkg#AP?AOWjcAR-&a}HVKNCT%RoVqwcU%RVwARhRjwi;D`r4=>8PYh!g-fj&!z=q&bLijQ^P2>ShkJzkj_SmZozKY5m%R>_ zEK|IzVR_bU<{A-sRwdacCw6qsH^r|DPkBV4bs}l050AGoyu&O5s@9|5(i9+?Rr{KV zMw%i_?>-4Wsuc&&?6k! zAGC36te5$8bmiCft&NNAP{t?gPq1w@nTd!~Bj*n~nRw;9hk*A!SBFeP1@EvgpH=F%?foMWRMG}*af?=mH>bzXRn5`WcU4hMv#wZsy4K2-Q^}`+IA|PN%5-Qjtjj{ zZNs~Q(6yE$S6{Amg zX)G0v3-ZWZtDPO9Jg2I$=t+*b!4q5iabN7F)-r{+ zI9Sd8u&^z z125Qo&1}Q>>8Qe@;qSY4;veqXk|g2d1;r85-h7HvulbDA0Sr6KP90~IN|!BkybN2( zD<u7(qfir(ImIIiv8Q$ZKndPSaNc9YRO5o$^N{GDI5Gf8~ zKo!LAxonT#v7NW66c2D6V6vXT2hwLaN(DRxf52>idDP?`P&S2^;?K zW7zzi51{|Lv%U_nT#u-CgfVTf3bMz=WgTDplS_+!3#gSq=xiu5;uVU2N3gG!Zx_~bLF;WixSn$uA z%WOZk9QrOoBV!bHswHvNc-eo7Db<}6CH$s_+d&)AJk546U#woN?$5P5WmG|CyilyC zi&`N<6f{GYK|yS~%G31--MUtDaH$i~(6!+kl&0O=DV&vSF&%Uj$|sq?$-$Fn3wn~o zavw5w`9%}-yP=EpZ0d&%3)2(75hDUT4ky0z}(CXf$A4Wy8!m)yG?yVP1ukvmhBqe{WMGXxU) zDA5rF&6WP~oFbVMp5tTIZDw+QTT2bC#V7$Bko>#iv-vlDYdgQ-U#sb3W6y0^sFgDO zHpQ=AnF)7)Yt%Yn;tVc%EYotRzxIz=Kyz(24dmMqAY%+$zDH+*qm197S#FDmYt#h1 z1`{Ev2&8j_kqS!w>;GEyMNL-Hc=$LGo<8BunR8}2u~-O&{1I#=mjU^&X{hy*~uGU z{W=1Bq50m49l)vez|XIr*fNDj-4g@R@2g*xc2nhR7-G4%5a_1QB|jltk=ZzqcQD6S z$yZdG_1m(TzHq$1-X|L4*%A&1cD;?|)j{!kLVh=WGsY%cpHHzyCy45qKco=e*JIiD zpZSgi7k5XC0+PinOos;r0)lyF9`DkTpW37^YZfQ+yPONuDUtU;TO+AtXs(yd@_l9l z0`tzkGnAl|?5v_aP*|gpn>ew_zQ*$f1%g#jHI$tdJ~( zecKrm(b$5r;nGLuUAf-H1h+?}<1nF&MPyLgF@b*^i$EUUVJ+>jZu#+JMtIicehfcg z2lpzP!5jU1M0`2Nn}m`bO?o?O!^DGZjN;@UKEEt?G^_N`EYA=clwouer4{e`|ED$E zxqCSz{#RP_caBpWM!G9<+Ifg#sV-R(IcJnKb=kWX%cEWR;u}^UnMzLG4P& zU|^0n&j_tZ(?|ws<0m>;tYlp#-#rq&?&n zsr0ESIEXMZ%iL_DV77^gkSB?M1b>PFT=hXaVpi{(3gd;ur65@j{^|TSPSw?^IrOCB zUwNg3jrcA1=*=_ZLCvH$yYf-pkeHg+rd>!r&t7F3(7CXT?#te};u{vRr`1f|sxmr; z%j-M35MAE-1x`pIpUizf^&(A(7>#ZHaZ@$mlc>>N1v{kvyKw(|sKKG!?bM1~X?_pYG8d`vDaYh;$Scg- z^O{#!SR^Gs`SsXC&3V9W?$}ngLJEbS94cqMV~H}%is#DghsbmY(Flb&4J*h@AF{sF zjZVb0P%5;<+TZ@gv0U$};cNR+!5L|2VkvR<0(F>+BQJkL8v2oM0jQ2~(3zOZf`gay z;a9}aGP=UNb%(@aib6pO$2U?OsdD%v*i)s}AVu!M$co((1E3q!*!%$Wl?|{lc54&m z!{4vPiB43mBq?!klf)Z->|5cu=AR>j1xk#{23&}_!t!-$D-FO1TzFb;w(M zi0=&(n-M%YyiBd2o*-I=xguv)(~FOuALWjIk5y5)J?*=1!W<&vUEnLli70Z5Wp(sW zX=;e!0Gfr)x<`?_u0f)^)DVHb_#hAzCdh2Q8q$yb@;_5sdZ-kvLb`lmj4ey*t?t>S zsm?SmhH&4az1~md{xGg1i{rPN5sH90#|a|mttd9%5BNkHO!Bqp1@?||VHzD~@(5{ueB4e@?2INAaU$@4xGa~OB_D|$4{y`6kOGS$;!xe3l^kbZ3W-p59naTfbL z_8HZP*<4WF7$s#PUmLm9t1A!$;IAdfc#WZE=w~;4jf>cQ*b=)xxI`om2%>1GLsLGdc^-v{(!g2WeH4PG* z#tIrU8eus8 ztHC;rGbG+cBL+04KlDQhc-QVV5Lg3QJ@+n)%d;VeaMcpn3w9@meh* zVEHalCu7I5=szGXwtK&#f+xQmG9X9_+t;cGe(`(-)uX36YTFQVH; zZF|E9DwW=G12o zM>BMy9w_&X>N#pEQCR;}{Cd#Sqr>nz@*|Rz!C?NK@}_vu2QriceBUf-=%?lW8?v)G z^sMGGRJLC&+f;+RNgv8q9Shh?*aze*9JMQ_EW6!A246#$)`G)@6GALW1*hom69InY zZ-Q@)0tDd#<#cCbbU8=$81g`}*TlnU=KJP7KX3f)U72dT!gqPn+M0>kou?%BKwL=3 zdX`@D0|GcOmu1D(n?|;mQu5y0YTPh*P#MD}fn$qY)oQL?YL9$cYtW?uq>Iu9NTz1h zToZmviHgJq!^=InO$Y2mm_{AG^twX9M;FsL&*|&jhd^r*wuDc6pXQW6KmJg(Z&ZXO z!1Ux!)g4q11inb;Wyq6}hCBLk+$(6@&b@!SG<)9*B;h*;%EUPH^+wRMd7A#P9`b?P z8lpKguJ|V04Uc&Vf`vqCg2q`u*+0sNh3)?ZBma+A_nKs{pS&>Y3o`cMyv+|U1H!}W z`qHhPJ=qIv%1|<6TZu9iN_)*+uQV4#%Sq1aX!m+PUxGddK{Y2gD4%I^Ou3KX3aqVc z$ac8Wm2a+~WE!6WM~me~a1PI@ZBvzt5vpVNIDUP0r#DI6RqM%B?A{>me5m-KqfdLo z;}U$k0_T{SjpPGRDFeqYHL@%>%%{XU+KeCW7_2e_(){`76 zoQ&O$^R@SGW$sk6Oeaqoc*`>=5!RxiR;Jy%R9ZT`XlM)CS6imO@Doo3uQv+}GQP}e&Q5N!V9 z-c*unsh{coV!oLl5Eo3KR6%u~zdzG<_QnR{iGi^xnVt=DVdGXQ$O(D12LQ zF%oeFn0{e6U&3Cq7?Z(kmW)G=X1-EPqw7Hb4pg|R+n`gN?1g}A7LMtbT!W^Hn{fiU z%@l(5VuN^!hlO2~=qX2ixt^3K;8Qj53R%G9v2-lu7zJv?oDY78D% z!qFthmbkszi;>s!H4uF9C#FO{<37xlNI3xQ7X3zoz^@k&cEttjZ}PzRM+H}FRpO_N-{#SuD1_{X z-E}eWGkD3*+pa(oM%stqKeeGP!E3OqR(Ei3x2RcD`$?=T+Z*09_kuL9jC##jG!3z0 zfLNv_Xe;=QpHe9rQfk zL$xFv^2>e+0W?FUJ(G5mUSpmPu`IpSb8}I#{$fp%H8~XR(ZTzvo1nT{&yTWUq zcNvV(o!Y7KHossB*laag`YKMW8G@mWq{=)o)XXZur z0d$|?1QX@|ghc=IT{8!I*LeP6{4%29m=^waCa+n8nphgc)ceD-dB^(RVn_HYQG{*J zjoP`p+Phh?cZH7-Qa=X^)T|m&o4nanWyKkhTD=#6|GA_jA(7GK`Q8P|->r-s&rWILyN|&zK)UXPi@7Ff z@6*|)Hvpe8@n}89myPOXwj;Ct2YdyMCS^)&v@rg|?aF7`+LED*#b+lCjxlXN`_7{= zjvF;(hlTi*f8}&k>&&FF-}x~#77BbqL*9JlolZrpXhipGm7A$y_gn!bf#)v6s3x?s zRhH&O-i2Rz7|H74yD9e^i%s(k;Fv`5{L^ho#x(=tyxW5@~Z+9|qb zs~>M5rfFxVL2~OEt$LVXE5np(wwdz_TF$Fb+hr-@!>T^w9?9Y)CR<5;r z3rdFJ-Sy$0oFE4JJAcPR>kq4N*c!aOCsw(0%|nc;ZK*G8hpMW*Z(UyCv%r^2=}v`8 zbm}4lF^F4#aX@e@fJ;0!tIe?Gwwy3r#>?NIHy7)-Xs?YqWYXPbeEOrGkh`f?$t=De zqGB!d#Ym{KEDynbllf!#a5qKNasOHy5#wP(X{ej>dxtJI{eEXjL?L|}U+>F*MuESX>;Cx1 zl=`pAE`(;|I2-Lx#%1p6=v{8VceEerm!P%;wZ%WicSrLYZ38D%gl#uXz@Nsph>b!T zsurwS8=qoFC&qOCQ+<3HxKOzznMiReZ@pA|h?se>|Ks-i84-o%fBnnetu#9S-VLP{ zzh`Ll>c#V6EaLhcN<_~!{(LI*?Uk1s@nlVO@s=UspiH{ad=UEub7_E-gRP|!Tqxb0 zNEP9=)W1If|MSVhcF%v4I8F(m`1-X%Cy+PU{chJOptY);ln@Czl3uZ8Z6gw&jIhsw zIOmQ2>99`+Il@6W$6hSOo&@?e$l_f~9JYt}uN}Q7p0$XfBeCIpbj1QM?R0h=C@GGC z&hG74reXtz7LBS%jV$|En5fNGAI1fhAOSEXZ|SgLA?ZKcT9%Q5Po0SJoO+m#nYX_Q zH615AOS7K3)vs@!mXD+^s+Jl{7_1+!&DHxHV1cMIY$-D=B{_CBa-5aNYHC3U5r>cO2Q_}a3vh6kfyHU>C96WRtOH)C z(HjIi9p!^KcSVh{JnTe}mNck*1w@zA^o|wN!(IRbE03BlvdjY?xYI%hm^4*t&1Y8n zhzFX@$dVLjm0G)M= z%!Ezbs)7Aa1RL709iK|?Tx8qabGbD&f-@V?pu2gA=e6iHOrJo3D?U8`RTJ#6EB;vWV zUEwymA*K7`Cj#M7J@{&+!89ODw4Nds$;!8n|g6F3ZAoak$-#=#rM5s6?8uMI-c!= z)v`%nHG6UE>ko@@6`3jhE9k|_8LPfGA8$%V&qu5`e^tuB=UW5>S<1GrDD&)5*jPBq zyxmje(I~A}F3;co>W=P-B{;K@yl<}k>YTYnl`kQPzf%KJiM7y`(fKL`ta9+&C-H&v zCEaDURkpgm*WH|Z?fg|CXBG6R3`P=V_ht(z@z+yFQOgfY>`nFH#4wI{s|f)s{nJL; z`{n>g3(|?VK3+9JGeid1J9B8L+{BI;j-ol*)wFF{uO8R zmD8SKSI@0F^fjBj?(a3lyD>Dh<v=)#DRwi5}!Sd%;BRe%&JU1*)ere zn9T~m?%5Vi*Os2Htfk2Q8XWE;Cz4#9ZgmfHqdKPbj3v0Nw?b-9Cp|CI%d~xI@?$3V z6S^%7d6l&?8DaX;%yu(^@;^r8|61T4L9ndJADwL8T(EjV>`}||WosUtwxlV(d;Ym1 z3wgI-{3-=~GG;5oWK7YpPWTF-g?DMBW%%HXcFO@JdUy#3YEm$u@`L1J@ul$y&24PF znPBHJhrSzRcK|w3(e(1ZJ1BxtmCF@b<;ESnyQTE8mB=Z%HX_}zZ9BaXHh{J6pXjT7 zI(O82&_;FCwzi_WtKRmUQ1yD9_+^Aj~%fmh41LVDO>I&GyOm;N^%FMJ%t9TK0- zFO%Aduf!^1TK|}Db#TpXc zCk0cLvhv6H?KG@FZM?3N*)paTtTT#i*I~0&dmOE``=rLl6-asxQ?06>ggSZH90#5m zi|ElVEAT!?{oMb<)VJaymBUSFo##!hcUKS~^84xG025J)6XF*k*drG@3!l&KJT6NQ zWm{2d^tqa_eO6>QqVmguW4hYr)zs|2?B|f%d$XW|oS#8xGtw+(xtL+%*_o%|yLUA$Km^MX!ZsWlEJvbhqx|%(CE7y>b zO)-;FP1O&>Gslz!|010V8>z2|UhTlRc2VMDKvTk67Lp z-?_RG4`ZaNMC+bBJ0v0vxe&Q?Nf(6Ca+1pyA>fk2JETy}x9UmSLbspk+Ei@_jzyi1 zf^uTgSy$~9NNVK$!4-?F|15bdt%s3GOZDwDxAvMArp!AuVd9Jqi+v6Ov&u(2 zEY^DM*%6eGLaiwE-Ia=<1M?Yp=5_8~RFWtDQajrUygj;Mtz3v^J-}mZH8X+XKQ$?qt~@I4VG*j^{G#&XsZ+W=~VX z!N&%UJ|ogigK_6z)~mS7W4`t1IpmFfqr(G-MSODPamdl7@sfWx{dm^4;S2x%Qk=Xg za(09J9j!|&zR2py+=%>OvDPvBU2g@Id3kh1Sd**c=+XO}?1s&NOnEnadU^GrfP*_n za`h+nPjqE5O~AcL*vduZYPZ1I$cN~*kpRN!D&+fU-g=KdY;w`7+s;q4nT_Eq`n;Fb zLB*l`7|`M64#7v4Q`U+ebqs;V2#$OzPtHq1{pN8@|uH?lRpY5PIJi31Io?ZnY9qVE ztZuJ#QU@ZIo!3B)J=c$okh<)Cd`PsA537U54gwj*ty!w@GIPau!jr(;2#dkpIVu=^ z?6Y#mRtfJHPB-z^Es0e};9<>2Z*->0oCuMb(>iXlI;Kz7k38JtpuN}Re)h-|F;uFn zwAcO(UXxWXaY3_vtOdD{l^rbK6{rD}x{pX1-eAm)&rCzWaZ9&~CQEP~@gNVqx7{?q z6_PSq*vV=$zkm{)(kBrC?xoxy%q8WA=A5x|0rG9cjeSU?w!gK$oIknhjcz3|ozf}K5bh}GufHpO&5RI7yfuv^L8V-@ zq&XdbvVB+^Q>X$wmCV?fE>KMqa8B9Z4OQ+RTR)Fn<0m%lu{_J_{J~xPP=T*-Dp78# z>q>+_Alup~oLnP%uJ6qQZq<%i%(e-#+ud{~S)~_yDNT&8m>Hp`!C0F_-0kDqazM?f z`gJ*yXEcM)-8F3{CSIjS)v(bqylqTkmDK7HwWc5%Vai1g;4#`185pSA4bJ)gZ zpN1Oq1tnu?Z%;H3E}T#NAo$5oL_8(thJ8vhx=q34l+1s*MDXJ%g8U!ER1L2spMl%j z8`>DG784AkR4HL&El1a(!MX#zMsf>h(qu*Iv}TKN4Mx^RJE(%Lt%i(g;q@U_E;u$v zHc4y4d;Ynw@W6w4Nw)M)Q^ z#@%y}@IZ-e1;@R(=JC=ARa$xSv3y2Yp`O&qS#yIt`9idi#`aW|i+A9mZ$IY)Cg-Nl z^Y=^QJc1f{Epnw_hO3i&keATPb_}d1eA$b|h*WSNVoF@~{X8-zXivH5|I8mQe)=`- zr`~XyHFTp;CrfhEFsE_Zk@W-RTi{XA?NOxXt-Q$fZ8E#f3iY&)ZQH^S8YaRxs$6g$18IK% zkXE_CCs^~W!4X0sy_^8T;4GW32-2nO#&gxfteiROP1^Fc|9oqW+!h;kY#@!GE&zP^ z2yg{^>wOi#JhvG4Y3GzPXL(eT@306tkg+v?(COr~n^g%z?$PC2@2^uZ#B5hPeO%j6 zS#4Q|dr3QOmdIOOwz(ifsU)fp)X2125sGkJXaV&iX7Ak?-}`hkhic+>lmJ7=heF7J zf&WzytI3-4(%qcF}m9 z*D;1s59Sn~wI>{w(G4z*xN{+>!;pUAdP9!XRGn?Va>Mmt$cF~1rqa81ky2WgI6sh8fv90>JmJq6u0h+D^USYhiJ;v%A@j_zxDFHOcv3A z**dsQJo_62?yp5cn9)n-?9lpndL8l?*B1@G?LGX%_eE$8FOtgpTz+l6e=P1PKR#u` z0r2s|+MF`#utq+({ANTcElu*M%caEi^}o3Q!7ElgMx9@WnFA-=TncXm`jdq@qFL-i zanM$^7^i$byB9)iWE-O9IN-M!)i(w`LDK*`_thY-y~^i0t@%#G`q3l|X(2)l-@kfq z+wUmX0cs7A(LE856aO3}!=C$ouO!r}o^Vt);f*S`Wce=Q z#DW=G-fP=CP`L@uZFv!vU-u^X-la@Wxh-YlN70gMws=Pu(PBMzIMnq*w>#r#P10lB z;A7SOe2KCE#mYkQK~LLylG`=tGZtyZ89rV7pq< zVH3aazze?BmYBm$ewM{yH;`h)POOlX2EzRUiU|ex{E1?l2+JxS(LUsTuRgV+LKeihIAIu#%PqtG1SEu>j`D* zd84Uzv!68ZL^5gj>lYE@?rYHXaQf2XaX6>-YP(T>!hZZzMEQC(q{RSspmHS>8yT-SBZ_m^ulJkcM%1#b!@(uFFjt< zE2f}Z*p&lKAMUZj{TPlgx9amLfgEVFIYE4u0Z&+s#JXN3MRMT@f~f8oNJ+wXaMBOo zHLepu?wq*WNJSNcTi%rZu90Dr#`8rGchu$;HSB3dMsxc9FtvU)TK}qZ%zMZF7sJXJ z5+Nmtumf%rfNT;)M8;$4TU`_{?ULlELFLyus!``-D%ZoP>(a|6C%sd`h$VTWab8CY z_S?f9tovJh>j{aa$5n)!>q%ueqAZ0no%yNQ)&%2z8z@6(TM*0wm3H0^&(%g-jQ!En z{@KbG$wyYVp6PnNBwgE!!SIDmUo0Vd?SiNJRK6SY6~qL%PmV@*)BMtC-bUk;laWdu z7l+j+BItg*fJr-svn{&u=48=YXrDIdqxGY~^=)!NK5OUf&mGH3uR}T9O{g8;axzAd zZ6@KK_NH4e(;n1*9aurCGe1GkGz5}xn9$_-#{+^QUnw*;JvId+qTS*8`cdTB5M1Oo z=#|SkvK_7OP}y~3!r2PDGF|>up$ZC~*F>1X-U#T^AgBV%{;(Y^;M*q{CzRxox1v?! zfqnJ>kLe7VYOAGU(yqrZlEx)clf!eoSN-`bizFtx$c^KuWU30==j079db>w>fwWEi0Cduq@MH>Y)dA7@HYIZv|SD;jx6v)mLVh6jB|;9LBV{xOz(cZz0aW^!~yIQFwnlVBT>B+Pn! z>1hvbItdzYu8)*Im1v~l#@76m8pNmft~_Q5;hCg+cCR>#xuyA?=##1uNm@tlNZnD% z=#fEEO<$nxLg?$}vZj62yhRTV*ymOL&X$$;w=3ec0}pK8d;i0 z=((p?y;EI5Uxs@=!(n2PwAXuejtFPMgM{Iy8bgZLdr*QZ!M7bP#JuWk4sek)IklYd zx{jKnxg+l#%`1*ZEg6SAwD!I!w6^I5hM8v3A;q55E|+f`rp?FwQ?YAcR_k;3*(k55 zbuSA9`X)DMO=EEbvwpc8`d~W<5E@HNzN4M9ooBzj*~n1?2?Zt|yPE!0b^C8G5YsBh z9YxtV`jhM-L@CbQ*j|suwj}j`vG(0zO?BO#D1r(KFCrjaq=OXc9Tn+KY9tVl-aDa6 z5d@UpkuJRx>Agz{y@k+wO{k%_F!8(h&NJWZduN_`X3igZ4q>01eb!ogpS^$Ux7OAi#Fa+w@aD55JO?#!}2y_-{fYaQ_pQs_KbkUk@r#9Tdl&lPZYet0{NqbADtQ&mU{2_ ziVW<@MkBQ3B)m9ptl-AJyGA)jRUcaqMP*A4_kw?cd)UPmj(GMK?6ayvcE>!dN4=i1 zN=6n*kFU6Z1=$m9)>AczJkKnZigMCzudSakd~mx3?plhNP{-b%%(8ek{ota^Yt!CRl_0NjH;^m|8&% z5ngpJ^2OO_7*aCh8B!2dNXriQq)!8kJ<59k%EnVJ@-((qHvUKQI*p&M$xhX*LGKKwv9U_KGaUcOc+ zQ(DWrvj11Nhc46Imqa$Zph(h1&~sy0o{L@DlcR8r9m!SyD=C`EG|BrK`JR$KwdPrG z=LIHQC5G)o^G2H|aZhimB1WsRxv?jSkxA8Sf~j~DnfmLRbu$oWn@*{{VeoKm@Ku__jS0ytM1QsB zjS|2rmYyK}O`OI1gxB`?nZW>F>rp{INvi|ohQylhNb?jIH$(~tI4l%t|2dh@J~8AV zp!frK2?=FQx?xug=NfqVFnzOs;K4EijJMq76nXiq+(Me4$1{t?qVp;$Ima(~4jUVEf-OAkZR0q1x|Zol&@n*$+IyX3Af z?2oOU+|(<&1Qi|mg6Rw;#+g?uN9j%R@b%Gr=Jdhh7uXxh9r?rDX12+LU$g|M=Dg*T zYM#ORe!2AFut%_tebi|Rdstld#7=0HGA<>AR(0jbuFD-&EJ4pih=P~NmgT1C@EY^e zMMs?9ThCbu7T;P}r4GqI50>Yp|Dus^XC#!zr2KkJb?g;@jMP?6rFB@A+Zq9XS#R6U z&V4^uBDIao8yL&XDP-B&*IjPFd;MK<+nF@$0$?y+X6uc*U`A^u%j@`3S)1i7$D%co zcy`WPfr%Dk?FiZ5u>wda+LaMphq@`fu|2M*~x7oXHn*Mjy5owldDow_?=bD*1 zk9|o8K6G45UaHqw?1aojl)Ep}l%OA50;ee-i3d5&3B5A3lm3wjj1Ob zVxhMz%2wBthJ4*lko}CrZT?{X81g>iGcR*Rmc2B^)psmPIsn8_(7c<=+FQcn@Nqx$ zP1`YX^>$qQBQ??Q+&+}2{@&XkIHRN`%y!_M&M>nj>pKI}7NVzQGYh3Rya+cgmFiLF z@0E@BFYrWviOt?SyIZS$l07?6nPVXqe?p9iow@s$%oVy_llq)LL#3#v;%v-#!*KWr z=X$9lwgR-#VM>|FOR+3IOLBW`|Gr3@y}{L95gNxe%dDY~>k0U$m2@w?w6t{d))UOy z04*F#c*2yCvp^qIuSo^XjEX)yt&1(S<6?sCo-8?!0ah!au=AZg8uqLE3C3t`ub9=e zzQ`qq-mf{#l_q&d$?Pr>wf(~GkC-8m@oLkNs8;Ih876(vqsmoS*bGLE%=~1%6;UMkI-POh>3#yl@?Kz@74uV(^1RdPigz3pKe$QRLAEx0^&5qOk_NQ&)Pb0 zv1zRN{500f^?rtXe+;LoPv$jIa}E;Q`?9B;M7eN0x;kKa;UL98E3woNSuKDi6k9%- zI8bu3F4g^^cfpZ-Q$zxdrox1R&s{|}o#Pw+e`h$0O@wgdnF+NuwJ z@3_{{-PZbfZ^&7`02Z3wo z>HIPu`~DXg>CwKwVXaX$a6iy@cY#55@9XYa{B=_eqYfMH0z6Ilu>N#4^m`*OUh5_8 zp+3!~7xH@rK}Hotch;NGq-GB+Q?>>MZ&1&UCM5YAT_@oId@*{0YYFR%^9k@-Q1*Qq zQf9o?BLW;|A84K9tmS;`U(1TVOZmq7_ag08a5bLNq?_&JLmc?~6oT$ucm!)V>L_j_Ua8MasE`Jf~}ytTNk9 zl}`PXPj5L$=#_qZC*iv3c2&=6uCA{>+w0tRT8uPur?;YOHmTh5#fiFja|SdD5b)0c z1xilTZBO$I!`Qu04OtXN34;#N1mP&nXWv9+B&MMspUp`$#Tew#b{femmwT@Feit%4 zBb-vPHyYaDo!ZHt_8o6)b4Oji)7N+?a!cVy)U})|c~A=t3#g=AU>%EY_GFf@y`iy> zR}Kg@Twhvb{#tV{hB@D$BLb4Qw$?}DcTu}aC1Kii;4^jRxO2j7B>H&KAVu*T(}b#I zAT8;j8Ir7v6=}8J*5t8MnV$>71V25)4Z6A8qq@-kb#7oY*9qmZBCo`WiMuv>7I9V< zT}P^6mFztonmc&OQ{;1JgR~5)Yb!cd<8wz{XhEE@y?%04R>;!%xkh?w9n*PBd6cjl zfnHdvu91Be)UH^#7rcG;}papzAz$JmriTr*WJF=gD1u)*!W#8O>b!_3!v z?&wj~enDF5j1(f6M-Mv$~~ zuQ}JG>>jChUb6b}6ymZ_F9MW_!^h>rPO4CW2Tqrfw^xY2UkCctco(sjb>b6j z#EBJAS1)Wd*C73!dPxB3C75-SgET3Ief!LhBHF@~>PWV~aOqnlEL>f7JERRglOT^} zzF54CLIh0mdL5amOesVUqOw9`62JX-2Ck;2_L~Gr6n*>Pz7u%ySNtAVLj)iaS}R=1 zDR67fEDAS7bs?2}8W`^^0e#uXkdgu4q!}KPj+v=MX4}$xof&kpJZ+n|D7oReIsX3XB4R z4Zw-mLpxtCMZR_{>e#CGx-~Iwg`^9;Cao*rJ8iYnUW%A8WI8|Lis|1FIxJ&?eD;O5uDfZy@-sx;&7`wI>1!BT01c(crtLwRSdWdj+DI3-eNi!eAt^L<(CR zqB0|tn)oXHQ;yjd+DNLCK9deO(TmevI=s~d{wFY_XG?13%-9rmKjwE%kx%a{j(=;uFOi+iGRqxd(3n#5&@ztUc)^S4?UwYzW(AGyuTODs zH1+?=d2pBX-Rr0CqhEkL_rLndyb1Ap@IY>#?q1B!UK4Fh)LU-9&-c!6hmxFE26%^^ zhX>47?w2*&Q-qMA3mI2 ztnc1R(Ph(>H!Oy(GEt>0t&D@rzHehE_azQC%y#AZ4J18s57s#a%!81Y3}r^jsEl=J z@m6$5eso_-Y`#mPEO}B*#piv!Qx}-zPRWTI$3bg2~D- zdP?TT3u^Y{pZa_7|Es5GGjkXR>)(#oh!2<)b!om*6i=RH{rK_RcD5$m z7l4Q5ZgF^9BSz5Zx;y4PEPggMiA|FqPAOP~33Mm~;if;qEOI7(hd*42ig0rul$Qqc zEp_98*>6I8ScDW>IgoiagsJa+cuFuq4QIT2s2}?}BDZ({?ao-wb>6&rQwYL*OW0*r znd|xx%g>8D%;XBV!unB^8<4%R4@*kJuRf^I`uy0Mz0Krn58)i;vcbRq2o?i74-ZeZ zA{N$C=G5-#1m_(rKlAUIBT~iuH=!gA>l&|z&!{2gX-B;=Gp2Vess7=528J(ttyq4{ zW2d{b8jbgsqNnSf&8-r#u%O(m-bePwfTM{rZ1;-4(0>n1Qf0GPW)M?B3|9`gm*NLBr zw2Vw1rUB+i=fR|5#E8p}@7n>_zc>5WUrXhcv%9~Qk|X~|zyH-Ba{j->H1#hr`7!?~ zQ!K2537$vvzqK+a70aZo-gxhM7l(e+htHosW2|TF`~AmXQfSqv|Ka|auW0`ILrMS9 z@Oij{!XKjgeE~@)H|7>tZQ=(JxPCc*N(u{04Es@9#;jT(_NO(&>b^k)r>cSEI*Yp6 zW06(}xuikV?$DGj@Jjok>7g=nF-%$e%moFFQ^x6st6hCIK;}EEJv6Ji5qOt7UJo7Q zC>)fv-3XT43+>|VdoT~F511`bUwBl}PzPmqHq^401R~Mj6woGESW#vpe`xJreVK1@ zSI>ut#?|Vp^0Tb5^^{sSI3WCLxM;Ego1aQOi~&|Ykw#9jAOKppkUcs{D_g@k{`3_q z&vBN@O*x2Na<>p?kz-;@3m;beUAO6C5XA=5VE`^dz?^2<*!d{!>WdMOKt zx08HJ%jeR}%Y-_A2`-pd4h?=Zai;A1J{U`ihe4QREL2LS$e2lENA5mWqQhBG; z@zlxO)-Mg>d@_>z2}RnpXi&gP&#GPfARcimz9PXa&fHvBx*<+z%qi=-gY8e_fu zaO@}rs8yY8b4z5}n%K~*s>W^BQ|F9Cz4+|)RZL6=yY*7T?z8bkB~Qj%%ou+94@0v} zqu;Eu>v}C}-cT-NBz+$jkw!aMF;4&s%xCGIOKRUVC`+{ubXUS|S4P|<8 z4?8kob;s$%?zBcg_`Y=q+`fRD^+nDbT#kwTfK0`H&jL^Q3EK&j$r~=9OL3ioVwiX! zrgKjH_c;y=OO=B@uOC7*+YbLau}l)nXV}4@oK`NUi*_n_-JE`Dap=n7Qyhm`HY&vI z)@g^+=Bm*~!0O}|E!y)WP2+qO@oNU)$gcS(0~|VW**#XE1|JZ7)ppaoI?BtRVroj= z>`E}=sQARpf!!P25QnaHNN6B&@Oji~+vaPybv+lsMzuswSgd8I?dEZL$toKiVl{H% zJ$QcMZv$0DVP#d>%8`)tPOBW*GnK4%xGBfAC#!Vbo`q)ZIo8}PS>Sj8<1-IyMQ(eK z`Uyao3hB3clEneOpqN#nG80K|brP}p`1LLw5wGDu8-{FWZ7j1m}{YL6rnav`m%yQqV`s-?x11PE{z8D7{W3W96;IwSs z1Sg(cLgp-)D&iO%jG9Ci)-HHzh>Nxq%t(X4CWp_Of!V3aDl?E-)|zyw#K_xB4LE%~ zccZm>o`|yM^nBTBzt6}X!+5JJwNAskE1SKdv6A#_nhUP)(jHy|doGm)&(l)NVOIIFLr2R4{w*lZUSd(4NqrQOO2%U z4yBFrOU3LK7beYWL!}6ck542Y8r)IFa`6%r%g5L+mXks z9bCs3aO*1X4fZ}K&xi%;Msb{gU3cIg%L~kuB9|cFQXRA%>niNxjJ!|5eMLK(PiU!p zo)GP6zK27yE2=@9Y{De;CEs6hF9892**IV*iOd%*b+_N1LPc8{WEWJJ9jFDBbZKUH zvXqL^NWR@33FKIXHEP+$4`xV{H;J$BX6UXj01HQ^=xP%SKr+Q8+QlW4E^HIG%+g8M znh`e2q$`~q`x1!-X!K{g!e z(!>?=^S1ddZPTO@OkqRqwI`RyB`%9E%y5Q?m35^q;jwM00?ysF)$P)-X}rR>*@V^N zVwZDY<3VxL^Rk2H`l0Z`srOsxdWwmn7(CqbK4uM-__A54414k7^F>udNg<79-IgD1 zM)mQ+0kvY|7rl}OKY%T@?|d2MQbk-YIv9mtUOd&Sjj}7Hgh0Js5bHHM+Ez=XR2Y=K z0c*i#N7fY+_pdpc8fAhpDY$cLPS^@fT3+^TtroiIC&d-pNS&mW12VtyR;Za*T~zMj zamGuLdw(K%|1$>IDrn$4_f>GDuFRly50V(bUhuv~33Yg^okzt8qbt2t7T~m4Z&JoP zDaeL<#l>mGn8X+a2p%iEiAC!RsfyCaCSea#iCAF&uP=+==YILxdiN!yf>v%)P0S^_ zM19Qt>oV4J5!kW?T}7wKXYKDfiqCQ>Ou4%#DaX5b0wH(mB#AB^Pe0w1h81}@mr9VA zbGEBFzvc(;>PaVA;Dj+p&^31YY?`ww$mZ2(?Mhg?&|5R|TLDyC0B+V@G0Rr<>w?Nt z2hAdDjxi?iLzsc(3@WrwH#=S5YK03vy9wqn(5~-M+0|1jz2BS@!x>|e0NB>6=*(zIDCE^^sLkVt0mCx=1Ok z(b#VQuCmp}D(F!+cUAV~RzM~k`FMOdqN!*)Czhft zhqViaYn9h2ov-(kGPZ+5bxu%g=@qA-Vo)L{GLNpF=|aC8xf9U^Y*?=dnXt`CboS_T zSEoPpYQ!_SrQnz1mr;11=Q>a<-+H z>&s*$EhZ5HfoLK{Q4n=8ODv;S5q3=60Y1gvjuNKMz;bY&^_>5>Qyu*M#fpkk>Xkk= zZYiw#?)*vTWqHxEb&QF{$fZQl=%-{{0${-VT5yRS&Aj zE^@(hl>Uuc%rL%{hGYQguud7R4|UNd+piqoUD;|IsQxrh)qCV-Gh=5avN+hXEvA@F z+#x{wF$+2M%NnqDQa1@~e^&KGs#U?0F_v}XGF7Vu{?z-TB69EDYg;dV=Xo{qz{~B~ z`T#ASH!ED1_$(_ekuNqDrf$dLd}yr_OH*-6L78`Qv$@*Pr+U?pN$JYV@b~@6t6Jmq zr+Uosy8>^Bjo{7IvYpo2@L=bB%aakH)wVHa1jH*Qu5)i{T;3f#zEsSvLLlXn!A;Sg z8v=^atrm#5G^aS~A{tnwRbiw~L_e7e)UFpE^Dex6ctZWPtwgH(CVDnPMZGiRrrN3R zZJO1Bl<>eTW&8pTE6djh0Fs^izg1eGWcmYG^0eH z=lvH~T&YRR1bzIxNH#BknkRAa#qGV@@ud>Kmp&C!!-!*@#&_prhX7pFFu|S-ES&wX*L*Vf6P`O z*R=rjfGU2z`Mrt+kxjmw=zb5-+CI!<^O`Xps_idE=pwX7bpUYAk(qwALkvOu=j@Xb z)5>X+$cF_pu|k-vI$G7H^rn-JH{ABYcHKLXLUph4Pp8%lZl$%VXG|&sEir{yMD{gh z!V&Jsm2bo%jw@eOQU!`N-_z;Xq4PjqcGAO^ZgMe?WV5QN7W(3#I;X90i_;)tyw>7` z#^G?G22Fga7x67`Xu({2p601UBOkm)pC)V{^9y`HuHZ2oY`=mi3N)6p! z^S-8#eB9hr67Yc=b)9YOpsSQF*-N;v;zRHrz`#dl=YwE8;xNd++0Js)Klf6U=TcZ! zbvsJD@G4HG=2zHkEqFFciPO#vEbj_-jt`q{0E<2jPK;*T`unyWqw92_WdreZ%y#67 z3!0ySJX)m5C`j3nn*B_Iop}MiG=Mn9;t(=<+IdDHR~`)} z5)K5{k!p|2`4{D&+UR$JKt?@P8KwN?Mr&t$t6a1C7FbU1QMIw0v{vQJaZi@?%zkfX zSt%QIklRFP2r;#|%=5x$!Ye*>tNB;#_c@ot5apm{s#=*9ppwqS#?5Eos96CMAA5G- zF#iZU$g@DPk_YA7;;i8BY}*sDW#1T!BISBveeLx;6h*@RQgBt3THHzPG1h3PfMNMf zm@DLynbV9<;6lL`t%*;S0vh5pW+$cjJtmw6XGQd2Rx}gWfx)?Ny-(CHrY@Cuk{DxU zwN7p;^7|HG==m(a7)~hXy8b1YiGCH@S7TZFqMSo`(5EkYkWE@YR4^T9=i)9#kIH+!wy15CLhvT9>q^B;z%V5gpHDkX07QKCs|!E z%yS4vNTZW(Ov|aq7O;uVs7!|z^meU0*j#qW5GSKA(!h{1SFR0hy;OLS!bwqokI!p^ zNc|tNYPUCd>pKuk8meNySShk$19kOqFh@P2*pZwJ1UfBbx+W#Ntxf~}7#%0<>m7To z956>?1ESY6Gz?PGMy4G=US7azG{CvMI&t-uWc;V0;vZvDf>V^bl>>ur;AhcVZ_am!(<%EDof$p$nAa!G{ApMSs~YYoRKvde^#WQ7K3W3 z(Y4mT&N?FZ=eM&kHhpjN9zFE-+eTG^T-r?ED>S|`a_k*|GCp4QeDM;b%#WHWj!wd+}#lt;$ZPc#BNeJ1U+9?R*>N-_+VvyQwOH z%7xp#*AbP`&XhZap9XHcPk}6|X;~kiFgM#hIqRm$`{@v@q+L9>LVae9iGp}4 z%D$P}wQl!IoUs_j7E4q#LPg{{O17d$PB4})&PM#*R0)*Nz;l(uoc5`Yj(irlatYGDN zV#KOzae&=C$avG4ZgCxf#dK{fzvYaWt;k+Z$(_A3EybV#eUW;fhVF2ROtsa`Er2r) zIHm5rG4f(dUp%bT^wO#w0rkudN{lE=F0?1TE}0F)xJaan`CC5U2Hd|-y^Pn&0Yz}u zo`*JE7QTkY^z9P+%EXq??C}V9Jf%q1v|qVzGE~Au47XT5&}MtqqH)xcRH)VSNvrY< z02IG{9PdsMQ*M`gvRA=R0WXUxvp?517@TFVrP#L^3M%w`h5t%*ZqVff0W&$;#dt5& z1Mx^`Jc(#&GlC`lj`J1%F7M-ZL#d7iv0^Q?$|3CgZ$ci&W5Du-GvWX8e7r~Av7GM? zr-WrmhfZ)}tA0xpbwga9AR}+6sh>SN|NZaj1~AfHa+QI7lCckm{x+l+VKQy_Q z-^Iq(XnZ8bh_;TpHe4JHGQ7?Q-&wLW{nImndAJzje;HpQMjBXA_ZCL6qALEoezE+^ z1%Qp|yPS?nA?Q!Zymop)Pfv>w!vOeoPq1DaHD%vC>mjZFhJ(xqtV-?*rx*c4IkE`l1JN;-O?* z+8;lDv`YNUxA6vhc|%t7{vVJ1I^^Mhx^B+eL@BV;N&nFbFm@>6APddcpJ2635ms9z zrA-j8wrRCWlMJ&9+g67G;GBG8!k#;-7jxg8wnZvJ_Objscrov z)*L6{tRG)GuYJR0i>XnuYZPnvWe+~rZmY>^kE;WkTZ^y%SyW3~3cj7YNow_QNJqn0 zgx68keK7F=)V-RqC`MWEl>y-E*!JKmEZYv_y>W>S^}=0egUflhUV$>**5^Bpdv?%P z?|F)wO7>8LIx5PGY1xt;54y#}(N`GJ|COO(_4jE3qpqmb-rju9=&NTsakV{SH|KMf zrYyRMLcCa^p#iPLOkz-RBY_poJ5VW$oDpUp?WG~!g zibVlD-f+PV)wa@MKmlVv3bd;hrJHxb^RunYQ)3NS1yHb*KVBmRj$4e$pd&DR4(v?X zpZFF?cbVtNloa#f#iv!>B6ahuAv3m8pt2}y<91FBhi;~-=-z}u#9ucfbh1kMZyO_2 zEK4aMr3uY0)+e5jpIJT`5KGKVAAVzaX(>;(UM<$58z39$#)p+tlD~Zm|HB%wo^Xdv zab^dZ{Mrqj^)>(K@BD;TB{b|iKF?Ec@mpYph73vR_g9|B#16J+J!O*SK6#9rdYXn) zGNlNBrd@e(m~MloGKxQU6d8Wjq`q@xHk7;J9o#QbSKRbB~sBJy;;$1eXO<~(pin@_YgT%kX)~n!_&=6xbM+av{qgj1`#t+~eivPItES$)avvg8${ z8sP-lRVerC2KuTTkWBqm&E$2;p{uBh<;u~50^kRvM!IY7(fH^6MeT8v$J+ibBQ0jT zs9hi4GG!fW0-qk=G!Zn{Ov1xi@o$YWspx~lDMZWBIH`I{ji%OX?hG_mX?~xQ@?|Ae#v4S5mPkoo#m?M#6V%bHIu%LSS)EmonQ3AB_sRz z_ln8Aq=<3KZAEH#oxu%Ucn!JY}GVH{Q1PgX9h`YWYhGoG9kWl zHE1aHTPeFbb3{f$XZ6p%rb&q1;<|Lbm1O(RaOX_Vz*X2!)O*uPWb%*uy&_C?% zr2p&!se8%3cy#hn&a4QNeG>Mklmhs8H_O% zMF!3TE1j|$ZjVzq%RreejB|S)-nG8Bn#u@*u~Xe7trmSs*x*XmfwNbY-L}(U#pGxd zpdZ?K{M_y3{}ILYh++xNv}RvW&n~M3H(Jm)kJZ-kOmQJ0-hyizrU@q6>HZgMh^ew% zg8}W@ie0TX@j{Osk(*Vq!9@po90Q9VHTBIVEspAqlbn+UfJuvaKSrQ%fqxcnQS_zp zN~kA#x0EN*A}7&nGx1_d#9K1EmEwk|>@o7P_>1CkiD6?joSSx zqf?V+?X!Zc8ZPyGJu~^BvNB)Yb}p4kBKURDbX@?RyWV&vhho(!SIX0a=VxbzQ!d8` zuckSC`Z5*)qmkoU7x?Q5rceQn51!hCy5>E2^b+1fOK| z1SfMuj>yYLC)aJt=00Y9Rm57<*$_adN3`HMClse2;{qWJ3hs1njGwa9vo_6 zCuy~Bn-P!3*PS;>5L&?DbyxL?Bn=Vjq$k!wCUO-yM^T~Tdm>_Yy|!TroOrV}N=PnQ z#(I^t@?7A-5r+rNTk+=ZIMgS9VM}=ZXAjI?aIfgqrH{edxWF1|IXm2p9F(XqQm zy!fsg;;`s4p+U=K5>}00C6GtcNObdZ=V7|^053PytCMF6`-$?Tvv)Yss--qxJedci zC=1k9c$!Z~0uSEE;xt^Bk?+@Pz+QA6zukwBII$uOGMYQt!@|HPOZ-8wj^91jrxLj zdt;#0aFmzPMa2tc8T{9{q*j>n?0;U-uW153tfv=*}LbPS;s}<{-U;E z@x*b^rcdwCd-s7V_Q}uOq{ng(|G~Y|ronFbTs9_5G|hK^CTm!ZPyb;L2AQI3*69vM z;(>qd3VM04ra|Akf2gAhqU-#*eO=>-P%p+fUQvJuvHEy^T@G*05vFO|irij`Z=&nn z`m&zu!x?HD1+gONNDe4CD}rXyF(noi&spf=mX@)#(6x}%xTkY{WjX#$GLpS7Myo3{ zN7Y37m}z($K0rb_Ru5>Qf7`!e;-G$+3y*zz1$JF zZzG+eJV}%y1>gcj&vTnxT@|QI?OvK+DzcH<>n*RO@ttK!MX-~ByX<;h5noiM)8g{q z`_wZK1T&s_ToW$y^jyF^dF$d^L_i9+xAot z(5aQOSX#J5_|}Deda*=zMzSy$aXQOzMygTeVpIBkX#CYn>En$7O9XH&hV-;FzakK? zKrRVkb+n*P9m)e0G$-&NMoZrf8XDd$=(r<+`UzY&11IJ~GMt_k7T~5W!oxDSST1_6 z0=|yb&}nHtHy0gjO`32_8M00Lp&!o1;!A4a;d$9B33#aGbqMxu+W3;iz=|j#xb@Hh zMAD2wXYWZk-eyG%s?UmXD!|R6U&N4mAyZGF0oAwfd?ohVF`SEA_D$AGXSK)I{HDIeQ5C5%w14tn4sv**Fa%SqBgk-B{!3L@ zN&}Hu@0wLSvNh-l2Tuy4FqPA<#oe8k%<@4*&2S%^B9UrO1JP#x3A>Tmq8P4#mxfpT z)>{^~ay64zx~mJ1$RoDeidXeL_!^~Llh$^2a@KghGga!uD7$)91m0RJKiuF;VwjHC z!`9WfETX7D0Qe0q(poN^LN*@T=1&u|TaV1udsddnX0_Aw>C~qM;oua{S;Hm_7Z|)7 zsv6B|PaDpz%|Zv5uC9Ju|W8p_ATYAB5)^ zw6=egv-d;u6@(w7-NO=2lJgTJ&VY0ZJuTMxp3U&yxsNg0s=hiNsrxkRF_7?<>+15L zohz*?)y0?;13R1@Z{1<=^bfrFK9+A92THsyS1a;qEqm`5JjG!@qKc_%%eFfTv1eM` z!}QaRsyD(xg%{!>P!8!y=PlHsqzl4Rd;VtDatqPWQZ#?fP7UtM+qB|SE5!mxr`~GN z&6->47uq2-WMfWnyqmzGBGV|Ou))|)9c``4r}bdZYNVX4ka40{pf9bhq_8X~xv5w= zk(%d%S;RsQo>z-37_FmMFetAV5#YAokHPVTj7os?%0U^EsQRmYuV1v6S+@A$XnrMJ z=onw5?7cr;N$Gb;P5WaNIlJk0FLvv8`0?0$s>U6c0fDJM`_%C89J-0P^OBPMgvKeENwR9hn>ExZ|hB( zH%*vwk4|G^iSjDV-< zc{iC>WQ->rxkA~KDEH#@yC_aZ&t)Kmizqi(#ds}+xK*Zp@}i25Jc;q?IR4|i>mv4r zDpaEMjeFGSa1qxJJvOAKgK40l3Kr`!n~G23A*)kW(gQS&`6YhfUi{AK;S9hy=BaZ=V2RPYRUV=-PmT2Y+I&6HJ5T1P>y;Ur~Y zzXoVXo>B<9Ife!e9oooEwd=*`X*JwD@E+mb3n20Mlpr#(m)9kQi@3^@ERcGw@X7Ou z+hT<8mcP&WwJ0_C=@?~yjfG~E`P?Qys;ErnvX^RHZH^uw93R;d#qjpmYpNbe_TyFp zaXz0_OC7~{%{}}^FnUp?u39&H)@6L`c>Wl;$9jp1{1Uty%!Hhmzi;Yom{r5+tL%}+ z;MIz-(yK{fYUPy&x!tHrueNrFThEC7$i2ML`yej5KC-soLEEnNf{_tzMD&OC_~pj{ zPJ)V-O~)6wg12U+YF7x}rH#d$^=$Xd+OYv{aZKeuR|R&hFvJ>;mmYlWp?VNH_U%H7 ze;bhUDZ{>OMnXP#4HJB>K1js`(&Le@jF9Q3{wd4GrY1C9{lSvNHDY2oG!Zc&9?;K} z3z>h%-}Isi+#x&jiIH=}&9d{EcR9U6OLcN#LZp05C0-&Yryyos0{SFJbmnbq*Qb_W zZDl6V?|SH8CX{oa5e!~2%M!KG8;=-lWmg|U4aczR_g*D**mXDh6}0l79pPNcPM^GW zcqI(YQQ}7+gllIn9ao-}wz}^V^e0?{HS_(X;o6^y93_Jnj>vVL;DAnb&W0MJFd6%1 zRIeodvaSpwt)5J?YF|m&!pTi`Wh={x#mzO;=1RbNcHNysnr3uz_qKOAL8G2mHiO*5 zD2>UNPdY`lr^>=Lbp&o7ISJVdKbanAVcYfb1y6JCjMUW(@;SMQ;1JU0b#H$|ub}^( zok~)9mJq=~TX@PJ!e)(2YuXD`;ui@U>szf|P5ZwgWlaxnA5XJDfl4HbUQCaQ8qfO# zK?5{bMBeH!#qE$=RY_U-ihX!5p8hLm#yK(6@#KamWX6G7pYNS58_9b=NF>h&OQFa- zvsF*-T0_ICyqN-7Zm}R<(fF^yncB<@g&S*KIQNZEPP5FlmU0Hiv$DR0Z;MH;H}&qH zU1cwdJu*)FD0veZ;fkKw(tcT|L-4GC!`qLP4Rt#l;8b^w(mZd7pyG#%yFtuYX@BRv zV_{)Ps$Um}UK#T?-=go{%-L68YO`nSz}O4@&N$M}Jwjd4-Wus7xRxftdOTe&4oXwe zV_(y_%cM-2GQz(z#mFd~DJ)unwO-BRmhJ#lOWh{53J3Nu1PQBg^2RkC{&g3~ z8fbf?WPd#WLJ~vbA+Vk73lApQfWKZ{v@bbs=n)xOpEzpH15SZ67Ya3WQz*5yB;fs* z-ko^1^(#>t11FR*1NFMw)eXcah%vY0>!TE{+E1$FnTArN+lgq6 zi3XHDtXM;R0q$x&7-HZeA@#HSv2DqtS0^SG=S9HC`2u?hn;#UdlYn@!1s>V-@iIx< z80#IdtmWpd3Yun};s4gSBM1IHgSpT38 zi22M0Ht9`f0)^{{Q(njiaa_{KP>;x-_*WI%fl1_PGgoyJt#@e!t-g6Gg z@uxpt-MP5bCD%II0DAKnf&8;K{Hzc&^&vdM@tSb-W4_#@m(5h}Z+2%U)%9x?XPVs` zHUgiq%|Ie4E|M7nt-JilV5?V@eGc3y=p=2x5HlI_s#I`Yv$rUFF>K=NIsW%ltsD+CIIkX#Kr3gAHTk@l6=o>R7f;pacnd!pZ86j57QFDS4|Oq?~oT zx{>Nj?PZMo*erq$q42Ghp>`78-Wy$>xkA2~PAz8nX>(1wXU7I=`5&acWmH^Iwk-@v zun>YnaCb{^C&AqbP6c;Ja4jrAaCdiy0KqM|LvV+ng}WD2eU-j_zk9nwzxU%Y7=u%A z&Su+Ld#^dyUh`{uk2WML^S$$kmnkQlyeiN+c zdy#ZZHJ1Y{F26P{-cGSUlG??(UT;_}R|T&gO=%%iFx1BKNlAJ0-6XD(omI?^rDWG( znl-t5Fy;9$XuM=}^Z8I?l3b3U(W1?w|C%p*rWQC6Asr|9a9+C1L^TaM($wG@?vP*} zeQCk3!ldVDJurV#=RRvv;W%EX3JY-VSxDfwa8B~HiP(YT%DN4pE2AO(_u70cqrQFp0PP;uSnwHrNu+Cj83Czdtv#v=!Jc%j>Bz@ z29M~P0(Gp}#zJhm$|1w3U-xGLb;1*dAXTxM@5Z>MHOUEik2bbfgatQ}l0J;#Lypk1)M17A^31NHh^~)+;&;qP!lP{nZwN_f~tRMma0_ zv`U{&Gh%9>ga;?OA^BMgFc+oDMfFiM(TQBjGz zTS+z>rGW;BqZSL8y-|tSnd1EXOLQh{L6tz^oukgnlI}(Z7=E=>r5ADye;qA_tRBe$S3}`eRpiR48A+9c9yYFJp=vGU* zhvKR}82A@DNz7b#BUphA9hjOJlvZ51>W*6mXSWiIauCODiaT$J4K)_#3ay+sh%oId zh-aEDwCY$16A!IoM}Vbw*RCGk4(yh?altP+39~ID5UDwGWQ1v!EN;uW2{T8eqn<@@ zezKyX;o0;tI@g@zYM8ldN7U8G-g`T0dvEVLmMbdsao;JbQD}#8(`lLeSa`?vQLFn?(*Zx)oRAsFfNc+O2D!r#taR4&akEXdTCUHFjVT%hOj+ zbI#S4DU1dvT+3gV*O>^kE14MKdcILjKVdP8x1?g!Ia{s8-0U4;+lA|Su|ucfwzn?j z=CX@?-0t+|2Awy>u@Z{^9L$+3{o-5ie6v@&7N;zyH6llSbQ0KL_;j1jVY|4+LW5kA zlkmIK!{@^CafL8N1sSbYUxbt?wSCTPr(12|EC|USixuI$fL-tH`XErSIUCb8>M-+; zJX{EQa^VLbd3?P1WTle2^pK3=vq>IXO1Mc8vMvz=#i9$j0E?7nF8Znt#FOW-)H472 zy_cL&=b2v<%6?HT*91LKm&H?{QBwUG)Vp?m_7(k>yMQJtQ!_z2u`!Ty%U`JY_-2ay=Wgao1r?B;A*>7^kRy{Ng&@qs)!NvrbbTa~y zk$l!|-Fovg1!unQ;^dku_u*C^V3+d4FO^5Aa}@2uWR}2my%oWvXO4YmXfb@jw*PH! zVih&s3*yqC-}lxiAES&<+olHBt~7LZv_|YZ;B7vcdcakqF#~>l+m;AbqvxX=&jgNKHqq#_CSRvDA#TNwx)?!Anupm zf}dw&eyjPfT?y;iy~a3256-@GZS3Uc&jbg#m=5@?a-$sgXOj_{6YX28i)gZwhB!mr zd{vN<+M_tg*0W%W<*eElS7UqQautf(J9rsx8#A8nkNX^rHPe|zQa&Du2Z-KXiHkfJ z19f%MW9)b@1IhKmUq2`NZJ*#0aT_Gfs2$KF=7Vq_HgIbs7?)`B{kGS!|`p5P4WBHVI`F zEqQ4w9qv6c=ctJ>%`#L!Pjyx>l2IG)HYuadOaPw?)?;}04%7b?w>=8ErbU(`yy)Hj z)bXW};MJz+4oi4fW>-h`UF)>{TeUnoj^8n5e3nH)rI?dL>F=qN$L?F{rb?Z^Tz8a3 z(uLIBpP%nu=bywIDwz-czHs}!WcILzsyTJO_3%~tcRs&{w3|8JREIn$c6M+HG?sn_ zV8>F-R~!|Lc4Fj-dNV3fU4DSTOtO+CJYJP|@EG-3W$GSrEJ`)Vhvwhj5}C<&Ovtar z@TFx`xlvTICCpQ|J)>?&TcV=)U*%}~VPJfJ2%r#r#}e>h+u|U(4>79448>!UrM@Sr z1=$svZwdYw67Ae$=5m^>z=C@a_%Dq`%i6rF$m+Gg-tFKmM zGsX+Af2O&E*EJiPdJEzeeCPe=+_#QssApSaD>W!F7(Qfh)3|7}jj>%E(-6Nb{*_Ns zVNLW-Nat=;`mcE`6C2q`f^LC~JaFy-K)0iJ;C5XW_8$ieiQUlFS}v8+GL)IKe^~}G zGt8$3Bf8{%+94E3Tyq{p*3hlXo~BYd)jJt0-`5JBj_5cAG@mXC-8B_$^1VVUo%{}T zmc<{E_`dGC1H8usu!gF%4kug|zgca%CMTcgO+Z45GMC6_M%yGizkN=2JkOf*%KZ9R z^hy=~Ge|`8m-{c&ON(1R^B*?ifzL3xS->ICO53rxDm}?Sq3zHDeQ`!W-->3d=u&WH zp=E8QBtV=JmlYTo(o1G^8X$J}`>JX_ zo+%=g1bp$6MRTfo#7|-;cK-$x=sD*wMYZ|nZW;fps;pXz+*h=9t4rd~&vjSbqb${= zIGi>3ske*73)Gr+Lzx;Ou~Q6~h(-cc_<%b!N1rH6lZT#UFcQ02(dbzAr<*Z#r7@Wb z>oqggJE=y{n*BRdSX$Sl7-`wFm(x~iZ!S{#Kjq-0u5iSt1ln!Q7WJJU;w$G%N*%l1 z1MT>!5+1MGXD8TxSk07r3nChp5pb9(cK{zn+GMP(_Opcl-8?NAZ}fz;z~auJ`X$tR zKGj7Xy044=JX2-RMpd8XM6Hl1m{L0~EYLFi>z&d4oFF!j3?#`@R2oxOg~L`$G_i2y_bv|)?3r^;*Yh= ze#*A=mzSs&nYp4&8gh8wUmmi4h@~b$eDakna|Deo==(cqg%k6|BBBwRxDxP7nrKD~ zBKzAcXvRjmtRJ$z|EmIj27mJ769xXcGe1vU)CHgXuLZ6pW z=MW}-gk&wOY5a@?PZ&*DJHEg+3N3Qc`FXMbp#UD|{b^W}`I!rqvNBg_cG<>GtNymW zW(fbROzuB>U?AdudSHmyhFs7qc|ZEE=l(R%Df-plLq|G)k3fD`7gZ+OmEzC)aZ3Wz1n zw<*oXmZzJKr|_s>=rzk@9<%a%$q=y>R^ z!QtUz%_mvaRXUsHcQ8d{-P&Y(ADyxK)$Rk~LnTlc=~muV!k&Y>2xQ@e@cu{nd+O%o zlMda!(yR{SPRZxW3k=@tQi6^Ly+6t{W3UiVCv10{p_ZA{GW-r$H7#&|O_2Oq*{ws_)=Z zF3~%tpfk%h37m2@CXR14e&_&T9D4_IB3iS&1Reh{Gef)l3RMU>-^04J7WUcq4qMJ-!K(l*M zWT4%GGO_U_UEnOrzq-!pa7d+|NYjNy#_iGP*2YY7rzP#y{qPg3&Burz{v|l_Ws0>1 zuJ3?Ak3^15=8SXXx%4G}eq1@_w=`@F62q!D_h;oR+%(=e_&Bn(e0(WeTY~DxFinNS zl^ww9cBMg)TAet&>dSnU3T-yh2d7?A(I4<-=IbGI{Qn&b&?eqdS)^Pk%?Q)s%CjpX zax=YNBykMDl_#AHd##|f(}NuvEdn4t#}o96(=iz9D5@fFKZx}#alW`+#Tic+(ypo; z8$mXYj={u8yTK^hUg8!ZLp!-k)bbLJ;#8tgDj>S0J_xka9>}M_pK8@1L{LSI{&?l& zv2r0CmaEMM(G5atOnx0vrq*l$Jl|%L)|nX-d%mjoyx3t-&~GP4DDpS$C`Kf z6$g@s8|SjNYPc^3lKK6^hQCs@$7&l(op$n=TC6r9k(^7-UxMXn+rU_l{G-82{SysF zCjGfcDopPiKdG^{w4>2<>w@qt_2S=JyJWoqC*##LG5=Skw(EFsJJ=*<=Z?gBT#nHSyVy&%5tQ#M5d?sAYiW&pDiFS{k z+_Nv6bTJ0LnPm1sMt*Y&spAwl;Ikt*QLH zs$5TB7QpR|JmL^QsEI*8X-{zlvWbI=icVF>V^eaX6y(9?&vk@IZL;JJJu?q);Ghb8 z!AZjIk(Iq&?|)t$Rpxyu0=b>;vGGCySJKG!v-qs5nYv_9{32?*75l;O9V#aq?*wla zZCKmd@KBb7)7oZIw`*Vde*$~vJUH*VY;&a?n1!0VAel)a_0(Y>XG4oMrrWoluO0y$ zt>5x{pwPKm4MeaB4+!vZ?>uznjEuvd|7c9X&$LjOR5YEJ`2w9xfpnVNko%pG+Q{b! zUud-m9DE;7M_zLd@x{v2g1*!0WW+x& z#wGtI)i6uAbkVFUvZLS6{my+}E0H=~e(fUz^OAv0vQ7jecFH*}hna1zR4ws~iHaTiwgx6I9DuVKRWwoS%Ou{1}I2F%>!3 z|50V9!eh`c7!jVD41T+LWSNnRc zKh897O3aRRv{ba%D$Z8V8v!AvRGm9YO?5IFb}M!B%8H2<;aD$1T6}0*0IAnBTI0=V zU%Gk)I8I~WIR_61mhZ|rr1kX@%GSKnT@f3KT-TqcyW#{+_}v=x zyT68RyRo6i`v4OkDQGD>5Ey}~tJkx8FQ$DaIhVn|BDZ7$epLKx8@l%mWqUnc(`RSl z+K1c9F`2R?2ZMqfc>}ygK};$B40o(0>H|p__Np_llDn*wuaNl^ISwt>>rTJJD-l%8 zmtyp;YWG4jN&F!#ky7*@IrufouZCK|u+QIbJ_@?7L9-@<`# zmyU*GU+4KMgteQFv6V5*oyp#-%TP80`8uGNu#YWP}SCTIQ1rq012Ojm0Ey9#6o+#-a70&} zpdNHiLn)su5XZMCWEty7hFh4h^Hn-MFb&ng>R@(DD0x@_r;arIGp1}t^eaFmtyCa~ zr9O?r?(FOsrKLJ^Qrhn_vO7b|bPlC?yqH(>-+|9R(DS%E1i$vmbb4_(n~`C%uXpP6 z09eXDI;nbecuS)D7#7nY(lcFqytGA;o*^<1gU0_-qc?25!*u?wf*?%%G*9zAC6`>-+2 z;f9nbG8lO9@ff*~1^NkDNq(3dN}$h2a?pI`71Z) z70?Th=(^6K_v4RJ9K)+dB==nrYxECrhve2m^n;vsp8O@%O@cn-pYhCyH?|Wb*o*2# z0^)Z$4LrWQUTPowbS2fw?Lm>Bp?EQbg7i*_pYZE|CfIANBtzO}P;jSe+@pV~XWSUc z(XiGkA6LHMla6!hRdd+c#gwbA=>^+~gJu;hZF(*o1HxqSY&kwUu-T~pk>gtEhHFr& za-;1{oA5!(J76nR{d}8se1?p)=kc9Z=N3iV?ypM|MZp~8yNhiK`%Y}$lI`sW&->67 z!dj$*j_nF~&}6adyYnKPeDw-$J;)(5_p$m=l;AH;GIy)x5uf@MxjevycvPP{lYabk z>m9vvF1v!qYoiB$7N6WiUQ{XcZ1bhQ>2hU%(GvH;xT?3N`%b@uG|g&V<~nTZnN236 z!z>M0BA%5XNSAr=w;j7@NeBqx8w)wE-6H8LGDuCtd*$OXC|uDBxf!`!!u3ay$pvwYeGU$_=`YJOBT)!#TX`spqoxd2rIvy#Fbe3MZMTHiiRtb6G-MPfa zE=;^ba;_rjTBEz#8Whk`^HJ5+nUSF~?_&g}*ZA_%xE^AbD6X~KzpVs!GD^{+mmhAy500O#$C7>C9WnLX zdfZOE(pOGaWV_6>91BRHBcYiDahx=~S)b+%wLg*1?2H<}&hM?m)=rvDj>P{#11(Jn zC*t~Mr`EnvjlP<#*;Fynber3->%G(4`Y82sMmMvYrT|-u-ILu|7?PpI3!UAj+~&I& zk$siUm4M!{EZ;xHE`W|ymLhybWaPf|*&`!=#d<02R@N+nq!Vc^KF1wI>NG%RICa92 za(OIwdB8~~Od_=wnqnKk(GDs(Hh1XWy27cLO3gfy!vG&St`dQ1$~M84j>NLm6!tQN z8P0^344AV(C~3Fkn#6e4GvS9zZYvOPvW^jRCU@+F+DGL&1u4i!TDBZ#)D&UEXG(gr ze!VgrZgslV6)V!l9k7&WI}hGl9*p&TNlY!Lcoym-roB zJsarnZaZ_lPVY5sh7u%4BOl#=Cze_2@BG|&BXb45=xVcW+Kc%T?sbeR%1}_ULemul zcYb6Dr1#-K>=5vaBW;W_m+~I429#3}4k|#5Of9C{S)5HSmb~L3gsAGq+|w5~d~{wUuMB zK*%Y?F$ZmKt{M7*#S`ff)%x6SeF78R5o|@TwZ~cMb7g?&!X|P12_zG|Fotdc_pSCg z%KhO|?X~|r?MK$z*y^a)J57OiyjRD=d|dsr!7pFPt>#00Wy&j^_)c1V*hbHTeSP6i z0CKgpnVX65_EX0*b~rC>x4K*GcQV#cC+_wbTBmDG%(CsUryvWyAES_TZ(d^+Pd3w- z9(#Y4+3YZqn?j_1W^<38<&~)z**t2IOh-O2uVe0YW5XwY<9-(e4yN(y>0EyEC1M0|W5M^@7^56DM8gZsKIW z^l?FV!i6&9wM8MBuXHCJPq3Zdiz4iQS=fwgJUkQQP~uO|ov_#`(r6Fsp#G< zj}tX~$<-E^HqNTVOGqR8Gc?4W!`&9EXw{uW;k<9YUcS9>ZmMW~_%e+%U52Uo7t0NP zcv@q!a#LAjsr8p{k_-G?;tt2@@6+92io7XAmBJbE^Y!=S6q?5s`V+<~xfAs3ZRJfG@B8jG%0pN% z&gNeL^?#&T90ionG+zmjlas>!sacS{Tz!FeMcUog5|o`sNH&BxEm_cpSq@9F(7p^O zkwq(7TkKz*0%U|x*sd>Qcz3RFV!QbsC-hM7qP@T1>A@bUam=PBX>-|sAcD)$<7~Qq z$6ApA_aXd}%jfM$8Okf~3&lmAl-}->_8xcBXLt{9v%;kbxk~ZoR~PVnl?_WZm}GBj zv+jT&;G;cuWdGgS*ClG{A__NI(*cHVz8G=c{XHL2I^;;i%)xmpfloNhfE|HvPI1D%x z^WTH&CVa_jlCyjkq`%*(+1aWltdJUG4h_~MsQ8n|F#3>G=+}BY zH@K@KtLJ2Byuor=fZh<2dk5DRo&4>{>cdB*yZ$hdhY+1>T6tb9BhT+C7&&jhI`9;% zsd<;gH6A=5_gd}DH%s^xE<=u!(zzg}nZSL5AhcHBIq1q)c>DH2XJ>~KS3Ukr0>7ju zP+pP(QJiv}fFIK71wPDFieFW6hoax;_P_|aLt?!MHq+zuf}Xe`)oPO$u|vx3;$L@{ zQ$}Rgpo;60E4wS~WO9=2KO6Z@*sq6qHTYd~&)2Ow30Os&YTOMUZOk5V1R5PV%-Dfl zlwEZC{itlqeFY$we0?zMrG-k!%6Vh3Y9n%iqI3{T*`NxHEpM=E8~#FD7ix|oM~9Q` z(QoZ;vYhk)nlVt<12fz#UvbL?JSR?yRC~f}_`|t9gMnP<(UC+GBFPV3$n86G?!T1n_!}1L=ujkXbAv`Ec#)3ny*9V;#`w zt@D*Uaje-CHJRfGyIrf%j~JKD?0pqB3KBdHUz&g&StsZ*GsiP-;fJk8T>K123h%LF zB96_d*mD7uXkYSy4=dKer#CV}?&p!S(^=DrADt%$QmRAAikQh2W#(y=vufA3^(IbD z?e4eeVpEq#`Ea`h`Z%COU~fwF<<|IVeKva4RF^qGUrC8}B@^<1L(0 z$dxp8z@Dqq@7WWksbWbPRZ1f5%icGudT(+~mippf+Z!(a^o}quk>Y>-6f_Y_ZJLL{ z7p7V0Fi4inv%V&nj`^M!sYw-8t;R@=wKbc_=VT?Mlp$y2E=0ZY7MB*!=UXTG>+OKK z4kNWnPAiwg@#hVC3J2^0MvgfTqi-ILUnqL~7S1HOqNwt&4zi%;xeJ4x6av>zGvKT? z#ecSJ1}w)46e$)Ct~IMVBpLeNP7=KGcIZ2P9&!bfKTuU%VZm)hU&nH~yP*!9Yl}iM zARTXE^X|HLqjZPC&D)n_KT2bgevvB47Y;(vwo8Z`E(X4#2)aT&HbR;PG_#Qt_IW^C zSf2C`$};rh2yAUqi*YxnzYb0~c6u4|rOuUq*r26mrZ73G#`jRtVGwX+n$xkEt3``L zVrTd^n?X%=faeZ1mVZne%O4W(aR;_FOaAb9e+9jyEh#~AZ1^|SVRGWr{|f~u@M!{} z^`T*B`E3=Fv2aryVxh8g^s48H(8>7XXy>Z=(SO47V3Zg2kp#wJL)CUnwJ9wdIxuPb z&gkKM{cX_bK<@&ZUN3_Typ&u>Y$V&$b^tHT)D;Cr&gpsGxq97RV}}EeAfnZ@ydt5hVUi|&@uB{ZNk*#W^HUVz9}8f~^hAMw@XbjTN{SZLzbQF>J%93n ze{iPjLOQY6BTuhT-@+vGV0EV^NqEXn_(RrfF(<;<$w`&L|4=|0zq6G~5;+OpRFTs7 zG1eviQ_(9Vwf|k2iGTLM*8l1O)7RV>q{8yfPelvBXff$0M()q_`@b-%4+t-q$s7@i zppV{GLZ=jLH-hU`OSY{1X-GPCo9zm11ZSN`oYG^*{?tcdHx@FBwH=4hu)h#vYLZ4@ z8hZor1f!BIMMYY32iEf)Hqnw&G)tdB=-H4@B9>4-*z|Pps7STs5}~!u5X7I@zMSGe z=wAHg0%UTyeK_B6^NZe|9YLUNAhtU*BCHms*nDd{YSjK{$#>S>sAhBgX&*Ey5#nfI zd}hECdVb`sFqoAtT9l;epq!LdoqXb>)miGkR{eHGdA$%S{F5M%Qan_DD4%6PKLXY} z%1`vp!Q&2f_qi8$NbRq-Mj?Jdz?Ql)kp2we);D$|KCeojRuBI*earpcZ&EC>d6*>B({EhfgQ@_QMcPYuw=g; z!FuwmY(57$0?|g{5fQ^?NkDCV)`^dcCvKH!Q~>ZucBLq@d^bHG6;67^H6h5tSEi6t z0V4Acy=KV4m?6Y7>IXTw+1ziUe?)rkM9Q`Trk#7;5xpT$S08qMrFO$^&>$yGjF~6!qW#UM}3Sh`rhsz(7P*% zq;Utb2Mp-qv0D!Ga#kfu`b|H}*AU7uxM>~FwMe`G67+Yl9t>G>4Xc#D7lut^$=*WO zx3;L?-Gz-2U5dUG80GIMq~k zI=o>etM$ogJ4b{lU~4k-5*GMcqjGOH7I9`+we{0W_ltbhAEM8jSNKD-T&xO+&3h-e zd#G?NRtnkERz1JcncFVxEe6bByWOVnQFB>|O~w1-4%a$CB7mdVLWF7+PAaMwJ9+Oz zhB){5zMY}glw*QpkWzQ3lp@mZlxESnH(iB2ZXI;y7$tJ1A8-V!->ukthuP1XMj(;> zytzyIo~dNt5iQ`u9}ygko+~qSwgRs$)j*CcC>YrUiv~D+YAJDquXeKmTMzv1H}{;} zSPUtbvzG5iU5xdak%y&)5^rDtoXsQI|0>gahG7i(TI6nb$UeklJ?x$l78~FGbq05G zpw4!$XWxnJGbxuN+}AvM5RuEk&L{th_u zTH`0x=Qt7h9JcTA$2?8mZRQjt@ziWIGwAmJdgR?bK^;LkNa7zf<_; zV_^KBAh44oosBSpi6TCHw8xAGx`raqT3GGgl1zAO2fkY2oLOJ-B zo7LNdCc_|8x~c}{)#yLou@4+ijhwas|0#k1|Kjmviv6Z5+u5&Ei5^F;&3HnT9;jOY zm5d3+qX_r4hRmzIJ zhml&BI(BBstuCfjBm1v%?Larxc*SgREIMAFi)T7EcNL*v6#-i2f^}ny!6xt4=1} zqt}^pkZ4#?MDibKjv-|kEt>gcXgISqVvq4e#&xJA~(jnf$NhmHj!c?Yf(8(sDs|Ep8>-#5oRJ_2FnPT=BG{8IK z*}@9zz74n+XZqKnMaqqzDXRgr=l4jc^NqSJEm0Xv z&_HG(?AFbyTm!ds`Wx_9?zvKrqd>K}}Ln%XaTs1}sGQd6XqI&_8MLAFtEbUR}I z0Wdj{kfD}4a5+9LW45)@i|nsb+gHCL`?)Fe(lR3|Yt1bvgvrNre#%%|V_%QeRugVOtX+`8|H@j6Xk5>6v!Qhc z%B;ws8BYmIuBF-hVw;tupLRpsSo?bHKBFh`d}`d9!k()%3FYLWX{%B+q6S6W2a@Sd z;K_SKFX95$1_(uV-YC-f%nAP(sZL%4f+N;|x;;aea7IL0?G~8BJU!@FRmo1@UNE~~ zP?qAz(YQLW^Tj#F@c3ZLYS>DH}Z|2N+b_EAcn9v#$r z&oN%FbRUOG+!YDr+n=oUVbV!9zTsR~eS}|CL2%#mdndB?hlB zY95unfw)_*`Wz8tdfamzA6;-O2?J@^A{qnC5X3wMK|U>$7%|dcG2qW^-KTCnX3N8{ zhceQ(FfbUUTZBQXR)@oa&Qi~Yg~L>=f6{OcphQbo>V>>Gn5`Cm{oOALF}=HBylSK8 zwRcmCKFg#-zt%M*;9;|u>{_M2y=p^ie?0lD*Nv8C@Y7isNOiAQUkU(fb+Dh>7z89w z7rpU>^c5W9M7P^egw6Iatkts}G0|bJ{YWi3)&j#v>8cn|rt&HbEo<9+uTubfbyuOAh?|(J9b>QM-OqV%ej1lpM9bv$=bYH;GF>rWJhAtdMiZ0wq z!j`2pb-;LJpq+9aA0d8cc}>i%oY=Y~mHWU6CYls0iDv_R3kYRIIMAvUCXeUfctG7M z_j!ju>y_y@-tqEo@zibnrA=EGMw7!fB@Uo}F#=xvpOD>37Ywp{zdaIV$g$aI3RqwJ zj5(Avj0zZ8Ke&6Rli9d=fjaBcJ$I2utzII%U`%cpr&Y$r7G!RQO6b3aQ<; z58C#bi$!V7{!~*cfkeN&!5LF2_d3w^yy~?8>96mm5bH~;iQt%qwJsw4)f~-gu`@Md zlR{{Nv-z4c=lsXtiu#?r8S z@L637zDCdV_~w7a|M3md-(cq=tGFLthGn8X2bqWq8Ck_Lro1ks6C*P@@dJdT`A;Z* zm-+t+#a}%r|2$aR_&dC{Jmd0(<|>bWZ<8X(-*KphDmPVrv%V;fFm3qa=9Rf&9~2l! zjaTp`%0*rFTdmEY!-i)v7Qso-P7PcF`>)aIeUKG1#S#V^W*fd{%Ga;WN;|d;^fkR@xu8|n^gI{ zFA(wWYXFyD~N=1?UKN);46YjoKKd--V^zc!t~d@o+Aac3ECx zGzUeiJ%bGH^sej3iFRvr8C8f}8lnNfPHsKTz!7=)=*1qCU;wqM-wsN(rU8WB(D=ZR;9`lRbM{J?#8l zjR!4uzxPn>-XVi(-8e_?m?U8}Q#${5Xmj~Wr*;+#oGI0EvmTeLP^@1F7owZU4qD+! z!DSL}pw;;H0=`;*94!eH+hS)T59(Z=YDbw``*!dTwua|ta3pH(y=FxR^JJ%<4;{-e$w}%W5j}>y3_nS*UY?Z?=?O|vk9jc7g zXMq4VW(E5B`-|$E6E)RqlyAKabT@vmfRlPUmdcEQ<{y1dt=TMhnxiJm#UGr~&T*r> zPZ8UOXyD%MD7mGA`dIV4YU|VIn&@TrV`4=gamOY z`Zg@72!u=#G?tvU>`l+HbQ+@fuxU?wOi8rTIRi9XaF-TKI5s^q_kpxL@&-y1{1tl( z?Jug=gh6f9fExbH#*2iC^)O8P&(O8@jhi`<&4tLo!6`R5 zbbWrmYo&)c-Ik28xTBZfO|QH4E`AZeym>Q}QE{~EJw2Q}oK(vb_j!Y1di4G@`fF*r zg9GVCx7j;KmGr4$(&tLKzbK6V|I=OhFuBO~yu9MMw~-<+xyU`g=wJDP2Kfwa0h1KS zUvu#-Ly;$An!rGTVkU(x%lmoF^6+8mLKHigTlxjHpNGRQ3+<8p`uy1Iv<{ws4wKZ} z;D8B+XeKzo62n0yyQM1Twl~`94wr7!*T!M_!;9^aih)ZhgnU*ZspDud9So)lax%`3 z7R`t+v?p;Cr5Et?3)yZoJ)@iyR@^Y&?+3h41=r$e7P%Jb0ft?iN_9Sxm2yob?K&+b zY5cU=ove9B2wuU(J+9YE6LHt!Q-j58YhI~0MTSk4r(|bf2k(dFAAvm-h7#rg>bi$b4rfj0-)?)F@2kw4H`e+Dod zmyb#EnN+50`t7v~W+VvM`!ZiU@;i>PVnQScpUMo@;j4{cpi_35WOw7ngKK#Y7`3=x z(L)R{m#OM{yFiSi3uyK2?uLJhCqv=Xo6 zJ%K27Bs>7y+UB)b98WDI#RXH=7+rWv4)rm2^`aA#nLW?4RG%}j7rlGwMNOkFJ!+BQ3ld-|DH{|IY1jGp$OY4T_eHs&|FVJ%BXJ(0xO&4eIa>_PMUk$$!- z-qGv=iQEtB$xCD-j`MltM^JP z4-OnQi$1%JvCMbsl}?dc3~eQ0DGnv_DeqH!1PcS`Y}vi+4msH6vD*!lB!gr+Qmzur z&h7i^1}H&WnY3`} z7+K^g%O-WHH3o1{*(atg+$jbJj`ybwGw)`dFYUco)4ydrs-!TrYg$;~T*tObt{tN+ zB~j-(ntnb;cBPuuCp%He+r$p$FQIOyj#{Cu>6%^G~L$#|VC5qp%# z#P>&&A{GmaBi!hbZUmlDbzbh?w84d>`e1Le0oh6CqRh8LB2rqc>3~P2LU-FOLb`&4 zOKVN9G?ZYhb|op8Vy2Bv)E44{0IU%z-}gP~EDp9p7QGm*>^pz;Mqpp= zT~pt2c}b#qLm5Y`RX%0D*S10W;c4Hce>h%BSdmKqvt4tle{?2Bm*q%LMu7+v1JTRA zF+0}OOGF|J)e+GV!`D+S$RR5ppVH_0;zXtG>YeSUcFlOk>JsJIgOhD`bTABF^iasG z*FB4+7Q-wPnMe-^dMSjRTgtkyOhw8o|3qGOm_n;7kN;uNtAe|`kMK9XE`$OeB|uVs zeG==VkF|Z<+m3gxffW#Kd43h^z}|FFZW*S1q9d9xTM!9$bkf?%g#nKZk1ekge^G#jaX~D37+hLt!_%uyHy%05U>R}< zR3T&b2QvuHTpQhn_msTqZK2CXU2jR@%(jmn3Jo$;G^^Uq;;kO5GOXN4)aJXc_|qEV z+6i>jUVWC7e7X+=sna!nfQbV~Nec1q#tvGlI;MHjs4lh2)>HAX3m|H@*E^=oA4w|N z);vEZ=)I$HEM1m@I zZX&s}cV1Cw|6_3!t=%u&AU~1YWybvurtV9Xq}b+~GbZo$&kf7_=u;079Mi&VFwKJz z99-P1B%eiC`hWGAQVpmJCIGP3;r;LWq%~4nTJs9fp!h!`&$o2!V7sOym*eFUx-75r z_L=9$MG9%$CHgHc3oD4Em;x?`zY>@aB#=SPb9xT9ayZl)pcorTjqe( zVc-}KmO4u4Nukyn|A2tn7KGoK$Y^L9uu9gnpb1jKC}O)elJ(OFzDOB-Eku7;^3QLg z!=G3f{`}$8_w&#(;-9O3{W^xp4A- zC0K>w+{ph^0Za9^!^e2Oo<{wVBnvCgNFAQA;y$QG$epMp@~Z#M=f9D1&O)cF5sd+&I*+rRI><7|7D;@g4RZEcFvh>;pC zrB)CTBZR7*7!`YW(o%cxJ(3``iPctBiA|(-)s9socDQqXulu_1`?^lof4^V;@$nGJ z=Qxt%INsy=e!nDq=3P|u7c1}E4xPOBnscClS4NXq)W{k&nAH><9+ z4|U@D8RyPVt4{`jUxhOpei;~4DYMHs<{Ww=aT<0OUh8Fv<$j+% z@;ube8+7mibrI!FYbMr!EvVGsJ{c;KG{a1wg!RB{vYm>~4Z)Ej^emT}n+#N(j~`(} zp)o^BrM65e#q{1`;$=Zkc-G$$c5cr;E15dkXKiO=gwsXqUOk*@<>m=?2e#N(r_tn3 z4>~qn3uqeI6FkSQ|D0Hw38R7788O(3F30R2r~6|IS12|&qWd5ujpkcG|AH2$DqXn8 zbYyi|?%Xi$E*rWAGKa{Mtx>8DZle=BT4PW$YgeG6ciUhU$4sM&*~a5VC!LGaZ=+m0 zJFV<6M=Rfg@N&O;vq^S;3!K_F*FC(*qJmRg))*h%>2TO^I#3Vei@(P!-sO4=lojlg z?H`z;aAHw*9d0#J0CKP`Gq8Ny7D9Tv>Pkl&fuz7064N1o7>{bPV-g_7(~x@KHAUH4`J|p?W+L2Y;}P+3pF2tS(p3W2HQ zHnJyl7IU^JB;Y)iytq!wdJEWA5h@ihx8|J>-R;&J5*68+ zLr~xDRPu6KtR%~m%@TcL`Kp>kS>n_M4&+u!iUUUw2VHiDLAuP7w@;9yfkfJ}nlur6 zAOmKM=R0!h*%)~!@x~HbQN%SY_f>7N#j513&De5CtZ0pws*9gi<(hd>XH}c6Fv&=) z@fKLG7z;!)8Rqa?jz6gxsEY4JYtBZIr^V{Jll2iBPBeK@+aQx?A?Z0IJ>STJPh!~r z@G%i3RUNvwTQDFS)B_fr2aC%t(3m z^~6|6bA59rHLT^rD)F1Gqy!^fZ+vk2w5g@L=$(VdKM(>_=Ktb z59N5bkILh08OJ=N1qV0jbLW1#ou!(?Z6+u1n@vt&%s!=?HQ;HIGAvMoaqkdg*sB$_ zJ?*$(Lcv=!)g=WTWs#3k`PkSgYv+h=42%*EnA*fWt@;)=@p&rSh?||%YIZ|uxA;*~rM!jo+ z{l<3{>%`xdx(08RBNelZMLQnG_|y#TzR@VNDx-;u(=d)Na)CU`jiP zF1_$;Ho)ePQ9&enfI!)DdW$oQ`u-eV&9PNwJ7`1R7&f%XoXSK||JDSB63A*b_J=nz zU5_g1QVLTjHUQ7h*>r!V7WPPIfh{BW;KYd8w35w6w`HQlm?LOIRf?k%nYOKzFXzyb zD3Bmlq;TO>JMiO!L8p;|Bw+r$89E?zIJHub35)vHF8&z zfnyhQc`rok)CmkN#O{&OBBn61bN_bmxoaP%=fR;z^Di;;cKQm_;v2x%!&rP(-iXA= z;r9X=Bs=Pd%QAxImXAU%V0LwPN1cs{SDgwKf#r7ebt|y0m8(ar$W8I|3+Z(xTv(9o zIMfAJug#hvf`;1gsAnjm;|2A}b8J;2!$QJ@n(1l}6N{}h?=Zg3=e8yDzrp1ey_MO2 z4v{$YMRtoUU6ti#mgvL|_`wRWYX%#ra#FN3il!#FMhnW_Ij8mbk+X}%p!9lw}?u_?y^dX|HC1MK&f&yT%$@(7V~`gzhB*s=s@mii@4{g-RVxx)sz zbn5>7x3{huHJFTu48~Ha$J8}U3y+z)ADzrdL36G1%Efw)voxrl7#}{2;^PHhG0`W^ zbwU6(y@oCdzYI3*gJdK<(^aoPW74gMI@LN7Z99umg&r2!H=JqO5)ko3;hRDpUnIE{ zQ*VfLRqLhsOAX>;?LDvqkNR%Komf<8j@vM>X~gY{!7)lv7wFavAg;6~^}%`_dSAOV z_aEViB4vh!+J(-A#Ghr^iMAHtul(j|{`iJ0VH~ho(vTr=*KtcaamP2G+aGy?!^fml zkT@2{qPRw`Hpai|N=yPw`m->LnQOahBt&sX#V8T*0tZ(P39Ii05|xAx-^7YN^;#`N>DB8(HL(2(0y)-dd) zt}1YJvt~I_6}5*c^4T5R2=MWVr}jT4?$&lS_J#rDh=qKvL;Z2wsJ>}9_St%ne$+d) zv5=W?Js$a@lz@ZHxN7Ld2>Y&ny;=mKcTnWC`fyxVCUr??~`SS**o@i*_Re>G;h1uC483KQSYXkg;3c`v9Eqk zO{bq|H%cJfBu`X)C~B_Krmu^FOkO^!aqN7Ao_nff&R?SvuWR2q2Y#ZavXbA`%f?zE zlUeMf;eAV{96UQnS$~59%X5MpAw~u(Fxf*1%L=Ef+Mr6)`%;}TZLwQ% zvzYR)^0r&QV~Bj636P!uFN2rRD$1y-p!%_+$y>0JQ4c6CgVwlQ^~AdN-N%ZIj{O#6h_$oLqu30o|Tlm29Yn+h}CyT-pI? zxJUPdEKdz!R``WM=^syS90YuFw-_25G0NW16)`??QX2nZGSE2UG@mhpI51C;T?;e; zOjI>$DLST{;Z;7*RKFC?5?4iQwEBZ1RrxmgPtugq462^RxT3?A5ot$jiGQC>OIx#B z#1aASjOxQ+kZ)-EGFa*9zM(uD7U=pgxDYaAuyBs~yIbN72}0o#1Tk2k6}l!2{k~0V z){Gm)rep;>y-Hd=1`)0pCs9MP5v!|hUCzG?3JqfDXc8lp0nz1!<2FOFlSjAQwx9+v zrwAa=l&=r*(DX}1EOg(pRa~KkYV>uIuh~g%0`1(4hlV#slbmp;Po=M* zq0jvk_}2`V!fh%iJ#}9No7HL;Ukd@an456#%>&_yb*g~GUZ;j)uhr{|UZ3qXHJXCc z4_}UGD7XR_#`fZO21c+_dzLr%jy}@8hYT5~WBIqEXt?lg@-t;FgfqBPUrH4~j$AEr$vQ~KRqrv|g z2t!=URe$Msfu@++zutV+jN2}_vpz0Ye#qY7G$swQOLZvr<$AWLM3)CKbr zI6QhBm;BL+{)v|fAe8i)Gy30vXd^TBj|z~ z2N&lS*MxBy2bBGxW`NxjTl~iDj&^$d(sSbjdr*Shv-iqr9`~smpWKZjlrxGU!TRXs zcyW|PxWOFd(lxln1B*yeR%lkn)YevKp(=AacKXA#=YhY9)|f(5sbcdAIX~aYMD|v* z!%GdX67-D*>RdWDM?^NrEZbR0&^#@FRnT~)EIA82xuu@)Agr$G7=<;>tQgDk9pd=O zn0l+fAp3BHv3`^4$~X)Gi4sPy=T|x8r>aJ$|JJ?nkATGQ?|8|VeFkXpH7YpBEa2X_HqiC64$z`5=HfQ+kRRUXbd>fN^*a1vX3Om&;K?^87 zYE9|xkX=ewP$MF&N@ZPdV>;k`omwn{63k`O;K&O~h2K@Gy$9sj2iB`CYHOQJJ(9*dunZG>X6 z;sJHus6J8^6FtzoMyTF0RbjaAJsZoU)f$GNXbDf#-^Hv2A5lL1u-fUFI~a@0uS~0R zD!ri0s7_tZedVW%Z}N|UHUF;pMW`MOxtt8q3n+*>zRoMRQJU@l)MBc@I&vJ@bzUyf zY0OxOo(;GQFDat9lx{@dCmz<3zjyF;x@$EWixIyCy&b+&9}hb;yXCX%Q)cx*N6nlk zIoPyJS(vo=uBk+aF#=P^Rn`k;kaYKzZ< z4lJufL9nv^)Yk8F5Ci6MQ_miQwBNWn%i=~LYkKkfCv;e~y31Q#^)ZkbeD_#R;Lx{~ zd|WHB3s);N^$Y#!3r&$xcyFA{@4)Sr2~*KAzgOP5uv*r{k3o|X!0ZFva)eK@HG@yZ zEKMHXoX*1VBNq{kJvwhid`8UMG?v<7G>hoLuXj-ACO&NA#2||ogTdz3c{WDbPV$U+ z{A^raK3Cj{^;TELlh2SZ3A3AZGS(wNF;kEU5_jP0>XQR4C8`I8Y9_y{Sds=P7Xy1#(0EfyV z=hZSNkRqP~x+|w4Eg&CrS%nBm1d0uONfaE$hFni&#%@e;<=Qz=nU4=xddSD7+P}s1 z#!t;bk;O&I&wnzKixj&*Wo)oDD{PBF-Ss>syKu5xD@&BJX{XWfe1AKGiUj=zJ}Nt2 zThK@|NDb3T{L8kr$6rHRsZWDC;X9K+%H}UGDb0h*FlR~Y$XZ`Tt|Z7CssuAPl@=vnwcS-=ch4ENPx2V zDHGK;Ji5Of%g83)X~n)CIn|%1;WWh@gvEdgTVQohoAbt$L{%W6D}P<<41PQm)`ZQh z6_i0x5e&E#MbPL!eeitV3~1qoXV9+2*hWX=>0j@@z8;d<+EznhWgi708YU*&H#P5^ zVe6e->K6Gu2z%S=+1SyD)*L!TXbhcB{krV{W!p=?*I`#NK3BLkDTsvcb=HZ`TUh3M zTMU<&bIrmYG92lH+fM4_3p!;o-=%qPGwNLR%Boh)bgKz0T1=aR0w3EfggSOl%gcQ< zFA?|D*^aA;w9j<&h)5g+l>NFWC;aSZ8QIqB6i!4fn5o+Zjw(cxcQQ+XL2l66lEV;= zT=R*Au&^gj#NMx@Ov2CA{okxRFF35to_1&o%Ih%FgxJ#6W{@mM0+b1WfIrb&)Faz= z-BnJ+qI3L0gQwgdZbo($)AuXf$YW;aZBVgPFU(*i|3IrGJ{7&QSYTBRT+Pr`w;T}d zn~Qap<@d3VBesF!cnizjkG$5r6|QN8s(Gh_YOm?Tz7JHtX7|UD(%K_xTKfzVt2MQM zl&j|o+KR{;xQM3MRq;=HD@F9ga$0)*u&Wv!RFwK`5cR^M^2aWsy=e_0{Sk94ZHtZk zuqZ&q@DmsbLcilKtC(vp3?EqwW5h3xujGqaA(nr^*u2WNxxveZ`Vk*uwQD0Z!?%u6EjlGKA6Qc`XYx>y=?%c+%H|*~mzD++w8~g(nC~ zeIEb6)X#s~35t~;8kI0i=bn=a(vOjvQhpffgiYGO7eHI=`!U6j8Drg&ae_VUvY9}C zL#-&svQ=}is2gmwbb?i))Ae@cZIhiN6C855VE%CVs~ta(PY|1a|9xERWR~Jx+4TfH zjUV$ytqI|b56u$Lk{lhq<^pw%P?BvC0B=4V{vY>i(=NucKg`jDUJNS-HqR223!_5{+U6?fOi z2dk^`;aRyrwu_3a+T??#T&^j=u-z~g1D7ejZ?fk&m9jau&swG^6n$P&JOl?8Q}GvJpj^m!yw zFpC%CqNVPMFRw`Ic-^7=MN*~fLJr`YTao&K4n)*Zv6ox4dClT*?pNLBR>!Ph--@Dz z(rd{9RJq{=$!#vu5#a?E!kFj+co+|BF1U+5!N#mxIUPUH*;&mK?@HV>C4K4KvpIEL z1FaUYi_3ZQubyTzj@|b!HND&-t6 z{GrhRinEPt45RtG*zhQKO({=z0z38AO8!qL`khBQeRKS4>R$Upd({J3UQnIfJIu8| zJZ<;5;Sg&-`1JqdSGRVXNx1vmUaTq5cL4q1Dp_PL9efjd@<)if&fc-o)&E@0|L126 z{94;nn*ct!pVK`B7L;_dR-G^PFS}PQk zV0#uZi7C-7ZXNh)7M2)u=zn}ZNYcHcH&v&^>-p$|3|+E;vu^3N_{P$aVR}#E%|0J6 zze#*XxQ}7<~4qZUcxW+m?Vq%P9&3!s1ATYd}#Q>MC^xfyhSYL}JpkJ8Y>O(75Mj8DWBmej8pB2!IRtqSg>9GilZa!!LRy7ZY&erH z1^&HMqL;nJ&~hwTBZkgz!mc8F$j4#LFvmS#FBC6z1>NyLty*f|CDIM7Gj1+pphfZ+YZ1^5 zdCY21ED?&10vsr|)e{4LXKVH|SxF3DJ-~jhp&b6~VOZWx^B@uFl@P^OgD#$t!l!*V znYiSjw?95!c`e{{oS;5d=~*Ppr$7+Y2SXjxbXaI2(+cLzxVJp}j@=H}n!vHWaDc_! zOuE`jJ1iDucDi!Y6ckLM?2dW)AHRN|R&o5G=V(6MnT6?KUc7)^EDc@Rdca7YQjQOy z_i~FjLAK&c!r}OmO2TwQuX#nM!kyOpq9n&}hY{h@7V~?iW&qCpx0W0*kgH))yeFuI zvNM876p=lF_n1~#RMlz*t7BK*GKC?3Y$whI6+eRV8k^wQ;?kkzP90Ne6Nz<3m*#s+ zr^(`S@&Dc;h3f8K!Y@}{a`&I@!Bq#J*p})4Md%?sIeE!!RHbqCpkQbA<2Zl3ItwB4 za#`YKDfK;>Bh zpF;)0oYnu?Z2t4&_xH+CXBxqA?hbwEX0nIa%T|`7_?C>18ew{FBVRyQy9O$25COM; zt-TFnI}?Jb9AEqU-_O;Dak6>~?-0;q)_;^Z|6XC2Yl%dqRyKwz{yz|s zbG8pWW>{;E=OSoW&vTQrz?10G|ILvI{$GwH`rRsB97kxZnAiEAj~sf>Vq*RtD&JYD z#J~TbcqgN>@%-Oc|K;%_p#6WdE0_L_jhwwU_A-0yX&B78pD)k03Z74ouI>I!z;J8+ z4=*rT>oQK`b$(|3sIYnBUH2l4^UO(>y2kr&T*>^@u&pnj4^Z93f?%ZCu_3hEgFVha=WlZdHq_6c^FuZ#;#;mIG z?z#F#ZgQU^?V~;8hwb>Pc?8oXua%GJ4DRJ4 zvA&~ytTCjeVW?=t)q(itE?8p@d+@puhb0!JP3`dC(x-hn~bXpF0~(6InD$itC!|0QH`P$&Tz#R{bJnQP)`M14a{*F z3m)(D8WwKND&;8+ZGa~}pNR<`mDQ&g-5GrGEv{65g<57lJZY?}f0(+iZQ}bzAqoi_ zPa|(vJ7bpv5<(tqRb6UXuwwPu8s69!@A^=^eltoWJ?pX6*HHt z?YG}*CUfI;f(MezJeG@mEWRiQjWuL`JN1WZe0yy8MZ9^usYQdjfE_zs#!0G!fRzjM zJ=`O@Dq(K@`WwWgj-dKWw3Q%ohB5boMvN9{xH0gbE@8s^TG4edyrqi3=Dwnr%dk#v z{u6S#EMXY1H~HrnyS5&cJuVjZz{{jQDM-rv2^T-nZJwnW(zc?}FD0oBe%~U+5qeFF z`)!s%;v9V^-{Wfq*5U=VuRA(V{GU+Dx$Z>pDfA+PJLvqqJ9R;)uGI*cI&JO2Uf~Uq z`Zuj^`$*+YBF=hhUB5<7ezf$Ad^Gb zkFdk1#UQ}cIF0gW)?vKQ;BU-NHW~i7ob5;{8Kc{5P^mkA?!}Xr2RNpGE`MLohFgr_ zX$S831G4_%=3W6UbnfX)9QSVtW}7E0V>1rAFu^3B>IL7xG-)onX(=u00~y2lXMTx8 z9XiS{-%`Hj0K)Z@_<|eo`{s7EkYYu_U`k$+le7Bw-6Hn;k8zt z6IB84uDsMb4?0An5?5X`i5iA&;9otruAd*;PsWP5%bQLOW z8>{rI>E2*7^qP7pXMroE9NpIKCiB}J8H)bI2v>Ah9q7vK5M^nSME5tm%PLLKDXM=C zf49&a*3B0B`P=Symrs+Q&N@RR9KNrAv^q7@9-LvzBsxA!dA3C~!ix9Iu~Hh1C3uQs z#9E!UzPSz8yo={+jKUpRNSmk&l>|#Gac~Ne_UZ8!GT9T5WN&e7RDKrJk5x;G(D>}G z+5L49@UYrgBRD(cu#wDADwI9WChOdrA4;7{IHK4VnK(?F7D^DTuQ#W-a0SBnYVSWuHiAJ zonI>NpISzkWI)EF{A_8Obj{ForUwa&4Pzp)0`9ht-yoi6F!Te5 zL{a+xw;W3g&NyEKJ5!rGCXdPLl0fFKOY9nvY5|lKK+mIZky#9FF}a+W!2@QfmS2y% zD;lq_EdJ#4q6}q7T;wTD$?m8|BWm(q{>+s_*8zGuRBVAY*{JCyxmnr_BD*_MEx?xc znOAi4r%dGWam)k;WRML*qum6d{&pF_zKv1^C9;rfAChb`o%{B6sFV4WYnlpvCh|Al z-E2jJarnaGV$Cz>iw9}f;JpP=H8Td0PPK;3#Wj%35);7I+ph4GktZ9R!4|Jg7>w0# z==wUcg)984NZq>FNT{Hg{a?0Mo@f6i{?m2(n<^2T7YtivR5N_#-NTKxR!Omoh&J9I zn5Ix`mFV=hz!Z|DiDnLb#!6zK$kBut?2&`;8%@N&@yUEdh6dG!mRprlVqI?iLh6_e z#k9G`_t+Pd-EWL->T|7wTk$3~nCgq|w+QYZa`{Z!A1=j-pMmCO5iq@AutMg}YiMDb8b+pzC=KT00{4PA3PNt6wl zc&xzvl~BDlawRey`OHFJY*HRZEDZ^w`~BA}_@8#e&se(x-2>1RAKQCiy+1}kKMTX= zk%S;z4-1!D$$y_aehXOgYT{bD9yhR@Pe(aXG;{Va;c44nwkiKnl5#U@`KOk7m&{Z* zxd1K5OJ#SGEuH`j&t@KswS?5kcHb^4QeY&f&y*2ufBUNgKbV(h7pM&#InEs-MO2m` zktOS?hHXWVC;B3t*UJ)vL@`EaLsFeopYD)#x*C`k_{vgOab_ZUi$>9}$b8hg5)@qY zO5=WNv1NPa&|36?do@hCRnt-_nfyCZlWY92Fm%|5xNs_K5MLJz&Y&GkODh!+uaYGX zvKavEaB>U@IXNiqwbDz-}eKMK6 z_^>)!6GgfFN^@DQjmGU0M_HWL!>UieFlQ=1*OlCpiq8C>NDwdTWQ?cY6()5N^3wUt z@Q{AB*;J3muB16yxME^j&3Gda)9+uO#2H0cul@bv*CVn2X7ikTaa!dwJpdkt-|omB z1qmws>rU>T2$yPNKk}O4ACDjZ!AyT4TuA*7W@e{*PcJe*_J6-~4;tHl{jk#8#$fiy$cQ`>7HX}Tq=-;*{(w*T zSmal9mvlTof8W+&p@B!H9(n~NZ=@Z>%Yrn`l!^D@3X_?q42)$~g&9ZtJ-#%-M_emn zN`@x7O=A2#b~MF;-J^i@$0dbGaUo^z>a<(jLGa9I^IIdyT#Lf~_9?qjD>&gW9pvwc zIwO^SEjs7CMHO@*$`v~N{J4?5aZ?zC`0aMueSS2e#u52eNk(_vM`Adyt(k~3rJWSF zT9s6FPGp(;E6T_LcES33#LLJ7CNVGZ5CC&`w|oAkAf=BjY*kX4vb!jOoDmh{twlZOWI&f4Xne0u`y&F-)91O$~ec5L|%hVANz&0H#66ytI%6<)# zT)e0>vgFn?rU+Vlm9iaFs=F_LORme^4h51miJT#ATz*IOqwJR`#=yw#n?X0JQ;M$}wM zyWAE+*`@Xc;(k!$A$vbBo^ScTtx`@MPv|oND1BEYg@E@OvfX}EhdVQ@E~g55dNm@L zKyqKSjus%W{zd3Iuz=dJX4r{muYVewg}0YNqf6A?mPREc$O8kj6r*N#lx!b@6!p5Y zvCgD04xO)^g&8PGYEnr9p-l49bt%-c?UYg zbI@MfzSLWfJ%3(F#YA)(iMwVJd>iM^A<>yI_bzJCsZqGKfK}*8E(RmcAADJ=jL`kF zf0OMs02Kj(PLGvP)I_@AMR{NFXhfqMDx13o7kuk=K?;(0QOmG$`+1z$~y}c?6?|_lh}bx(K#6 zO=LgxzZeCJ9Cdku{_G2w{TWm9f^M;{YnR|p{a2=lGHa_9ha6R(vF?>f2I-#JYokIx z(HcaeKN5Y}j%p{V2rbpq0bmoJu(X+9qQCULz7oDtXQ>Tcit{d=#?Xhh(lPJc-H*^k zsfXOZjnS*o5sJ>np;$_Cikbxw+snhG*4xybM=6MeuHwI`6UOhjtw?{ziEl!M&DT1p zH5MCQSe(?OldVlA({j=z@#0rBSYwSV=cm+6+Q&Ze z<+$CRK#&WD73|96c5s=+r~#O{)0y=(-899a70hA9bV;eo0v+;9A+OG9OLPWf$yaww zgE<@{W&J4xE@1lMCCU66Z(F&VauYND?Mq#K;}Fa92RjDwmT9-y%7!=I%o#q9LE4N*{G z0(8PArhXR#=jNBO6YZ+Q*57@A|4QFgiWtb{=iRY&G`n7X1|N592$^_4Gp|%=y00V~eoGu+?j29;A z)GgaSl#b-seRm;lMAJ-pEzOw5C1_sy7Lq5d^u0JIm363f?5)F_XzUI z!%c`G=xlPgKZvJ>aUfUlL5a7rS_khU0`b*ttK^`?@|s;1zm!^2aOMxoNUL!nf|@mX z3*~OcST@q_b||_^5`|UaTe(rOe1c|~O-A>t^V#Qj6Y@d^wi=`XA19|#qfNSfte_?# zU{nt@`r9Pnl!qq~N%L1&JqJ6LkTt%u?xSMCY`B$ogP}N;p;yh1Fq4(9VVCA(#17wV zEf9o@zqkzNF8t*(+GG&HL@}QJCCs|;27Vpp|Cnxl^pTg+pjBT}C0tstd+_q92x7Dd zO}8)axf`Nj^cODIL+41ibn#ky62s6uQ0WJL<$np~1)6ZmY+jL`bh0Gf# z&F9BwC}~x5f(=H&k6qXo6B}ns8BgkU2^u~FQ`_{_2l?OLD~UWh67(_7R~Ge>tgroo zuZ@`=g~JXf$H^b9iv>zk(XQ$@@{?+Gleh~3ZivZV0T->GD$do+Aj=Gsf35pIx8S-h;}+=UfjpwzgWvh7C;fz z%g&{9wgUXV^U5-P#Z~1#{73#_-Kv->poJV!)2WZ$!o>x94M##822=33S6wg zInn326LDF|Ol>+)dp>hxSnFP6!|r8ELEu90rV1Rl~VN*KV~|57k}#Y21mnSxS`LKt=D zA?Z<+orP~+u==GOOR|aL@?k~}*L9tpWV+>c#=9s0XmrS|PZzT|>X_4VSdeOH-`0Vg z3@09Tz;t+esT$2&Rvdo;;$1DRi%u*z$CMA5gAUWv*`wh&1*M2i^|)XDNW<~V{w}I2 zLBlhG4CtR3s4PEor|$)G+cI7#Jyz&Siz%dKGT$N8I3d2^$I=kKfOCsUs8G;9%*iO3 zjfR-6V75*5*zh^T?7*_=Ne(B&=&%Hj((DgEAi$u`yF=~uFu_6x{-BKlkv_ftH{vbt zZ+^4!URk?Lp`5G=!z4>{f&1)I`n@9@uT7RM-dn=!X}(nU;~<{5wV8R3UN2(j zcNn{z_;AamWQpM1zBrQZ$%m<5EqCi~d02Gx0d3JY3MNQR$Gu%QZwXbwbw zr8_HjeC}h(Cl3NM#lk<@2NJu0L!!1xZtfqdFs;py0k>(}x|u?{NkK>Ty{n|PuG9U8 z(2&5NW#%7Qh6vNygM`lMD=PW?;J%3#FWxZiH_f@i)@~CgrnWp9t`rM4Y}PXH2b_QG z8fjIwP1^Kpo~neK(FDPXM{W+1i`Aggx$cEolzkRfeh>^-GzJ-wQEu&Zi^&vBc@l>baXYw`t&& z=$)0X_T;o!-u%3RpfhPOQPB35pO%DDnn~qo!jIIudz`ciBQ39<9a7Es{9pX3jH52H zql4Fmcim1>Xn4tBrQi0>I6W2GB_ixvwV-j#pYLl`Q|1`klN7V=Z=B96Sx^2*u&*k_ zkG>W@{bW%&w(B%dmrg8lW0=>CFOwZoma`69keHCD`sCq1zo}Zu*UCNej67D?{LN)w zn|@)<__Q+7)j#Weq&YUp{EhM2D0aIRwH2#Yte>6O_B*aPOfAbR3zD3-4R9JXqH>>9 zhM!2A$1h|XPU-b6$7T##OX!<%I(X9JEzVQM%a^^JcfVGADrys;&EM@|FY!VaPz1S6 zvX#83GP~nwhs`tTC5_RSV~+H!h?|w72R4gvTy|EO0*GqTGlW@^CI3WD`1YKB{}2f+ z6=tJ#od8wkVAHX-Szz7ORuBtsLz%bHsSA-sD#uL^|JkEt%}&~oylpIM6Mrt^QCN9hlYh3U9^~)5q|N{<{fJM;nG@>h)P-Qn0J6i zpAu2qE=Wwymq$0XBFyt=3cQy>z*cY9G&d%Q;BM%7yPRz2{OS&uQ_-iXruj ze7-wWJ>k3M)^!ox``Ms(Lcz{`m2^P=eq$q6g-P@?d+CzxrJq?u;xw6f;^$K{o?@%5dS~6VgFmLv1Cdo+18kmgF=Q#3 z2Vv(lP3qX}O>Jv#4-!ekxe=`5UDk8Pj7(~A>X(4Z#Unh*=+T>@OWE+&PBG7nETJ`8 z`9@e+<`Rj%6aT+RSp&*A?;MUUK<})8gTw<1U{PTZ(UjANhm* zHS?V5cqR|Ag1kq@Wk2e40&E^&qsBwZ(v@BB!gowNh1r$%%&GgjE6~~$f)osp^WtDVwnCPXPE7}L$)@AB#z%tr4vM}8!!#+FX(qje%1v7qWjbt0w&BbpGuV8iJ_hx_Gk4&jHPd@dS^hAji_rfuq2VYeq{hi{B zt-1?G;O4?4q9>WFTu=)Id0E6oyn|D(g@Az``TUtYgS^)5w#Q14{32T8kFD8?))fMH z+w+T|Vf341!cSX68nM-MZ|HYSW5Cu`Jcb+(hmI0sAn*13@h=yN`DN?tDB}!qxc0uB zU~2f?Q;iuqO4QJ|tNGO@x?78%hL-`nl+J}eXl+Q0Xl+PzJ{)C|=gHO2AC=5Zjw21!f-J7bh)|q#lT@tBmXwlB5-9XojQ8}ZJZ4iXa zmYJAYm6~3=rC}WnoyiFCUnxw`Q7*Q<8qPTdQ#%nVgw1agI{ei;Y9&Ti^Fz1lO3Gfb zY+vs40?#Y+lq`1X9q!aWK=pu@xMsFY z23yJ^84u=#3t(li5^X)5%jBZ$*s4T)-POS@oIci&RE|MS{_*1!)+ey|DX>!9vZxcQ zC;H7Z(dq<+__3$Mu*`E$PD?Jlp1p-aS&wTMIr)5)*0l5hG)cneKlfC`x#c z{~FaJiuW8%pzYQOElT}NZq6Vxb3$!PW7x#CFmcOzp|CC6eXr)Es&KDU4bknWp?4Kk z)%M@?+I|1Ps{Y_$moBMGW5&}<>eOlb2W@KmHOoGnR+-wnH13s+MXhnNJN*Y(; zVd9)!9j&U1%yt{CR0kl2_etu3K|!Y!kN=jBi~$&zTlh_G#B2o=(qgl}G*rx`hLXh0 zjcA=T8jYFi(?`nTSXw_)J1>s!0{3`%y-tn~8iOMluU>6HQeHILQOHD#Z1>C$mJX?B zp7%8Cf=G)2yMB>zdqBEzHmmTk){fQ^1W!v7pSz=W#zy_Z897u0GMl^*<3ziIe?Kwi z>Y2|IRa8{OnxB(WfBg83s;X)wp27B}88e?8NLq({;Zt*O9Py0q9)It4n*S5YQ2#{U z&g-8UiF2v#GCid<_~Q9Zi~RFHznyV6fA0{${}}!!rT1r)AJB@>%d5uMXyZCJ5&u8D z0G`&3#?FiWVbQw}AG*mb&$G`$O)ABPWd5F&PoOtpVGdsOpSW1BU(bz+i79oxxR>(b z@)xnx|B2wZc9xa)ydxFAe?%8_Ft7*<_!3L(nTYZ8uVV>THXgdy7jf{NHnKg&;!@YY zC+@#K?o_4N8@Iz;fQmlvEd8f*&r`Au9l3cU4(l8Co2@X@1S|A@%C3J?Xx;r&h5#bvERP9@&aA*Rsv(Z{HkkqQJBex$?tH^u*DEC zyxRFFt@5D2*=#b8uRR2}Nbmc-r)MoR-EGk?yt8!ds^CsX_5d*8w+~k&e~eG7j{Hs; zkkvibq4-ibfoy;7+{4hn4p{%|FlfIip3`mTJOTxr0*miiOOQtg%PZl)ve_%%jxJws zH`hO{9SLsHoA&Gq(bt7l{SjJXbA;K_m;UQVgX(5C{p)(Ufu%?e8h>FyJYH|sYS+Zw z=Ca&v$y!!WMMjO!gL$z>v~|d)eg^JqYhIM9_<6+WSMoY$kRsMh{6ZnmvU-0oFdgz? zmh{Y!t>G#J_WBf5mK)3V7zIt#T5H7t>KhJ2ey3@hxdnD-rV!G%2Kja!w7bA17|ir% z_WDN7Q*+GA$t==-O~;&N#VfieYlEGofA=M^{n7kfn*ASxe{uiW_r}4S2&+!B-S{hB z`-bH2$PbKSY`KDJ1QGd9Cg(rT-x^y}5_`ZIFe&05B1Q_BBx7}BS_6+?LuISezn$F9 zypdCLnhU0Z2eEbOEO2eAZsTrrx#$L`IxzrlaX2pfKZiNRo{Y6gP>UK~^FYdO_{}Ze z%(+0Tm?Ow#hT{cPu1LbYRJ{o;`aC9hIuN&lb^fQ2~ zs!)09%m6O8IdIQGBGlnkujPI8`c2YGG609UXLHd#TBk+f0*ATx*oy}*d1n4Gk3T=N z&^i;IIwZHtnffVxD7bR7It1kaAXgc(zDA0cBIyq@CkqRwo68tEyb)j0Qpv`Al1Vf2 zvL;IGKBVK2K%;W403~?;|03zGbcacPnmLfxs3nupL#LD`W(QK)jh9xqv#H)vmrO&QSi)Imn+!is-DrrT zw)5myrzTUOAyJfhH%`E#0oT~S9yBY11Z!3` zCA+&agSE=vr}Iv0P-@kFatq)MiaFTxHlI>NonTpw4(9NdVsPrsz!Vr9P0`ywwLjIj zBve<`VRp1K74SPt$(X6ob6br&Mk*8AZDqjS09!^`H3(cYd32nC;txBm>4E*Tu!Y;& zBKq6)Lxp)Um_^lyrhT*d9gWZ?$~0m$k&LHmeGMbYZbH*>36c$<&yiC6|AdlgjRK&E zW-CW2NcSFJbDW0Lv8Dn?!P7z$4$+Bfa}EmI#?ne#9Y-3~7P+gte!c3^`ZYTNmgRQ& z_ytL6IfK5P{6v&fX6=VG{ia#mc)8JTr<38-5b8cD-r?xlIDaWO)yY&$;L&;teZiDx zd5%Ye7!alS9c3bSrOh}0Ql8Rw*`e{Ph~#&#O^1*r-SRwoTqSPFE%S9a#$yes@`=-j zlp+eH8%x9xCzMWP!KRA`97^R$ivDg)8|yg@2svH zk<_HL)tI!bJ)BkIo)(WDb5QpRMO(-g9+R=1?Mxd~A5PA?k*a=iDp4!;E~-9VnYW&x zxv&1LGalM9qbSl4PKbk{O-0V>LDCVl58qL%!dS;1jDeM>OM3UDM<-yQI&G+zD6Y>cgW zhJMp*ewA|c0(}5gpF^)zWnVnj7V4*Yjp}*QDl?!?YHeIhM9HU)=xXjwCH2zN5(W}? zJMZWiF*Gho=0DSNs#{eUlPW$>7~W|d(%vW#c$@H?<`i1a38FU2!qr@Lf31ktAkD6+ zaKY}4TwTB^CvbCKdEPaPwf-`*+CF|OOVOxlWI`+#c7E4R+mB#aJS#viw`MO~K3A^r z2Eo41Y%W)1$x0=;nJsqQ%@SC<)gP5xKUO}* z|I#oksd-oHNZOLmUS|`SJ1aA+gjkv^y)8YfWk)qK9l5sZs$G@Lyie)44ta%_My^CX zQ+Ga7c)JZY*SVCoU;0$IBVtFxSQiG9P2HL~h+c56IyF(f@jdQ(hq@R&W zJjdidoyJbI6)+P|Wv12!IE<-?qAo7vJU(fZNiFYVrK4W3_thz&zP)f#j4Pc`UAZ4RdiQ%1!k^EyBeR~2&2mhVta6(t+A1{qHQl~T{!&6ceVW7-NeR0#=qOFU-U z=%~!JEAR6!1)RBjiv_&cS}!FprpHG%cqW`cte$ru+$5HwLSw0-%(hCCLhCrf+68nt zI2(rF+0k5D@sQpr>a?i@{J7&H4=AFRD~e3n?>QZ4-ZKAM82)a5j(|MCTn`&)9jAqy z|0zfC^#EMn?11P9ewHpn;wls344+jXGoZxXwA6T<*znz2wp6xWwmeQA9VxLPqg;L;i&y$yuBG3ARy=y?_sG%p_(NXolGU;o$La^t$CX<7+YV z7LD%$7BbW-fNv>=y)E)}@0-@DY}?-z3&aqvGdVsqVe1Onm3*Hn4(a7&mn5UupW2w4 zWPUWUn%EP2-;NaKabRy*o}lcaCb5uF-@>t6qM!wlrA;(Od3HIoPp*5cRc z_6=2b+w7?*pK@$Fh~<5x5_A6VAV7BF<1LlSgtSsFX#_9M*VEjPLQh-C{=2OE*@)7K zZ=dClrQP38eK7+;xF*k}9d&Z@m2zDjQ`dW%l2FFn_q``7?XU8@iv7$$WhswR^&NK- zAdcO!!8#npjN9&;0TYet@Sf+Fj~&fCr7U-_n3n&Y~cpUV_@5llEV=tXGRb2mlE?UXAyoi@leXFGC zOIrQ9jcI9nvx0o?yg!)vMaPc*?FmOaiN>QwI6bd2qm(#+XV^d2D(sN}ux znkK+9KT|qr-%u_s7aJ2~=RyR>I36)e>o{sKzaw*zo@4IvtPp-vc){+ zhntVIJ>LV(>Ab160R6ycGrQR(ZEnW9Bq0CCj&bmWMzy5zz*+pVNdd0a+cqs9Fe1f2zLlv?8dtS3Fg~`>sSc(|oeP zae4>dd7wXzrk;O|8?R}Y`8QgVp(b=tsqaENiCw>5#(nN=8o-rQ*(J2!>?Sd(ExkZP z_o#Kj3HVcECKmdQ?Djf_OXj}B@kC&>A|}TpWO~Y8H*{o|4#CLK(E!%7y3H5AN#NUS z82?@7Y9~Pk)@0aC2fqt7f*}k^#wxWxN5}AY=~iJ|gmw=qKHPFQt@^^xyZ&8#gnySg z7lflo4%=>QT7DOXQbG4W^y3QwD_m>X@4Tl#@e5YK9awr-I3JYXzN7em2td%E2mnl9 zrTASqct!Ey;UNr==*7aoz<^C}-wu1Ew4rk3JnIl`J~AAXTT+GN-<|q-{7nYkUfP_?<<5_5P_KM12Jh@ugW269 z{6(oy1RJ1xWXUL8B*qQjzmt~2V1?9_+t?4AN6Ki<&h_=~y#ow#Px>d63UimnI5aa2 z8#2#co_34?sO8HF!8*-erIwp=%EyBl(YM|T?L@^Ph^b_5l@zBgYUFm{$Oh*!YW`z? zFeIXHrv^qDPk*;Q(BTxzbHjILTmyn@Tz($OJBch?t(sX;GE2gw0Q6N+PL^=TcJJBY z!t%UOz4heR8LaNq#%z#;)LIoJUX zwBURO^^^KWH5G$&0R>|*kgbKO64i(xftz9go0|%T5TdDZvfoa8PaS4l+_x(>a+Z3h zohDizFeCz$};bHa?tMj2jfih{tjmIOU@A~#T?9tQR9#}fg zlqq6P4Jy@=%0%yRH?G=CtJ{4L5z^c`I-Iu)13TfI;D>UK>o)+_akTAG9;s^42qmz3>iINX(&8K0Rjj)I3&xOA%2&A+ zw=6m#Z>Ji20Wd2gqxxQ+oA#t}a>W&u6g1~AGUYNC=ztW%xf-f>zX_covq-*x z33A$i_7)f>-n+;Dlg~XUHYCf?5Abl%o}7SCbbi|sRQ}T(6+Wv=vxW@hdy42-(v-pu`vLM9m6^0MC%vhz zJe&8OQ8mz3TJZx_Ix7`py@2_1M>p@)$!ZHk%6!M6JB{-$kK2WFSM0KH|5E*_HeK~3 z(BmMS43kN=v&;o8&Ae)IKzfZ*`7=+L&Z6s~rd{Yf-pDk5<`%+FZG5Jb+Ga4}=~|a_ z>MglnAW+EXDQcRqWN>x9fOD+6<7EpB<|;JS-)6Nr|mv>B1Yu=c8j z&|x-F&vN!B^;)C;Is{PA63IoHO3LDM7*ie4uEt;Za7ArcnNTa#md zH_hZP-sK>x`sn|9m-7$3n!0a)nMdl^l(p|(b?u`q-9Jw{xSb~Z#7<))kUfsFDsg9? zy2o79{Bl{9^+d`MHFZ)a*}bVizDYnKW}|fbO)bwjH*=!Bx^n(<0g&Bt^xQt@!;`n3 zV2c*B-C@a!_58dKZSk6=@bgB-v*lZGa1t*C%KyCymN2g`z0=BAw4LSDi=9fBK+8$w zZZgi|2c^7j@sB9Tfb6$7s%#7=YpTpaW-A#E(9So1(NAkNX6q}GIEH9$t!wyGj+6DR z+`i{m7Wx<5@39ojdxz?L8k5fSXOF%g%}=iPWb3N(H6XY?jRbznyX?R2Hd<-JF^VMD{L;dFsgmy zoupY~ArCVfA87C`TdCLEkx!dwQD#nq92U&Lt6d>(7b^kvG5=0DbfHSET#$uIz&?Kl zFnj~Iyx7Ht4`($Po%Z!dW+qF+zh@_MDC*DVS}|zHc#|Le_*c{aykN-w8w(^YtteDg>-()>C<)j>rLrz zEhc$TXH5r76amp6Kd9ht91dka$}XTf9VOnmbs)orWh13v+1hDQetXyOe0yCijYe$}Ffc?AYfr`%@ZqZ0m* znJfVr@?JUWKBkw6QBpAlBq4X^bgE}s-xX1JH z)PwOmv)aP?jD1{JR4Gu2+Ap3YbGbZc#x40!sCs?UCb@Cc0QxioXg`M_ve*ra*6fEb z55{q7-5!shj+0B7r4uAO1`#cx8!yjXTF89!r4B=~>rS+gM&A?<4*aY18qmTrFf=K? zaDCn0-kzsbZ|9c#MmF%2`mJhHQlR*b(hUviU*$LppiF4KpmT$)=H%Wk@@TwMiqJ$` zO#<@NGVwwct~%X4?&JM{Me;p@uG4&5K3?)giHHhHD*zC6hpKrpNzCJC#*t}HBd`i2 zSqjr9LOXOAh9Z@oOP2 zV#U3G*mKNwKs$rtX4$|>zhWHCTddWW0}Q(78`m9|E{>ya&3PNia$9pvIH}Z5#*4jp zjnh@Qg6A$y;T|FK?!0*dc65~u*zLD9eQPu9KhW3C-Q~R3VadXf+fiTFP#S1VucXRb zpE&jcQQqylnWJl#nBei+KEsYlYv*N;hbODS)CDjMsCo#CKzyCrRMri@AUCx|pkKWT z`fFzXTgk$7yu*gUEB`I73glkJ)@ka%TA{UG{Vv=6RjRvrfd5&;@QMbQ&c8|Fak7zK zmo*tH?W5pkiGfG*DK|9Kw$Tbo3~Svt(wZQz1=10F%8V2Ak6`bw&fHH{;w!GLZmb8< zc>?1gs8>!%oo8UDTGGY|O5aj;DSfXk`b8RLv;@s*A_XUk8qOADDoq1sxy`Txr9;wf ze7^+r=Z>vA4{3zdG*jalMwD2>Vy1|&Lhf+OU(`cND$BXKedfVq!S{;Y!r#x-RSq!6 zN`a1)Q>OY}Oxuc(d^HqPZ15RAHi7NtTPxgpm#)WajEFLvHpSY}x$_Foaol}{yt!

mL|5v{ z&l`-GfPH-D?Z)JaWQb*QQF5}C<5ji7jhDHPp3g=ntD;uAcs=mm<Ei~%d@7B)IOuQ@^Xo%qJ)u>-@(mc13yP^P zX!y}DD?mX@P{eC}I_m7byImEZRydx4^Sj}L87C#_8a`tnWF6aRA43op{luB?Af` zp{!dM(E85UtHALsX^}?#_KcF&ia7}f{`}hM@q=+)zsF^JkBQ;x@B|St*BOZvs;#E> z3U+js41{$Z!@l&%3RLN)5WVpM1x7?=)wI-d-#=Q`39sef?f+tIa9OdWq!G|8rISp_ zc7?WaIjQ|^vXmVgmm|k&8;+T?1!4p_0jlp&s{lB5f-!cTFweRCUdk-#l}sOQ`(K_nKS6{aA)oM zGriu{Cwp5gF}Q_$SvuqRSi=@;-P`*XVX|r|+z+RPR|lm-9D?;{mx+;UPG$ah(0k%$ z6y-(m*Ld~1nmgoXEoW3X&Efb^4ea4f?Sf@TL-O&SFyouSjlJ*zNh|A~V$U!O=}WV& z_x$epq-lt%jQex8QaYzJQ8~!*PegNOQM4<3F|=tuE@5}aQXzx(HKMF^>Bw(lOb#W+ zm(J=G@&-_*h6%(Q6exH)D45(PoCmcWA3^NSOcfhml%Ru09`Y?-Lmc_*1eWdHqar@b z9B1aA6L9>DkzN~c8o|+}+vLU;hR@c{diF-)L3bWj4`6AC3@(p1CJI#{8C~-LM_AP6 zq}!*XI}WtFS6Xq@=}C>(Cpb@I?Ia++#LrH)lx8PA13aZEEAMti4ZSP~1a&ua?;M{c zf_tt9;z!n~+yO=}iHT*B*)7NDnt9c0EI{orGRafQ9}^0xcidHhNh&8Jt3kZ9$hfd9 z2$l0II!h+wH$fv6w6wbc3sC2E*LZ2($&wxM#TO0ir-$x|8GCBe$=@g9U)BaSXX7(o&7KT`ID(89(b*|a zZs5;To7#hJF@)85>sFU8!cOU@z8#5Dg73Ng{Sy_?v6?nKsi&`lD}lhZna-Rn54QO@ z?4hGuu{wu4Lhm%&Ke%!3bGiY5WG-Elm1H~`knJjWi8_*8iJ%Gpt7Duq`-U86H`rW6 zi~fU@9*({60g3xZdyQDTH(r~MaENSkxGAhOUxmo38Jf-{X`t5~;<)M1`m zZ+Nl77{OTL$To|rEo!(3aM+p+5`9uq={S4MYR&7DZk^@)gO)pW;E0DTk9kyhQtE|}Zh?3L=dQ=Q%PrgV!!_?5 zK5552)7$gcDI_%;XC@WoDfTBQ0#$TE0V6>kwFhJc>}OIC zS{TK=MV+`*{bgYP{<2Y^4E zN`uHP%q#mJsc{Cw({-I5(NzBcX6Q~bc<;?iX$m7F6Rzj1hr z4p-cZVz9STIH@GoYAn#_B*TM^ZuQ*$W19X!FCHPZPDH0dri&AN{m(vv(KIWGrsRGoo2_a~F@qB|m_)KBDVjtFj? z*S6;X=sXehdcEdAg-QoOJHzv~IR->OGmmy~9S`h)R)nt>VQyo$#w!dybUbGS2|bgc zs}uQ!=o!75>x=V^+n>EoPu|`J&ZC>|-0W^{2AC$j^8aj_bl>>(A(MMh7bi^~@;6Po zxV+4EriQ)?Z^}&1yyGD#k24eO;Xu|4QR^x)^)xMqJ~dZ4%Z?@RL3YBm{$f^}t>eT{ zcZfIu9{vGKi&ST+(@*gEdG)+VaL)kCy9cJ;3i!%D<|o z(#pbMDvx9)vYuC3lkIJ3X zsg3H!xkD~d2=u$l+LXhPHAXposOar6nv=Y;E zheL%v`TbJ7*m5rU4W+Fo*iW23$*G{~F7P~IXT*B&6}#hYG=31O^_sJ1kN5Qaa(?se zw#S~T3T?O)OjKFkUiF76hPh+}38Wq6UOJBQQZ(WXK1sKfLhtjBntks>z{8(u6eD}l zg_0$6I8bFH&;<<1Ik7rH-Ak*9FQ=<8Kp=F-Wi;DC+9M|zZ&VblsMA`DWr^H_j<{Yd za&q37JeF~1N5VdCFu#NGljBbkibtiTr3~)SgKV{O{a5~X$uLLe-<7B;7U>wz>+_Y} z-RltpO2_5Omknv%6$bhwZp9MnmZo-gidZz$ zk)|`I%H%_JPPo_bjUH>|T}(OTP>O8qUujcK)5mhHh`F8(eVM6i1IS*NFUJbBt#L4B zd!}{%2>-<1qMGP$P~=MpAuow5qxhdHp&e74JYQv|`4yd`#Gvg*$Ei!9oIb~lOHBYB z_}%3;u>zj+Kzm}hi;6yPsoU*^mj&6pwMdA;!m)Bnx$4GA{kRJsaQ{h5E#M8seJW>- z=Oz2vx$AF~n4|wFF-cX!DMPOq!C-E>;oF)*Si1JlzEPJ@hW~x7&(oM0oI;igo*u^4#D@vPt)-D;8>VS;?C=2D07~uQOE=!hy{CDClUzA zYNyB1rgB7h-fv6F^So$Ctk)A`LORQF#3Mix^GI3)5gETfD%kE^v58dTw~XS_RM`vX zqfIJLRB57FN&itZ`=Q?Y#_2sSVQ2p}zO{32#6I|_3~@9cYVT3K;tmGRNi3}zK>)+F zXUU3_WT9~lPWD~$k94I-$r$wT7hQ}Pj|%Sai4cVFSd5Xbzb?H!9JJ{6O`|kvnEtel zF4ovomWa#c&5sr!8|*vu3Kks|zK}~Ri)*8In~#|iYQJph{I)T?j4}23<^W!K;E1KI zp;rxVX@Y~S+t9|RzPZ#E!_h+<@EvO`z9XLvC*~}QW)4C?$I%}=M@hN3C*Vp**>E*R zCdFBnT2euvFfskEpi)yvATRvb&5~2bdp}}B;=hD}e^j6gmZ{!!t%s}i+Za-xz-ju1 zguCtuS(B_Z8RJD8%NHvKoyn@tAv*DgJjOLqWXGg31MODYE46(jWB18^H+HAYwiI

N!&700;xxPxJYUz=p|d*wD!s+&!Ce4v{Z*xjl#EGTGqgY;!hGt4V)m4WyW%q#D>ywIvNl&-Zy#GKs$|#8L1Mj z=3t|f?&*P6JGu@@Z5o!6C8*TwtRETyWf@cRV~A6Jc4{QBJ{d!<+KFL>+`ai z7t3o9wVD%#k}l2VoghTCcRQ_78i)o1?HIO^nKHPKB>DX|Eql6TtpO%Kx`NAOhEcv=gdt!?+O$W+O)PpKka*0O4tH&HQY)g`p4k^^);Un1;K*r6Ti)4 zBIG$mt1doS39WKYjuuK_Q}r{G#F|qg`2>B?d=MWXQdS@Z7?#z?2sgldnHvqP>XJsb z-f^%HN#nvy6mX{Wl*BSvOX*6nEfg+|B(3F!E=IVBg7H17EO?3&WQ=ZVmzYdGQW}Ss z$lQY}x3&2Vk}8@^{81Z*d^CF|-tL%TdjY5e{7M7YTu?*3{02H%Lve_Vw}wF(n{iY+L_XQW??Ott?lPoVoDX`&|?zP!`BgLO)-1a~#(k=I z9vvk^sD%g`LhEaxZj@JGwi3}qACYzc>>Im|gk{@GywQ0Yy$>cY5PQ6a@i!MTXHO6n zS`U^-N*1(o;TCIaI614#8JI*V9wFS8FL(xD_izhsdC#7JO7xS&s0}RdB=zi z5iKyHdO$*#^RIsyu)n_?yD;@?G%(4!cOH&!0o6Pg8+SQzae356wIc44N!h2zSgmzl ztgWM?5LL$P-g8^w*T;VM?8&v|Yw}@m3)NFrQb}?)6P?n;&VX_e!x67r&ct(bS#l1i zuj!j90^)xdg}e^Mth~_g7u2`rC#g)A&>dW>Dt<=yRdU{7nkR-po}(-j#l>w=>pKs& z&Ym!rGeSc9{+2?|?$oD-T*{J8yL}Chc8C)$%7EZ$*o^zmx;bzuHhyEi4vRlpo+o;^ zXswgiUltUAJrb&-4AI#4)LocijCD3i&%Br$$HPuh^b>-0HiGIGgzw?j6h*0`pelhJ zVi*D0Vt1WWp&e-NoeOG%3{tv`K&uLmX&ecZ$lq0_Zk+^N+?o+}OS^}?ZXm!;W_`Uo zFUM~>8q7yW9Rq|VfxN^;uanQ1HgV7drP-#l{ut}0V5Ln*j<}E{oVP)V;r+NE zsnrVb#$>^m8Q4G8o6IXeNOT!=vc!3>5Y190r|D)0>t8~Rdb2Qu*GLhNcpEJ>GZEM)^a*8l;GoQF)TYilE z4X~k@Wg`WQ`orqmN0-PpI@1)oG6Kb^>GdC~ue-FP_aTX&QT#<GMa+!@453uwhwZPQ1b@}XHz^-4W zLCIAvNA(>ILW|zTR=veHfhgspk_#}(52>}H8F~ftZz=mEmA) z;vRW{T(j?e@j;=#uBAV{rc6GDE~DNGx3NXTmyR@y7Q)N?*`ntgx0cWs9Q!Eu#*OpT zK1MNQRCD>58w+;{j(0?eB_KNkblra6xF})GgNqF+!G*<`S0lB|#F1u{+GL7!{;9T15OqRuXJPq=owLwChhGP-)Iex-ThXIAfRyo$wL zWbt))z`e*J4EcS!HkK{v7Vy(i@HZuja(Jp(GylKVhnKswis>{R$;rD+diSgv?zy_u zg(}5AU_Oc439u}%|3YsHREn?uL~m$Ribnp2-ppS@M>2$jMMP{@+WqdixPJ4mKQCS0 zQ%c6uUR+%%lznUqAlB3--)OEoLSFK&iAA8CVllC#O-!y`PYlIza}B!Taf`sgkkC#F z_C_b-_SJheQJ}mFpG)>P!}_Hr`-6zb$>!ov?-2sRI1hG|yK&lr#0=D6M&Bq?_%Hwk ze=)d7)Xjt(_K<7=EB3vph=_cpvGjt3;NL*OFSR>Lqk(uMSoZVnRR7-lPL*YB9AbC! zrtudr$@QLcOzFlQ)>XvRfCrlC!z%B}SSG(<*vQX!uG_}stm=*gX#XFE1$MdKTd9(Q zG@ARLIPt?*!s@)FV_Lu9{}0FDxK5sh_2*x>&ddqdkn9Ueu}!q^*NidHokppJ6!yVP zMVDqL-E+3&_HJwZ7%tDd67dH^I2JU%E%jeG^*|yi#G7tlEcHL=>VNJU>u>C>q3XDB zXeVWd@N^jk@OafDDIO$JI2;Fak)t3wm@&0=I+vW-tM^$` z)wk7O-dPFL{o{3ZAzMxd!Tp;o3!FW4zEbawRq$kJ@-%zO=AGdZh$dwQw@rB*7G>r0 z09d@!1yz|Uy5+t;ZnXeaki#r;uvta?qwAsl1gg#2f@bw0Gou9~y_mH+dGf8ZzY8gu zm&wU|K9 zMkA{^bx2RC{)dK}2zmH2zc{7a5F_;&no|={gmit%rs*+$Uros0lihod+}75%o%*F0 z0Rsm|6lTC5=RtLSpQZYyerHlxSOI#N{Os?$19`VgN{t6+QajhpfJJnepH{5rXV>dI zq6qkjx4&tb%~LJ8zUt7ZTXF+;AC#JE-+O{vSOT4fD8?puh{ms{d3%*>km|>HQ2$Av zQLJ*C56vgngN+{1iqleB{VF;7;5mqr1@x?gr<|wQ=(FF~rjCMTHdK6JZ9@#?1B7Cb zpqtG0Yo~-By@ef`qI6v6*i^<##-iwDr=IzP(|l00W&YM3U)$r38vWnGTIxl*^fnoroC<}pZ*d0);UbA8!5A+PvKgfR@`Ax9BBX$}dWsknbmnkQ)Y{>NsiB3TWjh;M~ z*(vXWP$TE<8X*|Pq6319Q?7Tx;)3waMEz7$n_F5S-1+FLYUibJ_trRJXjRncLc3j> z@m-;#%VmJ#MVz^4gB4dGs5ZEafu~aM#5UfqMZ^>x4iRIZhsE~D^^rM8hNq1a?+>6I z*E=}bfp%9rdhK23H>aTtUAqE31DAU#*9Jr@1hOktMjv`_jo}ZAjWpCaIjgxsMF{BS zisX^G*P-ooPASC$s*LB=;1s91_Nqw2=bH$K7>e8qEj=$uZ$FHeN#h>7cfYK+Mp&US z#?;K`XfiXBIJ^0UdkR*+fXR;ZO=2N|S@c7{@QG+qVm4Rz!^$ELM`E(1IAhoG;l|lB z^7lKBR}3V%W<F{bOY6~H=#gt>-tsY6z z=xz5Z1L~^Ojr`%|L@eYE8ICD$8^sK`Wo{#z6_d;IG<6Q1-Eypk59{^s(7f_O&DWa1 zE~^9RzqrNG`LTy+u6FKa$_&Q|kSj65zLL5NF5{nceFHnIrTXg@%gHNHdU`tml1Bbo z#K>YISg?`hnxVo^O7GS;d9L)R|GOybjl(;L*FCMIE-*c|wCP=H%T>6}=RQh6+w2NS z*#nep4R;6(r5?AD!pAXXkh)&Uv>w{!$2w~XpI6#xq zWr@e(!tA*_XNofmZww%#{*}V1xPEUghNcRpMF!oxn((m}4L7)VsFn8!dK?Z_C z`hAb8cPDWnbKTiFA1}z?nv;WH^c>WuGha9pgl`q5@SO7ysNN1nZKbf1 zoWX}R(b4Wc-QA=I7fHIhvGxsiwcM?e!qLYT>Y!Zv6WvtMgoisyu@50{#ulTHv`l|V zVGo&OU=Ti0+|nPOkvth~=&Lo!@`%u3B|aey5$fQ&``~;`zQnQN7<@rQtLchQRz_*f zpFnV3yterzp%(EYh2w408fPwlDW5k>Qo?>ugu8P&!y;)!a#yx;Mp5(XhdB6K)1(e3 z^S#uCf7r^_b^bPc|6+MZ_f4hUm}RliaOdZ23E3DII{^i%qgYkOEv!v5S6imFfTsJ( z5imMI_KFoQIHBvw7NB?X%!oDV=qH;@l!kz7)mwjEynb+PCF$yGF~UgTK0QLQ+W8>C zFfj^BGJJdxofw(_AW4UJfw64ew~uKny`uzb~9y(MVpeLXMvVau9N(0fkZw?Q^(EjUgp;1EJX*<7Iw2eHo5TnVX!M)PH~l<}C1p>y^P*kit$+qpAV z>fhcj8I$w8bk@m*;VyRiIlN9(JhzLsDG>J3&kM!~QnV~9mo5RAD7aet^Emeh+Q|<@ zm38_5xOk}A*w`q`^}&Kb{^JV(6JG3={QUgn>+Lp9WrT>Cpc*eq9x7E)0iBs@iuhQ> z-KB_VwyaY>stRf7)wDu_B;{Mp$gJhO=2HkR4V>Q^`|U|Acn`7MlwZ^4xJ!IFp0T3g zZCY!%*%Bh;1h;0}cpc9uGTcccCDoNmzR(s$H}M=&O`O{#!dFcZ-X&ybtcc=>ptNWS zHJ9_m$Ck`4WcU~r=Hbd$UIQ_L$|Is8Wxp~pBrE&QVKFyU@(d9*_^oB_52q6`UxWmG zL9DV|g{ou^c&p3jC}ouvKr|lc6$Cn~Tt;tFhle?WeS*s9D3bZt)Df!h1?}%y*2KqxTJLZ)d9wMe;`X zhy{YPRkf%_>)>4>E5SZ=s?T&$EW__XjQkfac+Xe(@~5)c6H^)zFSfP9bG7E_(v-|q z(g%lAr7l=QTL_)4N@ok6bEPzV?(yfDq60sy7gmFIbgX&DZWVMpbo%Mo{WtKNM5#bk&6Sb%(P`dn(VXE`c3C zNoPGM0X*E|^NV*w)@Orhwb|)Q|C7(y`3e+~dyDKpfOmbsU3U9Z07*5!TOtxYPQ0ok zzVeCwb`rX4O$W(DpS6t>#5UN2Go*PV&ET*n<7U=`7pQujnu992=6=bcLVFj-qKhfJ_zn9 z8%P*fubl^QrwB`@`qDxdjCpO4cRR$%J$>z?XURU|XvLAn_2R>LKUd&lOYmV>k8SBO zQwR5Ehxpz|^2A3DkxkwCyu&Hn#)<+u14Q=q?Ko*uC4O9D+XT+Cm3I`b*84FNiPM0| zOO7*FMPl@_CryI^sU|O&yu>$uk7RlfkFOeRC2pKxsat65r1rT{1FR-+M#g%soYfAn9w1LU%F$n4Uz zI;xIh)XE0FI|O75qLWCWrr)nHP+GWtx<4X_trBB&Jv1au@sWJZAfw&U_<8?b7jb(F z$-vh0N_FSXI3L2kyW_TOIHDHau08bhT;CIC9BJa7+VO;=9!CQDBb=E>pV*wpPY`Rf zx59=7@4WB_(5~fcryr{fy2p$Wn@Wxz77mqd(BREg@`GebjIQeBLzD5lt(l(WO*L|1 zS1bk$y!L0P4)9}vuDuBEy6I1`7Gp6w!#keJ`-8nf&_5K<1?!&v0m~FtFtD>w()Qr3 z9CMYopq^V(nUJ`$Q7sA((EA+)d*!Jv+)h61E_xh@2-Lm^-5;UL}4Q0|3P} zp!EYjhN=4d_4p(A0Z&g`3<96H$bCO@m$JCgp;lDuBSx6%Thf0gPz7`lW7=70S>otD znPnbsiNE5Uj)s&U%@554E!Zs_%WV#gPPm>xru{UDcbeGZ-K?|O2OlM*Ol#6L-#Wr1p48*(jL>To2<@(yjR?>;Hp{BB%o zoe$at7g6Nq_{!Nv35cZk$IoP|J<#&+g3MsfK7abK;P=*~BC9!MQCdF%L0)0j(uH9={ez8z^+PFS!n!5iZdacAa=vjTH_k?AG$7u3EKC%lx$jRGiPM&SX?QKujw3Qs z>HMNL;rhu4c|OIMK(5hAj`sE2`Hlh4q(4==JR#VA)GU9zR$l z>un8f=_dj|w5!|K4+ng`7spsVJXw>;h71jUT)Mg-Q)3TFtLR#LRIFzhHkH5}bO?vB zD!YiayJ5CM7wXq6&58E%jZP+_cMfmj-jB0(R+p4{D(G^v7YL8etM{$%OHMUrZ}Xn8 zKKVK)x5$>3s<%QYktjTm)*esT)4v$X&c>3%r?bZoKJ`unPkxAGXdvO|SMNPjV$3|} z{A|9Lc!pL?jq|pl6g{zGBUAXyDRf~&T>NZ|Rl}(Nk5-z2KZB;xwI=5=OzQ$+yoI?<}*`h4=5%l2Lv^)-gav(@619-hCe!}=s59{1T|q0#3sFzu8+cH)}ju9h*L@T=Csdlw3!*)?^J z8Yc4zbcV6YwJ>ONtUi)3=Rd(b+wcC^2f{M?2 zH7sMi*c1^X>~h>ship4Ni7YTWLk?RF9cY!}5QbU_Tlqx$9Q9J2T+fyy6SQDvq!oV1 zO8!eT`0ojZY%Bw^N|UE!=|#U)V=R8F#+ZLH{lBFeW4j(@VAGswa?(qx;w;->>o{Fv zgDkMz6b%!BGQCkQOi{*_d1w&9E#=b^qSC)oV_(3MnS?h{swdb%yaacxJ-M#Y=!I=| zpnB_d^jdGi$OYc7RSVXs1z}lPKta@wiI*ti>*Sb)7Jk?RUD%jh?u~>xUCvzgTr%T~fPr8u{NlNq z=S+n$4h#;VcDKWuwX)yl81KW1)$bbCk=U;2QgTS%7KdXw0p9kWc80oa_ObgANULS^ z)654DO>9342?!iT;$wRcWooEHf9L>^lR>PK$v}aPHXhS^!piBB*&;x%$zw-!51LNN zaV2qObLxpU#M+bHXXSVqee-&tmUlF;TXj0DXN{!TYmv;Up=_SeQ{%M}TlstSZb4C- z`Xoo-&0!!DS7_2T`|43F@zU6a0cwu&@y?B9&-G|lV?syY$f^rKbC0vIL>!Oa?QlCh z_gP1(h?rjY>$cP3ck8N;>^#qdSxrZ=u3$SQzojii!t=|IyH-w45l6dw8n7`tg1la$ z5cB3?46Ml%_I}ajA_+OtmFe=2qGO)uNBK#7#m~V6e)kF0}>=cN< z%1-kPk8>zH){R%2E(=7dN)Ffvi9xs1qiplk>^@Fi5Q`p+;9^8AaZ1HoV540*D4>{JiPeQAgR{9 zGfwSn$9$J$Pii{Chm%>Q*rrb)HGj;QdDvi-hDBhFwa<}ARI0zZ{|1?syZ%KvZ)dj^ zGkdN(l{Vc@S9f^WH;9kIih3!f(aWplmGI=es)&R!SQJdFq~?2`m6~|Q1V4P2AezFU zn6b^_tx^pRJFj*mhB?-@nR?cZJMW3Sa^3G$4$uS}(kHeld+u7_wl<;+bT`jbF-L0h zS8q9Y!;Gz7olG3XjPVU7mBQ~_&-;=0E;%Wl6^}NK1;iz-_thHRbNdU%a94Th9`i@O4t5e&r$S)#-u*|$d94w2TZe{V2 zlR4Dk3^q7=Vd&DAkTXh0>PyGQbW^6@XI%dNDmps)F&LKQ2(FQXCA;cgT_d# zbBF~E@(cvx-d%SQocgdhaaICG2ixusdjircGT?$pUPcS!+##p>)8>wN#SK^Vgw&o} zO0dad7S3%JayBIVt1?7VDZ$g+I3e`kEVy6)A(lTC@i;g`M8HX#vxahwz(B-c~aJA}ryrt(U9uC7m<1@dj6H6zmz!UoELQhy&g7y3nUFh?t zY?>{B&iWd)RPG(`YY%FxxGiKq8E=!QjZ=e0U4574V# zb^OR7Zh5*Z7@JbS-kj36s%08J(!yjX($9yu}j6HNg4FjG2h&kS-hwo(C7^|3u0Ut;w0%FWN`-|Q;<79*3oz_s(1ek@9Or0so+$#t}F%z z_;XcdVGUI=KeND85(UV5l$=!J6p?6WT%hpmb5G&4wVK<$@;4TAmKe*7h*McfLp+`B=tGK9ws;qvoeYh=2}FBBYeEgLmNt z9n*Hnp4E9vNE?T@eun!=;Bbw6%L=bVaTTvoSM*WcI*@V@vqZj+*nMa7;xCTVz>roe zykvZI{}wH_30*_)fV^opgsJZ>*=LqnFoBzOexxB$_9c~GuPLOJsp4%%fK4KSB&mnz zGsi6|j;6VNKR&EVt%&ve2?#8kp$!^rR>V?sVB0J1!wZBfukqCmL^HkC$i=*01UzGw8=h?rK@<^!f{_V8 zMow~RtU*+=A0Ld)CBcaXJ;Aq-kP%$-$C|ugssEam_&m&HT}sN``7O6P3KM4cx~H-K znz|oF5-A4&zPQYKqmX#<^Hl~tK>V10<>Tq1prnk8jTM3j6rx>eAjPIwn8o`#BXF6i z(BQt*n2dCCzx>yjoXI}27(EvRKd^0$q=3bDqD08R-@SemUK>_CJ%+T$bvdK_h^qJR zk`k746=RUV^)aq^5VQ-uw2V(|eA^)R)npq@}S|00Px`1G^a(<-$`HdF* z`c@*IV%Od1wDP}RQAqL_m>3(sJVc|Agnc*m5dy4%|AprR>7%2gxrF|Z;?4>vB{y@_ zw2&JA*-YMBbhu~H!)=&UGF)`$QsBU$1Zv_R6;A;_kN=x?b^~W2UR)t{UNjD634$k4 z-cZLvCiQW{X|YTxz9wa39VkJuo>Kg)6;DJvD>1>9Q42oeqW4w+- zjE(lLvrV~#q_M*%+Ar)S!Iaj^aZmir9e1SjBoN+1u>~T7J z?m_DKbfdE^I3AY&vtn#bV%($N=2%P!i^nPgN4{u+yAt+Z!@+3ZoPLicH8mPZ!0g8A z=BaPzz!wWd&2~oN%seHPa$r1@`to?xVLYCXCU%Q2+PChB?djIHu2~L&s@~(D7B7vs zZ%^?f+uJd+eIE=d{{WYBTg{F7e*l>GHhy?!fOir!L@dFqlb~jnF)ZmZrP*nWlOW&` z@Vp*)hu-<&Jf~C)JTBFwdx$>%S_~GnC zAtY8_Lu6CZ*Om9@PBW4-b}m%q5&iKErliwUNZ&TJ)E$+VlTL`dh+pn_ z>PrKTD%(yc#gvSy5S<&}f)gWqxiLci$1wAZB%&jHe+_&}uOVjhlGC&%w-?5Xs~J@n z0i?&BUhP3nd+SKp_pJt9HSGvhpf5kjbpYRVzb&TudYxeRUc!xOR4{s?vc%qSl}jS4 zM;iBPy_`7L-0M1}&DV}Vs`mkOHSQu%9B3m{l% zVv9qIZQNR@lfMf^4e{=8IwYL$ytOkPYeY&*m2y6;<*sex|J_Xpr3hK8(Mm4Vp8qD7 z5Rx_z82W@Bky%@j0OsPK@ThG`%~4iW8e(adicvv_Dxd&6tP?P`W9fM2>WSaOe&&=sGhH)_T5za*ghc3iq&GVmId7@qQpUc8;cOyCARVyr2yp zzfZbcBHyG{N-J2g+X#c5$d@8QAxR3G$QWRJG^;Y6#hJ=EQ*LqPW%4|cv^7^u{Zg^N z@cPh($o-p3N5&muI;&HHN(tTJ@zFpj|M1y>(h}T$2w#^|LIUm7A-{lE6?@Rrdsn(> zCXHw%Aqpex5%v7HM|-bJl5nq%<_Q22h8GnR+;-9}ZVbI4$EaJiV5;d3qh*2f@>^Fp zOeMpjxpI1wfB_$MGE2>Ppp8q2-!l)RyZLM1ZaP)0a(e*$~DK5=Han+Z*KDUG_k@7}k{%Oyg zwy3Mzs*f^9fW0R%A+;xDeU!k<23I(1p<;AXQ=c^TAxBJkC&OS zh`*#{zwNIne+zqdlxD{WM8TJrs_4(~G%Y?b`eV6&5}TIhQTH}B&q(PX8hhY^!H~mW&fP7d|PsKk2R5wdN&7+`C1cRKt9ywSRe;ykbV zNTA7?NV=gMYURVEEB&&Fp!V1H7f%8It~(H3oc9^zh~#m$3E4QKom@dl|9QU~`;5lJ zR==b43nW^td%zQ5+hCM_$7q0Rt9=iqyrb2U(nB`7oja^Hhb?ttClT_9*eOtzUIT!i zE!8t#$2gVpq({7JvtmyL=}mu|0h0a;h4alk&8fG57i>DfDEC@D>S3*lB z18z)irC7;K!sv7Yp}PoW?hnX)EZy*DH^5#myN9f0qtQa8Nk}iu98AM19I>~WWog@5+ntn0y%v-dX>dwr2GbWkVJ{olbALz;rX`w zX3xNT1=mYlzSVa2c7eO7S5RqXk4K{K>r132pH6adxjrZ`#YJ7 zN0XUt3oMdaGF+Cdkn}S~pIBKx^$3kXM3Y>F$f^2?bj$G7`Oe{$amP%Y!Jgk$-U$#d zucS3JqL^)DhUFCb_@G*f+8EA%GO!MZTHEqsG3VpOSeni?!thm0X83zekEbvh`TJx@ z_+%2s>dWmmr^R&3OMskbBy*NeI{pe#_Seex=BE3nGQ)F$5yVXqIM@krl;GYEAz7xI znH9~==3cJU;qBJ~Z#%Sx>*o$OBbZHlhTNv>9b+XZ$oCyGyK^nPG$?IK$JUQWx>a*5!F+=k@ESww7baCbgO6FBp7L zz?OGdjnNOOm2-fxTW#3$(?sWReRtBrfu+k|C(NHH8`8h7{|ofdpLA4tCmW`eWptZT z^DPXdB5yy^(!yuV-ec;0&*0quG>X9B^{6Rk3etm1FCDsdrawoqLjh$3F;3ldX8F%} zUc97(Ar~QgBbCS`Ny8ep+2&$C*P(HxYf{SyS}BENPtREzH6cD3{>C0V6IClW_SSgk zSqD)|#=Eh5k88kEaZTwsS5#$FBhX*hNQ4AKR0d1LwV;~qC25ViP#R*$>DU93l(N_#`&Qln}UvnEueB}mB4&Q z#lB3Ot1PkmExHq6{s&^QjJfn^k1OIvD8?mrlDR>6q&?p7bgO#GwRhTQ{hZ$-)%x6> zCMy~AKFZ~dR$y!hIgGcQI1>@^W;_WGx%)oO^;${p%$AV=v6>#NbJPP$XqLcW{LCM=D!7VL}7)h@S6fu2y8HFAe1)`0sboB%iG+=jmChw;|kL_sJK zbnHM0OIF%6U&r@FG=1TLgF0vAwT;KudMa3oA`-w%VX^29cr9t8g5->Bh~>mMy+~KBd`gkDh+rd6c*i z38+c7FQTCgKU#6&7V?Y6ov!~bM|IsE6!M&bL}gzXq)N{-pw9RUmwq7EAv5G2{p9a^ zc%5{AjGcX#1#@kM*V7ksbn*(rUd$)`njh2bLCWzH z+St*7IGCOuBU~g@1Rxx8mG54AO@HydE~8eiT*&bCK`MU);KXwWCEgI_yY)Wy+IGPf&sBOuhJ$27l4b8t)GX_0J z-i~7%HTEU*!u5!tb0&KN}mX^EN?5CQvOfe`&4Ff6JIdpuY0?u>h@fb72dCyC5g+UiWkcbi#*PGb^O%ME^oylxx0Cqu6-RRF9o z=V+38LkFiusU2hq>t;ZqnD8#|ok1tMcBZ1i&)~@IPCxg>6*qycfCb&G|7={62+yD) zrwGWb?Kasf{C(M{m9A1zKWg%PnuT&7U99gr(Q;^Dh!L)ky$Zu;zg4a?R}4J~mH+XQo5`!>NI0k5Dni#Lva)CyG+j33!6WQ5-xv$Rf^t|Z7jurjYOS;(&o+%h*8yNsAc zGJrAUJ9$FEC`ThF7v>n@s(ET5!Vs7F>Fjhca&)48sg#l4*U0@Cq7`jnSaix!)6AWb zwM-p>8Z?}<%=a&qe1<;m$P!6k>iXA=%I8{6ZdvzJ7zs; zTp%YZ>%}M4VOW(j8G3WN12!p*IU@GpxZGlo$^6$|hqhE(``sqG5$_iNIB849qlmwQ zgaGutJ-Ce{7oY0z_Uv9e5kyb;HJQKj@^n25coU35C34v(t`Jy`?I&-)A7<|A2*GV2{D}Sh~2d zaQ7bt8-;@q7_{m_A>IV4ET#)Od8z*H@qc>f3@s@mLjh?30h{h&!%04kb&EJl83F(w zacQM1Xb5b>UmlYDyQe>%yg4z4{WtUN#~a#+zsc+$O-`|N|Gg>yqt;zKga5&-`wMhc zzgb8BC?d%trtv`kkNW>JDhfh!h(_u^GymsRG&;_|xu-vK4#54*x%pMk&&u2m zF8^G@fZvau73kC}ydZbnA5R_wMqLtrzM2AK{JqQl&ipg+e*`bGJ#*MkMzTEgg{V8N zqPOPnZJp$5_;h~3n~)R|#RS5B4szN5N;u;Ygn&)P#1w7V7yc+4_t%&KgWY9me6grv zg_GYFN6bG8o}i8slA7#Nh{jl`MkkY{&{Snt{_jtjmupJ)~73ZJmecJ`zrGy zP;Uz~nY(zw+nFkX3q33>%!b`+|Hdvt{2$HRt+qKIE?<6LULKKx|-ZpfrB;@1k(j zjqfEoM~r7UJ<)xpRAWb<5n=c{gtaiT(Qx>zv!O;xuH72F&w`o{1g2YqobCm_snUBc z`958~_Le_84|*fc!@SNM;p=7>$bYTCZ0nf^T(b!cYGl1G1+}pmGYEoeqHXXeH|cdg z($%L=HJi!H(RNm2hd278nRXT7Vfvp*Q^vN|;9)v8NHl)IF`!yzTeHo{}OaW$CCqaPYaWZJ?#R=^gDt}T@Cz%aSZr2WTzs3luvg>y3+%+JLAj)P zqaP84GC$7J%xo~6H3~+(tC$yzRD`%P@ntamF(p%{JzfJZ5peQ-Qj}?NTY)1mRluFv5FyP6mRyR62XW;a!hbDWaWp3|ELO(57!saBaQjy5M*MB& z!H?h0#CB;ox@n_Hh(jfKy0XQODXg`U7LWuK7*&ml+Ag09p1f-w$3lA8h5K3mk6u%^ zNl?`6h^f1azp&Cfo>**zjc?|Mac%E_DBkCdX1v{7*Qaqj%=ff)hJjwSj{5;1lL@bZ z05rOuUG<){vhYD0wL4jDm>s84k&ehEt zx`9(*=uZgq7>lzqlP#?S+c~?FD^?_&Rbru@gbE#{;ti`Xd43@nfVG=k2|uEcyFLrU#*&(UAQ8Tb;i<(bWVREnYG!Km@U)i5gaol$nP_4JsV_ucXjH5@_T{jn{k9>r{TH6tGUWVSne zo~R>9Y?Y}$ck*1(g%6Iq^m5(MFzC&sYE@^eb^gSA&#JwiHd|35z_jd8;*5I7- zHE=(6yM4cCjq})&TyF7ZJ$$BMu6Dvf@Ah4^BbgIZ^7>fiR+{Hmhtu{Ryqj%KXCIIZ z!Z8R5LZ%iL9D2d0+``BG-feN8{kKK7|m}%-&95zdhB>K)TO3gqi4#&Wro9lqyloIiT zWV0_ckDMLEkA%m|jd5*{z?_{UKuIb|b(pHTVlFm33$F&ZH$|?XS8A5qrr9?D^59cr zCj7AheOWS~1W^Hl%xiRe%~q^Vn@hVYSnaXg|{{1Xi001Bz^j&Hb=t3Gc=!RO#~L^ktow zvGqd~b{F2+^A9KQ#rSrA%V_jAwt;rXir|l1j)ntn-9m- z9g6hg8@&`%PM{A@W6t#oGom2Uy&6u_(bQZ*;f7JSO}H&yP?+Gz+sHCgkX!DJk0kty zhFy`;wl@u6jwF^`;CgZ#8bHJEdDM~u|FtWQJYLVq+_ACex=`k!N+^PhWt{KlxlurC zxc!Qf=6*Uy3NfxRh8$p|O%}Zb2MG$jVLW}T#$G_KQaO%>BqP8jB5&N}yLeA(rb5zo zA$x)ODxCJ*c7aBhP_z>ns@#X(ZQL)#2XL!tEa9gFt&Xl;LMZ3_5lW@5@cy+sY&$zh zT62R^hhrKS-6D~xs|Sg&R(So3#)ND6#9awwdumjjSyhwM%4bE@m4to z8D4m<%45T8x>(o-2GfVo?6&v!mWHdINltRZAIaNXpT+2$zsmhOpxkk~o1w|j+b^n& z&kM2G{_xkqIu8>VHySZtc;j{)RW+O5aI^@Ahz2KgcJ&(Wt)G_zmdxnL*K!L5ZmYKk zS5}J(B@(NGF+2rKxVm#6C1YZYKO^t3R*T}c0A`b1FQqY3#yW(Lc=(&|qYE_U>7@5R zkKpR|h^H@|fAK{9!hl24U2u184;$)xLaM= zo31W@pz>VY4=(ZnyFC3M1fC0se0hW1u62=T{3-zEY34?5mXU?Cr(Gt0E7rYu z9BVTtGm8FOzlNB}o$Rkz2+(;`<=6E()1A!BKC2(qCulp&AhN6`_Bnnp{@H6#9UJc1 zV;U?QmyT(RHrdm}#S(-t%nxBXEwwV|}TO)s$Y9>3Gbloh}ZMalz1ZFJfQ-s}!`a{tk#)~m4RJC~mnv!CLInWl%}tzPPN zZR_~VRa}!TnO|w39ua+vaLPKIKyF3Q?7>ypXvt(gd8|6MK5)m8q@K$bt6)xLwc=O; zsfGta88h7ZWySZ1ke#Qod%~JEjv^lzkB>Iz4SfA%dszlEbldVKGdSh+ySME1a8G0` zALyMU8LDs*!)$3U`i%*#AoIuv|4HugYX<#7oUmixF?qpqQk~pqZ@SA;xg+Wg26cEM z7ShQQNy_0`S0lOm)XMC zHq<5${V|>`bX~aVnOwApXz_mu8Q?iMas>3pFzXJo2cY;!{+tG$)t5tUq28{Ru6BXt zz!t#wB89K=G$LAB&-Xd0lxr;|rLdVlM`rm@N_?0KilwwhR(


O-Px*=mhdV<;57%bqez;!wE0di-rj z0;}XoOIrDEUy+aFllhKlmmyzeM~NHGe&p}cS&hK;%aqKmYywY5kgk3WT?a~v{*r)I zEtL^dZa+gv4Wqe>65amS3X{Xd`m&KC3Ba(TF#{;fqgZHLSS(6Ys!0Qu>F{BoTVG-$ zL~&ytt!#85rD6TLypREZ|Ewp(Aj>)TMv`VsVHmY9VIRusF(Un~9;IBN>1||M8KXj6xMcCeYbR2C zD2T|D#fc!>61h0R4eY=CR9 z>DNfgUX`L=$u*DB)b^(zPKJqZ3{*c%A@3_*e5hZ1692IwPt7`YDPe+&XxWfG-thiWIv9LQ(%9{O}JWq2e?#e(PI;HvC$mzzS`@MsyhzOYR-n- z#_X%9hEfL?hwZYQ$}0&OYb->y3e#PG{ifso25uyN2~Y`P^LALYPKO04X2)Hs+jFmx zrN+nJby(o`>6Iwz7e)?=j)z+~5haP$j=55gjUj^2DmL~cB$5{r`s|r*dV6C#$~d*8 z>_}bahPgc=G@{%3SiM9wqu7ze^C73t;GRDf>5gsu+Q$c0V19wUq^gnL;=i@uV|?V5 zWi{aijxiFkGm&=0gYK-hR;5xzrc>f*g*^@8JX<d;IoG-Z#cmZRh;h6)JL=?8!`VT2si6S>ilOO@TiwyKX`lOd+4W z2Hs+=gnD+m`!R(~EpUVwVqgps4jOwp(xE$=l`E4lpE|smPnEKK21hknn* z7*#2luYohR6T$P1MrLm*N3z_2N=~5W2-cKNIbMLHS0b5sqc7rYNU5cF z0~JM(wAnHOG_(d!r25{~tMGq5?Rtj>hq>TsL`6qub#8bafsg3EGw%7lvFue;%gSeV zb}6(8HB;|14B~Nt?`Wv&hCVdis5JvR4yMuAk{=2Ay)S<7wsWM+oK8zj zbCS^SjLW~~djr`ap(y0DL?OS=&imus<;?!WE?i&*p5oykVL*4UwS%(+L{zZQ769b< zc^W-biQes~KzUG5oanN1x4UXNyUqw>;C)*2WMGYt-yO?Q|{iisx6 zg2FER3C)#mQT>iN^+Ml;wtv017n$cev#@=<#_Lw)vA38APLvKe*a>I3@OF8|do_wb zKim2JxJ2hCzj1dSqD4XmI`IVuVLBbxl5*Hik@;VGAw3I4c!mmLW7t)1rBCNM z6K^xzN2%_mZKrFxbevp5`=O`6ktJ;kCY0 zH}B*{a&qlL@$-gFm<8D@+PnsG88sSU7)LJifxYkyG>w78-LuUtKG5)frWqLTGvO0( z(0L7r;->hy>#fz4HVrD5fXSHn1{+PNx9>GmbuP6gU(>qB-e$gmtm>PIxZs||FhN%O zbI*q4Lz$lSX4umC zieE&Ygd2BQ(YH!q$oN8?Lf#r_OB$DqgD2d<38&h*i+S0}J3U|t4$*FXEEVYtg(RG@@XsZ7yZ5)OuAsFK8kY68a!T%`;5ob3 zR&IhMj5UCTr?9UCxRdv6v=lCwuX6pV>pz(!(KJLI$^$L5L7PLi%|)|q0;g+zUSHj~ zN>OYKe$(a^-x>!-7+Ppl_GfHx&isZO`dkxHSDOQbD$(ci1p0_OBmC8M;aDc`Gsq>U z{0?ONiUUv{Aon;qoo!wsxsDA*9EOo%#*wa^>^3fYRtr__FBG&ApM;F$%AeE*^9_I> zW8ds1GtxG;k`Div+E`3{Nt3>L_2&Iz^s<;@k(g3mMG83B^kaO6`AD@wky^`{^fq=| z{``;ZxiV;HGgfZ`bfodFrl6>7=_RJs*trv178PjV;tnb7fS1B5CURD);h*>H+;`4R z4vI;Ew}@Ho5Rc_utQoFaqQcMMf`mV#D7ifhfn-#$wHg>C-yJr#J+65vp^}RI5waB=^ zehX|)&{pRt^g2*WW*nMmW?mNR$v8@Wwr*j+g^$mg5juf-ugPxq=*6FW4DRKJj8bAM+0!+_a!D~04j7vPqvXcPn}9XV#Oe$uilZ5Tov=g6x@k6I*jM> z-rkIr?y?kf%a&r3a(L5^6qHj4PreP+{;>$=ZHz$f;y2TWh3%ZZKUlki1O`xkhJ_Bh zTiSR62G45;9((&|;8;8mmCiP!b!H#Q#_bft%NYH8&`JhHC-_8fl0aU(hls1h32$gP zqP<|kmCE&8;BVQF6=Trn0o@Y-*Y|rN8$*b;zP;(H!Jt33Yne zd|E$8Gkb0GJO+O(wm4Ryg=*!f#ebw#joc36&-kJI=-Vyt`Pm)y2HxYTvl2PWW|%xl zu_2>eMQT&w2kzL)C!FoKIM~3$iEop@^UDJp_)n$>G2~+B3=CTx7^=~h*RJ?Yves`1#eAx@+!upO`iv{k!C#EwK`y> zf*79Qv6+reqWHle;%t8BIw$;V2XTJ=a9(?%Sa*sgHr0JMaeIekcG@L|Fe2DjFMHG*M5Gy(T^UDE;2bbe9ino!0^V$dP*Q=%BO1Y*M zimEeAi&HtGR&^>Cik`=^^*7iyvow~o1*U^-*FL_!6cS`%5#~7_g2XY$Zyk?sGmo2h zGMF741%NT3p}mrxgumQPP;e`5|KS1j-`1jW6vAD9x}*AK0r>Z?WT3Jk=bxdpe%Rhp zRJVgc_o*@k<{=B#{l=`-@4BF)i3Ky~W&d+3z=}YsU?|%HF2vazz{L`@Wzta*JYl-v7|83=cTWS8a4F7U}F6K&W zD4y~O9*f~Khy+8O8r|;t>uAiUZa+AY` zXoL9gzETWHB~T%+uC8tl#%)wzUmY%`z%gQ=-yYLKtji2JA^wcxi_yu&dT&=xHwFkR z23|!5nn(XR3<@I@7%=E^PCr$K>W4RH|Mb6|D#zCm^0~(<7s|!4nT-#umO_lx$m%30 z3|Dq+yf4$ zbk6}nbsb&FxJE(2kOBRK%WwAK1s5crmgp*aIXJt03w&3x+!H~eJ@T3FnKRJc6Z^;) zmCA)or{3rHvbl(zC02+JWCI<(B}3Q!1Ir*i1?|5ae?T18`fE0RK**3aZQV=Wsz`oY zH4k4G$RH)+mER@U$zZxr$$`LbAt<8(7>`HAa`T)Y+bO)h-LKR%;wb+Q`Wnm4STw#Zn! zX0yC@Ozx@4Z-t2r^aiX;TBJfovl*oL{6~a{U!Sh+8^$rf1;Fxup`&qd6@h|X+64v^qx{ThLfV+CQvuUyB)d|L4$TYU{IUGRp*A1&iq_UM`~ z5d`JHvDLtetrX?Ps=^C$^#vxG)afh)BIY{s_`tlBTh3sbjRy_a)h}#iM7*KZ=dSjf zj<4ia@dq{A$g>#Tvk+)W)@2a67q1FOk4|Ow7h}Q&$3In9(!O62n`sHSy-iTNfW(X| zWCoJX&|+&w%x0gT#O$gr;39r-2(a0>JH7q*HiOIC&&n;Jil>mwGfd2x_>z==xPVma z<@*~-R~f>wdAqq9ur-OC4?*U`q=M%Zy8q*!Ro|V5P!F4XS_ZST#(a-^gq`W2{MVQ zW!MIz5lx?768Y%@EUEQ-kpqaE;0kkyRT&5wvd(VnCpH-w+dH|~No_GmWZ4*iulhEO zJAM3()Q{~!^A^yU?($2WY!kv<^@d!GQfAbEMpS%g%P-!;M4;-1eG-xF9~`-6ICkp&mnR$vwahZZfmx$*EgK4yUlxC$Yz z9^F%2J~CH%86&eqi z+oDek;2uVM((L5^!cse_jL0_6IZSVAQ#;F{c9j%-3DdT6&O5%iUOERKkwD#CQeU7A z^trH9ezDUd_^L^iw}S`UBj=H-vs|O*o1Fcl_xLd>dS8aq7G+`Ia5apwhMPdKkhJ;GkY2@_;IOYHpuhru+kDF3&*pTH*~ROIq&4OF@or zuG>n+EPeV{7VS44raOD#5T|#Ku%IEGq;0!RDsv#~cE?;Oxf@4~hk`>Lwc>vWaTA!7 zS6e_O`Mf`Orc?2bIWmBN!>Lax(;)&veB0ljgaYng~UWl4a!Dnxgqg^e-Uk^vl^qCqs{E zTPI(C>Iz^%t0Oa4?m;(IDIM4NLuWOeWmT<^=HH~XKqZwKDd{gSmnKOgVP=pnSO^(E88)$rtG}Dt7dx9tC^x&( ztcUjb@Y^5Fr2QiA$n}yi-wC!?$8Az7P%6ANT_&%OpbN!%TWgN}fUDP9vqj`I=)u-= zJZ9~nyC41#{IVjYtXP_d3EutGAn|?W?Y_2F;!QMxb;Ed(y!QSkG~`^KxM!!@&J$T2 zp=84}gM?{CDAJ-pk-eT9IjZho<8E(D|8Q3k;B@Qv+uvw}AC4+>X~8jH{GW!R-l&6G zvv8VHw%g7(IsXJcsu1}k>3Z#`a>Fi_-WmT~_*j?ul}$M#Y(!oT97buMN>&4~|6|lh z5X)w!Eu-nNPS4;7EvNSaf>d0!-D(BqV9U?Tf5YJ?p2Df$8}t~d#I3D1VR!W(Emj;f zAkrG#wixPSM*K5Hui?~BO#7s5KTU5rH$VLpj=#Xob^>c2KG6!5FA7&PYju3hTjwg? z7`g)O@Hrn7?XaZKYl)C1z!2x4+H7hE!d^O!De~JC4#z7m0F-C2EdVKEDq8AL!tPP< zQ>g*(i^JK>W*aDtt^m*q$jjkQr{a0}nT&^C-Ie7pYbTV=gb zgVXFos!o&ro4ocMwrL1Eys}y<0CoLpgc?p5&#M_Zmp;H9C#nhIyhV%+M z(9B_W-q7nqMcoqpYZlF}IW|T$ZHC|8$iUm+OkfEJKJN$A9&=T3xmvXt=-8HoJnQ+ygOom z;vf@zsMAH4dq+~^Ez{jf)j!Cp*W2$IEn{TdkS<_)x$rYS`g=sA{#Y^8$8)lIJb!OH z#VnST7SzxsEGrK)dL7G7sqw&FBb?r)d_M5)o#Ik3= z`R%>z(Ov`~Bh=x>ig)Hnr5N8UxS(htRy2%tnIz-JxK}=4Myl-EYB!7Hdg1VCTX=q& zUU50x{OtOa!g{;iA<3B}^(BH@WF&o1P%5E~jZLj9ui-Sedn0(Fto}#`02QeU+oAHb zP!?(&kEt^AbQ|JpWp=-GdxnD>8|Yt=dRP4tqeO2DomMNBcqw9Wgy?WPm5m5h1Z<_o z-CS3b1+d^P9kwsh)hX}B+1OAC)twbGod*c8N8)`Z^+;T9O|v9csun{);Z|t?&X~W% zN~xspf>eIRpt3*#aCo#b_6Y@ zsyx^FyY~<}li89kmZQAo=i*THePCGOIt|?g@$w1{c($__!g)TfA~p10huD73lQA84 z$!lj-cGW`D?Tl_1>p^d=y%5cHD3JZ7P;hpBMyVVy9j@V&22<&uv-OfzwRPrj(3O^% z9Ii~0DST+mYwDMH5IV7d!|t;{ z%|AP5UwSGaS^L2UF0-yGdYo9JS4M8}{!3X0pYk=}mLILCgKXzA!3PQP1h(G8p>W>k z2Pv$(x^3+~$xZnSyW-bNylhs9{GL2Wln%Td4BND1WMt>P%2!cdfuOUV)q&f4E(o1XS7Q7hqh0{R`^RlUQHSLp3l%>qy zuZ&_pQP>$dmDUU(%`j>iYSU~g0B|ujdnNZ}P;%mjVVEl8&01C8ENsT0uY937^l?V2 z#K)_)ym!1~al!eiUyTQ1GI`7Yg} z#(2Ms?KyB7Y%QLt`fGB0CTpeb_DtaVrx;Z94shpW@9OO0tc|w1qXd(aWxnj`0=K7R zY3n|O^L6w0r_Z%K$ zVOm?Y^x0Y_lwE0{TQrSF<}RDQdYbP(Hz6H$K(5VZl!%xw`8>VB;tc^jXY@<#S&zJM zsxG4VRyM<9fu{W}p98{|agIq=1~b1JnO!8dT`zUeZ@-!?DFa=rGYK9l2Ouz;?}FbQ zL<|`B#_@2h&xHf7GA@hb+1K6WdE{J^h+w^E)7I@veefgqj^^s3%*ShqwKV7N5Re&6j8f`JjeD}U?VrjBxCR%h?U#!lQmg>X^oXvgP zUDq?L>2lS%hGYSi-so=(2A15K4msMZ6)G>}desK%Y&jK&X9pXFw{~|eg=sWik)BW6 z$fO?XCBZ$JuH?QCH?N5v@>46fF~b*nfwZ$Z$TR5yr1ZgO9If^A^sss8pO4Qnue%@v z*gW_|@>5t;k?0O5u2^?|&L@eO-yw^b5N4UPUk8TV^U)~FITOfK=wPyH+%v51m?70a za17L|??k{Sp3*P>;L+uL>tTh(NaJ9oZkk2U93Hj zcjUEwnkc9-%PyF}$6~ZN+uKm3&3WM~I;G{5XPzQ>2)KsB(i82?xfSKCuoF=DZU@8_ z-{%3Y8_?RTTecDoea7;7U>(+2JayxXHv|K(-+oJh^M_9EN zn#tPp7p}p`lkj%>KCLq0tp1st&D5{EwPp<9lKr;(1R4cX zwj7AUQ^|6sKWMN}Lk7?ZUurb_GS<(sGiEcJZaR#*WzuAz5#QtLN~qfr(0^HA%L$yL z`<)Zwslz-ccs^G;^#%VF`DBPd{zIiRS~2s%P~k~&yILjpgJ|K$?Da-$I zp_s)aonGArIPUVES^DibKVK4>G&xk`u7vur~YED zSIv6m^AgOAFt5!G4otzXR!#DsTE2K!v*`3pRj13^z8ZAhJDGSfO~4qA4JTVx?%gWR=Q@)v4HcM5@FDyyPjl@ zO*%4)T9p=uC&?SBXKpfovpP$ zLvaELaNKBRE~T2bpx$U664kkcd}#P+VZHlD8_bnXx8C7$e=6)bmxzUfBP<>m7WSse z?TX_0>5(+g&zg+jgfsmdj%#kSFbsHtD}&Ej$CuiI!3pW67kx=Nm70_2E3?y03VZoe zrA)0>64e6R3_6o6(*y3r#!&xm zlDKyzv{Cr)gm_HBj+b8g6?6+CWKQ87oBLWqidO)37d=nZ{%G=s-(#jNLM->omtqwZ zb(qPpu1n?Ka7-OXJV*;k6ckf2okWZ8kGQ-EUZ4q$WArUN;=nDL&45x;6S*TfKi0K* zfOHaA=noip z=8zZ>X4NLCs+*3Ms>=X{+heG`^}ANLw@s{C4&=7<9t!p^^tFG4Oim$=Ry1B?Hm>8P^OKn~E?C-7hKt_H4z_&5}(7iticdCTvf@)(GKxL)`={9?u zuz(C<_ZV)=X$h<3&Y=jVDs2^EKm3EM!o^DQ(c6u*22!J!gSA5$#4T8XSbLn=9lnBF z2Vbe=^4V_3c)WHWT||=f2HEd{#V& zokQ(D;=Fg|-zKPzC~R=HV_K95MSaZX5EQ6U%q|-H&T&kBn8x8l%v)*pkHMXPx3d&s zp2(x=(N0D36w_R&685-KQtjUylDWH_qx(`tOsW1LNz^d9o|yR}y?(lLqPFj`si(~F zbR>6;i$VSS;bU|5#el>z$B+wj0pMz-o$)|WkqTSe*zk*r!f2in*^r1+^#9nI43E_zW9}CNG{7EWruAHYOdw1MA-pVN@zrvfO zI_U^69DaYtUc3?IkUkZ3E|~YJ$r0#wx%;6=hXhkOE^0&err3P^$GGvvak~3#1U9CL zVup)*GJEmTMze6a)hL*WfIC>(YqqP8kbJgu_4rr;i3T#=>+~#+@?e%2b?5(-_e|&1 z-Ef1%9`56A>C-ww z-seSv7#7LGsEg0oW0?UqI^jlX{2;j0wJ7>+om%g}33V$CahgxOEB-wTYxc2(&Q^H2 zEqsqP?{_Q$kiJCWP<3gLdfq7V!KAnicSBwD7{X%1z! zC>j?7d?2}m5PY35-Wqq+Y%BU#9I#c3hK`k%qxBxqVxzvPkcL1%62!i^1? zwDD0)*-Be4JaonDT(>bES#HSX5#u}YWv29zC=VVw1?B5MpPgb%7R4o2Zhshl!WWwg zQQiA-RR_*V&KBN*blEwv zMDID)9is^RZg1js9kj>O8E6w#TEa=&ylqT|qP#cMocKtcdqew5?T&+L@;UD5@WT>w zTryBy1Oq?^gRFp4yc3M;=I`+E=2lceE2CNXrCnZW)jbaDhoU~Ey;#j9()5g)X#PE z8f!bhg6G2FOBb@N8`|bV=m<@Y%RFU3^@EMF%QQ_ll?EytIhA(S7r;i|gBy@%n!mo_ z6*sXKs!^0Wya2j4SgvkDzYdBBk`6Z*@DroKqG@G2R7Miwsjc3$PHCxlrCm0I$5%#k z`>=?_Uy&9S#6mqAjnKs{b;g#=oTRAFkxZ-+cVENfD_oFAR78_Gg62+CM?xW50XnO> zar?$CWYlb{r1;2XS}HZ%lc!tdsWHO2Oc}+{IwC4;3L|F$RJin9DUxJE% z>N0)(??D0XS=4pwc&Xue>a#zNK6Z8}+6=;XYuau;Bw%WD7o^|u9y|!2e>TjEdIZ4X zRYl4X#Moh;nX+1_NjDKZerqcGF=g=OZj92LIc!MkJ~z^2+_wmlQQ`Lumy~0t@Z-=a713M97ujdf_4{1@ z!+I~$!dTqL+y2pqfnTVcl-6t~jpR3w9*lbAs(t9)a!<7Q8pxs?eT`_A0qSdYT zVfTv{u5?;<;lavFQhrFY$rWIO2(F>K}sg7{2J19Fj}lAU9FMX9AJlm_eu@)5O=7)?EXruI*MX|=Y zgTXi#ub0zrsRk=8%srvOco;iCd!~3BsJu9c*mvUM53#Z<4}Lw;JXi`f%&aa4aAOqmYeg z&2JIG^+t6F-`5WPIT4^@;$@<$+bgyEJhjc9%rM_Z^Xn@^5!*w|vvOu!+FXxz9BpHq z7m1L~%bL>1-k0d`HNRpOvM#cqAKBcetu{$_EEM#F(s?~7)lS0?c$0Vy>Agh;8T5q) z@$XMBMD4=YMQ9Hv!D-c6ry~jYzz&53ojJR*qs=JM$2Pt3lQAiJ*n9LRyY~&22KGQ6 z>65UY?J%F%3Qjx&|A2YYRC#6Nb7~;E^34`o3%L5Tpd48Rrc07|UJ)PsCXKc+&DLxW zZCVH76WL%~Xd3^7Vd!*sZ?nUIM1lj(A@8AazFJ~vaT#}aE7FL9n&_Lgo@WiYOYZ*e zcSW#GSDX>ynDY=~U)wc`n^frO0jo5!?I)pgQ=VGT=?hv2OB@5i_btt5eU5)M8II3| zYRqJ7<>@qgkOJA5fObFc?fKQ<6Ot=1VOPV5zAkijn4Jw(okRV&6ER-!>?0AkG~t`X z!7nEd@Kf$RTBl9fhB|Yptwu~I&?w)0mj#jpvY-n!bW#k-9-g&sN zLwZ?MQ$~iItzz!DcG*{46*`k*flDIQpbWb!@o@fw(M1~gx>QtC)7Um;I@*6l)^k!r ze>=k^E+q-~u>gDgmDPyyNFlcH;7!89;SbAtT>W0)fy86!W|d%+fOO5X3)Xv_*Ziad z9A~ANi_4sT7=c9rr(`w&kv`T2==lsY+{*k0p2iHLo82>Tw^{C4SB)8;OP_VzdN*^p zdV$^6g^?^ozf#Iz-jd!kmX%nhJ`gy!sTi%koY~9y<)6PqLGe_)6Z%>lO0@e`NMXW{+xHUM}Hi+ z)EuJxpt)Eu3VFF_9du)Qh{7UbR*u>GM5AQfq3bNyGX9}WJHhnO>z(b3zC$ek&d;4^uGd!3V9;4E*Rbg~i%0Bf zy(l5tOT3EaWwB5Fa$F^edUFJSrhERqrE=wP9W^|DZ?jbYeyg^>p0|RpxrAYt30OQ^ zN|G#-)ecYhX|+uy1zPQIs9|e&VdIh7ak%(kjjx)gU~mVyh0MA8U`wWqIiCwSd9Fn3 z48PzhKFUz2(F*8`Sq2~0fugA`nQ0!);Zx&*i!{jJ`HNW1hn$X=kg0rX-=czbw-ZJr1Nu|-2)OaHWP#cp=5-ZJ1ji$nJ+|2`ck@wlLApY1LC)~D+ac5t( z^#P|RDmSNR9HU^Z8_RW)sC`!5dDK+}mmxz(%&&Y8nZG*uYr|uA)uK$d)8I8-YRSv% z0n3|wbvF3%+IMbOygWsZ(G}Hc4oN)0{qz(Iu>1oG*m!zBT=%G(Jnc5dZ@Gf0t9%tM zO8TN2e(y~-FHat};z+_(sjipcQ6~^$vv&!KiP}`2+po)71l{eMs&>?;VhqWRWT36? z5p>giQ&vZA%>9eJnuErN8G;#2fFSM17KrgxiD@VXzLcf6>iF>Ze>gaQuv<)A@?g@7 z9Yb3VYyGc6hJWFn4=FcdA53iV{8`>TUk_6Eb+=G%u z_f@NfZ7-OWG!)*N(p~=1kKQ!d_;zZmU;tAuy=zPsBPNVy)RNQm`+@yvj6BypZq8Wu z-mqKPS}l}^xNQ^T?ybJhjvF>HeLj~xJEu+%yZN4*X?RP}5;eSDfoGp~u0R*3z^Q@= zNNQf`E&+7n)w)Q$!tPi>=;g}zsh4CJs*cKq&r zmf>xqi!@Cy_w5(pV0Q#IfoLQ?V>SCpqM*NEPG=9R;Cq6pJYxY)eG0|c5lxPHU-sE0nfwb%s z%n?5#)C$vs*z~XS<|>D>S?!gtwJH5Ic#zHO`7R;Vbvk?fXo#&{QnZ|FuE&_KCan#i!b3O$2i{7MC9?9(+fpaUL6zHF9+RdGfKW%{lh|8j6agzQ*gkbke@2*Hy=&o#+& zs&1Z2X*uKar@lmbE~X7T>r#=9a|+1d>j$WDHt$VH8ly#eEUjxN6k{cfJBoSCybQDDulH^a zKL(4cp>zbhXS87*V+Pg5G@T*gaFJjhT>VLZP^~2^*opQITU2%5X2^UtEz@`wZ%XO- z$C+aw{QR1&NSjKleu@!Y`PzbToIqB?dq`y5ZZvCKEJsp0lfDKrI!afo->f>RqD%J3 z_q;t4=_fwFDyL?kJjifyZM59=e)CJbQ^du_+J|BEKP)#{qLGAco=b0thC3!`ZJ4Wn z?_0_^)kv*(z(nG)VHmC1_~Dwe(o-$YY|M{DvvA)M@K$>f+xoE+7QIJBEdA7liHTQd z_uLft?5O$TzS{mJklA%_h3yHn?V-f?RNzYY=LiN5mzxC3QpwJBigoH@W)*)J4^K=y zQ#r~0^@hF#tT{OQ4U46=nWp77Sk{;WeR^pBgJ|Yfbukm3R;<0{!KWe_sn1#`-_~|9 zJ={yyVzoxF(5)yOa!lAc$orX=F*YZ54?qA01jEOC>(|aaCU;2=IK9-7Rj5XMgq))_&_K zCQhL6K&YK&qC+Qo{le1SnA{+Npo7248fT)pAw>GxzLDRW=pmGk+K^NN3P=h16SSWs z&x$Cyt>-V3_jSq);hD86U8ZS5sDl4eiK@1m>$C}^GIEC=Z#`G^3Ryz^hxJgcaMN^0 z4nFn{vMZcEzX)J=U`ETmj7V-AOI!y>05#!hJG~V;_r~^~qSi|07rI2mlU`IzniDq+yY%z4GcbRU8^u@Di-QSJMoHKREYOyvt zh1*if-Sb)fYBFDCBYFSJX$ciP%42-zHQ7y#LNZ6l5_Ztn!fi7f>c4v{!D8x{JmjPXA{@y}ManF#%n8x^j@ z#V|(y->*eKRo+a?Rt5eKA^N|5Ze$?s|7Lgp`-6Y&L?iY87s~KCcBRt)@-?h6;>q5g z9v*C{a21*%zJDTw1l27^>dW8Yea|Z@{$GCq1_v#8Q@qk6vv^!h0-qC8#+__(W@=KM5E zflxyy$wTU_qnb@FJ*O6~;Trm*wix6_Vr^f$dNyA^TVmAIyUlJ*mpT-L{j8l>q+lsB z@8EL^WTx#C6B`j<*dh);`4pXI{`uKRrJF5uZ#;J1Td52z^7S@i9u?@ZVHGUu+Clpi z#@uY#Jy*~&g9d^?c0I;!(~RLQd2d+g$A1(V8{K(A1)WL53NhA7OvKH!n6Q?Q>1AUJ zInrsL21T!vwoqST4E<70f0Ye&=;0#< zKQ8(E?7suB0eQo7Wv_~v1S~y&b6V#C$IJUI!(n3zTf9M>cMm+94P}92C0}-i;%AIr ze?S14E+Or!@Avw0+UfMvc3i)7G!rtW-{G9zh)_c7^Du|+Aei~}G`$eD52{R~dV?&C z5h1vM|EZ7!4i`Y9ya2@?E5XNC9?1bLrJ&B*K@B|Hf|^Y>H^E34`O-lo!e;86SWi}9 zsS$ya^Q}HHmoNun3fuXzy5u{DN{svncZRdkk~H_Y)?a%~%(&rEa3(yM zLmB-i8gM19%&IXS{3v>)uVC){V);PFH#b0_LVw&)#A-5D!L$^hF|ZmboZNUsaV#13 z<6*u;Cn85`0X*UAz0baAscbNl!rQm^x*Ga>JX^v!7b8t>#?y~p->xx@3h}uct?#)( zbgGd#*=xLl8q4gQra!%5Vv~%^sRiPur`yF|o7LZ?tL*OG?B3C<3b_Opq+bB0@;*cz z-Iwk&*P@A{G(K&^{KCYWas^;scW8k2n!FT)ay&lV>YTbq zz>ALL1b~sn+}Nt6Gy^>Z{7(cSS(c`p--4>Lf-2V3NS2o?gF>bn+3}stp?drl3Pf$a zUzu;4lQC$52L2N*f`c)sk>LMu0si(uA>klj@0S*n`DYXhp#*r&X)r-ryaJw= zxEUkFO7qpcx)?X_7ec5JQD%Lrw(@|85YnnKt<8KB6=_{T;8X%&M!|qW;ddpT8?l&O;%lPs
en6h;5Ol8IlsL8IlG<5{b5*Jz zTSb{Cc76qeHx`*TkM3fm>g^HieW(*YRLrp;;g-^?#olMYsn^8k6o6B4SQ#P&cQ-!C z%0V?#M7Fg2yCZ34rsCU>i2$@W_;%R|r=%`Wb?#-OYL_5|%gm-^fZh@v%mgsavM8rt zf#brjb$pBXy!z(9w;1w^*gxR>`4rqkyWXD?UOmh8q0a#2rh-|$bvkyI`eWN}%`d#` zV*~+COl_j&##1IFI#W(wxPnUaeV@wSxu%oo2(^z9qB<3-T-mxNCd|byICYA=laf2%90>1nN{IzpjVU2F zct%fnlNcW~MmH`yW46IB8_O&}&K~VMYCU7HW)5pN2j!jKd{1X=dFYmGK8PXTB-Xt|)`jN2tL??N*qhnWhXgJdu z@jUj4kO@!44_g^Ri2`$E(L)c4+mk(c&&@XB?;LoU&81oAaYn$?5Not06JY;DgNQ7I z!R%!`v>s`9`nCmJqsqDCm#>LMFD%T4&s#@|eRW)F?;=Lr@8R;Ak%r03@y2RTdQz59 znXSn#c8JttF!1MKrFRWC{?H4jVx8LXr8IQ!mfaSdvg{EVx3F|k7Cnm57b63>b%wmL z1EQXnFO1~f?kBWMi5pr?2(g_?(>7WH{^#g`=_;|H^e&lsm#4-L5}o>>z?XAM^EDJm zg!7yVv|XZPvbT-vI}B8}z)0H=l_xQx-8^PK7T%XxZ2Y`&1|i1B>5XXkg~98Pq9gpw zS?!WH_Hd~m&TM3u|vJcJ1PcsvlbLUEspZB#{k!Denj?IDwmS{BGH9Z^SG zf|gN(YS#(<6A#jNHcNx{d=fY^YyD!6R?;$6LjGrx0w=KE=IF zP|Rpk{J{)~yxZ?wndRTv(LZ?doCzBin-3vM{}em;_;>?@ZJdBZ?6a=19>c5VSclf* zAsGATv_?M7R><2OVCQP>i3@+)-dLi-IZTuw@$d*2MEf!|RjBbE z8hX^pA$7gizauIP(~-*%<8RmyY))znRITO z#3vnsGNCnxH?VF|+krO-O*z)WuI?WyCm0>jmdd3E1B}-mZ3l_3d76Mk6p^Q4iGh#A zA>=;ZdSUT){00Z^2-k%zr7m|aUVM0Ivx>4WWOr7&`Q}(FfREVS%y*RMC#ZtBJdt@T zsacxN!h6!zyC=w)(f*DX+ln^JjkgLrBE6UQHy;Tz3%i zoIMBJr*!7dyd3wvD#3Yo^lh7g4XMbKTydjGiEq%zUt`(OFS0*JJ@aB_)~eU(K}o0P zm-uf)A$~oN$dyH3eh9g~Q7!(+ntRd^xfBy{sL3?e?~XW`Z35%nd)gDbKD_gny9VGb zcq8PIz{)t1I#jhkpEMn1o3ZNT{Z5GUUO9wW~5i)&Oh z6Y?w|n?hX@<0WkNJ&I{)YV2HZPvTEI*If(>egU;#0NFj2@;E$u^8%g453 zv|h{wN=CyvAh^=?uB*b{^o(tp#0aQg#hah8?Ei2`q@_;US{4YJ0*9JCHGQFvDf(6guxgFKdEbl6;Hib3m*y;2nN0$(PbS>Bny zt5wz$+87pT2J^)l5vQ;Zvz6+9^K?}H?KGz_HsW;Zxu76>EX!vXAsh4H-02oPvOfv* z_=KBa1N&}&{50-}b+c17JIh+s9aE;AxlC&S%R6%dcg3ZSg{XBcuA`UALhM`^qMjCR zAbPV&{tttjys+}>N1*Bd+k7lL{7v`C zlLk^fSm9H$i*hL6&y2(ZFb!hC7zVL`u+maC)1egj)}J5!*f=?1?7n6vrG~wzEGE01 zKFL?#I9@VT8fkryg)qh$PlgxVKo`YSE#Y=zft?~1D8s@Vn)$EsjYf<@e&mfH#l{(z zjrfbP@LK82pJ<$N#!P!5kyYf}kG}A2Kme_+TQ3_1h!4w5&lLANSZnH3(0H$yq?IsR z_oLCCnvvy+UQ*|o915x|YEC3*H9^TsDtd2ynf~Lf$S~P|Gx2MUEA?; zd5h?@#jD1tNY1B;coJDkY6hm-D ztiSPaQ%b{#vuEk#Y~+_wj%yp#e_62o5(eD>W^x<{F=_#adK>6(X)>|WEvD-2hWoX`qXIg=8hG0^HzEOJ1aL;xTfyl zbJ?p?d2Pu&%=yIU5^zHPK{F?(j}4+1C1jvq{k07Zs&&~|xgLhzD`Lh~N@>OC zv&QyRC6>%ygj`Weyka+cEN9GDF@}c{B-ue(^xGzR-!^Cu{nOO!N=Wf(BD*F$rZX zP_M?Gwp&j#9dc51d?s07G)a)hR{qQq;YuMn;40_CU#2AEPC-eT%xg=c3>MjXR;Xms zDE*$FPkQOYv5&Iz81f;xhAu$iU87ALVw9XxZ~O7vdn#_;DN}5gXbh7{Y9;Esn!#@@ z8IM79CM0s$?8;qyZBOv#$3bWLR=RW>Dt-hc#o3}&KfZpn53RJ3EW>Uo|Dxz1(;rQH zvl0;;rfN3Uk%+NHyVmlH(>21eBsR9rjQwznl+XLl!gqw{9r@14yKJ7!Zy~;PFHMTy zVVA|Ycx+o`y6YcpT%@@}x-w<#>>1HWY5!mT@VBpcAU_ohx6ETGyPn>|(F72VO)cTa z(}dTIoY?K{B6J_?_JAW2OKrctDbJazIU>Z(SxIZYQBNO)ELRkGo3RBL5->fJk?}-~ z30V&b%1p~~@keJ&*xM`tbB0&OF>lpXARR}(uE2X2)fX;n z7|V5)KJx3J;$3JALdS|AO9BDbmhPXZmTICu@S;<1ZtgZGx5$goc!p50 z6K`@iHoHdzkzbp6zXHe%(*Qt`9?bN2S+d-@h$J~p^8ufySI#&)YU%-Dk}y2)6;+3W zlt8=lGn4@VE`!!#m>C4LrZpDUpFp6eBiaU#M|@Xmz^tog12j#C*g=b9hDBok@+4R! zjQ9AgTQf^~26^)ik`a>;0g&6bifILk?l9JS#jnn@Ucn7*=w8}R`s5@o8^z?%Z3zv; zbn*G_wBhnKIdK@kr>e5Hn51|x&O{AjWoGS-1eNyvbt~~vD>T^~&snT@WIV1~UDZ!u z)|Q$n){X9KzDTU6PwPF-|KPcW)T8J8^W$M+xR%RQ!6Y>M$nOp2<+$K$&QdLAdd zg>8t5#uSUOy6^TQ!nTcj`P5QSjjLNlnYvHy zQ)Ms;nxwTsh`G+LtpBre_&HWI9xkhN-)!#UJPbm_6>wpCbpz7%4yB%eXn+09js_Yu zxlWloJgi8Na^eWC?H><-A#s){ObD<)MOx`4(>NZ^mU_{HqMprxTHd&Er}N$9DL{i zTTJAQ0aZM&uZI0TqpX#b!OflW316wXOt4LiOdMTFXMTh9eV6s?BZOJ~yiCB#I`|Bn zx4#=P^Xb7>4<9$C1~H%$NJTK~&hdJ(08^B@xpNrB!c%RdZLz!sztG;(A?@Ixq~Bio=KEx+CI{6|00@hVa_9 zslD!SZhZ|iG%0%;Go+G84(iULnRr%2=g*x!l@6_*Fv>hyIHiD^(a}O{wjr1Z*s2` z_8>~uA>>Zqe{aS!)xa(Figjo|%}xg16Ro`!TWk z9@iOSI=~z?!! z?fwS_?i`;tZ6e9?X8Rc2Ydv>A^Jo^x(zc?>z-(P6AA2Sp8dTs@nU&Wevq@u%cZN9P z$eDzmzfY_{4Cl6#984dP5U%6XHuu&wI5z3WH|FHf`v`s(IORB_+b5Q3}cENLcmPN|LE>Qbq`1N8i!ef`0+5Cu(0mKV&qtt)qn+Q7!EMfx2E05)winkluL4 z#I~9HJb|ZfVGi7xC1!*QUx$6QbXjlft-&)wi7A$VcOj$RHEfReI@Kgi-Jl5SIr-__ zj?rj`k|b(9c1-6pC`l;vj#9_-4msy5jy;ZT&!D0>9S}iZuHYkRx2zBWL~~{0nx0;IvO zK0gE0COGDc4IYkPjPJV`kcAE*-%&?aaU$|L%2Q!s#?ljnS< z3OAoQjb5eUjZwFAo)rTB&+WdAJhM%FI=ycA4T(pfZ-gRbxk_kW*e6;Z-Tusi4Fll$ z!P?jlw8p@7>xtw^u-QQ|h86bigr&$}y%ydI2BWbxsor$3{%~@ZWv)BR(bf?W7^!-3 zI7`v3q%nMa0d*~@r1b7$Fm{6|&PnxkLTu8gnjb*|a5tSH^h3L_9r$A*G;%TX2oSrn zKxB$UNvIQ*$1wl;GKpzqa{K&4qAQV2sCYC(9J_0TzoLipRE?#1QWIlds?EmncnV(D zmd^@ZAk$-5A@9lg&6In46^-#XyBrm8NVttI-hltzbmQt~xvWdc<<8^~u18EBrC-(? z_|WD zO%;jmpjuzLqAb_VtuSq`B=3pPy5z3(B!gvnV!r&0 z9oFt~iinCq;^i^vv~qGU#fp)RH$kAWg`a2SJvPfiO7w(QwDMVUZB0ZU?a0F(pexFq zm*iB*@?*8}^u(N!LSv^h=K~Mag>+VQD3y{t;S0FMr>}}AnzmP%qmaTuuR7G7_cy!c zkVXPDzx{h7O0a;`(<^SxW1#?V=tHE@p;UYI_~IHb`t(xo2KN;kLM4=Etm47=TF<++ zkPW#)!If^NRuoH`o7#3TIctIY>nn;^0?|cf7&h`JYZLPXnvl=!&Z9g{$ks1EtuAtY zH#xVN)cKhMYi3kn#D#L>OQe&CsYJmip$QE4sRT?^eh~SkNK)9QhhO7Y3l6cux&8i7 z(X-m*Mw&?C-Ogoc@cV(sH{_wPTeq;ThS2up{h_F9$j_h>q}ah;oqR+~^vF!eJxbWT zgVAG%wvg8aa-F2wxw=hPX`f%gmK8Ros@$VXSn^jnwtZ`5bU>2Co(8w1@LF&CnafjM zDhRrqH5do(SA?-yd@?%M?(|;!@cUffP;zhRA?3hwPtXl5uViWcF_zcAAYNnVTTb8i z=t?f(&deMUqGpH084G#)1k3Kyy$$o21qq-%Gsc4lKXE+u(7FT&1aG9i5+Kxc3z7wf zX3Ot_8Opy957ieu7o6k%zNh-itRj+G#FcqfgKs5xqN zA+9#{l^QgR=fvYhUvP9^2px=FwqF}T4%gir=-b60jw_1x0}`x1Fa!*@fJO7D^p28x z!&OOpC(Y0ZrCs&&Cf4-g$q|)O$a3QuyYd&%=CB)4STAbdBW0*0zst%PwVC1GR%1t? zS_Z6iU!H;H>^B*dJHF2H;bdNyQV*IZP|gV%^d|pyb@HF<=q|Hgp(bfgjAl{gLE$AB zx$CQXwDvE?vA2MVquJJm zNkT#(5P}C!a3{FC4({&m1b0Z#;O;ZHyThQt-3NDf2!s1K=f3AX=iIaIzt-Pt&GdA2 zPfb@>)!uua+WXncR;%;lp+8*UTa}IDzTyY91%GpyH_*at2)hs&?QY?PNQ&yL{+=J^ z4j+`UOly>PK4)}f=Fl1Hl>K-~+<}*w@0aUHC3KX!Ds!SrGTFgF<>+d5Aw(LCnliMD zB8|v0EVMv0oXTHK$S?$n#`qs#BP$c8j=#Ac&zr2_^mhEErP~u=CNw6}TNpXc!(`5X z;~x&oZC=SRuLN8jxJSQ>+fcRK&^!A3*!^gn0;S4X&M^z8O}&mcdVTVo8;wz&F454l z#cn$2P$2NTT$H6?DOi4RV*$8&!b0ljmRX7_E1CR9D9_mxm%EVG%ZlFMnD`C&j}ey8 z?o6sc8`ektsXo9%uyl(zmop#23|@V9dm`|r@nh|Z8}gOUZz|)jyd@l+GrS43UanQ9 zq8R)poc&4c9R`%zk$5Pg0x^s~FHgS(@TFI+2P3|sKVk6MA6zVw7? z43e#$oQA0Hp#`Ksfg4u_OslJD---$RvXf(hBX$j#k0Vc`?kfLs%lIZcihvq7#nva`=ljx z>YiN9k2p_$RlgEzh$AvtBQN=y2iH`onCo?;n?E*7aP=ywkYz}1d`LECEwgMGQz z;t8Q%Sr^?0=a34Ppi(tc3rIWTM@998HbbTrt5u4_CPu=VL1iYn&67?ch(%3`ficeV zQ9Y?!v)eLfbNo{yB!(*z^8Vc+vS6sNrBDUUXmQ#gfu6qM_-rJy_2Z}9_*a($xP(iK z{n`gAv08OyHwzc-^1_Av2JGYJc zzacL=*)TLGq1@cl7g^`7PsfKJuhpjgygKb#Yq?t?_iR*>{6fl$&vb+YBiT!5*Tao% z^BYLzYniW}joOXR4fjKd)eS=?XZ9gKtUDLIyC=RrlWJZ?C4J=NaTP#lX>hjREfUyE zOU$tjVICoN$J6gfzZ^|x)Xba+uYNrp(Oaxtz~9hE4900fSpyR`-Ba_K@44r-$G4Vz z8I`EZ`Gxj_VAu#um0c`VaOa2azWwgdG04ac$hIut;2&aAV4UB&c4^i;R%Hw?S03}I z$BMcDSp|*p@UJV?;_{^zY#mh7+u$yx_~||L>z1}RfbOiXv#C_#n{Az9^zMFArU6Zq z;EEKqI5%gD(67~ygabZS_1ZJj+XEi2Zm7a~gY0RH01udJ6{mG;m+ z%=;r;3Ha_}+FI@vd*GE45l}>ZZm6`~Ks|XXq-nDw5da9w*vaDH=9sDm9S3E4I%U09 zOLw>N@p}!yLNjqr5KuBTQ2x%Ec(d^dSy6K_-)JXc!jbWJv@{xxl*_)3$?dFt=Lm8}$=753v0Qg6)AKZn+H5U_PG-TReZTCG2cdtv> zRZhU^jjrTH3uP=(ePT)gI+JmnUQPZ(Lm6)*h%Q# zBxho->r&UeZ|gAN1+GH0bMI6Ng}X4%jbOeelcR><^57sy*U?OAJ5Q^AIik%O*fA!t zu1am@qGbK+@^4>&1H!^6eGy~D_#yHf{SPnZ*eF&J+oE}-J64Saaun`vFBDRwOD0=A zUo_d~Qm4z%aw|;ojB1JMoSDBKpQ~1+ryP2phr`h7$HwZ~+Hl&(8T$K~r;FYcHlveT z@#5Bjgk_YzYH%lKHzQyUXq%Zv`O-d=aoEkS7~2c8`=ej!g+1_BC{L$RRVnjI+n zlfnjKm#Z1ymkmSH3Oo3X(}9KY+y+0_HOj7A6P*7SyObgYxNDUaubv7kybO$kV{gy=I>T?kv>R&V;f^G zr5761n})J3|1(bom!>K8zF4EQL6@ANU~`yH3P-89v*PbUY-IYQ!B+KAO$Q@tHrd=t zFU@@NUha2Q9$ugLLV7S+dgT)YDfLUHSYc@8o2|EG8TQ1InUV4Xi{5-r+MIb4UwJ$q zD=}#)8=Z5ca;X}2BFHGKa_Y;ai zQwH_5dE%$v8+@a8Y*F@rdSeqDj&0%{e7E6C@=ZTv^6+xg880u?EF5#TIT8z%K@4X$ zHc{HnzN+iJ45hd8!5A3eMoHx>=WseCG}aIzxA52C{Z8?s!De_>jm0`bp!<8N(p7(G zM!T~tf6s!Y8dFN7zxc&)HD(7MU)2a|sPDNGUfiXGz_gOfYD{#n9o;h|pTnY?PUbED z0Qm;`88`JbTg~v(_g?)-^c;I>e$y|yqRr{c9;u%Ps_{cSGDP1qVTRtg#m8@R`;$5^ zjuhhTY_$il-D$eZO9IRr3YPkFv<$& zzHaW_1%v$9qAMJpK-j7~Q9mnvuxVcCf>v zv*O9%o?=qLZc;LLB*CnWZhh2iqfw}ZKG zd5u6`SFA`eT^bzqeDE{+;`VNdrVX(|6g#e|=XmTy+t%mi3;Nz*Vx#d1l9X3PJW8#4 zn(xS3vEi`ty%>xE)<>eC1#;+w<)HW`aSO3?r7`|%3ulHtzhyw+n>vffviN7_xl+r9yHJ_BC+1#m~S_4vhp+v7e=BMN}G?I zd55BQrFL)$E^GtJk=OaIyb^OdOUiAyc+#eJws?4~&+e+9%F@bC4ht25qK+3tev9CN7 z_d^Lq#(56%QM*Il{-JPlYamV$$6D%{$xu>>K$ut0=_clrbU&g8EZ(;D91Q-cJ(mX9 z?&+_v$b0!=k(vQ1O9lk5Pw{0BQjpXSW@rvuF4r}5Dq=5tGJftQTvMo5`1w2cQtJw) z`nMuMXNu$+ES(mJzyBNvt0;ow2W`wRe24=7GDRuP|Us*S)`> z;uF$V&nH9coBH)yPhwr(@(?_FbaeX{y^*R;p09@(XBn&8$JO!h9f`X^yiV47?N`*E!tPF5BGE6PU4?N2=4LlspG0R zqMKZqV`^^%vPNcs=Y9#|=Lft?4G5%MF1dcCHUl$O5V$a%x)T^Bfy7JC+#dRy514(k z45Ua`s*kgoc|vQ3@EL}vy1yx-$&C^gf1W~ zT7X13hG~VdIJ9?do5ojgVvA046Kz!+NP-eze1RU}-(6&c(zsVE4(Ho^URjzZ6XP;Y zU7R2jtam$w%-UqAU}%r-U7o|Z(M@}Oo#|VGe?Iukzcjy+EjKMzF|(;RyC=5zx!_}wD#zLFQDFb zF9%~KIfhD{iM$V2%2hf#rf1(}V{(*699zGgxxKw6MC<#QKxG$lJVZ*=9x7~0DH688 z$TT+?%KrjKR*qM%6-fv7MmEsN2(D+T_6-ndvA-fQmwW5YExW$(ePl?rcSghfQ9TEr zGOX$Yu>CR=TQ%YmNSevnYKk+S*n77!9hU6yk*2UnTMttLL$9>O+(%N>$6fl@VuFAE z2V+)0MpR;nEQTa4zemxmafS?PBo;?O+v7Y9!c>L2eqxBme8vjD@AA?78%l7theCAI z;Bw``igm+~%22`jW^T)Jw1ROl{I`6WUi8nE$X_^bQ4}iVvFd z@sh&A-LczA8u`-&-;$9&NRyf@q6P+w=BSk#U6Yc6z_^P|72mQS8XVU_Oo@FrxvlvW#qyLm$xQcBHX?8HHf~4(OODcbr%)cLQk1bza&3-c^y!se|YqN`WkdorBtC=V04RiUd-l!F+-Lsm%{5e46wzq9bz zC*>G^RDR=vFPr9Lhna`lMIk`kMe!H*@(*W|KOW7zfP2Q|d{>DV-X(6FRyKKP`+o`O zf6C=Q`nv+Ncj~X}0`;JVodV3;QWzt)%<*lKFq(lw(Z=2UYGo?}VQZK2Q`=YF6W*M2UL&8jlTu&y3 z(9=x5bPp4*rORew)1B&7HzPVDo zMk((1{W*xj*hF%wSXQEdGdaQ8M`AQ!=_Yh4cyq1x^D}@fKK^b7pEV9sm&$xILSkIg z{gMCYLw{qn(X4Y4!DzVKmj#|t+#Sz(gy zo^Fq{xrtf{Sz7s%pfg*rPG0zU{(efvOHhTzO2;a+!}Et%&>=P>9!@uoV7DM6eB0S595Yg?#M>xrp5abNwsgm##}!&BTjx4e+O-<=iF{DfJoY0QVtsZ)D`Agr zeVk5jm_df1xNiD#%MD&6=E^IUSiP=O#~bjwt0zqe!#COkVR3tR!W^MZY!2cQMO6k# zy+q$NNq$#Jc0aP73BIM_xYS`PQrB7Lx-${?%Gjz$=kWCqyacRp<$2EPj?Y9l)B_b$ zn)3FI5crH#wY^sUk&$nS01IJ}+pNTIQ~I`H?5u$|ame|_xZ?Y_7CFl)D#Wp<*UUci zqO%0eL$%R(G5E$tWkS+&tX8^w=x(}GO#lkwHwOONTg~&8Pw}=q{s)tcsEgr#4#(w8 zro6O9k-lqpO3t?EtpI zQfZhG%61cAhf!QrD9E2KdL5BWo7xoNB`eXV0*urbKD5m##YaIs;}_1YqO`Xg?(vd~ zV=*#K+B9Xq1lF*Sf>MzWc6fy2F19ogCqqX~CC~Q7iGKRgu&b^;8dkL|$3cBj&4TDdoHfJ!K-R zPAU=zENAi#Iv>cQFfWBgtU6_gzp~b7Ho?{IYcTEhheph|rnZw$k?V1&3qezUtM>D5 zv&+*O_mHX&yrS2#^~Xsp**B5~Jj5^Uc=d;i?r$I>FF_;d=-Iywb#tel2IvpUqtRyS zi&4bC^5j0wf1N7x4mtuMH8GmLD+?3L z%y%x^NZZVU6wwW-I>E@~U@ckmR&{LW;gs!NE(f(dBcM$1F)h+hr2s?jc=wG51ljw$ zZ0beePZqubb90%VHjsNXbjSG7WB`s@)>t=62aS+%@=zgn@`p^e@SW^yapDafUZ)_c zR9x@{S1vpWN`1a~_&Z#hMCRVxq`E;1y1ssu-sW0&Nz*vqA<{Mkm$+>H6!C;w>HO^SLP1|l#WPs~1%!)|z2vX9t z3DX^ICEuW+`YH@-cmP|JfNX0RO8mk0j;{5?@({W%>8Um%mA)YXM%{ zLeK5?`Gl9Bl(e`mIk@nrv0;51w>$heJmDmj3R>n;`Lm9MV^>tHO_v|NiUeh|mMzxo zUTEJTBOTt}t_+xqalFYFAN#xnP^xUs;+1rcZaEhs#3;VJv>LKHVNCHi)Ll^_mWdsif;IbEvvmZ zr!tUEy3X;YYDC*>thYs$b9Wrq$!DJ#H_TJHy!oP;XU*@54(C7XKrX_2!>+kro*!P9 zJA8HI8n|+mg|Dh>5H0ZN+cLKz3%~99xY8y?Lrz21MM5$`QIiNP8~aF=7w`RzQO;$2 zU2XZgn(eI1ESZ!(|R-C)Yy9w><(XHqoQ#Z~_RSE-Vi+GhEx zqn8ZpUcjAE^eJ*=?U`VTBhOcig$y8UmqkC5S{nzb z*gcIjAR*gpiu&2i9y*NQ?8)Ttn>yh2iFN2mA|G{OZ4DhBtOn zW9hYBYr5<|VWpW!;aQ`-)OcP|lO%c+EAwzT0))HJX{B+~%;nunlDbgB(_iFEX2TI5`gYJD44r4h`KP^$*bqYOI zDWyc{8B5gg^}&}u^_3mhy8@P1=SX-7mibvUZJqTC;CXSoCx)GhW>PqibQg=;hRJXa zFU$;cUM#r}r5r>}LY@1S9y5gcC{T(F@cc5!7f@ji8za3fcnLv{8)Xy8A;=vPRpYxq zl$_#9)%A1fD+-Hrm2#ARV&Vb<)r6&31;;fL!eGGCZO&Ln=rLpe*FqL4+b_usZGy@q zoyk08m!0#qTIRaQe1%o{j#o;biMcyx6GIO83h~saA)$l7w2A6_%;w|Uc-@obc^5tD zcHgT3jA=g2)Afj4;n5Sn$_vFIac({*vVZ)Q!K(#e^h4_il{04B7{7HWEBDzDjQY>k zr|hRq&B6O@U5Ne>d!PR34SThE-(QAeP|A^2%S!p-xMKcGHYLI0sU=>fuKI_*{@)Vm z(dJSA`j4VXsaV^lc%ov4l}h@I(_@>ML@|y_T6}Z3mjC># z42A&1A(8g3-4Hhd(ul-aBBa;HT zUsonRg^CeXGZy0dzMsuwsE>LUD;~h-$ zy8@qM9v_*w*q~ee2|V!q5g$JIWV%1~1XK;jAqL&Qd(oLrj@;p7KM~elqO>7e4T%(@ z8DcAw-97Wc0c{g7^_H8Nma(a8a`lEFDC)CPBfXW}F!Ywv6Dq!xz*s(kziV%dyfJQvasv72$ZASe3ql*pPi5yc>x@E~|3$Ko(i$)t9i z%`($_YyW7@eAb2VWFBXi@l8XGaL_hvvc^|YWih$c{fU-H7-nM|aI&+rH-W($ySw5G zHKq6y@y43yXe*qA;-2VRle=aV%$H&hk!b$!=X0P*O zKg?6p)hrJEu>!$Ej#~!rhkgJ+rda!De0^z5|2A&n>uU#cNGLY#JLO3gVWl+_y^9Kh zVVw-41skR?_s$M44kti-2F1=rP7J?;-L(a~08{SfWh`X$Qza!>nYQmrM`UJ@_H%U} zir4-2WUkGMoRWiIXtJ)nTg|+kj{_q`s>sV#F}Z7G-O=L%mq!HE>QegHgI10EcQ%^S zO4(i;bhqf!-S6Kq@4RHQ&A*bzVGbTRxZpal5bq#y8Rfs|i$jl!JX*ZLeR(YV2aIq=$OvtGC6n$IEI(vJRmos9|A|jp zvt`m!P`8HCQt#HfSE_fm)Wc3YK-2gzmcLH|6AazRx!kzD97ASK8)(9Q3(zlQ87&|* zn@MPH(l3&|BT%Cv$#CS>KvZjV|EgF;|Zgl1gM(KKl zlBgqix-b01R2If@Nj#_@c4!tShZaU}+pRNP>w87}OdniQn_{-fiwSwkoDQ90e@IcB zOC-%ur9Lo0B+fv01^_N>!!4|6S-gR~IG|R9s+J8hY<7m>K^P7_YW9=;lAp4&M95T- zavI)M29NT5ZWxF>k=pf3iLEr&p_Fm!kZrp}9T!NSV6g_G(2&(>mHw<)GmgnkY|*=U z&gQ_U5PwKc@Ga7Ncr^EBaxfzPWXqk=S}5@gBX9Tu zn#T?NE3a{kAdzK)%!~0JT{dzBglgL^g^E zl7e=L6!hWO{jKY{sbr)TLAi1)kfIXzsEsO?7fU9zR@JC2MZxg5Xd2PsNWlhC(E<9CYV6Xi720AUv8I%~NCPlX``cPm;R(NptRtlzUxY=Tjt z!DUHWzgG(TKJ{!U(#iI`+J4^`#y2-W*jk^PecW5skC_f_fBOPFpyoiIg=~&?$KJdw zCb-0%-yZY7mJ|Jv`qM$bXX5ITTU5tirq+oc7t^D;+IbZP&t>g*Pc!*~&T0Vkjye1O z&yNows17hd3U>(A_zI%s07jQ7hEx;2Z5TJO45wKxQ%?0hh*aok=?S9RG?LF~qhW)3 zv3U4!SOu}?S+z%`43IYY9MYpNY+V^8rt@lU6Rh$jxf<8W;B5r?kPrfX_&?5+ZnC!B%fjtVFEw7*~X3KS5tjZo}LcPAKsm=IVHtY z83~F+^S-|!CJCK$vwE6bHvSxs_janckT%iZr&yH&Bh!w+Xs#L|r76m2%6^RLo`n_l zP*p8wZ7a&l$7{w3n+)P~%se;Z2>Sl3JBi%&5)eZ0@%l&5+{^ z-ZZIIxnSPM^wan5qO5)GtWgtD0meE%dY!e~1@*mbv59{Bb(z0CxSQ5-dcd`$>)zggof@Qvy9OIeZ!>#PUoKlRq)pxw!^;@=%@dlNso+fTdO>Tbr z0vILb-cj*In;$1)MnYq;mO~Arf4aD?{^uU1fnF$6DaD_vUdij|GNDOW+%j!yxQv;W za3;Ld#wC_a%jwqq9}=op#&dR;R4u`s{dR^rtLYRB&|4oG=;X?Sn=4ytcY>DbU8$L> z6lV(B9gMfQ_S#^2Ak6b3@N10}Ng6xbxwj{+8;X)`sV=VzP@TWA|JJHMp?9;o)bvzajc;*XUC>1wQx+AkN{d7 zCxvltBn0~U`vcnNr~2K3l)Szx z;@V^w_BQ3WEP!u66O)rpX)eVT8)!;lj(py`VNR!!L7o@M)@0GBzIcy67L=uy*G=KX zzI+JDGwEZsu(wo-_^It0trqNXE-70z%f#pIeZ+0Gj>9_9qN+{&~14Oe;m?x8Z9%E`qbvg2)h-&n8Pixq=a z*??LJ(#{3%#`=+SPwEuhf}d{!=WJ$w=dx-FhcOpV)QPF?x(porOyO!d8E z7guy|6^N9|Y07ox)iI8|=~(caV=bSA?_jP} zN6Z{y)#+`@sO|))F?)57JFAn=O|{W3dmRl6o$bkh?jp#j8bQ(ONiien{=>DAwmbUt z?6K)^$xYEQbZgZMzWafL>`dOHwqPTvgIK*j%K4f`Zt)tn=2-`KqE4878AVQ~aU{R) zATSm@STzur4()KsS00a288%GXM>oBeV!dn~4)u$!F*SX^5yx}@3ZMEue}??nM!~h^ zO#RhTh$5LZ+DTqytYzOJ$kW!Wa?7TG4oW^@PX54JU^1c>;|Z0ws3wuW>7{e$PoZx2 zx^=3?c6tzYSDBil=1Kd9g^fj{vsk(FW7?=-bgAbj$j|XlZeX?PJAyFP-nJU)5d>4* z)HE4`LomP0#nNb~MErpcp2@omWw-+*H&Y)2TyJc8lc&=TuKFY1vwCq2^D(*h62c#Sf1%J9~TM&0hzm56z68{;i~WWL2IWvGMNppUr5t6u3ynH?`2th_ytFIxs50? zrb68nR+hR}Wjy`bTO?N@Whu5+l$HV&SI+u@*!F+0JT}Erzx)T+|B8e9mjV8_P<@OT zSZ()tSWv?(l+P@1KA2h)$#`Lb=zuom5*J)YnpzXtai>dS$l|)&K1|s(QsP&P<}Tu> zF%IlF!Yugj4h{fPurFGjyyj%p=WbyHhhsqj$3oT4?0b@}VXvBR{W^9w7Ev=eau+X_ zIB2wMAyi{gG}7hd4H5j{kPI&0SQ;BXriZm^0FtEr!b*3f>nl?YPY*1VH~>v-|2w6! z4YQ$gBr{9ftutEV*KxIgp5l$B8QoyOS^xo|+U?7QHh@3FNYs>3%_L)Bfe_?yo8+Q~ z=36&D8yime2oquRrb`9>0U6l$ib2_u2>TElEE6 z#kNd^)wSzS>zFr7m=?62jhx0~P!T%G{~4a&ezI#$yp1IEpm4A=Pqt5&@cq^iA=?gr zg!5Fu9d%neLw|rZAL;lGdrBLoEx{U`l`rv+x^Eq`;PSPkctKpM$xQ12Xb$v;B z&P>jX)rqR~Nu8FpdVWGq2}DmoySzTxf?ieS*y@9rzi2}$xI-XNoJ@wqQXJ~bH}0`G z!gsUEa>KKi5#O}N)uIB+uzqRxj=5U5#r5F+>gZ-gpHOq9*=4!~5iaJdyUTLsc7u&x z1~Ih*#gt8Pkm>qCe=8DLKCj$aA?72LovyX|7as%+I#Fbe*yHa^_{ zYy?xAz2Pvp{!PmvKR*`^Zt6*n>&s;>kau)Qt>mW`{I1k4x4(lO;dCEX$3fgoNr#;1 zQMTra`GRX?ME^%1T>8}p&q6UPTSyfDrhJ*BIcO_TE`s;Z?B z&#OHS))r}5Lao~zJqsNXtke6xqN@=-&wD1o<6Af~yZ$Ib>Qy&b&~ouS`WMq%g4b|AE)Cj_sT;dC zLhU|0D-PYqJT28*7ZQjGt2FK5n{kKx4Yd^2aYJER?pIh7KRl9d`*wdc8{6tPPyj`d3k{a$j@u_;YQbw!QQA>8$M zJhC7s)deK=>81GoQv17v%iaD+S&m$K=CQNcu+cr|t0dV9y>=+$3y}Zwn!Y_>JgKR^ zMU20z&dMb?5A9`eVUuOYGDn`nMg>HzZ`qfVe{Zrv=h4op?I&Y<>b{kG1^ig1n-|&< zJjCT@IddYQp8Eh%Xt=b)IgRDMU<;2b)5z|y3A&UU7UbgxcLduJXyz^`tJ6-k1mayk zDQ)rKsHUx~#!}d*N9`x)D_>rai>&rq@1GnHTPs{Fzf8Kr!Aa6y`_dX4!H64`tI6U1 zxNEhz+In)lf{XcB@kG8u3xqxe1Oz0KQizuIfBd_DenfO(;^Ey-h%pBE`>RwN^}gir zeg9%stJ&GvNu$^5?#c1?{1Z;UhztQLlLK#0&v~Ao405jyPw9uGRvKXchLYd3*nK}d zA{xejT=NN|AB%vX3`PMr{4L@kEKgLwLwUrkw!wa_f=0Du*=ZyzE9*f|`eU5mt94iC zS?;p*i?z#9oY_0L;;*w@=c;~Z->cpEFF$jI1@40YUjcT+Prwe7eg`->!Oj1W7LaC_ zBbW&Kt0~_zd&6;-+I|PF(7tHVC1G;BkEVoen&oOnX9mB*x4u$Dg`{v28Ev`~e5Keu z_NDo08N=@pQpBJnEXG#D5 z&Y;MDOjS5I_p%_}Kak$|gB7HI)$qjy)_UvD;#v)F{#Ev$9|kTp?r{F2fcLtK!JPs; zdQ7%J_hM-LuQNX+1pn)|7IOIN&-|WYP5#$KUsO}3TmF4}|0@5-2fJFY9sTZaQ#FMD ztN8B&!Givwj=vB7*ZxPqm;ZH#u#+b5`T6+|R^b1-?u+8!-BRMpU`McFp5=f2x;rK; zYvdvOHWh-fVTRK$_)IyqFhx8HSBzI|PU&?*t(dkWO2 zH`9wf$(Yksb(=!8-Pc=hKi(tSIcW_w zb|Zvsq!U?e|P z)H1Ci6)g#M^W#?FgbN%WN*vryDIRiIHLw#RCOSQbSgS<`?`yvChZU_6*INdT=rghRxiKDqo&A+1J}Vpy^hd#p@s7c~;L+MY@** zYs?$MK{BX^l+>vh%l+@CuhB*!Mmh=iCwHP?Kr3@gO%P|kxkrI>gjs} zBLxpUog9hnW^*`af2&_VSgIh#=HnD7ep6g{t4i!M26D(B`i%PbX!_Bg(b3TnMJ!Me ziO)g9%F5c7{?9Qn(BCfs8z<14n?|op3CZV3$N^hsk@lR!qVr@4oqXY=B%qdt4+eG-))0Oji9!q&d)kzw!W5Gvw zR)`ZQeekLe(N?=!Dbsnrcv|kEK1uW4Rc3u|&TL_SmuL|D*? z%l`F8n;D2yde>rKRC3cX*8_$qdurV07%^BaD|FXTlPJeO}Z!-cOar=e%>ihA4A7n_gXsKNpV5GEhk8a#ASR*uTGDz9b{o+$|R z`IOf>)?_+#^(t2|tf))#Br=@LO^TWN{y92|sg@~u2W>O5GhPg(;ot^5 zzhLTs4SDPIWohiCY{UL)b}pT9pzT5ensgm8pyJZDqgRaID8d7zYHbXQJX$gXtg-5jOsT94XR9tBWcqG$wnPo~Kyp2#m+MVOxLO zsh0 z+hGrn1ja&=jgO7|>TUGFahDLT)Syl1MG2;NL)G8mOQh~7`M0Wdm6}w3EGWYcTA|C1(l49N zVDnMAMw>ZudQxq6(;YCR;+lb!lHhe2nItkanHANDTOf|tBwWHPMEf@A2#MFL>VvHhW0R$VT0 z7G+0a;kWRMFHgL*qH0BqcEP}Kvvap=qutOhEI~C*#Q9&n`NNs#&h7c}E;I>7SYPON z@wYO8iwVu6yPJE^lwE94%5*EP@Mf^Qod7$?stcolJxr6eiJ;`NaXH9^Vhb7Paz8WoaBNM-qLoD08*xFuvr9IZlKV?Twcg!g|nO=Qf*5S(S zcHYqnq>F~GG82eot5*Q{SD|$jjC?(9vl_N5+|p0!n6VOZ#DyxqoW!xcB)vY04s)$r zszRgO&_L2h2S^z;x{H-Qdl=#2vR@x=j#@{Ru}Ts`8!?*zdRR22fld+6%U%lDEk|GZ zh!aj*_26&3UA8aqh7xC#xt#VC8VGt- zI_7i;+pqrIVAtAKmB1$`CKlLRbz!U5XTZ`pz*^BLeC+#FvlE7#{K@A9m|0^sn!OCJ z87>ucX=B=H^dp`aABjju0%I}^A5^NWP0MDq=c_#Ibf(oZvL>p9d0ldvTg2ixe}z!g zR%Sw1r%QFWkCG+iX2ZGtn5tzg(}l-$6GnmBz8+_~cGH6#9o`_DX5VLjJG|>z=_|J+ z>Rx#HnHWon9liR-<~e8C9Bd{)1Lh3|pyr@!`G(a*`BfW_#}69Mc@Md*wApBaa<)dK z!^E3KYQL~{$2W1uK#V+!^fCI+W#a*PQ@X3FA1Yb7BXbS^nl$8l874fHnzqsi8CPtW&Rnhc<{MXma!=vjYRYqo=W9JXBz%`4Edy4ywIwD;Ik zif7*6;;<@uVMG8Hmi*6cy<_X~4^5*c9e`|3qnw!xH&_)rT&%d6AwxOK)4M}-w7X*e z@%+ub%av03ZB4pb<@>2eTb4_2{#uikqAkiUavT9Z#kSo0c73gO21D+qV`jF+>lq}PXfI;qSC~@5*HoRAouqZV zCU6U&k4;RRJgMH8iiSoim^yv=Y)#QFE}}?M4EK6Ao``;;N>`_Nl@WP@BAFtMwKiFb z+#{KSVi0D3li<$HS#D4KKg!-ap3U}+|L%6Tz02LIDvAz!)~ec7wKs`ap|!W#6|0k? zXk(SwE0T!Rh)wQNBh;3t-6BS;7O@jgI_~lPKHul{{C?*jN#wd*xvp~_$MJce=Lzg2 z24g2N%U<(r-irz1wnWrahH*5PuuQJ23F>x>*w)9>CULoao-KsE%+@*!lA0)o4RC8N zL}m4|;dfWp2w%&e=7(z4^h=)Uu;3giGp`6g(28@9bi=1ayFrCl^W<4U?Y$~P>p4N2 z8&IZA^1)?`*%E$BCbKA=Z*%=c(pi2gMO==r7=9Mya_hg`wH@)1%mdggxgpYFy!2rR z%hZtTuxHOMu(ovrd1c!^`+Ppu`@jz=`zU@-f1zY9n~;P$UkW>aD{TWiz`z`ZEb3aR zL)(;yuf-M;+}{uHx%!`NT!d|^d`R<61#JY9c(o@WRf9R{0n*_Me~7wN05Bv8{L9}! zHTs<<-j9nyKk0b+>^Jt6~kQ1p6^98VJ>lh}X-9 zjcONWmKVFkIRiHh2()}@NY@=1x4me-t?azvpmQdRnzhP^Kj;NGyLv4s(c!~A!O_>{ zAL@VaH|~ex!CYL?V2;FbrEy2eJQkMBoNWzFK}#sUMQxQYWT|kSqsze~l~`<;Sd|{w z)DT&cfvVQ6QOvm|p|egufB1sAu9qUw)vl9*--!LI5mjJBv;RnYW8{p1|XJkT=OW zcA6um!zCHmeR8HHGr_UTY~^>(;(=N&(vy8ayr0I*8^dsAy15{>0M%cw-M4rJ?0C^t zF0X_*))XCfr+d9S+t6t&99-k@W^;{F5t#vcNe~fNQE`+Su@XNwWq-=~x#wWtB~R%^ z2W^T))m`qP&`+IVA9zMgMh!h!E5FQ##niFnUjv?X)oNb3fkJeA%o=?Znn$h~SDwVL zDHL0*VI`|~EZv=O$h@>oVp7os7;{1M?JK+OtdKGi!=7jm1NH01J(=xp2d4EO-tGFM zcl%kh1y98T0Qr+$l@Hr7^3JG|W~bP#@P1nuLTOT~mgbD^+mjE|!n%ZSM%bP9aN12_ z0)%e_uAG+V>GDgS_Bs<;y0)wT{t^g?*eS?ZDUG@)aksKyUzk1ODn?$+9Py3fr^NFO zRIU027y00>vKJr*P;9$omO^;7$4g>&!p!dt8A3yQbB z`$u@CD#_e}L9LxaWFBoUBq6VReMHEL^;d##0#!84(fv~*0`nD-=_qxMi!RPlbY zVdft4?FcB~Rb8P~)d_K`jBdp(%`SwCBe0?3n8k+MR>iBqS@ZE+ld zhnZcg9@;Hh)7&}Jjb4{EB$?&8c}(2vS%ww%vjJ$G)}%2dv%>?dzI*i*Lic#D+vxte z*=yR8g7dL0GCND>*mqQ!2`ZFG%N;Aq{IqL&1YdO)j9`nM;9X2HI|tF82yZ}SM6mSL zvgxzblRa6Mw&0z_aLc1j77mSp)(XSk1Mg8I0QY6B#-#n8mJJK~KDfQl{+Eu&z?~A4HRM%HIDdZmpbO{nh=7{Ff+KAg0I=@X zXSl5RY-P=H&&U0FhAw2`LrMRh08Jw?RtNXVP(115a}-{gZWf-1-ee9je6Xu_cJ5G6 zx2jVz99ELB{b9<*Y^!sHknfYL_xcF_(GSU?Y$MA-sib#_F!1|)I?`h6^zLmz*WsPek<;z9RkS2Kg2E#&^Gm7lcehX>*XTjO}ORihxxTL~Sb4u}&*#7)@ z+M7%&J(^ATVweuk^<~L_@3UVUapIg!8oX-^A3?_y)s##_t&bd$M4~{LqM%>>{^NVR z^WGrFgGV*M-K9!kw-m?b(tzig)2WJKR3Ku;oWe=8(m&I#o8>Et3O}^Mc&J4!py(3h zy|+mf_c$B3TTX=atwz_}G?2zT;^e` zr6b4JCO)x!gF(9n7NhO3?nD0?%l%d`C)^HchI;LUiMWgHa!QDewP+I88;smNITSSH zA(~YM7CR|KCiJ$sh4#jL+k4VTc`c&xwkP9sayL8r9CMVr+S6_^l1g6%hF&Y+&$n+z zzb&{EvmYH+;%vBBLNMBV61?~M&eJ$PCamDD7#=5Rx0Z3WEZlBQu!p=kWj4|rL>@b@ z!0h2~@}7%8kTK;sjQRHA{CQ>u`*|h&EaK0UUerhA%IM9A#!~hAj{5tqgf$thH70V2 zTQH6DfpupCoMh#@)bhaA<;!vcRf!hF zXguw%ni}^Ws5B?%DiCccqt8(uPK98-Cgk;dpUl$LUQl{F7hd!KP@tl3Vk2Zy@KRAx z5sJlhJ0;Th8vW7|1uWD_4yihM^5n#}rSGGV5cnh8BOL<7Qt-ak_Q0X#FNWXmMpmKAhDQ#Q^KKFoNl=5xcQHBzQ5eQ zQlCiwm4DLL`*cB+ZVrLI%RrCy5>Eaat3PY$@tKyBVS~m0Ta`Kj#jhqu>|Rp*=Tb)= zA2Rm3(VM4abXEOTdpRguX}gYZMFAeseEp*P?XC&o>MQ|c8*Ek>xN$Pr?C1!z zI{ga$5?4~`D%HO(_5EXf{H!hgYS%0<A?{0O`s3FhSjdu zwcjd$;QF4G9s5}ny^vv8a(MR0k*_-y3iLdF|L;8BSrf5svL>fbqK_Q;{H^7?mv>by zMiy7AG!?!7UJhs3G^$m5DI9Lv-XlQ#njGs<*Wd_Mra@|})|5&HQ@uN42j~| zGNysrRVbY6+(LrP3OrN(k`PJ27~G3f0;t(w1h^9~VoOoSvJO?7o<$Jovv&tptnE>Z zafnhkdnK8@KOqzWho*_hPo89}B1F+VM`0sw^9_!aWcG@)pv+HpsjpQ_E`(%Sb|!Ok zkXN}Ez1=ZZb2qox!Wh7V&&DbJG&Nhbjkcr+N^DCD>P;0pNykR z(#I^sAN}Z1A1%K=py!DsPfOnlTfC3=I>w_ebUMk4y=T2Q8|2jT`dX|(X<8AR@S$;8 zUH7IAs=+s*q2OkOO7P`Kj|aE~s)nbu+$V4$tRbi8MPVW=#nmmLZ4?q3O^g6ojR*~! zC5u#GA8d1hE0hq{eA;cmmC0a0iaF@yO0>~7zt`bJGsLYrFzPK}r;uI9A$|yRBOA0I z%?hkEwxX=g3U5$w0bfgC{n2@hmcPrkKh@LET6vhoWjwPa%rmBzE$@a^c;Ai$ z%<)?UIBZP$n%_a40WV=Ob`etj*0h1ueskZMDouG=&mP`nadv7w6~&{zJuoaz9DJ-D zMsbAM$}A(uNYhDm)Yi&CR&l)B^0h^xm**7ojh2@LZv`fStz9yGczKt@DeplshK(BH zM|=Ss#O&9`<=IVEx2;L5U6vC5_A3JCXtu@2qCAFrpLGhx@>s~Dn*9hvYxUxlCARvF zDPu_~p!4+d{6dd9)YJFMtn`TDaixTo+lx9xM3kLxZAIQY_s2GC z!y2|8X^28yMwj~|zDU#Rf{Z{a63t*wD27(pZF~1)&Z`4g@qbXU_VotlNWnh^O;oLd zghwml$v~gP2c5YMwO|LTXJ+{LW~9!ojtGU?ol>jO2A4uHIS`=NNzQ*|Tn?PbBZs=% zZQ?sx4ytGRut0!puhId5*CTXQe+&sk(I1_@H$f5oQ_-T_>(KhZmFr@RFKd2~692*? z{)3VD`3KuCR*Rk$f6jD{;4<47y|39;IK(yiVMDvc zlkAo1V`3EGoz<|>1|_{!0tX`SmUhtr#Bt~$+C$3P7ApkjHB><{f+59Su`J2$>QK>p zaDyr6`9^&;2x08+a8h3{SGRX=)<^^b`1qa6S2{}Gtzcs)HQ%a<+b_SIT= zSAkl;*zM&hjr0P?9qyTmu9$&2H!jCm^@1WVe2k-kFYIhJEM}Qr4!T7jPUMsbS`=#2 zP)PtsKrTG?7S$JE6QEJ7`s}HY!dH9G@jx)=v0E-Pa;!iy^_A}j^z97Zckq-|&pe7s zXg@DbCYvmL>B{t(ShBr}s2Pn*WNQ{J8Uu zn_4t_X|fGu-UH9{gz`_`s=fdzuZi`aEx%i8?l^1k`ZEWv-2FVuhTlMM)M4NIg;b!@ z#F-iyBJ?UjpHeMe`3%l1$9dSsST~ z%ZmCtt8eqx8n^=PNhw_bwDXn!enV0)!98&ms18aBPhoL8gx2( z##Yw&IO~BR9G-1jaiCoQubBmQgDeI994U$r1HaMdLiU%GHlP_~?3b@oIbm+8^kM$0 z+5^&mjED3FlKW2JG(8sbaJopg%5Q0t)ZxA^F>;aPJo0S&mdjXtOPw7)*ST#IXm2<( znfzqU>RmUGW$zUz6}uu`7@A)rb&Cc>{oo?hv`Z2PI&R`TnA_ke5tGnFZ&Ms%^%dNBYC!!$;$M$N98~T_p zcE*Trt&Y9XEjcEE4egyOKDaDu5@=nwT85!9Q>!Xw+Bk?xob_^|QsupeC-OYu%0B!+v5#@l)P_ zCxZ5r-EoSggnMjWh9b$TvcyehQwyt02fV)CzVY8}*5Ptn7;21Ob`D1jNJAkb-ehWy zeB}A+JMSul5=PX<+Ot19F{iWBYqE{krfD(8a9jB1mE{KBa@pIKrE_ z`M|q4m^8iKm8R=CH&uD)U-bui!Ng?MNtQrc_s?s`iJI{{SDUFiS14v>!@thr%3iex zs^hws;bzHa@M9A|uE~>ts&5ME2TREe*6q*j0t6Qr;vn3LakTY#!tj5Ra zY$UFPz16p~g#aGeNFI>lYC|U6v2wW@vXp5+J7mt(W-LT|%Fsj^8*DxWpkpGN0mz@V0@5|7ZdE&x-0sftJ-fOLW}llGiGPU)R*j_#r{i= z`EF5?-E(b5p%2qxLVl~Sgh}81>tBg2Iw2v!;}%ShZ*YR;vEY9MXatfrMfei6Z^88G zh}n-IO>)Fqc_wi)Fn|yet4)((F9xfLPaN21nssv&v2I1Vu2dxeWOU0D(odkSH+yRb zlZ)NAPp#L(kjn+lz($8U`0D>;gnS0WH1(5wOjYx3`cP6&Sv+f$i}OlLR!}M6RB{I4 zb%@TSS)_eGErA`e)$wdyWaCwOfD2zjS3TC3B25_&HmVNvGCP!H+AVI)8h{2_Ep;RI z{e?Bz2wwC({KSn7NQ%?b&I*MHaiY<-J|7E)ptZsgveZVCv6OIroi)LMw0+u!gdoFK zxlE1srME`f*tcM?&g$hH*+v7G?q(mivCk!QYX>%HDzuYQE$HCND&w;Mj24`iWdo^r zemzi(xE+?h&=;pas#s|^K0iJQsR8M%>f`H)L{x}0%9fv!7H0IN=ZPydlFM6gnP1~m zpgxzJDZ?>#a&1rdEM(?+71|tOD8D@93a483^?-^T=%m_zAxL%sP`dKruokt&j55&k zhS#l?ypegA3He>P@RQ0V*S6d*=MBynzH$2~U^*ROAT5}b&*-@JmjIp5RqPt=w^X7oP_4qp8FrG-wpCh75I4gIVx zclIhqJoc6_xLFd(kuGqnaC%+#K~1J*8KEXy9NES-z;3fCi991>uKn(YsKIiJ^s?Z0 zNNI|e(_o^!Yfb6YyH145*+$ud?1MzTy0XQCr#)_aTXq&pVL1U(48^KPs~s{rie6{e zp;i`f6us?K%5V~|HnB3}ZD~A4AGEAHL0F&1V8!It_*;C5rkHa?&E43=ZrNibM<{(+ zyh9{HXmhe;u_9u)eg@Uai)PrB9VMjEbk_F2Xd5Asc|baitWG zx|`m`Z44Fw*ID|C$YwTNlK!=h{6IG)&~g3-^rh@!9Yr60NUAd1ZNvHXrjlJ8Er%Ga zZvp_tp>2U`ZA|?c@hFO!Y6X?@hvAtu{XpBL-&SA)>KG<)&hhFqLhtmvR+tPnWGR<* zgH1hRh&sJ4iQQRU4dT7r-H~u(YTCM&0Sw1 z-{5R9UbFsHIn}#?TZvz>>`K$lFH%8zS(V!2URKakF3@%rj>d#@_+J@Lk26!BiBA&1$SH6IBwVuXK!=Po}V9Q z8@;jlE5b&v0uHxnG@5+i^4qP|2~=NS-=^0uZ|W*HH+OJwFn(%kYBkK{oph3REk^)o zct<>Kqd0u#jITwVHmmq#(zS#ki;=!SaPEU!X<@z{`$urDA!Gsu_hsmHgA)`WVGZ>_;oa)+V22l z4Jh!rk?c!TkLr!;*m@k6|2G7LNQoFQsb!{qeVYW=7N@*Cgvw#qZ=nTJ)j0ybG{+6? zk1NH$>auKnnCRu;S&}u;xfsY^sU2*&IpBVDL)r^}cZD6K+sjj49I)&iTe(@F&3kIo z7}ekd>Z580EKZu++fXgen%My6OLrZy6qLR?4xxf$A=CW9$K0TV+5Z*Z>!s+9aGLke7scD&IL-oOqLhRSA&v^xzDN#q= zJ?&UlGMLAEo5C;DM>O672M#2HZ3hRlg4pK^Rq>;5(|hKOT_Wqv-Whr02AlaoVFr9UY?Bg^E58Sv@(0Z83bxJT-i`_%4- z0acGPBRJc6`VL`6g?bIQ(`JFW(sc{G8nzn|26~ zw0fpbH(IGY^xekx_IDnv*hr}zx8*9LtP(b9`=X@G0my57eR9)jOSm@Jy|b5cG~4bw z*i(kd{!|*ZSl7)X&W#Bn-`-D6!d2u7^BV|=Sj>m%N&H}U-$H#1>uLjP>hv0l=9~63 zGGllogm1AL&7Z`%?(Q%mUk|PpcJq!X%=dgYvHy!G_-k}Na)iMyXdUz5vUbYC=S6mj znYZKFtEFNDYc6wH1XN(j5!~QGh}#v%cge*1?t=&$VMT75S_hlY1Xf0OP}gTmZe$M| zm6l|6rYS^~lLU(P8t2Gg(F~2kFtLwehHAH1`sx!Iit{uFWJKR568t{eB5xlE2MA`l za-*tkKX~b1ma|Rul{U?m?G(UYjQm91bL?Va6T7xYlT&f*PFJh-b4&$2Aw%pty_xhX zV@_uwuMNg`HoAESVAAlZ-(nha&gRk^IyGrK%Vy=eEl$z5+-7JuHrg?B^rG)-p2yty zdRNHW{OJFS>DjuhyVw}*p6Ns%lV~je6FSoKQQ~<9_IsM-CuVMbGE?NtTwW;vaDoSkJF6g)#w?TNzK5wf$L({HB#imss87VUo462ad)UfQh|=MoLY#d2lEObO41v=qMt73yFXIqqmhrTg?fyQQM6;B$6O^J)zrrzYV-YVqNTP-g7GJ*|i ztLRMYFo|fR1hC8bCzl7^1`p|lm+f@_hZ(QIvRxC@I_Lw4DLJSesvoQ z4I}U;r^5TS3um0!KV!nKQdic6{>N=RRGLDq@BQv2hrF75A1BVIk^ey}IE3Hk9nDF;| zGd>$L+RpJdTKi<2>J9^CW=k(pooMSd0mf0Xy~9}o_#}d&rT^#8CQrY7KWe25tdpr z5^Y*#)zMv;PSGq7sfK(1)n#}8{eD~Y?@HO*<~&zC-=!!MIZ^mpGSk5Ah~Ea^v$)+xTW}lm}+4>H~4h=BUiPJ zV&h{{^j6ouYKhpl^8_&krM+@dSLa`-?>CM~aajNQx*k6XK^(NvDT^jqAM~J3=RO@r zo)yE)t#s-_>nI*@RhcE1gT8B)eNG6QE_`Sn%T2EEM%5uX_thhBrNx!?_I!2*DTff#9_VwQ#603qa4J%efmZ3Z(~KdqN6SYcqqBT;e~SXV)u1_=qD{DpOm z2+CBM00oGOlC!P&|xa2JIik`7V!qQ}lSEU4$( z7drH0_7`sbV@CYdjV_8f;&E-fqHALowp^Y0pd!(sr~qGD(CN2g7NkWdXi3T#s#l%_ z`j%(m_?&C7zw2A}=B&+T=>21SylF5$jMgf%HKP>hv8Nat!bAqK5?}dFjaMDbq{4$>>52eR>Rd5tc3+9M|lpgktRWbBLFS z`cAPWwrf5Of$HwA?u7?Gow{ZwVuEukl?;(3MyZGrH1)%v!QR><844}B&;G(o|H|DH3`}(?_9InRx?GAwf62#)0m zVksr+iCR|Hz@;&Z;)aP9a-Bn_8+(p)H^pS@vAkPKj!mo+aPv9Lp@*ZGuiG6zCFQ3Q z;B8ISR@3w_((68~2%7q03;8%V}_o{|SkU>M;OyRik^0c`q-j z7YbaTMqSUNPax1a_uJj;K)_YNd9AzWoh!%Sl*!vVo-l?rxDuB{)pH%Z>Cm;~QBYuyz~mNz~R%Px7;LnZV$u zd=T(4U5N4D8a@dL>S5=spVaCJcsf-3D))wMcn-_FNeu4=+CW1BQHZ!<9N-xdW@|OZ zC~FRbtt#=oGd>m1+^Q)oFF~0WnICrD0!0YP1wCd51XZCqJ)9XODhARQ7%)Kv=^K_!xzrDjF}zfwf3~c z5QfL);t1{Zc<+BE2PQM7X~)a58b&&OTWcvx+$7T(cMci%(IUXgl{2z{wJZwYYKv@M zyX(s5b%>WOPzDJ$J2?UMr+qds_<##pmhkE<(M| z66)W}p}kCP%C6~BTD&v~X}7hNVhfY@&Bqu8OFrteMW6QYUu)N1CaVf5>@We{twG_+ zT#~l(NY15al=;?iH)+zj0Bvn$3A3ta=#oahj*i;Nya-}U>DEr`9(7+8v8c_gSik+>k<`Z?&E)AR*ehZA0CKs= z+zHPt1q;}qUSPOG(&%O}{1{s)R08Fa=;ijv_gR(r7_#Fseh{AFww;v+YHKVY7J6Ac z(UplaFSDs_kMA#W_9ye=yA1)@tI28AXe9CIRI?P(eXUIQHYFl4a zCIq4PnLd{>p!^g-J37h7g5OXBZ)eaKnKpyH)-9Cbt_O&6=0M!=jiljC8PRa>hNq#XF@aaQkT&_yJ-e{eGNmb+!(D%H&JG4=-4YQi0!{AS z)t&Q9^eeN3IJI5W=P+4HxqI4u>bYD>)%jkI@U?)(^ z(OtPv)|Nd#m0LXf0<-(r`#_=%v%{>lH&I0;EC;`V>4bX#PcpvE9XY;_1hA$B`(8iT|!_zm5$X|98~?*MU!``Q16#Bi|%be|_;^Z@!8e z-&MWu>GAKMuy_zr%wL4c)#K!0%wbObUx$9aKYDrFVyy4xtCHnk z#QhNm-RS7(U(fmXxsRh>5?XP1Jl;t}GMm%~t!+(8y zr|RAp@qe8`_X?%b{wYT~XXX^_9K#}2qfpA|4mI2c2i!b_H;Qp9abzt<-)g9qz{3wN!T|M)+v zL{LN*9d=^P|Dl>~=KxV=K^a^9n%ooZS@bfAis#h{X$l9eQN6Kunba3zM%07Dx=;|R z8N{jMkATgMM}0~k6{BI&%WuRiXB9NYZZ(vgiHGiXz{!(~qSOm)`S;X({qek*19f1o zMoxNVgifOZL-EU{XREh==G1B%dHOFw^3N3k`g$Bc(z13#py5hMJN&S8_Gv<~4@^TS zMOd5FV0qZP>(b(|mpCGS>e;G2QPS>40NJ|4nmhO|m3_DKnxI)~FAY5v6pC_nZyM0_ zgOHzz!x4ULsSFdp1ljSUt$!8w>!bfsOT22Tv^SI|Fej$G_Utw^-9Uf(`f!e?ZW?&w+sm<$Q%~3b%GtV-e^dWpISa@w zCC?gyKappXLA9n6GHmc0T~j7&P6@?H2?;S~#VAHK72}1IT{!*eAot17UTzb8w&A?7 z#Sfo6T^9taB~Y?+KYyLIN^ul$+dg(~%^Vc2eirrGP#ah>rlW@2x0l+s#M}_|oS@ZSa6*$zOrXEVUIE!5ri^uvu&C$Xm5T1I%Fx zsL<6DndkP^7`-NCHC>~}6x37=^@w7AY)X5Nys<%XfDW>^^cEg1|8=A{eWdC26&|+X zz@@PS+%U00hEQaGmSwwKfcy%sbFm82kXrv0@Y#U%K5*l=bf#T_qn9+>^t%^JvU|_dc{e5*lBt``oa*la}SJm zA2g+AuN3BJb``NxhA-@9^65*!jvwLl;lVz;ZPY!G(&jxS<9MQK`m1hTp?e+*tkk;_Vq&QUrj$ zL7=X0hlBMA8GsjJ2_`!~1>*Y*k~0zye^!w_0 z`(6ZeQFQghWEMW%^I~mg;o>U&`c=0R#BapQDdxJ}ldsb>D5MuWl%rhO2 zsA=xq&iU6l6J5ArTaY(SSt8pypA-U3!ccE2+0IOzv2D-G+|*f%k$iz6GAT?;MFbVJ zUrT84Rp_{B3;c*(3JVaN1cXIx8Mj=2CHPZ6zt2=6MxXJ1L-()#?KLL>V|%C?^nDcV zNHHt5MkEV^Iy*jh;DYQW)5^WR(D|ZxIU!s`P~2f?;?`lAx~={~k%=>CF>@6y{k49u zyraal-B4)c0vf31j?zgMlC>o~RqlV|5Su4vGcX}$dgaVTlcNl=cBR(I>QG(km-GSD z(>zdPo+j!fva6$Z^r48E>}tGp_HAUM6Mu4WLAj!dC|;Yyh2W8$DUau@e>fcA#NNdM zj<4#NT@W;6Doy=aK+ES7Tz)|TkAK(F(+lkbe?L$zqkBr&`q5{4UtYtJO7Ewsx_(1> z!E6DKmOato+fpk_igSBvcdwj5Q8}bG^-i`+`=!mA9GsV%a;)XkGKu1 z&jtg|FOv2S5)C(ZS@Q{$E;%;^N5rK~#8vI`RMaKi4_+(so^KLu9d~OL7bbt+)K#U6 zf3Y5SPSKZ%iS7SxCOm#sBi=&CB_3z=piQi>B{zZfOx(kG9!(hm3%&R@##RUs&}F7v zH@H(>#j;#i{BWfd(iq5kj;%~ft-hgvL=PRbmHH9N0T#)=dc-nngrHer^8TD6UcT<| z@wEP=kX6;=D;_rRxL2srZ{Los==qwF7+3tQCg}5tzNh7<&#>ptwR8;7+v$(wpm~w@ z9Z6wh4zM|+B9y5tLiID++c#X?SsQqxMC{IvcX2a0AyNBedX*Vx^$E}YN9nh+dY9pE-X?XeX)9TXSHJqS zA9*L(Hyrqeq4=}01}kIrPP>L&q{5px50luFy2XQ7Wl4f2+6h}(ND6%LAk?`wC-baE zvFQqQJ<#t>eUJpuosu!8kO`8PFY`pM|; zP`?})i>z+5x!L?_9It#FEB4I*{kwYj`rGlMd0(KI z;-308tfUix-E$cRyIv2d*vHr@(~qp%3rnXPhf3Teg6r!$mArijE*nqhB5gj7@<%wI zC4M+@-t}ygKL;)jU0eM4Kydo4|CaaSf#9M^jlbYDZr-*jw3Z$p zx6y3Tm$l{FE|RR31xAUjxzd{Ref{%}T&B0G>$?etLlqBzK*r^qtlo2j!Z&P)XB$Ta z-z^GwMt7q$)b@~76|+X=sgvw%Io9noIGjTf3AYK=pJ_|z7w!!p*elJEi{q+Mt<=r( z^vWeTXey(KO{&Osy3dOpI~`+L?Ev??D+U>Y+@iUcP zcHE7UG)GEW!){fG^!H3Sa^&Hm+=#L+lx8CjTtm|*7dlN4J}6i?M@;1aZR3c{xOSHo z@fkpuj8y$)IJ0|^%jd`V(aT;bns?IiDa`5n4#yk+@G#lc5GCX%SLbb0OSp0Dg^VG2 zm4f~;{yuHJ1PRX;}*=f=1jlM8kxt%-X=e=r#YAH1wp{? zSw$sTnyhpa72UV`mh6uWT->qr59|sR-I1|rjbYUS#(6c>SY;S|a#=tbEtx(6d0hV@2U5umn(!?clXtWb~0Qb}` zNTfft#cBz&aNm>5O4sWawk1GY{u^~HeJ?RTy>cP9Xc8YYUTq+JC~LB^Z9@>h#ta+- z-kN>4Y0k<#)4WZ#!qqp$iI)D^UWc^Jz4yY?8o`@bN3NDqap^tS>U6Ffl=nR{6Z2HF zYG8)@ig6RfkUX-*IEu52Zd0N~^44BW9(;yJx8!$261AZ0g8)n+J>DZ`n?&p=P^Jf3yYGsB=)f(sX^`cd>Kr z2{Mn`Re4veG1nF|ANl_7Zubi_3`xGYBq&Io9>0)Wpv$nT9AR#LIe(u%*#UM%$A1Wg z0S`d2W0ij02H=<2j#kt=`phyN`+cUt4bLvT1$4HEU0k%kPEtz7vF8G{+~Wz6U#<(K zB}Z@pYgJJx-9{Oj=aaR5BQp7cgoNI!uAbCELfU;G5zT)9^(@|obf;ox;TIrlnF*Df z^DjoVV&-MHQ$FmpsY}JU};+-`{b6O z(il27rf^T~UF-pw0Q?dV1yK0hM*G=3{(R;T6BD!7tC~ljC_^aFPK=n+YAAANSGm&JRQnM9Z*;KwB0Y{lR_a7)iNJX8X-CuG3kW>{c@TtkMTdTQ%kvn{u8BG5wY@#W98rwmw(e z)mKXj11K!G*ZzK*n7t;egL}yTpk709z?|E9si?J{RjBx#cFdugX*z@3NA5W3ZHx@N z(fIqlKsi8Nd#7jZdR~gMDG-e7%0E9w8yGsmKLTy>viH<`GsDEM;KEhS+Uk%NuvhI9FjTJ=Snv|A=L;QFdc_;c&)3VN4yKq+$-yY? zZRe41R?GE;h9Jc@@5sOP{lx-!00amE^$A!6uX7jhMU>`}MnHxA;?>51-oupUtIo+@ z1e4?pk(k@eg0Tc8sf%TglK4Ea#ouaz2>G9I_5C%M3cF78k-D?Dui?HaYmD)25)1P6 zH@`ruhrU+12@78aReDWd7EM4Rzi>CaHlZ)bU1vM_Q6Jmg$bt+~|^aTz&n-kjfg5)HL#|uV*>Mc2b`O2Sob)Uka`C%rFdfyJ4 zehlj0Umj=h9j{i01yGi!YRu(J0z!psP5~l1%`L&;>yN3(vqF- z8$fyd3(nM$ve%udhEilZb|1|a|IX!t@^DATfL`W6w>kRahrVe?Ar-b36A)OV&*D=t zHpcb!^`vjv_Cn6Kpa?e16De`TOo`zTe6z82Jakh^-|~^=i@K)V2ei^^Js$w+jf$}U zw-ZVhg4^JksEgVWuG_Q|a=Qee=bF{lTT@2@dQq@zBy2QoZpS3U`#m>#z<+_jJ_H&?_DB*WR^o&y-9_J+^#~pFl^%mzm%LMCu^1-26sn@4<8FU%z{4JeHG6=njdFtI3(4AGqp~hmoC!8XHfsV z0{d&|{JX@CY;}|OTh6s;Q6;ncQ+oj*%H#IU&0_BW^xmCpPG95vTs6Sd4GLhR_P0zK zei!OSD~X(CSm=f&_(>5L9qyjG)iL?u1v!&dh1eQsO0h9|6Cxt{a=2=wf(2@=e%!_t z9tzlT(zC8<&KL3h`VII6aMULy!TXwA`VD`+>y7=oqA`k`*J9OFcP|-$&88Pj0m|{0 zz;eu`s7UOJWLQ_ZN*7z$B$~bzmP?)(Mr;6qyg_L#DHZZbJ>Fh-CFRXqbN{`ueuxSH zsrc~iXvoA;o6-r9`2fD_+MT2u*^1SC*Ap9Jb_7xdEzUdl2u|elPrte@$|$tFlqk<6 zzt=I`Zamj9SQq@sQD-t#YhtEJf}6?g>*)$T36xB+o>%ZARwJ5X@T_SCtms6xJ{xc1 zxT91L|5nu7Py8El>hwA05Fggy+DFCrYwsvYgqDWK>B05(xJpm1(v)~DBASME!js() zty0Vs`;YmMeN;68d4~~~Q^m{oPoe$%bbr2t3vyFVZbg4^(oHU~Nm(gWBT6mB{R>o( z+_#+9M02gPoQ-%Wn`L#~Y_YKC2FvoeWd-Z+z(NJj2h$Q^glZJuns5P}wcEJY&Mbw) zq8U3o$Q{sM-Ai%| zkq)6r@1P=}fFQkwP^2X!krH}{jV_%e(xpQ}krGO1@7ANWEoloi_Beik<0qGTkA%Nbt-jb72CCK}5L4$T=0ni*Zs732 z(y823%_370xJTMBB=aic#zw3pdrDl6#n8=glm{x=OWkW@8MJymHZd{7rc0o1%qbPY z&ZeNV0a%Yc8lv-|Ab(VsYPNq7I#^(xv9#sMSq}QZEifTsh#cY>tdxl{WtJ^|@uHv% zIZMAie#MeD(6GDxY?r*D#PFo4uXm^OOY3l|<1Mt(Bt!5KwlP-oj=i@ZcJ*@-B4^y5 zTR~7~nMHoXD^^m=8&G}PsticWLA-uOZg(h|?}-`2uHV?&V3Ve@QL~JGCsbzTC`~itK!WHam8rJ z2BB~JL6UjQv$|EYFF0JO6ntffb&0&G>bKeVFs%Avd9tsik#d*^vozLX%B`W~=|l)zdveT^5WsC>iIfH5_SY*@ z5|^q=S@HSwMPgo{YhievK6$sSqdS6V!rbz$uCbs3v&IKY+b-&{_~Jk%k#^GiEYU{2 zvgb5&jbkk0beNqR$c9YKo)CrdneiBy4X0#4Ll!%mu+_QfIj?S2(OU}lL>f9LpllRWlw2p8rLG!cF)m5Xu6U12RbloZecpl13N}Ja^=2t>z20Hqo*@h*&9l3W@IHxvg$C7 zNTz?j-pbSqIegEry==|Rp#sHMdOwBNQXjBJFcjK|{@!URG4p-MgnIMBWmaK&(A0>F zusfz9rG7@$1J*7dx5FWlMFkcf61B%>ZyVQnIDoG>vHp7~6w+Z~j zgpZ*R%EzKAh=oAiCW+z=rkAuF+(AZgcar=@N?%*L)~vZD>l~qTct05v`$a3hv! z)8{GwHHLE4tg2whbc3&I=OGc~erSV5)r%XIN<>|MAShaYEy>gBtm*9!eiHbNjMp7s zeMDp#^o3d5eI0#Y=?>iXev=E{8ySvRmQc;pe?4-~s->mNy{gu-#B)TcO~18i+qhfK zk@>{0NoVQ`AHwIec5OTR+U}+8x!J3j>W4yM`$Jlotxk3PJstQy0j42xfssdOD=TsM z6EZ)RDy3PO6dT_n?!(x4<#M^n2X*CG2IEH6L|uJ)uQy9>fv*ji{TI}tRI}$zUYEs6 zIT}xfN;%k1WsXnGb1Hce4H7@)^1VrdG@8(b-_ZhJ@XqM@?(<2O&-Cs-X)S<|9R|wX z$9&(1mPQA(Fw_&*c~EJ=+&#jEa_pa0A};hOrck;%p@&?gu%(OGtYUCaC}C5(h4y27;;@~3t_cDyT%K8z~~u$Sp5 zjmE{wxDBoK<5I^f{WT2k_&V(BL~%56=Np5hO(!m%bmsboplW1dCc0`fuMfOq!XNp$ z`v+NU8TT3LZEVxDdf&bTLV(nD6juy8)&eQ6VMU*KtwNL{z{x2v2uN3PN;VBqOtOk@ zIdCu4F=c{lY1|cX@^>XN#(4*z%4u}6QYBdpfQF}2%vTm~2spxJ;OuFsu3ZNzZt=DP z$%ZHkZ*l34xN(OY--l3p*4~D>Wk~X;&PMW=Tg#T`?UzC{s*;o0JMUeTUT$C^ypi}Z zOa^kZa|ZI>9;f1F|D98}v%=zWsg8RG;zrWHNMEXC9a{3TGJzLVny|L}Fqv4ZMR1+U zGfV?BK>SN@2aI#i&Rk-WwTZlPqorKgQxV=AP+y?1F&Equwrl9Fkg~wAF&8#^JSHwJ zKX~`IpuwD>3RmJ4L!5&&`Xx+Yz^1wsf=A}Ap6Aj!&7vRYzlv`;LZS(qLMwkZr0d-s ztEJ(d=It!3#tHT}`4E;&LP-wntdj-(TNil^h4fnJxa}_*-omU78U@(`Gv@K5#+Ghc zsI|PNbrd5nz5(&O#p~^v84E5oX!muQ&H1xtUV_EH3r!3495^FwDSK}|FxFU^M{NV4E5)|1(JW&9~r*ZSChgQ`}Ymk8H9xUX>$TAF2E zWT*ne!dI&mL2BN>bB|gyIA~6O3KH?w@v7)Ib3eRES84micw+C6&$OLEXmE!;0Pi|^ zx8cEB731P}yoJFG#?>WOJ;e{Q>|_>Z#cP5{=#tW?wK#8bAkV=gW9C)PlKGHZ#y4TX zQ#aMM=L~!`$<#da2yk}&)$-(4!p-#863`$2NfY_2MZO9%v5bRU=LyKlx#Z%1K%jP& z=aE1>oSvmp%7++GPPlCGYXkZ1HXrdh=j$SCE%jQd`R;Ko#3|l<$4au8-5}M-kU2El z`7Ta{*IC3jX!SNy#xq$LyJaTgXFzI|N;e+6C2usem2I3zDttF(0XmLs^`%xzNUC0~ z$=$ca!9-K*wCRgw-X1;t#NvM`L%kF&BO+JNEo=BX**rjN=*O2vad359s`q0YU?nunO z>mkTLm0jtw^(D}*4LQwXx|#P_TG_8nhrduOEJqFW{mtp2JZ~FdWJVUAsWfGiO7Op#cPJM!D%3| zM0K$48ljE0iEd5L60NgVS|u%EWZd@eM9d%EdeylxS0U{NBcyf+$n08Sk7gu&+7dgu zkRET}-_5k+t&0~3glR(KyJdnzG#GrIN_@JBrgh9dI#j+Au zH!PD#A|B7%5-u2U)O{L%B)e#0OkqkJzDCw8^TNp0(Y?*`qkiP!kfzhCEF6CdD<40k zP!nC#Lgrkv8xA9~GnNE!C1{t8kXd?PJCg?A*_l6Ky<0UlUc%T-!ZkAy&z#&i{Gh04 ziSy_yGwQCLD-fDV*2>$AI6Mb3#cJPRKog7q=@fJgU9q5~x{T33GD7Qh>D%~S)D)65 zWxTq@b99twnx4s=t!Sf~EiMJ$i=$9NFA5%~b!uvtqVTc5vx%*xfUnG9b(7 z>qa8R#^v10?Cq$Qzyq$<5IVyikD=|>8XGu_-1ccsFz2s%dT%DEMqN@|uHoKThC9eU zes0-N2NR+@z&C4UK)%6s&J}&yesz~Fjt0LDmxv*_9ArnC`AD03oYp8GokhEjE&c2w>0q5H-&TnhMAD+0s{rFF}T)-HM-v3AR67Vqp9a%Pe<^O+V84$Vr)&Bwy#o`zq z9v+a(z`)?o8uF|39_PmYf**Y=##giZ`}-~%Gpzx+lh}{|n#aE`@yOc5@|!w{@y@?T z@^5GS{B&#p(SB_moqwaoe(w44Eu9CT&m60z`3`(40eG6afts3H zI{H*Co8Zoi|EJBqqj~4}|Mq@&dwu6RE-S05@&UEtUce8}r`}|9(ER*-vG;tJseB^v zJWv_GMqo#ryo`2W9!As*Zwcy!ym9jI=gR0(E*7(Lu)WpqCEta08kr9i-t{w z-G2dIxY>>*Hg8|wR2=Rka_xuA%A+Abk=%ECNgr|kF;eg+_V0T+yp0gOF#FA|`}iiG zjEq@Nj$}mt#E%j(=*$p;NqCGq`-S|%0)E?dH{lusL%IvwKLH^eEmI)b^o^yF(QxG2 z5Bt6nG!Jj8YTU~x9sFf+;H*Q*waOnC1}>p;=WkpicR9O0B}E(^9J*{m2?1A5vClcXzihmGbMlZ(F3~mi|U21Z14}{0AA;oE(7O%Q4k0 z{$ZQ%X9i}zWE54gYl{#1_3pqUO0;(T#H{_g{`ZZ?(EPohID^0Md2>~VAR%^v?SHRr zSt6UBEvM;+W-N#bKuR`?7>uDA|3rxAz zYolWZ!ah$es2y!i|3e&YWRi#S=$bVLANhFF~8~Bhh}3JlM9w26`i}@N^A;c>9U|aHaC%l zj$u>ylCN{a0?1y!Q4yQg5lKizMvguK3Tcse%3%S-Tyl{J-!lUYll*g%3j*PX4bLm zs9s&9aXPruHv@m2XbX_Cm3wFC2g9?wdv>)OToGEM*c9LUnlY!#PsXv0>F8J{MZ z<1!R!Ex`Q42X4gfF36p6!~&@(RX&4+;X9nd=y%&MQQamV%Ga*PhEHr}vv~Dp3v?4^ zb|D%u#!PiXAaR!U;$y4!?X3VqJhGKXU~;4QY3RBU*;9Y6>Ir1Py`VS4xkT`YkK4cf zN|WZp$^<)B-*z8F`I`;>S2{cbk6+cN3dF< z8^R~mCP%VZ)R#DhEE;pk#QBxrm+Pa3hILj(s45D@gq#;#Xd5<<%i8=E1!1l_3f}9L z7BoHJ#2C#=9;Z5`sp4zF<_)j|Z3N-d&@1K$(r7|YFs2J>t#!fjBD5fHqRpAYN`pNuBX5-lCVE!X5*cn~DBmXrXXxu=W zbM?*c8e+GdN?9(gvRgV|2EF^7e#)esSS^$cy}_h!cH(VL$qdms{*bMxzPXH`1VP~2XDPjnrD8a39c}02{eBDV@xZ-?y4)gbWBJl5 zo#dd8MI;l~R|_pWNoSrV7^nGe=JG`FVfPlANFxiUF#=xlT#P@WxEnLNHQo?e3eO|# zVYhcMMrD_=A}go21FPbfrceiVT3=LgJnI!APAR`kM9VGTt94;Bl?q&?XqO( zsbaj-JDHv(OKmF`zBQoY{N)R@tfB<(p`?4&6Sr?7)s?&95!NTEa_K+g=al7ZO=50l z`5tlyoYE_Hey)-R=FKwXNNdHxFK?eRMid&>W;~hwZ|jW}y)$bwi32-zRM)ObmEhf+ z4LFReS``OG8_5O18!E!N?9y}uJ9h{`PY0Tw9%wYRb89Fp>t>Li>*4aeQP<(kp#e?> z?{7|qwe7tM5c6HTyuVGg;G61s7lkuOU-#U~nw7~~%AYwFH~PBJ-lZh|J4;fImwM9T zmGuVlC4t#oLg=-MB@3jO{Ubk1A^N{XIXjsB%?EqeF)Q`z^ue^?()T>F<4E|KmVS*q zVe{=(_`giuoMX)E$G^o;OXM~wlvH&c@5cQW+6F;dgk7B{_GzCq974>4lY{IqR**q- z6R%7zz7G*@*eehJB-0%FVuzESkn$lI;ih46QWNkN#q1$~m|vCl3@y$S zxHjjy3dB;eE|sp}tIr9`<^K{xzL#dqBs?lnP{+yaUU(^^xj4EG^tGhDLdnN!aM%(M zxSUSRCUQaFTmM3*9M}(0zD6ucwGZA4E{2^51bs3sHpduoaK+v3eQ?}#A~0>XM>27L zjxLo1ha(HG8X%L@eXze%yhYzztceJ)6_x;deln24k?EJltOJ zibipH2k9o=kiOU8T08x@mM|H+4WpjNymfSmnRB4(1YRi)QlfkW?+D4i9%>3^)8$^- zwXT_)Xkps!<+nX1xKc9QSQp#T|L)7l$ zj@xqf&bmUG{UV8`!jByI*kcoIuHD;dGm2e@Q{t*~3DZSH_C9Z3>+LCJ+v-a) zJ>e|{p_U>CHjE=vcd#2 z^fPR)4CR{t>cGRQri1tLymMdI7um=-_#2qwsw8J^6>8PC2v+(9s3NiYDs|xuL0*|B zgDWA5KfCB({qkD{({Ia+HXPa&=R$p>>sLu(*IqU<;ryV+Q!8vxS3T|U^5dHZCeigb zWpRO1+hqJtzxT6x-UWN^{`tr?Tw#3 z;FIThZ7ESN_5HAUWY@b3Q5^muczlMR+VA;z)i*2SImYu&D38X_N>D6LZo zSmZ{WpMvsxgxf4)OD;5X3P9Tml6Xli**CUShs z>pzzs-|f89Nh&B!PVpS?@E{BX6>SeF{+7MhbCuUw-MFfiKkk-#G=FEOM(@*6EzOU- z*x{hpPod_nJ5LMXzOH@DN0gZiP5j#CX{dCg^%#+VD3SFdA)8eR6G(OnF6@BH%;mpl zo*dY907M4n)R{*y>U`lQWgGYSFdmyK$dDduk7VD~`h;lnxi6LvFp+tL4pQqJONbF! zArHPUREs}dCvSG_wh_XrBHh$UIuZ!L-;~irqacM|1=dTL{Cy2EO;p-hXEi;ChAEst zk3{@lVC#+K&Q@)d%Ncqp;Ir^V%$)G?&lM zp6Ub{3zNT&gT=}AVcMpXmMs#wYCYeC8b)4^pGK5{`YtnBawaD0x(_{dsTQYh40&G| zDFh>4HMzC^1t4_5Q@+YC)PJ<2!ac#-lVCMnq3oi(6Q}jwBG>v8#RS|Mb|i|O@VS)* zGG*YpdSIZei4%wwY}`;15P+0p@Wu$E0W*X@rlxXO$G}K`*r52CNhEvKq%2PHpXbg= zUbff_%@tjIv?wYH%i4wZK|8Z{o3|z``r%hq6Zovwy3A@48n>6xGb36uxR5*r=pD1w z>~@zAyb7eQ*z*_BD&HMdOJ z{5G_n3od*GNhEG-Mq!`_AZ$)^S^2Gb%5+yla8dmhb4U^xWG08^J$JGy@0+?4?}`kL zbVRK0c|a5jN|Mn~m*k8HdCU%O|KvBS{hSEav<~YSfAjUoiFq+gP>;xMHaeRWITDaS z`C+U>yufeFai89}DkVKkR5iw$nL9$Waka`Wq@&%uHYIxtq8S!i5#4sShd6dxhxcpD z29un3w#;xse=~D6UO}AEmho|CkEI7^=ku4w@dfNJa)k$klRLH7);b+lGUpc7I8!bc zEoI7HxoulW&(=A&CMcPLT^$T+&!bu6wLm~=h{?mV@>qQ|mNx)eI0*y|&J-co8K14o z5;&4#Gcz^IcXO9zCa2xC*N3#uAFsD<_GZc1Cx~{I0#ttTl*;Pm!O662$=$~uEnV+( zx#Ak*(EyjB*&~iFrU}y?MFn-9aP02 z&?+}wWK~~U0KDlgJe}goYC!3KLat=3v23{~U5*vY1s$xS#Y#eYpIyg*$Ogi}B^!0w za`I|e&VSzVFTR5NuI9)si;95`iL|xC`VT!`;={aBNxCM8^3_ew;CHVIoM?^4j1A%G@^H$GHNdvI_aT)R}nz`RY_NG4$eqoVQKEfE94 zhK``XMS1b9s^wtQZ>eZ*cfRup|vfvgCCVM`OD^Vn8 z#XVy!WGA(fJK~@hlG+NN9jhh#7Mc`?S7=&lS;YDe*EQ*qaf*_BkNol_R%I%1Ef8+7 zAtwl-ufMAy8ZHB@cAw+uoUV&p;dJeggfFHm1%*M2JM^NgG!MHSmPjLd%1k<4P|1un zibqTt)_N(*_(P3oJ0hFX4d~m<&;N5Lb_`?Y+S|H3d`So%czoCeQ^aj93Y7;$yi8i1 zk;7WlKbPs1hOLN4bxv4%h|u}TyErUp{f03bXe|+qxk!e;`t8E4S zx6vtq2hXU{>kzy&wy(Hc3cI3Py=?`$mW3seKQ#D=)fX_IYuveWAG5cr!&E1fA=777 z?nS8{!&xnAZTgC<6ZVWaW3%U`v(!0F>90l176hj_+0gg68y{BUD7rIgj7hQ2fq=|h z*6T*2=v0sPF?dSE%E0M);}P$c7cKdm4(KsGdMHvRd@is}3sQe=aS(3Q3)+Z@#E>-# z?O*LhQjZe<1qk9G?oZC?1XPE1gY~R@p820;Ril#yTH5;Xbl|l#rRU1z) zXQx}s(UH!ONk(*Lrd(>Nn}9fE6d+rTa-Do_O`n7WFl4H7zH!}>!VKk%6 z(4{Ts)pL^wsnRRJ?L}LQU%K89`&#_l=+dCZR7E!2e_x$ngLZM#)0NQ2S7WO@<5ECX zAm6SIu%oqZe884NWj{Fb-Q+{P*V&*huG^_weX@C=!ac|-?a;*zzG?@CZ-fBU(w!-@ z3FPVFmtMw4qL{cwEm@>N7=w%Y32!I6g={A}6P8<1>Noe9!tOJ}cAL&UGqqFHuiw#vPWRN%RN;+8T2VME-MljUZO-K-+?*qlyf zbtMr!mGp=SZ5UVTia*VxTFlFv`znq;#2Z->N`*>9v)8mBAnEqc)(5wxW$72q?%}(d z#sT5RP>Zfhd#D0&RL+aqg1YVK$+Ba|6`vRc~|osh-nsc(yfpk zDwb%KBcWs&=a|p>)YrDlN`*GNPA`t(MJXrzRX2YFgC54Q#|Zftk$j_xzcr`K{I zAgmxw5_b|yRNPv03CV5BLs~0kef-&eXI`x|u+&Dxr^IV&QU?0{Vv*7oTM9us3Z2Jd zIjKeWd`{OZJNLu~QFj-{9>wbkz?zJSxf*Szd%7b-Z(Rm^5?l-;MN#c#OCTwwl=GS3?)VeI~*C>+%A+`GPY`F()^ z&A9J_X=yVEE@{$v%u)&9sqHdVK@R5ER7-~~i)RyNC(&@UQP-9Z;_&_qDu z*Qy=UR%P#79(gFptQQ0y#UMro*QnGenZ|xBw5ySY*tPBmfvLKOQT54mEd3EoBSFox zwUFU%wChZS$7t^U>vUYUwuEeAoi1XMWa^J;yI5YDeISF-ZoL^RUwKcl_kxicVS$PY z34-@cv{uMLRY;L8eqwvG(eQ>kDBMW__4c%@FQ=~R(Pwn@_-p%FTW?yuDPd^MQmZt{ zVz${>T%e>Qztya9tdRGE3Mno0+~O1L>Z3?Xz5*JoIRu5k9Y=oO^okwK3cFF`*sk8n zum%@i2kY#yjL8xvn1lC;Gu<8icgsQoR?VIjDLlJj} zBs$IfA4g-ePueP-Rx~)mzpEF@?My~|?(R=}8)O#rj(y5W$a&y%lDd=m;qb~t257)g z1n|3EUe_|5?F&X&4IPmT6cbUWd+@_BbO(Cu0wt8Q=omg01SJ3e{qy$fdoLgEmwZ56 zSxdq-o}hiR&@bSVzo4R)Koh~>VjL)l++3E;MRYkx7NB|gN-iu8?!72X65R_E=keY8 zEfBmcQ0wP$ZE)IIK74>`m=ayUY0jUtz*Ef2N zlwcK>=tHGwQjUY6n43*}ZWv9OTlEtrX}4E0bhm%wF!i7pd#Ic*647rBXv621S5ETk z*Wnf-Bp$4Kq-Sb#3MQMjxR*jE4ns+zwj~VO6TFL|Y1_DSc4BK28ZWMJthk?5Pwq6N zHXgXe~mgO`)+U>r^BraglqMWCH zH}M>mN+Aw6+dDdB?lO$Wb!z&xpMeDJv@jj6YG{vf%<~Uvd?*bsIi_H*CM2mV%)6G~ z-+?w-$li_OPqx)v{up6Aa@*f|w4XVkVz}^d-H2$;eo~TX-!7QqU6Wnm7kA$IOGj4r zey33EPDg31P{PnBFRYRLP)`(NlflcW?>Z0h*j?70s^ygzCvF9%0YbgMbpBKQ#pJgD#tc;i~nt1@tErw4?q7( zi(hbLWF-9`e|*)Gt@2+r!?+UH3Or7gU!$Yj?zc-EW)u9TJr2m#2mbGB3s0XurDJ5| zQB+iHXlg2jnCA3w=Jb?Ap1lM&!$8y*PM2R8s~xA;?DhVQMLZyWAXTdh5yQOA}0ZmSSL39 zm7D&LyHy5Tb$nY&zX(Ns&WhP)f#~T(Q-I={$B%!h17R6WD=RDiy1J&n1rmY%kJD!z@#j%M>h*t-xcRl`?LDcHZ@efmzxYmm?fSm)=LbL`LQ+BD*yewWX@C7o z73EU(k9^?2pZ|}$(M~ky&x@`Rxuv8`rl+SbVMT#Ja>&xykK-P9bf^LG^v;P1c~JL= zn*{L3EElMUhl4algrubQP<;j;#>QlOx_^H=bo`_E2zV<673w|eFV&FwSN2Uw@ZFE)Ubep)6C4{=W(;QIREc8EH6Jlzx`(t&_6B> zRNA%E0o(wZ8G`a_s2`8ql`fF;%`o+kY`z=j-|@EZ2fR&Umi5;HxLNw-cgJUcMYX$G zBMu89j`vlSW9cdp^8Z!2=u7z@zS%AEQtE8>9iC3owkd{W1Cn4krCq5}rJ!pJE7K)Sbe|{}c9z~v|c*>H1YjR z2fA^33jXoP^M_ z&#a}pehgTbJT^+d9_Z?nC3dI$q6K$Bkt z!Q{X{xT4`M>OwI{&H%E(T9P%9u@UQn;`t5Gdikb?a82OnGyV1bb|9$?@T?4iQ~eX% zP@F|O+=5Qhcz1o(eYqLmjXkSX6DiFoS<1i`2W_XnGS`VhLHB9oIU?Kg$XTVz0#(1g zPvW4;5g+7Lv}WnaQ1NFu_!Jh|Wnab1d042!d}xW&A(g^7fe72BMQ6fUd>TGA??{U^ zQG9>5(*0Xum5a5MaTq`GoJ)(z$r(@9G93=oc<#15rmAi*zR^H3`mCJCoWaeRwO^|# zyY06t!<#3cGG09g+9#aC>^Tq16J0Du3h$+fcCT2Nv92ZHoW{x`j9s*d!JB<)>Vl}e zF4JvOzw1>-0q(bt18BLI`2kf8UvEJ~LC8AxCD#Og1UVPJ7@ni$?TNd)oA6OvA_^63 z?jScl{B=x^BOog`UCN2wMNwfurglyVQ~pZVYAq`j>Fn;8Q*U`~T_$VQJw|rI^@1qs zs2CRQYxMH=$lTgY34g;8#bUA2EJUU^LA+Fgb62r1&p($dforq>cUlNoIVyB~o|L2= zb;@eEfBuA<8h+kP3A5kL0$+z|enS%^FEWa+Nh`n0NDi-dKhe^oB{oIC_=7@7b)REu z&2`0kzmI*|72(V2O6g6gFiVi<;4-q8w!X{a?ZJ0xClw^{earGe1_D4kx1 zDhtabuhA+;Sk*$!N&_Tt)C>Ke72$ErZEt8x)?sPkmj7VxgltXdLS434P;@xWIC8c< zz}ZBgu6^P|s&txO)2$+L$4`M_3dWh4Xl83& zICWEcMn;bLvSQ*?Md^5*!E*s#Bk{Pw-BuxeY5?UrcG51D0ITdOG854*+;!IKZewa5 z0?nIa;cHeWOT^Q56x&F{Y@A*C=)5{-yYxanX8@$MvWd-pe3AS5wQD2{NocvWBC>%d)7<@N2`v_Zyeg)PXq4sRch1q(QIEcrb{-kIpz zY^d%xbOu{iXr8wRJ9Te6aq+q9b%86U?)y|`zx_w$393yUk_{3rFML#z7iR4Ymy(J2 zFRjvzdii;y0Yaz_<~T7#z*Xk@+Iu$?;p}xr7$t*U#t&{MkgoIM+dF4cV)2mI8G!1- zC=3T_U3mi8SIrDR&r(EU;X%r#30E%4g^YUTN!=uGxRCS~X_3Mp<95lICB|LRQK^t< zmF7QQr^E#;9}uJs>QVn9mRuqsIb!QF={(-h{7a&J$ z;jumcaId#d;UUT!hoKMXX5kW{{U*p3DR@O+OFl~A(`a32(wVwZ^m#<>@)mV+IaFxp zpVLQPrwkpj zdqX@&{ez&|t6LNu;sBM>AJKT-rGpK84)07f2;MG<@rPg$kdCi*yjPD+V>zlY4tJ_kY#tJ7|2`vD3twm!=%TmTKCq# zS{E3Ff;U(u-(vmVm)ki7093_s3~cwoXj6v`*OFc8u0fKl5FIU>C0u<}2R)cCC@;QI z_eVp95EpJM#CL7YSVnZ6?dACd@O+}A>+F|J?~H;iWMi3kQv=hTV_M8!v+>}w)3dP> z01-wD?tr{Xq;c-5An&fk@R-|SMGpnhWgeyP{I%zoO z8WyMQi7=9s6ZfS@p|(%AmmdeoKoLa?p0FbS1}%eab0$N@yQ~QZdeyRM02}0ZFgDH5 z)ON?`7PjB%S%s3-pgG2SGSKF+fYFvUFFNCzE-~OnG(6a6cTVzQfYyrqk3LuDT}m7G zor+Yd`&iik$TO69;E#AM;n3)EoN->f%0YKtbKw=^A_HVR6*oVy8RBk6g?s0)FNa}z z4M7-%BMrk^Afq{066lG+=%wr=Wj~pSvc&8rg~o}H+dvxzRsgR&CNI%@6r3EqLB~$6 zGb`$ch}F*Cph}Z(1P`sthK1ZIrc53vv{HBJX!jOgjo;87TuAeTKTok=J;*f!2P+v; zBZ^qwMH*3E!l(3N>%qS|=DP;$fZpWeZTn50k{N0K(VN?mEu+I`0RIolo^?pQqv+A5 zYq`P%EG+|A#et5G({B*D1RWb3&}9skque=UKPV7h(&TI@IYq1{?Fy0ks$bVfYEmc_ zcTMwL3e(Ya`Vys&0P<&J9iRIN(LB{~|D(I^S6Ixd=HLanB_BJnbuvDDVa9C}TRo?( z24#gp3o)YM1BJBHkP*)6*HX;TNqyQ7q<-Ke6NI868e~0Egzr`@`%p4Lg-j%p45VOi zB0qokddT*Hb!D)^7nQaL<1MSBj5eUpYk(-^)ZJqKWV+&scM-h30(UX+#;!McgL!G1 zHOCKc;a#_q%>vEo{C0GaM-C-a%rSVh%0NEO)PtpKtX*tcu`O+C7^i<$TV|!iKzkH! zertIz+97*W$Ie}$*2GnnV4VI;?2IJWwV-rJ1vq>DRmiyM>S0h)33f^)Lu7q;<)XAh zvi*6}vNhT!7q7Am4M{gNk;cq7{NxPsbEt}O_3lf%4si}ZSv7uehYq(2M_E*MuFSHn z$7G&;xEXI~5(p>-x)kl8*AbhY#k@BbF~RT7SauJatncub-f&UkoOj#Ev*NKCe9?NI zjxNXkH%pU^2$BqsfsoFLKDN7Y3MZ4!69;J?I4}kj9E6_<&^f+wI|qT|Rq&DRoLDh81)T?^r2l}Q z=ec>uwZjVAxigQNvL)gNGU8OqO28V5?{}MYD@h$y%A;2^G=;WF6}Qh3>C^8Ek+J?Q zv14_5niox3ef#pX#`%6V5n$tsjW?o5fo%+acbql5zcBZAE2`cQfq4i+$5J7(h%6#b zt`}QjgUg8rp581L6##ghiGUN(!RQ7flfTe zP=6rkBJ5+H3USIE-8{*tJ#C$4I5G-PDjP>h2b`xpUeFAa34hAjV~Q3?8RItpD4`9j zv)gT02J+-(dZzQLK=P4hJ0WU3mV! zbeaJ^Hm?eLU>I`$3df?ANr{4IUkdrg&~^~QVpsQ2`^9Qa!p$bZAO=unbKTUKokdGo zceJUMRbFSa{Gy8^_sWbzXS;bGVYoP^9?w+NlY;}}IK#bldHyVq_lZvVJ{yBY@P1q< zkHu?nH3DgT2wQskfLQ#o;;}*V#OkX|OFNUQ8A{*uED$w=n+U_`+RBGpKcco)T-t+X z9$SDaUc>nH&1;qx$2y}3hB=sxG5{D#FnB?C9Bj+8gtlcdKEm3**ioK16tftMIItX8 z1A$86?Z{gF458)5PR+@@TDp|wq{mwTZ~4`BdkaGA9VL{N>0B`E2}kJGA6SKrDzgX* zvT?8YkZby2s?>tmG7&?!ZlUvA+7;p(Kf@@v!~D$%lctjky0aJMr+;?%fwpPf`nOvF zfb5rh;}wV9AOHHKDx|3I%W4tRDTeq`3``KYe}5f=%1;Ja6PDhl#HtTVOhe`r$Z>`r z=g&9ZG`tJqTTJD-{ooeZ-5>d(g~H{LGl)r=OXrBo)sDXX;e&&yTVsv?3keG!&}sk` zo>1q3*(x8?^^_-9yurj_)?&3$ATq)@J@5$Q5cA$G`ofs9`&g(NsxQ^>GTFoZVnV9T z_1KdDL~Wi}c_4N%wJ+7+q&QdGtUS62bh4&c_WS{i%lEkL#BSHQv#Lmhrller&5*R! z(`Tts<~nt;%TBg}BW{;xt@o%#Ww|RVE_NGL0SVWMmAz4@hq%SIbLpsRp+ZYphIF*E zZ{L84PmvRC^3v}7t1PzrONQS7PM%JcnLfVlW)P9V-vGsLnuhju_gmV9*2c8SC+l!s z_ET|s?X}^#J%AqN=y3Kjjd>--&t&MEE21VKh#uAI8jqt(!3e(y_wFH(H7!yo zkuF`#!4>iD6rwwHt!j zuEP!AfsWz`z8U@1g_LJM>Z?4udJ)+ufx|Xi$fXuJKh9g1S01~+u9lKOLs$ynBpYm1 zQY$RiQaxK%8gwfy^*TnRcv8@z)$AS*lffR=4kE2&w~io(4nEtpAHJVFlQ8P`z~TN@ z3KVc`QtF%jatpqCt~|o)KloFeL>zWf)s3NY-WHYVp}dAN=7Te*7jlD3 z;?bW5PL{r^Bj!vsU&2GUdG{n&>jimib0k*8==zZ`rp1^2J1--+jiUuUM)Gm-PvKK< z=CFLrjSB{XLMd+3VEVklC-M8>b{+G1i>eBZsf|DkBEmH7Q56YSbh4x}8Vy>k3oRg$ zsNIsT{__GRcUyu;koN_FolFt4jEE&e8Lvs+Qrlust_YCL@b=zFSk@I**wQ`!qMBeW zXi+p+XnAD=M|ZRSK29sx`U&DGCF~13W?S3*-gM2K!XkQiHO_024U-$Mnh`k&dkbTu z?U!y*OVHWvcNNZwr`bPH z zHX*j_6@72RkI8nRw|sxxdth0+HvJ?n85sD+BYk#6AS14^Ov6GI3ltUS*39+o_VXW% zI@JO<+v_dGchlkhtZ0T3curC9y<@AM0zO1ayjNmSXVb)C zLW^2*VU27cY(|TPcg^~%%KTW4CP($EIp3WNjGM;LHqbm%y{T(>q5*b~GJ3_*c%A53 zmK;G{YI=!VzPlnS(fJ>Fy< z*0iy{H*1J*n0UC_VPFY8y9-{m9kGA$872w5A%*=$j!GtgxNWlm`Z$gXWiZ=Z}DbrIVldOJ0i7c4so zFA|cpJiG%W)ocIgxpDk5fo>Ib4sT2EO|4aH7cMXEY=$Un-e?Y4}ars(6!jy6?mZ!2PQk z0)|YEpK8pa@#sxawp1V&8ZcaF9{sul) z?&XPz`2M~8{otmz>ZgzISVgMp7{-iV&aSho9bFXG6zS~7<(VB!Sv-2Iz}TSWNpMFq zvYmC=IWaC*omAZ&yrK%sMu6Z^q<0sB7f@?Tdv>zJBBK$~hB3z8tHuX}N{Yku412-G zF2j3&?$WsOlp zH7DfX*;wN*zGZ8D<*whC1Q*Q|VYWJiq0fbl21e8cb&@aNC^E^p#WujkM__wmb`;P| zvz=KHR0Qb&CDWBw$f}UZPz^OPtf-Bo%kQX^xN7^4yqpBbc1$l+y+VD_3_uxxkSnOQo zQbuG51+1kC(oKDHCF~*kV!L@NE)!;PAxF^7r1%TjDma{UKWuVP)Fvj5)FC-r)0_Rs z&5~xqWa^1xjSxHqGNHjHymlFA1dmnu!m2E_@^}xZIRI>`2ZLTJR#xD+2$pTWG^EKm|mE+1o?EkHRX#g&ZK;* zjE?3WhNOe@MR@AO`~l9Z+N1aZ$GhJ6TUk`&t$w6j<0(0eTu;{=B3U0HS74( zr1n*=8sp#UKJgkM;@SX4N+rH_$fDD1&5XuooR##w34#i&vV9Lyoqu)vKlK5}%K z*!@4meRV+7+xx#>uX;IweeH(+zIqL|7$Jqh$tl)jw%vb+T@x>y@SaJJSu|6yQ8`MN~cf*KKjbL4}_NiW!g-M+1QLY;6Vpq~Q0B3vhCm`dkJ&NaLN1_#qnt@IU=GA{-`C$M4!J*tsz*ZB4sZh7Lw>yJGJ!+J(9jl$BeI%F{q19X(CAnk^uel;PzH49Rik2#C{aO(f^JZxWDX zy7suqxLMy%mHR{SB$o>^Y}YK)u{OP}@lSFKBn}V71yHlMkZ53lF@W@O#;Qt3;Las$ znC(|z+a#~&TcGy5m!Rl%Z?M<=qu*z+k^IE9j`1*f+d7VpDdqDeMCRKSucJlu!=TGs ziGJHF#%Ws*em7q7d`KFo|rzP=j| z61~P7r9-+dnGx}VX8s^X(7qs2$%$zXhHcV`@54TekD|qBxESe7*mCDa`cYKIn~^#; z?~dFK_A2>m-wmn=5{B5MpAnv(%~|E1^GB*c1{Z_F=~}YOsl&jv)x36BV#1E}Ljtx4 zC*cWSZ*tG~rj20_B916cTGHYfKX+~w(jXhA7i*L2y*Q+$O*Wl2X(;FNx@8GY^t zZy74jD4A$wVSK)ip+%5EMq$o^Rw*;C(;s4NvuPsjKj@||K%)>NhUzW#*DIA56VR#c z*0m7yKv}m#VdK~4;DcA4UAX@PB9|R?(+*FX2RLfQhMl`}A+8^Zd5RDv z@!Fs(T?E*OTeDnX9bxObnK`?GOms1uH_xr3zO|qfo4(~(P2Uhz=Y=pAS&OaJqPgL+ zYrC%9&;yr@$V7Ch*3gH5@b=vYtsQI+S*D+6`(DYF@0jULlW~aC>Y~W|H`X!Jn{Jsd z;gtgDnE9-9a%Zaiw(pUwePz_F4%23?pra^fg8u!TDZ%+Az$~wRZtAeTRjJwf_>iL` zGObl#(Au#^=Ja`*8jXYQSKXxC%=&w>+gvIsC0b4eRA7v^?BS~XneT))`{r(v<5(ym zudxS9d>)mdNkvsApS@two4S*<#i#;iiq&=IOog_^=joj!fQNG)fooJmAx|U<8;#rh z>d(=?O-{@S3hBUA8hBwz9jSQxU&OX4i|QflB09mGsP6K7I#e|K*+|3)T$}|!N&$yR ztwdm*2OPu8N-0~?^_60je{jD_VL2HTG`5k;jHVh+f}b=-59fV z6W}(Dsepyw$?>~ZREvUgwlfs!A!2E}_M=<7P7SB0Yz2VJQHQBI2bZm+-$Z3JwnD#} z#c1IKJ?l2wJdB{7Woh1@RY5zZY!Ek%c+lYrbtc%D4&Sfk;>fiu}7CN zq}oXX1d#f#P+-Q~lrIe=%(fcACSzv9?p#dK^$-c`J=;UHUTG$WxHyVJ zI=l^@UFe%tP7dEKGA17(T~6?-DuA3CLeE5ux47L-QB`vU5w>f0Z4P}KtqN|M%`p2E zi_UG9fIW1V`MGYp7`zPtdm5o#2%6Z-l~XnsdWup7^y-fgVz%LZuW1(YrgxZmUB{a# zK%~{vfHo}E(>{rmFt>WaKOK5-S0!QBNChB~5o@^Hk{7_))oY}wPeu5JX+Wy$pUu(F zI4`;I5;?$r!=mGQp3qL8uxmhL+YP6oO@fS&3K+#mnUXd+O;Uz5S z%ZXRvH7T@s&93k$u(V$ZoB*qe?_xXQBhy5`lQSe}&MxSyn}%0RTkmtj0L87vENux^ zc869&o>d#XzIbavUq2HG>|$(%&3hwV#3ne~9QW)zZqQ&1#?8&9(3f!qpV|cHCFG}B ztyxC0?`OJU^wA?$ZJ;6e%c|W=$V`9>f04&YOym55uCn9dPAC+@l}_j2RQ1F<)jdT+P?GGH7;v3utz;J8w80zO>b-z3Ucdbkz%f-K9>JcE#rw zxxAA=fB~&q7mh<~$!Iw&`L=%8mVjBq9*!#^DuEa_lIOR)Ag6esTAFCwb25H(W65X~ z8+Hf7e=v4erJiR?n`G2M-Qy}|H#jnMm!@lPo|||eI@p>Q&_rL6@1!8nk+0~eLdY&h zY~rJ^2&3!uj|#);(eQEt8`2r(p_1!H7`t~-7yO70Fi$}g5#=qybWU9xu6IE16-F-@l} zv;`qvb&;C~RVo}-NqvxnK9jrT1g<0nZ;6&%er@cC_R0;Pa{TGBKVs3htY2R-%(3irtS}ME> z`M(gHfnc73*-6~pfqWi4A*WY;BRoTu`**PmdP>4~aG@$6nMuIt3DrFf&{ETPG6dWg z=nnXOYYVO=uW=fw6#A^D1(5Pt)Yy04n4{9v`U-RonWRZ=#q6|YcV*ipPJ_z^q{8R~ z<>}9lyvo7V=Es+FrA;OH;)n4j!7e0?XWec18RUK1-pa3-@^Yq2-;pVy{|kIpfh6Mq zdQ$_2+oi@>Eu-I$74()GYPR!Y_`Qi%MB}kNcAu`-Nx$f^o3*6AupFTS=Ro2-6Rw;m zj+xEnOEYW@T>>0E(^_k(~V!?i^{>t}F@!Rja40B%bB>>{~lAc{@9;* z!Ef()+S~*MjAeoemQsC0^Z*H4gW&bN>!CSVt`-#)h17SkKwRTti)&EUtxeJQ{mA|e2AHRv4{^QSapN(Bd;xPlI)lHOA%{sDIPL)1FftHrAWDNMlj$ zc#+J1IU#TBdTflNCEQ~ggppnLDXb+pu*v8j(dGpo+bF`R6$r4+ZXXCut}IB5!h^Iv zH3bm|O7kQ4n}Ke=aYEtYeejyOTV#lwAQfs@(Z_NTkBxF}4dWOT$*ig|pJQf^=T%!9y!tZjd}3}UE-7N zMco!K?Y)h?9^5&YrKrJ4)WK-zCCG~bGt9Cc~m@@?Ppa%taTopF)e@}b{rVqVxjA2#<$pL??XHk*~u6i82o^DK9a zp<~3x4H0!)x%#}8(<9ML(%Mw{y?VC@i9HA5Q1}34X?nGy#S@KMoBLH`%@!{g6LLj_ z?-aY&pami?((IN@Kih3`gY40S5{~rxIzu|9v^Sk!U`0m@uQeA$ef36c-et8>$vm8m z(u#RV*l$OPPZ=x>e;BoW_7^8~g4KoBljtC}L{DwrY_q1+I@%)eJ@WlvNHz()k z6DEPBPX`+KYYTYl`TEaIUFFPezC;f-)P)(L6iC zm9a77f#wA(zU_C@924}?9XU|;tlLFH=aCSh&4TXYls)w7(&K|ENm&S=yk_ZUxI3hf zO#F5^LV%>VN0{`qsg5a3EVx+4(2K#$<8#c{Moh#HYxM{|YUrCay{Ry(De|=*M=cTb zQjxs9?kJ=~pV_4VN*wk}ZD;$W5hk${nB6|WF|(iCvY%T$qfk;^f2Ep4kV7r;$SSbFKA&@i_<%ziGQ;z zmA)M`KV+0tLPtQ2HK8CQCGpj;nD`kLF2Y!Ls?0LV0d4GBDP@nHHBe5|r?J*9+!b+c zP@9+JV^*+q3FCk$5DzX9EA&bJX?t<~$B zMG0h|hpvx4uATKXn)f@r-;iM6GY5dC&5((TyPYOuZ>}D-5kw*Swnn)*AcAe4YUNGX zMn{(3-Sn)ovs`^k%h%b5dVK9XuQtJUNTkT+*ybpVA|K4oyzh|Z0{^G2r(A{G`o_Ju zc;%z!;F?qw<1O{TXCbhg!wL*r9>Vi+mBitVD?0$JCTj1}QZwI|`@k@B!kj7hRx%SZ z)M&a1ffOF_Hz#e%fYaFfky68`t3nLw3OL8u9~^I>d$+>Ve(z29u5sp_k%#Cy=7;DX~(6 zVDtoV7SaJ^U0oS+DNlYw=j9_7>O_a{ejN>V=-D}KI5p%`lrM1BW~Vd)ESloNJ1=o> zsFI4dGcAGji0U?>*aAG;&0wfpfv8N4_YpJbdygUck_?LF5uEZa`mvB9f4+^RvA-eq zvmo64tWnz3OFO~2>!PDArijejr@iq~Q-|e7V{OBE7n>n5W{5}wLh$$tEU4m*XZ`?+ z+twlySCLlksiTp^9cbO(9kaUwgU31J!R00b6OOb#U?kBetCOy7m$+`(vRca4KQJ;D zWZ}MJNKUV%538+r%%PoO#GIEFf*zz6J4dG})zO2~b_#dRy>$e3(>=R`L@y0(?68%Gma{PFn2-ds zElOdhV7F{ci1<}fiiK0b-e$I?sfgHXkr~6lmse39JG_}#vlZgM*wrs+h~?MUsnwYk zRT164w>isBy5Zwu8yK)xm(~?{A+O=0E&u9bchSt&y?bt1f6pLG19=pXp?@3Jn?z?l zx#h#ZvMFHqVAJTrBXIiEV{*r9%couK@p~Yl_H-IAKeU8}8Lj)u&gYW$(K>(wd+e5$ zHAa@ddyjv`LeEx(j8)VrHtceCvlKGKi|6>&d>oU*O;TrlNig!XYVoAsE-7ze^{6jX zs3dNIBZh)<5$5d}Px6-5E;p^2jmR}l@d#n^lUtzH2l4d@E0fq4gVrTa8^n^ z*ys1#VG#!V>M-`b!c1DUqG;#I2&suVSG4pa>F-6#Esgt9K+#UASAyIU+&w;u4GsUi%-59Te>DB zIr3>X<6>2`hVpJMATcBL>Km~p>1`*J$*|Vi^oH-~xqiqrUG&PcS?V{Yh@~Mpz!@w3 z?K*3wXv~$~d%kL5SN$WHIgXdZ(MTw6@t65T&TB z_+)YUu}7qis3V&NRT=<48J7*0zqzVISFIVkt}xi}CR3$s{(PM!azH$xcy#^&zQFbw z^TUPSZ3#(Y=!|H5XMM4Qv4rG`H>4;=KZPRGxoFf7JQ|*Z@(atAIL`= zIL-}5%L@a{6aq7ck@!8WzU=tvG5+cMv%{2j*Dw=uYM-FEteF%zp;q(Nhd;uJ`S|-X zHNnh7*SbztW4Edlc0k&pIzBy#g*Bi_KHK@akzJvxN)WT%4bwo@2%~IUf5}d(q~O_0 za5Y*}KR-5e1JP_h?t#e-MC|#Ixf>yh8-^@L{bg`T;*%5^jlfb{zn641Mw#@&1=BbNVSu;e~(LJ3uw^%oE2>B8#KYxuz6Ku8+6w%Wy<+4PuQX zgwL(&!uV!G+l|H0r)=wcta{psmD+rG{GJ=P$o$S%e{Lq<1<}v2t)f)2= z15r7KFb@`wC&lmu#I-9!!Uxx%C^>VWX4b{4<#P6_vkt1mZx0q#fnp={g?eO0xuaty z;MYrSmsRE(^A#KxHGM(_9YS}6ofm73=cb$9d&1Ws0&!S9`t!oKS*);DBd16zy{ZS> z2NW{mN0ActI#PYtbzDah6_y-So!X@@?sy>>oFo*yt|Ciu6{w@<lR4C5UWrSzKSo0C)AqdoC@)c@tn*^fb2f*cm=31-L8j1y0- z7zqc*o^MY6!b07J-6hG250lH~khJ32*-5T#P_SZPHV zPIfs8JlU;x&J$A|L66*0VREf*x|oCx88GUZg)6cqB-&R0oqHoeS7zPwW1*Dos=Cp| zkbJrJx#y5`o;~U-Yuo}8jBJpUjc2HA=M*tjw=MXCCJ2UJL=o-afjW@GL`SUEUF2G* zX+Jw;&XuB5IYG+E5L=r@Gyu@BUQOi$BgGwtok^3TIjJumBm4`7 zYAvcfJ==EAc8efR2aaZ$%q7Lz*K#e4vEXN-(&MSljAVoam$BZCBqNRf_xFjqt=VG| z#GLwdx87kUSk%V&gh|uKY?t*jvlsmG9xh+R-)_A%I+GK$So{a~LxpSNlaay>a&b{C z5rMq%=`f}hM1ITe6UHxpPZxHHXA>10mIcy07~-hbUO$tRW_atE&$d4a?*?fVP!aXq zgDH|PMnl?LAZ0h)}Ml;0Qcg#1|7aRfwYx=cN0r=Z2?Z7E7%DRuNf zWZoj;Pp$ktqYKP-d#~$`oU8Xg`7W1*010ZubY znl;M`J|krw>(k(%W82B^CP=rDem*`vNW(JMxo){lkssX-K(jadllHIE)6=iN;8br8 z4^#|iXfe(U^V|Rx3{wzb?mJ+W_&ymG2g}}RcJe6BXv8TynwWV%$BpO|GasJ=X|>wd z!wj+vgpTFX-rU;Cjp+q;PY%B|_{;0#Cg%Z5Hg0aJ>bc^#YJrq}3shp>Hy9ep))J9OpERw@oB(|%5*d!SL5 zw*YjfD*=ok^A8Mcy=#F``bs{PKeX)UMdR9Z}- zj(yT#j_*XM~vrNnNn>I*xO+Q(1N9QmsD^;>;jf{}19V=1XkK20tp&cfx|xtt@@R^Hwf zALaz`u6y>3KCmiO)BdQQM+*MRhf^Labw$bdvXRuXA*FVjLKuVT!pa28S(2C&g|(Z( zg^yH476HD)j$hPmz1P3Bp^)I$SzXa?$(q!0lv{ zh5(l8#D6Fn9#(4MI2wH5%Gb;4vLs8CEQ>(hYZ4pjEDtFD69OLdAG4Wz%vhVWhZ{4n zudYz6C6;$@yep=y*w=w^PQTd*?#kgWM@EQnlW8Rd*$UKp)OoSa#2Xk+netLzx)gci z{#j0XW4R7% z8gU-hSfIl%T`TxYy5;X2$y*<80oIue43R{0q=A8~7!qnmw=Hp7>bLzW)Ja{91t`LyC&dCMRLR_#*pe z#vSwa1YP>3`kOj5$k11Ru`I~SyyP%otu%k)lj|)sF?c?Vwq9k)aX(!riEDOPSm8V# z|3tbtfLQ-d>L8XQ!r5HePbgecd943|G$r&NF?z|^MtR1d$ZR7ZKI&Cxh(r%RtVz)4 zUJ-9|0p*WFY?QPF#BQSs)FiPWV1BGuD}C^kulDk4QtuN}0pStdokPH=n*aQA!KN z%%pqsld4Z|T*LyM4$0vY? zb070JJs17Z77qL}Xv;D!6EBy5NHKy~%e+Gj=WGpElNVB!eRiKkm(wF^>{i~!r4q5V zsmK90-5Kttqgw2l)1XgK?U)*mXh5%nXM}f0G7q&!nY(_WWf}3~n7%8Z*2nDupF~`0 zt+0sA+DBH<7lguTG`w>=8qJ^iAk$6xYK{c~0p*x7yIi)cB(P4OO)orT+sBB+cis}u zIwzbvyz(MASSt%hyB!9to&-x=lw;?Yzc2JPxtGka{_jlnhWj3CQ>qd>EfgA}I?%Sp z+ers`(ZL>`Ej>M2$;pkR_o%-H4ihkC{vo+-+_4PBRVzJnCc90OL=erj^VL-Kye>^G zct|@gdtEM^SoOY$qw!u!rg$i>=Y5pIsJJH)dq*&7q(+wwgTuV}h?O#k94d9+@rY{` zjCLG1ZW0p3{RAU6dKgxW3 z=GtC3#}~;2=u~ZznB{GLesBPL2Ct>}hk=u_uc_Vqv?exZ`i9nHYz>m=aLnm?FmKPZ zuy81Lz}!6`raE)~#621+u+F|4#)MiMx0Kg9X1m-uk3 zfTD(=f~Cvn9PWqoo$WrCoOAWGvkboG&rD{C2%NY6lzc_RZ4_jo^5#TTF%OT!cAnq7 zTIncGr$JXFG-k0t zSLu4=(K|AK+lJh-c=ybhfWv;R!Wb97T;c~cbl}|ezz2=sekQ%OL z)e|OP^JFBdSXzwtNArGL(m`^os>O#xp8wo_i1~K)1%h zV_*}XX8<;FsRuONMu1v0eU=f-8r4>{$yF3M58*udDH6)_Z;fuIAgC*V? zB@}$bJq;Dh4)aSvwgJepmMc9a=OR=#BNR$0ly@I#MNHvE$Bt6NW!TGoVr3fR1!K!6 zSU3|mN*rhk%9E2ZxC`7ZMamayS0C7ILS`lPcs-t5+Sen}LABX*Spa9_mH?D;3td;^ zlE55S<{5XrG&G-PFr@f*Y#7WRRlbMg0_RxBL zVMip34nkKb|Wq>L5nHlRi%Y?w+&y@XfC4$UCZku~&@OKEkBKYOUdbFnqqGpkQl zfYY|`Fl!yl-mAnII+uN!S^>an5R#z><9aeQ)%jn~HqWxOJeCkvps%K@!MjZA?_zh9 zVY!!3ZT9F-;;4{-i}_5J)WZlX7`=uum~B?Bo`e<*C2?z;1d z6*Ib0=rC=UKX*WEffOIg;Rm7I)Eop}8QXRcZ8 zw&;4W3tJqi78)%swrEAEBna}xDX$*Ne$z>_RdTq^ijk}n##!9=FKC%C7pxwf8z{*^ zX=CCiiX1#h?mW;4rp(U_e6@`%(fTbM9o#Agi zGQaXE)KK`67_wlj8 znxGmC9W|cQn!1Zi%QsP)2Y_CAeW}8z_B+VT*%CHbAN02AksbL^%42CHT95kZ_2gLK z_*aZt3`RSG_d)n0qMvW#-@|G`XbSvx) znn?WG_+B5rdH&+X@}BWcKR-W6fx%AEnPZhw0*<5mMRjL19RSI1gwH~xbEwiW6HGkx z8!zmCe3aM^3Hk>FpxhP*dC6`8x_aebHHBWgr9d1iFXT1<^xB%fWFQ}~H-py9Qd}J* zZEdM-7$};z#go!DFPum|jn*mj%{7}tYNNF=$Nc-(0jF!6G?8w?4b8)82bEJ960D}nS_q4#Tm?0o_|8Z5} z>BbHHGCMeG|G4?yovPMZE5sdIzDf9%I8*W;V)*0C(5?J^Tffca#g=+$!al-!AmEeK zX)0&r5LUkOv|Kj-gWp*-+}MuR6pDWZ03Nq0tF^*|HoLJp!vt0O?z<_>wBAKgnVO(M z2RFrxU-$+oTG@XIw4cf?#zW$-P$U1e6ELlBKBQYRh4Z=0v_oE1BPZ9VCxU-}oekM9 z4N5m~0O$b$JAS_u!gUZ7t(N_9S+WTk_WPcO8kN?QCo4Wj8I#M)N6e-_MD0&=WU~~b zzlu*U=bl)xW)`ctSr#5*Ivq*5OJ^O0l4w-Xb{L6aZN5R`9JJGiuWa{;x#$3J5J!2Nk*=OfpX~p>De~yoDVe%8h?SYwYKlGsiLGBO!BSFLP z&CGPAKYoo-AdMK)bT7rPBLC%)A_J5*o%!?6+3B`~D!`o7MCdOW>WMk!&4qzz7A0yb zE`xhm>0hk?6d(_CV>!mZO-|h1|ru#1!={aRRD@I61zabevJFR+&``8hGse>0YxwvATEsM+}=UBH;JhlWbet&$ukh z?e5PMKc7$K-T|`e0F!SDWdK!RpF0~p=ph+1rb(3yOlW0iR~++JjSP5t>I`%UQ?2J| z70ZHcP`)HxZe{a%;AbH}pI-)~z9GW^0eJRXB`Zqzk?arTqdFNh1{N<3d$RcUuqKDM zVTpW7tvQAG&w{5@(*Jxc-88abJZ<;0h@a0DGT_GXw?<7SZwHN;l*;ajjCoA=y;p#0 z7uHjg=nDkHEOSk=!DPQtKR@!mF3|XvQ%c0CT(KZ+d;K~AkwiK~XO#Lrs~2Pp>b9kF zREu_)n@umG6)_3lr!dxZ&7J|*jaSo(?E64)CgDA96{-h33Jq-gC;_jI+aD8kJwgcT z9ff{iLN^8CgRAKd4Xxm~4rYik_etzN$gmKzOE#B9IA1wz)94BHZwie|6VTrx&JG+= zLd{>xWN9d+VOmu*)ES5eVzl!f*aU+KuV zT`>hzUdADWFda@fl3DsipHHq{o8@fJ{gB?-*q9b4D?Yi}jrUveeO&0JGFK(PF#6oa z8JFC-4f6P%Y^w!xE@gemygMn53|=(*tSe=*_RZYSJBeEICDXT z02RxKUE0do>#)LjQ8$D+KJIBxaPdfIw}V9~zs4;~4}(fjLcWL(ztkn*p11DJ1m&Q< z65>WZ8>J1dP?M#k+1Q~yi$=-gQ_WOGcygJd?lO<~1xd74Y`$}@p=RTo#{X=)cYI;r zcOqcq29V(` zie30>K)&ED%Y&DA&*d6RJFlQ=Fi%J0zV*lUO3G!YeVr(>2GCH_RkNY`=3}_rzueQD zi@)bgiKW?$5QPlhrsWZ)unV&8wFP+*>#NRpv4pu~O?-wuqzJ;~Fg2+qsdgFS!*VTP zjbGKmX^3}P_Iu;*=S(--y*VC`p(Q*T@ zY)u$xtjcNEQYmV9UQlZ!Um=@%Z0eD0UD$|BrVJZZe<8EsElc9VAN4XtOJv;*)+Z^^y;7>-4C!xRuGzU{tA zY`D#Gn@Id&>mCRisk}1;{rJ=$D&`)q2OiAUnb*-s`z&ZE>hZ7uF1E@|FwbC`?3AeXZp`XqOwxvb+ z?sz)~k@eMISH)%jaryh07MoJe-t)eD`5#{-C362eWq8+%*p@Z|ZgGAf8Mdv!mXDZ3 z71vVRjC}TmYTkP&O5NTmG`62A<9C+br7p2}c%WY<%d4Fb&$yTC^#1ywpkF|?uaJ)4 znSOJgF@#DuXmE}Ob3nQx&~iPq-ts6{*f%zM4F1%z@IYbl!oU^)&E3+Yt%ZhVZ|3J1 zJoB52b*%3zFYzTLuRQRqbTWf{!fpH)Vkh}@_LnbT_F@9`${mu3ghK9wwoPW!<4*YI zq(saF69BRj1ZbcY!b%tEWAw0^qTj4&x!>I1-v|8F$H3j@W;SfYk35%kYdx_b2+EvL zwHf^eVSY7$Y@*KN!;e^?tAkhlj%oj&?&;P4g$Vn;)_qHQ1OK1-!2hBEf0hSa!uzWl zbW~Mc-D+6^P}exi67i)szhYm9ziG1skj%#lc-{V4j}v+A1(RcUbc<(K#v44x{b|g3 z;~3z|zcR|p*$F0u(+Q^oNizSNoar(l#Qq|)!CJ3!;B3eEubjgpBj4ynPCfo(dQt3t zU0ofmpxq-xYnk0Z`qD_XF7cy5F}kzf30fYdJ5a^~WEs0HJJH={)7s^lLeL z>dNZ1xzK`O2{}*0l{lDo;zaV>47mu!DTJ}_{w^})H?b|xv7mTJ{?}ix0j^M6ya1!i zH(K=DOXMTmmPY~QmJw+A$eVfe|I}72g(~LQ*#eFND2442`1{kut^w!YU(+2ZSqz#`P?6`k`6lI5##fzLa#)(_ z@9K4@P_i6p9(<>LdCM*giohcUMQhTHIF(kpmP(0YaZ zAI*Q|bKdv617CQ82T{0XQum6C92E;7WXyg>HKp-R4tY^uOZaz_{rFg^2W~VzyksxF z@81lMwsDgD9v^Aq4`z&#_PLcU%M(ExrYv~R2_KTrGS!rzoXx}+J>rHIQ<%tFiJrN# z|BZ|?+lPzO@f9=04l>sejSAOFroqp?QbFd!+KB^s1?Q`>9~fMmXcudLl|=9-ZbTx_ z*SRXlaX-YlKkIn;&lWna(bLkG-zQK+(&D}t3`Gj3Hu{|V0b+~RJy%C zWzS|c_&q9qAnN>k@zj^N`j)i5F?-GN6IRivFCWGJ%ZZ}PoMrRAiwaHUU44_^|lw|`gTAiKP8chsnO zxWvD-ZDA>^g-T2G$Kd$VHQ=LMJeX-cKeF7Vjf1Kze)`cDz~@J0d_PPz-_e^n#r+A| zp5`2#99v>CyY%^k%+gYDlI>Ll6Z<|K+p(0siC_*%o-dL;+oThn!8{aAziZMfuVP#S zX?~t%*N7sL3R0kto7bG{4MPbPC>7-Hd}~&<>zA>fDp&CbF`sw9>3UkQIfC3`i-lHk zWfP#Fy=hTcePMk%5j9ksWRxfXK3ir-AlK)y5NOPIw_m;!wr>|q?Qp2`KHCnYxdS_J z-2NNOk)#WsKXtvz!#qubQ9`#KBbj+&JluKfPFBFFY#UAVhvHA2VK3@!hF5U$_2X~3 z^!U)~{sEpjM>lGZ6qBp3l)t*QYrpM&uuyKecj^x+I!o>BeLUXp@B!(zO=Rff#Y3l; z0V;->7#{je5a|NPCt9oHsd6}q;$x|nUD#1#q%M*-5hbZ~Xz0CNW~7(Al4;AN!E4o0 zs9EUN`&xrBPql7aOKxIN;y}bLGn;EL^A^nmi;5}^pt;VUB2;0F;-o%Nc^x53du!>LTM?)pd*G8DS?cVBJ1)wAdlc z57dTe+PWA6FXYN*P(xq0Xgevz)d8$zo2N})f(HL zj?qP2s**0LPezjuw4lf53sF+k3C}w!=Y%gJ$!>u~WdVeCu3<5?yDs?{h-K?7a3_bRuGE_h7~VDnL}BQZtKAJf4XF0lP4?7LkC8t=PM_ z5Lre3iVLt!qy@*fmpuR?56+xi{*A7ptQc z@yRrDj$)P;+EN9FoRQu*2)u=Noq33t=RGNW4G?dqkP%7ijsSqFm?N#Cyic90J8_Ft|)sA|x_|kIYS{9~@iZmB*K{V!i9~RJe!e`7X ze?Nm`wnu=YcTCi>8FMf_w@8~rvQ3GE>RJ^;o98Z;SDo6J=-qV=?+IPpP$rMBP|~p2 zwZ;>fJlVCBJxf-{)S$cGLiWXGLVSJukF@H;?FkiWl9Ku9*?hj;5q?`*J0k6XlBBH= zqg~=t1xP?a7ec~<@{0DWX)GuezOUJtbKI5yNBEYjK)1BgX13dJ-q*W~9~5|maZ@b+ z<0)#${?Y}NWFBM5i}r?JNSee`SnAFEFEH#N>Xh}5HpUt z)Tl>R22_11?=^Y`)_bIe8S_&Jw~*|fh1Z%3lF2aYqZ++3qI2xEqC+GKU1m&&Zi8j0 zN_+}sMB%eF*yn3WdfEO%4O62Fw@54PZ>)_h#48O#++;!eB@w+Db^)TTZ9AjtW8qgy zT|e`3_Va3EiB-dk$RR4Pi9daJI-=JucBBrDc;-G&SgH%xw``m|*_^kZ@HUBgs4Ww! z0_B(qO@VDcPR++&z|qyJU7(>yayp(RpEc6E_7$vHcSYet(Jy-Hd&>eN^{*d?oNERC z;KCVmfNv9}YHyUg%o^HLx?I(2wP(Yr&-W;rchqd?74rN&t7tP!Hz+Rk(cAS4SyNMw z@iAu2RB6szZzk`}HLhh%n%^O;K5Z?=w{g4h+UjxV6H2@0S&+JxNT!7GbY4T>KDCAf z)Ej+e8N>O!6G_E-Fj9^nXjSX0Af5AJ&f|ory^k975pL>Tn%uYZOdI-;N5o73oZA|u z{C4<$M=Tc;%>)P0nd+!7?HLd zj>jGKRTh_}al^ zc~+$PBa0H2H`OfAvCa|CTG{87M$g^asCAV!Gfl!gMrk?GWN~zKld0Q2wja+Z|4S_K z?StI!eV35P(`P552o=SNGn`#{6El?d?zs0|_jzwpG1wp@nN$z-avp#Xgmg)Y<(~Ji z1W~j(yN=swJ|eXCku&T5ldfK)2=mKD5Vi;golN$U^X^qZ%dagb@%Q)Jm-Ou__Z*f( z$R!vHFS7RGiHD=kk>>4NiDI0BN#UQ;h@^QAErh7eC!((U={sHL?>%``9{ODI(U*RM zx4Gwa(_waFC;hLUo+!P7@!O);tYAk6Q?_5avOGdJ0h2xk7IshaY5-HifV9U*TQJ4FbiWL;=xV+U{>%9Z=2k!Z^4D|W_1k;jG!%+C zm$%d5=Q{tqmewR-zdD4L7jC)b$fawpQ6N@n5p*cGcTwh}F`=k5UXUHsGcZ7V)Wb8P zOM4h$=`CSA(`E!6ECuhY2?diuLIcF**olD?p3IF7^$h1Yb&TLa{(5QlFk0hK6xW9CZ#<4@sZ}cyhI|tg-QP% zolot?13MWr1=-B>^iSKr3GVOT{#5Qgz)DAaAJR9bLeYAo^<|?693d@W4+R#n5?rIF zO3s!;Z_`1nIs2flc>E-S45_%=tMyD_Y<5pog>pgPNY^o`TcWmL0GWU`D0K3K!)#R+ zwe<1YLfssv$&-fP8u%Sv&q9bd=ULeV_M_@~qHQr&R=Kdo2B><6ekIlIBPtH;9-^A) zvl>LSQnmC&zU^LIY;K?0=&ESf8@5KVlD)~YyfCJ5Qi+{(bv;?TbXPA$$Xmfz0tP9P zvSgopemF3ZD&&`vtv#TO$a+~7wwPwoR@XawhI_8?3<)gZcSgpLqO-_*M8NL}IgDXQ zPRU0Os@#AY9Lx=`G2pTu3Wf~&Wjr0-U%i5V5*9S&05Q4+>=FtLoC41Mri)AB`i?pS z=qhq!jUqeCk*c>!hZ;`h3Xie~@?|3xK9uX;toZp6H31z`*K@e-+~?u|)K?qLFX0fq zRrt#&ru+3Lwuhhfez?)i#+ro@`A2kFW0xXkzQywP68)qX;NfrAb$MN2N)x zp$C-SQF;s50Ht@NOD`crO6UO<>AfVOqd@325PHHL^&HRpe)oQNek7Bb?3umyti5Ni z^{i*DU5ywmx!W(_vV*iPT)1{YkLRN~^;Y5NLxsN*qayF#zI|K0WVftp0CZXB@#QP^7gY56&3q__J_W*PA%Z8@{DL9FLm2KeArLO>+;HP@> z87wFc)yVomw{#G%?`j0|b+kyZdy(W?PU=9MT%|j)pd|6l=h^ZKnD^|x2{D34flEo^ zYgC!o^ybQ=!US1e`~QkGu8=>w896ksKqh3FG0&)F0FfnRnXMYhZ7ieTr4d$E295RC z(`6M3XBqWAntm|zajgyUy2slsogU&omAurprj0oD}OlzDyEw>11@1EI`nLpj2Nh@G%`{ZA1kp2^o)>rg&M zJITodO1W*08~rnOx)o_E=#?^UIdg;NizHTk`fvA0eU2nye22j@HzjqsY1L3&K5|hT zfn55zDXDKSbP$>PB&8)!WsY3lH%#Appudx>j^Trbs*nh4zj2ENGKVSjm7@M9$n`Sl z+YLrWNPDUpfQ0LW)9?bI^oG(e3()h;QYF0oD2tz@-^(OdhzY{|?i{sI_)O`k@KwzG zxlQ{;&Hf_0y^6$Nsu&GGi|_{XykzKjcxeDO2fRff^SZSkf78>JhQsV;J zS?Jx7xcYm9ei!LZ<~PWY@T@?%R&$@y0h3y-W#%tTY#v6xL&M_96kj-avS*zkt z|7FJWeumS2908V33%2@MrP;{f3#7)vZEeLgHwT%8 z{wW5Wk6ElpJmFRbk~r1f`cFZ7m}y*P7kl^aUEDv99{97=d_~58(bKoglXW`*>~sFf zzua@5gAY6Zk{$k3;nxo5@2UNtgE1{mA|_G0R5x!H8CBX?*CQP)WFkbyEba zasS~a0!)BXiLm(@;6}m@BTs<-^7@Z^T?WC;z^iCj_v){4^z%kOOKYR$azLyB6*aXJ zC0SrV++MWeJ{0BR;;NbZrzU4U%SHL?03l!b?%sV2Zt&`L`wfwNmc7Qnkk0a_l)-h- ze?<l(L3^I_x1nt=df|FG{rLoxih!_TTbwE7!H{`cr@etCKMdC$wgk9>x> z8+117o&I^7KXkdDqV{J5{rc1A^Iy_2f28~0EB)Mi5(_xM{DYrAOe)JbFv>#iyl*~aQMU9YpU-a{+;RLy>o9}kg^5!^<>e~GYP*JOin>sj^`A^| z?0PIdrS@u^Fe3+_Ec*%vJwv?aSRWc?ryvcr5B|p&pzfL(y3shJ3Rbp>=2T51*>5bJlrh&=9O^2_O_#*;5T;|J z+*DUPSNwjJe{VRh#_GP_EZnco?SoA8Y6&xi2B>xdB5U;DO+9nw0Q1`z`Y`H~LLYkg z4pMltG+gD9sCFogOvSeh^cUx5ySAJ*zijjK(wB8fClUpZcGjrHLF+|o8`P`QI&l%%aOJm~ivanDyGsAZP zHY(}`;J5>1jn&S69PHAVwEo)`*^v%XY9gqSoqB0y)L`t!xT&!okoXrM+FZ8HOCMJ@ z)!BVfn{e&TOWnjH)%Uhlfoqj3;%=!&Ro-zkM-NE1g|OB!b>Fl`;*v)^M+Lz5292`% zkJOM{{!48s;})Jc`Npt?_&5>uLEBaS&dS!sahx1Kb@PKaRh)aX*5ZCCtcOtN1_wX? zMJ8TDkH`I#+Zfn#^ZW6-r{zSU02I>FvTnMW>W?g+*`Qp#205O53UP;JCw0sAENwEoO#7lZnxaO(eSB|RJ@^h zS}8Oky&51b&}p}T_!7;A(ccmx7ZI zJ(iDygF{?gyc4!@N#cW3$NgEvHUUja%5&G;+n~;u7L-3wi0`bgtjV;jw~>CJOQ1K< zELj2YpSgkF4;@-RxXP9xo?j^v9!5e^{E5w3mc7o;w`2Og)lHj3d(0!@ z_4q2=FLxO=HAKz6Y7lA? zI9~cH*l??n4g-Tv&z#&b!I2QQl_L1EB#N7Bu1%)$pj23(L5b+r%4@hLuPZR)W`1gjz%rwYC z7p1E(B3>OtMgf`%s6^Pbu!C>v=pX8;4vlNL4us^2V1oqoKx}VE4967Z#57hxU z=x$}JI`Iy8r0Qjw#}84$NsAhCdYfO|$vB5-?E*{mXL)?7GCjcYUZbt#p;+7M{E=_! zsgdh?^gg<}Jlkzp*qLe2Y)V!#cjy^-H=zHuK>JBCBuKn#Y+6fEw{{*WYd8JHN?a78 z58;-y5$~_$rYagrV)lHF_TgRLdv8qZ-tk;kx6^CI)H|=*g{U1KMLraMRyS;Fn(pRTa5kBg!%oEPUQ=59luGLI@EjF0qNJ39C(REg&wm3dJQ%T7UE&Aw0uFH zBBktH+6o%v&232dUGxAh8ALpBcC2*9T)#os;jh2%_-b~aDTY+`H7duh-1fO`<=Tj@yX>Jxi!t){X@t8&rA+)|gkHl3Bl>8@f$R&#uPf(= zJl-ydAnT%?pE4rg545@$N=NcFrm&s_BC^vcah!69EPEM9!vtE)cLgoBZHAbUuIAE3 z_YbGH1{KZhdU4U}sZM(vdOtO&Yo1=Od^pvVTGsAJC>hv*;MKA=9L&C~qC4~IK8$-i z7uBHQgRirq9JgZ5XMFuN2!A~arZa~Q!rGtO-FPP&jT_3) zx=4?)X2lV9*jU=_2DfYnQy#2_dDC5LkT|8q?+N$w8y4qlW)p}D85#H07ug{kj;1G( zT>9noHJpL{fnaIB$0Qeb>toM22~5@3ru|0Q+(J}i%*^YR5gd@5{(_T_u8O+@5&PjK z#CZ5B@`tqElpv&_I6IGfFig3xkSkg*aqhrc!js)7q&Vg)6O1jCe6`A{g<5*AC_Jy* zxFI07tUi>pF&i53O+B^dd#&DvFM^jEI$UU>dt91xgklg1n$us85Y%g1-@EUsf81My zgR{mrNKN(#5W_%Djp~X`LN6xDI2SC^c`^}tg$WtxOmSE*2*ogok(74djNgx0T`rL1ZUgs8aS9eWx zG?u@GSwKFhx8QH@i~+(5yXYt`29Yrf(<2q>>C^^3Tp30@pVfk;9#pG{u0nroA`2*9 z@rmy3l5Lh0wCLM)HXcey9e@%mpQwzM_>yUM-MBBG;V>>(_(xNJ7?mRJU;VYE1v~4u zlL=B&ivaYDJOFC$c0f#fMYLLI1G!L91?u#GR$?_>=gte5<@2poMeOl?&=Lb#=RJ6K zcpBPnQ&L6Xz7PlGZe}+lnnq6?6Z{1vXDf*{!J#*v~H@RvBGeEbHV9GLjyu zkIwY3h{BoVedEm?ap|~zxSN@M3v!~%eA8*TyjU7PQWZcawn*m5n{agV$NUuC@U}Q% zN%El}hfKBwde~UjGrfS&sH@a(9-om04@-2+y|cNmBb?dwo0}KIF|_c*%(z;DZF^rO zeGP(4^!Sm(+BwaEU38CcikDlyj&qr~+tMV!#rI1H_u0)kh3QXH0>|Cun+Z~n`Y|=b zQOfQJJmaRr~ohWZ58h@8%eGUMq)$vlJ^s&H7rWwPf7Eub|pjgR%vrnPk1_oAp)4Qq0W z@9YDW9je8ZO4R(&#Zz#?Ur#r2>EzUs(ohVxUy5gQ1OiD2#GGYOY$&*@6V9c8oij0P zRlTAA#Q|>bo@0fuVX~cNmR-$o`GV`;gq>4REi(L)vvPmVb*#*s+x?p7adXX$6=Fjh z5J^@=-ETR=NYay!vyw^O&C4@MImE)!Vl(EzpYWGxqNAu@y#Cs7Y{rgoy{m95oTw)) zC%L>MCwfW1w??l#y#_L%8vGNVh znlSS0cdh4hR)1=<_Z-mYjOKK%2dOsg%laam?!syAa2*oqEB5h8!h9OEw)~CQ4^@9# zDQRnqy4VQOI%$<0(xHZSC1K%)@=TifHDr>lW z(gf05@;C?5o?*==mKn#1$?9HMu6qMtv~cC`{YvK2#@Coi3#S=MLe9!mm>z;>qI}Gu zR(UB-Qw-nHFUT{}j?61~hq==q3ZaVZ)bHZ=mRk6x@Wj}! z4(NSwWRb28Qy6-I-+Z`sz5YRgJN{8>Gc;H~@HnyQ1ZM&nuq|VcV9s-;Y0PDpS%&he zmJ!c#Ss7)sNP4fv@oG)iY{p%woIIaeJoDkNV9;7=2!H9&Qa`!~v)G$}OLsRAUf%u? z)}L8gSLwZsQlYN$Lf_4J;UmxQ#mBwF2)+963&fj)k58l0wqL(BjG7uq-Au)yVYOPj zwzg;p%YRJ9KTxXfSheE-0rL|bouN<2WcSC4jZz-ohpyT|NXvS&PQmm^*?vVkWGr!K`?-|QSeop{D3S_}k0 zuRl39W2~v;E>(QVgN`4sz$QfKNbd$Q@97$;R%`t2r(4J4%;YjTeLn6E8@RS;$DO8l zDJC#ZO@c6%M-O^Ax6jle?yw(l6+SL1%9bR9wzQoX! zY*YlC0oi&R;=jr{P0k)hgj>xpfZWM@{3xf?Fm8 zPoJ-$#@0x2g9`Ug$r18wtm8wy8D$PTv()uZnREIV0QYT)g6W zCB1Y|HUNt69~s7k_jQU}<&D#Ji(UJ>uYqCOapib_6Vn;bAqYE2GppXKgny*zRk7cT zh%~Mf*1*#@JQ28oc$VnJR$HX86JjJ~C;CXzpv)j4zp);@KY(>#^e~FE(hgq9x1RRZ zI*ww6g0uorrC^nXnLUU72hi8th6w>ag?nwZ+D51MGDa&+3Y|cpq4Xk1!ye~gUBQZ; zSBzRF4qqMbJVV1fF>RL5)X7gu{H;jLBh_}EtFtS!b551Kkn8fu@U)4}_$kgW8?K+) zz9qg>72UqiXFr@Ot&)HwrRn1jU$e4Jihvs2$ifml;&C+_1q&P6#<;`3Acs5F)R59N zI*CG;YIs>vFPUng&2mfUB~M`vjoWv09F=5?&CD4Si}ffYmkb`!DAPzvrbJk^wzFAj z*P&T4=SZ+N^*QI884cX(oxQwhI^P*gq8gsOL{!FSTxDx*EnMX%+au9yHmN!dOZBqMHzE*7lWFmsZ2SjNr?- zF{<$f-*Ad_)fo4uw2{Xy36G^&TVfjN5PDz?$oNQy%ySx7R6^^P)as|`s9}=-8pB~6 z2VSRfSlNf!1dV_giFU{om8_6MctMl4Xsk=FhfApcSieIR8{LW@rk($>7ltCwH@r9^L1&dY#*X}$?I9#~SwzLu6f zE_e+6LVpaZwE?4eObj#k-q-sCG@zZ{X?Zj`(Cs-DrMup0$-55D)UTvGS}6ocS})2P zB2#Mxl7B8;V|dxAG%0?Kz{#{QYHltmDO13!vQHmm9^M)U3+!$Edc({)OwkowK%V>< zh3n!sCYn^77>7d39MJ%Z631!Ii>I3gQM;HF+sC?!hbCm5drdvRpF!g^U9dC7Pz5y z^2>LU?Qu)o72;yuQU)v*efRe2$79=08Q1tZ}$2z8VLiV>X*(*Lx|2 z-PbWkR?p(raCM#C@DC0mS9O+0xH@ElrFSu5%f{Y(8l8I^Tnq>AGBdUch#0PLjz|+y zC{~HPs{BwdGEK+;S`8m)#9t9;I4Cw8TUpsP^-ru3?BwwHG%fK!R~7Ay2@~h0PIKa@ zIbj18Pj#>0XLnZg#Antq7*SJAS$%oc!VCj^VWy6HsM^fGo~YlMUjPP80C>|Y)?riD zDb~sN*j*ZwWHJEaMy!!P?Sl`XJ@Ku5>c$l-RVqsSsIw*yJSpLP?L5&t`q{5FhF*17 z@H3SjwiKC{ve>M ztWE3cq#357e1cy_fn3z-r$=Q8a>MEXI^@msr3!GEN7xNM7D?mf=>OL?AH$l`Yr|_& ztpNjtRgJ)sO3cTyr2`50^*j#HT_Dltx+Y|}CatM< z5=3Q7p~ogEm#k0J%m{@iT6UPEid6)YT5FfE+3(-<^mB=o;z}A}<{$&Izbh4|q-9&` zX6p1CQE)BNXJ6i=6|yx|qV8dZV)oiGE5ig;@Y?-H?&hV6*1y4|m&Z;3jJYyg*w5=* zTkUuy42&>K4m?mc2$H;~++~1x-6(-bG8qmL5T7osvJy!X_QhENWCDXBupUv}#N}T^ zszZ75H-0u5$p@~V+)E7&4b2R|b*3}kGv`IPf*z|DxDI>8hp$NQ6ot){mzF7KsvkLi z$07ZK@DnR9)@)I5kn!}Ma+o;8(DvL#N2eJTQJUxD1`cHf3X7`~GnCzk7v88B!pZ{0 zdUI`D;?8k_vMHLL%&w*9Fztwp5pVv;0gV|tF7t14d+%vI=P_BH9Sivj!d)G4l?K11 z;LKQp3?*iM>Gr<9I(C|C?oxK)lqjM83e(1aQZs+eFOnqHE`?lzvM4i5n*;MKi>?<% z$6ZupHE%V<(nh+fwU8)aNV;|;4 z1yuqNAYfhSYHwd`b1Ya|T9TAegrG`5KO^F=p8X@0FW2s;^%|F31gDDh9@y7V=ETIr zH2wkE30CUb99+ZEbCD&r+bareLru5M6RijfltL;(Bcw3f)@%?rUIi zpxOZL*0Jz5~At6y?`3JfEEcdOuTNNmU+u!g1e*lzhK=}0AqH}*L`CmIseq(=F>;IhS zAOpho|H15@&-{Nd-2aV`%ku{_i64 z_Zgp?0FOhjyu3UtEUfEitLu8&+m(P`-~!is{KmECC5Q_zyaiJE|F1ae&$E6OW{+2n zq!;~#>F#%yfg3#5Mjs?{>axRs@uS_ygLY~~mlw(Yua->O0=IP-DT=+?((&`o`^xwg z6vAbyzLDZ*EjvIby>rufS^uxw0@!l-WtuZgj{$l5-NP}^gFgSwAv4MUrCVZHe7=v# z{>c&XtMMIFzynHg34iylHaZqKGEYwP^_MujJiSX?*zQmH8+1PqohY{qWnf?+ZukH0 zwa+c=_wQ>}+Vpk-nNrT&F8sFK(X~t``K*puH3fg*EP>c1>mBt}KJChHs(#{3+;E2o z9ecAadh(<^;Io@cmP4H)#w4C0Pg_hV`-k6sf$Vm+y*-vakWDIT)>j*da4z>{{EY;s z-2KfrCcXm5S`3H(GUh+Gbl#7cbnYxfJpFctoUukRw$o_SQThRxQT3>J_H#Z!r#$|E zZf+XP=-j}JVoS6PySq=`Fxni?{5Z~sP^+wP7D6*xP$&DYHB^PS$_uW8L5B@ zwTt1B1=jJh!+Fg5cB|P>z}0m{45Xq(xL|E$0-IH-{Smsw_la4Ip13_CP{Q7E@JL<-z4w!atq0H5Pi%caZ-eE)$c|r zd=(AtZ+)xCq7lR(mA&M?c;f}Tvf?3w-yEaE3ibg~xBpNjgybBqNSm?F2TDHKF-2UAaj|5 zaEW?rq)j72N6^+|@PH(KSN^43RFtE^u{!TDB9V`pT<1z9khgIA+gSp&F6+dVPu1}= zcDrlMpxt5se0bWKU(2Ky(#M}!meqG$w9{iQgv>~;NXf|%%xza#*&1|LsUj+sgr}bD z9?YAAj*4pab?`DUfGRoLO_l_Rv1^uEsvlF}d`!P$n`lX@B9GATy|YP zKJvFbc@x&UfB&Rc%xzoxfo~Fu1(BEF-qjfuUNkoh+tuGENv%GR7T#Qem{TEsbx$*2 zVSEr)Puuy3QtzqT(W{&)=RGIqhNS|FRw?T)?BNz+m;Z3*??@=Wy5(V8z2|DdPv4wT z39q#em>)o@B?i4p%st5Npc3bL3kFqPrQlYYZMF&Vn8Ql09=3N$cxj z%HM8gE8d#Ra%}7N#5yWhPOari@b?Y8AG=ZjjXEq+#4 z0Bc_4FHYs>(^gw~Y{FubCbK!Lml*EXJq3N)gRsHVs7?x*FNqsrsbIU%M~D@#a7rzou!eLd5B?}evqtDpTn zv3`V9pDOf-d$p5U_&wO^{4Hr39o@4E0oWfa?3-V)dd)lcdq;029vL-c8m1rB4Ix`y zZen)ZyB_!z_zF|+dnQ90qDc=84064Ihq|%@u)nUdXq$w962eX7AZ|kV(S!A)Mos_V z5kB}VN#p#+ELZ<)?8wLVOU9mD%Sl11v^7Ebi^h7O7tG#uzBF2$T#@*-{r1H4`e^?r zj>2A%sBr}-wYzB6ExL8)UySqp&%#e2Gt98T+~Ml|5&rus?R=@AisNLueV;FoEIpkbMf^Zqh*mxMR@iYq~PKLgD-BIS%Z#X)1&Td9(bb<&RQaU(E}|L)>Qi_@a0!(iJu zDOr$8wnRR!YVuMGhp7F`0U~v(GNGa;xf-5V=IUVpx}+@7jr8lhx-ZJNK9D4*@9R|t z#o6LI7(8)&M}}rZ4-oh1e@_OTXm`HFw^tki0EC(g}KLlED2tupG83Q=n;P2g{7^l#h_>| zT$F5fuPiTWQ#sCZ+&$d5><-|caQM?dVWZGX=E3-bpn^83a@E)w*P(flKvCM8CSj|C zv{|6@SqTO_Y_I1X;^ytNWt!<6z=au&jB}oD1gYNB(waSU{NNtoJ<#nnX#|jn;?L4e zmOklP?AOsjfGZC(MrrcbcWhS{&$puPHC8g=%Q1*y|K0Aeaz8Ju+j?f54zuWf=d0k6 zP6?SgWnsozL)ylY5`}gdt{>?i$u6N+3bB=mTOEHPZ_cJ|+pdj2f}K1|@mionTQZt- zwBJ!)q%1`bF)J3$WkZb-F0~F4%GJ8&P|Y-2#87#)#GbE$^%RxI-hf%kj_=fo_cC4H zcP=mEPmsz$&6STwW2fK0-|^g-6i1#CkHaD(d!IJ|TL=YX36Se?X0Zbh&6k(@2|fqC zs43vVqUf*;5FJ0$%@g+5Sm`4=~&X^JHO^4a&G*4Dz93Oq@9$|Xm)DM+_ zfz%S@|AUr%=1lD-po$B98CGAPEwidcYRDKk^Uh_#nu^i^!uW=3c zqaWltx?+*4x}k(N zV^~1}v$5uKXdti9(?ROQE2~9BMpOKLTV3kDizvbCMP{IHO{QsL(L3IW-F+e2wn3z`HgF`-SI%RcazKs3(|*@ogV6 zR7#G*l6aZRZr3DqM34=m_@2HLF@-xoFE}$2!U~wUvjfA?4jz`2DXh27(-$jgY4#Eh zOvwFrNe)eP+J$NL2!$7y534rcJbOYS>9D&NC2Fp^l8?*w6n2|ta1LmGpDLLzsX4bm zEi?ogNAU&+>C%W6u308|Yl)KkH5sP@t2$a)TTXm^3K?SX-TO_z0)`zOm1c(OcK=A- z{VM6uFlQ<3hVCW0d`lsWM()Ti;h(8`G}(DWj=O0cbnjs$*fyE6B_d_&j5@{M$iRbW zOzE2Q_}dUq4n=KD(fs@)pa#xiVLT?g!cyktqV6&^MC7gw%+b8A0i~g6TNs%qhw(Afizf0qRHk}6T_(KYINUlmp5IP zbaG)V>*-xeR!+A?QfIN*GQSM^q9w5G_+P)4Fu=zNy@H}5myC?rVt-aMbPfmzF+V$- z^Ej9kt7CQMWn&yFm2y)p?zP}X=ueN5+q{yAuG4C4GKZ$kJTuU|i;p-HpHg`_%#~dj z!#EYy14i5Ywe@kkckBT)NvTC?A9H7~V0a^*byqDV za&>VicS?hhmU86Be(5yGze-&K4{z+DJtE6aLc6>i0@}aLT)ky*gWk4dZG&^aRAt+E z5{q?-<6Q`wbsAfn=mc-rzpl7(6%(!r08!os4xLGkq?GPmC!~Nt>R#+v{$j*!_QrX(KnQCaqN85B@l}dYnF%aWffVHG%Pn*UB?AwhNV4{yeXH99>xJ>l&jVXp(x=hgTJ!3r!F9rp_M zM~arEA@#bq>Z{x`^;<`|4`8CyX7?ss4QcMwLmy4B85yj2NnJG3!1hpApY zSujX%mVW+K1FJM_+KiHoNkU&{jdGLtUu47`l_Z|xv*$0`P1e4sFxKsgHsPTmzj^;5 zkczisZt3UL9QyW!(W)ZF$lJ>X!u0$3ncSN(HkPleBYhQyUHo4f%q3j%f#5Pi5Ppw{ zq6II3Swl#Cs-^2XVs0)OkG;bod~5|<*u^KmVP(6DeoLXgyK;~$RK3HFG(yQ3XbJ)* zoy8pZN=A7%zHO&BafaKx?Bd(dm+NsNn*QdNn$`L#6qL_#uDF?TAxL@w&s15it!1K} zPjN2?nQ+xNF67}_y9C2-2s;w}By*DEAG_T5D8PFbyRuSJ?L09(ybV~Hhf)M>pPae) z^7N)7&BVrnKF?2c$!+OlhxL(yo(qvCP4fPsmx_~+35~At)!+(UL_s7rdD-BC(xEqf zG0_}8@DA&aS5-6d#5ER>?*yU68|df;zA6pI#)fI!Qb4UH##^_ztdAz=x!j>}yGN5V z{ic$6aUJyBbbiGmZv87;D=WQ#fC<(Heu<7LQ5J%ru1# zdAAYFv;y3z;8z4;487XFu1Hz^gm8b}w^vG61rm6o1q-Moy7)k?2)-wpM!dlwnE?V? zrEM8*Gfy`9XSak zZN29;^@KdrLoXB7G-NBS(v|K-kzU1uKWo+xbuKo{kfBbi&kkEDl=+fwS7LSXB85X{Wob7e?}TI%r4XJk1iyG8y&k8vqNl5%;Z z)rT`HI_$sz&C)BevW-Szlew?pIwhnCAo4V~$C;qC5{Tg=aU-xEB0@oNBunB2F^nj) zoy|X;gZpO8zLX4zW8TSkbh;ldUi_ z!uIPfDM!M8hZ-s80O~3_we8jVTgf^D`-o^njpivJ{StF zUnQ^vqe?d$=(G#-q;9}^&6^5dObj=QvRCHKk63*dT7=A9pH?HPXMM=n_N*r}3eZC`9w?Cs<$6C=X=NX~!5pL>(h2U<@QxRwc;dM-q78Tssor8D}x+Ji~bBY7jTV(|=dH}J_CnbEqfPW{bS!Q;Y4EoNB-NFa+rQd!A(HVM`V znWua0xN0Ts9yO_bHfd(vEqo9Pq|g&62alM@+i?SxtDsP|)oC8sh^UR3qOoCVy&90` zA>kK^5`<`dapG?~#LfBe$?a^C%gA7jC2;wp;v(_Xu_EqTZ%O&{X|EnS%^_F`{#?KCCu7*noAVTGSFe)Y%+$VmJo_v)-Qd$# zmBWjCi{=X!H;EoAjKP>J_e1+02ByL%l!K$B?Q~6_Dty|^>@Cd@e@jk$ou!EAYY?SB%RMt6FI?C!u*Ea?CO)Mrw$@7R z9RI)^Nv+si1P~;1kIhWd&NgV*tb&~R>tjOrQej-1%bk0ym%|~_gAKa((+(0hm{ePX zKiYV21ylw~ZLd*E1+3<(`7Sdq?9r?8_fH;&$zG41qSFX=WAm>Go5vs=F;K?W?|`jC zconBd?6sO|&=j<(p`4P1gv)$UyyKi;aUPx{!p&{t4ij9=7`wlQ;}kd)4VvA|WZ`)3 zRiPs*_11E`kdN=In5A&D+PH##9aF^72FW;|uNy+>P;Gc?+Q68-k!atbT2fAkM#*zNMiv?0xhJV>a2M#lFSc~rE?j}F5> zJmiio&Ha`k^upCNLuHYWAVy`Fd-hdwvHi6_TWk>Ygn2_;pi*paOl-DY<8x+G;6h7f z0yZeN=>`2Qe~WvkTb~85d{&vfe(lhki|?=|?{p`5Th)4_@kLLD=tiTZ@_RFRB_(q` zCqQ~}{kB(DTRytv-V#`sw3)($rK~c@OF^g*e0p)MYF7K1b7JYMI^y3*lic3wdxYYZ zYxOqOYK)Uz)So^hd)7T8k{&8+{%t9X3EQ-FB>*o^c1}~&UbfRb>*|kKW{MxCi=3IO zv=OmzQtm~N65GD(#^aLx0@u?xgQlr)qwPQ!$7P+TgR9FVr8Hfjd(pzSm(r?j+-z4X zxmn39Vb>q2drP|4D8)ZRf8ANbhBca>QAJJERbuaDrU<3lcJp!+PCq|Fc}uu&_`XQ# z?1A8ePH4>EAIk(qC1tV|shD0q)es%-^QYL6@kyES4^Y`0UX>=}!+AP9iFWxCaM&w9 zO(z-C7A>!JKsugderb5+EfxEiz5S?~AROn^gyDmqf>%Y@zxr}P3)QgSUtYS5$ZTRd z>=XP_HETs8xO}5CYH}{=Giidi*C)sh&Fp&Yg=8j{eUiEpO48bK@yrW&r6Qbq9 zP+1r*zsbgBLf#`PQRN5dc^zG6^C4BxemlqaHLK2EZ;>xkt-)Qw&;*IIqp^PJbGIl; z5i8o5{mJO1(rFo6cAt*%zPv$mL2uiup;4KvY{RcA&2Osv$$Ta_4;dcp2+_c1S_bvb z&veC3itWl?b)fdJ@fK5>bed*3Bib;4jOQV$%lCilkcn4g(=5>^A9U$mJ3Kdau z|894Exj^#O4~P#w{L9-jVj2SY?P@jYDIiACY^du-F3vap_N~%mB6kvp?|{eXz08dp zI!{Ffxu>b+aF8s8wISx4f`K$p@Ai1Capo3{be(qxxax}dF~#$5J@Xm;wx2v_?nE)j zD%4Mfc|Vb^pA>w{1*;&H{j&Vt}w5V=HPknww+u*-0@ zANRIqt@lmzw0fnxmu#iGMGJp`xEGhI_qW)E8xIkR>f6!$8!V=`ZAIgo4&LM@rAlqJ zU3MukyDdIB`{=nsw9X#vO>Vf%Vs5A7nE&mhgKt6=YP2VhSBGDG&XpPwWaw|KDX{Oq z(=Mc(A|6pKs9AGMenvA0TfF5fHN0buuBLBIH<)nuqf!#Irmbuuq?#|nZD-zJRWo4j z0s+g=Bk5ZwS($p}AJWrtVxrB+XftLtYoE&D{wgZz1(%J}>GzLjAl;uGXzuHd$q=~N zdyLxmkfGwSac|-^?`uZ~ed}Pd9>uK(`Pz9`Fi*U{a3=k{ z+bIyXRfJ}-DQ|e zRuOEr-ffu}-7IRU1T0$yks=(tiE16tZw_&dD^yL!nUP9q8&x~PXS|K^PMRs4f(JIc zR!33Gs!P78Aa`qKw)FqT5;9&${N{o~!0lEQxQjSJB&f zexhu(naXy8kfmPas@eW>uxPj9CGo8Mz(JV(yO=;chN=If#!GG^CD8}oZ901s&=;Gw zE$`j>O?Lfk23M9ZsBnAMd*0b?=|5O`mG)$9>aD=?@z^)slY_za16qd4I?;R(3vB_+ z>}!4Lbd@KkPqYHhiSXlE>~vY9gdJVbx4L2CRNz~azG>YrwN56ob694|M_Njgq7hhR zq%FTSxkJkoAuWU1c7NleW?#y! z;T=Xhk=#oebQk7g-NRZYYIHW<%lb4xP0HbK@>Oi>F-)!WvRAWBaLyi)_rjrUX-Mwt z4>V_TuOx91d}}-}eq%X7sk76X~>=_>>W4&Gj~y;y_vcY0+0r=25e4dyaK=x{Luj z-k+BCeb*}G-Uwc4T-^UTqgHNS!x1DQ=y(sp!Hr&%5!MbWojrbA+=y;1+FnlZw2>%N z{yKkx@xq>?x;iv22-`Kl9{Ov7rR}`d-p}9I?cfi|^e32=+(3w?x#tSf`$Q5QZmWk) zeum!c!`B@atOOkWh;AgTpI2kJo+;^?P!|uMNs&*_XK!&SGw`sUR-JELUDQ004iLCv z3#D%9Ajq*i;LK=4$aQv>pHJXAJ333R@*yi2ZxU!bdqi>7StsPH&ZXYcoBDl5U!p!M zdaN@AN4wJ~iSk)=?)R6k`IAj&tJ|Z97mY_LwlS~s1CE<7G`2-P`@Gy^N=sH2h1v#yWC8PahKlt^S;l^eNzkeo@Qu2+TA55r7w z&6^*V(|O)cT+Zx`diH?puV5rHmWL$HVAA8AOzLCI%^7>(G~Tc2t8zU1pNLhzQs@p` zNIaFG5+Yt(sWVL>N)9VNJTKwp5)5~zP(CJFEKfeTI+4{%YcBo7nf6TlJc@a%L$KMc zgDs(B4|&B?)B3c&wN%O~^kt5JcatO2j>TFnVyVUX2W<%{c&N$qc|iAL8knR4N`HOn z*4nGszyw}y{jJqi&F4eDQgBc5o_z_rT7}8a=QFq$Wo)){^jp80TMK$hXG!CPWY7+ho_+?+__fA-^QP`%7_JXd~aqA-=AD8YbcjZ?Ly8f7P}7sFifTsjmlYDues&abqZwF!Zmc4&{8)R=jcOx}xv!{e@)&vjkv0rem6h(-}Uz=KRaucXi`zwpr#y*CC1Y%yn)Yex-Q9lamG`-?eBb<$Y?96Ho|!pw&iGV>TgYuNU$0?sDtcwaWxd^-(Q?|nCX%{M?o1W( z=qI}~Yj_cor=6blSnYsG?AF9RS`7Ci4}MqI7cMY}pzYhO*T@-ztgn%A7fDKo-(c3| zOt1ix^8v@OG>7dqm1KUO=HA@LCn?_#l7Z=W23B17(O&7+#v|*&iKc64-%O5`mNql& z*9$-g=Tp(En=ZPn0(AIekCPUhjqaPub?DMLX|mT2e3+6S>OI*LOa8#QH(2lhM2LeO z&Hi z#a@E$HgTB@_qdwC5Z+QG=jS$mKU6(5ep{fFul){E0^>K}I8f2N8kIf8)EiOiz)Y{N z-J$WiuaHE+l_8&Q^u9PsHux&rrYAQ3x)Xrt8jmRa-UVcqMyp>G4C7OJSyI}EL^Hr* zmoA=#l3Mc(Yes^*PZU`K=eH($c3KARK1Q_DttN$>vf;y|n&Oo3$ zRrDC5mu}dN1(tYN5)1IoBxA|8HXbLX?_sMVjD0mSSt3Byxnn7{rV7w!@VbTZfS|&LcE>y)={MOp{PKVi9WHr`O3v1>)6j1p~@H>DZ@UbtT!*Q z%p=O2lkD7v02LqqCWvR6XQk7}NW@|!8I0DR>^Xo^5_yPj>w8aixkbqTVu3}a>*-=W z>>YB&^d`QOZ^h`WqR8W6-y=usR3eq7Q>Dmph=n&EC#!YLC1~lHtC=kLe5ARxpDq&w z1lONz2~6%VJ1_cAnLFHUw>&+=pGcn=^_;b^4=cR5J!)lw9(X1>R%DKiMs-$4dZG(# z`tuQ@BR!*E6fZI@1Ul|MLf>tu#I}mK4Qp*2DgB&^?6`$u;mki#m&E1E^vHbcDqeNd z-F|krd|K@=2(`g;OYwR2aXjD5{RH<{n*9nw5iD8%$A@5NNVuoqb8y?5zq|RCG?XFZ zWBanpe)+~GLzHY8Ms&;7XGg^0#_8rq$AgUHw_{=1Untcu* z`rToP`MH!0R|c59skhN3;o$sT)9n)T;dUuwZvDfJ^25U zZfLP`gIQ1Mb*4NiIy|u*=h_AG=SA>u{pX_lGK-)DW!W2Av$|T;&-Y z(m`G$8`-c?iHuGqf;H}TNXMDHo;`v~&Yq_1d@*XZL%JydBi(1!J$Fo6w6Th<9v0VV zf9+=Dd)>}z5wOl;pR+a{1<#Z0iRESi*XKsPD=m!QWNgF*6uCR08N<6D$+f-enSR{G zby->od%Z3XpIlw;Kx7dkArSLl3DVy|~NLw)uTywO%LLK6s_zIjI>Vq*JeqHJlc?{jf{;;pm%|SksH`gMRnTu78O3!2VSI zk0ut90E|UULx%2OUb+Nbj_Yxv#dGB6alD!!`E&NcOhH(ie|_Cho<;WGH7Fka3} zTvTjl;ON_emzIPGv)i*fX+y+Pz=4|k8xpUD>n=q%O`-j(9!dx5PhyxQ0RoJnM5qa* zH{MKSYjBywa_IsqL?e$hZcIOGcd?>BZr*vJP#WQ68X)=jiZxOz(8^z!HM|-aEy&*V zQs^@nrS)!LN!4B`e#Jda)QnlAui5-)^uiM803v{;_c3S+wQr7 zB~iJrGLTUps`6qTgnT?a$>81HOm@0!7%-<4N@q^Iwp7!TOVKu@gfp9d{frYXQ+2&xqdZ$7xei9P*&+gJMToV|9|v7w7xL}+B^=I%}+uO6OAZ$6FLW^bpP zr`~_xbCe|~Ghcs~bCM=(#$?S_ucbfF(Y{@5dXGa0q<|B{OM{RHBWV%nkA%DlU7lqG?KhjV(&djm8+-LGz`F6mhcvmGXS zc@JKnXy5-uy$}s-AS}t}-CZvr)LC3&bEOIrkfK1J2?>NWv2$uFr2xJ-+Brc@28}5B#cL8w6r^(4W7F@{ z!wQ+quvCN)tr2V?2ZbWe7Wf48}6!Q|Q^=AvQHVf;GclhQ{zULO+E2 zL-RPt0!3OR&NT|tN=;NxjJ+Ps-&dnJWqYfjVZ};L*NdF4-_|$4$&G^jp1&i(AAgWl z_<`Ht?z(PJV9U#o9M6oylnNTzp`iIzCCdDifwr`jrj$RFTUxU|9%K7;Q72WYRsV;$-v&ThOFPqCVI7|Eoafgv zb3g!y%Zev8{f>a~45fufEQ4#6v8?8p@d6W!a(0(%gV#~59Z)A8nF)7 zqJBt`>0X2iLxYT2-~g@*Oj7UUH{;V2AsiqUn}>`k)(92VXeHd|e z=v8c@(5tG-8?d#i{lQhZPF#%}p@4PG=41{FT}$~zPGbAA_imL!M2;sNr5twj=3#B2 zL_JTYImQF3Nrdr?QJcrQCw89^7H21LFcgNl5$<7z%P(nUP=^@QD-#a1Dfm%tN=CW6 z)a-;@E}~dSSVynYF%GGtW3E%H<}1a_9DXQ^_+t26Ij28YTlfXgEHBON^sbkaJKVaE zXl;1>2-oY;iXKdtxIf1P`edIX0$G#)2KtG8)LW^^9vjC_?=wvWm*aMqI*YL0A&l^3 z%FNPF2wunSF#IkY4V+n*glK57UBgdAfLFP@+4XK^9&U)djm^2gzhAfEWJKBowR>OZ zGkESxYQK&$bTis;65ie4YaVM0{z=>m)b9pOmYwfAnw^L@lLHUuNQk;aD4S$Q$66JT z=bc}N&)@+u-;0Qm%@w;=yT8s1JX>f~hc+OQr13k@IKCQPl;`V7E+{;PRkCPpWY^Hw zlpI7ujEh3)agrX$h1{j4`yBoP?Vd@68w+wHY^l(XgTHQ{!6sVYs1$b9ZqFa=gIym+ zxIAtRNQ|bQ`b7@^v?GAw`eK@>%ZY5X7HTHP11D#Rk!kSQM($<&@} zhp^4XVqI_e5pB6Wu{|d#55WFudPJyeGor+{3g_ zDmRAIDfs+D+0<8w>%S{guL%XkWeP7BQ@u|ZDD&425;W!A3L;Zr}$4#W01U( znsJm$ip-+->@O!#Y7vATZw{0^Y~sxDJjxcWAjjzXN$SR%k18CTqi>oy>P$q-t5z8C z3_0cN*k5$De>KEkb|EVjdINgbdM(|T^qk26e(n63DnDRHBNiFu@9Om1FVqNkP@?7c zLet-R%LqQr=Szudj(8^$Xmg~i~u>hmp+sM$Zq|VDm?4p<-LtdFkbb?|$KU@HHuN->E=q2Jme>X* zYPAP`_jTu?cr7>U7Lbjzl!@zc7>(Q~y!5-Xw%}C4GxBziiD1&9z^s2B2J(JkjYU8Z z9v+TZs$Nfj9qe9UTIF$XXTeSYDaQI{szmkDEeak4mQpl*L2R>Tqd@D7BSEZ$FY8k>U|?A?W4e&Z#fMC2^%K zsY;+8ML>Kg;Y#uH*Cyom)%zXk$;ksCRb!2YQ#v6fPb9CGe0<(O5=}?R|8>@%&(U8? z!^`_*7JL@1oU^5kMiu2>W5Ls7Z8V;iOKt>VaCmh5@mR5}wk-Y;4_RBgf2JS=vr8~K z|M~RS5mjcKx5x`S;@i^T3*ce4GS7dEz5nx6h?yg}TI2Z5-;)0Sej`tYT<`z>>923g z(16(Cfm>S!=olE~PPDTW0s;aao}NWotq;>E|NsAFrYxS8$Q6w&b0VCrO-aFpWTof+ z?-Bj$v11QG@|%5;G;&GqK^H|CNc{ zL(Q@$4Kwd1i9=}`2QaH z7IR2M#NU%f!w`UA?ya-68_snw8wL(W&9nStLIrZayf=$*EAD4}I|Zo?tezpEj)R+u zJw;KuLoUWws3qSJvTyZYb#*+;+hfViW>v64v&hW zKX=T@%~h>2WC*W2p}V@1&7y{(04H$sL-?w(YIr#JiOreayKJFvw40JMQFr4&J*naV zt;S?AREtjN{H1WmAf?D6izB{K9o3ez8AT}g`VX^MaVkJ4;>z~Q7<-&4egg+l*WJ41 zIi1a^Q5RIEw*%o}l@zUE^Vy78y`94iR8G7_OijSPxmAHQs<&b##ISXb!^jd<;WldV zqSBa{5iAp@=iEoh7!VRPvOix8E$y!%dCs%i!zyW)>EDoOui`+ONa)05ILdxfvPxKA z;y;|#;^P>+!HMUFSbiJ*S+z=P2H5uMh9Gtfn6cn^qMz=dH>RxiTJ1bX!cZDB8qcm< zlE42t-wwCpRc2t!X+vJVb{T4E!kI@;oDBE`!NWZ~we7_zr1_kt&hKyMIpvWeteHhx8RxC{?>Q`|Z)}y4s&)n6JgQTpk)KazqqxnWcpBoH>lErGWgH ztaYBA%Zz#m}=kW3${YR4TmtSUeYx zJjiM#!IvyuGQd2rRF}j?Wx3}8WaEzSK{lUHvxLGP6lKq?3y06FrCx8-B}t|4oGLmg z?a_vaLT}$LusA#VhEp}K6$i}@L*CG@LYFGbdr6JT(XU@zko`dVoS;o$X^2F_8>1cm z9hoe!TDot&v5Z85Sj0djto+?&3en`*$Dh`yW}MnNj2YB&;<~WC4$1LlA)P9 z8jU>8^;#X0;c+3_oPh%FvpX|?#PR)>3@@G%tWgkzv9PB{{`m1@h$#B6Ir;a@44x_1 z9$RU3FH$O9_%E3V!{SM!zxt3CXzL_}M60!3q+SoF`$BI(*;i@*NIa2No3k#!c7FQ_ zw=FW{=jPzTb!tlLqG}seB+#;T6mXd~P@+mCZFOS(hE81xj7KwVP0-09jT*b97;5%5 znL1Y#@>pfqES5C-D^F>GVs>D0pkbHEOanl$Y@cwY&et(muF|-d`F8S_O8&$UZrY(W z@3?uEsG~5eW?d(UM3LrR&ler=h^-^g18N*MNYg3$6|^GVLca{45an`1A(38AiEju{ z0QBbuD6{j19IYgUNqX;ozacgn5$KSH{%Mn))(K&Pi&KT1t<|0$;e|TOa8s?Rm~a0` zqu=j&Dv|hXdgmLx$~+L8TCBO;YMZC+MG2ITE~r_>VIYnIQc4|~VYjCk4WhmEw4-!I#a=b6eqd8xewaOGnqDwenCZ3@F_5O!ODeb1f(q>eg#T8`87n+%EYM42=LP4 zbInxQ(?@AX%||df5dO!{>;08-lKSaO9tPhYTLXa1RYvM#q&!Tt#{(}1EcQ1!CJ&SG zCiWA8nRqLsD%)uzxy70;o>SJ#DL|6tQ0a>?)og+j8|W>3aAC`649QKLK61|Kp*7Rz zCx=7!sFL*FTlu6aqg4dvk`;xL`2a0XtL>mPeq4j9t7ovQr7CxUJf{%9N9>|MQokBl zU5H=DOO(;M?H=w{vDVKL(+uAi&QI z)?e)J(I0soBCKdycb`RVOqU1!8lLOLiEit&K9BnPFx^3RARy(I!!)Xxj)BD-jsSn$ z^HQ6X!t?XH=6pMZF=zA9DPD;Myfi|8fBG-5Q_bLYz4&ueU?=?(vX4A;YQDG_b427? zz~;@?btHhcREL@`0sN|$)dqvl zG@<~*8}|W!R+hOZFoTqq_0X*jH-eaquCrqwalIcxJ3T4AHh&1+HcT)}i3@=az$jRDH3O5bcb*yf-&8BgO; zPXe3Zj@42eBN~}jnnirIC8*YvZhy`24M6FrYvqSGHp)kpqBx{O z9I7j0X0?cQFiRo)C*qQWHyI_B2+1j}K~s;u>Z5=cC>4*;mSTYnrS|SD1b`~fY{i3t zu^T+5019_uXgrez*R!qQgzn7POA--NQOo0?w1U9xRC_16sWEFXq0hRI|3ji3hZvPp z%Z{IRchHo>LYI*`N^{-Gr&4#x7NiQ2rM?1Tc%A&Oxj_M{I?hyNRVo(`<7%;@bwbk_ z|HJ|~4xLSQ#?M8c=$Yq;U;Cw3K?HHXW47?Xf1~wpqRVlIW77xpccD8;g4aKne2Rda zxiwp^EdZ%DqXKD5>#9_O_$U>eL> ztILcrQ@@q^?bf4I<(-)qjk9plM>@BU7`w+5z1ZNARDwN{arE*h;|C7?exc(cgSWJq z0r%LMI(jZ_dGZ+6Np#|U!*hKT$fh;chk?48dedP z@)T-;9+nt!nO>uiH>=-m5|@b68LH@UKP`u{or25n*sz<_v~^RESV4_dX@?%n7xi4} z^iJUbvMTpq|L7rmqxiQg;6JJbRqEcJNz{XZ(AH{u5~O+^WLKG@i;INM8j_HJ2}$X4 z+BxTTJYY2WMT(TWH9avrj5Klib6l;Z<*bP?a7KfAyh+_XZCkxJ)qY1C8|ttwUm1J> zGUc|Xvro$E@%1%tRd>B9yMe*|!l#U4^%w(7HDED^DFie)_J~wDE1!-dCK}WiRwOq) zq>7vdK zfCEmeO)}LqAaZfmc;GEoOI0M~gVzL?v=;G9gjEi#h##2X)Q7Rz0n1~`$1(QO@(@wA;4x3{#qkPiN)+`*f#QoKbto5bv9p}{)!%>xSmEkjxnTK`vYx{o2 zQ}M4n*=IzMF(nlfEC!>-(1$(M{zy!0%59VR7Us>HBMM4G0&kH;6Iq5-M*=%AWl~39 zO_7#xTGYB={=#(;j1Esvp7M+xC%DJvea@~vs=a*gBpQLs!~ME$2Ng?3kNo_PldRvA z6(@W1AAZJn6wN_NV(l2}z*!%EpPkdzOcO+>zBW8DC&G2HJ=tf0y_Ipwu*`xE>MQ^W~n z9DKY##70sxdY$SXJvvvi2v68RNI^DQG&N_ew#JDbJT}*=rfQtJI{0US7 zy)p5PiT5gSKx;_e_&uP!1dXphMQtBrBpvN<#MnTBOOX7E1K+>hN9?>`hqp>CW;^ByQy^vDfM&UWVoy<`g?+ zkp~%M!#TgimYI?>aW)oRIREskZLxZAO8Y&X9fPIa(XMZeyT^NY8ADxg$NUIE`6yZmsbYq^Z}sk&jY zzp`(6S@x(Sab8nzrKsn9LMJ=5_FGN8luMnX3~(k%`xh*jPMllhW??f;m_ z*ZyIA&L9>OF6aQK((QJ!W6puDCQK|16lXBw+}w!cA!U+}|2FK~g~O4FgPbiZJC)j! zC9TTNE=}C+n@1>x1eI2s8+aQC$E7r={5d?(e-4>Jjh{12H&#moB@*3`~3QmdtB`(#RNbKai8;$)>~uXa+qM6E#jOYY7!C>)XA zHP@#kk9rTeUl_+;6CREEs(*h9f0>em;`sCYuY zq)5}n&g637TDB?b_wyFtut>VB*1<8cBTf&92;zKh5Z^f$>dCbGUJL$i6=DM(=IlN9 zPgh~xM}~W0&BW6l)ql!Jtb{UJKtmyx>?~a=McP-v!x6(57t>d1w&7(MPU{HxD8RJa zO`O2;<`P$)!?n#~=a{gw=$`pM}vqkAI zzp6kKz%e0@9bt27-{9?v!OpVwWOIzK?!tt#i#_lY3efH;0J^KxM|@+caNpq&_l8?B zPc=AwU!yZ}IJa4)c>~_d>WWmxsoBN?dv!+PiGX0|FGc>pUcc?T;!yzGsV0)>)Kyye z34T1@LjT4Px=n#sIl+&17hZx%X=bM}ojd)*AKLA3SVIt7vEy!W5k5N`Cz}voe76ZuA-ujmp zm`4bdTnIYI1(LUJ6hB(bKbE+XD*{OLWPqP8`8@)sfR?6e1BlFWoL*ZWfU&4HGPx~* zF+fGr>8Y$D7MYkh(EAw))-vrR=C`ErpJbR-pVRh7_0I`$6yML~1_k!pSbw zRQn~M=oM?Gs~%ZwWH;3*Xms6@K$Rpts2irc2#R9~O(fzCLgL8AAF$7Z=7_{}8w?MIf=MxW=; zw&y4vTT_0w_b%5NE%O^ow2Cac+}7T0sTLUhoTH%%@CD(q<;couOB`Xctz!k71=i0o zi%q;>>#?@4uLNxc$sDeh>Sy6@0kXMjwr;pafYOb8Ek3;G>B*MGb`0w}o4&doGOZL` z$-rg+leg5^60$mRdtyb@v5V&wjZ~8}I`kmE@#%aKz*Dqsq@yZO8a<=!^yvt~*huhe zoHsPN?Os8d-DVlhf|;A70xkD^kH=06)B9%9Q{9I>;AJ>iZ!2y81lH>2H{H-!}tdd2YbmNc5uE5g}t8Y=w9ZH-20;; z#>&FJN?j2`f{P4&&Qjgp@yx5z)xZ@+<@4ti3ue6}#+ylsWPZ}_@EPY-A@H)kip{X- z*DG{@aF!+5CNgh-ndn`!&5kAi=+x=2ur&(%kXqvk^Am`hj-$S`EOB8nuK@i|x$(=4d4R<>uw_nIoajbJEspwe#w@Y=R~s zxV^f0KjX_g@-KU>w=3?atv_@G1%=Zlgv0&_fqL)P1}V#pA^1J!(*!2WeycN7p5V7C zo>P)+n0FsOygN9xAGP;MEnJ%40uh0CM|)u`1i1z-&(QlI)AfSkrasQw+VFM78wK4c zbw&K8wdXz@MMGky;K_Geim2Ad*{D9EybaMO!!w>=|9sj(q4;FrK>KT>%|O&Xj`rKz znS>p_fj+B7o(s`h-I9ANmc!dVx#AzkK(mXHIjh?nD$(6!$@BYk^ZABz&YO*oglf-- zVk0#UX7YIL>W2+m`I?7%9!vUkLo*^1KVywQ&4Q+6PVsRVM8Eu$m>R7~-PVrO-7eOa z8#x3{7At@B*e=&-!VK+p=nLT)DyptrOA1DZ<=rgbogt+Zcmg%ttMZy! zKnD14xX8J5XcWb61D-HKb`UQ@w0X2MzT;$wRSx?MC5v7u`Z(Q<#KxV|L(zXk%zxHs zp*4J_TT6(YIlb-E-|_I8a|@`}<>(kdW?03{Lm2(i236z=@@qkj_-u&ah9V=<7AR2R zG2|5$D2iro+s&a!np$N@mfsx^TmV`cV{=9fa&k86YPq%$a7`q@=6Le2`ml!{9y%#x zY(J`+nwF}>bpM^OU|pmrjRNBc-g9ek%VZ*$;cF6$`97eIhzp!}2pH9(`bLo8`?SA& zqP9roPDP!kI&d@zphDcD49Duo(i0I%X}BeI8iP`x-?&auW`GP{W{^%_5iVkQ;9+}6 zwapb3epKTl^=MGCw_4RMgXjo%B30}R+y3gv3@c`_h9Au%(B`1auuOQRV|`2fOVd%p zPo?A?ESB}lUjrouW^);WeMo@UCmgY_<@!x77zq@}#7v>l6?t@DQ)6HWc?rRdBLs8H z)HL_;YEL+j1gIavH(5Is95Y`R-m`t)z78pljQrSlz9$?#2TgE)4I)CK!IQxJ*ge@0 zi}~ARpGQvl%8xaktq}#41!5R)9!C2aO+51I#IfDV%h4U8F_Nrp*{x&-15Hq3a6AaD zf#mpQMywTK)Nk78Un~rjcbBGw=SAHdt%yt~$+ZDmNWFsZ zOJ=SN#x~wID>K3#1_uOz(i`Es(>(=&oHRtwjKcwA*$PYr$wtkuxDn->h5KmT&1 zT}dsPf3Y;H^R~$n-evOm!KTApdvbUzynsG}r;u|mG%L-UQd5J=6o`#_Ds0m&NGo~e zZws)Db!$=2TgjcRGTPZ@l6So?^M^A%L^e=G5Bgm!bJExaM!wEgY>*u&u^YS!uPZJT zh+-}G5ka2sEOX#MEW6KI_A}M_l18<}HSaK9d&ZA&0@a$LxA%khyu70U-IFuAS4Z5T zSyD%C&}NKgz{p@3v!H6Hd20|vbxMj~!1Bu)lr(@$t*xwmYsD9~Q;<~6MY(J7>WD;5 z)Gx^ZZrZzt{DSX=qYAjIk>c8=JEfJ1XFXd_ezwDW1Yb7CE&KQ9!ou+e^S|>Hn7Z$| zF@bj&9Sw1Vv>hc3>X+s3Z!!nlXPsCK`{49SIx!j2P{K_=eimY6e^hchYKS1S{>fvV ze16u`%^2F|L=rTO~TqK-)uqHs`MyZqh+IGBi(O}dSpMv z8m_x7ttaXR`tush4fG^#J+I$zMzfs25V4UOAz_;fLUSrCBLCDON6cXRwSi*$`z`Ic zm}KqaZ^3=};>kA8>Xq}T=g*Y>oF|!U3G2X4rRAdJ?a;~Of3pbjXT_fi4*L^<5dSke zhW#zgRYnFRku4t)QgmKoLQ>=3=VtQxCv4-(-3Dt8bD{MXxJu3`mLR)o#xvv)z$Y<# z+LIUPQfN+#DoE!K+WuxL!?D_n@=deP%7k!Q{F!rp=@X6TjA^3;V_j{Drs-xR^6hH9 z*Mz4RqFB}?1TE*xIS9zDL7_t#0UCO9Y}PPBuT>wM`64dCP8C+$a8X*4Ldy&fvO_%U zVF2ZNDgC=&(;wU;i+52fuagy@ycPtLZpikuCh&YZ)JA^Xb#g0t{0d!P@ia{tN}mf4 zo@d?UpyxrVYG}5drHg;&q@j#5GVIc?12wR^(wuK;gR#Drb23i2ZXPH2qgX3!Uvd;M zdKq#6rW}kWXJ7TxYca{Vu{x(OSyzzgQN336(2)4I zeaI&~W`l1#d;iuWPu3GslZc9|Y|kXh^6e<;7hq<$BpTR4qwFb310yHv-nYz?)6frK zLS}SG3+{{7w)P~^quo0jF<~9T0!8{iWY7GPNLQ+r1x4D^ZBAD>*pJ`cxP^T zD+TzAIVnP|6&E}JnyxOV)au>OW`NF$&aHFze59`~Q-^~NLP_VZ`%RZ>1+x;4;-^04 zN5>C!hWI3wZ@VjWbo3UOC$GXyJ!a?y+C-l~qTdPHQXG74tUU%|umzZKJ1RC#PI??c z;>rBT*pn^t?sNI?wNJE#gN0Xe;`Rs*kJkgl(o|YoZQ(Tt917-R9)=&x_@BewSafe} zJr0qwMcklSW)Q7WLr@SY`&ez;uKnNBN`ukz_c`~F)Z4O#Q_%EN#+y;nQHFPt$BJXS zT)O7|jk?S@5SRT#nI;cFIt}IvB&KU1m8I~7B=En~BM8P~mh3q6&&0ORkr4V=R1uFM zN_g2=jI0P3VP+gH@y`c{+J2#Z%Ms_@**lHg%`0Y*u=yfQ5cRE#ObSU^S;Go&ve4c2 z&KVMY+Td@hH?-_KI~bk)xD~zMyiWE*PB!W1St38FqK@EK~y0t&9$F+~>yoSOd2Jrf80?Q(cf!j54TVRf6Ldv-=)qWj2-veO^O!# znt(;4q~m(AuH?rOyk?=bK2|DLxoSUSyN>E5UHVSl#+e#cyY@C~c{PCh6d-YUpH00sqt}Vl27#!Y99~dTOeLWx@&dSQF zXZJ#FV5N=>E5n(2+nb;g$15~BtYN9ihIa{xFm_#-f6ET(bYrSC1x|7a0fi*`QT_b) z6#EBwr6COja?PfH4iG`Ci2n`x1>!6rt+p}gHSS`GFp8fJ6|?EFT9Ye|ioK+MvIItP zEp5v5Wa_N@jNP#uw>B@!R(zj<#|HouR>E{fEjL z4Qs$Hu3)^Q5Y@idX(IQ#RW^SuqKE2H+OMyIbO_8=iWAb`Wp9~&9&+b=YB0iYXlm?@ zhK}e6YLR;t^2)@Mo{pj$Flc1UA~>;vGZN-pN5PmxA4-J=+l+y*w9Wm*%a094b`UvB z8o#A4*g4l~|8Hl-ZywkkXz6)4C%e0G(RD*L7X%#U2LFStZyOen&^JhjkTQ+Ni~iAD zz-wF;6A4NhILSGAvQ^__K{A7gQDXEFS4Jre3?A87SxzL5rDgQt zZH1J~@R?tn)D-hVC*-i3J3;9XM4|aUL*i^xNuziwabehrMcY-)_t*;=y496+gz;`+ zT)Pk;Rq@StlJUkp=@a>%()hJ&)^;;pZI~G<_ZO*37QEx07iTKnF41y4B!5{xu&xa3 z#_5#uc&A0j>X=7|kxuBY?Vs2|dY1DRaXY}8YuCrK8xO*OH8{@Zi=C8- zKbbZbialNrbtFs?^Z!QllaNZ4!N6BYb419hJ_x<&Ki_|G;h;2v_pMlO1vFm~(0Hj_ z6%AtD<4R3LY?fcU@kfvU@xwd?!j4I2`;orR4<4BPsY%V5MJmg-_E2KNFtX7SRkeA! z)9@Js=6qcVALTjqyj6^i?b`Wc>hSdDUV3e?wHQ0m2Cd`yb&syH=1==Ys$b+)F2T(F zKN9eV$dZ8XS*XJf0S!&fv1fy&RLrpg-b!*@l$<6#$}f(>0ciVgEE-Lh%i$w0RJiKA zm{Z8&_^uWd zCGL^1x#4vKLfq_G=?-{3MvjF<85=&X@{Jqt9-$-^OsBK3rTv^8LMb@>it!>tDjZ`6AYvXmc=;CfXyd z(r#M<(kjBY`}_|c>VH_~&r>LkD^*n5JnqS~q#pH(R4VoC{*D~H&?te#w>AptK)Tc@ zlxy)dcDua)jU3;jWiN^uIsrcA5`7od)8_Z#bGOKa25nv-cT0+3uu=!ryk09soMo>1 z_x4?8;HKmZ`u69vdDJrE&GHfTIde;JG<=_YuPY@9Hr4Q21OL;@ZZKxWTVZ>%MWwO= z8epbET{{tYIH<^^m7GnHhwWola0UTdGH0bb#vwZiU^p)6C$urkVJkBNHB!1T@qE{4 z!x84#PI`bJBVZSxK$dq&zrY|c8t`*8n(*WA=vn8#7MT;mke7Jf#KFl|XPoy_=3l9@ zx@ohT<8oh0Q(A5Dr6>6J2xdDQVTnGEdvN1SD(9G%S_oS{MTvNe%DenBo4KNiF!x)z z`Bf@)GVbeKaPnzFDW-GLt5BQxkflZLH?ncSkWOEB%`$TT-c}@0&CN~^|ciR)0EktKdVJFV{C9GvB!NeQaa*@C0@Qro!PzH zAuW%c^Z_|YnO<-;`tic@(a=G{_-)Re{Znzvlr@UCrleTsQqf%7E0=ZwL}v6Ok`Bm( zOHC@s|9^qIk@R19*b?YI%N=)L?sqq3w|00S5!)c<>+yO~?rTvC)bP!0Xu6Nhwjo*CD~WvrRSSRJ-;%A!pSi);~Z2Z6cow z!{sl(w!RS%u54D7Y}wo4>K@{f1BS+Kv9H}363LS5-lZ;vL)IIZPRE!>J+nnHwwQOT zq`H~8CegKh?ZX^d3oedF%q(J-tLXdSC4Gm-HOf?(h8U!)g9|q*5>z>hVv}(#Wd5C0 zpSnc@WOMV5RK4*gLc^Y4@TA&*6Y=p^jfAXS-X(Z)8X>(J$Miy>@GyZWVAVa+)>xJ2 zf$isxczAs=O(vDlXN6lbugI3^b^OPj>wNKXq`St(jZ|)UES{+K`tT^q`w9qpUx+WE zhIYyTOS#;d+`C}pH~v1{nx^T?YjaPH7GdHZCP$~2DmFc&>dnq3F%LULf#$?op4Hr$ zvF53l-Krby%Nn+!?|Spiymu@Y`+DHsipzNX77+J1;&$8GmQDW-M~*cXc_oqfi=;2= zNG+16dTwEs2`BUZH@RWeRm%Jt#J?6>uE;d0S@pUGNU7^R;`^w|s|;5hL|I?`Cof-g z%({K<@-%R0tct?Ex9jUaX_nbKjA-mcnhlkiQ{9_uD7L&|F+-db$m%qE&6zTni$`ih zq0hP^Cyzbowq4w1be17JnO@z9gbJNGbC+@gmZtX}WiiC⁢TOUG$;bf~1FbSsHqo zm9Ac66G;+!E)k6Cf@;wVJ^()5d)TrCd1$MH~A-C`3^GvyC^wTJ0lJN>uHqSrI zB3sOd%l2?|(g<2Kepc$o052Usxh@C>M%+R&{5k7Ac?yX#S?Mx)1V4rQ%4FvlRMQ#l z)@k;j1+XaDU8{{6z1f(%A*BB^b44U!>%Xa(zlr@PxJn@5*tPSe%9@8=9>6oOlx%Rr zVL8g=Z6dQr?)A+Ee|53%6%|#!=zTM6m1q*%j%ClED*Eci*KY@-0iRF)9lV za>1H^5)*I#>=u!mLMuo0OlVx|uH3~eQNC;u60}bJ<#y0xzj?_!@~_* z9}&J#t>3cB#WXLF{Zs-DQMin-e{q$VtYVs$UCL4-=KBB9^_2l}WJ}u+AOsKYl3*dY zJ0xgucXtRnxD!Hv;O-VYxVyVUa2tGZcNydxvb*>0zI(s=G2H{*)7_`fsZ-~vs;7>o ziOljQJ=#AHe>R#gzd@RZ`YdZ4D;Vt4gEgfdkj0)>{hq86M&G+qTj-&HxufJCz!k`y2!E~*D*DB zgWhv=hzaI(*d`6o<~NV!j-JeaYn%S=!>!QhuvT4^U=~@COXo*`h)!!KO2TVNEUB=H z4YvF)X*;h}D}tE*lTXsfo)4a`@oro=Pl(8PQ=t}@`K%tJsLNw&HwcA`c=h0$RV!dH zZ-u{NG*vqSIB#=U{gR-e2>v|B-+`F3vz`c*L{u_n(E=w>F1@Ij)nb)!CHFp zQi~ryAhLrS!oo(kUY+||7|hwoc#12{z>qS;h@L)Wt_U}al+WdK9_kasVq6_+G?WL^ zJkfhDkl}k7}vgNJ$??1o*poe$%MN&?r zZF!#6(c{PHixn`$ZGJFc6$n|)8{##_KpdF=k*NH>HM??`V_i>A&uCr03ngwzM+G?Bfg{RO_Gioqh9AUAAA%twc=O#j3M61?sw&u`~y_Lt0ad?yM zlZ&jU&2OZb4g=6k0T0)BDy)PKl5C*O(WM<=^Sgqy=*n)D$Hcjmbn-T%t|;1WuJ)~? z0QQ$JNG_qZ6w&eYdw@h@u0;C0eUE->9Yr{|EXxVENORoYC+{l4nQ)wkdpp6@6eGFv z$`j&{zDeCRjiLrKoM>*7xSGC-bS-v)!lVswkUG$sYo8v$?rQ#c5$199-bTa$h6xBH zIp%-1JKsLpOSp4HQ%d2WlJNCIg2d|WHwUZ2C7v7jFL@M(^xBit(>GG_bOXeH=4^ao zVR~i75strduVDNZ zGazpG8)JgTQ%_Uq!i6!w&1^_kb3cOU#*0vGMEgdt>l;y*VUOV#z_~lA9-EI9P_}sO zV>l3>wEp8vc7GGyqE_IhQmgR+t`gpa4Tq7y@hEVUREd4FYm1Xxa9icGOL|0$oz`7g zk!<=0wX6uwz8|^{^;i8jbm}EI?cHq9M2V=YZ$#aYL!jf?*oc_Z6C8jkWLB%unNSh~ z8juB++h^cJWEyXX3#o3ITtwS(f;NAc$p4f#a=tv~{C??*on;OMiEZn~FG{XZj1T_leK9 z0ABMKKX_wyL#A*}*n=C(jFL;~Wom|g^TQ6C*a$y7P0D0-<+dHfFMR9qFszl+gEPP`_eM;j&XThEjs&2@ zB>uGQ7AW}ve19T4cIK-06y{6c$ozEDQq%{y9KKCav9+En)))JR?rpn#;8lu=p0xVb zD1ylgL?;{RtLbzuXu2NZSFSVZ+TxAojd-0W)CN6uEoGQotVFiCI87Zm(&6ub3(#MU zqoQ9HgXOIweS1_o`jR6Bd)QJ$#{&dM<;%NCFx9@&8g@$R-8WG0F-8chTp}e=XFlV} zk+_LVBxfK4Q9x}2uYRab2D^$sbmQthh_XRZ;U6ZHBE|os`jj5vk+gJ7?A*ZnJqUTT`zY-G4$S;E6l(AqV&>J^^SL?{dohyl*P1vb zBVrAJBF@9k57f`-wGIo+b=FL4Ixw7mqBAA!b`i*f)pgDqbqrQYV;yy_m~;1L-|BB! z-KiFgj`rpb>{xdJOklvrQa~9*KP;5M6F`eoGfxpa++(uXQZToK3BvZxk$ItPs!)C? zG5)*{g9=#ohxf9~)K8swt4EH~w3V^ilh4vAPaN|{^mq_7;Y?cN)8gk>Ev+XZ|kDw!uWq(&BTT(RJrXJO;`g=4R{__6%9@1g^R! zE3HDxR+U{*T$W$JFAnvB-;v!2|4vtXR>UAt{h?mM3}++B0t0PXyEzEW=*oRB-GBqIHs+#g#2=_}!O? zHl2>IL4ueY>v93W=>mMq7dBW&59EZE-km=bST)$q_=XHqPf-TN)*1^GmLYKz6iBmQ zFElD&lzp`SBimUQ- zb2(9NO{pizU+t{MXHSi2!U~roc*f!dG42c5ODb3y29!pDWo!6iN$lw-Q8H>t`M@q4mp~uF#7iG8-)wrvr>Gb zp;aw*y-x`JyRrE9%lzK&ugd)22L68(0`52Z0%A1cXVVEbGc$9Hg~aXU{lfz!-}8-9 zp7ej_^?&^Gy&1Q{S&Uz|S2Pgt*FT!)qGRtpc7DB~!$E>T_?|PT{j8Nv`>Lp<0@7Q< zNily}T7O;mpIf&t6qHYpysmer*QBL(Yn>3-DLIB(&i-(L9a4KFhL^$(R!&ZikDng_ z5mEB!kDThi?2vzMLEI9GXSU|%J5}Mr>3+X{$wLx$2V!Y3pI78!_JI^=`pHyz7WR8n zG_q+tqIPz6kiR{*=fCC2z~}xH-oU^>j%}u|FYv8sFyH3)=ZihIKpvI$i3E~+{o7*y zbR-W#hdegqI}x`%MZ+KY{{MWyTlnvWIvFf%smYKOdY>#U8%uk5$aT-kFmQ0hI=;eX zm>*>LJl@7;Kc9B%Qbpkcb>>NPdY#d=W(R>1qN1Yy=d0kuMhy>R2n^{-nF+C>aA69v zCrXnZ0(M|Mt;(&FjL$Zops;JBAa8seN$M27*7uppy7CKszY)+AA62KS=W(_=Vo9{( z@r@Sus^a({I}0*(L{YEp?}J5tgEb^_(X>y=dAD>Mk=xx&p%9M^iJ!Obzgy~zFG(SP z-sgmm`AYnlkR5pbYqg|q0AQP5;ubVgWm-Wqm2$EBK%!AVHRgy2$$uD zkmZYXV{mFz@Qe~i%L4%S4-M5@?3Yq~9wQHcL-~((P7Sk?DBB(2VWZL!6 zo;LcBvL*iey<#d?ExrQY&9|pD?qwCWx_Zf2BVRI7XwwTEfz&oPK)6jcQZx0s$gN5U}wp@3Q|zWVC&oq z0;bCxnC~V=W5si+QY>e`N_3+Rl9$sKZv9RGfZl1|$l{*llb&#oA?&}H&6>HC|7SWl zMFST@)gjpJzL}O>g`h68H6w1{thVAlP{Ogu4c7Z9sdT2tga2&^E}0?m!y?)SnwEyZ z?G=oq8~^7oX)u%2RUA}|4?J-l)M{jm*aR|dNipjDKe(p(Y%U$Bj(InBtIFA6;2n)L z4@H|}mq9z6I(X$XVk1FD<|(5uTqeHSvNTlYAhGj!N;xhEIPRoH#9m1e0nvSn>h`w( zRCE0yQjkQeu}C*JYN>>KN#i39HpX=s3=*&Zo3aj3*glbz)?NblTSk&x(21!j)1jW$ zILv?rR30=Mk;l(*2t>E+Mc&K8+Pn9sgddFRs_ZY}iW^pP?91W$l6Egh$_c6#)H&$9 z{pd!a9?WA}*eKy6OfSZCl9a*DV)VMxFPS!cY5)?i1E2j?K0&pP#|rOu31vp?RIfea zm_1s4o=#INj~?FdFjr_L@i-C2V`TiIszafhH(zR{BXv$1%Q5LHSeQB7dGqJUiSh|ByT|GR z0gG#mCDy`Yrh|JvclC57uxW(IXAAq}S@FmLt5C??x(`<;ljmO*p2ATR4G@P?b z?#!CuIXne-OCRa~Q++>w1Ce%;l{=FUHqLY3&)U3&PEbVoiNB+Ne1=Wbps~tfGZsN7 z_&KsjSEo`-=1&kI*7i>jVGk=`R;RN~1fNAyXufi{opqtk0;9E&v@AmKyIzaj?OvR; zdJNNh_XjppV#hq`A}Zr@DD_u1z<@y#HFXYaX56EB*KN&u&W*-xN~;cD<$X{8qj^M0koTJrP} zwD4O#-Lxi1@-7FmSsB)^$1>dFFg+qL2p$-R?_0dTvg@_Ufs=a%(zuB~b|m%dH1m`+ z`HV(;tx4MbrJ(*ck+>0PD`DF@e1F~eCi#i z>H(3UYpl9B9ulu9Iiv)6oz|xj=7R_ayIaL~W5#AiAorIom)L=dY^#$M)}In`mI@T^ zS-hb0fwbd|2EPtbO2j_!FU*`!?j`KfaXHym+hBPdv+ANWbU!{AfOhYg(^v%QM&=~b zImO4bxrz_f;-%-`j{|OAIP2cx9v%OMsQ6$no@?~_cQT@wiNGW*iW`PYXUp8GC9agA zu_oWQ(^`aXV+QjEcTTOc)`Vg`62t(%N4g3cr1KqE0C{Zhp|7Q ztuuPjvt1#6-!A2gquY4hT#=4{9)6~IJ?x^=7_{(6-j>Qzp-yy=#F})uB$)m6+Ruf7 z;4u!b)<$py*QX2DsE>K$flB(J_=R7Br(A|%dW1*CU(@GU4{PZ?SbsE0bE3w=oh~Zn z)>@11x3fTzNeODXbhO?zkILf~72+%)0Us)$j+T-1q=XH{a0*NE>7)TJQQqp!lD_H# ztxxDG52ld#$l<2yv`C~h5u{PycTB@>njd=P{c13PLo`8p>mNuv%8;HjsuEVJ#93}~ zM7E$dC=*#m$dK*}DxFW82OpP6S=l=+QY;r}ebFc71bX=msO?+lS+%w8Sr0ebe4C?F zr^BIBC0(FvJjHY1JJ5{zcp%W~{vbnjT&qyMXvJ}V%34JozIk4Onbcs#+EiO+B0aeZ z0{j0Rd4m`iKBw+< zoIKV{j1ydEAt6iqCC(9l(ulnbV^<}1!D&x^yHqu$&`n98u|2Q~Q#P?1_`Sha&)9JN z%1h#U%w=8E;&n!iR6@7cH>!mAQT=&rPQ;qsK1h1pvCRXoJdih@o^`u?EL~syc`R@w z3(tF$uP!?0@NXprprNfm)^IM_#2_|;k=4k);b0YY};wl^G zgK1<~w`luBY^83!Y+M8k-t*P9vw#;IPM1BtqqdvBW7VlthvpUcz7GxxVT{bRhg5n( z?Y_L@E;UB!B!(#(!7t;h*^%eOwy7|iYqmqhTrL*=d5vmXCmjaeO{~$CdhF9x?`E;1zSnU3Nj$Udf_H@*URx9u2g?9;-z)Su5NZN=)<}KH`8Ub6X%prlz zkd^FLKd-T$_LY2#+_$~<6zS`(buQ8vf9(<9e*M064CMM zRHcFENt@oh2MEuMK@`Kt6+`(4RoT_*>|`UXz1*^0k}22BWKo^1S32Ot5x$ae z_;0YWy8Cno)W1L`nvWX3#v$~6ef~nq^g;TY2W4aUUF6lZjU?!O!xdvz&sXl@rRfl~ zv&Ao#Rzznnv(ZfR_6wn>7`=!$^7YKw9#LL$-1&_SQs)Mj(Y~o!RHWY_Y^}Eomxs@h z{XG01J)#gD<0Eq}p=)cp?7g27&iI`~cFr`aOq|zVhq1BV#TB1WpuTP{pntoaJb0JMQyp-~1%(hefsAk9JmbHWd zFt}eVbGG+Pl(+5X+v+I!JGFX7-uGb!lhIcg-sFNcPn;?9DS|m7+|=dA8$(B= z=lQk{rZ&l9F>E;PIpQr0SVi1XQ5$u?3`77{ruXmTR}mc#mi;dfNIa7O9x)t!LxGwHSBtoV&srrESYL5~JlRJ()eDEM7`Tw|7dGpX?jF zJoh;rlB?QTIpZo$6wlX^dvAosa+`a1p@S>&!MBjD1pWKQFo!DR%BYGs%hudqM)+SV zYKRHh_C1X6P&f19d)=);fv?ZG0h_FcSxgqCk+|4ZhSYSqigof|u>h@@KQmk~**_;x zrnH4wZeLf?Hxo>5waL_qQ#QG){g8EIY}FeNOb&CAr;q7q(CHiCHb(afS#BX^xT}jo z)+GpzqGIf$zRX(m0wbYlBerz^a=txUDBt61N}Mmswk!G-NkD_S7`r1JcNce(e9iB$ zZI!S0_%@MOeA0SYccNNPXk~&#-&OuPdyVa;f_|gPODILg@7;m@F<-^~mA9z-!H7)5 z3;dHBF@XK#i#$@+e)%@Oq}ZFkmR^iMw`1d6{SK9uv$x%m0JB|OF6OkBvkyJD>Ux97 zB$6qsO?pV%_2|8ub|>$&leJ~5xb4r7ompZ)*JIpS4Fm*1?4rz)rnRR-^Gc}>AA;fe zaw<$pgmR@}=G^z*&8&LwmT!K6T}(r{-2i>`^SYj>S{=;bxiP!FsSyO0 zxXk(|*sX_0UNfQ|iKob42NG!;r+T&52i?S`W4`8gV{&WSvS`Paf}K;3**E01WGy&e z;@9`5PQiyuI4ABUb%~3%6k+c@r5j*3L--|KOhG4wTreV>n|^~RNv{_Y8CAnG3u(U$ zR_^tgK^JIn0zLGGJr&tHui_wPFsJ^Oj>Yg+E7sLwJjUnhFMaa2ErPm` z=9&8;+Kp2t?ucHAgGZYtA1C7VV-$*ppuw-7NyW*m=_bshH!n@H?Utq}XlAD|qyrIH zxv#ds(z=&|Voy6_`lI%sx<32sTBVrpFkmhdcyIx`G(i+!{}GvCJ^)S-EtNGjAZ+LNGM8s_wNaqsa-2Kgg{RQwGm%PdP zO`mK=mux>w^a#p}!l}G(`)I|$s*HDMYh6wprRw5|HBh!~8mFc31*N*_d~bC$|7ycO zwvTxb->MP>C52Ca0>#Ls8?ili8Z@IfphG91D{sdeOAdGI;LO<;owPyLEmtC=BYvBl zoStTRO+Iskt{9>)c;=$hAMj!ZIXmqWJE&-Uwo+;-Z&qea`(Zqw@N(QY#k2I>%=1Om zKh3&f&+-U1C#8L^i`+z4%o!$47L%& z3&bmMz@K0#q2B3j&R0Uv+-JLN;0A$OczeWjM4rF`vD!(D*u%K zBMR^=eM20%U?dPRWP9?g2>kXG~sw2Z&NCUCgir# zSMA=wL-i^Ge^5?>hA0(wW;HaYj)%*c9DCDpwioQnpJwO$f|V)&@BD~WB4Y#25b2GU z7-1@~=gJE(_5S2UkMKOxjC2GeBWOg2yI!{TMo%?xW9?k4SRML29ac9b2J>}DS7^k^ z`Z`JV(F4qtr_8QE)?4lu+VucW1ad*`)NjTPNU9;wb7>YQVeHJvAhxPC? z;9;!?B9mShrFHRMzZQL^TQ}AXFyGeALeXO}l??K4%b>Ui*_3bgseD@)WVXLEU&v`p zvhvTuz z^}lkq?)ov>N9UbJ8x?fb)~_;66lae2GGexb;k1NYuM=WVUp~g|DfI4B$2%5$dRW<0 zr09pS1X`%3R|+TRW95}V9ed9BAMgA0imRMe6skG}2i|<>#=o+v8b9izslMWDk52zw zb9Vk1(9o=~)RA0i@twONt!R^)^i-(g^;9t-{nOa8j<`6W20-*wD*EY#?}u0N zWc9c%fvYw>nm=p-h&?ntl9}~dQSm~jtBN`1AyNQInj=-B7ZT1c%Yt9Oz0Qe^#PZH? zxQa|`aM(`TJec=zIc6Q}Zj?@1N>{a@Vr{gLT@M%nu#;$So%zAuP%=v8TEXnLcw%i_ zu9w*jB`j`QkWj#(b&Dz=ZFxST#yLjApC^?T3;P&_4n*Yl#2>T^4vPV5;bt?~5; zpiKvOoeXJy=hN_FZp(qM@=@~EBodj`jZqiy!lNZg1VkLlyl6|sqKSn*=8TrJ>}+U;#k7<|nZ zip3#p^0a-*+A{5tjzx(A{t9w`Bhl;WdI;Nq#5$w8NLz9Zw>C4{Kyxvd?GY$(z=2Qe?OlJA@E%Wvta46r|LdAg-3TEB!_d>s0Z5LgfW?6=jkZ2?`Ia!n7 zNGG-zV{6S-cyhWBF?64vQ+ox8#WJQsVXmehBAL=l41WKJseUsgT|3`$GNzldOw4<( z;hR8hFV2s7`X1G|_Xn3J_yI9q7AXCi!L>Um#5S)P)Q|O)(Pu6z9Tz3Ik>J3UZCY$R zT|EMHS~$6okPdhoM-w+d`!dh*@15hn8uxp%9P$y7ZbvG%*-6=C?3eEGjJ0Q;Rt)^f zFhb7I1a{3TQFnfy) zU3TzsxuJi4c0jGkd6L%>Yj)}xeRD%8QY~@69Bd0Xoggy!8*KT!8&!AIA4OhmIg9$G z{>X*Ywhget+9>o44+VA0co(LA50D~lE{~%W<@M%g3H@4Ihc!csusLhvZ_dR{2@^4r zRof?(9C$A@X}p=}IFCOd%Nmqiwm#(oT`wZ~^SSw8xVYIX@pcz%C@3nI7<%x$tmrfP z+S)V3AGh333`Y5w-mTiWFZv4f>6ofYeRvR!idZa8@+fy0<1|)UE{D7ykvAyp|LnaY z6k{1Xok_Lyw}9^N#fFn}R6q zD;Tx&L~XBwhR1PDK&jfifbXoFf~y&^(ah9zA08GOg07WGB7(T!Vhr56&>?<2&7>D{xw9KvK#Fy)tDNi|xr0ib^6iMd2!VaPjI*TFe4V!(w z1)c1FId|QtH5x*QRh}SrPgG)O8sA7j%=Wm_Hoh2fYEPbrn>mLea-4QHYwb^i+aE7< z0=-0En%qI|p*dfB;CBACn6lU7hdx#l-Ltly?~mw~?w_ymWsO$w5)+@Nnq$5t%m33r zBFlwjWG8TF9vA*p&o6;>?wU2v)J759(=oCoM3;dDDwqy2$rnnmMtJno(DN2b0$QAe zY=nn|z@I9`nSnm`Wxq^)Guw-zw2kH24n@<8zG&9Au6MnO zuKgq&U{ybyUDS1x!v3(QM5RX+P5nKrDFlV{7z8SqjKFT1VXl=ivCj{U2n-EkYHv+sW_@=Xo@g z7r-sH;H{#^3M~pTPaF=WU&1YJJO3HgQ8Hcf$=YF~t5gfY-EoIDT<@#gqjbg{+^0=U zq*?V-37v8QKc6PCZi5cNZP3}BL3Oe2x8VWL6T6x<0%~RrO~wt5RX%P%D!9p*?nPqU z6vAbRDusd#I#hW6-Hy{fEKOy4$t$*?Ai^Q+lo0qQhdQYlO(6x-o^IOvqw)TC zdYoh_NMDk;xRp*CMZNTh+OR{|IV_}RvO_a)?^_~Fs`4ir&hWKe$}*ikBXN~gc?@W) zl1hpuMGz=-Ee;>H%`o}cxD1X#oy;a}5KYHhXxvD(-oy7+Qt)qT|fvyU^;u3H4DN2o+G; z^!3#JqH(?KCjgXnP{4;RRPZ;ykEip3rC7RO9=hGP=;lMUmLq;Dy+J?9#GS7&hBhL^ zHZGoz!SWwesxW{`y^Vt#5}PPbMjCKIqiEAohjppD%2M97KACo_$c{5}%}6qdKPJ)*6b72b5J)7&2l73UN$_~ZDmpB+$_1bv%^ zXRY4i*^78g^{w&F90sa}@s9AlMF)=2<6H3AyeC!?ucwq;=LywR-X1vrMP>Xx zHtop4tOB4;GuXuM#&6F-I#eHEP!{-b4vjVVhz*tuH|?twyGevPlCN^Z8T1iMndiNW zZu^cxF%rkq<%N&kCiT z+i|wLTilI}vBk3cNZg^$`bcq7n(D95mJ4KSe$d*3!72}U9Q){t*}Pc zI)N*-mHQ+)K@aZZybRW$J_Evx1yk9%Z;Cn@6i=<8tT#BbwtnKJUyUnA)^FyKxLl*} z!B|S#!3m=w`_+0}P8_f#R8N}G*x9ZGNGY=SJrcYSOT!G3%BNkqm8X+?qb=wXz7I9m zufv8Jf7vuw%NQ$`tF3$7`K%mNG6R#AYuWkpOShFj@d*@Pz+r0D{m>l;bq8DRHlcT} z^^kMjPl@3oQd`TOe~R&eR(ksxg?Jc(Ujnx#GWV;YPwf5vZEJ~%T)$1y1?rkVi+Ap~Nl3N|t>looAP5ufL0;6p>EVgxN5O(tD zMS!ovHi>g&;p*@A%*24M zW3|KWb$<9n9e|6|Dg`|w(P-jERC`}2;0UL#3nj4_(0s~<4{Rd*2F)c)vYFG>QFB}r zvko?Es<_kLY{ZQACq+(f{-o1L*%hLaJ@G^C=k+CzsZamdWnZ~oJ!;|0tI(g(emUu=3}r;0 zQi1~Yyt(x2c-xJ;Ov9S9fJRiTRPFKmNO@O??X>IORcJ{YZHF&dUM6g_8?Ag_#;1S2j;&n-$7HY@!6t#{%&;-Yp68s_MQXc_we{_WIs}f_W;ME& z2%EKFDh={}X_=|XT)Mo6t$&5Z?B_GP-@Nm_FQkfTlaP&S9I;qxWR4TOxJ^*mOHEBb z<4%iD`FXKqc=o6qc%-AnLbGa?oL>oPS4uWY3xV?TgLZ~1e)CVvbw1crg6mwBskuIL zr?%Wl{=y-zaSY!Hq_i2_NX7W*g;81{Mr)*|BFcWK2*wV20LH)3Uf|A<$QEZcIO1U7 z^1Lax*YY-B3~uxnSfy`$UU;0LwHz*1{HrmUo%u4r&pC;=wv~o8UjR=GAH!$4m!;Rg zuoycu^zDrs%@LO>m$FiP`*o6gY}N2n`3*v9lI+ScD&VQXOY=l(J+S8y-UAi3O;-Nt z3qsNK3$fSNU$Y8j_2`0?QOQb;1UK4}dJ2BM;|YVbRns8oV=#oXsP=*^AC2C~ylW~o z=>ePld}a-N{#1ICdJbe;aMTD_s1?j6Q2Wt!a|A-s7*Wf3YNw$t6Y#Fs{NY|Rl{hM! zJ$tg!04~eA3oKSG#`^|DdRrKPAMc3$Gjh2ztOo|K`f|phh>-V@NNn@#v}3}fS=i4YPI{BP+`F&dKH41NqHVT~=M96eJAs_u611%t0n3N7m5 z9Y=0!ca`6V@5+2gC!V5<@#k_utuS4a4Cf~6+la4tH|~W;T2|O6M|>9LrXVW0eFKFC zmKi0Qi_pv0!&g~GDL*stx4%In>2SG}a>y1VSzqSuun{m^>*l#>9v5ma#rmm8vXWG_ ziz6QZ!;TpJwibIkjGm~Xt-vAiyIvJ3jG0Z=El>=^#S|7y$rAI6J<+o7+W!6iYt_rq zz(bidS;*2V&4kLi@vNFyD}BZbwcKi&-5#=9C`*E}x*v%yYdk&o`-)7m5NT{mc8(kR znKMM_!F__VoTY02re*!6C(ctZeCr%r1%JNeRg#)=o=|#DeW3RCSPeBG`W~efRjw+B zK|GhPW%tquCV06}xM8@pKFN=}ahK<1!Sb*~@w~ZU7D@;$TDD%$aB+cryyqiebrkOL zW=YadMd@~~?;GWa_(fW3oN?S>q(Jx{JY?B?pYZNKnE7Ao^Lb0r`(3mGS}JL4!N0>H zp1E{|IF*5<`&8mnz>D00hYnf_>%?XRyxRDT7*B~ZiJ>HBcNB)8O8H_}T?WRvk8~00 ze1o&>)TJHQDYMZ{V|CKnm0w9Ym*65`Z_F5^kLEH@%BfN2~^Bu$eaLeI*W+t*YMgr-fj4l(20Z%H4ij zJT4PBB zG<-$TM-tn6k3Y6V1zu?tyN@x?H5cz{QLOUvDIRdH%4)JGBUF;!EfpL6cKUtHEN5`E zL5aq#eFq;=8koiU@ESRlG?-o0YWs35V zo$EkrLKP3f)4vaeevi)(+6q`$SP>Vzvf@8+ zvF8K&wJN+H?siap4;Skoq3uaKs2hT#0}aQt(FM2OdnG)hE|faiykyV%1dYpS59{&q z@h>pU1j5`>_&=*2oyh`-Ho=aGGzH9 z8|?4*`n=yPmHKf`*v7$bLpol&egLKl9^t-9zWxxa_3q4wWigBQ1LTf=iyQj??-#5z zEJ}~Ig8qsH5U}PS$>v4<&w2D)JE$N2-ar4f-}&!;45FOKl@f1s+|ByU%=6cep}V1} zXJ<{aTh54x)l5^Y!c3zb(3Z@;F+xJeT9;sH4RONOAcT4zD5fzpL+lFqI^P zPDL`F4qrtl1cE_6V}p%F&vlu8%O@_#$zjpnK2HxWlCkf64e%mJ+m)Wgu3U{L^JEk- zAayF9rQf5cHKK!3l9lNvjTFaK<`)mg=b-vOL}7$z3Hp!Y{`l|Mo;CNYTAw2RI+#LZ!&Rj&ihxi1)URF(L(!q zytasDaqB3wDjhvrsVERjpE-;uq<4bwr=)hjnk~V>3Rcao_Ld@4Blmw0lH=s_R8;t( zOX@9v-)h2ywC8Tfk;EhlStG7i#g(z71MGLVRgHr-#R?D-Tpz#h_8f*T!Y55uF~BL^ zt{$z69f;t+o3SG+8uM?R*ndtPJfjlT*jzbrae@TuyD3RiO|niu=Meu_mS4sUVEujv z{XXd(ezay>E<+N@lGZ;XdxJMR=ovER`nKF4`R`6x!j`Be%Ml|3d#5L_uPZ}=jsCq? zj-W8`=Z&aHDe>F$d+W2$L6CXxyGRf?Ra@Xop3Ggv)mJ}tw+!o3{V}Nb@du-_V_(^< zR=yb5K|;3!%L*Dd@q8Ea<>@mK%A;E~%^GtN-FVPv>w89bH#EGs5eDvc70($!ZwdQ6 zWwULNxKG>R+Gee{`37zX;4EsEMUp#n3-o$Z7CqD|9W~Y7AGUTh9>TnPy^pO&0_l5E zoMeOlyILCsODX8akxaO-QDAw!zBUG-WN%#H#NoaAdWA!;I0Xw#;)!%p!u>c-(Q}W% z9CZ*pSILeK)pQ}bw$hLQn4l$)bFeUA-dsY}aw9V7UlQ<`I6@;QX~xEe z2XzGahmv0AjETz;50Avr_cQkkZG~^_#vZy^Fut7iChRwpX*C&8z}&6M?{XL$n6)*# z$`=b1;BueI6gAMJgBq0@E{zGhJNMC_xYNb@x%wEP$N2nEvzO6Ye?=7j(MkFC?=JVX z+r0UIBWywA5a;YUP<(SRE}NGRaz>B=oj`*Hw-a>BS-qXXks9*CJ(*SD2II?3hmPc0 z)Z5uFxsk@0N5 z-!yhGHF3_y#? zV80>D^T_E813%+TF#!a^FWzj{@y?z34ENz{lMqXE7G@~)j18Q|(Q;Y&j3Rt>VXmKy zNR_w~3~(OlI}bTbK4Dq{xpyWbYqv&}JcO)T+_@Zj4%M!miwCtqZGDSEqV_DZhJJfz=+lj;(I#rR*n24_oJgV58Ej9MKdJDlEC<0jA)J!_B z3Jv6rM#8JZPFJbwj{IoCIRTy23kwsG0&&=V%WYh1U(hlJ%$e)iwzXQpU1^FNO^Pg6 zAw~dNzAr1@NMK&$%Qo9q-vG+LaoF|HL^cvd6dzrTWdgImXBJ*93+x7gpoI*Y*4M+Hc> z!g{Zl5T7wit#Zu`+y$Q7H;H zFuspY3b~7Xa8t66fhV1@67N$)XSK8j9b>ERAjJ5udN8mfG=^3m_tay5}jU&Y) zfX@*WUeJY8Hy;s}<#<&~M=Y37RkIigM0T0ISP!wtKPlo2p;xkuqUhw|+VOMFEH$l`Ie|2{k2*@R=>|_dd`LJU(6kB zd#mv7!20!IkVRNQh7HQlf?3C5!ArTvS4GBmwd7d0wu+n21d?t~c-r6+M$+lSvG{$C zb+ci)puK?;J8cL_mGv;8eGo`xFLH95zoqTxIaU4>U(Y27b)@9E*|QQScb}_45%D@7 zoYrQGN3d8-P$aWk1`J%Jhf9b;?Dan!P(iX=T+7`Yet>IK7jp1Y7g2^tD+ke{DvOad zD@)uhS@d3eSueh4$bMZ1x!OmTc~ijs0US||yG>RYyNOES=0SH^;MHj$adZ=({zj^3 zD(Cjg}W#^Z?J%E&j|+3xxDxuGY?Ye>U!E_{Fzr^0HC1gCiu-WzBe*&xmu+~W>52;6S2 z4`nQLF>NWKGoq?{<1$Y!V>F%LBYnOVLNZ}Gk}TTdewp>= zPsXh%myq)<6dUdi(5`=ekew(M35(AMKWHy??OfWf!CVvB*3b84CR&;^qcWYJqRrC{ z{wHR&Z`XXI?(pK?lOAu;7O;q_&IkbQ$eg?%3#3UOxQ8Q36>yK1-=@dmkR9qY+pUWd}T`Qq;6ITgd?l11*_Sl6u}$^@&`vc~;>-c&l{&jLCTIi?W2E zelZ-|kn=Oig}9QD?(_MbTC0~M6Rm?}zo}zJAbl(9ov}U?j^fO*$g+&^O{oMtqIIf> z$x7gEo0vKha;Hju<5;|Jjm7nbjjVRFX!&#sXnyEKW6ZmnVV#g8h`F@F#tuG!ad9jP zbGzOhEFe}aV$3j|NOE{)XWxsLN53+dv3+bH73*I)0?(9V{c$~Tj0cswi;=w5w0%nD zfZvDox|>w7(7>hj@bw3bP2^9=`H&$2c}VYuzJN?Gjng{Zp1?6<^UGLuk`YR%^3}8n zQdhQorg|@?$d6uP%-6Gm^#|W&g0-=4^kzw_-$n17;zEaaO`6Z{Q`bHLLML%c9mZ^W zcufR8I~{!FzpnA*1d!}srGt|BISLSGwu;_({fwKTKUl3}qXrPA%Yt?{|=uo)^Zk5FftjSULnaa@w0xs4;{X4=w>6C25OX zR&|j~Mq(I=zMswj{Ps@zw`;-0sVwp1MtQ&LIv}-i%;i=GKgPPRO#xTWQuCC}xk<%G z<#q&0k&_;Pu6BkbExcoIc5+XXD%6MhZmkD{)?lT_7=sL0Qrc6$e}-w>@YyBLJ598c zNk_?@gy@}SKfcNd!>f;bXmdkHD`G<>jn z&6;InR25T8Ag>NRT~T!Vw87?%cr#SDvrWxf0%2-_SifnI|KBlz9O_pd$dAK zXK0p5cdomKkfSl#BU4m*$ld7a3^@e9+q}NffAKP*x-uRi15wu#o7~?|`;Wr?WJ@~y zG4YqAi`B}Wv`BQdX9=@eBwH=EET$y??X_ArUkzST^G^Q@jUA@NNSzaWU)52xhH;rA z?fTSnxk&bvqlkbYw#4VgH<`-=KetV+bQeQRbvh_32psI>jfIN&UqAj{lAV?jIh6-7}zY%xva&%s~^QBc6dL0P0Xt)SXRo zNIq?X5i6I|EIl_C9hLgU%WxN;J`vmJOw3D!=!~*^UjdzCTFXB_Xih$8FQAnhEyH2# z<0n(8xo$tWu8!6PacMqEAjH<_66dGC`~^*a=14!wj#2c|s!R@gA1=!-g8B{9pu|cc z^*IIY(DOnqMe+Th%ulC0=<$15UyAhGyak_hlDuAS)a*#3fxX>K@Zku#t3uqM8PnaT z4%W^e(@rtuO4QwXdr~bkA4socY@Bi8Xn4wcgvA!3!(iQQT^IPFx9ubBlN+B5G~LM< zHFnhGdpja@zR1zZj#oVHvF*M~<9qH; zEr}Ta1-%5d(G>#L)dj=I!A~W$DYY^?V|4VES6by4_W@Fx?R!ht+o~m#6Eh6C>ZH$c7jY4?r z_iDMKdASUDjfqVe4@&v@1nyxNFg;d4`-U*a!!u@ar2r(K(X1`k%B(qc7>^5VXn3@> zO(^J{HSQ~vx-ywbF^OxpPisJh6&&{1)!y;7IJ@WF&D-<6l$Yc2vLZ;68MM&<3hE`J zu|Vag{NwJySQ2M;<=IPPJ90ieBwHdE(xPc#QN09#Q*Jb%QK;&}x9f<=c=`e~rmmFv z23PzJesskS&7I1S+AlIoA4 zjtN(Fzv|=X2~-7hfh=Sh91&kSfTyqimKQLYI)iZ zFMrGw7XUd}$)j6Er-tXS2$}CH*)O{r;$nAm`qKSvuKt#g_*CFGo$f7)m>R(5Fpw1; zgX?zgjzWGUOl@(h$sa?AF#~%ng(9g}0X=MLn7ZobLhq=a$M<{HM?0$90*|CdqmBtr z4f8!{3m8}Y;UTNM`L%>Vj{9eX+mHS+P7p{Ix1I#E@yfvU61(ns^kJ~UO!wBv0eFml zNlWE?|7he61)TnQN*#)aS&QiUNoE%#Z;POGW@YNBS5l4`dZT3wF7U2a3G~99QdkXY z(UJ~fPAGu!h~H@BoPqd~%jzqZZ~u*pTXygTFW}lCnlp38AXQRPN8`{9qCeijR{9 zpR(^fyehCk=AHY!c>Xmb;&Zj#c=twetx3EQh*5oC5n*>_x?i>`{+AJ38zlLrViKBd zcv)MIrri~z9I=1WZVtjUCnvph-e!?F41CIyva!1A4hB)sETqlz^GQ^XWn{_$&t;~Z zn0Z#jpSmQf&|({xlMZT5EzBys@vUV#1Qjh%1kG|3K{M`@`o=to8`% zd4?Ljv(nmd&Zs}oXA9~5p_?qxgjdkmVx#;xk8pAZma{E}r2zo=dMjJ)Sgw)FowmQG3Z}FGz_$EAA(738{8UDS4*@?QIMCfU| zI3bTjFd5b2=w!n;tp^qcJnw~^{y;6hA+AclhAlXIu89efV(_Psx9oCq6%IT3JT&J( zq4;v|uQvK)WP)D9WjE0p+y#*P2vl256Gf^X~T4dNBM^cX_Ws206K!+05UB&HIireaq)~2ky z8^_0QP%Ok+7k7On_(KUJE_`q4QgFqteZk|;WK3R;Fg7u^wL^T+H2{GJ(8PS%vLkZe ziLN51s|&4JA-fQA99+mAB$rn#Iu;0>8R!Dp!VRPdv1TuA4n_FcuDZmP)VM?EK+`?V zR*=h-T$>mcbld(`%yhL+nXC83La?XKJ3-T<*{~N#fO=@r$Rj z2}Kp8&;D~C1+TalGg0eAF0ttFOZb_*PyXZo32RWvP8zaE{{4VAV9+Rghklbho zvIWWvlc>6l8`*$g@C+l#>=7#lf8x7%vV?8#~D3Bf850_NHjo)H%R<7?C0eJ_CfQ~dHiqc9aiPj*v$UMgyL^U zi&cuwZg1oM8bkGEg&s-(kHmuu_-{7~eS;z$H=xE!mpa`oZ3Ge6aX9242WsFWoH2gs5Rc7XNX7-BsFoN7N)QhYh;C@-j2= zwW3|^xY5z)?Nf}Sh3b>X0R5l^rv5C^H>i-%iJ*?^XAtMt-zyaIfS9jlhg0<~qRxGs zVjkfY+uO6-TQlc9nQd;bX7d6zDT+%@UmVC0FFX3pX5YbIVl6xb8*XtRNDv^LpEyrt^>d(&H6<@ z^GhO%qCcWK>7#p#U`aDJ6sk@At3T|X%fCzt^yh^C@eCorR9#7pTv{^~t?U(hIXU$T z-1JX2&j8jxk>l>mb{pn2;`7b4XIxN|+Nq8m(2+owMUX(>Y~o8);i`wN+@RkXE3kV$ zm?e0Cz50T8;|R?41WKFjRZS(?CJ~JDj5?{qqvpGJYMDDcMx;mNctjynr(knX{W+}a!uy4Y?&Bc(IwBLJZvBZE6 z*-)rp2A5rANjX&98(sI6UBmu9Ur@B!d( zwtMj?9?0dY_Fu}=+3%bk+38T3Av_Vcv|Wq17u&L!bHKQE# z*M<&TC2%k}&3PSCHN?ze+ReqBU_J3~QbI*2o|_hmQ$ddbzM39vrR4;f^-LLF!R~t~ z8{cZN-fn9+h52vp^j`uO@d4UeHMF6@!!_)mINm{f&ub>;Ky39irFwJA&elJTR;dAY z)mJS;_CpCQ!K}x*XwFJ>Mn`;)hKLh%h^6i|Jd52YICQ=n_QFw%=(#JL-STB1AwOc8 z49Ab%HG9=753kX|9J3D3SQ&Yw{mbp$;3D;$^z(~|yX9|L%j9%`-$2q>{de8TEaZK{ zC!=fnf21yX2=;_B+JE=&u0D^RBXJ|v_xA}~@TU8-hr9QoqpM@g56%}DOt~E~L;TN} zM|InRmnn&#=B1U3X@k+A{_!>@T(DWu7vwZk`vAkf*4P?fCFsrWKgcD&R2|P^ z;&kB08K}=WDV~iB?NN&kz|+tqZp>aJHnUu2qd$R3J^MWusxUcXx(4}FkHR2ZB^ipF z%fDN__AR0|Yf*`Fy$8*)0mNaa7Wza|VK`bHs@Y;}`pK_`l;ky+!cAWPzsT|xsn0etfb3~({xI`sQ>$QBRk@p=uqY?XoPdTe zM3G*CYrPIKcV32es7t#2Cr)PF8{PjqzBHkwSnv-Q;00?sY0v`cKXUI6tM333t5{cg zN9vO<_f;%-OTEhsM`rKO-+cTgnpdJ&y9^JSFPZous?7k@VD*#M86s{578l8rSi##=Ocx}pzk1!9?|ezV zrI%Z7r0NuZVhY*{@QwbQQjId8O8#9dN@1czl#aLvMQd`(a?6yj&|eenZUMfXK`)5( zQHQnc0oB{zvd_ziPtUs?NF$ie7^U-l0qzGsNfEu|lMp#xQ!@&H-V-u>`0lp4uy_E6 zh)&4YJ!ch+xqFzAjd>s()gB@kXjqS8JDhLwRI6Q=6i?a8`bvBeeR@zkjyE{qr^I$_ zepTz*3x9%j=(KJ(u&o(|F6Y+5@nefyEbcA&I`De6zi%LGK-P3>=ZGcTfv=zlS+wuH0UC0YPLt_aR+v{j$;D*LozWg(R0AEHP6H%Gi#T@82O1G^;`EDFF#S6>Z| zr;@38j`7ve73PSZsEVY;o{F?hV;qGYG=2BC~`JhHP=8g>{rwtq% zTe7gh^OTh!j))la{k^mZl3=Z*A}X6%11%IiRBSc zkDcwBcx4;E6zi+q9u_k&AZZJaK$s)&9-$N4D}z4_UrNP{g6rX|2yA{o|+J+yOV?YFlKy+RTv zr&*0zgIYBRD%?byp!V%(EB(N5&aP>C{iF%7$p-IucuNt#_#sNSz2<4FY0K!0lz}2$ zDS^C{uGH~KWQ_xY$j>fgFLy(!3ou~Vc6}>1?~Bp;bUa3{W{>7H2f_YSQAdZD24PRG zCcOr;LD$1j1(NNof9|k_3D2H-MioG)Yj;J*{g4MZsuR8}n5ew6PZCMX&!{189Mv?G zRLMgQt$6XG$0N*gs$*50M@M}Huko{yRgN!00`)CxS1zcDDcW# zG;)d~-oBI7^rA(O?iD|zI}R5fQdnsDl~zp7i#l61^q=}S*3v(*>VTj^X)+E_KjV0G zRbja5)f$xzKis6_hMM!V<=C$uuk#hm*EdRXYqNdVD2+MR6WYiOV(4WGTGh@S+S9wp zXC{uo@0?T%SPh{B5W^npHWw_MT`uy0i6em)GnZV*7e5WyS487s@Y$X)nhNmn#w! z-Y|(?0OL5Dh#&fNTorF)9j#H!2Vffz;0y)Qsa680+E)6>hi z_GD|RPt(&PV+ZvHr}Ux}NaU&k=|qP4{K8INwun6s}Xejq`^Uglig`aa_ce5FX3CNMqVkPUn!-=4hDw_iwr> zF$4tO69-^`=X3^eAl-^s&>{iZvn8WazdpX+)=Wq-HUXMyK{|3)8XpUi%6K+BbR(Ew zK8f|O0^hrU<)Vr22TreR`xv7=w}#_VSiji?9FcSV8ecZWCNNrj+E6SL3_;q7rS9tc zlwc~wYDh}O^%U~g1fmtJhblm8VV}QWoT={#o*KKR3c*v=h zaf^ttP+HFxqq$>|^06|{>O+VVhR5pTiP2`xwn>`*K&VFyA7(v5rL)r|8uGI{9Pk9S z#{H@8S3LB8SmkLt@1NX})Wr>MYPisANgb%(v;x+QTjY9=B|1pvx*IM!@B%(;e$VN? zCpI|#OPrST|ALdD$MWBo!-w5>kGNV6g4Y(D`D?jNZ?G=6Zrart797!m8^L(<3{%So z%<_pxtdUfuLK|T-A%iWy-kCv5Si^aMK~eX(JQb8`^gitFOWdmTe(8J#HSv?g_NNP< zr+cV53dl8LG3U(X3fy`)kimuY+r-5S7Ta633bb=pX!|SlqdxO(j#W`RLlcTK_5z)M zDB$-0Gz$!_P55taeVX_o-8hymdds#wuTq06G-_Tp>%Xgbq>>IiGB+G-h3FR`dnt=K z**=mbpEiAdfZyC#zLJ;H%TrJZz0H)EKLNZQ!jKN>L^pL|$8b7-zvz%?ve3q$2EY0m|0YjV##coi;*l>KF@;dIoZUS%?aJqJMN9#HG!U1};U>tCWA@OX%0% zJr!&@-@BqWq2s06vxkP?t%A|{kDf4D9nXQ;enZN>8jO)t!lMUX9ga+Pg61A{q2!-r zp`E|EO+c%$w$lEQlrc*zJa5LG27nBAmhdrAdd6OTWlQh$27cO6LBOa#jGFmZ1sNpz z6$|G)aHDX@8&cRq&s1#nT0-r1W44axauj^gf5T`0WwXQvJ1&yLH+nb#bmChAKBdZGY5y^N+0_p3<$Ooezn3 z(OG#u)b`@Em21WxEetbeVA%|O@%|=&&ah$^buk~dUn!#lIOVSB>3IG`#jH1&_&wu0 z2j@zY%-Sg->|fgWDTMHH>U#GN#pzNAYgB-#b1hPPK{Ly4hW>Oj_v%by8W|-Uo0}Z` z%GhD_D;RQOPO2Jrc|N|YoT0CSq;m!IlEEKDac4@_9+f865>q-q8YDxSBh%>1KWwf^ zhw28o;@)u@a5H^+*OSp?3w0%-8|MgZ4!&4}|68vm`QT3}b>mc>&8#wXYGF#mVVeKb zy#;jAX40?S?nYap8;90z)aLD4f z&`|XE@4pXNM3{N3ieM5NZXf<$+&{dn|DEEL5$xhKyT8$L@{o)@VD5Kze3Z6ECDZc z2ZvMczk4(U3_(A)L4dq0C}N&tG@GzNJSxJwPVmy^w%gNZ#^mI;#)1=BwUe6^(uLXC zc4^&&17GSFL&~GMSMp(5CeQK1nyaonWEZG4&dyh09^9Za;n8@)}PJ>h}*s@sHCyrBA?reD|6^RL;|gyxARyCcs>V?Hl|oMx0zUe9Q{esY?LhwutN*&hdo0^9n0RIYN<*i9 z-YartHhkY|(^&3Eq6gld-(I^4)FhtkP&{;hK+SIZydI!3j%ZFMQ<`&k*;dndzZ;PC zJO@R7oEkK_&9JG7hS>ajq}#(wrz-|C(1dM1C+K(}q(R~1hgIgxtB3DYNi~~q178*0 z`g(HDeDNDZ}~Fr+Kgn2G0;$%Rh#&^9q{}%qd7+e~l<}sMFv) znJcfhUE+vsfuGF3<0`Dc1;&LPPR`#hO9KAsL;TMJz4xfhlRW!i9K7mE_|LsoXb9km zR>YE8G0gVVOn6Q++v@y@ZH>@+&2>S2K*?^%g3E#nx~oMZ?e|VNg;g<<-cWcZQo7C1 z9vjPzEyCNq?O6XLE27|-@jVD@U>A_Sh3Y;>?MA%_j=^g`CrkE`vrW%5+| zfJY6rZ&E6oI@Po${v9BUI)vXisk)=<_8|BpB$SQLw$YyoRo054kG6W z*noA}qu?G!aM9#XZK-#raxz2tsB>vVQt|CDf0`eA;|Ib-p8-{JbSg{C?8Hn`jx3Ao ziEJ3JNYIQ&dWc@nV6fk}YPv(G>{T|n^iui>mAGb(1ciTFDdPW`%t=)+5l^R5A(*&F zG<#skj8mc|Eko0S=&=qP5OPw9(s425SGpQ;Q_pgk_{zikms!rUcR-I2m~u zJX92((N#{@V~D=zMyLV_yoRS+A`3@-mVBEhZQgr+!>KRZ!B42icA>xgxooL9+d)U8 zPgsR6VS#_+Kri*7tK)o3^mb=|6ZMOOwW#>ivX7Z-;nN1qhKV45+@LVD+OsV-`e5=q zDET+!tVf;rx%vAVD{i3X4GK;8^78r0nr6@`^Kum1*Wk+*m0@A>a`{*a89m_8;W5i1HIUuIOZ&MoiU4gjb#6JjbXx&C4wGkL9?&}y zc58iWK0mnUc^dbRV*RhL6xqG9J#Axa${|i2YE75G-}ezdY%K!Qr&Hm+H!$MLm{(n< zR~vvTSWU%Wl%gH@axpPkgJ$i$Kjn$;_sxyqV;tmATfSv?Mh_mz)}sj*wn{iRwnmw` zn2$Fdtn%0z$docrRqC68C-2MV4@J|`QQkUpI)Rtm)fvG-^;mH|1~!&i$GJm6p<8c! zSF+NzPFu|{Xg=eU8{TK6p+ruZ8u84(7A~}FGtC6Man<;!n*o#lKv*|m6JV==v+NdD zZ*M}Z6>D0lY!MIQJ4aqsX zS3eGd7HtrX3)j3_KxF@1M zB=?}s)2M8+`vUZLJ440F_|TEEJshMCK8D7W4L8S8O_n@MKv>IYqf4g0Lv315kx#tKdX&x&f0$2x=phZxho{d)PIRkdyA^Gyk(qu;UHheX( z;H{g`>6eGSHioPx#+)QxX^_G2-4ZZc;FxOMO^Ma})_S#8QykT{p15%1!wE7^mRwdVtNJNIL-&P3@4gkWOk?KFE~i zHLjEj*$7g_!G{)yS9wKcy@}l4e<)OcA0iyplED^`rLdHh+`}~y6b$Ld>M*VoH4=KL zCTJg3(&edy%>x`}&7HP6fZ0^q26h zGFQWBh|+JbozfAx9UQx^RLFTev>NkgOLTn;{$skI$=ACd%i_`ZB~!mdxnzOr?3=)P z)j5x-?*=XF7S95kjUg@_%%&5e^jq)B#7%OxaJv<%%=+H-`>AJNqVlKej9tnj!}Eg% z*%e#eX(yXf-|{!6^F}?W99G7R1YGC+c#L}V`CrW|PKxDV2iGE?4*m3`@iw4x-d3Ub z*Ik0FR`F6Hxf?*}#=CF~Z#Ljnh&EdOb+0w(f>;F1J4-Vi0B7ey&2xzZH76-vm`%?O zF-%za@ufQg=FGfO!>DPe)FgOQ@DrzCqc?NQRvt#~L>F9|pe?HwOV%Hq!5I#c(kt4> zdzv@v$OHsN^xhNuMWvWW7~K!q_ooys{r;bG-`!hXK0?`demPVpw``H1yN1l(t^RUc z7<-2zjVdzaRL(T4;31{4>(BL?)suR6tNEV@VQh`cth53n0Z+i&j_b~jvYzF+LpF1# zWrX!!U-|Nl`+e2`u8tTQ8A=I#*&}&zx6EFnFlFRtKi*^Km1CNlkD`&g1>k)!cL)dP z*Zaa5?}NC<$lSVsTnHpNS~xo`*~Ult==@gW3kB-f6GN=wW9KLXPeyvWa41`gQD{rf zSi}4hDG4P|U^;F4<7z!YKWa)d=*fkzPB11gX7sax(ywlcuhft}>YjHd?gJ9Q^DIqW zW0+;W(SoH)$%QM;sNAJD{al0ZB@(PT0#Iy58Xx6VaT`MVMrw@F-v0?=O^TYZSG8#` zZiw-}CyCaA*9Z`@pFKaRYkTMZrZ!_J(Z^&^aEz5oz$Uus5&Uk(z~$#q*&o>of?H*D z@iDrqY|mT28ofMefbMi^TH;L9Gg;$67E-cpSPkm$ zQz~g;Q4m+5{BkVo$5i+xkReF?v7d5p)|ynf3|C}+A#OS6OgT`p%!SL;UG?M`wd9$@UVVwxD1|t1VFtY6&gy%#=HA_;?ae{oI z&i9KKm%aCyPro>!sRddD19`21lv}g|sjQoOT0wWFOZTgvhU>G{@-O{B{_|?JsvrI) zi#v3s0=Lihiz!WZOo)PM1}PVm-SA3gqMn0p>*~N5q7eCS(H;8f3!+$B2^~Sy-QBIf zH-|~9toTbYSA#Gf`nLyK4#kk(2&vfG9!+sa!4VkNXl>X70*~+01}^#$+o)<_LvRj?TafytYy79_+4K1~=Y=Rvc=K zPL!EaAB(jpu{6dq*FkB}xuAw&&j?K{%L~$b<*AKm9z!zMon@(HH&ut0OG-wPT?m{* z8>3h^C%jSD5%5(@%@1fAd2NWE%qXE}HJKsVzxmZWMiH@@+gxwfn(&Y1wA z%@)CJZ-0(GvvV;vp zJw-nBnhD@eCs9A5&Q;;tK(BFo{d?iY?5TY~!{FmiOck`>#Mt0YdVE}APOL|4KfPHS zXy}!}xR57SK*zLdtd8wLItlj}8eW}(3$(}2R$oX+2y`m_6V8G@hm|HYwA<>SgQm*u zxO4~!JcxICn}m%Pkyyc##-4FW#$l=+DTNxVm z;i-&Tc;=Fj-ycb5y25odC+KQ_YIT_neVjfKchT*s3E!X)@WDgDBYKA5+j97`Y5z2F zK9@FPhyUgiZ1Emocu%heMt_h{>SRZrZZ}c&Y1OMt({skGA9!(#D6a)F9ZbslhKa`I z{m0}>&SYvV$(HJ*_0^#s`mQG(e`L78)Mid!gM!n>Pq-Qfd*2+Tt!d|tx6};S@&N|0 zIpCb(eW{#%6LZ~ao+SL)2O&@gT3=%(xb9#)HS>RhHS#*bj69=b5ufC8yyOLqod6uvOnKt z*=K=u6BbP#x2-pjEs3wmHbx?T| z(7}Mx{5UXU^E{)vngJ>~xw^XTG3;bgV0Q1%H81UG#8g3!W6qe;{?5F2TIkFYUM7d;qm@_6#{))2C+Ah!}NEji| z9@w6>i+*0#gF+=s1*`cRQFCN8uZ}7D0DxDJZG3RLFCcLYuUJ zF4KO~K+DDDP*!MhA9BZ#A$Zj6hHJd&jlV54JDjOM zz+>nd02A-2e_e}FZAj%{e27?u$`m{-e5bigr$x;~;4Aj|^l0+N!dVP@OI(0O-)=72 zFCBi3>ZfRwyosTwCY85V!U+k_^;pRI&a$4y(X54e550D8IMRUmRVJw%O+-PfF&`~K zbUR$bL4LYKcrmFkrPu2ogV9+;9@v;(#ZkTk*J>b5=MOS>Y(nQO7lRl$nBAaz>bswQ zJD%!_Qg^t>hAjAY&q;h66S)V zOP_@7W>-5oC8X%4FT48Ovs8TQE4RREZ`|xL=e*2K%S`)sn%6nHnga>L=+XGXML6k!Hhxv*rCKvK@@00`Ao z%9nq*0Kp&$!n4bOl@ea4l*F;&=ja97U+#<~(y2wp67jQHj{lf_|5t5c%dVaG)7j+F z(NQP1oN6sfg3$dLz4s|i`yNiD4j@g|g-CK)$xZde9E( zT^?r1mu9|y*u}nNhnY}S7qUa^{M6mWxC%`L%m(H5{RRxHo!RI(Dd{!(dE5ORLdS2T zCJ3*O2Nd*}CJQG#+mG;ibMmAG+rBoL?C?7sEp}z^i6?r}AaPlrqN4Vu5A0=x%s%c3 zI`zNt5rD-Xr~V;C)bcDjC7r|meArc1A{h`D=hW;tSB}hX`DW)1tf2DSE=5QBGbqh}@yl*fJYY)j(jMRy|{3O>TQYyDR> zdIosP!M35v8%23#WQ?uZylBtIfleN(RVwxu8<<&HSxf#J(QtvD-L?ho?23rSj3!$J zp0A=l7+kIb<4v^+=a!@33LcS{T&Hzvv_G>n*hyeN1IAtPVa;n0Z9gnUdScP?z$f?= z_RYT^&CZgD@G~_)U#ZZB*BG{^y2%(BOx18~{>GNUYC`^?{-)xgwh;7rn#OXht`Byv z;YqqRLUx9I%4*pRuKryx-W11oR16!%C&eXAMkd>BpYByImWm~uQRaFa~#&8Y; zF|A{54Ru5Y+UcK@k!rxi7?%9eJ-cpY`T(xtH`h2>W7dSF5je1fPK}?c+J%{<6uOUu zaz68?I(uO!ii>rw21Go~AYY+ksT0F6KV^^Vw$;>i0_F=ty5OWK;oF~|LtvcqWu%l5 z_z4q=x*B?cSJ@po)DB{A5OzI^k^{tbvk0Y$LciN2s z?vV63Kh4H-FeYVj3=%pykAw%rWS8+^7#v}bX7R@LrKW!s^Yt=a_6x?KRav1oA?!(( z*J547F}hPidf(Hpj>kfPj7z+FbTR2O+t$R27^4Su(t<`ZxND&NS!hOHY&evohmJ1N2=Mk! zKM&$yi;v7xEN7 z?{>l;;G@@cDqVi>*x}X4&rGo{c=R^cR#a>CKgc#|2jlY5e`DU|&h5K_D?fhi|sqD$)jB7cbfb?W=7E1Adu zm#m+C&Iw$2OFU2XE;zbCQU|HXLg{Y`ZYJv0O6HBEd~mHc>a+{x)78f3Tf{ za3A{b%RaTFW!G26xYFvSt^0sX!IgA!HU$(rlOJL;2&If*klj-O7C$_XmGfO#Ke#(` zx?o=y%@`46JReAW278h>jWOA{SEm}!bGvW|bK^_YA)gajZqCS&hsewpm|jT6I%p4F zpc;TBCU3;3+kr^@XKydtn2%{>gwH6EJJevhD=a-vR(qij2+K& z6^SsoduCWHJMn))5Lhei7h1MsQSxb~qE><~?_8x7sQlFuMtQT{_>uEVc(b=LboaR2 zS&_sY){;kpOv~*(?~;C0=73#Nl(`yJw=;NyBTlXuOAF)7^8Bo;vF|bM=Q|nc<#ruN zANTx`ADt+ps46z=X?e4?E|f})zh;lN;?|Jp1!xBrT*4GqfU|RvOjxL$s0w`GSLpS= zftbAx@}HKq+9>(E9>rNLmKpjPV|!D3vErh|inVwA*it`QFVc9AG)c~IUEW>z_XEh` z_)+tp;y%kBf>Crz;8dnrS5zXxDZ)w3w8U*6Vtj)U*!;Wj{gK<`qj~XY1=-L2uS+o9 zJ8t*wI}2P{2)MV66rY_K=2(IqdKh>LL7!p+n;ZM)I^E;F{MwB&OvKs`^@vkic=O@M z;&7+E1nBwVa&ODb86JBNBUpRZv_l=Z%76_HB>l{~ogRmsBMm%^)HemUyH6egSDqvK z`>BST?#j%qh^)1v$RstYZ!!v(j zQ&m`3fx24oHOds=va>QipQ6lS_KQM7VU5 zijWyw2@$0?gSnB(EWel#na5<2rqRPlIw=N-ne-g z`N?Y09fV68*?B9r2LwLzCYO#f4X(*L-H$y84W?gWg!hwXqpz2co39oEe=lkJ8%$<0 z+`tH0uIWURJxZ{9%h~w9ji!D@d-MJh?7s11O0)t`kY=h-5UVwtD~^npww{7;A79~CsJM(AA_Pa6QE z5LV!csVY#4(4D65Y&B(yX?J-rz6t?PS%7(20fCjqy; z>FG)v58n!2%Zb{fToxZEbY!JxkJ3v`9Ha%WT(9K@w9#TSTV4Pi*^YSPdc08gQaht+ zI93hyB>rX|Kso;nDwdX(KjYZ{@#M&!u_NwVZJ{w2CZjfH#>h=CyukIfPsW5L1qH=7 zHnSm$JKrd5M(^?)2km0zf)&?)RXbGlg`yBZzk{3uNfMb2p5(&L-)ZvlHdD0Q1&}{P z_}wJpx`oHsO;%n2qE)lf;$O9h>?d#LzF9xK{I#i)LfItYxHntxsq>s~b7G7fXE#y- z?#R__O|rA={bsQ3ZHt~c6Yy2yc>B$xYg*bL!p`b2|B!c+!u9k4$9od(jcj~&+;h)U zxS_F6*&!LvRA2K=%g4V4_4p`J1G9P;ewoFbm+_?-tBlrM>0dBc9qpyX-G=r~uHUvH zp9fsMnfb+1z7m+PR8yR=O&{ym6x5R^Z76}P!?&H^yQhjgPvR_mkF&N@tuTPj5uB(e zIxkoWqtRXwK8BO4nhL=&84?~?t2;s|^i4WXZFw3TeY(#{DDwtr{ZUZ~INyvKgx$&X zC2Ecef*WyyQtfO?GgN+Ep!J%b?<~aYsHW9qrPWOu!Z0AfW30^rqGEPyiW{DTU4Rhr zhCq1GFl!|Fq0YLSkZf7g3LS8@8H98oiVm{TPkfLNHiyPzY1UZ?d^?|dJIW_ zxRi@#00(lZiTBELKKCl}UEd7p?VgrS^b*wtQCP77y3}kEKXYg(WUWmed#;!S!xp#t zNnZD&fBg?(`@dg2JB4ofLZ*a0&>cuD1P9~ujMg#{IzWXIx0GXY?I3e(V!?q4&9hj( z?k<(8xukP)4c&;`mlRkYIjp(u+W594L#m^5H90zLRq}4kVp=Ar4@;dnw>SwT1aC8x z#nYMPI?`bq;!tV{m|}{BjcN30HmN11I10TUm8n0p%~}eP@4-0(pWA%V>B{UyRN-jU z$tKcFfIMxnDVPmIS-I=LVsh&6s?e%mR$SPE+mP&(3d5KR(Xb2O+gs`MW`b<569nYO zWP*Y5g{V8r8zn;N7&FNjj-|t{zf+LqzR(opX^z0c(G!}+@3r&4^O?g*M8I7hu%CR| zuW=(XtOc~)-U^pA7T1rPRKBAKxzt)U#lm76w4Q|Lvmb?yaU%8hS!MUX-}-Owed{lW z7J`mk$zI|)B))~ZMJsqx6B>%EiOUuhvE3Nk#s4pF^w+s~0%3yjc?asmy z3EdJJNpO~Rl*TfiAujKRS*d2O^1$_}jf(=c3;(tD^abUhP=)kq5YOAxEZ_5w`u@o% zJI0jkiO?8S`aiV2byS>5_br?RNeC7oSg;B1?wSPm0KwfuaCb;>cehT^;O-vW8g~mG z-05zlxeu9l=9_tccYSxQyVk8g=d`;r_o z9w2)a=EYUUn0Thv(+>ND9IYW)eaz6!);IBaz~skg^x{jfs!qmYL2SS!Q>D`F$2~#AiHJ2YV-(A0)arNP}u1S$c#s5OAO+sHt?Tva|sBBP}Y%$N{&anF%e8avI4^F3zUP@xKWQmS6HJEz2~-6{08PrS-~Kn7mP z(3J}+IB`!Cm>;T>RZm&4X1>806CEB$AdcjUWmb_mV2fR$L7>)t#uI;oqrqpr1RE=l zJ7gDewHl~l5GQE4F!r%L!}U)?&zZ>2+H^%!@gQSQDanYCkslaLw2#Um3RhHPPh})t zsEfC&dLdb4^Mi2meW3>%u{rZ*_c(_})`Ia%0Y7b4FLmre`IL^G=n)!h8m^r#K}A2GzM6I>_W zllBi&@xNM&V+O5KGkw-%K6~Z;lUMThAx_jC|Ai2)eDOAMlEdbf^V%1}7p`U2cN*I^ zoFZ?~>>d9M^@X{7bn{_Zpgl#@E~w73kN3rzxI%gGsKMH8@8v-xTMTC@ei=$xg;9qU z_ZKEVZ7l9}I$f_>>mRnlPLJ98QrWz?edA+iRBu_0J6f%9!+1+gAMzzda3gEx9ak>#ArK5j?h5W(oor&+c`sPVB#JD5wHQM6Y>$~t=x4pzP z_NPiY2DVMiq;J|U^9b}7m^ufB>J>JM;^vX(zPD(@C-|kV zbCIoGB#sRP6CCeN=$HelnA%4sC*w(lJjQA*)gL`Dq!#@axGE3%UC#brqX-PWcm~6T zu}SOY6lgleFL)dK!*KlKjauc$E@|R$Of!>exg}|9=WLT`B~HytERh;!xfO9$+WnnS z(QZBro#DO?ccwzE`Si+-wr^UylT&n=kqK9Jp0gO)q{83mNE#h-JGd?BONsIg=XiAK zb}sGCN)qEIh4TywgmOL0d5=vYKYEzc7$ikCn@=C9$G^-~-#?@Dm%NFLM-ca?UlX>( zSRP6+R~#{d@}^hn-DHYZDq4_Mr+=Y3Kl4mv-;~Dfsk{u=Xxl;FC5kAJReJg;LRg+~ z#gWvsS&^JpkrwxfY|O}rTz8MCRl8D@1?pl96L@n6-;N>RF-gATYe|~z`hh@_n92bu z4=}CN%{S}R59a8lRh$2Zl!3un-c|}JBi(FxEbjSXpdfJ;dj3Y8k43_SLQ;UiQOS4ZY) zwY>@{@+DcHA36t=d)Uu-5N-3>_i*iD|DrzWyXI;SSr@;XNF#8QW`s6zC|f84DPg#B z?eL9>+X50noN`Ui9}5ETZkBXlOE==2EhjCV$;R{L@Oq+h$o!==ECEq>$in5gF>D%d zC~CKL{!|Jy0Gq2vQmx{r-xHN{ zf!?y)v?~Z5_%9r~fjOAWa-ZK7Gs_&rlENx z*XAuSTc+#z%|}O9m+t-74u%N1hyE(@K4~cVq@P>LIF{x^|KQceCQBc|+iBa8hhJV^dT;uY zx%?V?jX}bH;nn%z$^LFFuYc=U{PQ|vdC1!~S9iF~!5O@e%cEuO|B@aoj|Fg0_crST1qTl!?mlU?#9I;adW1es#8@Vdmp6{wnpwt|KjU)82$Yk) zA8H_%cDYivD*T_c7k~9O)-!`{wiK0W$EznO))1-9Ng37a*z$~V7UY+QG0J?0b#6PU)C{X)Lya z_do9L?{2uGM+k$)+F`uH1aKh)^IF5*g54u(SZ{^r(i^o%e(bMu55i^c4D%ba z&N$}n3h&}P=V|L07_DN``Omjmea#i0<3=&aZ{Z10b8f_wI?j{CX5BU_SD%l?m!cI~ zp0~tiB1`Iv%J>ZMQqjk;rYS?|P*$hmMeS+4ggv^zob!#r2%=>UhJN zYxk6m^mO6|Y^$+c|6vthO4kIgS#fJ;+dSNnf3&mXb;r9WL*<7NjvSIpUX!mMatf5} zG*9?13+isr)zDx4=sgiA*BS+9&(7)2;U2zQO*%%4rN=0s$E+~7$hRIROs2{Y z-hPAlhSAq~=u0M_kiK<@&sgiBAkGlKQS!NEU9Yg)d{w;&>~O?npIBztvPJ7*M4rxz zBtTIO?5M35ObA$wqv{1SDKOU5?PwR{VT<(~jcK05C``y1q%yZi6|(Vot{f=`!vtgt zhT#ppm$V3FHf5sQM zoF=wn^e)jXvRQFdQd|d;@auERB;|S5$4l_|kwxQ*rR(_8WUH4lmXEA-?idn8lM<$w zb|J%IZVy8~YWDi}$7)8iTbht%Th40kq{;0^di~947V#c2Ft`|s@L8iyWdCKXI`n2( zoSAs}#}8YN>fXv{txX?#w!Tr<6(=`-;)o*`XSd>ZqcnzMjUT}C>F%zcvU1iSxRcD% zT)ca*xGMwz-v%Y}e&c<$>+HCajx}*#dovLYN~fqDdW)1D%F&Tc-b;ot^1$^m(!89lEK*#1;d@@LGo;10Rkc(M!e z#+NW37|NBtpUt;h_zMdV*U%~0v<-378az->UOV51*QeL=r9L++*eThyy8ZTY>+B_! zZ;5@$TuWrSgvWYnN0T{%w#_`-LGygW9Vtld9Ferbcte4-X{SI#xc--j&cpP&pBrVX zR6t&^eug{@-8}9j6Pc!Vr^Kj7Uzy8nG3~P($DrQ%FqO%g%5p9&V3BcnhQvHi>X5C< zuCsU(!>A%W$o)~Vo;y!^?OMMvhC<{VRv+9y?@Gfo!S~i~v*&@cA6qq>F@AtGg4SD_ zcE(p@q5uP?+}G9BLkMXoq~$qyRF@L9-|85Ru3L@6VviC;>ee$~Yh(EFyv|E#hjr!` zih>wzCKxt|lbJ z>toCM5;_DRo*+L{a~yeFK&BP5z4E;6yU=GLJ>1>d`X~1KOM^$?IhjE79GqTt5O0U>n9?ZA0_i@W}$Z*Z|I|W zp>iu_RMr#{!&w7U_M*F!O~iC%wgz$qXPf0*SsSmTQ3>%=R%%5ACR~2@DNb4%J}|Jl zn~M#3huhygst(53+}SOjbG#x2+pENtnou&>D(x#UkT++E>kxS;6@| z(UuXlV3u!GKV9%i-TKv9XtE$3y;Tp*q_dbZb@BZkag)L46i1ZI;s|~B%%rN@NsRm~ zA#)NCNnAC=(=VjkT8?I4U1)C}^M?dUgGhe8@bbXA z6Sy*4I`h_PFh{6nI4a{l$n7&j7!IXV2>k+*KLBNP6$xoAbIFM!j$yd7p1x5Hh8+#idwwm#Kt5 zh;aAJ5WZgSIPa=eJoEPe#MBlXEfP+~1E{wVA19Q)I&lJJAw;pY`6y{I|B?WS*QO{> zr$5zhFIYA5pXjoDaX+XDexgzCFpAvkzn>xCO4u%ja;mKMAV%9_nhn3|_DQRB2Ef3r zp*2V{%Jm`G^Wc$&kmq#Vp4 zHOL>6&FQjtR~%GdJ97_n`L<==96>}X-;1r7K{SL;c@&zHj5ZhYYUHk6ycuxr?lu;^ zg&!R6Kbzj*%iv+nc;i%i?0Y#ncQd}{`!?6=rP8Yu(sYX+tO#cXy}|oduf}7^>V)V_ zs7+JPO!j7i6NiA3oD&`f7Y$n0Y)(@-B>U9XxaoVBF3aiX@NHiwhV)lV?hk}Fv7_&* zv?A%2ZG<^^Y}ZPJc<3lRX$#D4Ud;{+LWJro?4uJU@^tm|z)U1$-b(2{sJ=!+y>}YL z+goE*TNyQaJ0FWn7_BaKV5Xq>*VBmCM=R2!!%Zpx3_iAA7N8e>)w>Zurs7akw=XXR zS*W3n`8n=SaYJRsHQ3d6PQ&h_>w1<1Fq5&a_`Wsgbsmp0k9{;jf66nMx?%DMtD>Cb zYjQHd8&ieM#$Y;owI|qg$AR3 ztTri;sg+wDa~&{pF^8w4*LhvAV1c09VTf7_m2UHTOZdm#S>JF}?+dmLfbXIVn=8>c z{5&uBA#xK91?BN@ivIZL0SY`)>INbs1i+xP`XRX=8TjT`wG)hQTF#i=`dJ9k$1_b- zC;s+BI-E=2Ql#EDp_gVo)RW;TXUkz^9J)5ztzpDAGJm!A#^2!oKrZP(wzO=7#iNNQ z#HJ~Z*$rF)0=6=+Ke7aw*V5enGX`P>=vVk_fhkJ z2uLN#cNIaRLTtCS?SnA&Y&6c4v*T)>WJ40$5Zq!zyNy|y2BFYSI;ul%jkUG6`L5Pt zsY|;jk%v*?vW)8mbfXpR))=7hJ|vjyNOTQjd}6Nf5pQz?&LR&JU)U^Avv4O!507cQ z6l80jHRx@9-@I^d=!T`9pio|P#w;AENG__eQ@;Q+O z(ZX)$=kdk&#OSG0qqXfdfBhixn%hIfdOR<&C*i1#$i&@v9?3VpW4vuh^+puX+1U8V z#8UnIt^q0$(Wu~}fd+6{r8QmhG^Q;NPfI-F`=jbzVszcjL9bUdu0Q76Ni2_V@y|;W zt)=!4BxY>18;_-)k+1V^&=(_fewAyJ%a!{HND||KE3tp-*ARBq>v*rdx;dFLy5@dH zDKChrBeWi0_XYvkw&5yHcu#fq%HYa3nM_fZSSFeuw(8vH5`jhKWhbMNsNdE2Yp&eJ z+-dO)kuo&0+0!b{toTiHr9dMo|BJ4$=}!g%!U4C;(dBp4_zqXTNBsEo+ZAQ8ii3;H z)+TP@akrzhI6M&E+6T(e< zTZc86h0mLv0z+{HS^LU*j_dUVYXL*>SBpK&Pp4^Lc|Dxm^KugFHv=VAMuy#wKcFk# zC2PQX%GJ7*t8k?!31Xz7bu}HN;x?A~5LE;-oJ^^USTUdyt=%(GK6)VPY+(~{wO#eL zA+~w(wD0c6Su>vU&S)?Qrqn2#PQ$vnLzUrX7_rMB*f4VV(|ol`U$ZlW&KGArG5N`3 zMK$?q`+GPllBSRkx1@E}=J2^l2J70Pe!v+ngEHGiv6o(4vmc+5%b*&qn3keY!f$({ zh$b|MvbH&{GRKG_l|B>P-z3j&Q<@`t8iqCxlty7ETBva_&kXhPTG&(6p;X*;)dV5I z+`uFg>faS_JhC$M0gCHZ`t#Y^Evx%)&-C8(4{!}@G@vBwOcyFqvmIR#5wBK+h$HM* z+;5Y+L^Ga$7k)GhO|p^=W|t;4Rn}IHo!uYrZPsoFq+KpuKzHRD{D)AN#p#ndBB_R)CIBw0;#LR{t>fT5K^&>%NIsf`N6EJeU(N z!c!oH-|3a*##X+=h(qp4rQ@BxqB1qNfEV*00UJ1b?`yW6Fn7yHRyvR=akT}0m2KAK zcg4WjnBKmj)+E0Q-!xd17<-#EqVWSPhE%9pAb6@%qQh4aCSrDxd-m-QZmUCCn|euA zVW=f5u8foMWY^})qNNo2HoJ`}tPGv?b=3wzalwKrw@ZFzr#mufGLXi88@g4a#cR<@ z@@Nr*mZ%%6`+VZO>x1s3>=%jYh%X>;X>Jy%zqcCcXx+1XL{)+dV_mgbSm5Z*jN#4K zH%80z9kZb5E&cnelHF9Y=vnl)VtQbo%w<&b%CqAS2_@q(^!AL1nX4mJ;y54mk0=jx zq!%xu^Ybb|nQu49BU9WvgBeZtC&=?~lCR2);7yKm!}eK)SJSgD_*G5>;~k) zYV{Pw_)X-3UT=ltON9g?jtq$bJ)dzlo04qfN_sSbO@-~}wHB#^KfCuDZJ+;7G}}P9KWajCf3S572+FDQk~CU z0cHk|EcBF5V;hlIUH2Japq0Oi#n@*xFYc8jnKb6B%qWasP`T<5;x0Xw_>8&+F*J0W zhp{f-P-J)zhf~R1zmpslrMwJGLZqStEe380s8yc2IDYE!A(j|(nK^a~ku6()c@Z}D zPcoX8BqE!vVYw`({NM85?)#b(Njb_%!d_gb6k$t6vW>$i_8cOcbNTxOxhT4E5zc$@ z)xP+3M^4{Pq7&UXIeVhRxSs6JnQ{5@?PU8d53_L@JRqZ1XzKiLHCkS5WIk7BwRBkL zMY8u<)l#z(61Cf-_L^m$&GE$8r$*-d*m>f+H22dv2#Ku6k=J(fXgw*{q7_sUc>eQv zA4nkD*OloEtRvh_BH!Xg zj8&g>u|3o{I{>=`&h`f3wDat_RE>jX1H z@cR|pS9>c=-dODQxGRI@TD&5m*(y=yius4EBCZ78`ohksZN|@QvC|*>gH?qo)aS?1 zNNeM%{m+D#`!Z_q5DL)9K^)~hOpeYAu0A3z z%s`~`*Om92)rc(UlHph4(0LFN9yo+bfopBjXp$Qd@SxB2rtDXYL$+c6-lU91kBjqI_qwAetni z^7XRDFmmj(dPzcB#4cHWST_HQ^GtRde^0Vrp*5{hnogiKSvD)#y zwgjlo#&s8#(rjEzxZre6gXQfE1oDDpC zNfo8jx3me>ZpU+pC2rQI(7%r!`_oJoJJ3uBwZ3oDy#FX7lE~aTYm@*FWkS`8ok99a zgMNn^(|*hvRBAO8@cdr)rT#(JkE^P4EEoM>Zj7<3_!75*E%y2$Jf;jLeeN5t;2N&U zTB@Yh^+$^xNkn+;xGa9hmWly?(LVm|0Ks&h%N)&(_m`sSiu>5?qHt+2ZP%&g0Q5FY z8s}3jitK`imk!jj&UR2Tb5F51KSf$Ok2{dR)X;b(y72hEDQ6Q{QDX1d+~ZmuxY(Ii zx{C-I8sTGvAd~wXu|*rF-I;`2#j{6@7XA9PNbO~E3Tq`RSW-W@D)MOG`jg{pRC_f> z+3OehV{k(7-Me>s*UyEUL!z8LD^?mQy?t%oYU$}6sg~mt-G*ycV;U=7VhN=QgP^D{ zx))aQ9meT+xafO!uIH;Wggld~@iPZ>DRGiK0sZXRS67c4&GWPZoivWf436y=8KPHR zoJgx(gMX^mQ8!xekkvY05xY*jq|_Jm=MZqQTOp0*c$G>lgpWL%G-5K%g#X-^FNU8^ zpMwKdyMWUqz1@cC})iJ6V(o25^>zfRs&;TXug>EWk3^{I%34V4)@ zBH)>?G8Cx;jAQz~bM(;9!9j5=@1Ji6>PWK6plAkXQIWIfp!ag2g_m~*MZGJ1F&=>* zId5s{v?Dk7-)VhPqPzy^DBowkJK|P25a`f-v=3s`@*q`NkZ>wW7W|N1#G$uxG`6@QgqG`nNwjCt=+EhcR+?l6(hqy-yhP9jysC^*WjYx&tTuK>< zbRTGXx=Ujcl&R}clnSKs?I7NkKcAjl+FIJ!KjX9H4%@WrY_er&J_?+C6L2l*&me17 z1<*r@e@f~;Jlhcdd7!$!#UMq0&gEhy@M_K2ODL)r8`pb{C@Xk&7qv1bUxMU}SKqwH z?^5tOb^&I7P7O|(c%LtKJ)8CHpZoHMd8U_)bkDqqQm1R^rJ0Oh$6xThW47IPt9$xJ z!&=SnNM~ay^v+6mB3T(w@%)||KjF|LbO2GGeUt74HZYXz zDJsg95JWs%k-?rt%x6As!9#uZ9QS>An~DUVD6{!coC`93ZuitW4PI4MCM#_Iy5X7m zxqLB9?17jQI@g%S=CsX!mD$*P_tW5Lm3Ig}9sf&{kA(DFvE5a{%xAiiIqx_Ih#v|@ z(?FyDe(FpCHKBejZ?ddKuTBjXXSpy7k@G`}>5MyMCeimWS$(`z%a}TA^j$&f#>co` zx;V8vB)=$osN6F!6+-{TItOco{?G0KPXf%@Nj^^pev$U&&ECZQ*BwJH$gJ_K_V0$T zx|W*m_DXaY3ym|X<{P-n_zQbm8qHNR(x?#m3XY zdqtkI(wtCznFnX4*OO5Rl8AJlzMz>f9l1Cdx%ExNE;sTXyk;~RKSpgFYasN2a927E zA*?5qzIhBuKH7Xlbf0niG@XhrmHnERlPH!?TF3`_t)5h`H;~F(3q35(cI)dt{@fot z%!Jh@Onu;LW8a4%{IL5S2vR8=hPG#`J3$w0knLy`>&YzGawxl^Q=UOTy%?Dch}VPt zM3lU*UDIJFN(D6|Hkl1dNYD@wMHBD5ZX};_4{q6e<$g>_!#wwlk1NKA?rB@Y@)rNB z&3vaoiQXUNcR7(9eF}!Pt44a&7sH;?x}oKIT^QprA$uPg>-vvTDb@tVT38Sr2VYGw z%w>+^j~HwnKL2ppG`yhdSwUqf4J%P{k$s>V|4+jDk|=1hKkE+7%F=q_Bi+jlUalIpmPlSZaJ zn3leh@LlI3(rk|{RnB0pLLjZnMr0^0&$Gd{s$*nYF2gx24Um+p6_5R8Qe{w?(qZGf zWSheJIOr6*x@Lc|0H13WlGSva>9DGEJb{E-U9U@qNx1gj7nj98=&tjr3;5g>QL>bX z+eArjL)Y?JBuacaQ{@d5ZXm=dqNAMbEsRTEMeUar)5pp|5ULM@#mv-#W;j1GiM|7o%HNtfSf7S;13cUk`) z_lGCsx)+r9uaY(9D(Si~D0AW6sa`6SdYjbnCk+LEB$gxXceWCv1$FGiYYc}`|q2L=r=}QpwNFZ(g|^w*?3thlhS1t#UM*F!yTg7RysY?H6cd z7HY0Fvl{5}dbRTDD>-)Ul5#wAVW2obA_#eF3}}?=a=x3rYEJ((=|IqTC%{%eM77|} z8K>x}YS=es#G-$?$TX6}i*efn{~1mDvWUzR3ehKiUK#U4glSDN`Xnwz-#PL^N?|Yn z??4^>Rz@{fN{q-YmGwq)D95K~u3NW!>BIM5_}g4_<9xV!pqxsv5|)dL(8y~0;PV|D z!lPA7Ss&3nJ&w zU!Tp~PjGh~kjYarJ}4z&YCw$jlY~~?B^V@)L#6be**tFS-y|NM(RAd+F{^(8+vyx{ zdl8*o^9k=wfA2TWqxOjAfnp^AUlS9r|2pIcf~h~7lnKD}?u))5y)YnJH=Hpl(w%p5 zH+{?bafD-QIQ02MgObmB`>Arr(aS@=gy`gH!*`1|B@bWRE~T$SVy2Tc=EBR#tID?7|UX!nHD$PtPP&)ra*J()SNh9!yPoKz zsPLE?6bvNn%|>I-bF0+qaIYg}noO=!9r#Fn$E5}4D4Z|yy41i4w7xm7nV4yQQ+3rGpiufdefy?6_x?T|!X) zV0F+Bg|PcDem)l z1YaCB!zT6p!D{ev@;;%Su;2cVphXdGW2y4gggv&jKb4hUPxLvi!}BN(+H}(f92a7R z)9^%j3LF^m`flD;q&MFNyJy3?xXq)FE5NVY%fhv1}&+{Mv% z5wY%nPGxL;m9z994f?-pf2PibO_$bJeQk~Eg-n)N5Hui5W;=|_w6lMRoKn0V?@Rdp zyxmGi`V9ykpRFWat zO~gsFwK3jq-z4u!T}C=uk#__&W0dH+r;qAD%P-`KqAO?-Yz^nBLcRE zJ^Ja5T)qcCp9iy1Z272z8Wo`8g5{VhVn!jcbb*+}pqNy6&iAS)m(GRIM@QJ7H}fg0 z^&zJObKTkjVRAPes&b>-+qg7}g}NL$H+*;!*Z$q^tShCXy1ZdG$;p+hEV%dN5h;z} z7xUO8uZ#9dv}YFmG~#*%r8|5Z_q#fEd9Nf^JL5I^Z}5{=IPAhRV>TOyl$sJmz#Uy8 z!4sanR1>x70|koJjZ6LWg(B$Gs)i1r<9RJ-)-PDY*Wl?CwCS;B%^;w>1wl+xh-6Y_gQtxSigAbVIh4&YlF>iF6 z$l+*8ploWxE|8*oGdLXBe`rlLg@zG@Qt#_TW1gI6CC!r}EOOhsw<=jlIfn$I+y$hW zu*MT0Hz_%lyes%d3UbRR3~s+>1If(F4JH&JtU9fsAWC%cVpa0l$$16x8$sY*Y1kh& zCKr5$Gh+bsZnZ?$$iLOBfix`1k-gh4C!9AeVF8p(({t|sTk-P24{eqjHra0koff?V zKie9DNPKA>986>=)T}m3sC&KU#+$w%Tno)vKh^=M5`@2v!WD``ucPBbxDfT{c;RF@x{;J&rJr?^E4W zT)=myB)T^~Lp=IZ*>;JB83XfykI_YG;K+`5!?AXwmunOS4cDy5n82276MYUtvA{JN zj`nLgC@k<5`=yV?^+nm&?*Cfiu^-Lt>^(#$y6yW0c=7#q|H1-T^_tZET*o3>t>L4a zY@ms+(#M>h?t(oRcvn2})Yla6?HWnW!MQ=&R002*mkkGY(<9k2bgb)Sb!AFIO9I zz?r$)(-u0Z>SUw8Q1?k*{@Ar{=Qs*(Z`{v{$WRTcaFWt~q9cl1nfWvM)#D53iO-d}qLz57By+)}!r|)f<;f~tx ztH2-1C|MLr&2|CN6z+I|gsqOl+LHZLoO*oA?Y*<84>nxM)!ZA6hsep>Tm@2xg-c+K zOvR@9KaL_vh6(N|$Z$o5{WDQ5(%1)QrhgMsm<1txbX>?If81T#9xI`)ez*pjb`SJzvspS^MZx<2^>AAVn98Jssp_#m&zE`VyCd`+L94KO_5X~%C z+?bLdD({vLmW2~UJgkRJ_p9pgUAVnvP&r?)XWb)ZU3j=`)R8A3r-E)9#(DI1^m!Qz z%Y_}0XcN45UhFcZ(v+SHC-vuBhBk)SXi|R<*1S{fG#XECO`gqejaNLc!fVxt=vhbx z!p4ZKB~ve!oxm_I!?mEw1c*Clq0GLKJj!?ez_s|RN$CC~s@aFht4%X_q=>e$EEVLg zoqBinK2IVm1!JSj;Os}coAa&l-yp|_-nm-?ef^t{X7r9WOh)im&`*?uS{X$c#c9E=ozd!3zgHqG88kKVniSnBjXthccX=k1Qf zxzY`G-eKI%;*4!`d|E{9aUqCYKV0)sCCHYDc?%+r|8aqSz!$>Q>3hD>r(ZR2Z^;c$ zh{W2J6xRNBNTvWc?mBBHMs!QhB1RH!JX=4$V0g-`_d3J08@P#LMiJCB|BN4EUG>D& zzwrCQ1q&21v)_DqqVy7=+G-ivn=L2Xu0uk_6El7gmpE=?(yoi)cm4z*XenBbZyMKa z-O#MK7bn|;2R6mqwuQdOf}ecusechV{P~XjJPkklsNDPntelj_G`U9Tl$E2-=++eY zi3-Zyc^ak!+i>93UF@nt`u|RBl4u1U;GOOwDPBeF9-h;Z_YFK0?{1KF+k3rLth@vd z2|n)zV!JRO&3ExN)6|}sJx@F_B6o>e%5~N1fG_*vyu;Rc^vrA(G6LN;5JtAymr|?e zV&UFP2#T=CM49J`cBe@{*VHoa__-HUdw>em1IJqNwl_Q=v7{nY{;fvRa_(}tAZ}pr zRTQBsnoI=zT`7lFuf>g1jQYVoke?Yg+ixI?2BCdZEmi|+kg4C@NNiTG-28-pL-7(h zXLO0i-b8&ygVggfyo5_&tT17S!**2{hI^Qw(OVC9s=L(+rySim6$UeK)7WQ+sGhEfJREtXk=k&}Q^RH>Jh_OKsRRx`^N;B5tc77_MMX6Zw2T?>6Cgsew% zjc!*@TmU(7Y#~o|qf>dm@*XhUai`JvjUY|{F)VeoT}TYvCSVZ@M$vOw{HV~==e@xC zZ6exmIB>-_VZ(IbJn~o~(JD4bT9^l)NpV9MI*8JSNOiS)JdS9S7SfJiO1f z(&kQ>S<{<#&h}AcTpEaapMU!?kuPYJ&k^GqQUo_zw@s0wWYmxJJF3>GI)3Cj@I|p3 z^FbP``>`3e>UEN)1+)F#Iw8ifR+pc<%C4^CYX;;JGx6ku2E&t|od{_0_yEW;Z?mas z?KuIapPRuW9RrV9_<_{o7bZ|XCJkS2fMTT{nr)+Bl_(E;)ggZn(qbnAOXgw%MWC55 zFzsUNKO`*Yf9wbVro-P&3|~_1%R+-a1&7)27-by*V=MJz$?tUFVWMXIjKrZ3eSZ|N z=Kjj7zQ-;A7`ySVPqpkW2O4`brLvuVNF)n8t$L@k&$h?>z7cb$+B-xBM%&V}tM0xj z$2r@4$Nw!I}+#UZ+&7HujJRKvO6d8Xhi%LarOEkwH%g zx@~5-yBXP;G^$M*D;H3C#hmYsjbn3UlM)du=muS?z7587dzP}aY|qi@U%EPJTlsc( zjVr`=i_!dXiF%_s!bYbvII}rIKRdvU56RI$1O3yjS8@@~6-QeX{!_fDZ@!~%(aPRu zJPqeQH%1{Vg+IXFZ8HH~&f0l$&aI5UhXr`jZ@KuVFEPYG6LCMIoGeg`-u@1_2+^J6 zW5tR*;83^ZYU1#%)f&bF95@y;c-dyBe$}UIbToRZP^G=q}d+>qM6;Uh8#9-v?{{ zoL4tELx}EsUL#9hp@lET(#G!!PQ@#^DQ6KMvXo~@p@3EnKrJGvI<08En9l;}@d#}(82Uz1npT3PYeyQ%cRKy)92^Q7Qj-RVsAo%^q)kmR{{|K1rN#&~ z&pGzV?OAD_U~nmhQCXnKnAKG5ZL)#q-v2gpEza4DuzH}{SxJ@a(fQ6OjeeV#(n1hm z^fQ4-JYV?DUwz$VlTUzzP!zwxrT_4Zg@uJ$F69kCiOwko+?wN}OaWITf?f`m=4JRE ziT;m24({YWekcSWm%KVUIv*!;Q64{jjB$LfR|dV2kaMHD>RNOPzVnR2QGTuR{q0xM zmt|T>ZX9N8d+GC>&{~XvY^#9p4>PNHuCc})TjdI>Tx#Jy(ePN}1%#|&Z4IuETxM^M zzfo}1y_Xi=GOzQ<4y+r$R~XFUboL&v2J|j6fZEONGaE&+<7hQ)EdzCL1d8oFc>=_@ zY~BDLujxO)j{q72#iTG31@0^Bx&C<;j+pgRV!FC>A`Rc}AeHS8l#?yL&l2z^a!CH^ zB;9v_Qt@!$&Z}df0ji`#Kmn5J)OV%vm#M(0Sw<1_y#wmM$xGW#;(S95&W?4Xd6zCv zP#l|&r&X|u6oHVe$<57e3@B)s$d$(Vc1L_y0(or@R*$Vhp<#D^qe`DqCWZ$gB8CeH zTPLICJJtH26}5c9n{UNxb|9g=!-ZVe`OdsE03|1nE2KL@Byh{X(Y#zA;hV*nMg zu{z=J@{3+K6yeT@L+UkR*7!Uu-NLra*Hxy<06X_fEy=u|pq$>=p)7;_y3qADn@yG3 zc#^EC!%PCH8!=n~;WoF<^H^UfO zozi#KE5AMzzqq6JgyIA%Wb&`=?-Q+gQ=DlYiyEF44nsKFsGvh2P3|q4nMTS#bm59W zvmT#LjG6SBdHF)q-l`;VxDLzs>2Ac5s}K%qcD4PEWkQ{jI5$}m{PfkS3+&WvLUYELn2&400;^m&TUa?B#woIk-@st7wVfS&@o`{A2jBrUDp8nBmk>x_95=dekZMN>Y!#?SJiMSr zX*u2rYd2G_TkPm^!FXAlTX0@yz%Nqo>qnlMTA6b`1hJQwZnTM~ojo)q(pMwMjfSWu^SyP}_gc*eXi`yl;StWK$>$NlAc+}F??Pc6`IzxL+aE@!4GCt$ z;zY(-zN>tMdHjmm0Bi00hmYG*c%T2JxcTs!{J2H8*#(P$0Gfq?h7VN!q<+cVx9aV< zg5sWCC^GQa+gD@(+k1|g15%gA;X$8)#d;$Ny8PQ(i00Y){Pp7DaWfM_%^(eg31WE` zmfC@hhrYWGk|pfvOb6C@vfX>Y*3JFtuj&V(kKfJfd&0kKijDV2zFZb}Eo);r+j&l>XpBVpUwCAgsIxko4azmIesq0>i^)xE;NDF{AUyX09-}r z^Q&{K)N33B^8<>Eay{|QQZu`qG3?&E6VzhxqA@>#eavM)W6-@%h$kCKzvmHroDU6T z9}~<*@>jQ|XgfPQ5uZNo`(53pv{(GOyF}g#mdCQXg=54o2&{Cef>Dq0{)WN)SpA8r zAvA>rBYuLvdI)$c{Vvw*3tWj}z(Ej~%9{TeT|_rmXTdgwM~K(w?9py@Is6k>KPkVD z7sPElH0y|A9GUe~jB;Y0m#bQ!v?;=5Be9+h#uL)j?wap#Wdd#B+rVZJ-rZMRJ6I(6 zj_Jr7 z=j$rIDL>CARKi+jX8UURo^^)2^-tvbkF;jOLYO9glh?{;qf&w3jr-*%}QE9&xPJ zKA#|2eU)El8SoeUeP`I}W@$e3XJWLwofZmhfPINd_o0G~I0|%W0DtP-Y6X%tEG`0U zw$2Hsm?~;?b)zrrpC!nZq*5ATQ9w17Y;GC=6JE%MOZx_Fuxwr?D|9* z`DKnxfl>)R4DPP22skr9)cfbvH+Qeu zY~p#9?w+pc$T^=>TKK?=nG8(#NC(3TU6Zbg?S%f6XNu}PEqClH`IjtK?RYD9eu?qz zGnA?Egpg0|_K;NT&J4W?P!Q52_G%ZdD`<1``$VY4%`rCac^2Z~-52arCJis`3i4rR zH8kcZ=0I%?NFcR2yVD}fsfnkrFaOojJcQwJ(B#ML5Xq=mD($ihxu-sR*HEh{$F3d+ z58Xz?#vWGm6m0Kg+7CxCq@!{Hek6&JToKh7VA)B=OW50*cDP`Z?|q5Y!$H&2w~Pzn z9q3mpLvIJJ^=P!Gp)vNTv4vH@Ji8CHb}Ky3awZv$){v@8CwRcgg4s2gcc`*^W5M;@ zL{7rbjS99KVZ;1juYbP0l-J-BGXGc6@)10o6MRGz1CQ?#*3g1hf>_nsZxC|IDJ zcxX$CEHuE63CoaZzL^ZAZJuzSo?NMdNmqWHeX~yC@?jUkXWH3+vJw@&>clcsQL6nB zZ(VVP7faA)gW4P;b6rb@${etgVq^>jW|!tal~KiIxWA?-KEsEU7_8-jKiuwP5Y=72 zPPP;qY#k<BTUMxQ~qvBirr-2Xe|2x*OYD-w%J)oGvSAHS0^D zZHc26bmaVM8Qmh7-u7u{;@Vzr?)G!;z`8NDk+F(3O|Me@W&xw;FU7{Dk(1_zq*M`} zoXtvuI>t}ZO?~yCy7-Ony17&ga*f|17PjooAoJw}l#9~JNDfCAwn~{N!AHBpD5w)9 z+L++QEN_v`DP;-yRe#F~6SrU`rLnfq3&OTkF{+{Q1}8>8_%b+7L}J`y|8JE2#G%Pwx+!LkDVSAbrep3CPt2LZ5zpt@97o}55@5Ko8gKrr zGM8LC>6suecIYF=3^c^;&|O-wO@H(D;X)1wD-~Gg4LKG3iQpV>EM0IW9d8YaCP;A1 zy&>|ouJ49bw#V=sdtzFs+{stm)x>_u=(j>C6K*IY@q9jTxzoXuc^=V^AIi|T;zc~3 z87%4am^Tiwf9m~+hf&hecPfvO?AZ-&TuoOl+p@Cixv4OEXD&nSeQJ?(H;BX>NMIoN za}PU)!iRf)LoEK8>eim!NHmtKNMPq~`q;Kih8bO{TEFMbgQDdxgEBy=9mx z(NG5lMPYL-10e}%wZRV#XT38?rSE_X#GcoA_N(cOZu#T}p*YH#ppTDN3M=V3R z3gTdEe*d!78PKQLly%sqg>czO#xt%uw$KV)SEPZ60(X#&D z;zY^t&bEfcbi#F#Z)Y|jkf>LAr4NyyhIuC8bCC*xu!TruJ4Q&xX4=ou0@d4_CqcdBu<3AGrx zsW-SI`L_zX$I5?IS8%Ho^>hX#9*X$(oe|w{42|qVxuXRhWu|TCeoD$8Cg2YDNz~ft zzZT065Vu$^_*HEiL~N*02x`D@XBR;)e0$4k0}={H-!6CT3fVf%eJyYw#jKdGW|`V{ z!fDN)zn1zUBE4i^EnPu?ePTO)^OhavL!dO@$Xkx?jC?CP&V9+t`3W2@9zj%cn=Od$ z(y1#ad`@)#>5JK4G=h>ICmi%oRQlb{V&44GAfQ{T{naP!9yUp1RLDl z6Wj@b;O_1)I3Wag3qFKkA;I0<1{s384(<-aAa}mK&))0o@0@#Y{h6+{rmJgJcfI{q z^&@J^g6jmfdjqIi_AkRcMRF!ZOc92e8On{RBt7(SHm|s&cR3sL@~NGe0@m8CuPwiK zr36(;tlVrLqt{jtzkBU0uw>3at<+Snyx>j-ZPGfX(wBeg?;A{?BNMPDGV4>23==IZ znf1hBpc>OOgSSu#8DxW(>~DB@DqmDMD40c)70Mc8eX2lqB-7UA`;KIJZb@VL+HTmV&`Ha^*cB%83p(oh-Y4Z7g3)?@H~5nq z^H?h^Q&UWx*dPL7r|eY#6Iy6ks)G@|zw z-zM;$iMm`xs4YClCT?9{Pc&p&Bv}~TttB$WqZyu-IHO89k}yhYyf?Ad)SBg7YMT>rF%3f z0T3NRE=m*!;^}PczoX9mP+~&(k?z!YYM@_DWo6%(+jX{%D9~uEy4ro+45I6%UT9Wb zEFdtGQ}qz<*#?{JaqYIAhcvo?hmme+C!7vP5p{ z^bNj9JHlf@BX0Qi=Qos<-O^^PRH)4;6T#~4aEoN|vaZ%lsjt&y;Y3t3@- zMlu>Le5lo-XCAD$nD#mWzS+FPd(fjREL(PcKJh)fkxav=u2HgP+wKY z76I$d)UNZ_yf`j2-cMFuOZ?;rL~qJ_n1PGpYKG&? zzzNFHT5&wfN6xp{?c$V;!a`6=0Y2D1uF2Ls(ZBPUTt5L zzCNST5(Yu|2Mhw1imk>EJ`Z7woU;?B=%>y~u1M_3Cm+k(jX z{?0kjE|A8TsJu4hYY(nbD2cv(1?X=oYdj4fa~JD1Lz+8mc`X=7#U zJr|V6sEEO0rhc!-fQ;DA-#bnISI@&Av-`i75Xl>vW2jWO?J(zD*B?i}-3ZkG#X_Wqwyyl%qiCn^4&CC=LC{ z@N%&(yGT4975}|o__}s8OV)8ewR;A$f5s5zajyA5_0~vBdRWoJuVm&-kwcjh2RPd` zYtGn0h}o-%rHa&i_1<2SHRb^@^h4b(^cgLbf3bnQcY9qeQdC`6=Fi%7HGhizB}Z zS{w6DF8;=EAs{Q|Dhv(Q7Ubb;luCw8`=rKabAnB@pNH#BywDD5OO3|mkbhPpAI^DF z+1GE}_H!ZSk&_x`{5TRYgBYc92p9FZxnc8I*XA$fp*bv1#X7`E3+3Q>d@kf6tPy+v z{?|0K((@gca*Dg;RQz_+<*1{PInm^?TIS&rS08#}lmbS8^?%qFbHE8-WWPBYCFd zs3R@p(GHd$@cxAbVBOmP!&;d78$MIz4V7`&o*T1-Z^P?pbr<4`4}M5q9#6*^-xFR~ zx`j+?Ec~%gPCZYSoqU_LY!$nBu&dL`osZL!FkeA98i1u*{*;rONn|~Fw&g(jF(zUR zY2++w{8tSXc=Vao>pOtI?I&C~Y>$_9HIq*j_H+3M*`AnGqnkH}RoYzoDCI4oLM*+B zfC%na^_sQ(ih5Icebq&KtbWi_pR2wuxBjy)Fuwt#?rhADtR3zIi{0c`9@kli2As)n z&@?`@p6}cac)q>eFq$bReGi>xLAd7Pn-2~6UA0YkWl|s!alxjF-c4Au1R271sMr^l zOENe#z9Pk=S7iIhTN`!N*A^0qh}YrTN}FG;?IfzT^-em=U|=N7_)XDc zX>>2xFay=t58uOv4>Nqqyr&JAOhRdqs#@R(A!CtK#B z#C61Eu{?0o&EHYw$DpjYAaNMp(Ot*j%e%B`cdcp`Q&YQ{@^=OUoaIz{1Jy!eKRpB^ zMn&$D8M^(-N`Cz*l%Y1uc$SQxYx($D!yM7m$JJ^)?=AAQa?noa0{Ak^8$?hSROAy! z1YiGILu+g3SgLm|0`C}AR3-ZSuKo!|)Wz<@lsU^Mx&Prh-bS(`=z@ptJFRZc zlfRIZy&ZRv>)ZPi8CK!xlo?y{XCY)+0+kY?gzYjl5>bwoIc5Xjc$V6HLr3Ard+B0M zwcEF7PRBAe;|)LWhe=6cIvMz}H{zxuT&YMr90}iN(BnbX>^!-N(vYh&`=T@!fo~G-#)ADxQ-duYkTz(q0u4uxAk(|<% z6n>Y#3;0OR4?djB8PxZ9ea&6KwRA2O9(g>_w(~{M&YW2q0Kle5EV7Phj_~asJCXjz znYMWk30k(aGHcDIukonV*U>R7ZJGRXD?iHB+2G(j`f}wCCbfNM7fUa;>KWsa0^{p( zw|Aa_m9{4Uu;}#<3QQk)v9~`ztEYTfY-YrQ;N#T8-mcFzR-2PCILLr) zkl^!<4ie7Y#a4J9)4Kv~0fxSgos2wTM@sF0SlV~E`^6m6!H@aGb@gnM_e(#rkJ00k zmT!HcR-xA~*XO2$37o~_o!iS~Gv@gs;olM)u6Z=}ge{0ng_^5Oq0i3!M27|&#ZxiB znU!a{*o+H6)={k#YqJ*66nHf$NDtcznB6==rI+X(b^j)k%efsWzBv}WTD@lG|7+}} ziC4&G{7K7uhlBJSGrSIB*{k-WlpIy4aLpVL;R82XIP%A&eXj~fBjYT_HsyZ$eZkji zdmH`!#{ZwzoEL#mCko z$-dQ@Q~R7W=kttc*z2G{tojqd@HP{>kvYLSOBN!BSAiBRBIRTjsuo{P9~|ag(d@6y zZu|LV@}FXyjI~pPc|bW8onlfYn&%>b+I^*~5Oc=ky9w&gM|5(kbCsK8oi)d+kW|dH zsw`--;QB=mh0+f?y6QP0m$TQwvVz57X?bgF`O@`Nts1Zr1D&&Jmg8wJ_K}A;Dqy#D z&cgc1n|a*`RzpstgNBP|EOLRY(yiMJP52mAYE)7DhXd(dSGR{}XJJdN@82HxMy5q_ zh-g~Mmu1B0P9^{Fgqm+q+V`t&Rod$o)egS@Vp_$8Vz|>EfSgUEDSXe_;c4F^!Oo#M z*4Sm7c63_1$eUbh;V%5m|GXU`lqP1p{g2Ig zL})US0PJNg&o~o)(``EUu_>0-_w%NtuxZ+p_z6wb`y_i3| zEd<1G2pvyWYr95a?<$3Z`E*zN(cB5PvCY8p(R-M-XP0PVCDYVs^!+22D=S8uLpS9b z3Q|IFIHwgk)&RAApqo$T%NVx@+8v`Gm>LY?pd0HYOUK{YDY=5FO!~eF#g{etybNrr zHF1tUw#@m6B)69wE>koM=@iJK>I?5>{*z;AZr8R%CC6v@qNs6tcivHytOfVG!s^%X@me){2Vs%CWCDN@Ai)M@aSh zPWte5-?U`#M&gS}K&t6zTxl@tdx#nxkW01P>i5)^ zg*;((u6SQ?t_vJpMJ|LrO!YT7GA3K-%1;R$&0PFo@~o?Z3ZU-=_4$;8}Sud3^J#KkI9lIoGuzR-PWfs zLV6z8$5aG3$qjA`-OPL`+f*w}yZKzj?SNE$xNPU5dO8R=$R=%c)!ORmDN)OyPRbrv zD0qO~jn#yUhX||4EHZ0Ek1yt#6IoG@59Xs|At8E!0A&@-NB)U@J2ONv(OXE$1k*V z0SgmtXDpO!NH|UQ>a@%8So-bh%ORLat4Q59&Q@?omZqUJ8q*Zj(9jnv=#^ioEY3!r z?RzlE-|vw2DsE5ED~Nj2=+|fWfdu%r!$syACn45C+^+Y3tm=(UWc#IE>r3N3K#1catCTel|e?{tqFzT-*gWH{8p(?1epZ714mHM zR3=Xh^BEsA0nEk7^#p5i^!!sAXW<^=LsPQcE-}UFsRt6sF_&};UQd$k?rCZePESCw z1WJPU2$`~g)47ZjxvRt9nEL5do)XIr)%(xhx~_42){xEgglDgl0jf+M#eKI1Das&= z)TT5WnISOyN7id?8&$2bof9DlZ1}^JJ;pGW9h2p%NX+^rMDG*I^u2TJ|uv zIPA$lGbxLKz3X4OVUTHvnGUIlI3Y@OOXt)NwM#9tf$l-|GkS;6(3Y9P+ zbdAg28LUT9&K3Jy9qL@;GHEj;gS8N2*Syo1P;*2q%)y~JmLoA)*iRtoxOSfZAL>*Sh2Z1Ahb$ z?7dKZN0+AL+|5-4g@oETizm^o8Q#*RuMK3~WVHR}^!BFUp9X<5O;vQnIk9@k<0nG0 zGF&bP%k%9#Y*s>MmSo4Z)s=#nPT&%Yh3GKc(I@>I8NxBK$HE{)}n)g ztB=bUiGEyD#RH5bmzACkj%3@vkSA1zF;_BSrmd%L0GZ&SDZ9BON~m^KV6DXQK+(A8 zC1tmfB7A!mZYC0tJ;_hDQ>@v;pv#>k=2Q4oEtpA@|b^mzs}aAEx!{oyrpDTaQ^`ez8I2qvJZT z-75I5EVvW7zI^e$e0EaG*v^YNLBD%m)9V&iyQE`XKRPAZq4RtpQm37n*sQty>|@XH zgf9j{_$CMvALphinl~oPUsD`=cZ~lOyLWQMn7O9M~y^g3AVhSmob71b?KV zT2Q)y)MU5Y^<;|k?5&;xV|JGt3;Ia%GIF%d!%|eXX^cj4t{oI$J(BD-1i&v@n zqSRX#%mXh{0*6P6H%X|~mJjTbT#fCnV({3M6s8-J8JpTZksD9JBtA8M^4P^}!N8;G zo9jQXx;fX^c8S+PcHQ%RB*}P^E`ylRumlsyXUWl+5CDD^PgPyJYCzK$OQ6-p#JQ;`?$ z168}fkcgLB+;Mvj66Yr4v{(D#xeMc&*rbS6z#i^b0Gb@RGHM=mUZSY%e+D9i z)~aF#H@!+0e*hdynR3dI03p$MCN+1jqBwH>n_R+`NVF#5s1F99%m9NH6mKJGvtKgU zU7%7u4j*&Qwq<&p$evr~;1|=haZ2`gF{RJPsfpgdhT_)vD%rSLzU`#c8AStm-#kaSU`z?yAuxQNIgyj?x9XA>$K_s4u^VQ+>oCDjLeSb&*7ncBP*8)x2dEb#D~agGfszeqV$YwzhC@mI-C=I zVGL(S1%gHtL`*scogeyLSyciuH!-(1LgjYuhH^e&b-!%&N>pn2fZgF8t;KY(VF<9S775VzSKLozi5Mm$cOtMwz!xy|1~s3Q&T)?i?{)Qw zKX9_yYg2U&&b@i6RbL&OBWQRL!cSFrox~JF!4s#uI=!|-6+Ip_|FL=76Kz&flMyeP zghjh%-3fW3)NrgWC6!S>j~qAP?&4zM*_VgW(iIn?_>DJ=_udWfljmPpIsd{T8Pg^) zDvd`kCYX1PkZqnNMS&a^YJZpu3DP>-K|!vWhjh3X*VOgI6Zjdk$V;aRF@0h< z1O(;#D3kMKMkX&n1z>2*@kXOdRwS;xeR&1ONZDFWCZ6v&ExVsgG(LC@ET+TR)VSfm{SpTw$^~bXPH`i4 z{t-8=JWT4VQJ2>ijkbeT>uZMoo)=xSYVOzD(YQi1DJRD&`vpd7z+~J7fu#M^yK0t4 zq7ef=(hlj0^4YA(rnP;u?#AuPwjPIg_j3 z>;J;}2_C^)b@RD-Z=k4F;0jd1Sn05X9%|X zVi$KixgH*rvOe5}Dr+@Rhm7&woy^PJNMG#D1M!P~)sU=mia7xW^;>W|c5eDP^pyZO z*)ri9Wh>;98(QI^?>&v~Tz8w1?p^s}hI#Cgo%*9Y9%6k<2tV3&lRVmhcKO`dkaat3 z*nl~h8ioE}rK9_iiKCR2pEebY< zr}ahA=wa(BXlkacR3|9@&l+CJ8OhnlJFYkW=~~uE0@hom%fH%QNMIHEJrZ~Xahc{m zzg4#Hxx>$A+SrJSM(_Uepi`hG6~*sq%UjSQ#y0|?qb?tFE8o@eSuC4V z#Dsrf>AFYVL}6RXEjovX`iyD&B;J~C&jIW&?}Way*)i~vnvcB#Jh}OXj3YUAl86Ie zb~BcIx;lS^9z{Ho_3J}Re2`S03El78jDY>|i3+N#9W^tB8XDHeVb$#uy9B0Y?GQfp z`CmZ9+Sqxwy^-S46ENN}X3%ahp8ge}rud0Ps?-NzdwA?TQ6?_)gL?~noD`ejra)X} zfui4#q3bsqGBK?PMfn_Rfk-@v5xRbfXcAAoiCB8Ej75HNy2nzp)HhQdrl1ePgU$k+mK#oG@y2HHW^d&x=0DZ%nYUwz$H?8y+DVP^ zo$)`TYYS*AU%xv>Z6Bs;mYfqQrSG|E`e=23EALgt|FYFTS4*+-#C)6pgaV1 ziPv`GMKnDsEfPYYBC8+Y>v$(OnV(rYLYVV8Zsm!E;EeK~g5%cc1!|91jR(wUMCgtS z2m$(E3;urf?a!WLNYJYF!>X;LI~qAf=Syt*ONv?fzo6DY3(ROe|3R|JdBGNIj@h#! zuX<^`iS!8VR$d{BKyzr7#@wLdzOT7%lE5kK!Mgi~`+8X1VQ?;3cbO$otT5v==y5yu z9ZyNMwT}}{1--3;qGfI6@sulM!TSLFh`hRCBdzf9g@gbly4B=&-+Pxv!GNNMLS@KY zMXogodFO)4P31O|+TLxVw7RsZ(=R?1_G%xJ5x70k&QYks)ouDA5%A(hMuc+OEeV40 zm3-|afLaIBib1KjX)k3LR%#U!TeC`M2l#tyLfxrg-LdY z;<~w0QW|7JZ3z;Ut~OmkGgUYVH%7&5NW-$)jcZ91m#Z$Qco%wURnBoA43?7wJ#;^Q zhU4Z2Az;p`ZU6yy>tzEigZTT%kD9}A+~G@_*J`N6L3vM`v@hhoK?vf9$_|n@j=Apy zNQe3Lwd^#<1{WowJOG8p$U}5o_+CdCYW<2vh4vr%5BOQaJS`x3-YFF+xN_uR{duaB z=;+;fC=k+=R^*$Z6OUF6c%4!%kCbM@|2UUBJxjBEE*P~3LhqoG|1@3IR}L8RCXwtl_3D03=lnH;Waaf|ORor; zQ`^;_c_+Ps9G#hX1wsT}0`s>3eUW6Erz7k4-t`dDH@mp3+pWdSy!zaM-bCmXTmIj9k0SArGy#GOPxOPNOQ7NG#0 zIqhsCuDfsJGXKYBOO8Y?EV0!pNPFX~2jqeivp;wXjfB|^@wO}D&r@EgtL%KK2vTV6 z2A*ETgs6=*xmwfKd;^8h^)V)P4dqu&Nns_kl(Vbdu`-6ST1@>a3HL^K`^6Ju@VbS3PhYOj#8`k&&t{VUzI6G3fUV0R%!1AM zPl=up`P*xCFJ9x~-*K#UCzsgvi#-p+HisD!VNCr}#^6y;7qIEGL!#Xk$2At{J5p%w zY+3T#0mqF0d}^umPNqvlS&VEu3|cOrLR`fs{&1-S_*8hC5LB#eG8%wcg0aa^B_zD} z_VQ2!k(BgSF{)ap*1<_}$;4=k;0Dq@!{Zb6)Ev6V`+mWbJ zq_}fnk-Uu`{VDt?NUS%r@D_Vn|jqRC>n07kDU9B@^Z{!`=|l0#YVwRhW`Qa8DJARs!ATa$9oBRF^+SlgSk7l|djs7;6L64rG%9N|!Ng5Ht9`BpZ*#^r|)$l||-H&@{sHuY^!X0j#YI`Wb zX}7?JRF0W@<%dQ<<@WdGKSd+Ig@dnA+^dW15UMK6>!-QHIycV5-g1MJ)VL~(1g35+ z^SmQ|!7^L!8%K7pyj_riF%66&Lk5g9=5(=IvsQYG{uYLsi4*g!uD;%pJ=!%qE=JaF z;^I*D_9L4Uk<@y!xOD>uf-7$69a9V9#da3e;+_n~Br%jKR$M`gF zI&d=lUswPk3FC>ry7SY0_3I^;9uCY7>Kyw0JxZ>|hDyAQb4X9c2SxIVBP-YjTQ-on z^YeRb`EwlHS1OSQJpQN8z3LuA7v`@&l)IsG_wrq=O&B}iMkkzhX`y=Dr?QZU@H}NH z3qE5aeUKl^Xxim0puo2;D^$r$4}8l?Q?V`mSZ;39_6sAwnTY!0m*VY~N|@3vTU@C` zY!1O#lI&SKg_jAzkt|hz%Q|;6ksER{*_#e3<; zNv7+c32AHPNi&Be9}v}S%MDZ>zEYnVM?$A^HOpm|(+ai$n-6^xm6}Qt!ZVSG~{`C|Kxv6ah<4x}P!GXgL z-~;`|`}^Uo{;UfJQH|klZEQkQ8`C~(fixL{ghnQkb~;) z*UF@X&HYj5wmz>a6J%Q0Hupq6qs9XlVso0Xrn%+vxO#37nFUg}*tyB!U1V@e?(Y{M zpZ)P>2aFMQmGH>MX}`1OMo*6;{kWv!j&6zASY%89*N%ffv)YL=o^_|U{2DS@x}i(7 z3kK_+9@o=J($b~8(#*@WFz__CcJlkR<#$-3KRReDT$5!2+N}?et*hxg|Gm54*c zUrdq2>WATYdjAYNHs$qFaHJ#l#>6A`eHD~7ucY1LRG^7!^nI+IFlF@*eHA?j4&Cv3 zfkC<+XfAbOlKVh0?2`HY`U7@J5|4PEH9seOhtD7eIrI0nh zU$!Nf$Tb&o=I>&{G2n=k0#16I9w6LmDlxjfI#ilZHRdT&e6Kpq8hlfyGGgpSTrnXr z-m(Fuh$x%4S(wiS$6BjPJn^;v)K8j%2+XzIT5mr%CX{H1F!%8zt*blX!}|gbTdZES z_!nvS+sr*aL;|q=DrYrc>Bq5oC_9?_#UEm3;21x(kGsw*Papz%2e`GTmW# z@>%>de)gr#qYo@b3fv!Reb5#>ZQiZiQnkqO;{ERBMBx3pzdxGmR+<7Nmh0BZ8H7kK zW~rUhkxyAH=&^(a!cAMj+nsTrt(P*dl^?lgoC1!hDW?6N~W%66(Irecqw->NN! z_$5c!z5CP@XSn&8a_5isR2$S;L`db5E4lIOOX>AjgOzpLzu0C`nZ@R$T%x#{OJj-h z!~cAjLGg9C3o$dEj@!oYH5H^&j=Q>{kI{F{2@m6O{b*6>Fe`+0sGe@^sz8}yrw2Lj z#_4jc`0iYEi%COR3};S|s|hVxmG1lT57kYdW=AW%Ok5{$L3a-cw+lUX(WlKa0cyfT zpjnhgCKbOkHT(vdq``!Z=lSs~D^G?vAaj&vnRNRLHK!!?MrShZj9Kd!EjhzHO~Co$ zT>E68BWi$1T0Or1DH(wEZ?$^Opy=3-%v&slVbQZSKG1Eu}J^_7@?vCk-#MXALv zz0eqBv?`Z%>h|I6D_1?9$X_aE%h?4Uhfh410LMORTlW1Y&h$J-H@qXtPA?G8j>Fu^ ziHYI~1;_n_Wc3UR?4L0YZ7n@jRcU5pJYU2-kV@u6Yr-{BuKfS zT&s<;6WwTbbOA?-iJNCnpT*9~^1H)V4-yvhkea7X#P+zLU(nI$$`1Fq-P4cE$|rhY;4q)*eMkP=9~QGbQ1Au&Ht2#Shg2K4A*agyXFWR(IHV+Q)I%?8n|8tnB~{GM@l(9s_9 z|9;mYhM8OUl)9(A@W&bQ5fD=iO=Kn8QfzB|szO}7l>q>B)BL4a^hRG-z?!W=k~|{y zkVmopNH)zWmMNi=pv^-tvC8Frt2Q}}ao(liv&J`OYYSI&2h&-u(F}ipfiH2Yl9THs z1yC;^;`EsEN$~8V!k-#rOXU}nku|f2q8?EN$4$;`d!2)X#~T(ot<-i0B(sQ0&IK&*6W;TV7B~hWs8*9E%>nRhGJ$2o z1}6%H$VRMN(ZNg^ZP4TWiDs36Zi^QiAHvjkocl*_V4`cG#`w0p`3#6s4t*frFpm*K zVl?HKkF8HDHQ6;z@drBd-Y3ugGLl<{$EeR^X|A@-R2+`AOf*l)2mbbdW!%Gcvpk9kund+%XmuW~VVy_fXgB#l{uo><)xyM(; z*Vi%J{e`3lTOJT6adxq01$T-Q2cFZK2mq^ZEj?xk; zz{C|4p&0b6e-y?GUP$4iPAukPa2WdKp3Imp&yCni_~sXBgjH7ebxaQ1$|pKQGdlkb znOVP~7B(y~hw>Aw&{?;2YUHnb^0#u{0ZGabUJl<-7hu4lYGKdCs6!Bk2jvRaR)L5B zF?>Z`dp~y-@!WkPY(!-7l#i*@!htugDU`C+YR8!8tcKw>7yX{E&$c&eO}0V}`YDRC zW@nP_Ji=NTQZiVi79Al!QdIz5{QRLkAWc*my+quKKC9v`!8o{sYcM*>{K?|ttZ`HA zzJr_Qe>gNE?s;T3ld6{;5Q2C#&J@(M5M%0Zz(okLAx;dBA1WS_UUJwf0UepoLXq7S z71nSUs~hCMdjymIAGo;xY;F_ZG`1uLyCd0kW97nmddw4@zALf7fOWuP-U{1K4XS8KxJ>|$;TUL4#AKxnsfpsw%yzkj1 zWO^dGR&vM{3Zr(v#(%6jpn00Sq*!zO>f+mjB^zrngzm{YUQqv+-r4^sFipf`RAEZY zbr+>>x}!7Szz@^t>zf`&N)r@Mq4L}fL1hZ1${ss)t(kXKuc>_6nd7+F*;H57hjHAP z-F|$77ioJvIa%_Jm7hefd~?RHv6v*7jAW%6UrHO~8<1deD<1YnLB4fKY@YJ+cq>qt zva-n@XTvwmVw3vnj7mn?K;LwcWWJUyfRK{KDOk>L(jZ@f5y8yl6x9xM`v z1M#K@%T+k$QPtu+J)At_a#2}uuC#mSE{vr=+Jrmqkh^;Y*An+w{Fg$(e~hktN(+-iXb&C!jxv)BUTtDmOdw>qLjP=;^p39FDf1&eMT=K~ZK|7vn$yD^pP#dM zNXMdJF%1{{8ddNr=jyzvbv&w7q;jM5W;{{k8w@ME+X`hK`ZBcs6Te zt%?&>KsX{>xEb?yNz5Opcx^Xn;fV*sMPC_Si?ZBn8jd_nZT}uQtDrSTCVBL6C!+>R zWJeb`rX)xVZ1UbFeP4BPA@k5p#~c3I``|Uh<3eWvBsxRh9KiY>m}v2G`!Y9WwlMPN$a#`=r1s!>8Yc z4y3v-W)Z_ie5&A&cB@$d-o1TM@waa=|23asCy`Za#y#GB1?S%bu$=#7ZdGOd;oagb zA`eVC{-hw0`5l4cF&k*J;h(riLq^2HM+6V#t_)2I7?#{JX2pL!5{HR8%gjdujMep^ zm?3|n3UG}JPGSS!?{Z&?aEnKZ@H*Ah`RNYffCdGm4%B_6-;?JST@^1@zO;4J)}60@ z`3ZoV554tuI7tdFUXPx^nmT@>Re9}y*hyoZw9P6#fooKbexnIvJnb5e_1T^yVNAb) zraE_2emNnnv$)J9as`91bM5__?x->9t-gD$n&Oq)lBH?a7I;sCv1}#cghiT@&d!{F zTH1_P(_;y9_|2>Q^`wK*I5jy_B<@98Lhv1DRgTI0^lbrd(Wy(mY zi*+Vygnd5t_Rn{r-yjx^i~^t8aA^zB#fJCaV>4z0D9a(`y-J1&zQ|8&lHLU8@%w%~ z95uF@?uyo`F~v1J$7dgtYBp{hnx1%(!cjN7*TG!EY34(946y{g;KGNW`i$6T2v5%F zv~QAEcQyB#r|vRysvP;w=0O-1@{$hPa^wbP$)Z6V^`Wwbd577CQ>mHs7YWq521_{< zE-sNucB>V{HD}IRSoX5>4&X@WMugH5FM%U}q}UA&sP}C>4uaR0d+RMIw6^>0vxf{R zw?FiggIW@?fR4aVO3Mpt8cTmQ1M)J##y*CCDnQIiAToTi6{}pCHMXWNYulbyOFUal zj0d`wo{WU%sLr7+EiMWrW!Z6D1L^B7)Q(&Wx(rJ{f2!w|citH3_IV+_w{l6DZl>|m zkjJ0GF?+EJAptpCP)ApAD1Z&N!?t{y$yxF%?&Camcd}ro1h!6$|Z2FQA(TDN` z**T7fze;|Sd#&#?p+Va4Xr%~`+Ek{*B(fIRpc|IVU}tG0UB9JtIFtg9y~ZEz!%Gt^ z88imIvZwX3syD|PJ&E93Zg?RInY%t2t1bN)lWmKSKQM}p_M68D?Dny6@q|36J^Hz% zAbj9MJM$Syq-eH_iyMQ}xiZ0}eec@UEbVHYpudE<{U)^v4M#Qwxohl!)JkTXZs2ww zCS&>}3+lN{;w7C6u)mLo+V*_bbgBL2!08Y_hPm8Mtquhy=lxe~hbL~v2HNdLY@PE{ z*z4nw^5Ek6oG2d9)D5-VHn3P0M9}Ny+An5`8YMt7T7OW{GH7Jwh70vF@om4erA3NF7UeGFVbphBnP>A}=)W=J2kp?~b@{}tVmHsA4JJ)Ek z63v}$CRC^tBs7_G)lb={Jo56(-FZs`1!RQ<$@F#W%HypfTcgP>Z4}ZN*Flt@;DE6J z;gwU0w@WWg`_f#wBq*t}#P+Kh>8igNi&AjGDLTD8G4r!hH)^C2R)@U+nQ}W1eeamG zOhA7JBBnR5qv>g}NN#VsQU&asD=L5EA8sNl4D(&5eEI5<$ea|WA*gTny3ef-ynnhM zxbFJE;e3|}=;KNFvrLjU$26!>#=yeSx*>jBbX}io8f7fXTJE#kaWfxTZw!)Rb7ld_ z$hzEqGDb3XeURO|mmAqwd*&uAoY1sGNkeJ6yRhx8pUot8HUu53>?-T%pKP^|ecdFo zzWX}5mjq+nV!Pz!su8lLOtEM}Hp+y6#YeWxvFY(eA;Iaj(C ziSI0Xu;DuvOCH*9Oy;I0~3FH8`5g91G3$?A~Oz;Tww7qE(N#h^2@)}b-Y-Nw0QNr=5qg4KIu|@aV&-s_bZC0c{;e_B-{xIPF&vRK7<52qFRH+@x zQlj>6i5zX^2~vx?`wNdSb!*QEb(yt`tKvnjv(R+fOi&%8)dn_`Qd+l$J~aHKoqf_9 z`N70iLJs-x(OvHcVJ~oj?_Qm8BsP85&M>U2W9|^eFRv zeO+4Ut`*Kq7L2?VHTavzH+>c71$5Im{YxaRzd<(>TIdBsr}z`_I;TNn=48*=NT(^_ z5lfp&mPo;-dz68~_Vobwo7PcM!W8qbPi7mN1pLHg{qEYapsvxaoSzf>ew16~O23VK zPOA)|bB`^J^xWo(21(UEIlApZ41OVti3=2+{gD(RO*VeL<JX3#C|)XL)GzRXdcb zNL!4lQ!g5RFii*vjH1@jRbYN5sdyf!^9*_o@J+4gN<+&T)XO8J;+I$4O*PN1ZCrn| zKBaRa-r4ryQ>L~D6q0+OBU~X-_vk;!Arkh1F_U0)CYda~#esz#yZ+KP&m@tZ53t@tlKyO3NtPHkLg6YxG2I{Qj8<(nkDEsDj> z7>#a^6bGF+-bl73@z=deeNr~3XfurL6Ls^g3=KDEKJkto+r*+uw1>WAUqy zv!PyK(wpJPw^n1jim5#}^UY1TNbG7SqIN~Sp6RW>Rp*`>C1$H)HxBf=!lp68*5923 zG0iGYk)P<}&Ryw#V#ZksVGCfgYa@C$fyOXj?;(UHN&WHIRBqc5Y{zpR6sx1?deRJA}rM4`pv1*2dPZ54WYIEmB(CDaDIBK}#u4ad&qQZfSu+ad#^Ox8Uv+cXxM! zd$9bnU)g8x_ndQ`?^}ONW-^&8vu2)W&6>4t2~K}%ovMAwsT8kE4*Zc^ReT(>&?&t* zn9Q5pa_iOIDWuNsisPvmn{5ELbZhi?ygcEJAMy6kW~n;`a`(?X2DfTgVyYh_-3!>A z?sRt*15AI!zH`}^@JwMpS@zFlV3_^>j-*GyPD##@SI591;^^K9@~V@@nYvM=mgD6x zhAt0E6nzj{#f zdh3=tDnM_3Xcn&XKffXN5|Jz7R9&1!|Znx^y-A(V*7u$9*zRpmnK#k-1bsz!fNv$0p!T zzMNXfmGPBCQemg;l4;02kbfwF#bnxN9%G1XAf)ZoQFIf>!|gjN_hBMx_6O1IkWqpa z<-YP+CdbDt^z=86)fpz5U}7&!n|?<#6p%yYVe>us4R%=YAqrI7r*rx(Y5^)9b;*mY zujsamhC8mno27l3()Ax7Ue;(tROs7dgx87Rq|7C>F_9@zT~4?r%U_kEtY_s=8YK*a zl^XIA@-m&01`}P6jG@BxoTz-?9nx%Ci93SBr1@$b7F7cdaLY30y02Ql-f%K}y-l<= zk7tlHDRnB4W!L!kf?MEtFE@R@2X_xKB{q)}{H+8D7)&}Lki4MKN!1OF^3FF{}>d!29 zrWd()(?6;BqRM5N=i@?$?l)oH13n&v&Ef~-9C~D2wuDk+{sx}hrLthnd5pOWxgR9y zwK@6R!DHxLqt>6r#W?N}vJ<>4d&bnf#YCTi%w;W7@9F>o-*FyTkC!DzOZ6?|FdC<= z^QJ2w6NQtn;(GUt?LFPCw~I#XxO=+1^|qCr3Ai>gV9QI*6a^}o%qvd#G7lnHw0Puf zoP}oJ%9fTFsW60;B@OM&S~Hs z>6o=Z2Oib==%GT;Kl7#@luqp3N`yaRG^8w;+5>1 z+CL=e|0uoCwd3Q6)>cr}Kmw!I6^hm0)IrZof7Y(*6-^O7+Hr-;?R92XisJLG$*SIrb}Vy}@7hZG>a07_jkqAK=ZTH&;?ogds@^^RKrE16o0yYu9ko}{ z3^?}ggDMHnpukxSPk42hPW=bWj8O3iH{)-8UFb7;wsNJmrTUAjYhck#Qs`Vi$%8gDmr-p2y!*y5@L!l=dPV)GpMC~qe3D4Gg>92c9@9RO*1N11*K=VT2b-97VO3`(uGjCQ_x<)d4jFnZQy-#z>zL#=Wo zJsHCaulq+}aqzhpXQ7MdcU^)V?<9%DR-%mB$8be3-pNKhGo2bhHRB>E?ZylF)l%oZ zD9w9u*L{SgzgyoCu<^_a2eg$0=1~k7&rl5Xsc@Z z{!jFbZL$e!aewU7ZGXzMP`9Vuxy_8mw&ys0c(~g!PdVvQRw>oaF^v0q-0gWRj{it> zK;B8$!u`)BRG-yP)m)pB*syTZJ1bVyYfZ^ZTO^b@Ci|n))yM)$(dJfz$D<|fGCcC? zP8*tky}zA#+}z!C(!?$TmKlcE^rQU@I==OUl3W>Tv1$xVeX6|E$(zvAX#76 zyR7lgM8nn(-+{Y9xhMuny(x?>GZD=qYg zL^vOQup>xGK{3~?zT6Y+db}Qj&CPvbMcl=2r=aWMwpOhjV@9>_4LHwky0}*Ry7#~| z2%$l$_qB4H`UF6fvrWk$_W=acv_?4kW{=nO*qD-&=%CS?`*T|o0fbUFG3;)!k?c`z z1GiOnPc(uVui|0z>*s^j&9!i<=g|vU(nR>fj4xV(zRn&mZ!F?>$i|K7B#TrT z_a@89pGtmM(YMB%KA$p!wi|a_vy~CqZd!3?kcm&yX!+)W2=cc^yO{jbGG>b!wbhLkuUly*!Q{VAwAT_W+dZZw!_z`On)`-gFi- z_?W&lRn%>ibuy@D?g`POk3gEANlvprJ^A3?V6AL9^W(a)Do1SkdDJ|c>P#>l`BzXw zKZdiei~UZeH}s&dau(raoFw2dxFZ-36a?;5hZ1na{JOFN#AK5T`Dn&}8N=20%oIGr zmXF}o5NC6oa=Zd5g!;x0JZD__!8vrtL3@O9h2@X|2_P9_Kg4xqu3*MH!$xWAQtv-C zQY%xFy>l#`$^X5>-u4iaT4&zrVflQEE!54WegM66rAEY88nR39KEBcCsayo=Rb?KJ z5%7c6uytKmm4WrbLSM$!M&r5ncRARhF7N!vy}ws^eH#Dqee08i@n(YSHPhv^@$_dz zJxb*oM7++A-#%(|93}meb?e}5DR7@F*x0OeR|#2ut&Ng6!89tZJ^_-2&tj}R6oo#J3o z59^x`)Q6JYv7XO_W*aJEQL`sv#^%9`ZLxi}P3%$W&c&~D>%j~2tOwud1j9L0VPqTK z*6q*muX>-7$_@{I+KmYvOW5)La(NX}hGQ-amyGM%f_8&rPze@+q!{UH0so@q^}S0P zG;Jd!oyAGRV^I6D9^omaNQLOuIei~+kvO9~qKlQrE7h;u{19fR+%BKF$nP0FfRWYM znq)6`Bz~JcCSJjdhu{6EhL^ui~Xeu`#q>$9S~Nl73qHHQEHqox@D>2w#x0FWaWC6 zACSaJWEWGW%_-&4orxKMaPbc7TuWq-RhM~d_?xS3#J|h1-M@V!6XDG9y^ml=y%s7k zeVH#CVrLuKyxbF7l9o~R+FDze-FH~&v5(%WmM9{`M{<$wQkGHCn>$TZT5ci-$RdqP z_H7ZVAfxk{I_n>PtddLb^v->1^7v9-&s?~>x8qmtxSd*2aXmdebuZyLnrkun2Xhc~ z6ibT;?mGZi@nhOcYScx|k&733=A+aUV@s;*%RNu?o)AutboY+nRhqAuVM|m-i)#5v zUJHu^*FU?$OM-k>{v)t!m@5I+M`TXbL;guXhP0OC?_1EA54c|mHelC5hT^7JrX7&2 z#KZ~t>y#DRc}u|> z-=~-VwY7|WN_r1XZRCvEQC(BWz7F-9|$^=AtS^M?7 zo(D$gQXr3gzZfT+b{go=P2lI*PA=EnZ$~aN9a=ZbRR(Y44E@joPsO{VdP7|2zr@J= zxM!5|^}xjQcTG-F{XTK;=GKG-$)jnD!xk_5-QY%q`tisY-`~1CM6UJrk6g%oS$h%8 zjoROG4#a6QGS_L27mylkSMkkL+t5rCsBvq?nDwgYtHW|`( z&&?5pzV#JBI|;S#agvM3fczL0x;htsg$=^-J7OQqmWjcvJXCw+_jn1GSM1rr&ulHX z?pjGa_wH`0_wIY=Gw!D$bxqUWiaTy16BuJd{}MyDhnD!VM>@*}Y+jdOD+~@*N@4-M z6CZe4so$FPfg;)eWt^4-G~rE1d7S5KRE1`-LN|C~ANz8R6_qSQ_Q-l*r8ko2wQjfW z=G>=78shZYr?UWdFol3>QaEYI!2@gf!QVndnX&b~LZyb5Mbvs~h%uNrN@LAvlG0vc=V z;y3G^`tkNW<1pzitB?M*E;Ui!upVXXjzDZB(O=N3Wa%d- zRs?oUiySS7L<-YgP*%34c4~|(m6(3I7v~e-JdjR`ukPD6-s#UNnmzsHRPrf$_RYzV z8IXsBu(Jl2CY7ZQcqe-^01LN;3h(i%oYWj{K}T@UT(OULw4(Eh8^_Iim;-ily8Xz>@()a z&dcn^No!-Y&UmU=f1-k<6cb;*24dXFSF66$w$HRbB+TY-O?>(QTDSHMo`hgehyxf9 z6B}KI4}RV+{V13nnIsMgE!HL(0=zsa@A;c7O%-3LQbPv3r)3j+mtR@T9g>s#cf0Am zX$1*2_4wg;`x?hV4wDyqDCn46B1 zBy`KEyB5jH_dp`*z^xw>1>MV9o+ZBnUT5^9=SR{e4(VMP^}!O^TzCa{Dl_iVhnrOm zlwql-WU4zccDG8D#*E&4vKvmZdAFjsZurvi)JbQ`3e2JZ z=O^h`JBFx4VAh?N_`dZ{cr*w=eXs&qz! z?_aj&iNUn9?a{YygH`|}Cse|IA?s*7u$_(-i#I8OoZw0*zF0HS>S_&j^fXC-uV(AX zSgI)k@fMQ2RS`4j704b)rr^+zrkTeq9me)r19vi|@bX%T4jd#MI2`G{i+PJ<*`GhM zQ(n2DHrZbrF+X)4bF&R8)~<*N5#&tb&m!;BbvH&dk;8 z+RqoHE9oz`dQL^JkIkD3(FxX_8ef@ctvEWt*=cglb7{)A1VP95L34RuvmrVGp%F@N zJXEqYN{k0H%Ka7!7FcS&s2A1YLc~jA_1GQqgwJp{3J8t9C1AN1s!?_3mwPQ0V{$|B zsQVsb4z@^eOu}^Hp)WD9cjH&XGl_^yB)!C)J;U_ zc|L_8Ucb3xkrrZ>jNk`qCBAFfLS<%ARXZ9|ZNdI!zPQBdd{hlaeeF~ks@587I_|hu zHSZJ5o`c#gO?TE@+lThf&YaNK(%UX4I!^$>_=A z^e1;+CC!i>oejKd0kOn_k-FzrthMFG?Cm!WM;j4I6KBJLQ~0A^?*>LZ<=2X~jXk52 zCr@GfDZgE=i1s&mzl42!A=$TLt=AALkPxGI36(2I;z_50oZh3!x4`j}UvipE(}?y} zXCud*<+V?EgjBx7SY0q;-zchY2dxpbt;+?TK4@rKyoVPhr!aC_DY6-TIH;8?-};7= z?zP!Dc2xs3y`@20Sd%Rw=*(ZUc_ziO3OYVjswdfGgNDeSym6 zz-pkx%Zy&(T`K1>HYtG&HTyItO+PbuK?*53Rm%Wj^V#ldVEamIT@<{a5F1a|MF%@0~2xVDC2};+VNh&K9 zk7okK!@Ajh3ckZD=qC1ulm_34WHoN=+uw|b--W(oSFLpG_aN28jAjGs_N!dp?66c+ zo2~aEIpH@an>3cP-RktzcF|!S4=n{8Cklt&3;xW=EvEWCm2v@~SK^#}0wmP@`WQ7q za?9rZz|mde(!=d(@yt5&8=uAklc82&6xzKZt}r{z`6vY=LXg^YJQ5*?enagMzYfQO=HGu*{Kj#RFG-6{~dm5(1~PP zP=&LV;%EXJ`rYn0Fh1vq_5U0Z-qvU*X#xL7GnG2HZXN?f`P$KJP%c|lJt+AY#YvzhfKC2kTuxhe(tlGF&glOrSRPj@W436n`o zT$%YGx^l7?E9LehPmZyxVWtC`&yX>U_JiZRt_P4(qqEyv)!P&9$|DjJF|l||1?ZKo zwPCNab>#_&G&N+(K-A~x^^9yA4Ssw_`F~^@bTQQ3bX|-psxt2G&t#76I9(2(w z&<<_*Y>F)((a$FPJooDvHt9@-Xc(No7wvvRm`J8i;}B|tO#%#{t|}4y$ryq)z6&O# z3{#eLMY+%%x?%w1^KXkIY!8xE$eAc*)8d|SDxL7yPLyes6HupOdaS`3kS=vA%pf=; zGxDfr_Y04|Wm_H42slHgP+JWyy^**fo7wcraZ)%B@Yli4`pdZY3+l+j%`)*!=N2iK zry5S+PuB(r)!OwmcWDWywl^x@)Tw1#nf=j%@faVCDVx zCRKsPYms}LGw|$% zv~2)JQg26CC2YS2y*7KVSGS6FITP7`rfuy{xGgLp1V*v-x1@%X=B9Al30}h=G!dK& zXXv!ETONXQ0Y*?4n3c>JGs;E%@&Y2(0SWuaJ2PYf2{v-Uiox}^Y|?9yC=-~Q>hx}1+85$T#O79aL6nc z-z&O8q%-H?Mk%^d75n?2rv#Dkdc6JzrJ~8r0YRxaL;CQ*UbteURclMd!ZNychRdu= zTy&{d>$uh5eDo0^K=RxV89fW(^`*eHP-TII@Llxm;{3y4%+q?Y?$lZBJHpsZq26(8 z=3gX>RD@w=47o_azqez5{rYt?aDV6Gt-$S1WG3sdWq{UW?AS%)Mve6$CRQbRow^OMVIoA;i8@?D3&@m_mM7f3(yYja- zB*o~qhbse;_q*zS2tI&aCES_}G@vq78?k;ZeAn#7ZJDTZZNaWF-ZnUDCRblFfoz+awXGWZgz%} z4NraHWgcQcQXBfbNmKw~thUTD{Iu%9hr&kBRX`UY_pFC>&G08W-dD+GTlkzH=?iI9 zk0Z29Gp_@!ktc5^*bxqN|13>(hA5AmNivYKzw;cJsh4$IeTrK0t)zZ}U>-NEM;`Y? zb*8_Jm(U=MxQKee6{xkfv2|$96n6>Q96XT!P0xtp_V@i8I)Bq9bNAmn|6Nho3=yvr zEkc0Sdui%#``it-XZ{Zw!D}qLBoG3b57GG#LPc-uXkuKec%$`P=yPk$$hpji*_g%7 zeOJ1E6Y4gfHas;e-#TT5zYfG~R)_p^UQVy^KgbkOa2C&X&l`+-yu&k!YCQv!zaI8Q zw*oN+Sv_ZcTKx|SZXAAVEfxi!=n+`;}0X&zm}lg-^+u{CPK1# zUI3LP?)j}!<{a$5{vc|m^S*)pf9Iq8Q3C_)zZ)C=XRXcx?1LdB2zt$byMurIC&Wdk zr~5y68bk=524>~mUE)+N2?_Oa&n@_C!Ha)m0UDqP@=W3G^7U1vp8nmz>(E5c)wqm} zQ7|gL(6QW6&%~pRI38Qs#$D(#A+a3QPo9p|ql}_N-fg03oiZfydlHVQy~d-Kqu~F% zWB<;=({;w18J1ADhpwX0%3{LBpIHRWr}hYxX91Z?4@oy}Yfej4=t5&6rzuJZs5SV( z`47?v&RFv?y3x`|{y5zU9nZHz483tdky`c|XES6*-p{+z^EpOaq^1XV$EOb03f6T5 zLgxg~%okn&i#L43a6B`nv+XhmOCP=Y%jDnjMJ}(FM>a{9EG8VEq+rAUXKKI)Ot4xk zjNAVgSHY=0u#<6|`CVKq03Pr{^+$!B8_7O~Za<7;%3=b{y`-sx(-Rt|3(UXtZ1!KvX=NR?_k4?^%3dO2KE$a6) zt`yzL0r!LAEx0n&O4vfE1@k2ok7B>n!-1K2JdPKH+~M%PIq}o`r;%aPG;<=I;25 zSc3i@UjN>T!slsDHnd)Bg};rCTL;%{Nx~?Dr#}aD1i67f>wR`*wd#Iq4SQK>>Mi8R z+nR3aug%*Xb?!=gW*6?@LArr!_Q>CLiH1;EkHWi*T=Jt=@afh4thAZ)xx_L15^ZZg z$lE%D+fRnkW9)qowA83hefci*4i5m_Bei{sZb6p#)NH}qR+qPH`D-OXoh9zXGAtZj zh@*4l%x$T$Zp-3R<0m2QgX?eXIx$?Y1r?Ob%DX_99GIdv!jrW zuym=$4crS}l4=xp1Fk=YB9Pk{C6CxJ?w5lBM@HlMQ;P#r5l@e^y(+hb;P1L0&WQzF zlHM*X@V5t}^UcVSZXc9zGzH^I%Gb~c&<|!m{APXbd>g+1T2DChKQs7W+wjk)xClqs zcb{K{dM>sYb*`(04L3JL@9mj?=yaoc`tpstTYyr+0VOTgr|lW+8$^7TJHgGUWfptD z9E|EW3uyb4cQnQ09#CWq%=+f;{$@1l==idx6uNE6yAD?LC*<7S`CiqZBdo2Y)>=tZBt505Zh7B!#rW1lGW&>t~ex5ot(Ql4N&f- zIkzTWfb6*qog7Zc2KSbH`+rodLbt+0LTCh&3R#aL(K`vH@(t{Pre7CjsAZ_JsPoXA zU{sUkmd`Vc_rBd?OJzJq7S<>Wm>zxHAstOFD6*_jZX4Du|IF4QF2H|ze@s6 z=V9z&Dt)XEm_p2kBV> zNK4a#Q|4;b(mAm5f|N1w76@wWggQ~Tv_K>qsfg|~u5&w`m7GfeMo*29>3EB*#+jL< zsG^)&YTDw7R7wV~x6k@4IIo7=_5@m+R*+0%%^(%a`>l{<=R{4}L?G{|dy1+lW%#uj zoXNWBF8hfsQqxcVziND3qgGm2p7&4 z@hMAn^=7DxOX*!1a}FLox5j@U->S@e|2>6Ik_|h{C!?M?oTEJ0WNDoPUe}X3N2Vn3 zo>RA!sgCN5N_q`hW|7Q+LL4GT9~g++20P^+DM3+!d|CQd6GDVPmPMK5&2R5;N@>xc z9Sd#oEkgdpBE%{AZLV1mcr0!mUKz@~5v+7OZ0)nC7jZ99>-vl?krO9KK-=Es{DVsA zr)9VyXWoZ&(+%E~Rty^}on^Tlx5tzU0T$%BM(AJ+B__OKzACB6q?SA0< zt$~DNXSF{ai2q2$WyjNa7&qny^^7e+U9Oye$kWr9^?~ksy=@lPL(U470@0ArAeI$@ z&SB0F{BbuNVIFYx?Dof6#oFmko36am`;VNozx8V z>$)=cH$db`!!rB7!Je!kv~>NxTk%5a-EUM+@)Zbnn+!lYtd3oF(--2DejQW1hFUDG{Ar&cemCzwCd{RKe zM(h#73MKLu$s-S&<*eXIcLf>9=h?v)TIq>y@j59AQ5Iy&jdt8+e8Onssn>-A&So}| zV~@&``7ERquA7r7>tRF#pxanpB9O^hyr@@X-)n?{<=qEdyC&J;eP_2BX7b!dv)OV> z94w*yLD3oSL91xCen^8`e5qK{^Gc0+A1pl2omGd^%$Gg}cZ{fW{c+?f%0%;|`r=Esx9oVfzX2ed{pJ)xj1B6Z+G11HmE__@j(BuwzUT>@vi}ooo^fKeblL)R zL>M}2c>EZ|u^g{xVYbC!c3`*K2i+C|ZIjV0C3O?Zu1-I$2EJe^Ey-1y^N@Mu?(&F*FW=W0zk;O$IQ$lhkjFRjh_Lai;?R-Ke!S38Uyv`85^Rup zh!$;@p7`i~vrjE|#<44Q9XuwM)ddvD3buCeTJVGl<_uito!amQ9~b#vhmG<-IV?fj)>y2ZcOzSbLx^{#3AdwvbRm zQHlBqlzf-)Yc|p$RBIvWxX@Ef!ymjrsJ1;(w1ZM=2K`+)WK^*FFsVbA>#4_pU+c>5 zvS@jf7%ksy?vhG=d(evU=5(pJ#9w_}vDo}p;``XuxfTA@IkF^$@C7l-`h^rDYns*B@HF;k!`-*T=i=cDW!OVv+pi8SwUb36maXdcR)SQt zx)sR_UbEm6PkvwLq?stXer7pj_qn2Hr)OO*gmpzQX-7RGB2TfUlmTw~6vVwRb4z<0 zL+9Xb8GE&vhfe>hVLTke>+82LcCA{+fXOQ61jc@SSfds4_+d}0_hqbR&EdccYh$$}L8`0JZ{)D2EgBzUJ%vjl!0np&04 zmO`)+Zss~9llbgF7vB|_{pJE= z`_jtOG&?b%Bk#@zQ84Cs>^1YR2nU3_@)k&J1){EcsmF_qJ*s$9g-ZYdTew zKHJcPWtbYr#vhrn_$pa^^egvAC#WwuFRxlJ2XH_-?fuT#?m2MOK?B)$gIec*f@%61y}N+Z)o`r)#9(sw71i zPAWiw3yF;4AOXrB+7}Ttn=)(!ZNk7`qA5&8&KiKAT>0$3(j9g@PyO+I_VL}U%QMvJWp`s3dnvrGR;`}(E0f+wy#_r zqulsPwp4I}TW@ndJRP8bqUhE(^%bb@aWBkJ>+(&B&=Rzq(4T${GZ|jTpCA9yaldra z+6cGxR;I!4C*;ObDYf8&Gk&h5YpQbIaj1^Ma_Kaasu^!f5EL<-13bM zh}ys{iAVlxKFL355jk zl~UoB6Zl-qOdc`*Od_G*&bXa6>PK{DF>T-@po2n>+>v+4xMytRxzc-v0c|gq|GyyJ zPs+kP5HP7iDvo$V?SOX* z%6rH&b_?IxQyZ*13k;d=Njxf8*4Fn!`(BarY`*Y~`7a@vb&YISQr*Zu=prCKj|*Dy z2vTnglfRA)_AdOvVKXw8`jj3queb-&(x@<^F|+RK#k{+b?+IboVo4!=Dcr^U{}tLw zebx85|Gw1DO@Mf5I^5u;jDwxS55J!h+Vzwp(o5+R1&RRntq^qmzEKFQ+ujw@qUKIlK)eOSb%v6Vk@yA~Rp_FI%JE_z#I`UqAIkP5>{iuFSdK zaK$Ic=l#)~CBF{o@_p^sL$<-4B%?oDCgds~WU_R)Gh24+N}9-EZzV8+mzpJ<5;}&Q zkh~~h&rZPaal?YUkwRgWT&_O&O<3mmeG;bH#shMJI*%1s$Z(S!)Tn6Ap8g$@_ ztx;qx>23Z6Miz~3m~bmjzl=OC$`U{m$e@dGp{hf!(6rl-^*a(!8G#!mi4mEj)a_vS zi0J9RXk|sfWphQH5J6B(E%VJ_mV{wybwGrxn_^%_#i*3-q=`0G8yrvT5AE^PI$%Euoa5& z9-5E0&VR|TB%v)S$I7+b{%o0YWhXxY5ZIHPo<{L-C zR~cpNu@f0G}RH2?5N?SXZ zTbVb~M~xAOUQ(<)twVS|`af@djtMuE5#0cbzU_ z1`!87my`K}N)uF19_g*kF0WgF9vAW0&gNm$WT8>4X&GLO$T>xdT2xDRmWQ?8Rrl7! zR^J3&j)6{ke&eb|MT(@{RUYO-CA@HdNvln)tZbIiR! zCROB|f@%3Uemje$Roi6HIAKpsxDb&IO>VwOLQaJmT$4gGaCd@Lukg#Hl=s-9I7yI= zc_OgrlWnEp6+Gv}^QCp9>*b6JV2kmAt13fPr;bnefVVaa5@7dJb>A{fg;9kc^vSqE zzz6b0+nrY0lIbRVKF)P2z1(Kf;;8kka7;o)say4DV}BFrM?Gi;;e=VZ?4p446+H?O zheQa)qDqAViAm6m3>)cr1W$dRQ1*{PQ;v_f2NpVI03Vx_ag$g`S8fdGNLjn~8x3nN zQ?4omFRsf)HE(2&QX{rioxHy1V4S(~dUsk$x(qr$WrcCkhkkhbsKwY|tn+ycJd z6|)vq56<^#K42rx$Vy*%%*R`!^A=4?j!;aPG1RI!0F)n1tj;r5b=Nipn_R{Z zl(5g&n+HFZ<*HPk!A#zF81Wxwz2d%n68Af818{n9*vmKanGOO}P_Q zxhl=s-=p5&d345c%&tMH(;I(m9nbF^7cRW58iWF^1IblLw}#9oA*h0C8>KGZ3y|*> zd{q$P0_f#b+vuf-s|P#IJf}uA{icHE1`f#*P)Vixt76Kx!9rZj{1NUE<%N%2C5+Ib z{0-2)V?7y1wT^7F(1G-WVoqR7p}IN|R8>W{R%yOYzx*-uL~VdTK!q*|*of6OK(RgY zu8@ph-3%D3yq5*ojOoZH%DcAcEDYmyVyymnX;q{jVvJ^9(!OL?AXQslsPtZDN~E7Q zuU2Db#NX;Jt}vPZnqrHi%kda!uV=Jf%TYHYqq2XNW{ERfoLntMuO*ejL~<{EGz1!R zMPF~YHi==MZs*vsE?U#cEBI2YaBDo9GCx`Ji{UlhuBiKPmmj$Z5dG0K+{aExBMhmw z$RjPd|IkKxv%qHlUjAmXy=Gy=Y7K9xYSWYsop4++DJ=R7l>LrOPHpc|VA4c2-<0Fj z-D^w3$RqA!j8*_TQMKS=p(D)hx~hE#9sSlLw__dz8SUUxrpf-<#PlF1y&br>!cooX z(gu|x8aaRf)O@zs>w;ou8r z3GdhVGpbnn=D=dSYpbrwso<;PViZxvXf!D;xJdQxT~YT{Y5scaj0)^Pmu-nR=j)wO zc2BoM?6kMymmdi;sxWOj?9&;?A+5^@!!wu3HjFcVghF~mn8MOMs6h47@NCM#Mz>79 zHAAw55bRl4GjsU#)T=vO4*uvcWhR4kdhH0YxbKzT^5DYGvF znI3+xS*ZD2uFsGOI(wvZw$~&}Vc8(*sA4}8W!YL>8sJJ_bU*MJN0C2f5zJ%>-|wuT z8|d7*yca9E8_2C1>i=k$)e`se&j-oBR=y>Of4JXV{4S}VhKGXRiaO@zne3*x;8k~u9E9MoHIIk~JQ9R-C*OXZ) zU3avikGph1r+>@74$aiz`$#~b=E!oEOlRx(H^~7GyG6?-mYhhttIvhQ}p=S;~yeW)Ay)lm|B3oGk6;I4V8Psh>5{Y;?yxN*t#bfwz|3pTh`jm4aoy z7wW=tDf=jPQ5hFjAwB}FQ=y_*Rpi|WSWl5!KfX!x@RiZgic49vXT+Puhs!ISYG(Wt! z?sS!FxCS&p7M1fS3~dJ4J~ampjoM9!Ta{0V>{TKcW}Y@!p9P;U?+`P6JTU+@v$qtA zp&yoLlj1G`96{%_pOQ4YsaI`wTBsN}y<$cNG_Dp(TDZd1G=V-Lex=7%ii} zr-UqT*j!yl1>9@Rf z=|ao7EpE*%O)6B7F0P=IW7LC>qm-y?`e1xj9qdD1h)hY9^3+i5ZtA42@Z|BLlOc6cXyWt8fzLS1aDj$cWtC` zYZ@-=+`ZRcXYcdw8*kk4YV;WW&#Ic`e^t$@ufA%2s9qK$1K*2v55gpEvx0oTJ{_+Q z?B{k|<6+d+x!PjSdoyggpukV2syRAxMy9^K>qp9CQ9vK4uTd+|po%gF%y{K6#T*=j zRPHVX)%VPH+ztFR$!^6YRHqZXj*7QDyow0%&c z8&C}0Ak9FUV2zI-zs@hLU63-Q4brC#7Pfd_l->g#Un2SJ7n?n7vnH6-i=!tLFff`Q zyX{Tm?YawlpHKV_#E#2n!N6EG8BFDoS$J%_&I9lr3 z2A0l*N9cM#y@}+)ECxUmNp*a4y~1t4&kbKkpVUP0X6SJ%)7;heuZ>Zq3OTk$67GYt z((rF2jB9o}YY#}Pm;-?dH_8&vZXf-hWV%WMQw#PCen>ZzM+)ld1YD-~m5d?k`U4i)CE9DT?`aT`GhMQfj_^)zDc zIls!IG2-I!+cs?6%#@MX#hI#Zr+B@+o|J$Q)c^r>v>6m8R|oK9m$09x|0Di8Muk*v z83g@b=~|{cc^>G`$|SH&)rI5qX;e~_hnQbnfPHp#x?9b&Iwf8CDqsLM4vaTX3=KEg zFw7exl$FYUc%P=2w=JaMdZlL;4`1({E`wasFha~O+6 zu*1eIhU`^Womop-nR$z=N|K#gKiy&evuq-t;^Hd(w-l|_W-ZR`SM{hF3I@G~0jgS^ z=v;+Nqusx};CU*KaJ#S5ADsDY#jz!EjRYT8od;Dvb;UN~{gtJE3eAtT-Vpxt;lKTR zi2ZSU4;cF&jKLq~76dlXxeNgJ-&}wBE5^|)#5Vp**Q6gSV&8RlcJhNP|K{)OUHZLF z=G*-zK#EG(*R9sOZ+t_{+oXc3@~j`pg*7O?0Q))^4YxxdQse$EdD*Q&3_s& z^}W}7tnzMIE}hKD*0837L#5j8ywgs8OW5~VE=cke>^q6d3yJ+-2dGR`_un_V*4$| zOJOLYOfh#l73(ZhQ(D906X{j!uPe^GC>wjdHe3NhB?50oICNZLi4zeIFj}5o94Ez~ zZ(a^kaB0QWectX8vOe8Wlb{++eJ0NH@9_&7ZR50hb#ieaYN^ zWJ~(heH)nFcPsL{KYN*+cy3p=T()@ZP}M8!`W1+?w3h#?xBqu(fL!aidmJ2bIGF!T zx$}lcH$X}Oo){-HhhNu$4-i#j+OUJF6Rmw9(4fdX3tU8U%90J?-99;_mcI7B>VM~T z;o*BK#;368clHG5ZmdYjq^(gSV9s^yS3z+4>->CNaudx?sLGfo9FK!qM|Dx1KOBs&4jYprqHIc~WinRfN^ayFCO zV5=E@7cfdogv)-l{;m*Ve>O3(PekeGC^-T4g7?q{v>*P6k|9|%EGX_2)oVW8Ypl=C zcy2aSa1J6C8>ZLUZA^%6vsW7o_i3e@8y=YQhAfUxFGV~Dp2sx0`58uluo$hYw{(?O zJpkSFASd#_x5z)`Lj(td0RRrM7{dad@8AULj)Ro1LQ6H@rhTs_dj)6Z5QgXZshF?WdV9cw3SAN_qMRKIb=M8SA4 z#CLxfQRPzYXTvSlreIr$5vR{LOgSF%G_5+YR@2hJea2pIY9`MgI5;2z4dnE0@vF#^WuI<)&^ZU<+%!m7`}Yig)r`3Bk=#%LZEv7E6X_SPuiHOp z_q)SatFnrXCE;3i3dVeqh(oKi*d%Oqx9@Ep)O=S2jC5`Jc9 zT~SJd*lO6fXukz>=DWnnRiDCi(I$gW+pc~sx@G8&X%ie0hm00KBYNfevrCG?)lXwxbS718v^#I#|jMsht_Mwx1rp+J}Apgz%JIU zozxPlijZZ9P3e|rUlu^OU3#Xcb~#VrRJVxZ)1YH+dd+>AEz=}Zp$`CC*$oXzcJ~IY z`Spa7XrOy)g)cly>$v5_)ysyUA;srx5mt8piXm#&ZZqrrEsA5n+L>m-mRTkpIA3Y@wjibcTmbALhP&EKCwGqi zSeA091p9Klv|;87<}7bdmRJJyxpSU%tG4XQ2oxo7IPb&rS^$bPv)XVv_l5V`?D0-! zxhQR41#?qTi8cDoRgqJY?sKY*@(IbM3gNS9j%o1zWO&6HfF&$xUO$e}H&YfU>=vAP z%3qy1lZ}Ve&@jkacXC!LV3F9}J!$aY9i64Z_f>6sVO1XLImX?u>1B>AE7U%GU z1FF2P1>G4~b9s#QT@hWtA^`GhKz9Ft+8w#abaB9M>%aGlB6(?kx-h03SmN@9_sYYw zchV*VMLvHcp%Ax}f<-p){L&-OI3t&zGt*4d#U*@iRQF6<@uWq>3B;>tk@+5@?C!Sk z0jn&tHz{tzeM3hKTmf>%jWfIt7q=(;8paV}cjK2))*xwf_J$@pHH7>Vbx40K$~Mw@ zK!6`vYdCS|x1CM;gsXRaP$84#5g-rkg0=$k!M?3{(j z)*He%uvMJSj$={I`bWd1_`5~c-LMmwzOXuLwHM6etoV20Fd&Ow4w8%FEJpxT`{-t9 zpgUVeYLIRr>6{nV@4}K4h@u#h+K>w@wPKWAi>guGo~E(1Cb9&Bn_4C&FUv;<0@Kzt za${0|T*8E}4Q+KV!&>bDvP)!f%-JpqlR#~4!8*k@7RrjmGrf2-6h?welNxwNg7Fxx z4w|*vp!Aj1-5Q*jc6-~n+#tu5R+uEFkum#0^JGd-xiz{GND}=i2qXnD+fntsP~<`H zHi~nlU3YU$?*FOnuo76p!wKhJ^YS^oa>0Uw3JOoPxhXr1d^rw4`7&z&Z4*f5z$&an zaToL0t)-&F+QRC5gz$RTi*%n9Ai=m=+VfUrmMb?B=G&~%{psv9u>O;%5~3L4 zO$~8e*m~|FFsGe;cmn>XJ+u?4FyO$zt`ru|dDpzccioEFKd#n%XO! z&yGMeWR7)TiSCR8t!urzB_qIF&L}-8B)s@~W5Q?>aP>H_Si%xhTghfT^hw)p?EVT_ zE&7JjSF5$Pn{v2VRzXxbfIA6ddp=A$a_KK9fbzdCF=%ASvY%rd^lPe3RT3_l=t2~C zp;{ZOEE+anS{Cx8MOvMKvq~z{GL3F@)N3UHS2$!~NZY=ee9CusdT$MinR=C;b&xyr zdcsU2K$n+Xr88w*r){@Xgmpb*`N&8}M1|G57XBRm3OIl6ym8!IFphHT-OfZT61UbB z6qTy)7cCgjO%^Lyn1x=;VHf#;-I=JAPmy7h^vg1N!kO@pw}Id1T+{-{p~GQ)Md4$j z$~FU&yH2>JIh%la7qcZM*5s>#PZtX#*Q~y;*U#5Yt zn6HA-KFKm;u0}S@ywm9=%ae&RcpB3>wTxr|3u!jPA}a;OuzN~%vBnmz`Vi_|o9haT zxhs!hq)}5G0iPlg8ZWsaqnMx$OQTl0DG;_hIOe9+Xp=tw2|=hi3EM~8-HL_I=Me`M~39U41U!!(o?SSJ+ zZ@qlC8O=bW@>zA~2}j3x`y!i#rtVucQzogi&9yp%Ev4yi?Tbyu*99SVjfL*GlabiW zwXT*8sFU6QhhF3miOwE=VXI#w5yQ#o^ZALHjlVRWO6=&kp;@XcJX%B{zGqE9!vIPLI4bY>+K6%~~OCtq!37K`ZxV z2Y#m8Hq574~x^Rb;bE%=y&T_mcP~EQ+&8nb1x7{S-tX?KA>PoDpIeybN%D}}| zqLo#ENX}YkU&iUiaXp>9{Pw&~I#$1^h)=bB^MuFlSP`&>vrIYnRr)hkH&XY$8}V< z%N~ezv}@9PfytHK3uR!x&#Ryiur#qA*>Wa1Ia-=NP=W2-1nNQb!)DEM>cUHMxZP*n z&DzsoD*l^~Y#RzHA5ffiJn;9eG!6^WJZ+>P+|yD~c(^n&AQm?%TpQ=~VMVKg4Ve>F zM4@?II1Vv8-i2Al=34{ddEa3d`{hc09{M0roO&Wlh2Be7W|CYct8ObqY=PjRnb-!e zOtspe@$LAd;2Ax&RXc4&?kitfxXyyK&ZDE=KlF_;80b48 zqmaqT6N>am9M#-dyjnLf6bad%u-BKsPC* zUib}3%{p4BcX4i#?-R|%P))l2LWZ*4G)$H4gO-J4EKvTkTL2H*bOE(s6`^LZjznVRSL@JyU0b$@TZ#m6>`QBLi-2ZB=5+7dib1uo>R~l zaW{x5kt;Ukt;to&7_rhNcQq{sc}cK_E;gxoXKlP$(?*Whw`yqe_}I)seF9%D2%IOk z^w-{0ig}7#Gs8{V!-*vfJ`{zi+&*W^GzbDQxN@$}XoSb#?;pD)`ZcBMZIEgt&duNp zIF)M*2J;voPn7Z9D&a@t_q`1Ht+0AsR|hzyeppZDU5j^veiE+_m@PwaCoXDs zr#y%tflt@!Y?_!cD-}Ia;|9a3ix@i~@x5OzR`Q)G$eZP6DryeYvA(^+DdozBQqHQ! zo}FSUkPChm51PNjp+JKowKm>Mp*rr_rp@icV%=NV5L%~xv7_-NF^!NuhK`V{)P|$N z{9TRL#D?K?$f)!10jB|`>)dEFJhoag>{3OrTUtb{^q)OnMDF~ zCh<95;!m`d7CbStCMInP2=;8@qqcJ{Oq6RU4SEciN(tqf+B+^{{`(>&3>sO>etzA) zX7Tm~rO#`%TyG9J7RVMWt^idoUL@4Gh^#mb;gg&0Xw?mb=KWN>b4RmHduwzVInF=Je*YcWprvc)RqPZT1z7z?7yTlW zk;)M7Dkm;pvUP{0n$n=61f=v1QT4*ka&RC}(DtQjz^s+a(U4;%zpaXLgAb>~t&)*Y z-kR$_*LVL?m9L!}Hwpf>a2KAjdpbIuYoCu63C(et&z`Xs#TNyf&dgKQR!Z?e-`eZ3NwwS zED^xU4_1yBZ{E(2_4o9@nVWp750Np5Y{gs?b!Ue%u11kuyETbP)}*QC4`tg(knWz) z?@#1N$Q1a$e_`ELu)u`^LUA~WU&JoZ=h^?nWFrAb7Wh)8*=U8Hj}Mg_zEj!@^B2ho zKpP1YSBPuWIK5`d4kqH@Vb;vKae@wyiuz|Il*@)klDDvlht9*2t{4NTkE37SS_1}F z9+WPNE*~NF*$|(8C>;CbrwiqndJ-yssgrssBH>2>GoPA&gmQf&c^tJr&(G~AtX^T| zYnJ+6gKO)iJW6z!W{wI}d!7q2z%Dr*VE!lyE3nagVc(+2+5=G=<)Kk8nDM@@><}u= zq-ns3EepOIH39*My5X9?E_*KciiC>7cz3Ld(3uvEij*wfQdSYX`Yk>ZyuvFH{4Xy~ z@Spo9`qGiKj59$-D=6?ZsXR))sxYb*#E(*zSjV_^S@_}4Id~xie#-fDJNsO}Gov`8 z9Q)Yj|6WDmm~{#cS)4#o2yPELrL5D_DYg;cj^5^RRI9&KZ}o^`mqK-wngmDo0gu&M zKNuY8`p#_^@wM&bJ#iI*kB|!RaMfon+QC)!NwF4M`Q~mX+r?w5mvoATpIb~>L><^W zj5maFsHX2i|6>(BHuiow>!P7=Vc`vGX1DQb+1NqS@Cg=HZ|&9B-?%;7E3ZdS%-*M( za!X?daQKOq`P<2JlG4rC;9|+M5~k42>_hK>!tZ4j#G8P579@~^as3VFf|wnIqQdnm zbGZkQLNY~OQpRmzP`}?YT18b}em(|l0lKi72NbFlbIKk-`!BMUe8lDH z^=5eYszo1-;8o9Z5Cz!tNu%Y=6O!0~YwlSPx|wbl^W+VQCflN zVN4RcrGczgbjH<>f@!Ji5(~2ek5lhF=y8#!YB=XXECsMAU=3dG!pt))EcvKV0bVgA zY-)G}ifoEkFGB24WMK>NpPQblwQ%^qtDj_vpb+?E(&JkeO%+r+^m8Ni%8s(nGFr@h z!{#gllc)Dm>(@jwb@0Pg9_37j4BD^lrip!TBxX!J(ZL<)n;$19EGXI7QQA1#ru~(= z6jnl+(drqb#)-{IT2W>Izi{x;&1W{)**VL8MZKh&RMbT8QOAVa;yd3tV5}d-T_Y!* zWZUPZ23%SPyG_eBVjRpqyB2uXQB2u%kxnBxF;VFnFWBPaKd}G?G;L}5t@cABKaH|1 zr;fjs#?HP8P~oHn7qc_?m#s#sjXv?-V zdc|(NqoTK0dgeu6JWGnRTGS}k`Oe3189(hBS{KLq&tKpTlh_b}F*)#Et#lq@A%sTD znaRh)uw42V0vZ%w5^OBqDqvmln|X0;FGDhcc;s|3 zG-~RwK&O^Z@^+uzaxuEPkwW5U;zc3&)HZ#^Fd){uAim2FP^2i?TTxqO$}JCj9j#4| zlGK;O%a7I}$+Uku&kAz7OsVy_xT`%emrHOD^FAqV3)*P`|6X4JmeLm?is(B;#u!}X zcDI6#o|-=J5Nm0?a0=FT+CftV??AH?Qx|jcfNi`A5x#4X%xz~gSgP8LJjb+PO69zWL?1^Smz z7O-#jNO4SOhJ;NCq4a%F#C z+&OLvYR1d0h-(5)3%T;-dr+T-34}fLk^ishUS2*t^N{_Iswjc`zN~^p;Gt<1x^RDP zxL0HK=*!JGv9NQAc`#n-)h*F=xrOi~+PuCo!e5G@$voEI9M@`&u3^0_N9W48DQhOf zdH>%V8Ahfyb-v^Lsm__xarl+~c;Uf#xsX3Z%4VXhfPr>tj45f&(>(efy9vQkRU8dI zJz3rnEMzIw7JAQ-D5&^8ZiXd5SQ1WSFYLT26&t=2S}bjz#|BOH0i^32PGd|U}ep))a-?ZHdk!d!#EZe4`e$Ny!TzO zS?+f{-r1%IYf72CfRe;l$l4~jw3R@X&PR`Ho@pcj9wh+eR~#veoF3o?GwXB zyRttR4~ZnjY}j6Hw&y;*K)G)x=Z#Np1q)ZBCe`vd?P5Qu7mBeKKo7<)7U;K;x>ZSx zavYN{``%HYw0)(Jqc4JW*D5%{!7%uBQTJ&|9=>~)?!O@{xAyk>e1YnT=KFwQ)DOSg zQ(=Y0-Q4Pk-R(soEz|K71$^#HRDqz!N#BN`;5nta@^Q1mL~VG{9(-tffTu~m;nVBb zxqLb7*3nPr{=DU}CKn0P7CH(FG*9^swAT$_CKSEi>ijOJjs zy~tha=yaY;Dl>U~`Emnxrm+1o#jKk9AyO-}M6q0cY^4uz(%~oU7t+b|=QmWqn7Vbb zY$mkU&Vg@G^a{t`s`9dUKFu|L&SrdOe9JU07#5_V!L-X3aRqFQ>=bNw8-x7Eu;^i~ z*#CQW|00i~1n53m)CDhv^PLfRU@Kg&0&f&4kWB&FB(zEVM^pkk>_B59RC0u zD}0Ped;__vEc4su*JlmO8fhk#Sl=~*Pqs~M-|tQATeg^+^=IkYaWL~#pEVtma%xdE zC&JnjfP=8RO(7v0NrG3t#szdyQp5bYr?@f{FC^J`{W?k(K zL&DPN)s%HgR~3{dRic9SfsMuZXh>G+5}|vbBBDrV5mTmM0zC&kl^dj*EYXw$T(?%M zX?%Vht!1#`?de0Dkkj|aSxU8zZIPQs7L>_atHE@*g)lhT34t~;L?kf@p8~pm&uT$S zj~g?_x}SudS^Q|z8QLz9bx%#?%#R9csZwMutOF>w&y?!2D(|rJxttGgL_JOxRzK>` z0k*EbP`KsRy4r%PPEz~H5;|-5xFKVewp>Y7PWt+Pd28IsF7cuj1`8p|qlYP_YA{W{ za~60rkJP%xwY4wGZpx!Ih3;I0C;ug&sP2lpX_$@T3|M@7=8H_CXi-6@wSe$?=4(Z| zR9HR6QAdu;Bhzse>^7h=akgEEs%OI62A7Qy!NGKA?TRP;yAW>7K6U9VoZajvIpULT z#(w3`ODewH#g9#@&7y*}?JF*223xXhU+a9gF7av%xo+^+4p|1LTqenPiQ4Rb1nP{{}lO9uX%jcy5CJQjT5}1yo>p(G^5!Sgan7JYth zxv3f%^m13PU5`g+DXg{DF`^eYnaJag|09@E z6g%(EJGFYdvC)mHh)ylYaz`O=UbrQGs;C&2&_@II*fN%f&G;oIl8R_TRj?snZs->{ z8=1{?L%lD8dcoh#|F4|!BJ$oQ&o3305 z)dxc7?8aNpdoIIkAPjLt`kqh699OA8F-g0NIZ>TAN=PcMDWjFFUXBV!yD(69*h*SX zM$(Wc^GSo6I0#f#iY<}!(<4q3oU5SjcE#X(=Hqoz%02KvCfu)}X^IXgdt}paU zbj8q?l);!ZWDvf z5FjYmLaPpbo*~Z8uH`^b!t=car8Oe<(I01UGsTS}J-V3vBY7DDVl6 zW|mkS#Ab+?HLSLu)lAUrWob?+z^U(5zo%>*M?oYTS`0L-rxs3EaC4lf8vM+6vS}!T zNHE#C_-v0A#(l&5BDq%nq`Q3Th1&BgbN2k_JRc4c@Gl%c+-ZvcyT)OVo7B7PjH$ur z^&!9n#3X3TAqS*UuIk`$$i=f~rBR_*a*s|IIZU#&-AUIp3o07r^X4m6JGY2%eu!b9 zZe(Pn=s$$P-bOZira+Kz%_M1fYoFJ+zOnJ@zhY`GO}|>|*8m%ofBlNl(A3mpE&Bfg zWxPkQeXcSeOwG6ZUT3#Z3Y;vZbLF}Z>()7vT!8wXhv-kV1;#IbSSSH=I`kO4a62J? zBu6Vt6h%2TL*_^x*AB3{xj#k0bEK1yUxp{>cxb3!)72W%zE>bW-*|5lP`JZU6!?8EdR-f*QMOgh& zZ0G;Er!_(V-1>B`#82XmtZ2f|s7{B-CXWDWywsiC8j(mrR#eIs0QDa3`UvBf(Ui$-t7R!>dD|Q3>xZSYCataL=JXG7jr#vlV;Bz8 z%<<}w;`MC**Id2NB*@ScUzTw;nu&Wjp^{1)edbP|HrVOKVX$kbYa2+UFe7t-uEvvA zZkmCz59N|p<|V!S8n--5wmB}3{U2bkv#I&{RwLp?Wd1}C{=0e8o=!MeJ7*H5-0FhE z7!NY`-H=7NHB0NE0gajds?b#d&R(I)AkxS5uK%%X{byLe{7J%+{{tQNU$Ok(fZqNm zfZ@NAzMQaLdkCHcx@wI6%kpp1FXle0l_iBVUIEay_dP%`-2e+?xvTTfR`&1a7pV8% z>;1_cL6D`)*v-`m0Xg~Jgdhe6dtqhe`^*Rb+y5_$=6AS%dv$rzSRU~|!vitu2d$X@ z8w{|MPP0NUmBU1`Y>Cfm?DNXXO2{a`8VnRGsaW=lejpb)yIsB^6Gb^Iv#Q`oF?GRKKs5zt=Tw;d26} z&g+Grcr>r7=>GEe@i!Xl9%iM#0F~!TqKNa4a|Z|n+#@j`V_+=n#RzdXEb-e8j%jo( zVc)RJUmCnPKbhtC`dUcNTFQn_dk10+nZ@({Y+ZPhYs&~M9^ds`PdEPzysIwJIfZ7C z`f90ZC+Gg7K<=!@3l*9!hNCJ5`ej@GO28$%)9moxJ%&?FG_nS9SjK+pm!vZ5Ftl0L z;rgm+h}AMLy`;MMD1OarMhB@Eqq795Z1!cgnx@frV*19?q|DFHXWkqEi+Au8?IpfXzf@8m_wi#IwU(N154Lz!?z$k`y96yU zmlT&d?QJ7+eCA;H-+^k2wG`LT~*RK0IL@UM_u|JagP9l)aPN}qs%my|30nLIr_ z`r1C@pP|lvQDf5XHNNhXo*tQom~5VVwhx2lrXSkbGkTIYX{n% zq0JeFsqnem{@wupckwBixOu%O94H;D2>U=o8A3TfU*u^*i1;Wddetb{Lh#Hu>O;w) z|Ij-aV&Hv%0@2I;(W-twrKhdQ@#qf2+VV>oPb>n(A46Ut#ABs1`Q@A6i0(PbwYc)Y^KBQev+%pl9B!)!xeV3)?TCMd9vc?>G-_!yO}2BWhz)S zat++XNgMMAHJ-#?%M*xZ_;l4Iu%u3wkyWP_cvC7^JDD>{2r-cuob{es^hUOPiuFb! zam9Ka#HnkMTWgL~xCg>ZC+KwNwk7A6eOum*uhPfE&xUx0C>FaBC5G?q2i$!oFPRH( zj|c-7Ug@5lG$3h)D8C>}cH=`$o^oON!E(=B8?I#;tLg7dgbcK*P;W^#NBB3x?zw>~ z4NZ1}d5ZaNFs%B2jI>6^>>H`=Xxd{DZI*4Ol^XC1dbb=>4^=vKHr1j$FoTi&D`{g# z&8NB3g71Dl&pPN7_NN0vOCol!UJPWSu=S@7*3W0ne4<5DG-8w>t@mWi|C5Pfkg4-g zZ4wp~>yA!IUAR^`iBam9Iklo|4H=M6vq!15&qV5{1$GUtinlw7Fj913_a)Qgf-wbk zX1{vZsm9Cf$xPf)vy)haLa1O#FDOL-zrCzzXoR5aXh!5K8`=KuBZVXHomZCnz3OEw zDXN0uuakQHJW4rk7`MVKOczjGE&lTX)+4xO$!Nlv!7uyTA=h0(N6uiXo%&mv6SF{lMDeOW_Wpy7r+ zHo0>|1y!{D4QiWy|5L8-?XIA5F{cc>-&9U1tFWWIvW~1GxMdpS78YoniKh{OYVV@o z0suj$c-yW@f~3`HyhC1ZanVA@K9+n(*LGoXN+$Qq$Vno~r5TP;{eVyt4&wL3IK+BD zPDHbCjO+YLZ+d%eNi-RiJCUB6#T%)e&6|2wCdrtcT8Ai+;CA_s7l6+X-7TPW<)eX( zCKa8Q0U5hO^dn6wGS!8SU0oeXJ^-QP!RqnOV!Yi0j^^>~`y1)aY0J~N2y3u2!LReg zvUbSpXH; z+#g7!CyZv)0x{=74WfALJ6n-R`s$ZLd~QmcYxD(uoBKg>OzfPSCDKLDf+-`#>uPRZ zt&tP!>5hQ}{WY%|@4=yZp9?$ag=J6?%CeRKuFV;6{y%+La*38D#m$F~G zUh_rg*Ga)W?RMbJs~)UV7ii$72;#}Q8yuPT%TS6NP_aLYQ)j$sP zAM{!H3uFWQGgT)nuQ<4(L`WmhHpC0C4eEekE=9YYKK+tMOXUrh6C8iBGxqw=wfds8 zT73li6Io5}51FwTG$-GW($!zuA8rn3WsR-;oe$CZ@v8z_&TXZpCQ6{OU4(Epy$N;-|Q;XQ@U zulmu2;)Y#9P~t^Sw0WFy zgn=w(J^6re;C2|^Pr>FNGBp}2>bZDtd2Spa`YX$!GXs>f;S`z{HCH{P9I>BY8E?T1 z^^0c?ln!3oNH-Y-N?Ww_ezWCsknt7upRc;D3`UyY<~P_3C`Zx{0@wCm_XX;QU0SOe zBKDtIbj^N?cX?3ObXBUNFEYC+UXZA7mC+Tb%ivz!-<2@&tebr4;_MytSS;Q(<5w;L zs9~BJmn1iATCx1g)dMn;Su7RqZ>+}yGo&NC<<%Y}7y(>Y&+Ap^g`Y01S;E1hMDutWs7%{MZ8~vQIr6wKMdJfp*67;#4^Nf>Z*W z@Xn4Hfr6Hw+`U2}p$VRI!NLP{WY3W|XH|C>s+Q_ReW(E}=r*Zoe z*?ZbYxenOSMH~54*?h=k-b;Y2prhFs6R%;j>_jMpyk@G0Van7YZU1iXElf3Ytjpwn zUE}o&mLD7NjhmV?%-0TEvn3{aPoua3h~F>AvT>y}ucrL6DSGDHLJp1)m6&~XW`(Y! zT4~zkvbAJRtPmMmZ4=EemNSQG_C{JQh?Xtk$;4?QCkYyCd3Nn}8k(&hVU_W``_c$^ zPn)uPJGKE}O1R$_2pufA*(%d=L=NL&uQ9ryK1dDe^^huYy(pZxG&_5n&<@+-8BeY{ zeRUN;Hp2VsQAdPHS%y#&p8dpf_z59B^swo|S75>ogE@HXwv*jxt4{^OX8Xy<@tJ6U zg5GU@wZ8dDnKI!4OfjNx|LGB@lkXjMVc>bexv9f3AsLae=s-dlBlBt=4Nyw)sUyN5QlC^6qGizsRhnhs|Od!g|X zws#p2-L`siQ>zdJo8D5*&&oa}Vm=HTiyO7&? z{}*-7pF*Z~^#=9qz9R$Sw4&lBYJ|%J6F0|~QmuL86_QsD)4z8@ZRZ(DOJqnnmlPjc z`lN8E@=g;mM>?ex_*Sk8%Xc`n656-&cq9q#lvFVA%l^vENYfA3EsV{!v&qGJ5vjcw zGvrkJ5_QFRdhNiQbnIeuaJ-^^7Rlf|86PKzJj-v;ou?B0BK&K30keviGx|Y4(J1(` zj%*F-TdG7pj`G}7U=3sQ%27D>IgyCz3oE%Y=04(g9M|K4#>VSph zge8UP#5}6v!x({IySmZ^_S)9K#+Ri}>l}{k4{W+#mX(kxLrh;;oc)xhCYILE<-Qsi zpJ}!xBC;Vkf+9D94-6~2Kmz!DH!}F5G+(wlu92#_o6u)iO}7%=Dfj> z`7EYRsdhW0J{UhDu$E~^9bk=j*al7!MNv^Rw}n1g9`Z`GuMbfB0)TlEA6lQW#vKf- z=Scy@mcw=uPK4{!U@V~05RYt6#3><7(v*7$_(&$2%j9OqLBrt(-vnRxRE zNtTftG=#=!{G4qHg%It%KIHj0;igg1651e52NSBzbdc{16?u$#H`L`(=f~qwN540( zg;;ERr_f-9J_DZ)I3kV11TQJXB$|%k!#U}eQwc1RJ#)9&OY&FShil1Lt`EN~;C>wi zvt`}fJSkxPihk}ow^20e!Phu6-&@IfaUftF6|2rV9TA9c?p$HZaD(%ek=-865do!C zpN=X-5*5HM;!>&$M7!kZR;q8NFoS#rL!7OwPuk!oCJ!qqlupmqv@fvD?;QQ->xXjP z!&FYTE_+^lO$!sr*`4n2n7T@tR1=Z}KeHuA*S%`+CXWIvCO7bi21#5nxD6@UDYhq$ zUzzRkE|RFr<0}5o-xM)-`JYXvXcg7f)yct4dz2SK%mj2f z?jZ8=of&H9@XrshDNFQCUe`Js9lTDQcPKJm1J&XLaipjBtpnUw z!M`AXya;eMZfps&#VS8a^8WFRN|Z`oMJPqUj)KUT;ym0Jc$jaThq!bI$q-UBdK6y5 z75$b#Pm4FEG5|^u&V?6#J5fRObNsAeK;M!1dT^H|qbb&57{Oh<7jr4NP&(4w%06Xl zG$2C0Amh$k>4T=2XPU_U9rvn9f>xVExJBCbF=~)(zBa)14yVvAlGpdq>XY{COO-7`7cvR3v>UVPW!AmQ$^IY$;&ZVM18d6He&rODBgQ6CHD&9PC z80t^+)mgTm>zEj^4Iy=>y6AM|ccM`%r1;k#`?LJA&(Qhj7L9%w;y@32ku$| zX7}{}S39TLsO`?B&iBh|O>Z~!%E@P2!_w}_+W#8oZk>moq;Du!1ymW#-S4S+PnI)M zWd7qSlK=YaRr78Yx|7^Dzpl-gek3?vTkHJl;2Qe})mpCr^Csd+Z^jo;8M%*f;c6)nqTZ(hEtS8=v>H=T7^LdD?9B&s}a)Gf&cvCGIDFsB-E-!Pb873{vIy z5i$AOY9?NWV`R4T^{!gE#?m}61C6Eit;mPP5$0ik*Zb;@r00-8fw(WU4nL zOwv){sAs5aYrUw410j~)xp9DYI(@EVU-DKz`qxgGua zeqXku+>HCtOAYz@MxFYAZ^ijAbc7%*pAR@iY5vV|u^N1D}xcH4o{pZK;kN(Ickhvv zeD&xqRRZ~uC>TYvc&%VAkNLB52^SVJ4^}dgN+<}w+wpFt;z@^^-}LhBOP*X5(>KRH z4tdkf^1@QJ5qDuz-lS`vG+zHh#1qXiWsub$N(m_J`grReYfnG(?H?gFciE!nPyC&K zm*5Cnn@hvwK7M{RI0T8*=X)sm2ys8*kd5A=w}tn~}QQwea?wtVcep>|5>=)FGXT6)k7gG?^rQYJ*|9p6EB6a!_2q zs~ES+M+jCJbb|RnMn{@3W2ne^G(s|l=h+Nv%MALWW#-_)@=t2i81!ORZ30P`utpPD zjEBTrlyL6qthTA=rS4bb-(FeIzpsCd#_M>?Q#+|=0BE5lnTXI8SpkCq%ReTe_=rAy zfGbBG*Lnr)wC-3sOJhFt(qZBjt~2E!J&%~fkrQsB6Xkgx--vee)(iAf!9>+|7SBbrI@>E!tEGv*u7YMzG--*~&c{Jc0q2;9Bn40+ zL~VtCXjGyT5-w%WCaG8E4xhynPGf?OU|0Gx)ns1$^ghA-px7b#r?t2=n)UmYz%!>T zmNo)-jZ^s((`LL|6n$G2y)8sy1R)DqpAc2`!ndCVn70Tu)vw1$SAMt)8=s?V&e&2; zq^GS1EqAy?3Txnf@7oJ?+pBze13{m;7$o&1)w`fFjh?FT;n&1aFC@+BxFY7Cb9syG z_^@Qe4Nq{2Vk0_#bX=u3N~EHW??46GpL$_OBV(t$^qAhaqB5d?@nbd}80u;ATC4#W$s`;gV>>B9QJbpeOnle)suZ25h{IqX+*cXN(|;v-K=eScd4Z)(%F((E4~LLmOu zXw{@u>=tayguko+lr7!|@ds`_I3h|(v+mT4RbrpzYpXc?U_P?x>1=?y6Kh$*YwXsC z)|BrqK;yn;8m`HNQlTgrK704xZLgM7efpeeIiuC`rV3LF$;q=*6CoN*{3^sc>VA;q z1_Y>8#k*3VFqBgJ>@XFl&wzhy9>so^{P7x>9G;Mu!Fwf2kTRaT$xJ zdn2T+9BIFU(JJPg0%jFVH*s7D4b+om5Hu}@A&>0ED>g7w&{FSpdWbjAeDx=$JhA2p z)fqR;rFCWLaF^9Wx=UxC(TRA>hC^Dqj-Jtn&DkChIjz)F;noE=%4i2f0VrGCf?WWq zCI)r=Jj;`$?;Pj@L2Gkrh>wji&w+gz%TNI$ih@XY^QC&bIH5Jl86GRz_se>|JVMd$ zg%2qNkj9+Hz>acS##r1TPgijy(^Mdp_w2zK!em|O1=7{#L|<3G?1Y_1ye7Q_c}FqK zJ{agVVV2b5eYcm?A#obje6bLd3#}cwRqNo zPlj_>Fza0^y>aRcjf|570sGAB+!E}*55oDNVfKv@rDOr>lOGd)dp7)lpN0gE<+qA7 zxeQV*do1|gA)tcp+1`&I`dqR_zh_d!*Vocuu$y4db=f*B?!9Xuo~_RerOBUT9{F}m z6A}9Mnh+aNl|oLd?PpTT{&r!5Qmcvk66GxG*?yju`%gsvSWI-G^nVrW!)0_Jsnu1L7b}rkjXXvQ|eN?2yT`3KMx-cDE)FS?| zV3o*XmR7<=fmjv&u=}!RH}b{l_m6grRp`W{3Z-A_v9KglHACiQl}w-$0#`?0^R=1< zo0(y`E4G1jV(QbcLcN#@)N#4eN@uGkTqbBf%e{5KEEKJ}%^AE{iqAq8t6DW~>aJe%%v$qtQ1P-nbEW z0>K>4J9AT6=E9FX(lYu&=DO5t8EjF2LQJg`Axr9W6=&ihx*JS;1A0~Zhrt`yD#NF! z=KJI4rO-h1rBT-MUR3jqYXRVa*aP^e%KS4%BO|+Ei)RLkL@m%`8c%-Ng+gYz{Kb7K z0tVMQ7yjD)nl@7LHK#}sj-H~OoV4j>AaTL`eGGsLrS~MYZVl@Fi)F@dx$5AQtL9-IVrrBt@lO@ot``icKMwlUG6m52mGX{fn`^&O8G0t< zw-56@!yO9LoKlWHo{K(yJ_IRqF_`#}B{17NinlhX59@m zL%2||nI4y}{M&m>%0<(lsxuXvMz06?3;9Z$jgqO*^k^s3)aH$I?lV_4^3==P^O4n; z4pY!bTMdTn>A)Er5I5k~`2GcmGmB6rX8qHVuh+RrZOD1zcvf&}(b?KQP~CKJtPc%& zNt44vh2~9v)X#x^R-IVbJfnDQaP`%BZ|kLiuCd$MkC>T~5~ z7vlr+-d^q*ZQfz(j(;0ON>v#U)1Y|)stuBun2`hYXU$^Y1+qF>XZSO>?#X>Uwn0o{ z=%oosWdlQb_WCq_%r!LXJq0oooG?227m7R=ysf15ThP`}99}-%-`-8$6=$m@c{ir3 za&~3C z4Ck0LhLbmhb#)(!Arp%2NSS_eHYRr3NJw@xWjZX{6pPKX0HJ(PgA#*A9ecQK5s)=0 zVaYY{!!OcDiWo!)S-h}hs2{qmEa}*c=w%JT)>dw7T31TcG4;KkT_#w!U_MkGxCAqc z_52JT?Bq|0&`@`JAlps6ZOX;$aY>}KTy49H*R<~wZ8`|G$eHw;Bvb&a0tUE`7r)-x z^|f`jP)JLb6k9G)%K@Z#-cuRevB6$by)*S0dF9h#AM|-`6e~|tb=NAm)7J4 z(GCY&zs?qdOBwKEH%!~9MDTP@m-@3CgwGfe8OjPzM^gempsj3osgRoMvg02GOT?TO zu|*owBeNN;zQ|`H?ZcQYsm~peU6~j;jjnb)jy*wI{xuQ4at?Z|G;+5=M1#ieMm!jG zqe*74KJQuVByArkCexL>CC4O(wnK&6OaV$B4oU8$HuGRFwwBj&oUIy-flKg0n||_*Xo^H|t_^_~Q zXb$4HQ(>wTn?K|!0kC$pbX7r}w=2NJcINeA{4HGvgvw)u1@Y%?>B5Ef19zg1EuJC1 zI=p#!LV;Ohlvdft)RI%VP(%ef4DEMnjhPq3ys(t#?FD**LU)_=9?F-}(5+`ls=J(3 z%+EpO1K|jZ4XkgU$v$vE3~^V)?$}Re+X#fu5b;1ypLz3y`jd0hJW}c=!(|~J{+M)R z%6^D4*VuW0?ubR1)JPKZA+)Jj(_X&9oQ~!k3}60=I5x$+O35438} zmz4T!0{V`7(?IT5)M_oQWLg@UakaF!Z!$u~niFdfbI$ME*Me+gPmPB&YIIFZ7N2sU z(+}MkW^qA#@~fnrBCNgn?Opey)yY+q#&Tv2Uti z2;KyA|I7VZr5y371ay&K%0_s5XFSIUb_Qr(*RP~85C!!Lz4vE_FfidhW)m~~-3U90 zfHRuqQ{Ck8uB`M2vM`YIiSQ=hP%CMF)naDgapp*h)MEeHir0$DdUkNG=%r~xCDW<{*YCOa-kz%d){$`^uW)(w#H1x)iK73#;w};Z zH{|%0KWKW0X zgV!+XOPE;WX?GF)(%&DzfRZsZAhWibnk4HkbKVe``>7N0gINt< zU5Y$a;)7-9#&n-oPq&laC3wh_mETkU{h5$!$;UF==Bx%?XW!`9KUYbi&Gps)E4Q=& zeyhZ~!rwWuV?85jNq;9^|Er3B3QO@;{IJs>uQrM_e)sMFh1k%gosaX)`Tjkw*y8sW z{$Ge#-@IR~)F>TLuKDK`|F?U8+ovk3$1TL}J5}364U>XCaT=Jdw zXa1-$EdTkh1md)uRJ22PZtW6z_>hxdo04p#@rH$NmKdz&GawFV)1p4mKp|N8SAA({!&Q;3^2hxbn&ce)e*0y^!>S$$g$yW%9N}- zO8thFULxPCd$GmGXcK{I{>@tp;x0O)SK47dB}l#>=KDEOkLMB<3J$5x8lKTmFf-GK zY(?sI&l!_6IQkki_Jps9on93Wo@mbmVkktPQnP}WQHDl?Dxx=}wybYN2yO|@A0|jV68v$d#A$n zvx99*{<>AbFtlWio*u*4$BeW1+Q&jY2BY`5 z2k7AGadGs%50R5LZXT-ko+G+CPaI*!l08Nm_v80QpyriW5b6!=7mR`jDEa+GcDWvqwvF4 zyMlUkE0d}&t=P$w~@obOXsJVib_W?s>>PFXTv4%(VH<<<7#0bJ=q-rHsUfdFkaO zPxU`o0II#4CF4QGtl*%#O8avT6SAYx=e%;2gQ8X`qa|QiY^}uy+?WE?fv=e=IkWNi ze(XUqe8R?5NI(!@Pb>U(XhrY%9=>t2CpEQ$6JRvBUCAw(A+^6}=2s73?Y9mkal;SU6zGd?lzQCzVOVA_7)i_{vM8(*x%BW{QGkjI0tz`#gvh^Gh| z6C{~J^+2C3RtM^<`&(BuGYIjxopfY{Z1%@~iOr2v2bxscf?6e3JfX*bb^rw{m8N{y zvd^RH2Ic(8BnzI-h|F~!3V~WDuAj|e_(b)MW?*#6U_lN4+G8h`5!G{iHe7m{e3)IO z^8s-QnD|{byjKr=5!mWgDHM*CRi>xjMp177^ZL0YmmQ?RehzwcCF-!uMOuq zJ9kd=KgR_@gGOe_kFZVJ1XA_zDOX^B=Qi=4CYv#JIcqO}ht?Rq(tFu$!|HO)qJRJ4 zEr1G*3D0zC^7+T=tye1I+@p=IPnXkFazx7_-SQkd*VmcN zhmZZr2R_8YEmjKgv=5H@i`hFcjh*DMGS&8PI*l0g77nwZFENwYM?yq2l$a#=J~iZ0 zXkV$CbKcm>iwlxbhV&>*C6%N#DCPycsY6O*yh$pV7?SG}C`dU4LhxE4}&`4+%PY9r5-JD?G+(xu|?TKw(5xOh=r z?C3E_Wwdv`+Ce(0Iw^iUc?MoD6#e_$Qu!0S0t3`WU+WOt)jJpGx2kW62?dnajO=?U z4fXdf0lmS~zCVk1i#G;W{eg}a&yamu@6ajJpTUR-<(-81FG ze(oW8;R*7qAClh>Tmh3S#D*8nHWy|Ckxi$cE%}F--;a)i{oo3)MCJ?;UYJg=rs5z; z#)JS7Xt>E8l+A{chemtU_UCx&E-Y8fKl?ugwAee=t{wnlzi68{-unos*0O8`1Sbrq zCViHdulKl(1G*`vIuQ;XrCe9$SZ2F{qn35iW5m#B%wxjeOxSD>rZmlGiyf5LFF8`Pi_1AaP{c*K6jNb^uE^))91n z>g3W%Rm02+Pt0zhiE}jsHe1#2&f8N+_b}pJNMtZ^C5mpll@y%RaMO1v?%IjChPT%{ z+%;>+)yny8cXU&>c7ytccs|Mho>gJQM%!B$gxb3wK+*s-NNq{obsU}e7RD^z?%{w- zk3N55t(cT9MHrO#s#M5Y1e4|oWoD1#C$?tf70~@aQDR6%(g=2o()SF@;-o6x!HjR; zs?d-6O*Su5&4<-o0ADUe+$h^g7xPGmv-ncW5+B=FQ^VR*-&dFHbO)ia16cP+_aq=d zaGhQ=D$-Ql|2O#5kwxSVz4#7sa$|qesC+t{j1iJY6 z6t!?0Kj;$_K)=m;mD4z^&XrE3e;g<55i*=+DV*)`Q_saMG26Tk!;Q*-2KWH==Pn|B z;{dkeLnOdf9(8fRvZk*!86;#zp0OHDQy)oRtPKSW$?J3G+y4lPuAXf8Y&@8In}M*; zZ9lIQdV$#P6Lx8Ng@wC2+$dM~dcWnKrBq@D_z>yuw}tzH1#Si$>03&2n7{l=)lR0d z#%}xKEKK%5HHI-6ui{}p-0jKBjn4@`VedlSjL~``?i4k+0Ve#nU(JFBR+mkrP?tF_qV zC&i99;ntQhO)Q*Kk3DB=t+#Y?%5cdf)zVwjzitdZLvpRUCG>xbe!miloMB@B+FH?q zdtdZjQIpnOO(5W$+U|N91M^pJb;NYxrwW6%cY2SnucRWrotI9_Q0BBHkM|)Wy~;7=*`-zY z!m9-rzzFbzdObZqXKF2F_fY@keMAc0Lh?d<$3OurOD0!NMofr(o16j;T}P=~EefWo2ggKx9E7cSJX3F_%e%d8f|f zj2DoW+2;sG_SlNrx46G9ld-WS`cS%euWmZ>zUFH*hm+7q5x{Uq(U6v(y42va2#Da` zhFbUhp_-ZOz8|%q87Ie3- zFSTQy(KP&Vst}|K2e%^yD3(hmiSqsgbvJ(U2~cZbQ-QAC$C|LEc*=N=t6!y%?2st8 z&kp=-e>;%X+6hs^XFk{~Oap}q$F?MxR|t<+%haibYGJZXeZ>=;Hy*z}4{pT6-XY$% zX|?#A98(MVSZJ)OVQRlNGmvrMU{B>dyw;!1x-gp9*7y;)oV7$d_tm8ZId;?|7JkuY zHEtoaqnIQyTgoVKS_$Jd~2Z4?hfInSi z-HM6Unmo?s5r`)}E{#idEqi@FBdInCo;J1h_Wgs+j=U~IRO|p_m^`+mOppj(J)^FiMf1(q4vzj36oU`D|s>CP?I>^~BKYM%-FE=#UA0Efo;VJgS$)0dUzic!-ykL;nG{7^t z2c|~3>J-${+j)`>af|EKNmThMdWT28}zysgs1>Dtqi0_ZJQ z&L681lTC9Ey%rwE&G5q;$lui`dF^MzIJAzXy;Rz(XEN>PR$r<~_~qQ$V6+=S%X}rc z8hzz4I)?kr_n0WRWSfyY!3e=df-uA6G2-*PN$*Z1w(6Arg-W>-Zn&k5jEBTR4znl6 zj|+i4+E2--wS??->ex|DR`7ZFGJ)6b6V!NkHfh#OtZiyz zq((T@^3^jT*P_FQA)O`7(VBlP`D2^VfAm&Y%O?f#hnL=mA$9qtq0?~Nsb`F?hcAb_)0yHNdskgGle^dLI*dVML;mcrW78z}HzJ!p@nrP@YXVhrq z12q{H4GQOFDbwsLB2}D1;|RFNDpoysgG_HaTekJBhQeJ=kH0pRlLqw}N8vj>O7wC; z-2~2}e-?t022l%*iRfbCxlRPk86@-cFx``nM=Slh$G%CnQuk0)RK(D! zb*i~B`uGAs5nZv9=K6zpDNNXfUnyVCb1=6?@YBq=>UTGlocFjG6kNl`<2^eZ;HG^* z-452M@tzWW7Z7UFgxOZ~9;a4~*M8%sE1hcl>1WzxxUNzW5*}O$YNe;Y!nrEygZh^j z=MK%3qIOTtEA<4~vQ8ruu+~ln*c2aq$rZZ}@#v{XSL@MA?o3&n9dQUPx$<)_IcO9z zHy#g`P2F&miF;2UYpt*(pXR=M^=?Obmozs7&jT|zH2g<-c=)$(UntaGiatXS``rB$ zZdcm_Lphw{ZHw!Rmy+|#?!qr$y~E;q4cC3=s(sgS006K9O-D(bkG;{!g*tnlP8S~7 z+UebUMCX4eJxznb>)+;o$=IEKt?>P8G8(z=wFOg?cjng1y(#+W%>%k5+cuBWbzj}V zA{m6Y=Rde5RLk`0uwMoD8^?CvPQ589qOl9g!(`{RDSfw}50@_Jb+ZQ{sZ-20L1Gvu z4qGC^AV^Q;52M0oR|3ij3Mf!l^Lr6J4o(l43U%G~w@E!10+s6bX__@UI(K>7SRTDJ z437~D@J3CnBe^d+r@nAk)UH_+wwUSJfH?XTtqsTdVJ^UNAmgCchJx zMP)@y5fG>ZRRNYK(Zx|!4JH_Snd3T8*O@cdrg*W9ixNAI1P0d(T~mwEMj2DOznpUw zU3+D1@hbfYCusARQo4F~x>ZeQ7e35{Bq=YL&?W z(4K81As)yryko&Nmwd_hgS&-d)7PMz7GEH9qD%sZ;5qvbW~sBHcXNghcBfCCk7_mbQ$Mws$xE2- z$ZWf&z906KoTVD|W>0ArLVrxMJ+o*ael0C?P|$8K z_TrSDODExX;wWr}j*w`kK=+xn8u-qRif6yHN!hzHI&st3aXTvBvfr7|G;ybEaQPE9 zF@rW&7@i?K*SCjuTx3!3Ixjvq%rm-g+~BwZI&8veJxQLevdV~9H zS00+%8-Blh8)M+?c?kJdqWF(veWOiY*_VA~7{G20YW1#S{&T>(^BAe!%(6u8mq)~s z|2%5gy>WtsfiMnD7n>C?e(0M{H_4gt8nGv1*EnA%(&bxmSZOB@tE#Y`*Rd14TMAYm z7T$V4%{9{RoUGb$KrYDz>~dG9SA2$%*dH68(+DR|N1U9Q-Bp$Kaov zVE;gfwXs@GC(e(BSXbYLb|h{#qI@f3+GNld!!f2Sp7w@g@+;m95~9U$uLj5Xy9N43 zY^c*j(Ec#(XycM?Un2Yg|5~?3?i;bA+L;T|vB?kPh-m#|LP?Cv0oXMB$qZmKJIWQ0 zGP)$;;c5i`=&!ghxfu{dG)r&X)?cET)NK;gc*zM ze5S$?R(<=+*qwDt#^{ zEa%tbbbZY9J|+QkJ3B_5Z5Z2)-3_Mro*630i9Q=iFG~|C@?_SH(>Jr)6!M$VB^kj2 z#BDy&3qjD+vr%cik1Adf&7(y;c6`hAg=NsLGI;rt7?s>eQ{=-X9h5v3j}bA#_Htf$ zA#1rKc+h04sL){b(MZZ>h@__1;)enJknv(H2Hyfi2+C~sVxQ8y&rz@0$&a6*9&qTj zOgf|H@atR*2JTK$WWIOyWX`3Ar$rI(IEwK~skk(?iIl6r4-4n-)&KP{o}Yb%*L{M5pP7ZXBkT zRijvPQoH3mG{6qaQ%l^G*8|1~F1FGABij+`w?o9GJ zXYk>K%QeOhuIy-uiB?~XLnnfId6tJjUrc7VIjxjrG!9*M_>ya~+Ef!#MjM|@rHUZo zN;5+PJ3lY0FN+l= z_8^cNs>^jMUx>v3aVL@xEIJkMGtg>6$!L-o&sHZ_fy{hcZ1!}8l)SLtoJ6hisr zE_%J423z~o$w0mx$@!ammQlCRv*WcpPxe$80O5jTgSVHoFGfaMQ-)32V{1=1^=eb# z@VOZst!j%SBvsGGu0ou(9c=friPA%NjAU(p7r!ALZK?eJ~t(J@TMcV3O&QC+EKmERV+3~UP8RG?0ljDq z>9((g86w|MFAYQU6mO<%WG@2)8=5S~o*PHe{j<#xhbP9QZE%pp=tQr5>*M;*4Dny` zz2X1$bPaSP4Dt44n30b8C}3a18uMYQgsd}U@d~(|f(<%k0(2t&q%#f16>eo7ZWS|IGJF=L>lQ(ET$|g|mvw$MXZmBZ z!0e1z8xoRnN2(UFMN^K;&~P5xw{GBT^{S?`>r~E!y&&!IWLP2lB?_?4*2r==eoDG< zFFoxOpF)I$u?8oa{*g^Z}I)SuPTzbp6?~_<8~9SYcOdHTlIhW0$L&Zm%l2D2KoesQV_fVyH>=~->tW*+8iRFB9EJLO1HgOcx-W$$ zUqrsJ@^hcfmZ1>fR#E99%<^MozsJ)mKy#SEC@?{GZ%D}09yl$z!pR7a+Ui0At6fbP zdT}2<1MKG_d_bZTg-@8T^KicpB`pKs7=e@)~$SD|l5 z%XKvRUfK~I8TTT{d2z0)PYP_ny(I@;cd0$H*JD%+d`j5%9g@rz%Ns$?1*VXQ5!HX0 zQdD&8y05R9tagT<@7L1-YO@7nAz+bqb(DeX9D5QHKLmaGbl=6s6;pivPHU;uRTQ<@ zbQqjaN~Sw@n`sKvy}yWzH@(TWea62u-=Hf0p$cFR1qQT{eiUl(q{6k#-njGh)O6jZ zxV{EFG>cfCAFM72oNpltd4EUp?!DH(VQ0Ll)*#w4D;CbvXdB=z)m=N>Eyr5%L4^lJ ztQPW)eO=y=X;INP0#t|2M{s>|d(d$R-w0CWUxY-WvqTss_Zo~h^8^_qHFE=PXe zSz+DX;NAa&n|=RMKb3_~k+oX`;Y{8z04WAZ{^2Bzc+t==BVp1ujqB^73Ia$AgOk-#OguN(0pgDUGxYlD44AlAB&`n=&>Qlz zg<)ipjy9vbuRfUh@=a7JyvL%)h^L-}G|ixW#-hg0-v1mw&N49-(%WKbg)}HuG13#u zsM&DNu_qQ)JMzNCX06!2&EaOjCkjOrov`!ZEpt(|rTofgCaQIGhK=HEP{lzgr8DsZ zihB~B0+J?)C5^(`JEG#pm6{MEZG!<&Iv1`05C5TIuyuW99=QD(qR%;vxTMU&wB%uV zdddmXXju6!#bVt-ulhbuHsII)>+nF2zw0(s2TTg+me6kk%!ziA0o7DOxT@)%1 zXt9ACKhGwMuqVA#KzlK%Ym0B-REcRqKmvYM$}D~~aFY$&_l(CBi>X=no+}WNVL1AA z7I0(wBq~+86CQ((3xnpSpX0WLJuv{VKgq`+^TBO)xn?_{N*wne5tbsK{m}l8ivO?s zqcWii%@_+->xwOHN4y}>NtaB#TkR1oUv;UJ&>dmz2%xqSV|wq>A{?4-dD|fc*^Z>8fCik>A(_k^cGEKM@C@s=kZIT!rp(d0A*w6 z{%g>PY&m`)M?K!=`5hS3^Ghkv$0(ltYjlmYK~UgVQ<5Riq`YBh{uJH1$Q1cGpmv9x zq(^r%9zQ}Kt|BRa`-E)Rj4KjjKfy>bKKL{GWk7_)eC2?2GJ^2W0nmmI|H0=Y_PFG& zn$`0<@|=xk6OO_Z;_`anfmSmHzWd~*0NjCc<~MEsaa8qlexFhg%%q-YYHwGnaC;D2 zhEm(uCU*fD=@i6A~!g>Tci<{ey-Bb6(~9bBo69?W+>d=gP-`Nqc8o?cEY zawqrwVNrJy8Y@Y}Rrp@tmp)nHz~DTHrB}f{sB<E=wzrd@CDwD7@2adjm*l)UCEW44 zwEk%Qis07Nd>}V zd#F;9hVw-jk!TX828FPlMJSjnZofR-!=X-lt~GzleAeOlua3uWlq36k-vX(*` zV$7=RsREu{+L#SZLd(iT8s9N$&g2&wf=3TyX?YBq5~~*gl5O64Z(?2#W>Zl^g(Y_v zsu9@-`LRheJ=1(fwU`<^=1j}4^`nJIkBuWg)_{Hh=IPw|J(Gm7M5GAt3lt3g*Ebsc z^a#>;J(HDRW0xD_Hz%{3)i}?sB^*6}O-6S!6wUbO=Zib>7`+$pdDV^H|oPE_=gpdaE@A6c};yh}*el zOC0;be#=)-rem~u!ipdxzxl&-QG~e)Co>?-WGt?$zCVlgxwqOZRZ?d&3zRf}=6LMR zd9b2LjG#v_rplt%s#Y}UY@^$?Fpc&yc}RsfJ@`H7d@_X5tg4MR#x28en;h;U+Tk^-;n zdiK8N@53nAI7^Ny5_y74GCVtaaj{vq>60`c77O{kis*VS|?>UB%jhyq?o4 z94KTX__2uZGbDb#-H*y>YP$0JIP>E#74W;@aLvX5^$Y-fMF+9Xni7zs#^~*ZZfbF` zVSfH5kRh}u2C`9>6cMM8y0SRNJQc$!M+J;-D8{B#ZRB|Iqa>r2`S5}?!V8*IO?T*v zX)lbpE!^@Z{mEa#H9&b-u8Hxo>I1vBBqUEQE^cgI!l#;UihH$7R|c>hcNM${H@n$2$-2*=b|iRZn##zwTsD3CyCbn*yXJ3cJv0HZY|WmVwV ziY!VXR(k7FW?JD6%K^|VUpLC>$Q+Gn`12q?i48wmb#jdUY3HG!r@MMX~NPVtE(eb96(O=cnD(I-l!ZBxPP_-re{{ z778VFkPqjbyUN)Yx2KsB-VST{jS<_j8Qk*pb{l6)9&!V2%zYO&K1+*|Ijv0Hy5R{g zfQ%%&t;D_EFq0*yp-`Ywi3I`fhb4lpe1<9F+7#Y~+mj=1M~M3dg}@i`Y?VXl^pr-j zW7(D2ZCuCEnMm!H6l8c|z2RYZueLobBjh*LMrd?5y&@m99-_y}HX5qtR~G~z?UgGB%GEwGWFYX&xBbMVq?cx?FOAx zNQg#dq{v1xAk?_Cb0i;T%YF49BWzFa*KHwQnfScng5tEMYtn|W zTy&p0;C@pX%1^-PPeIPY*l+A^>eL+8BpiHx?9G!7Z)FSyUf0MRZfU%QJP@tApSwBOGD$BB zO-5kG2YpR9O%d=Rz|L8(xY_t-*Hb|7u<|NX{w9dvdV9ysYW`d=gD*hQQQm(3=?E&U68c@1Gg@%1c6JKw(y*NwIk z&E1Jzl^WOotls#vuc&?xaTsxCYslw%v_vX%#H3Lj3IiQCwoJmp926TIHk<0TEb!y#C4bC=)LXuVYd=#fQ9o8Hg<|+-JU+zsidN#pM;LR(#zgKB;IlNm&z>Iw^ z?-Aq+7xW8WO!i79nW+V&{R^qhVfJ&?$MrvP3#N|`_kqE|E5|m!wk4ni3~Cjxz;us9 zy`=0t7+-lt$>#b7=xHzJjc8tRki%U=7f&%9Kohfx@t(YHT+th2Q-Q8mPd5fUFpyP1 z^rLUlk9m8kRL|sOXBak^zJkS-Tb-^!goYHZBM=P3rfY*RDrVmM`x7qRt?tpp;Y=Ws zQesE*O^OW`ru&JO&Q#V_4n`cm!b^3p1D-K*y>nZ3^=9tCf?$_dbzlAs)r^at0N(zE zr|b8f7D@Qtj4~?dHQk6~Ya6c68dbw%D`vA9;Bb8tC)n>Tqk3v}`-7<___z;XMT}vA z3hJp+{ot;~M%N1%aPquR$LppB^`_seZ;_ISq(~q-uM4yHica|NvqjgVKr7GiO~?cl zB6+d>vtvGjr|p}k3$UrIubToWDC!*SU(fj4yP+xJlWu&jM)6Ea$6*2`DTrTzH*X(` z8X0~I)b5c+k4})^U;cp!aVeoEjxS1u0g`J#+5}zByH6#4n=6;QxAv3ewpSHiMW6*@be*Vk% zWRDaWM4GgjkM^`QSKt>jsi88Q-<=C#WzS(U>C2?->pF}_04w$Hw*Dfn zQ=k5AKo?%y(tiK#Hu>-0K4LCQC%1yM{{+QjHrV3)9S8y21w)Nrcvb#~7{LC2rkkw4 zrrX8BcJbG+g*|yhKSK1th5okYe_8c#mg0wVYj#Fc{~qb~pZ0F(=EKxLCV$A$5~KlY#7;|JuM-_WUFBWFoHILKGETqi@Zsg;S1jjbyNhGEB`7KHzk zqkqvG`U(1LAUsA5*!RGt2zm3t!l*`n8it1U2hg&yeHwf6&q5^j*=@GKKZXCk$A&~e zd|dwuc>JsKUxl(yH~&Wa{I91lY!{sV$PZHD;8?|`KiBR5<4v%bj<gZ|P!el*um3`Qx#9VOpKoOS`A#xsawwpjd^;jV+_f)QM zN$b2;pqr!hUlDi{<>l>tJYUJARc|*I{g;eg%Li`~pmz2D&>rfd^Fiy%I_xMpdExQa zD4t@r_1OGeO~HlZ9>A%~MXg!oE=Y4n-O_^+pw+Bgmj+{n0}74jmRAQp7zK6+w{ZJ2 zQCMDAXN`xiQ9cnq;AyO+4eqf}_r=P@*Up^;UJd;0s_3~zsvZXyAO_s5klb=7auA{- zY_Gr;G?qfv5TaDcRfX#jXFKcl{-)&)eNJS^*#V&ow9}{R$X)q3Y)q0l0@nr^S>=H}kO4gkHB<6`jSUR=3- z2trZhZowxY=!PA)8X6TPwO*fjb9?KsH#P9)I&GqMc15?<%e?CT_klVv8Hn{Q@JuM@ z;HlfyT=6!2GdXiivyd4tvFDmU<~M7OlX~%(Ak*TO)TW(5(>64=x{U26pu~5mvH=H6 zu^mC$m&0>2OU6Wy`|@GL3=zLBYCB^k>;Lfe)^TlaP1|T`ODVjN)(Wef%ud58B$-4h{WPll z^f&mEvJ5(O)n)Zzai)fFOs`i}2+Ov!poih}h-avPtJGoRCF@Nn@LboXz^b^wt)+ro zU0UHi?&l+TxIZL%eZl=TzANFqtTp)W)uECt3pBIE8q@V2jcyZ`r=XmrYOp@rpyu(q z{#x~Zc_5*frpa1D!sZb&M;^a#?d|Q2j@~~UMe0j4$r5`sn^A{_-e4E(1E+?&{;8O7 z*CyKa)nq17v-w>?E|VgW0yVx^e)?GS&1d5-M`S*_9}{;z?Y%m*w+EhNkqD6cSzr%# zj%c0<;+0wsz?Tx9w?wz&LNY6B%C7`qM&V<>y}2F8^agTSniNj5cxHxtnD^|mB^s-h zYWiW#$+Y+T0HUNht~*-Qj1Ll<1^cg3S+R#vrqO-Y{4|dNO^m2%lU2$9F00Ir^Oo{) z{!n5@n>%G78RzrexkNs5^!vxjkN0?NNKx-Am5M|>?u2`XBX%hdZy-?ir;6I z>xgoTzoIv}i$?QZ&-5a5U?E6PzaZt1dp70+ec@w~kgz3w1-6z=L%I7n;<#4sosRC@ zFul~k;CG^?P4N)Up&^7|YsLk`!TlvHt|5%u11opn>)a~6zwK143qJE_YT`B7Li&n- z*}qPT&JJ);%;|;iCKVW)Xu!kNnH5`Kz<*q6vcW;sunkevxd>% zZb#%gXoP3IPgTFDZ8faxjh!3xOKZLuuW}~5v0WOP+Vk9-Z+gky>$^F}>P&+cA>3F~ zEV|Rg6VGd@P^8-I*c4$v;dn2l+@Kfi`)GM}RCFRZPSg`;tzs+ZoU#>}IOTwRZy|Bg zEL3l#(gn4eW91sxw%v|1{k>@#aFBNJTY0%&Rr`9x#NoAlcD1olub|-H6)k@WMPP`% z^_k%iA6{v5NU0(kGEO6LofG;qU&lOkxqBrLV{T7kbW=7@6o^X`haT52)jFG4d06YE zUJBo9;JeSyFY~7?Gy%OlpCVyys&&Li%fI+#z5L?M@R2-Fo|ucp_r;W3YRn)PyQzdL zQT%`?7Yj}^0z0U9bPRP3TGQO=PWibbj&7ZF4;))XH5-v1!&yj!3)hp^=x$Dz4TUXfE08 zkoSQ=f)Ixxa5ZFWLBc*$y+7pmf-aMiBU4wSU#sk`cL73nsMOmoC&LlK(mYc}wv7Ry z3J0Na$pah`OL`~CM~zlX`J10?9`dBRrJng(U{{9TlQr35KjBx+`v&HAIeGL#^`P&^ zThrGn8`8aOF6JNNOtZQ)8~Dp-&YOsg+2M*u+sDdvnZ|NmhRpfLHJ{ltjfnMX3WeKA zeB2fUPA^BryX#KaJ$<2k) za(*sPAOaTu(;}|StND6LHi2b1L)6CCrIg}+hD)7ps*&`q6|y#kFQWxCl4MVu!UuaK z76la0<;T^xvyij3NE(u@lOdZs6nctZK8m4dyX6(O&AX|w*z{60njUjGWB1+h$l|f~ zW-%7r@hh)YegN#!s&6jt8PCH`+yI$62KbZlM)*tL0O~Acm!rx<tBk%Z zZo!JznUfbb0tKaHLQj*dgrn`X8qOqKsvMP#M5+QNZkk%Ccn=5*G|mmgiIkZ?tqAKi z3s|`U`=z@t$=Q*~o7Theh!^lDeOv32Ghb&dMh#Qqe(K(bL2)eA0p^c%EbwUyvS`Uts+5}7 zEoGJxpq+=mbdu^na$#+3k`kO9xaCxQT-W7ZpV!Bvjcp>2OT%Ak=#8M`@`4dX&wh|? z6($$3cJZph&)bX+E{nd})lqUQ7ybC+84$^Tf}8czE8e37by>WW_H0aI)gAM=nXL7_ zO*g|*$FrR4FrUDqb7VG1lBuoGZudFk$FUip&yf$%X?=G4Q@^)#Hf+tSF+ z<<2a#SSx}g<;cy=VoKy3uFYPc`*xMWlr&1~4S{o9=XHE^Zuq<_#g>Jqbm|4gP; z<5X6AXGrx21-z68bl2%aD-f$ISScvdd)4@L;YnMBUW15oy&~GfD?pXSHd*>~7>%+N zXNYEP{BYDzK%h!fi`?%5&Vn7wLDnQ2 z$)s5fqxtG@NWOHbPC$-EZ8J-rfa2sa`@xFs=Q|W)yPeWc)df;9M^IhW(d6zrHwl%P zkvF501C+HEFHie)gsIXnc3<%!})%^zcq*n}7-aS$I_CUiU_ zD1e+fl&X4p)8RYwH%lCRgOy|v&5uhXO(N zQOii+#(io2e}Eety4hVi%5=`8nSF5|`8oE~@yN{QGLL_$%30}jotuc;rB>6_NP*dQ z=2}vi6lfe&ehW)v%MLXRCr2e1e9*fvt(4qaK-+?`YW5av zPS0^A+6N>3y@#dWvAF+TzQ4!GnkYmKp)eyGzIO2NaXsRMi-ONs{>#O<^3bA<_GUo! zd+`>s=9zc1(|Qz@TRE}v?1B!YCeX?0y>r;Bssvj(2)5PMU~%ywL6_XvV@Fmhno`F4c+sqHwd35UKw=jt?)MNNfTyKx{3R9q^?y zzIuN0)l4Mv>rnr`tHJ7dnPjls@Yz*;$M=NEWVU*&>StPgnz`7KnnGXv>%kh=2Qort zuCKvZ47)0fg$fA*y(@X2hqNP2^IU3dUq`4R*k+J~8c90EXL-CF@FH#+M8Aif9j}t9 z??@bzU|*9vtBOF}+<^HuoNIhb#T=~sfJ%^WR1OTA-sgIvY=B1=j$ z6aL3k=bsv7Lp*Zi)TYP6L&8HRqGsCVI1DV1T!%?H&i?K8Z6k2C{(?-8=SScg#@l}5 zfn@i?k%M(&Ee#lGZ5UFlqa&Vn_=Y8ABD+KC?DEdNXlYudr9Ve~;=w1Tqjr7lN??AM z8gGu_>>B3%VS{+^4D8c;m~fG=C*x4A$5!G~fNmX3nkSqS)x5$)0E6FI0d^&6a4OV_ zWZ#~gs8`rfnnsGFbE5PR&XmrFQm)8t^$foBaPH#2Dm7YW!-X#Z#Dp-`1o}oZiYA>0 zzP#Xe_fz9H-r0qs%k0iZtd273FIS{qulY1Z=>AiAB@nTMeigM`6=;(uz3RX6Z{L-! z)6hLA=4;Oof4~w7ki^$|J$i0Nxt{Fij3y3*PI><#X%iDOdh0S?Dp4c=JQ04G^7`(` ziy#{AHF~&;=Xf5Otv$@83%ux<{=CS5t2)T?7KN@&F*zzLB46zj#@dENq+J-GDZ~(o zXJ~Z&Rs1P<&U8<$@-?~4Z3;DI>KHx8w@7+hx$J=pQo`o>3JhvZdBcu~yXI>Tl%dOs zbE4_Ay^qhvL26G8vbs(O_`_KPBZ0=V0yaq&E~Gjg&BJV4Zu`VLJ}NBmwXi%o9l!(g zx^|m0kkGp$mGwLapK!)P@Q%E8gYO2{_EInG6<6#>4&9$W(c1W(=oKUBp8z1RKxD&r zNt&z0qlZKxf9{uh`7F{&SlJFD``tVjOp%VRMjG@&Vf+~d3YB;&?2+4`>6mox7n`HA53g{-?b!7aSHvr6_X`M)InlVcm&=8IRbjD?jMrGAYu=@Yl1*~6 z=7t?vB<;+A?|zi=x<7zT$uMsTrpHdd-mvYqXH=Br9$xByaRCU)TB zW&$o0xU)Ff14ea=m(YqbX+=S<;r1!7e8>e%TEPJ(Lchc2D53T2A(_>u-2Q0&KyB5? z#7RM&3gXmE$t2sL}2M{ zTv%F`JO#~=fN2UXaY@;ds3FZ}H-nFTtWM$%W0v-ljA$|N4twZUg7xxoa)(L}-h=n2 zm@SQV@~5pr+*5mW+qNYVZ9_U)H#9&V7-!Z+MxAR*3kitzA+cc1yb8mYA3=bYg3P=n z&tmn7a?F)SQ4qS-3e55d(t&uP=<$!wxfgYsGzn|}sgrQO&do0>|97M}R+aFQ)F!yo z{=$S_{6H1Hep2oRpRQzFsS4LwYcqy***Gkjo$N5EAoj zg&1xLIMoT;GC;;thSoa^&dRkjymmNBq7nSg zM}L&}Cy2+D>p`baCfqV=Ty4*6YyYpwdyyFTY zpp1l2#;*S_0D)w#obCM1lAk0ak8O^}=#_aUN8sto@(5NxdrXTvEzxy%wflszi_U?A z6;)jRai?-FDJeb8nI%yf!AKULtW%wo@&|qD`(1;mCc)KQ=M}lZ{~IJw|N2jmfQ0>h z&5rG-K?kl4S1S|oj@KQ3zy&Z+|AY&Ce!=t)T;QaRT54eSz2J_~qh|V-m&pKafwu1) zv&=!E-%_1Fm^fEJPFivuF5;;yf89(C+qT=Akq4J&1>sB|sCG>{`}w+v$4pH<*p*2i z`&g}H)GQm7-EkzpaYqH`d%Hs_OZp!k$psA?h2F$=cwGBbn2df0^9EhS`2rUMo3y)< zpFGE|T3_PM%EBja6%4S#{w3G4p*~V(2)`_LHAS3AYd9A^G9kOz*&TR$=<>MhWdmcZ zdKPl=FP@fFa2nF|mcBJx=KNNTo;A3>$wfcK_?_B=GDd4tX`GpG?+>Msq}0;`AY;pM zZg2yTCk-r<#idDb{_6O=b=iiNl{MtYk0r_0Ll^$eA-wExJZb1#@|Ve5tD+(fxC8|8 z8?D~ncd_0l3w7P$NfJ;KP{BDz!Jo$(sBOYof^VhLUa7s8!`6qJyD|U#&9eJxmiNFXl$4@=|ARc>z~ew751fwP2qXRndjLv}Ibfz713m~>rC|9)Hzw1a8uqXh zlLIMJrN_~IKaNz}52c-x-7r{QW>Suzs@k$J+P~bAA#pyjty4JDh(&X=nvr!Z9HCsJ#N<~|4&^^_^5NVWV@&+{!o&u2!S;q4l zfPQ6D%oevm(?lkdq-wry7Z!s(6x_V5Qh7NJI|CNaC|>(RVwt0{b`bgOCZlP#_L@U= zhAq^8D87_&8>*GugsiJ4d6}9>Kc|LWaT0)Qc^CV}{-CV&mJJAnc1#+-BqsKh9%D#M zR&P5Fgy{ITQS2Q;v1yto!#@F-OlJ28($!C)Rj>Tfdr5IkYIS$_Rsbe&XGwxguy6!&g%D0wAaC7FHkPk>~kr%&_BM^WVD7>RohyurpZ`Tp7w z+-*CN_}Fyo5?|Vw6JVD*I-68fPo>Vh0~A3cO8>zW48$+<&u2^^%>M%gG17U1Pa>?j zGyn8&cmcYYfiJg{<6&PimgyZaaFaqIR3sb-F1b#@GR(=b z7Y{*Jm5&e)JFIxajjB;G z^y_VyLrrSuzqx5Y`_>*Ba?A-|eUrY;2OIhQEPiNRa%e@5@Ko$6=>DXAmkFlsFxO_~ zQc1btsd|Bk(ELEdX|w$)rhvAxWkk`3OfWXaC>VyQQSh2^CILrUOCP_HTQIKE=lb4n z-1GEbn1gry0fM&XR)yxKNSuL8J+te99K@Wa=97`sIcZx5Dt`#e4H~!<^z|s5l_jgWSf<_9#SKG>=!#U3iW+c)lS`y)a0y#cISl6fdPfQD?R>S<*VGewQHbQklHg_ftGG=YJCZY5} z9|H)RzFV%@m*j~upi(0{H_%SX?VXb;b*k@8mrGBsm@oNI&d+X4CXK{ZWO4+LL5pRT zkNHB&#iP~^*viMZ(hNAs*|I{8yA|)6P*MiKBTL|p6u_~xm=9ajCmkAgLpOPv;fH`5 z6q=Ge;#Y~5bVfTYTe}A?cq|K&iG1W^KR@XXoO?yDCW@cQRH8Bp80RRKdpu2k)EUr^ znLp(0W{R*>u37d_#%MP=`qp%$_=D^pqb}F?jB%;$&CS~KM@Fc zreT-C)u#bSPwh9MEJ3P5e}eB^!|L~1GaqRFMb!DfFc^(WgxyXAMl*ifblaw^=6BDq z8;arp>;6up^IbiZ%wC!ad8dNu2A_}Vd~i8T$vd=nyeVi}znldy>N9feZmXJ&$k<7+ z0wH4e3(hDxB6VAxUyn!L=OPZJqD*TGc9pF-$>j)otCGkzo6KqZlpl;1wp+Mzh|)C$ z;y#XRnB8_Viq*=59PwgQAHY5_N~qY&hTp>Knr7!ZgRuOiEA3seB~l%~{{G2Qve=U- zC`W|f^lF2X*~avM3~lB$lCS37Fn1xL<=*v>Ycx8z#3wnum&a=f-RJ63jfkwsS@K!b zurVaCDYLgNog+ZM+Fy|Wo+c5|U*5@KOy=k+Xw}*IOiY`^o-i(3?mJq00{@xrcGS6t zC&@AqU~mg0Wa!g-#tD<~2LFG8Ug+?m2Wl*cI)0z*u-X;}Hl#HpLH^EOBBJJsRVW* zmyPk(>K#m;Ms0lb&IJW);p;4S;=MedwQI(Ia2A2fWfez* zqsh)IJvr-<&t(rt%^9SN6H(bnZ(>{li=PK5sWW=icQk9Ta5^e&Fez1aC3p(LOW+&C z6r`UxZPczV>AypLFOT_~3-_ZpulXexo$^g;YQA2s5WlE0IiU`tV}1$x`Hl{%^jZ6z zA4OR9Ph@8&c9YP@6m%h0^IwIz-bk6ou9B0!kyxma9Xy43WD4Qzl*KuY3a&bC-mOrA z;?c-xDtfioEfO2aC{fcu*{N!r3_^sXiJVHx3mcn~5{tD>OWek9n$k~y4^T#nuep2S zQQk(Gm@7ZmxpAVQl9l0bchj$+b@<4~y!>=AckWGhH=U`aN&c!!X_V~yz~`_UdqlZ4 z4;Fr*mzkTMct?rv89apdbN=BhS$B^@j=EESu!kU@0%zQvDI(^rm(Y#0k5Fdbo-N0k zh1Ot7a+Z)h{d7@~{KhJR)sq%v!ThbsNIRCpn&ZyrebXI*TfFU;LBnTqqojjd-e((gr|As7UNM}zPV)#U8=!vsCIp_qC0Cvx$y z3j3Q?j(!f)w8GgI%5{6ol%6U*=#xHR?T1By17*JyC|$Ef%?5t;^IfR*LPO zjZ+m!Hgvmz0wru~TE{(S2E@Dq+y@lSISP#PaX+A?rrcyKyk@t4CYlB^^aOd**_^ex z7(DTu+#;p6A{T#%cE!Eyi^go}#liG(a=Q}bWARQNy@}rV71>$1*Kt^NIT^P%??99( zyRTUHjb#SrseXS)|C({wTyqjvV&qujIxR-FsN$EXBRwQ~vu)p(bS;y{BVPH2CHAbNXRh`9Y%fYiixC-Agb!X-#7EqKBzr%bT+j@4{!(NzOkd z=N~a2srNJ|+)9*;W#MEp$_W@N z;>b_$j)JfXreh1>xsKl0E3*+5la?uWn>LTNyatF#p*&e{Rkl=5OXPYlyRVHA!A>?V z5oE&yKV~ru>#Uu5Q6`ixKZpszv5tCi3fwbfoorQ7+6MVGcx?%9OTSV&%c|W5MHnR+ ziAf2Zzp)k*7;4^5JEi0J;Zw?Jo=Dv1YAa6kjL~%6F>>qR=!%CrIDOt3)-FnltavVPD+3FdkrT0 zBN}?AJt;V7Rln25cL8%ZR=@?7^#}NtzZqanDnINKPqbJt(W*iHB6*X?b&UmEjdU2g z{>rVfSvM@5=$~}JKgx_8NvLkALv1xfZ}Hf7a;V+#8NcMwjI!>ui|@_<4q1dr4_!6) z51l2s*-v=^<>x})|K_RnNUk@e{czTnLmv&8|2EE2R&Y+~ZMKWd^ynDA^97+Z-ZO@% z0a8ZO?JYy<(#}TXqQ{D`3bj5y&AHP9HpAchdVtmkxiw$Kr!yKnZ_0AjO=*i&6WWP1 zm#;dl6d|OEoip-(&f*p|zZzxGljkOb@+-a&Mqsq+mDYrDRo7t%Uy+G5J0JOE}f|k=iUQ_fQE? zQF+ZH7IBl9=O|=qUPF4)_A+eBMsyI*WRi-)_{x*UcUV!-y=FWO(aP+1+k_`s2A~Y& zyZE`@HjU7{QXpgW^w#vR)aRxt)%$YviV|+Pu1Hhf^w_8UP4U!^g~X?d?77-HETL%I zTA+flm~F3?4aT~*jVYgV(G?E}DiJD>MP=p(2-V03o?vkjW!#beR%YHU<|&RZG$`Sx zLQ>Qe7MmYZPz{BVD9KWnCOc9rLD-0IDU+@57C=ugGE=&CW1BONSqO2zWz`))emCG`?=CEw`ak?^|nwxsLBI5Wh)})gjTnQqvkb}o_pFWQSzUL`Dkx|1Khvm=Qc8? zT6!;%H~H}Q+qds|x{mTVp4M&TY;*L%2Kc?eJDxO*bsKwGNfm}zyK^NdW!f)NoM)q? zmsYsqcuw$_#-a^!^`rX{R?PitAh5~ymObMcgUIlX>~9}K6n?L}Q(2qn!!<{W!;u(-&8#9kaF^%}S~Gxo*?>SE31ow>t)!%d4pZ{TMQD z8y)qwLGwPpv7()@n(hPX$@2C%ZnXFq*937l*K+zEmwDl3lz8`n2RGI9f&g zT_n8`_R0TQ-unh)j~Fnt7ZDj%U2ByR?CeaFILg8Npgk1Kfb=bMLF#uwym&R7kR{phq1mM zIA3d7(0LaSjQ{K%J2bg-`_-$9`FeZ*!No>OI7q(MLizXCn7%%v&tJYYt^l)4Vz}(x1tA`roF(R4~atyYh4uN&8ydLP=S zLmvYWI_&NPL%(uzvY@QEl##5q?~^B0QvN2@6V&|@`cLV!!(ax$_dA1H*`u|iqqx*Z zmX+!i>W`Hk__wPqAF#Wuxb&_xG~3(XBjqr@&K|r7WP@`H`TArJCZN5`Ry6VR7k!S6 z{hpb5Wc>yy&CrnFC%M{*Q_d4w%zvJBT=4}Lagc1{kmVxw^Ux$4cLro z%H5LHjq={0L+^w9%ST4vTN#lD7p4}6a%~$|v% z$XCL94r>`I1}inmh-ky!@=0~K4T?%JfM2*uzQMzXX0EOG^zJMBkHbQYse+O}Gnn3M zcP(@lgh-vXfrTY4YRG!hXVE6|exIr0fBkQ8@ALiU#^xrtNe_y3qj}J zWjp3Ty1Z$TQcfV0TDC!rh8FYtu)Ft-)s6b3MsL$o6%K*w%qim9=q`n0#th=+PmnH^ zoy%3bl}p*i1GgFXn8NC&A3x-v<%M5$nwPcfYL;euJ|Bx@s<>P16J<6|Z@+9fSlZc) zZIXI~g*Ixiyr!jt-Jny?{!ccoUshLF_YK|GN4~y*M}|g5inw}Aco@Lyd2S+xo`OO41ul-un_CWg0g|PPfAt=M+YVHo3pNR69Cj~8zW-J=+^Be|n$-Dr$B+{V zI95%ffGkTwx*{V`55@|$GPJZp9;AqI|1R-F4q}?*?rtuSK_UD4A&cP*2!U7veF8)8 zzdw?+bNuGdcmBGq!zfx%%*+fWc(5nxjweZ)^3OdL`>{t$=Wj^E|J)k0D4S(5?O;Ou z=U2rLZ_f>Zk?D|v|Ao464c(tEF1T+J2@LxzMn*|bzmJ!=n<_M2#I{!swsB_rdv72I zTL7BgSYKRRTt|!9KPU3nn0LUi^3kbcj#vbIJIQJG?!1zg$4;Ld4{dM=Xv>%=T(For zyfbCQtC=|N@aNPTZjruH`LxAwp-%X}oT!jKoj$9}e2wUftg z?OlOfhD-g@;$m<}$c-Eb^*Ihp`i+M2RNj>DsE5gO(~RnPs;g^FBXGd;^T|E)pvIP`ClB81}e8!kxVp@sWK%b#W7p&U#Jrh zZTFvoj%kwD)@IZK9seb-d=tFzz|+%?!-d+(^*W>tAY}as`1K2wgjuf|h(*k8V^`0Z z5g8?aTe%Ir4 zrKV^4_Xzl3Yp{!4lC8@c`%STbrW9lBp@1ZgMyMgJG;hYm6&N|K*LdOG=7yDj%5*8k zf$`sJiu^(?ApBqZ-IaHt|z9XZ((xB;MQeN-LKxzgSJOkKAh# zdX0c12Qp3#(88>|WqCWhkV&I_#`3Sfvg4c|Pu`6npAg6ucC45AQ(=y^rT!P>YSC~0 zP}Z&jG-<46ir)Am{yFhqyU=aIR~-3-^;$xjq9GtmHVbC~O#Wzcx>()Yn@y+1W0DU! zlhBKc7V{>BJgGd-q4?b8^Ve>jopA#$e;MY%Vc?0=Upw`m%Qc_mFKV45-df8)6%ILW z!07Joeog2;WWG_>{kpGAho6)g14n+L$DP93pkNT`7XYi_`P)98E>9$@Z*Pv~BaybA z+nP8F08rIiopM(C?4g$>b9gvsZ*MOLwjF?sB=&Z9^CA9WHb)BK*edm}y>^U^KCT@S z)}D$uM)xlOxIb=T+v%yauKcW1FXA;&8M&ekz1d75?)@|3{jcf9G)a|heU`kOzhCaV zA_otGe7ow6Y)P~(QSNTBP0v#J^@D)78Z)v4pTX@MJZ3G^fv;i~RS=D8ze!%p*x60! zsTW7jXZd>v-5sj#_z0zb0PA#kc)iYeq08?gk%F)OD$B9AwR*{bP22`q(B=4Xr zv);_KI9{(hM#I({d6H)2=lIj2O^<2#f(N%el*T2Rw;z?tB7Q#bzWMy|(q;`Fcots-Jd5RSYKSot1WZ z<&5@5?X%5$f0p4O7K84vw~V)2J}=T7j=!QW(w=Qpi^5$7O)%eQ5Vkm>GN>|cFLQk& za5%1rGNE}QWkNK!9|BNrO4S;Usob_=7b2O=ws`mr ziKA$jKMml1PvOaDgIdW0S3*M-C-+-cz}Ii9aGPv2mK-TO0Mb1I;suR)boyuQivU2k zMa{31CO`!P5=?VhOfv8N1Eb)o0%E)axpk1-;1aUZN%br3apVk_&t1fp%{T3~+iz{S z*wN^>0Xc4dyPLAQsXgiK8Wyv-@`!owpSg2CQ~P1vbu*O+vK5wYaixZHHdznZBT)!@ z{6TUhZ-1=pL}KUAZd9gnPZz_+kiR-f=RtR4_xOnv(U3&c6~NUZOCN&pGySca%Q#vZ z0iF(&+~_%2Y4m-}1WP_;yuf5&UUpl_QNQyd6p)3R!Mfj}6x^44O&WocfVryj7r zV)mG>esjh8>Sm2(WdFvoc(C}{`0=mtl2*mc<54Vw-5*JA`OfAtp-5rhazbzpckF8D zmr0Kgc^nEZn~n`PC%!L}G&%X{+>QYGQ#kpp-*fi}G>rCynwLY5Pg#o_P%Rzu{#l{I>aUl}tvDRL*J zVAXV3lA+a^q~!H2eokYJ>2;Q_vh`|sFC!Y<{Md}l0=IukuQl6Joq3D?wg$LlOS~JW zp4d3=qt3)(mCj!umxJH=aWezy#EkazoA~cR*9d&TyRyGhBh9^i>2#BDD&dfnh(p1+ z50m1R`a9uMr>+LB^PxH*#^Yti^);Ey{kh=&Cc{$}&0rc*qS#TpOmFbr(AKX(xQ~Op zkRE5sib*s3O3M3WT_vA_Eg=pS%QVOQw##tj{s?jGuDa)G6ujZ_yvm?h*?)JlDhBCc z<1g?llBc?*lw; zwbeasm%e3J^8@Q5M`nR1Q+=p-2Db*>6O9?KOuACr7j=S^ruR0BA0!|0;7aZpC9ZJg z@}Zu%+*7HLmJr~DU5h5O5x9<1;Vwg|81#Oecx5M$1$%Av&`8KVnxumKZ#A72;+Yf#$Vj5e=u5Q)loLBmi`8IQ@g}g~Xekx8 z9<;hks+Ah@Ql$~uz{`GX(mLa|17}Ek1OZ6 zoxk8k`oK5e(8j63vrQy0*;i!)u(@~9M!-e9&uTW#C|1KHBh?rsxNqBfIGX@5#m>Ez z&Vw5nYC(b5YxXXNv(~S#47oY77jtA*a3#WHq*M5QqrCr+^X7n%%WE#}xLmei)%(kb z>N8Rb?c|yHR52R-SI$*q;%td&vp^6VvExco}MY<=*lmQDnJ$I;4zgywP6u^=7nyr7v4#OyER z9Tg+U1+@ua>ALU#4FMQ{Tq%V}R-+YZ(9%3qx4S_eY=y8lJuRT*);RvySZ=Zwmp9}k ztx}Z*D?5eIhU@#vhsTTN*rcI7FI5AJP;Cw)v98}1i{5D|Rx~AS^pOs81Pow_EY)z- z2G$t*W(-XUW^xkT5~v6)*C>H9%hQ$#__5pe9nx)RUtfYe-e7~O)gQB^4P%1_&9tiL)7IAXk;f|K-x4@_0IOCXf^soE5aWAa zR#iQ{*HE;$9{}^)z+b;UYpa#zLXqJSm-+{!lmGcMPivg~jnH>FP^~)S|C`6x0Hum+ zXNd_<8a(Zr%er=)e^kWdu`=ruWa2pcdV4nA^hSl|LqV^wU7D$TMZ|YX7^Lch(B0-7 zwzvGM=YRrT9~z6it=|i^oX)nr!`9ShKWBbhm8%YY)}?b(`g6?UO_T$G*UR-l@f5YW ziJ3iM%97!M>Zl7I1 zX)5fn_`o+$ZVe}o-vv2SYAKbvv7!Lwn-L;(le@3P9=u*y-b_Ot^PA$~WSi%8Y+b-Q zCP{?V1Mvg|&v2OYQ!2U|4~R4OmI8?KFk)v%BMO46s~&gRZx!IUHEW=XJQ;FJz3W%Y zrMOrW9Plh2F=nNV%m~+N&G)@6dQ;`LiK`wmV6Ce^pr@db+}|TNb!m>dry{rOMYB^w<>-0*q&RY`=)=ctoGxsnJ}R#YY5G0s-68dmhh zUJgW)M68tU=2R-1z+~;Kgs`p7(Zf*QigyWFdY|8*Be;HZlIdO$v;eHl%c@K-zc$V? zOOcV=A~51}%(J33d}(CKNvlKU$*kr5i>T4DpxuY-q4F!QKMP!AGf+&51yY@XnjhY`E4&m6IwFfZ-Tqd`rznZ1Jf9w_*pRN8?(IrdzNYDm%4t% zFd9L<$ZjJ(pke30^r$T3isA73n0i5l>GRKd3|ncsyaOjwL|yKQIRFsovLXf*tmAP; z94R(bYX|p#bic=;!P*s$r1*60b{hk-GttD>P4~!{8@V6p!e3CV{rXNw=zD;gWpB8i z%??6#Hpa83n7O;gs{7gOrlp6s-^En97sA+)KHz5aC@whrV-s|L$+x~xT7n_t;CR4q zOqrAYA#G^=Cw4Pj6ZdhtmGv@5B#L0FQnAb@Kd+Y4bL?FGyd8o26-Dek&x!Y@ z$4b?&En^29+-GHiR`5TCdil8BK2xaBHoB4J|FLwe-4vxG6ny#g_3K0RtLXepwSn5L zFT*iS6${wx`QHhnvso&*sy9WGe0wF3(If|+*|P0=(Qv}?Vj*f6-0*T(zR=TyZ9mD8 zd1;Z>!Qn{!+*~v2@%_s6)(5GhvQG8aDRpZu_Zf4KZIuY_RJ-&*M~Marr{_iOi~Q_l zj#{K$F-zA-a%YE+CxE4Iig52UD3sDRMv9ZPK7_-35mfA*-|556ap4$Mn?qh8>Ob%X z3%hM`5(A8&{=Mk@GVXx~qHncP^mGP`E-F|YT~{;9Zu#}%xV)Jm*DL6pVOeYn+vUXu zo}h?s4mW9Q!;kzj9diJ;BWHe}wpQOxa_?R;Jy-9+84%q{w?26@U(?A#kLQj&)#%=M zLrKS6v4skiQOL~$9$O&cydZds4ohO7;hFA(T3fo$07v0JR5JT9Ki4M5}Z z$YwlSBLXsON4qYQ35+pgW(CAqXe|RJL9sCyu|F~Mjl=bB!*~f;w*MlN>U|+x@3$x*1fGU+r z8X64_hRLz_57l2Nb}q!>K(Af~(rCk#s#plA+~gMhlU6d_r^*(CIi!APl05AvFd+L` zic5MmVt6PMmGx05ni_}EI$yJebDmZ)tCto2+`}LR-m>z{XKXKTK;#Y6mdwh2O$(U3 z+k2Cz+VLYSNshAYo&mFwo4}O16}m`VW5yeM^yy-E-1TMPrfY@Weu2Qa7XTee6~v8O z?WBFTNxD#TO-@{zXSPzxqBBIR&iz2FYf~F^#4*EGC`~8!&K^S2BdZ%$D8lq;RZ{&b$X>SQ*MG0i#5LB2&2a=uU=QlEA7#9+n_hoiE&GQV;=VnBT2+~w@_q&pv>+uJ~hD-u<;E(-wJ$7IIgmp~|ey z0&-QydF3F}EK6x2aiu;Y=-7VBO8hO53NWhMQ79z;8d%|A*Kg`oxyG4yd?b8g^UJLl zF&M}mci)8iSxJG54C{J!u15cl3uO=Z!;C=R2HN*NXD z!dL+50s_*lAYDLuQ)yBoy%Q7>>C!t<>C$U}0FmAkr9%Rtg#ZCUO$Z^$i=#8YZ@%~a z@zz`Gt#=oTdvoq-cc0zQIs4FY3_mSNQEDB0X_?f*aQ)MW&9l2@_cgXUp60Zi(p~-D zkoye3%;djDT3)G`h>8R;Uw6Prt+u0LWUvXf8^tCi+f2{U-S3)*Exh8Rw-ojt@6s`* zC+r}S_+x>eFAI)XWX?zrdyu?{90S^qoK)A$xCB9W3~T<#xvWZB=9z*m>e#GL+wnT> z^9+snG*e4Wgj}MQQF9iO$155Y^y$5q8~0t!?qpw9j2>%6Jn$a0y|&uTmL_(bMR8;9 zT)o`-r1$skTFRj>Qf~Eke#F5NTID&11g`^0A8=wYh;ddf4%%`Qt=l5bzGF942@%3D z@^c=&U_WPfyP@v<)*NqJ6s|WEo)z4%KHbLjDBLwibyctC*7Y21=S%Tbr%hmx-1Dj` zdRX=1ix$o26PPRShhoj}Zje|oKR1D8ru4zr&~?W%axU<-E#8!7@b!=u4FBSR3UgNL z+1p{{PEBj~*(eW4NXd95134NYU%kPgvNe^`Kw_)GlLZQpT+Q~aS#cSwfv&G4+uw|- zbcFf}!R6KmyKN(yz?eGkAz-3T9dwyYqAnb5svZ?-y$_%19fNM4a5WUxQ2j)$52Xbo zpZ=xPYe4bl8>*iFwzB}Ps-?>0+&|z9t4+MBDTJ`vxik;YenVqq2v;aU8QHe17eML zsnsuF_to%sbQV@^I85gonzC|b&o7wmJ`!lf(;r&%^^8fJ#1Mv2HB$lEdNw6@TPnIu zWBcZ@aP~vBo$m`(>uu$HDs}JnC}$Ke;MyL*-@vMRy2(RC2N;)j^@yDYn`hK2 zEh4^wS(FkWTE?!V{;005VlD)f)nH2hC&Y(!Yda*>$K%n<>D>zo5uFhaf_8TXV=hcp zEf42Cu%!qnDVAJ$6icUe?zU)HqLv){w=F{XdP0w7Tbf&o`o;Hm!t>uZ6=>IVzG5%Fy?TV> zo3sj^ZlJGnJO61QTw>>yKH&3pzv?jrgO;ayMybk}1{51e&RHhNqiX!s^|O38G)TdD z-Mpy5=t91|?ppp6c|S2w{Q&M`0_?q@jK%His6In80`^onAw^3(Jy#1mSBu4pCxt>{?$f>rVLutJqE)k8~?pa6m=VfB1wRB5AX@ zvhw}9P(}l zhp2cZ58d6gX${b`n$N zO+036Y{8=%DTgmjKJmpAOJF+b+Xk|a|H@}*0Oj_x3)#obbW*oV`w&ip&Z^4ECTA%9 z>z!?x4cj6utlEKJC3fMTp2l&chTba=I`aO?;K~#jww_(&X_IlGdS9~`Q!){FEnfvO zY|A(9Q}Nn@up2-H6U9C;cTH8=nT`|;f|+yG;P2;y5x_evjVH0IrI_yI_oq;|(17_-w;69v3!US`t-BqohE^lkePcg^4_m-*&c(qHxRT zBm6CZ!{4gbqf-Zg&<*ZepjLFu?_H7=^;c-twZ?p^B|HIi-|4OJe_e&JI{%e2a%O*` z+gC$c8X-}$G{aS&d2~5BG$eOctWsIVoe?mYECKzH^U6!7cR6WXW`KS7mIPC|M+nmM zm9>NfiI2YMO8#B=`U!q3gjMR4k!6|g=;GCd65bvbkw9_q4f*RII!Ci9Ke z1_DD*f@S-*fv-O^>pm$;c+Qx=dr4yM302q5D<^rzE906&*F|HSoljl$Xzh@%_kA4`euVU%f|sbW2U+) zY=ZFm(hWQcGGRQLxb|7Im%*p4?ZMq4>Mq%2t1|l#nU!;bT{C~R)f!Z5Kj5jG#dXWK zLpu+;`^Ni0v$R#@jcWVx{n)wf2iRR~Cc&Gt(ncgthp+YPk(Ek4FO_>ABp%0p7daG+ zr0|}J4SCHHL>aJ{P@cPO-QeZ!>uZ}OQgihZfsvW?_D*OJRMlo%qPK1cXlq&b7wvF3 zpfqpE@n6#FAw$*i^gB--H*vDh>aVJO553i+xLbC+#GlivI$4+{@y{|M@&r{T$ z%V`av<2Wf94WXmAC>Wt@@NycUavXF8IJY;)Pjr0|Yo~+ z;&qD78L8c|71_)Cx9H2{7W3=cj(mq$XGt{YwD0qwhaj&2 zs~Wi&=u%kdHnwGIq}Se5%{e^l!`Y4(d^fQN z4Gk!&vYmo|x~k{K%X4eznBzG_o+w9Jejvyb|3f@f)dsGJ49oLsgN3*=DX$V&8ZUMo zr@o6UGpkE)^0P<_}g^?-G6>G8z zEnb`r+0;r4p3ljyLf(;eD1v)W<60D|He`C=SaHasXHD1k(pc8~aW27>%~vg3M{kSb zQQgVnpkpy7)?1m6R4bOcMbI~0e{UK*zKo5MRsUA2@zk>*3-cyK2LsLKF!n?(C)YT6ji>qP2iy1jDR zf<;#CqgYWSI6dF^)ow2L536a94}G&^>hF1A4w}_-n*TqM_aOT5IuEikGS-gZ&OOZ2 zTa#E7y(Z684n+?jZqNG?L%J^XG7r?dt1EW0 zOM9CjDh*F5rpno_XDoUH&T z9790D-cIR_<-X#gpq{;$yxackVhWdsk(YcXfvb{^TGvin_!T!E{+^haNONLhJO|D^ zT&eT28xzniFv+VYDb$C}WG@X&+210&SO>iyecHtEfMneLr#vVV`$BqJOB4#rf_pr8 zbli4mx<{XN&9m>-Y_SzOozKLxBVU$$ra@CD>9?K6-wRYpxtH)F>CG?X7A~ap5jRW1 zByY03R#QCt-Q@j<_uYZlD(gj|CxJ83@^}%;_(t3Mm8-YfUOhW^qpBxtYtX*3X}Ygi z{tw5r;TMPYKrTN(JYl_mW!fVx_yW^Sccs3fIO>A;+vk52cucXqeHDKNk&xWn1-T{e zp}`0pw(i$3^vMftbMdUb8K&xE&GnE(bF&YdfBo)#4x|5B+R8aFsoJIP>P^*u)&g)t zctU43`MTWPxiEHQo zk!ic+FOQc1v#V@Vbs}3cp%En_zKoQ6zuRy4+}n1>m7ez4ZO#7U?D>wArf?$4ZAH6? zp)FGsEaH>Vlse;uevI?qSj~Z zyRDXu2z~XjFCG-(IO#6RO1o^ID)|;w$zSzKNoqZZPp?F6nai4{`f>vwDo%^%V_|=4 zlStXNQRGzO5bVZW*^ET(V)~Y8c=lLJTJiZQ_rMpX(q31of#XFMktaEN;(ja8ym5ES z3x)@Lu1Meg7$F1Vc#(a6@GIgU>afD6Nv}`haD`vguQ5>M*Ob(nuhDiam;H&>;^)7x zbosG0wf@v>Z=(DI|CLXX{x^wLgnh$l`_t90aNM}>`Co;K2m$XUnAtxQ)}~585fASw zb*>+5yVUQ+tfsH;TVgNGy#i%TnA$4VhnaEP4j}Ar(YtG(^e|0%H1=NmfF+byS`VEC z*1lXn%UHEc!8v(J6_lJlh>I#y`V1?Gjk> z3+YY=FAl@U%&MsyBO-PUaBmU%Q!;0E+))M`@xuZPE12{#1Ojeom{dEY8GW#Z!4UU(f3}`U-U6nZXw^kG?6TDUx}t z|61bIQHPVDd(m({-#2JuR9#GQ&F1H9pw5W4sN`z#-O%fe(#3bOxe1Ctc#Y@O&#fS> z6FvWHl-@+hx4j@ziVZHA-HsCDGu{)G_(aGzv z(r@8Aa??@mo-&wZpyb7iY;V4^^%Rz@6pwDQ({+V5B8o3k)*Io9nK@} z8&#=>sE=nr(fW_n5b@m@Oepy-3-Umkw+ZWy#w1tv4tml<{Th317&b9AYT z&Iln25pxY6wlOXQvc2RS^WLKQTk(vp$5Fo#<0*8>+LCAzr{odC0-!qCfBjne*jd)b z81^PR>4kN^Fh7Uzr|}0G@*G}_l;4jys~=gd7zAd|hTwTTKP+YO`Zs7`f?#yA% z^B~!yMV#Z;Q2ubNR3-uuBy0kQL}|j~pFguQB?UgvOmR{J5kjAlA`Yr1H&Yb56k=!k z@~%hur&Vb_QrGaUVK~BMT!x>UDDm#{^y+a=Aw1@lSZ?3_0UN_eG*KEew)Jr!TUA1hWG`OW+;RJiKpW!? zaRr5-0jQlo{EWOZ@Gp9Y+-tyw4c2(;u4+etT8RcaS(uwecRdb@A*De1WOo6312S*D zm*?cNE;xq;L_HoJFN zAo@rBcDyB~IU93lc6(-R3yPu~X$(S9;>&ntbUOJr62bn@gdEA0LLYF@Zh~1~CkXbO zVM&hKUz=<_j+;-sKX4gSDXG3)&!_G&>J(KQ0{v|zQ28RC`fq2H+FA`rfrtTAX11)F zwnca2L9boW=kf9jZ?59$s5~ABm-B|rY+7{T?ACc_Hg`R`F((NvKN!P*FV2>bTGqA) zXPKm4C>}}_yZxDx#gO>5G}*B_OZZ9kU4^=Qn#{1nY{yP>>tY?%c6Hk>{_c_Ivuxuq z+>15QIdS|=58D3j$h?dA;+4)QNUN9glG^oWbyn1c++soAu(`aw(hK>gss$WK&$qHU zZ)Iw8RNK~_nwFQ@*O*n7W_KBh3<$X|A{-HTDd-h*mrZ6=xcm#L9@=UTWku%axrJ9l z)EM(MW==B10k(rKfEuMS`-tv`A{QqXr3(Qyv6Z2@Oeabyvw<&yTre)XE(a7z%%-s(60oPxCP|^ zOC=-W(W!%p#Hbn1&w7I$8O!?7n&{!`O}$W5=HtGs_(;JhNGK*j%U8+e>1S;=wOeQM zPsKj>4xmc&O8D7+xb;ljTx>2=f=Pfy`^uGoGQx`9Y;jJW!2 zP*!b=|2z{hYZoRF)C}yn(F>G%jkCeR@HHu;-T$`$waLOQOqV~UtWk8^gy$0PI7dzR+Y7qTv!_K&u1z;_ zC7iqb$AE5Sb4SKFQ~-Ql9ZB<3p-pYUf)QuK_hVGRuury`oO~^devBqn=!f(gR)%b| zO&wvUFcR+}?RV7vN~9fgcv(Rqi$MX+Dr)YDs+z5VSrR_=@|nHH_5`-H)8!d;v0iO~)r80h9vQiX)cDiMy^h;FUUr|! zc5@?cSLYh)0-#B?*6x$}9ewP8@Z9N)jB%IgvYv;!=7RI}mE_iaDZz>4t8L=9v6k=o z>85SpM>W{)?DnWbx1#>nWwbw@``s4s8k9p(^#)A`0l-OkMfzsSK=w(B(ULU<$rdMB zAZ65qHP`Sm2;GTpyW$Ka!zTj4H~^ufdv?sA>-k@pg3^p%T? zBPD;o$oleY;NBgVjMaMdN2~h52wx3SIKUWQj z2UzD0RF;Q?+xf!E&HLZcqPLP()djpYLJP*t-?c5zI|LN*{V8*ijrZO6V+II8?RizM zoMFI)qRt+n7quRD#4`l85VixGi(}hm4>>inE)pHFD9cZFSt0zjepufZi~%>T6mF1b z0%AK@gU2|W20df$%TbjgnM3$hO^l2hAGyTiLq*a*KM`hmv zieUC9vCr%MTX#mtTEh-1q!;wN)<)}-&7zqq&Xorm?y>Ukg6lVDQ^Iq|>3t2Nu2-WG4?Bi*t4g+F3U(TmKLsDOCPGUSvgjqq`iBO`rxXq0i!vjs)3P&-f~s^@Ls*AHf0#LCeDzMNcM=w zV!laAbYA0K8hLNc$fFRU;zp7pHTaoLVl8HyJuDN`z8j=9N(5^oifwEUxvkbt=I^}I z4SeJ9AiBjG4tAcDd=Q!iE{i1W*<{FioUR&oeefaqoL_TWao>8whk^a=#Dp(%XZG#E z?3@Zv)h)iGHx~e~m6{&CKa(z@brbaTqa(8(PdCI_?LMLQ%E|ku7kD>CJyHbMD!0oq zjfp1EqSVht2}Gxf(Uy`o(Oly6l3N0mDCs*}mx5!Sh<3l-D$ji*Ham8Q96XbK2f97@ zyfeW;PgOT!04L?NCoq^})w%xF7&#@p*5Zo}=Cj|`-Z+Ya)-21heKfsbGwpqVe_Z4FiWbp`={2iJnuJ#!cd?j8JN{ss zWB4RM+RXcQPQ`x0(v;^NtMdX|-*amahxla&caD9#arG4k<)tfX9j#|xP?ZNxE53C= zFV%u9MpO3_tcUu=PPN z3W|A!GCY^f9-EoWS@d)qqP?R1b#|RswB+UCxldaMUyS~b<3Mq2EBVvQKZ@)z?|!$m z8ezA=-C(0rbWGQ?>s3*Fq~QC>IM9$U(0}1|?$KJ=jXPEYy;1Ao{*X)6)jzpe)NSQD$D7_0&bhO5>or;UyU7@k^_ElHO>wnm zifPS27k#*LV%c{OcYltV#~rH`C99W5qV;;~_(xb18;|@iRw{=5*ywN5{!r6H#~$&$ zGAHW%`T6B=l(>DFQqjfSHETr7{{Fn}@Ty4ZkD$n~_Y!_DSaA0f-f=3w-qh=wWZKo6 z?(dd#Y5HLPm*Ux7@f+Szk1M?@^!5v%gYm4@l#${G&{a^mFMO)z+iHV}6VI#H{1SwP ziNe13dUfNxhjKP5^D&Z&TdY{+oMK@+bm=m3Eg8w_#rRfv=Zu8$;SEn`o4|Hxp0rc4 zPq`z}&0FGFTRz$mjqzXpv?I#+jPY&#+FfOkX(;98??bwd_Pwp#8J#y-ojY5AB0!tw z=b2i|7jH$dUK<|k-Gw$LdL;fg+Q4|Ca&%n2TFqJ#%VD7R=a-FYe)2wygjg@67cNLI8N7QPw~2;$BFY*yQXL9)ddNQpCq}7 zszH9dju>z1sS{}}DKo)DyV}TUjcbh`Okc#k?bf~A(D1b3k^Ung=d%qsBdzaWLe59O z`!Joqp>AX_`=#XD>_yJ|0t3Tj@;y-v2dOAd=|wU=%Vby?E{_QUL6qQaUaEvvMVt4P zJKur(y$4x=C=}L!WcyqLKrmicbjC5_jB?}wWC@&jxdr{WRWVz5ZC7JRl1V7Yu+o1w zc}flhuu+6;*J?&vlS9;Ob`4ZQ?1r;)P&vL2tR<|KA=@nunqyBeWpN(b7Ej3WRX$3B z^&BZ%YKNMX{m7ia^@8B~f(X%_CX(s;SMq-T$e`4EEe_L++dxodLKV^Yp|+y7#cWH<^=B1kPm_adFd}`k55#oYj%Tay*%XTt zYl`g9ZgnBlq}HImb$QG>fxV>gId7j$?~5G1Nm59x!Z@J@`673-bxczzaBDWle_lG1 zn({@QUu643?vz{Rx~=ZW085(%W((y!a&H~=!Z)uK-Pn4ZT23Ja#Ozc0uBmO@zDWvk znX4}e5TOP^93=Cku`28qn`Fbodn!lBn2anr+`tT!?D7Q?+mGiC%_PjuIv#~WiU^S` ztF;ew;W|}f$!>%h@yq+a6&@=40&C}nIa3=dt=sMpK<~zPFiPjg?viR&mbZi*pH8*| zHBE-N%2FM+VoBKP)nOC1w+kyzC4HY&}$~x@?w2H0E zm#ym7i?SuWhohq_OG`=~H#5IDf+-TVhjg3jziowCbs-4MG zbU&_zveB0!RJL;s!J?a9>Fnns;2|7kH|PAwk3#oIiJT$F%$&R6D^g8!DN6o*4~RAd zt9`@+hT_fh2%!FeCc+Lvi*Xobf=kwM+{|-3M+^yOr~#!1MoCqeFbC-G#X8?vW6 z5Y1^WEsmi&BOU2eDnGb|)?09?upnhE$ZHIo{`+f|tzCfu9>o<>AGL;tb1B++lup4- zP3c$Tvg<*U#O4FVF6of;!@A*NAck6NvE39*IBm>i-c;+_)Yb3ZM(O2|bA3o@98xoD zZ@n!u2Fk$E`xlyde06q`A-uNq{`z{|A2vhWeK#cf!an`8_q->G(M?s>?@FsvBQTi6 zxG^Ei?_~q0H!Mr$je*!CB^j{{uF(V2-6T|mx+bY!zE^706k1hF`|I!8 z#(;;+LY7nrPm3QoCjchNIqy=z<3ah<>_zhOnq{Mxavz`M90fnvqi|=QXglFKNs!Hn z<~%+QQ8Rv3B`SM!NZBRNJvJ9i&6UVvn=-k*>0IEjm-Mj%id%0u&5d2=u}9!`fI)og zN#e;~(v{kIl;1#Oc#A!LC}9PrN|E=fb&YPHEsO|Ln4rp6bd?x-Qu0_FaaiWTKzhJH z{Pjs~FdHAb0z;|qUQ8b~Vutz1od_z1Vp?#}{xh!}ME1OG|6)9xO_%H}cvX543$c4aanqe7i&L^xM#e=%DEO%;yB5WwUcWum&1 zE&emH91RYklx`jQmt|Sn(*^1dP`u?l;vm}6@0l`8E2$v3&K2TBLdxJXTW)ioJ&_9Mbk$bsV0<1-1F6D~sMq+{hS;#LIlw`~e%G+nQT+{;A zX)Ockm^i)OE5$UN*sUs&gV;s31du&(+ z1RfY`5M*UCcaLKNj(0JmtKS6okWq)N(5b@8zRtkI<~hvDuB{wA5r_lnOqz>d(Q;UA zhyr6+45Mq2%-IeR5lD%R!{bFQr`(ZHk5D{m4D2=WDO`FdeyesOOW6Rw$W0_=yVxI$ zs16;g+hl~}X0EdHwA`C)_Um)4xqnqc^^Sn8O-`~*eCsXs%DJWF7u-w14Ic4MHcwH@ zE_3j+7AH%{O&MSK38naf)U)A6&URf~eJ;tGvJb|LksVnuor&kqKAv3mNWURuEgN*D z%@4-m;bi?7#8Z!Y4>x{R0q1zoI5KHf1>@62Nah#0rpuV?!DA%62R;$!+0&aU4 zrc^2>z|LCCXY*MBy>(Sz`NQT*B;WAW?eAQ`+HI-2rH>f9fjA{jXk$xqT*WJjI#T>; zu}#m1xZNp#O%oft#QW=9@|$n2d-nB9dyN*kti0Z8gdGnxj%F=1Wo^KZl4=9D zF)biJMTu2PDFqIwT@GWf-I@#^yv~bMh_wL~;a8NDK-2p+HIP435+aRnoh6$Gni3G&5y#;AIR&5ts+yGwct@_Z#@l z#a67BTzoHN-7D`{XY5Z>jrYVUvxb9rN=nCy^7Wg@oCaK$*}@-|NHK0EE3rojDrxH0 zUtmS_Y(~$nrh>Q9DOgmFKKG%{5IApuuTLp!YEZVnw0O%ZXsz)$BByp}PIh2U;Z9YKW->d*08>n-k{-w7BQbozT&Z+ZauhE0H!;U6>k}IcuK_=mx*|b7==Tg{V8_w0XiDLnRPI>F$S2NLhbg`L zHy*9mU}lG!>E6cMoF$rCK#zMf4IVXJu(8?qhPLdHDYuCata^Nds&Fg|C z^W0Q&m6aRi6O zT?q;@#XR7kW4Z1(uj6j_rK`d<(l%v9SMnR%M*Sw~o7dkUq}+@>W}k|Je0;Cu4(U?O zj?-^AE$m0%SRXBWVBJQDRytZ`$V7a85J*7WjI{P~)}38U-XWQISjdL?y6|O5!rfD_ za8(JDgv<|p+y26-6ZU3Bm}t)GLzcQRwmE~Rvt^+KLd!VOv;@ATA}H1(mOYBV4Oig; z6#3Z93&%X^rI#|erH|RUi;Zd*(*KwscpUSy`XH`C0}fu72aK*+68nNYC$94qd1ua> z`GnsSVomyN{|=qA%VIx~9GYo^@^z{7zqQ`F(M#L~(9}bejRXid=<;EILQTGCMDCGt zLY0rQp!asOR%P%>N4ekNnq}xzNb_+GOH$+Ib;V~dCq+QXq8v0wYeL_g;H=wm_~sZc zI!D&8Di|;(8zZOIx8((kD|W=g#Rou@Z8tBO8{46o+S7+cZ{(W5PJxv&RoHWKq$`^x z{46QYRD_*Cydo8;BVea6#i#kgD{~Ot5qUl1LIOc|KyNZj0{^r%xIJj_Uh~UkX)j`w z38s%gy*VUzB*&WKa99D>sWRzX{lYM>p%aO&n-9gTtc)>_2!K>L*!E_tKmC+I`h#-v z$}GyQ&brFzspb%5L-P^2pcSKO=7+K~PTG6t&jaL)@d!0V5hOPZEa82g`o$HV+t(8u zD#p|?Q(%=3E&}c8@`YQYrG4jS?25Ofn_RYninap#>^GCk(B;W+cpQs0D5h^%(<9q{ zG^ClSj$Ex%yV-g_CdiIZwykFb&-dD{AYig$9EzS8=ZUu&4?8HjrQfsSA|3{|p{Pfn zJImwO=l182do=xYId(?K38h?CPMyo4(%i9aDtx%~<86!r$dBEN%IY_F2T@^@TMTHw zP0ch*+a{~8mh9^e?V>1~?fMxOxmm1*t+vFaIk48$Fo79)$C0|STi%L0#W{N%<94Xv z3!c8EZiA0G!M-2b>z~H#Q%WJC-d_SyK(5hr6-;UIndt=nGV)D!5HUD37#7luEd_hQ z+Rx|SB>T-umL;f&f#+m}`j|PI-Ydk6`sTXT*+Voqy@-6$`Au5JoX5+Svd1f%P~9tn zUn4f2ny?!@otH%W%zxVO5;e=<3|L50wGSkT)ei0W_p*ZiSqq?Ra~%A~-!g*s@8eZg z9gs>$qKi@-x16}*R=r^x!xcGq%Xf^NdxhsLXaN)b|DxH?F8Q!~h9v{zB48bAcpf~@ z)&^E+A$y;TRQ5C@O_IdiU+G69H0w5g)b{lF>5i$c?x;)bcVNT3)aCN(iH4bjNwC*k zyv`v~QqdNQQq13;mi24%FjA8Rqu(eAp4y2s>5o;9AMWj{8mvt}5%a^LAOj{d0;R{x z?dvsUotd=_>S|?3`h}KbVR=>8`&x@6z6ol7CO1=m%^35LZ8B{5gL%4i)qo4TTVg6R z)sLBn;3+;^ZdMfpOE=or6z6SJV-6xJHe(`&q&|~7rU5|XUy>oln|WufS{si+&3j+3?>`yvT%T!vFv|+e zkh2NC4Q$0^vbw!e3vC@pCoQ-vhErEh7Da9eQbX5fE%&XRqD9Ww_a)LBP>g8iN_&Rt zoQfp1EH9g#qTjHvk)-q0>muE-Ve%ACMVejNoe5J9hZ)L(qZ-ftj@dTaSLwtV8 zd4-^w1u`RIsXDqoJ&iMg${nbxwk32O%7e6utf+#WWxtX$l3;b6iL7ioQKga%Z8yyF zX`Gju<2sfJeIB^2NQ~9K>H0w$*qFK?G5*;K;yd%Ii^=dNs|s0TF9OJpmxj|~%uL?! zq5p;Jq9a^lCqtw8JKJLN&lU*MjbHF?(U1^T0vWT%2rUV zml{jgAZqV;eRblM9jX|Ql0YoE%G>?rkp05|XgsTR*_Emxgx_YSuZ{bc8yY(3&Ed@b zD(xopymkm7zrd&Xz&hkH9(u$=?0L;y=te($O7#A7V*%>}vbOfLPp4R@jpzzc#xoU-CMV?0s|yOmYFt2zhP%K}|d0$}wiT zZ8H!Zw3<{CB>U~<*Cpp>B7dfNh(_|T6%w-$TcyyXv0532xj~mvY%j}2cAe*(8~1sV zUF!x+canj+Y)G}^bNFOGsfALPMGR{-8*s!bYKnfr}Ypk}zB&;w~cq7e9 zyhSddwK@3R_{9^kje48y%m!2vV_x)JZt12%?DNMwy*UIUMO#JapR-=CbsFAJ%n=W957} zf8;{l5*ypYHhz}$5#G3ci`(0|byv$=);Oj0_S_jJU9cM06}m8f6Km@{nnoVcn3|e8 zF>9>?VdP#(IuZ$^TW0_xh-v%x^n~ zJ05?4D;pysUD*q1t=Ze#mwx&3rNK?(c(QN2vr({%2dy z){UP&O=-i=iby*Q_tOIP5+WKKCe1~HHfz+QqoYsa{t;9QTEgz-uQ9M(LFOkZorQ-C8`cX~!g)n*p1B21GssG?_aL8@*BXCPgi$3sYv7?O!*BPlu z-oTfE2WyFW%0a6O;VimCX=2$eqCa!cg;m9k_HrHV_VEGAKdH)iEOo1a=)+bAB>#S& zrHg2E^Ez6LEPisczzxwT#ClH0>f*1WU#HY)R+k^rqpz1sK|{)6ID?T>sz4t@_c0*r zj>l))zq18@E^WVAWmv3BEBfXa(CO%y%D?|J0(5jSWi*@^92#6bs7B z%O~4u?oJIev$Cf~Bjz6~%FB&}g@v6fN?ThWOj<)+=0iypdO#3x^XdcH@5Zq`kW?Y1Vyy2tlPAFgscEOiSyuOo_KHKaoTBe?eRm3sd+zRVG+mi zSz27P_HNssocr#B+C7P%B@SuWGX59hS8=-PSF{>K);>jYxvbsLAmO*9eK)7oa%p2V z^mD9K#xii}b3iINPF9v~2TddPqSn^%%TYf+x7~q@|3uMsy1JKx?Vl=t-rFamvs?a~ zM7LlY_isPwzK(uuZB?QX^ABe<8jU_bS5#guN+STDMu`BFv5*AriIyAR)C9y26wzq% z)O!R0fHr)S{aIz2^}hpsx9)qD4b{A>k~XdbG-H}e{mSt%^H0j@e{%nQ4|BMG^l$l} zZ?euV+WaRE-Ae(@|ABp20Ij!%G-UX}8*9yf(ZNLV77g_6->mh&%h14a-jXttb7k}g ztmCcpzxyQ0OilVdw*^uZeqjDT)Pifpj#Z&LF=8SvsbExS8Ep1vyQast4UWJ9hT_O; z;rdW~3V!)J|NTxv*Xo&on!-!6_ zrr~6xZOh>nsKX*e1f_ZenF*e$Rjc|56*{_hp(5Q7u^;ml758Rovkm5m)yyetGc#hu zkWDDjrU74CUT*n}1h;tl)tBbmiIKt6_^H?dHT|L0FU_Ue+ZoB|rax4!ut(yoc`?8) zA+er#)he3ZrKB^m3R4Jd&zzZvI3rpuK9Px^Eer7Tt#S=m5H~Asy=jz+v)hQ#Tcw<5 z9;h&}%3j`Xkq~q>&HG$ca_tw?k6ME8Gmcp;zyJLG(jcxi%-w8~IG-u+7g^{ZfgCle zLqs{+Q7iYawNDUnZ48dn;wG!Z*TqNN6Zmo`v^IGD;kCbN+_2wGL%IDvkqiWd`^{eq zH^wGM@5wqDP0HpTGY`W0<`RLhEFiWyQz@{mURX@W$;n9*5kCw-Wq~j5L(^`O+MWK|Y!YSNdCz_ysFEy0D(nei5qpEYhSGQv~7D8}jiRgmncK_>3H!U=xEp;h8}z z5rpl*F?JTc$bgvbqC0b7r5mc8^ZU!=o&$TF$o889o7(L!i(M&Wk%q0S@iV0NMh1I( z)0PCtbt%u$VI?U_2BT{xtAk1|R=i2&k^;-1FT^z$tuSdf>#{`)Ots|j(M8J7oo2=) zeHIheaU$8*eXqs!3RC!@hf%eN=zHr~R zS^I58K!G|anzi@_e<9k;K1NyUa}a4I7rL64T{$GFND;KxLxI9ggf$FusVV_My-G@A z^o=NaltsIh^E}z2cODPnX++BiInOC#KR3a>vxYaS^s>JIbjRGj|lD#^m`9YBKJ67*PRT%&iSg#@G zbcb&V;v)dOnZP5Bz3+8I^tU*v<98ySs8S1if_=2g7Q(6DTK=Ti1^8(vOODoYXwHXD zWA>Hrip+zWV#zDh!HyH3X4b}IJQtfDc%u6oLGCmzvh1~W`MP1_!zm|U>$c_1lh9FQ zy{YZ1NihjcO=CDqXpmOu&bn+L+CrUqusQ|+6N8hlVausz4LxmsBUPbEjjz6jdHQ5&`|Vd6-*=aXvIk08t??c%^g@2wiO%fLkr z8-ilFX8<|q7>N-O=-6>J-cp3$C)S{>nc81b%#)jLZdANM2Ja7gCD?UJ8}938zn0&O zqEo5{!beUU$|kppGNfj2l$#E< z3+pC`H4c7dBVbU5)>=L)XQ^q2@KtWVp>>n?9ALY3Zn=3J~spke+&?W^BhATBR5%szQn*}aDbM&l!m5+;;?&oFi zhMogKU{})CKP+_)51&*&Q3w1Nk+YI}nW*A5pHos&3T{S>iwcvn3rd=93T-D|(SzPV zS-DZ(1M~;eETqNK>QibLn>SN~YJpRq&1H}NV&QEI!MC}Z8za_tavVWr3S3BiS_iXF%m`_}~X?*jeCV+Z9q+6d0Xi>kf;I*|4@uO1cq2^nFU>%1O`I}^)D0IgzOw9HiISM=1KD*q=JGSf0dW2H?ON7YP(6!sSR|%h)`q* z+(pP5o8G*53@Szm&MbdHrsi*4rsSpyZXX-YyVux@x9x-FKO*`j*yjV~psL%eCvB3> zXZ{0=k7mN|8^3Lo6}VI#&`vj>0+C$ik2|k{AFV66A{d>NMObWZDcGXE^ci$8eYsu8 zukn0xIQVJX4RVZuxp@++%J47?w@2oDro?Jx3~Z!94~n>R^_N2WPdn}PYSu)sFx78D zUw&yZi6}0inSF?dYXlvXQJDOSixURPuOUnY6MgEC;AETdJ4PoL^dMG$ct*)bCGa*8ZLVyM{{Xwk82nTID{ zrC+A#>}Q^l+(r-IWqY2yciZcPaTfweN#m^qJBlRuQ?%#`bc!!cIe{a+xvVvLf)Z#x zX%RRX{9hm)^}a;@K_hDG7EDrW{oM!p3R@8Sc$=IZfCp|fXq|6w<7yu|E3$Gh0_aS0 z%QKC9-H_KXcg)S-9>}NpmknW%t1NRT*+@Bvy#n4`9_xw_i%TVuO|xACXERPJH!BNpHcpK|9J0zwBw&CccrhM{M2v%%{lUR=a<3pPtxs6|Elc2lD=vG ze^`-TWf87*y&PPBr-v2ZrG+1s zdfxfANcr;2ZMnzh=_y&#yT%KC>3;9gBX$Kg}B~yYTCq7Nq}Y*yCQ# zh$8;RK3WCUtU@%d^ba(D-oq09r^cTt|F2OiMb_tEiDu&nZwL~XDb=_d@w8Y$21Eh` zLe_Pxcz-rA68kT(?_O7MFI@gtlTW+Wqhs~o9@6bd{@<;w|0ibKXZ=p7Rg1S%?DL=9 zGL1gUzVNH=uS+f|I{=zzW`9^3e!KVE&t%cll)ZFlffok$gBpKcUk!@uCC_Y4RoMvW zWTl+FB(Rd}H}4et%lr1Sh~~sfg5@d}+dxBgtj_&UAzI@aqfj8Vm+L2<{(3{RtkoL0S>@$9OwtLdtsW*w{loxQ~G;7m$xEtgsb&0pr+p8^|> zjraWfQGY*t+x*8U6?N0pGHj^^8M~khFzkRWM3zbAfZrMMbSB-<%3YI@Txm)53ga}k zD}MdBdExO|ef!?cIWe&z;}LjX&fN6nfAQ$=dUu$f%$DS{Hw=Hd4h3BhNekZHOXB4m zwcqvZi(s*VYf*!x>&jftFUx*p!`k(29k0IG=Ywq#+HyniTUnop-~eE-JMdXxbQ+2# z$((17Wd6768>X5TQ7QJhxZF%Hznd;dCoapOa_~O08KrZ7Z)b~u-U`9%Oc6(+xCGiV zN<9%+G-^&J-2Apq>VLmKxJ`6^4-)q=a1ZCT1GBLE<{V<6KQB-*I9p_hx;H~?Qrv@^ z?E{qMlGUryjSCBf#AtRTB9XXdv2Xkv<(9;JV6ZQD>;0B`muzNblH(A)#NZ{sRPbb* zv#0z2#ol{|HI=>pqBt|^jCE!d7(hUVCP-1LbQO`_n{<^XH9#l^2-pAxr1#z-1c;Q- z0*Q)9C-l&xLINc85JD0lH_nXT-{^eLbIx;~-@W(T=YID;8`jQRd#!iBYpwVFyk#i| zVm+lF!grWQU02(rm(PgK;NNPGpBx*%Kh#u5(hkITwpQxTL17ZW}I*jG<%!DBUYbU8#9REn8^TxiWZH)@o@TburS{^N6> z{IS~!`%Vwh@uq!(eXc(AB7u5oYEf<-)sWXXQo`SHPnXK zvqFozwHsy4*t4WHS+%JMXF)f+TJJ_|_>#W_{R-0#BG{DI1P}sG3Zm_m#n!m)I)JZi zmBdcc8rp_@wU7a?6PX8_M9h+-9G2)Ej8uhl8@)&R*vs)R%Sp?+qf*t&iOM7keK|Mm zBGvnAnh+p~9jO1QnulL_w5Ey1r>o2NE_2m%gUh{B=h8)J4S;gK5Zq>d%|XOlkNIYa zu6@6oCv5BzG&inYx(wG#awO%NN4XT6O7=!9oassBp9yOP)2rjqaLZUdt6X?`8Dl-f zWlcJ+ucK)$yJ>eya!yrb;ptCJuB(VrEBdRsk&Wb=(IH_ z)%aW$F{bsTO{M7(ft^I;AM6EkqjHIP`*wkA#yKSk{7q^yPc`lHfD&}wUHUjp#O^?| zWuGtsD(SSK&i@T4{*xHGpH&1l7uS($SErFs)0*I&M(Qy8TNKHy{dV95xJg*R`$c7j zUqB$QnPp}~8yG9j!3aadPCEBB1beubg^i53ZN9fc?v3nIA>l6T-Eb3=u1hCP>$bh8 zfZaU`_uuNb5K;6+x=Kv4nak_|1)s}C#4Q7=>k_Umx!@aCAfm)gHo3- zLdKsXDiD$J-fOA=?>3XeTLPn6F_U&izM`!``o06YnZ{Q2&%L0e{BZrAoGcCw;0FRn zeL`(;8_C-}sq+k@>|x7lD+RCcad@j`D-Kh~h)>rY-ciH7rnYr{oO+p4kZmu{#4f>0X5LKFbE)jGH5Fxh%kCn2!uBJj9vW*fZbEF`l0ZsN0PJn z?$-u76hN1JF36xE@$qoZSzKJiR#?dWdLjpO6@*h)QHWJmA+L|jIW z21yf^9D!Y@oA9`&aavIb82Uh3(TR8vXn+RYm{CCEcXEUJAdKbQU(}TO%g(uum+3~Tt?6$Hk%?COwh{+X~uct;4ZwtFm(6vUBQ;AOQI(=Xub_*N!_cR^*AiZLYua#TTH``T0%pbWCZ*!o(C{DX#@r z=>eQ`Xfj;#;OXyQ4_QPMD~2l?lGWA+=EC!{k!o#HO}Vl%yfC1$aBluJ*(D6ep|}nr zj(enNGi?4L`1T1%1$;M26+BvAA_TKAcN#S=HbMS?`Ik8MM{ghDy$+8$WmhNFw2u^P z=-Y>{!$8E7&?D@n#8+O@CFCmQ&^ODmU?`97QOPv9DSt+Loz7t%ma#u%yS128)!ap? z10m4tmRTd`r9$vgnWh+{QeJ>O@U}BP%+DD5m{{fzGnM&}xCVm9jfXS+BvOr`X-+gd z*TvNr((Y%a*ysCz@_G3uy+immB(3AGs|5$Z3Ew8CcU$SM1J0rapQc{lyDumf$>tF*fBck!nx^XBb(6+01NwY$e$_g?HYv5Sr}2A(9&OBO z`haVw(##G_%W7+NpZM8@JOW)qmV%Z$z&$SZ7LS*>KdeVqW`eNx(&gc<0tT=H0 z)3flH5Lc`&Bf;{lf&@m{-&|tfl<4o^_28HVT6;v1cp<=$$Bvql<2QdAw2a3tBB#Vh zYcai6t~1`$Ut6$-czeE(!@Jozw09Y1XX!U~^VGC$6|ZPwgMsdG9Jy-BJ2N>TdQM8C zh+%mRxNaWL<%$E`Qze!Vdbi4Bvy_sf^{}sXff61QmbweK*QwY)(D6y5X z00X*2azEoRx~1W#@$>9eX`drUebx2*YzC@i0HbX1SwD2O%sJUn?*TEU6K{&{6UYai z%-bg_Ade$oyg2ow;7WfEmiJ;&^P}L5r>Z=d&VZh+5LGNC2oD415_`B<3T{6CVp#lZ zZ2!9@X6eKaOnspQiBugeHgOpdoD(+CV;+c>9diD!-#<##vHFCi(P*BigI(OUzjWc$>t0@7 z@0p2LW*z^l-Duo3f7;Fp?%JRB!bhpkH)6j$O>?mN^o=R&F7?HK69N9a2>Jh?c2Wcn z*O)koLfoHw&t1V!O8j3wILTwt4?|A zg{WP^_+=*3^fU1!X)tZaZ}u-N=EQglaA|COywnnAKcMn2eO0GiYzvUY^u|WmYJM%? zye>DXZTXWGzc3983)`>%f+7AaydLrM|6wJUO!sF}L^_%bvk3$<6eiyy8^6=VE{1)P z3>!QG#th22#-g{|NyV23@=|^&U(G+lRh`I8yI49PYF9tc_LRhQgiY2Y>Rx^j&Fc8Z zQMeocO|#m_I6nGn8UDVUX+~6WA1%|+uk>&qsq-qYnkWV|&d@h=d&-gQQ})C-iFX84w(T zCE`^cdJVSWD);x_!j|f|qL%uI@CWP0U#q*Sti4=}GG{pk&2YP3#U_m+=R9;}o#8j! zEYAH%IIll=ShR*1v{Ua zsyA;{et0i%b}Jkw1kIb8w`foz>){ord?9K+od;O#gK+B>jO~W z`I1?mPj9B2iFsDVjds>e>j~p>lj0r1auTwbC+TG_)~4pIfOh?fP|e@%^ysZ|pst!3 zD%y2N;kfJTNN6c|X4lH=sU*Ijo{Kn*N0p#@H1Yc_uzRKqSyq;wOCVJ0yK^KYuE(H<$I)?~R)3y8hP`Qw`~D zqf$D=Gn9oG8xzMz@5i*)Q3j#q0jA)*_Kn@y!{h_$dw6lsVp48>@2AqbPJix)W=I6E zDPr7je5o#gelv-h>Az(^^)VyFbk^z48O7kIW-9WEm_z*XsoZPAl$Q#sU>ku_h4{tk zn3}%HR`Ghes(M{uS6TmF5MpP!)&G0D`Y?2r4VkXj8urjz>A}O@)%p7nk0gPYl8db{ z?{pYeS&8e^oEr8(2eH32&*j$v>5vM0&kb7MKjMb!M_cI}cwq;IUx3buA#w$Yt zr^7%!BZEmEY*sBFqwPLw)n}}t-$@-$x=Vy9P_6G=l?7RQA3yCnQ;baYl2B3%rydM|2+j5@b219ypu0Nu zAt3AZ@X)}x`4WlUBVR9LVhE`&6lr^p?7EnunO>zIvogyVy3jJpsawTeGnl4no8}M( zAANgg=Ot>X;cy0DMGQ|>3Trb(jzC`RwZrq(u3*(%>VrXBqi$^mokObkqIuv@xd_1F6h z91bkbsI3;PjvxYGgrsjzbC=_q6Q%2@A{1N=uUD3wcHM^|&#V4@p^V;>ex$SXr4Q!V zEJjCOJzqF#VX(~%?iD7tO=F%evvR3LW-anU(5K}wz(Xf*E_(gy9UCo^UPus6>S2g| z;yHsh5d?NK)!)i?Zo-MUaiD043_u$i)!Lvu=h`!l=jCPyFA28Kgz|MA?50~SY}nN= zA>V#25j?`d{q1Plq66r6*@JykuKDfn@_|6=WctX?jSY`E;f_E%NpqkuZfl8CZB+<_ zi{p}Z2}GQlbiHeR5aeEFkedZDEiVrwO5%Z?mL!ZX+Ud>qp#5?ZpIZ3EaB6rt?vXwo z_qZ=^U_QG#`DKtApS-Gq>#zpEY4y2{baimwYI}&Ci=LhThMVk^`*oPv07zzm2XH5D zsj9cq4pHL%=H33*v@ggRqA7_RR|53T!QlP7SQQDSF=Q%+%|w2A??Q{0zDq3fYIvTN z^?dokgJ|wL9r}HplP<2ivnEORE$DCg6!0?$r*@0WE`Pa{{53Hj876PPM@8&TF(|;g zyKkNd9=2t^aP^|{U5<)b83`CapY4K!Tk&T6B<$9I5^bQZKI%d3xW`qh8P5~Ls6r4s zLBTgn3FRo-o7yeQ`ER*7bPvziE;YQIFpd<9>C;jwLi%8SPJ{s5Q-g`?g`=8O8$^iW& z#=a%qvN~0t<{!4?GWUt;;1)zaj}4VGRAbzGvm;!x0`JcmPq`U@XaG2(zqS;;?jpZA z?OiWY!t}n3NEvB3HSS$_M=KiYI;oJ3PslUZ%^mk!W5!g~;vqU+dFtD1AD`Cg=HH|4 zH*NHT)KJ1vhkgg=qqPg?&M2%9m?z?vdYhz<%X?67BukQWB3ik(7iyF1u;P~Z5#6v% zVpxMiP0IsB&S96@Vso{sXYTrm={Xnt&#hag2X7RNC2F36}+*y;X)Z>v3c_^7Nr-k-NX9)glfd3KB!gKvd zn)!I8hZ8xgtnJz%FLgty@d$ezpu&kkS0)k4EEiZ{R%>&ctbp5&J~$Z(jmT4hJz zRKRumZ1B>HsQ_$OJxMV_FMBgII1dCgnBC^0u4v1!SoqPZ`A3oPg@E7VCssp zoJYAWcp<3njh|PUS8ob7O!^=$J3+Q-TF!=S%g^nBUmADq!mWqo_s7a*FD(`a8X(S( zc<1vjHf2MtGP$A z{n4W4K57ro|iO0v=H`u;`w9+i*_nKtX46$KudG>_x^ClsiuXEazw*bBa7ec2tw)c&N zafFbX-c94`QMfB($IDY|L@}GOxjTzGJgPu?O9Y~yJK*D};v>E<$@NrksB=pzR)Z8U zPtC|tpfYrAidp<8JCZxV3++5IkRk8JUF zl*3%IeC4z&IY7Q=SAAM+3Cv|u?@lp`Zxc*ESV`>{hwH3OgX>7X7+n9kCVeQ=Wk+sr z;$;hL#t=9SLiOchY!l_Dt5WqTsX@jBgi{j1-VJ^;(Snu~|Tpduk$vhGx{ms+k@)Tz1 zXug7JnVxn$k4jbu)25D287|f=pPW_ynyXn({-3Yd{s%Mo5BBgcuKiyFp8kUwL{vy% z-kcNC>t>#$L+ZT@OCkQ{8E;k~Vb@yH*eKT?Om<&4{z6y_Mdugc!g?7AM^Cajy?%5A zckNHVghwYRlaBGupWeM#nL`8t8bw}`f?{u-GS-9;&&?SjG&%dV2E)Q~ zGS!O&xKC#;pqnD2J0?8Hk9cJxm5W#`%n+nz#MJVu7EeUn1jc`P*(;MeD$|ehu9d8E z&c~>5HP`ulf6lCszlRN|ruH^gRGNuSeSUwaXX#Y3-ze1;$1XpYE_|rMPpVXMA(LtN zlS&);#c>LkZ2YYsXP2;rzqi^0Ew!s|$*6*@cBgSEu^_iVyu4s1TlHw6_sc4j8)G&2 z!!J~9JH4bhJo2Y69b&HD6u!@1Dx#Pt<)j$!ar|U${YdT7qt!Nt_$rfNaY?;>UGH|n z;A-H`IW)NdVd+jTz%P!iCDoLc$7i>q=x=KNA4Ka?|n z-!4v-oE4kBqn8)%cH2Im8E{ymQa^VnyttaY+aFw=)(nEE#vjnS6b|aLNt@DS?X_c5 zF5QZm6B#8bl(~Jx-uMWj@%yH!Ygpybr5qLf`+f48@{w0W3lW1BK207!gWD?9n`LN` z(gAlaml;X!2CSA53?yE{09$MkXyN2aw`)-+mX6{ zbcSul9L9ZXo?Y%xN&Z5e;~9F#YL(hzpMoDM5VUgm3x_W)eLLO~(9^y|Hlz!jPVRDf z=XJKU6CdI-Sy1CPCnJqk*(~2*dGb9IA{hYf72Q}d(n@LpEmo=2%}m9Y)zTZM$OWn^ zJ4_36C^28Ekk2i1gx-aUaj>Ojy+8Ug=5Rix%tR!Dt+Rp91`4E4zZ!$*WQ$M^ROQby zf`taF2OK0hn|<)w{6MBmWeVR)SPdI$g+TLi88S7=<}sxyCb@)N58TNRK)S4=1rA=$ z$l(Gg2s21}A{1pGKRJ)YlCAOmgT`ziC7I|nq6JxJc*hJ^|!@jsKF**DZ&ZzNoOv;Ca%5@S-ftVfM&9Ds% z*u`!?KBfF&=)&&6_fpN4<$|jHDN-IgnF?F+=OMXvAx@JSYY;r5Hgw+ z<%r67+S&&1ZB(=gB_`Ph-|ae|wD@vM0mux|Uw?jCnh^VV3g*bCk7fu7GggOXJee-V zoM3kv++lBiWCtqkdBE?-(0rISQiZ}L>1w(L7CHv5V5DWW>uAW9yYG+yhcO>5InHK% z0~GbWvj6<+Q}%5ynuQMHXeismiT)UJzq}+$6>GasS*S<*&N!v_dG~HGd~eFl5Z3Zd zYKcQRGW%6KP;HZ}%)%(IJlO1zoM!C9i>?5>WC6FFHjPMc^3z%APjUN{*MJh}+P?zR zm{hu)Gr;`!`cY_~!BTwB!9jT9$uQr5!-t)|EyQT)xFjJ$>7WkUCf!dT}q5}!v+}>Z_vq?G%C^=L!T!K+l za$E_zR$ko^3ir}?H)w4Q7l8yINW*-WYOQR=O$+!I(4Z0p^q)!7i# zsl9nSh48(M3w~R{+I%7na}r$#gl^B;vBv32|G9?FUu^)%ZA6kz?VZ${I&SW^JHdqs zDV(EYJ2hz8QnA@xo8IG|hjtIqaFmMZ0(wSBR}yU}quH^yzu0$tan`lfxm+FH>t;jg z7KNZYP|AGlYDt|WB(}dNCsx6CBb3z3G366qyq!EJH^Aw|MZzM&(s*sj{yG4!6JeD8 zn7B)<%+umV#wK@mTS_a(%p}_^N0Ze4t~^=%_IZ1Il?3UXMyzJ(hx@ql>|=nL_OzR= zuyI9@zl;0CjEK5iWiUEOoP&rYk$Mphk}lN&Athxi^Rc`PKhCDrv`;fpZ3lUjm*KiG zhG3LOQpr|+F{!+qt%P2fj%%%N((e<{R(I!B6;4-9(x?T@yW#~-$K!U5O-*MPHK_yR zU1du}U3uvLVb*50M#Bt%7Eol8EsPN;$JUpTGaYvmU9R&JNB<(j7 z&Z)Nkc%!;iaa^R7c{+pG-h<;Mtr;ov4^@DDGQaS6G#3H#F_46@Xmhl z%5bd5LwYM^mbp)>sXinDwt!EiN-zov^q?r`%_^p+Fv+Y~XB9r7GusOk*DTi(Uq*3ft0Nh6t25=~x4KZw zz#GhLuB@bzJi9%8X_iI|A-R|%{O!sCw2d(u|13g?7``w)JGxMp6EsYwl6Y%+^Ow>_ z>eSP#;8cSt-zc&v$(I+_Y8Z!HZ*o(l3b%x<%C>CApN4qPsphs;rHUWh=~MJlU41mM z68`?V?eKPrtv{(^A4`RmLo~AeE9_*syxSe+9E$gRh5rV-7I2&=5Q%F3>7#Z*bE(WQ zYmdyc+zNh9%@oX5r&8&oL{>ur8wGsjmF;t~GxqEp0-3h>e=>+gn ze*T)F^42Y8bV0tQ0~mgx>Cd+m+#F}xd70V|7og4eZ`#ZVQ=7>aU>b!*FvEZE@Mk-v z856qvy6jQJyMGMq|J{&+wKF;eqF{QCh(Ud{g?7bC;m`czWmF)|L>L~jaXp~qR8J$1>%J_#;(E|U3`H)1R_Gk0j zf=5k)mJaxjeD{OigQ>kRwWWTAy37`!>+aw|_0noRb2of#@NIwchcBG))&2jA^W~YNU(i>BV8RR7Dyw>-76h|+GhA3e;1)B`PG|jd zT*E&0A0b4m))6OIlMsIao3C{p4c5QepTD&JT;tn(8h<@`b?$4Y&o32NSd?!3cUFn( znfq4Ad8Y`($KF&|XZ`u-gju^IER!uvEV-|PzsGW+nk(WRH4yTkU+zPw>yKEfjT z9r-BBW}C4M3k&*f&g?hV;V*6e9FzKuvF3X8+Y{DIN=aqvy_iq`+?!K>^yXnR^3|7Y zIA3c2b-ye8Z~7T|?^Q6{Aux7m!TO3ziIBu(C4c(&tScGXRwQ;yTr2k&r9(p0QG1`@ z$C7u3d~~;GXh01Cp@qZ*h+H$V$V?Hft{1bXnic7MA3!*$nNI5!i&|V4dh~;_&E5P8 z@#{MO;HHw_LLc)m6t0%b)V^#w=6S}r>?RE2Ju~Zf^+~|Wr1ycWS2ZVPqiW<7=tD#? z^0n&J`SlQO%cowwGX?3K?14$Ygy|yF&v^9h!^XVU#l-XL45XD7g-VW2^0}W}JqJIk zCGu_DEelJJ0Br+8^CgNqSE}7WECrbkhG5s>A~IKQx!obNvlPgPlHOxzt!`N%uvrD# zQ|ob#N{y#Tqp0_$J{Y}OGgQ~w0*9lgho{Us+8jW?XLE(}n zb$i?IIYT~K>W*y+VI5U`*5f|CS2Sr zs&rM{JC^VUlN-Hj25TLZ`i}B|{$iOP9@ADKTa19X{32;(E4D3aYiFlfJ({{q?|OeB zzZB`^4h6rC$iVg zOKbLWZch?Sww?8>WS-bY^X-$>;EFuOucLJAycumLLdM5+?E5ZjNqwW-*p-xnfz(!R zjK$C!4$h&Xob6`BrDRQ>RJUn|`ZGuS(pD*XFW0uX;1S}^0PQOA_g=ZS*Ywsdvm2%9 zN%ZCvHxrQ3_DTm;6iQ3I<+_0`=`<@uXzh#lg)I~^4XVbq1Q1k8$*)%bDh>5 zd*QdhkHJ#@05eso+xmV!GF|JA^___mam7O!Zf`<;3k|Z>Y?a zTEyi#RNkDPl*TGtu^!+A7oxnVW>Ap4tUlOIi9xe_n(a9}Y{ey0>&BM4Q^SXO0c-%$ ztvb!bE=4sHf10n=V7zlmXbKW6l|2=)PQCduD|X^)`U&^(weOwd70YnIunDEpgO`Ho zzX$XUWCdxpREWPaWPZu$kryw#%v^^oGGpY;%PA+jKh7!+9C#IE@t~?tdmOL44DO8hI^VD)1hLIj~_ zY2*X^37>f=b~?Db#1&?KZ;XBa_&=rUq!*60_MB6|7m5aXg=d_b`Vgbp!BAJ>@yqu? zn=!~U5o5q@TXGxa?ay#dTkX?A;zMuM)y*sQ0>(wMt)aV~Lybf7W1__Z94BV$j2Z8m zD|~bPbc(gsIFyV=(fE;>J~5^U2ASx zn>#AaScoX1&m&_HWjp-<-w1JE;o!PP#O{4>?j~oBJ*acAyPd|*%n>HpQw-Orv&)CZ zYkDSrR58fLqadLWLAO_mZ6><1$h?A|xI&0aw3Q8bBJzDymJAX(qLuVZ(dh$G2z87j z3+ec(_hI>qx$@m5Ya{w0$O|l5p|PTBtpdpPhOY?pwL9KU6LEkvny)PxjtA)d1I~S{A_yyWSS3FF{?gN7XBbyefZvu6LG#KThW3k zF8l6wEj;`kDdquOY32kkn}%SU3~M<(Ns(LGm{p^P?_1sXt&edSE5Utw6d*%%_cUQM zOW3pba4TDL-Li=y?vMsXV`1o^B$bUN@Dc4hy3?h=JGWPs_l;@W307A>@@=<2)Uv^> zjZrtN+@%g3WqstFehX><9s14rixneJ+p#{xMSmx#9VcoBe|4ep!Vos9c&x>O@X+z# zusNvPQdib5e(23*c7MV537y7CQWYjI>vWX7A_j9#r&a5?Obtq6ionKxUgHj6oiapF zn}Ut*X@Z7OdOX+(~3;>pj_&o*QTjXocin{Kaog>MR1n$@M2>d8-_<&JJaaa>-DZYB{CX zLfSuquggzJjw2#Ww1W)X=bsmHssuqpzx&-O^=VFyiO5YMtLh{ti^2E$=7Ez&UUzCu zgE%LQTVIJ=*WwzbCcK3J?AmYG{nsPSul}-NhT3e_q$esGJ$@tClL>h9{Uf`pzXy1} zdBB~lEmW^9YE+SHnQ{JoY=?xsRN zTZ^+?Uo&S>!b2+!O?LKDd5+d|ftrz0eZhwfgEri$s9VF6sSz6+kncKUE>+jwas}@@ zL38Z_vM^>eTz12K^#a8vbk*{~W%&ASck|ySwd`F)@NYTnURkqVD}EZ?|FA(fZvF5? z-3uQ!mbM>XK*Z|^BbhPLjS&y5Hh#6<)#7&n9s8kIsORI=@~a5v#O$fEp$|q=0-4UK z8;$ugPLod6$`7sX4M(Pk=H{H|XN^lFYl96utBa5y)Smn+zr$a%NbBkym6HrF7iTeM z+MxJqNUO#S0Ukz_#dqlwFiXs)n43&zU#Zu+>*~+(Z4b zwK;Vs=y8k%4r=IoB;AhQ9Zs2;=X^zdeul~^g|)LAPH;-nTY-9PN`lRV#yh+ey6c?? z&9z}o)Q1c6SNc4Yoa%eo0K6T;#&JoWk>vT>Aaqc;b63c~+yDC zgBcT5UCU*^EFA)7$W*8!;ht2FfF^E3*@8bCwDR#(+LQvyFLQy+u66H^t*Js>N}yh# zzC0^ztG%^t+vgpoL`ET|XX|mTxAGm{{xg18w2gfO1n{%x1H29(fzDM`HTh>IJdR5B z@vS}&V}zzmU{xlD>c>S1ClC3*l`J2fe=0e&zD)lh)$0+TkU(Atj`m<0LU(vBk2500jgzggsn)MRuimm%o4?XL2d4za9fVA;_O7g7 z%trB{v&iPM`Zt&Gx|@59&!lb5Zg_bB=(r-#wNJQuuR+c-+=g`gl*!ZW(Xrl9u}tL@ z>8RueMw$r@R!oaHXaDqS*hS)FUq&~PVvoeKb|feSh2eakC!!1aPe}XqQSJM#DuS0Y ze%H%Pk%VRIMeryrOC;4_yvvgG!k5@)U?1~v*&OQaIa9PSEL7S@ z5R92Jj&tex@$4u!G1*$Wr&wEayzjRH)^jxCk~v@Rd|k1^(KSA;(~ zw$Vv&^K{!%KZ%EGf)PyMkvo#|#v=?aT-d@mbP!}NIU_*-b^Sb?K@OQ&Ghg%e|@ z?Uon(Jvy&}DM8P>?;g3nt=-(1v1ku{+^eMVU}kUFddW2ePr7zZvDfL{^59xGyWEDU z!=}TV-fy7(iyHUHV*5dp{=Np1=Jdskwq7%nOv|~7|trD``$JLE^mOj$?1F?6jc>7^^DzZ9zx3>ML$?wS`Z^$dZGTH6`)GyjD z)l)xiNpo6vA=62YF9~Mq#n7^3k9xGs{dozp&3;_vg={EoJf@pJfZ0jjiPHQ0@V#O` zozgu=l|%Pvib2Yzd$cc|6CX-Y2rfvI<%Sr)6!oxl1hDFb*dZ*dCO#(Q5UzorS1Qe^ zsp^+X5R81XZo{T8M&$q?eRJc>f<1*9wAf(H%hNA08Mkq8h`m>8U#9U1X0nar+~dAI zPH>?9zVxX!u`#w1Pi?4pSq{u&u|UIJ@qX5{L--PKyO=@pl2I2r#G{gOX<*MUa^8N}2Ed@TQ%I)vxuJn}B(yd#{D&EKDRS9b7fv9=6t$|MQ1rhtj}6Z+|yW2O_&t)KE#^!@bA*48$!nU@JCCEOWfV|g8uUj?R|Mm?YH~nmj{9W5LW)x+W)Z1+pYER&zN6fVd04%f7BX0Y&)MR?V1)7 z6SIvU$o>o<{<~}akCD3$<|OtwnXHVICL`1&2OfWaTtJ(;jnl>F{ku9WEVcbf=a~SZ zNvTfHl~_i0wHd_Z#7{qIuhYM^TmD&n)-kQ*(W6IBXBULJ*gm6~6yAT^uE?_iK)KM4 zcS+sRx}J_XQ-zb53Cob8JfcEB8ZP^9t9&SxJ|7(1g51DZ!&v)@tE`k$>y0#I*GS2Y z^Up!6#>4D*sH^r_XW~}+?~Jwcjijtym*c0iH;QA&6<6lMHYz>%0jz!Nd$zDedymL_ z%9zM|FwYb1p|=MJT1lG8K#I`fs%0=hO4{+mqr^kEKY*B(g*Kl>6Aq;ILZ~IT!g3~&h1U}5@TD#frHK!bIB0R_?dIwQehwP6M95GalIz#M!VR}Mx%%1yl zv($!)w0h!=bR2Lyg+4SG$lHZvA8RXgg;Bp;RoY?I34*BDREq)bi z`fW4Qk5aPZ4Ma=p4N8f;L?O6ZQEfqA_Q8}nSS_=pT0Uv(W&CUrnoG`t-lRH~PKxh3 zsC%L>Z+X^u?TLa}0qwYT+Ox+Tz*YA4QL5MJ3tP!-yr;o$Ro|@8Xi}KX7f1$a0+Q{-=v*U`hGxc$5DDtMStiHIIDSeE%!O<~}a#fODQU18{L~X)G zvC%(=1}9l$K51E8S+A)A*_-2T&+QDCz!lH!KD)GBs75AD15cc3snAcxKiD8O&k9H{ zA~wZSd)GwdEiJ8VrTh3jBv{2vO{=j7)}*sX2`k$Y!_!+DUaXRn>M=<0c^H5(OC zHsdwpDDq8dt4Nqj!*)vN{lw1dW*Xpx?pmpgE7fbUI1AV;Bm>C`(;-C|BFri}jB+06S<}*{O`X>?Yrwk<8}9 zcB+_N1G=!THX6zEu7@w)1DlST*4PKgtl#-A`Szl{xE07e&N&NG*mdJ&#UdX@OjZW} z@H@lAwW2V$Ed821*`2l8aP8`8Zvu>OzzllxDr$wySK%3Se+SLZy69coec#tI6&5d4dHYrk zv3NgIyzY(^^g5Ot{hZ5jm$a(Z-pvXSje-g`#tAmGuwoKY=#je7i5u%HoYO6Fy=_T$ zRD*;c=`E(qlKiHck`&7>_LA?#5zfv4K-IXCIiLF=T2hG&(MPwHm5eOR6;32b)3q#>bZ8tpca70zj!~DJymummk!~7$(rC zFLVB5kOt=FDIA1e#(CZ^=@%X`RG(&p*KkvC$l--*PLwUGVIcKgt&8c0h;yyKu9A0D z5I{TEL8?eE?MboK1hLgmc73bCez=Vnzw(qYm&zZer^ZaBYN$}5rJhvP8cfZq+D<6G zuxMWP#IIc8QvPzRsOgq@srHBSA{y^j6bLh*M{KlbYCji5BR>|mUj{dXJETO9all%C zdTDNYn-zA)Y(@UUP;LXP;(kwm&#vxq3oLOPK7GD9FgA>aXt`|>xhy;h}g zP~VT^Ee8nyD~G>kPF$fns7f&Uy5JsEF?|nea+;oZvF#a2U|2n2q*WwqXGYM0Nrb zRlGbHr(x|oCz?4@;UDADOT0MO5@uc-^Mb3jp6;qYJ#3CO14aj>m@m093Oaq={IVIW zb}tilBmoGp-`M5SXp#1nh9{??5;@A%Kekt%N-BB4op<$CGUH5okBRz5`~&EBXOfsp zjA=Qmd$N;GX;EoR>2eG0-WiZPbV=p5Q0*193>03n=`79 zww`BD&mhZ^XV?ilD-D&ijg@tRxYOW%AQ#**DVa|<}F~#bkDldo&RoZOPu_xqP zWJZFBT%CstgGB<38x>E)k3&p*CaW?;0&cMSrraO&8k#MgNvXW0F1wOoZqQmvQo<19 ze_4YE(lOR@bbVGG{;8Tl3z*#Z@T&nF@a1`vqdEKmq_JNzM_pRepXxg8Vaj~4x~-g^ zrt`;uf#jEB#72OwJ^G z7mn$RZ<9pF2W}R(GlGf}iM5s+ss(Nl1OHd{q>T^rTqRfu z@#|^pt-5G;tyL2d=WN+m23p)~7Ihu0mdCFeKs3X`E<83YIir^q?C+&`p zh^Dv~?%v{vRt&Ipb+oR0R$P+dXszg$hR=yhG@({pZ?XthLp?3IM9sOzg}C`j{YW z5=xF~h?#5(a!(=cyJ9-WOG~siTi`vEW#hS5I)0lbMD%T_VJbcU<0;gVkGPzJ9R;o} zb-vEIEo>fR;E)pTBP9QwB>~|OFWQ@M{v+(sOk@gP1ARGAG!+qT=5M%e{|{a7*SJ|lhkfgzM%6>r zsH$(&Tr%fc>#(@ZKcb}wpORCpX|adP)!pyQNtQT{&z#k9Wqld^m`dJ0)lri@OiwUv3{NK#Zc53bODLubB)AZf~EqOB*}O;nl)?dxjK=uXsMHRX05b?2F)g@qsTdkjd^q4BX|qzW-r#)ZM6SQ2(U)DXsJ~g zL7d(G>7dGCU1|FgDY0i-FRLZIO#8S?+jZ?RrJu^x*B5tp%r>s?kJfMg(Yc2dRPxj* zt=+2~)k(>ohDi}C9J^ww)f;m=3*rEuhU3?|0+H_q^K%zxrB)9b38T|0EfMom$FIw3 zs`(Zw1uLXj+&V4qlcy10ser5y$L3*hwLA zj`3M%&Z^{soSk}MAW=T*i7%_EZIWeOj%aBn>R``hQ0Gdc<&!qO?D){F;jme7S`70e zt@|? zYtItah9*0%|EWDQ`Ml@lDOj!mcoC}`>qqvVPCm&;@^QC$sCZAp;T_pOu34lv5N$PG zTt)MNw_`nc{4PqZ-I}~ZeT&PlQ)DegDbn{&ZaNl=OH~k{?&WE!5>R_Hvt2BN<~Jfi z0xZALC&q5kW_G?Q1C4tiL%dxYg69|t$h??J2S!x9J?nc{-y_{WLL3K+`P~eZdi&o$ z?oI^xkaQh$0+-kdL7EzB93*Jh*uIYV1OBAjb1Ebn)8Zhn^||45lyQpo>T>61bCoAP znA4d-vu~1bE~p`#p{cmIwnJH8el5L12nNV98PT`9zOisiJRBy&e6TJTtJL81IGA4| zP*UvZztu?nwH6w>s@?h+Oa|dm>uG~X^AjkJ8&xsI-29}Cg2~pz#N=*Zn%unH(sxX` zr10-67;8Dx7wl1DO@ssmTa8?EX$$0qPo;fcw6}Vi^Eb}Epc`>e(%`WXgU@+adg^Ci+zo!PlS_Q`=j#340P4h9 zroP(mB`&qr9UpB%hZ3P|ujgDnF>dS4r8kSF%1ex2W(Oh6L$voH8g_+~bt0ZXf#|{}hVk(AJ>i>|qXP5Y0>=hQL zwv8;xl$jin%A`GXs+Pz}UN>c%;y>^g814qqHNL1zSQKS~_WO{rc zIM4%_PtfPW=yBNiXk?IL+6IzvNLB|0%HK@K{j%tg>N_}z?0j^Lt8#XGkQQ+p!*$qI z70(?YwDe5YX3Sbv$y!7&6RW%9a(coP5?uMHb{6%KLx~FtH%xQGHu>sK_Qp29}SHp>{mYnx0-OhWY9yvmFf+{ zC58$BFHcVfgHrCthu&4bjl&~lSwvm;SSyeiKX;W@Nr9H+5)bi{9+3Hm-DBCIO4kD+?y?6ng&sl{^2 zr&cfHBQJSd0n zzEAtw0osf9`_2ujx-dx(U!=?3?yW&ZkF>C(LVLp_0&3n6Cq@ia(!zhj|9HXVkWOEE8TF_PxwVvlsOZPqL))Ti<HIdG^DtONZHpZK9Ve(Z(U>7?O_bhtOv3;0{o&6O+x_+Earz zr?(3izj7t%&1&;9Tv8$`onyo|ao ztmmR2`KnX693&&O6tqmcdR4Vv1#0K^TKGj%z3f9Y*GHQ5fW|{8}T4tuNim%BdTV5WCxB4=PO-_33 z_`8E|_3HY9B`G_zN~Rxop&ndMy7fC7rIIG*NAbhN_|?wgMQ3fL)j9Fn+&~Z(ou^*o z!q=)raW3S};w55VPMhvB&o26OmND|GLYThwGMqfom4l&MWCPeNz-F@YDZ5N#oF*g| z+_3HF+U_D{3BMI;jc-k`R&z;|R^sPt$v?WgR}!!@o9zTpb|`%bQWzsHQzr*bOw#S$ zj|{IF)dzbC9Cwcdklatc@v9M5eej8%{CRo!QIN`bU%9gNumnw>beL&PH4fzL@3+z` z4})~hERZ*ueTU^=^uTA_#v30`I;H@qu5`gcg3h~&{PCZO!`pEmdcA0eEm~V=tn&fI z4ij;ZZ)h>$N;^}<`3Q5XwXDBV(M_wZWmla|`1pQOFbj99v1)E>kyFKPbVa%@ z=$DB4C06$vi+z4do0DUt-Rr*;w1qAn8jr;(gW1c1r}rDe-;N2a{bJ?W3sq(bFt^p~ z8&}b*)0JBwJ+sWzN3p>4izceiL+)DWMOEstqZM)#r!^6wOMyF-4j(z5=WQH=g1sG{ z(a76dw~m z?|w%uOloY2tkBQ#pQ#^zVP%Jhb%Y2s9vrMnO@&UaMJ=274}LmIh|UfR6Q~cA5xJLy zgknwXM!;S_f^y24v|ZX`uC{wN=!p;dBQs-4%S|A9=5-3zpopMM+^2ar+a6U++a=X( z`wjzxY&+rTnYmICYsju5QucZdWzm^(!cE}qX=}j;@XL}HGqaML;N^nn4a_$F6c3u8 zEj5>@)6PZ)bj;A^@zoKr$5IQB)SK?X$;EbEB78fFYsG5taDkac&5wwi+=YAl%A~|hk+c5FhI^xIuG1? z*S>x{HsI$|`8F(PSGfa(28NSIq*c@~RoCyaEKq}r$xNNY=}Oj9LKj;eEbC-IY+&@+ zj0iBMrFHNPQm{13?^f%-#}D|e?t$i6p*;WCJ50V#aYzvFTYGG_a!<7jKnsOutSwal z(l}>BRImr>XT?@qxip-P^{ChHA9$lt`porS%ic0o!8_%{ zseQ~s;(9VC3t@as-&~UIr`7hIt*16IJ0@#7^|`SA71^s5U$OE(obS9ekB5&>g`n#+ zSkBt74ysDa3%IG=fkxFnZPQdff0e(-w_5T zr~lr4RmzdU)%G|YphNd?+JFS}8eo}SKZ~p}Yu;ij)+XfIB4A$KKy-P6^k%!{pgZC_ z(YZ4$da3Hv1TGuaBTQORgi2Z0h&7K8o(`vsz$CKa`laqhP5YWon>QVelAGkupAfYL zT<#VmxfLvjN(Ywt_$!fF4g^=Ze#K@Thce-ah2+ug5OY~Y!nICSMbvM{Wf{4KuHrR5q6L!&>H7%UR@zbH#8 zf1f=L4UIvjKgAnL8w0>9v3Y$?b1SJ*_9R3_mp=U-iP-H;_%;Ifz*Co?*7?nSZM!Rl zMd9=S{AO+DC$y7?>+i(Z;S=J_M}gs$_Vw<#M%78}Z(2;AumXJ(byrGuo_=&H8a3St z#&){+xa=|CDs zxa1e-nBb7VzqC^}gb}S^-s(zMxyONAu6`FGIGm(9@v((E3napUwVgxL-}`#*#2>Ml zdzgrMA!bQY58;kYd(0yBzl!*5uQv0MdoCPW!o8RPQ@}vhLwtROTlPVl9L-|=lq9)5 z(Q7t!f1gyWpt>5LS@ly*yo|R#Qw&A~95Gtel7f4s_*0KtxNyzEUpG9`Gx(8S&xaf( ze8NWtWO_IFMivHoAJ|=NkJikD+i6b)i{k^GtZ&oaB{hzVj+;f^%<*85-Uv0}y5WU% z&m7N%{XZHaU^fNDm4(;F*EI5)>alQjdWJ$DfR0so^yt@SReCL}5!Fp9l!2r~A&j74Sg zv?Qk7rg^d1;&Z^1!ZzsDEiJICpvl@isFAXi@KI)J3cp#C><0)3pNeF59JeYBVi^)u zb_A93n6O2}T$=+sW`f$^lss69_>nC?htwDy;$!^wskK$b&rlZPP1;_*JD<=DGrDo< zAkkJ9v|_g>D!+>{p1nt!vGoe1AYF$P+IA5OfhruSl$aV?rlra zSh^bX4!JSuuY(5=>$wdy9T#I@U3B4f{#@Jkh*zJK7T^3Jd0j4kYavqWJ4ZX#-|K8G zK|g>pM)QxE^WuhhF<(6DP~ls~timbM0dr8Ma5ml}w{l}NoC#qFye|aWt|Ge)?MTPQ zDGl0EPEWe2Tb^?j3Lc2D!>eF0=jE+s|K<Qxhb5H5ri^f*T6c*Xm-cl zZQ?fJ{NZ{?7g^2y)9so>w+Tdf>W#kx)VaG!SvqnVNY&*WbAJA$$<*ewbzaqbh>V8M z@Yf(2bpC9Ba<5@4d!#Qg+CoJBHFkY`o*+%(l|U-`Q%}5_SvKaeDCE!5Rz-Jyy`bF5 zw;JYThN)RqWxVi9T(JJ9NzGg&#oVuUKuqm<#P0J)rvQ9h@x$6XllBI18wDx7>Ik~P zF5X4TIfMF}QO%St$lf0T!B?u^yWNj627SN$+w_Bc)n7Vv$&F;^u4-Mg-2>w1G|j9@ zfhM;03cHsYj8(Z9em_kSZ^kc(<|@l;1v?pi6kafa}mZ5l0ub_NGCTtMP?SZgQRu3`805L*)EWT=X)Qj;5D>)n0q(u0bQ zIF~aLmZ@WW;OFNHt~zyie|&GbZ<{T4zI8nnWLa1RB0nwdad|li{M^MFig5 zE5l{w?o+ek#R_-4x~yJ>m>)P(fQ_AGYAyH4fWO2~n#+}6-QQdwYEIFHvPDR;gZps$ z6SzB1T7Tj&XKI`!dOeLjDbw~xN5x%s?6FlaXqoT#ftL@6$owo*lPMdw|rp2d-N@d z9HxmGA?3+G;$FS3G%E{(M~LH!weOT#N^mB^R-X7w8ijIK7J^PF^pK_AxOfcnly+CE zxh(Qm@RQfkUA~SeUYRaqH<_Nl9(^)*&^iM`7Q&<^5iMLiRRCzq2$2PqfHw`r%!XaL zKxQljg+C>psSx;f+LCUmPz*287R zt0}WlBeXLi>53Q;H<_ivtFEw&Cwp2IKzYhGm6s<+h6#%QmZYr$$r!nOHIpbAUE}Fq zr+OM7m`4HaEdsAnE?hJ)+1+A3NpIzJk_Q)8iH_~@{rE_90!WplO~U8lxbt_DJT7FG z+*ZVl)?%49p=o7%EVF7woiKM|s8_iJZvwa*-FWt8?5E z?uLTxY~m^1&iU0~Wjr7qO(Ga+yYNtOsVR{%FSBI2fS^dq;|E0%1u$`_3bb)&P-O_x z;9s2tnO*e@qz~s76L9V`HyVEN7t*F<}-1K|BJIObe;fi1SJwM;NWYbl4u{ z4UN+U&(s&c!hBlyFLIuk{8g)&CW3RJ=*15&M}X++D^E^-v|C`07Iy~|lIjmm-xzWJ zPokr3!X2#*T~SFpoz9_+#}r0UyyEwE=m`1@=^No1vv1y_(=`1Z?x2P!8w{lT;F2fm zN~m=SL3}DM?}g_t5*)m$(?>;mbMiMR7Bajkq%+O^WWG-Y7PRi>xEJ4^X!FIbQ$jzx zF1uxP&$~=k7;1DPX4*(Oxt3KrWPKOx3rEo&*(~6CharJd?R-O*(15s<)T3L;76H;~ zepp40_E%5*Dd!rLsW%l|M)&b%MCNu&?Hr^V^>+u6y(XD-owrSf1suLJ3*0K}8)*?4 zi~V4;@i#{4Ab6{uXgzpaZ@_752>S$16U~UN;4=EQ#Qt8L<+eXVg$y!L0U$hDI-KFj z%$xby(W`C$0m%Kaqk>eUv0^`YpWpJ~kn@TOS+xNrkpA|Xu*@Ikumzyp3qc7wclS$v zici2uAgWF5F~fG$|01sE@4)%DP8kJRefUS!04{8HUje9aitVzBVsjJ{MkzY=TA3y31zla zNpriHRHMZzn9KoKQ|ef>WMNdn?KcuC5pvI=P6zwOE3k)cv|pQgkF7U6Wi;!_rBZeA z4XWUJrum^k-id;&d|X3gL{Nlu%*=&}u@hRP=JXkC@FoCXpQ1#>_o0?eL+cq4(Ez=t zO{qx2f4IO!`*?aluz|6;xy5jB`p?>E(KL%K!?NV#G|RF?rG+#!L!h0&V|aeuD;~9fSDDVM(}Yf= zySA+I&;P>xe>>Iu$fkp!=I7s%ITG47TqrV1)Q%o|*N43e9o$?_Q|hcF;)(c(!{>CuJ_r};#3UDdw`Ih`GXYKw-w7D?k*1^AMH+I-`TK{Dv#HX8=1p0l| zyrIV5F@0IO%JiaK2I$5BhWV!U=CIQbjViPT!(A)a6PP_fj-%?JxCQYbhCR0XC=-hH z7AZl~JekeoiWR=rNMaXOu(I+}XD*>%`r~FwhH9PU`9T=|WqbCfMT=in#CXNeaH*(& z7>o6{u8@RoNs?jj@TmJ*eI>`0v8viZy!d(MS7HuuL!m5}_0b(NwD7W@_7bB?G4DzD zC!1=E?IyG-9dEQhH{%tX2F&NtjP)_7P5iyJNp3L@_C4H-}`)NqB@m792@lwi%D-190v#y|V~IlNn2e}4aEsid#A zLYTL=HS`t1R_HslMADw3nFz8FAX5yL@`ptZexD*TB(Ps?HbaM!ge!KsdK(y>xBt*aOVhsfG9vAyn~4g+`gJb6fa1QrshHbx2aRkr?}1W@Df6;rF2tk7VGbdxqEH6h zQ)@MV^5Bwpfm%*6R5#cJ6+Eoi9`$o{bp275SGHUxv3;&@|9S0>AGW3K4t!l3a#idj z&Z;0EXN_Ye!3ddfHi5RS)79`XE(@niQH%kC+uflTa5a7O%<1)~wbS%J-Pim|0P0Bu zh(U4-N&fPZPAN%W{Jet-UzvuZ=|uy51)$3LCO7dXhC>+%k{JIcd{+8aD14)L1xr;w zDaQJX4~MO%hxJ|!WJW(rTXIITmOoKw&*k-s5)t6;448`Vc_Cc=pP$~a8%Jig09-ms zM^AXwuaq9?iEnHV$~`<$hB=iePNV6`%#6L-u6bD!dE33S5gK+TgU<1Nm@c*VH%(e+ z7xO|)Ne6e1{&}q`6$-N9h10|JpEGoNCs+YS75rf>9lmP^Jdhivm3kt2)iT~H0xhl$ zwK5{w7j}&*;qD`c(R=Nb{yh7$IDCsf8C6qG{%C2ypi|$dgoOWxcvUxnph(IOoc0_6 zFJrY1)7o=>b#Z?C6!Apt}+U+X8F#B@B1VER2MJLCCX_#ECl9C@%I(z*EqrMT~h zjC{JU6A`<>8g${dDUfitWYi12p(74SYq>KyX=+V9T_+{iJgWSOp}>#+nM_Szh^&+I z7HsY`ZzW`vdJQ*w6OTVDM$f2!NdFfq3c9})`EfO!$ZSThBWePF&76!6c5L}L1j*cH zEGktddlHzn$+VRPr7j)v`e|Sm-q!TZ*v}@ebqIXaTsVZPHU9qh^vu8E;^&%=xcCu4 z5h~%f3S@-yzns5HzRsI_-PcwCg?2ztlc^OyUpk2r$nPC(kP{&R6MjF zB7g4yN)u#4=dM0NLOF(Ko3Xi+P$t%HmDC?WC4BU{gGe{U1Dann_`I(PsAUO!MGjr` z{Bc?pXPUB=*jhKuDf^}mzK@Nc^&Q9vq^j}w>>;9ub9@1JcGm{q#(Jji+65AOU1Jne z7CeKdUuD~Oh8R-)4MiRYxV|KJ7BWHXJ5IId8ym@y+HPzn#ftcN7@iI3W4*B}4%Zz= zx}nd+Bn6FzQBe74UcSNOcE|8Ih^0iZFHdSQkb2DF zDf;7&A0rDiW~U1??RLU~fTzl$Ku^D%ZZ-6|kO4kl+JLlOj?`i4AT@usJcF?&&eG=Q zwhvDy#CxHckw*=`J{~_QGIKBh%b{&b85wr7rim4t2eWCu0-ffE`^Xd-)r#)6JdCMt zB6<0ja-}42?0%0#IpM0M&(ZDk94~Yp10Jsx4ELk!6n)=)lHmLsnMa?qmosTmceru& z_*1nSqQf|=Xi~c`0oo>hJ;fn>j z6m<~r;T3-WhG|b&kmBKuFxXUGKA2M&#Nc%)8$9+DM!zc4+oPGGJH5V!M`w|N_l7C% z?hGgYiv4fex3r{{81Hbir(J3G&IFsCJC;zTmS0+cotaG&!Bg0$#dWErW09I@9fu3Q z1wij{jyZbXZ?H}Hcmx%DDM`oCNo0IdJgpwdyOW+@JzjLE#_^0dk-Ue4?_1$Mh4N5Cu!uBnZ{KHFFL@jtV>{{|nZpJ2&#x~4`y{5rW+i=4x-9p|^2J#L9YfE^OX z0k^($O}ez=4QEsV+a@+jSE65MJ2Jxr{bR|cK*lUn$?t`HCw?xhilb)1Bf}HJVCK`RBJ38i?Z)1#kn!&SaW zvXF}Y<^eWT#nn}0LhEX0cIrCdMSWvx%v$x4nA^*B?)sShc1yjA20n@iTy&qZ#|upu zbKgAq7Jfb8pCg3A_L<<;Eoiap1&-`E7=0+!Zu0~81#zlBcw|dczNY>;5*BV55Bjd0 zK**^Gd}b9S%U&XNW1K4uTYmf^Skr%XypqdY(io0lrl%q~5gO$gxV0I;AaS4+<3D!g z%DDV`YvsSMx1N;g4a@&E@DQ&bC)QVpFr8#>@@?SZ*MPpc8$2LkxhW}HI`Q#(fBxR- zjI#If9#^xQ+9cO5pJ#PXeiH@W`74S{-m%b(b3C^bRp{zTOJTiQk*Du|B7fX@ua#I_ zi4~1D$}xWu_49{p!`Gg*vG)${XD{dt*F<6(7`Z>DthN^WniDn+@)4-{+1`gaM6!MX z0EH(io{6)gj=p_sHr;7eHlsPxs{evfz`JFtEP9nEUraLcc=yfNRZ&juV4(<=M4c@2 zkC={kLFJS=XlBgnAOGBEB3^mpEn+N+R@rQj*A%L$`QAdo1lCVjMvA6Rm8rRKMcX`o z6i4#s2@yhc&|1H7XYVDB3aTdjJ(oTMCdGI>D#s~>0zE@ed(C**Y}c3B&w$}$0Z5z) z_Tegv6n`!yq67*{@#+~OQRA_2Obk%+PP%Y`qlN^8_A?cw`1a~G@Mc8TpfRv^p)N%$ zGj{f6JCVb0n=F;1#}%IswE2p@S!1qOK$TXjnSh2h zZS_s0%NZkw$3n3+pw>22m0?!Okcq|YylGB z(8?wR^#S-7GTgx?Qtbw(J}D1Y6dCY;W+Tek$&p(%OyjxU)M^%?j{g49-&L6;4;&Vw;%e|fT{9`WuLo^Em09!8%+c4Fse<2U#cqE4Uj+)>yR z9V8yrdcSzK9m1Pg(h*No0}@1E_5mw%O_Pv+E67ASbuS$U&$OSpk^Ob{BQ*lk_pB$6M=Wu&kY2Dwkz_!1sHvn8VK3R~Gc%{IRS4>9;cx^IXZ z3xp{F!V(LFK}4;L87V$(nho1nqswN#P??Tx-BRT`=6<~a=^xKgXC46{^8t}TY#$6f z^fFl(-+qg?2~XRbuZq>)HyCQa{1XFwe_!T1A=e#!3*sBlQWTLry5i%5E&`xV@=!j?J0!JmbrT4#fvJFe1;LBW-P=PB}iW;F=nuCI~X@Ub8 zZWTB*y2o*fn^l?}xm6P*tA4{TNJTSKLW_w6YuhW5Dw>sA74R?Rgu0OGqWLa~$K9rM zeb!L=x^PsccnF?0DB}22ftsRXs-G`Pc=1@q-493}DUKAr^QHep?k#-Ub#9vIf`KbrL46qS{~J?Q1% zqcV6lYGhs;i}%D2v3+2eHYIcE$1bo`cHQc8n2PTKTfO)Ym;884?}|7@FPfxZ*5k$` z{kEVN0X+++d${Bm?N*7@cYBY81%w*t4ezNMWa&V}hGM%$mi_*$&$;ypToO&wI_!0- z(EwoWmX92HnGoFTey`Vx!&8LTXnRg$QMyko2**00?L?bldZFO+QI`}xmpvxCmQ}kiZKBYZ3yS-Qtu@-``nHj^B+C=uwMMPTr!hU%B)OW+ zR)`6#+n?)mI2)|u=y^Y4XInr%Ywo(N`7?<2;-T;zqbhz19&!=BGKVXwhMRiI6n)sebjjZa?HA zrj$(83-d7-Yw`J!di;6PjM-|c+N+_P`ejguyrYJ|Dd^&rm&*DPczR>QWjG-k6Qv-6 znkmG?hoOF&Av~Ht&!TfxCMDz$Rou3Bxmy)yWf602@hjwu>13nJ_hRo@1=oTvZ$gY? zf`Z`nDF?NyxHfNL*h`M!+&Ne2{JlFqnLcew5n}toBTTR4LxuYG#olwq3f^he6TWJ$$ zTxh=9Bt?f8AW%F~FlvVfT;YjmJb3xttrBAIYb+)Y~#gjENlvs2pzE$x8FxW0_eei}k|UBLH)& zK&3AB$B@bse_KFee^( z;k7#!Gd77~XY)@AJ=)sOu58-^w`RMTI-d7I{i7we*hCR3MI|^$Kb}q4dgy-F8f`b7 z2*ADFlrske=q7wdbk#$kI|qlTWP)|Hqtco8_wTO39qy$&W#pnxh>cGl^`vf4bBxq< z&WIqKpLw%yx47zcXD(T9u>j$d^ncnFbWUq?HNHXzM$G!sW-D}g)5FBQzwR1FLMP;O z@CqBzvRZSfHe` zd$EpRdYBu-rwY`V^_V7p((XnIF0v&f(V6H!ulh1Y5|^{)?A!mCW~62BAb?>y==m_u zYc3Yy(Udn7j1Pv%WebI*W@G2d-%03lB3hbWT@JhAU&wLb|7EH|KKT6H{BzR4Pj;by zmN^C7)5vPR0i>pV8%1ncgoOfj1?M>Oh5(6b~ddsb;fX; zCIza*5!9D#1yWqaqD*=tcWV3(;l%$$`Tt_HN*+*2*s`NgfZJP@K7!5u=@2^XYIkSC z=h|YGv6&h^n^TGN`S5-#^G|;kQNC=Qlh6Em^9HNtUs?d~UZJ@rH$eV}B*}nS)`k0R zFZ*@ycqRl~ZK5wy=1uG087Nh`>Fc+F4O;OU+#a}V@w*^&XCamoJxvDp!*%e(X9X)$ z`Mgj>ZdQgD#opdb$2+m`TQR_u`7W)!1X@b8zKcz`tZ;^%=VgVsyT`> zidG?icL-?PiZlLVFvq@~+`t;GL?(`!v5-nN*8V%p+D=Ewarz^OR`Oz?OzB!5sf41Q zX)f+(#^F2E69}7Y9~r2gVkGJK;@~|tpN}Jlg$hN!py6_7Nd0jvIk=U}X}va{Zte$6 zlPk{Qs6JmZT6L`4^8-7O{Sz3&a2fjjlmdG4&)oEJ79Wo!;TBQ7;l@gu8tn zUI~uQRGsX{Zx5QSwg^yhSe}+VYwg0flT=6jFuFEXx{@@GHf;GEvto{Sc#6&bFan8w zkeTI!@^$u9x}F{3*ET2oXyn;0o@}P?>$_WE%=-5_-)*pwAbq{2R?f9+8Os<1bxtCVLh#=9=LJgR#QsBEW{tsCFxI9tza%UkqFeCc6 zl_|!?%CF`yIZ|tW0ECY(G35yiy2zfG4CGf8(sxG(la3}Cy_Uc1`#f36Wf1nq5T4@N zTod$*Ge<)UPT;2XnCpQb-QgGpWkX{N!FJ< zAFUNgNyU=|)$!2G)6UW_-7u*WHvg#4$A;1Tu@}O_#iB(rcD+uqG_KevBv@Mk#AA1(v>ZYOv?5&B#i553BG4ts;h=B59$UD!bfN-B6G3Nr zQZA_%3n9Fe zf&xmaya8K2<*DfXK47ROCyh-aZLATHYZPL6D@ZD#-2O^-cH?9olpGXr`Hw{pGF~ zY;ePaST8uL)$C8_g2LI~r0AXj#a!Ss|I`%2>XxQP)kI^Gy|4Mg!40|(eWY>OvQ?ct zSsheqfBV{YXu6W_)`;)ttCii4An zOx$wN@0bpN47uM7M~UvD;*j|?GZe6e`q@9jJ8lE|Dr~%-v0ynGG=aiNmdX#A#h88L zlj=q{3z4h~#9CSIFGtFQvtb$dKGSv4I(vZu*7{4)XR^{zl5()-C>MIpUfyA#kZsoe zCy6Y0Z@=1l^}aU2TVd_t)2JZ&OsaTu11mfxi~8dBRis9cX7`aEq2h_Eu`5cMe`6L6 z;@k7~j%570Vm7}yL3OxwSF!P%-9Pa=*7i%IdSkKPlpma~NeNijdoMy5CCiBw9n1OR z$lD0M<|trMkS+hcl#spm9+1x3eSU*oSD8GcyIZmaRY)>cV@S4+U6qkjjr^jSzhL66 z#5foImP>o0Oby){&zD%Dwh8bErVw|P^QP{7zmB8BcYdR}G|MQ-!sCOHMjox@tkmqv zMN)4UT@{jcXu@^2_6x`nt)7S$H`_%~MfIEQymK!|5`noac(irhM+h!aY`m{iS14<^Hy7PR+f8jADVuj zJ#iX33^KSNvl`(*nol!HS)s)y;ol=QxLVwDX`Vg%R*aU#+wwF~y&jSv164wsBgz^; zU|@p3UGUk`E5blpRf$GKlCqG(v*Ct8}YpF!916b+dilHkNX`)KX2B-CPTG+pfA-ZHAOj+5ojUwWjz;1go zlGE}I?k%CV6*_;XGW#J=XuaXOkX)in^>c`Exi$kg)oF1M9VAewgNf z@1sEDt2a#YAfC4Uq|HA?LLLUydWUv9giZe@p~9?Wy_TzzB!Ol*;uW9tlwoQyVctqZ z%0v1w#BJ_h+dPD1_MLjx#wePwWpHOKums!z#rBQKv$aC$qZUt>F_x;_tf#jmWnC0> zF)N+f#|zErf6TKx*lVPi;^OpZ;0LI#uC8FpzWR4iab%&ZL=pqf$L51 zJ3JTQ8i`mw= z%b_igCPxVxjDh7qzt8rdHZe&}NZZAJy&(u@^s%dp+{q_;=gcRvj(5_wg4Jo!NYh?u z6Fw#dI|DXaJdJ$#m#s!sr3-vMTPj1OO}s*gcclE|CRzF0Kew6E;{$Cvl@q?C9nXfZ zr6FRu8%BjwJ-CZIRgD&$HF1>tAl0ASy|$*$uF5{u>E$$INmr)=;VAFks$rg>R_fDRRc>S^L{gO;*c8qO)J45iPd04b5ms9zA%ghtJhj?g+o?_lGU;uV4QEiPU`t+)y>|@;BZ@r$Ps+1;q_bi zr@>A>EMp1vig%*de%IdBs*dCYj9g@zbBu zF#MQ0fnV64($EJ9JIp`9#98%yc}-=8f9?{x8yy3~*vR=K@gEb^emU|tp+BWvcruR2 zKVc%)mMuSp-HCTWGk{ z)7k?Dine%dp*-^>%-y7an5Z}sXnFL%gWPSN?MPOx_Mp@1W;AvT)|?(VzNBCjBuwTL z8S6m8e<|$`R-H-wbp2eBk|}6D@+azE6>}Qd*fVDrXkNIvZ4#tS#Uy^+g(Bx)7WEN4 z)TfY0cJ=YoUq=bFJdm}c2K@Y%pUpyb9L39*4x#|pIX^kwdtDG(>c0Fa;EmXcABcH!qZJrvgw-s(O_wFJgB*{4yy)yJb=4E;L(Qmxu2>SkC(HYw{sK z_o%bqF&OK6{Rv}Yhd|C9VJ4Drf_&=DlrreLms;a$D<0oUJjsRDf*~Sov324k_tOE0 zRhyn~^_PNPDql^HhLKRnh>Xv27OdaXBEq$$Qd;$oZw?RyRE0eFERo8s*gJF@ot5E$ z1McZ&56*~?UGnb9obKPXEQf5-KpA!5VuZl;dBOV=wXEu&-`)iFy|rZzGWIlNoQ|IO zY;mCZ-b_6$&mCq61N(c;NVJ>%oIDd(9!kR5s>=SYt#DGFJL3B>*^*^hMw6#6l?83d zSqV8^GO;cninVwWd7z(RcWJ&CkgugypMSPLB6|C$g$vv5q0#Pk6&Vaw;&}g}M5aHA1jv0IjJD8ylRa_@)X`$gJ|J{0{ z1U@JiDy#G!&T#XaRH4hWE$b4ycOlajRG6e~%JIrsKhxdTEP7Y()A%8n7mdTyj@|^T z3Lz`nXEG{M7vun`+4cm%Yj-`s!dpiRODd18M`Zihw06oqXKQx{Zn@)rFiDt+NA3SNj9n^^|+_2@r=f&`Skma zuw~i?VCM?~bYQV`+fXKaEXw3_Yfli!FW zMXl))w#c&)0GFt*g`{n<-I(Yg-a)~+UyN(7g?V6MWUhFWlmkJrrk%fVL&lLB0F^Rp ziEcO|&~NB`;rZYV2J%OD$oNF{;i+}4NNn!VQrU9%mEdt>YeYxzNvbu0uqGC1;^~w2 z@g4Sh2Q#}ToQbNddS((Yqzv0$!m<`O`1UI{rqh95mQ3bYM3ww+gdeWd4l!hMS{=Ma zsE8%FYtIJ>9z8JLd8|LokMqsByQ^8MIOzjh>w_x;Dr9Gd9WrAC=oyaAg#LnVdCx=d zd^V8KaAlv*;JAHBpUSoEy#8cDWLmY{eHs;+@PRwH+Vo@85Vxs%)`5wU|-ACh4uaaFl?qC!>gB03pAJ2~s?Bn?^52lApAgW^wr-PmXt|D*3 zodp-N>lS*O4*MHQ(TT-s^0CdDX=VjPjtEIcmm#45W_bLKqi{SF6OnE?_{fw0Hi8K9qQo}p@sW1MHk@h;3a;gwR)%qTal z9e`p9$gns%KP`UGY7S5z4HMxjxfn~O>GurjRJ)&Y2jcDX#3-)wVQil0pZnjGnAm54 zetRv8P&?}k#zR2rR}(Z&Zmx9F6qQ>QMUkt9Nv8-yMgUlj#gm!sJIW~sl*@L_=xd+i6i`R?gO(OANWMGv}yMITV9dWzi&^H1HTWe-nQly{03?AjBPH7kLIE}S(RlkIXl1Ea^FS?0Q+WggBlYif{(DB6~0&nxw zrSOhJAv*>#n-{Y3*g+pa>z00wA_SEuO)Sc?`C(B9c^wC9q zO>63md3D?g|ygLWqukPGZxxRY{N~jut*aJe(XoNnOT7x6k8GNZ-A@o~=w%||f z?Qomlmwd_~wcTIIC$z^=EH}2xNJSm?>4cU5Ep9%;>O0?ZeY`NEOJ)a1zTN=Os~leM4UZXz7gxtb z2VkVC^WehriSi^lV>1YNXSeQ=hdS1LA1qh6Csr7HE?Fb$qZgkBqsed*sg;<+65Pc9 zkZ#Pc4b83_(AP_K;GVzV5bg)wNxgRTC9ir3B9fK*>A81O_qAu%N+D=eQ>Et4irB_o zV%lPHH0pT4PYb0hr1?*WDQflda2*Z8Rpi+@5v46GLs5y8Zy zA%-~d@_(obai{0me`aPvLWFRRDhQwd$S)iM`;KOc>bT(luq|GTprpdX!$njOzWfpR z&8A+{%Kr`f|E2D1`KT<{nW9WhO=)#{K?DX#UQl&(bnfo%DHisJvs=y&~xo!|}*56#|TehnKo>a}R# zi%Q+q?KY_Sh>F^~)fZaFh5jeXKv0IA5cfw@=ndI2YL=`}NC+V*)k{{X<0f>votbmF zf11T1U$H{8KVtDZLzoDC47FVFkQ7BC)ISUuhaimcXHe1=xq!Mq4HssF_kSyuJq%G9 z^o`alB0@s2DrGl~M-TSbhw@NY2a_*Qy@{t^jfvvRYfQ#*V+eUA#Khj7EjNrF+r2Ug z(u`VN9?9(yh??&MPC_J2@^>;ji*+1FyWDbQ>HlIPyM-&%9HK%(zqqp02V)2f=Sr2! zH5wue2V>TJovx~sDz!K@8Y~80u`pX}Wv$R`>MS~v&R~yN(2E43uvM5oRr1jIiPD?d_rZ0RRJRc=80Q$b8he z2m2AH82cCyWT`dw42+>p5c8OGH+jSTAU_}N5xw?F5ofL+&zqQ>xpDxF-;@QMI_f$p zDM9*tX5NfN6~4s2nQO&=6zeRdo%U^1p8(OZ*|XFBS(6;)CE&42>ZhO&XbtJt$V3f& zA@hsd2NCD0s8N{cyBEROk`4O{;4Ys$%TOd-;IWat(0^^$VVhCH#YSs9WMpJl>5a12 z53Vs7ct=b^Qls`&?JMSMM!m)$n40s2D2>aRIyJLr_d~M6Fh7n=3bdqt$Ok;IUtYDn z(T)V)k|*>7zs2B0!A93k9YN8vJ~zr>Hm_$`R1~S}`D!AqW^%hbh{<-H$LHa!>8~Zh zv=vX4?jMstxwRbe0TB-}-^x)YIPx5&hHU#BG%gyi&~AQkxIK?fxt<|Qhlk>o5N_%U zx>0Rwx!cT`Kz&*AG36eYC8{(XEa@+gA=M0DtByKEG7WE768ox#e|uDBm(d<&>3)S~ zS@+42H6}H7-P>$McCjIo%GP>Y371_7T&!)S))r2p`r-UZqw(tCUj6IcKIQH0+?Z6v zi~kp6kfJZZ$LhBFu1kN6|d)n*=DV^#_32QnNE8o zPdM^$x&VnSBN~~2tJ)o8!e+ZJ6^cwytx>@P*-iMWQGd99wbtq^IThct$GS!(U(1Vx zToh0D@r8K@4?TbTH&DFQ^IXuht3Cr`$K!XciMs?kQofWM2_X^o@IGjXagUXI*oZCk z2^Nh)MhXIdz&`#<^GN{~;=Z*bK+Irb+$H-<(*1(5?4Drcd1koDrea3w*Y&%w}>5) zcL_6nFetLN4saM0?ZUEvs^z}DdU&Y^@%0n*2wP;7RbHOU5e%Wru=#e52TvKk5tNlw z45tg{E=!&fc>_w#nMjf&QF8wEq@@+K*G1GzTg{-apL@r}ci7tDB2$k4t>}v-rwe^r z^paXKxb5T=%jIHz^emh*8B3R*-XS^Q zp6#>HK;O?YHyZ0+FIPDa3c8RuqNY$sS_*3%f#7fSJiI&?Lr0S50efb@jakaT1M4f= zWr0`%`ugbOJN76^JulpbA^*vN#8m7UqBLJ7WF;gdoVjQlEEi0!52qHb*tlFyhmPmU zE^lv5R~oI^Q_NQyX_ZTrwptFd4ezgy%C%ZhBL^HrC0*z;xns|keK04V!OWm~s|Ew+Mm+TjMD=g$1P!UIb=Jjt!zeMl1 zdWXMr^ z)KOD;iL&Be{mLBsrt(G27b*#uO~y8-3nW==*E2uhv27k4h<5orsWn(&sFWqelS!_x z`RV)V_jV27wa>M&uv<1{bWrX(-g0_hZ!d9|(T~Y`+V1Q3myaDzPr_Ibe~jNWpX-WYChVSbarMJCD#Mk2i&}N*J|3GDG@cd zKw7L(qFjV8DcIOju3oX`F~E=360oR@@s%}fHhgfa0l-%H=+OeBw0(b*GH_=CrW|MxdrAKO6&LZ_8jk;X$;KYK9RJ=^ifm8J6G{i9I`=CD9- z3&|sRCr67>^BH3LJ6h3MbVDpVMf%#BnIC;oj#RaXOk?-I}I z{IUIlNW8dmxnt)jMTeO_)gO1IW|i*!C1 z8BVS|nd{Vi^nZ4zn)-=i3+#w@d00TM0VlZxVT}g*>V2}{;f>76vl%eset?``$^T$!5GzI%C>=ILPsQTB%At5SQJDSR!r(ar50n3QD1H%g4v3E4g+Z zl>J91M&UiHz{9Law;FNtfXAn|lyd$Pk;n#;j{)mF&r~sSJ$tt+JGwvVH%Q-zuy7OS z6qv+)^YVH#q}vL|?6RRvw&-H^1qN{T+313+)7zAEvcdd&z6rr0p8;E4Yf?8fji+f- zo{|{U`ucNFqGiwT*qHV53m@wfqvbhj$y^>EH%~}H*VRsxE=#C?MVTDO?^vzeq(c^S z#|TjXp4KW?#`%Ylc>d2=J;p?ahoQc4TB5UnoY99Vrgjd2*JBIutH^=t3&4gSFkM6= z_xU#h{YHDD)$f#Buy)4_+5-x~^9i#kT-^$d&QuPkqVVQJ}u!GZogkJ!zfsG|-F)CW?D};Z6F*b@L?; z4*objKaqsI_Ii}AnsRCI!cQB}#C1k(3{f(Fa9^u`d;OylZW2(Mh*oZNA5l6;#VQ|9VH36)|Q) z|4ya+dy)mK+3!*WG*zj*mYTG^lZ2i6EJ!w$?7}azpY$!?X{Jr?Lh)M}_tkv2=H4}d zkH8Nf_yZ(ZO}Zljn|RHM=NL(lZZaF=mSN`C9$OSg+Z`{)lWb*Se zmO>S*;Tev?zd0;E?~kS#x;Yy`Q`7mzJPKV7g0n0`!x5 zexQx=9H#8Js-&OC+cL1J)3M_uU?_gCTlUO;S;)>flS`x`my|IH=xz zk3o8H+|=mOjZK=M|7VedoYl&Sl5=OiHAylsq#^efa21u=m@EEBlm zboc&Ecih1fvGnAK)@2MINO5hTaHH!+vWmE}1?ObWk72nG-ppT{#;NS`1CL@&pZIgkXiO-m90mBg2}>;H`fcpn?2 zEp>W93fw2`?#D>Dc(%mp)Ab4Igfw0XEVSRwp66e=-l$3WuVatWcklRI-?h=MJ#rVc z#pD}Ccq}bU*wf92|M<=GYi&*HZkFKt#<8Tk`O;vfS004`4k0Ys`FZ6JyJ%QXcte3W zH9p*D9$-Iz-)ig%YOgx-AQoU0mh{v>fqXJpzs{gR!v>(=sK$_SitlL(1;c-1bkRF$ zhMn3UzC-?wL%<=V0{M5ha199>ePWGo5!Nyt0Zc_ zQR}tF8FB5A1{N^)j-%U|{E}d5uhGGh!RGGGkh3;)-9vK3+3=2Ar%Vi>JK4s)Uw(WW z8!wtxn#t{RxPQ{T;oD(}^D>>pJY_Jl<6>)xEgrsG&h}#oCQxh{gltIRw3~*nskXt( zvUW4w=_|Hg%~?(EEn1)db5y-EjV>#P?U=7(E-C*`qV%HdGt}|B=YzIc2+{tvlFo!`S6)CQrz4I;47z*R#9nu7A!edEx z-T`r$&(Gv|SrA@2#}ctl5{%dxpv4fLLgOCsljT8OjG#yWGo*N#> z{=;f=^>W&X|06Le30PU{)#Q9KUt=_k>aaW1(`>&}tX4zZ;c?TuuyDK2q+F)5w>=P9 zuG5jO>jMea?+dX%nkLJ3-^Y11UnRHy_|&&&#?5(!`Aa=xehdgf#=D>UmH(1c?r}@; zJzGuki3f!34MCN6VKC_2u9!Or!>&pEa^|4_rW8YZdlJB`R$D_cQ#SuA)0#ZP1u)Yd zL(>?TvFMQd*1GqJLAYWk%NemgmD}I6wCxQB<)SMME5NH~GW@1EgZNXg%Rc4c_S#z- zWri#vLiUJRE2&RVBMLnFNM#StBmP1|Kv+FMkr+m)@7*}h0z;4tSm=1r~ z!r^kFOf~fLO`bERT1{9=@YzZGG)~pf%5|3G6JsOGFM^|sQ2jJ8GBkO4{zNvDO&bX# zXMVilrMxB0x6T_<>biS?jm1yw;QoeSBledpFZ)mG0i7kWDS;CRV=m6CyU%pJ6ZJiW zDxNP`fw19lSFK&}EsYL-k#D`|%UF%!V6kQs9hC8C^1#4A@Tc$8;k8 zw>X6G2$84q~kF9x0Y7c61m@>Mt(IW zCUrgYyboScSZ1!^GwN;9Qq<7$RW4anXZuPt9s?up1n%-l*7{zoRs{b^MsC0ntE}@S z`ND<3Tx<5tmd&Z!dQ`>A3jmXFY=SKAl=6~^8{k6R|2{Eis8bg2;_^WBNcAfv$hX3s(N=?t8lLZ4^YN z8V~G{%_MjpG&{ehgQssjHXAc68%p?jbaqq7fW7Og3Ua!m%rXZo4x%$LxxH4QM5KPN zI>A-L!c5CArRDI>l$Ja9$WZOd$QgG0 zG#RS>=I&zO(iC@$cWAj%M<}Z;Y`hJ%!9uk#3NMk$cLjMnjXi36fY+we(KXtexpTl$ zj)oZ4QAnK5yEES3M*3*EmaY;zk>`bq==};H`Hw#w z@YU+*xlyFgi`ibqTISlxhV;ahl;F9>__Q_2_|E>AwQ}T)!BwgB+XB8ST}bqKUeoBx_$SvWjfhX0(6UX!4Ix9<`b83cHq z@*jfg&X!CRCOcRp8t32|)Yjwalh+VL@z zh(o>}@g{(F(dB7^Xkp?~F!o(}M~gR}_`XGEEOR%fFgScTDDC~UQ$^7tHm83Jp3l}0 z1U7T+^Sp|`5Y1}VhZBicuY}kmcZ3^^mJ~V9S;ULzEehLd!jH2ylpEd`bhh;8 zqFFd~Zd+N(QHcEA*)W%nHD!d*%r-1~gXxD->vfG8E!^<%A^JbA2X(-MIr}Hb0`0zz z_B7%9%bDTg+l%KN{ktVH4SFDg2Sd^(W74Js7m43}Sorv3o!$>&k&!$7;b`deI)B;Y zKE86fG-gvMwKf;p7RQ7Ap*WJ=p}0Wr2eAFst~d`bFXFp*tqr#D*r`KvCge2tNgdg5 zZF@OYKYb0ygE$i<9%;bE;ys+o1zk{gO0BeI%*-2{u063=CY34zmYR8GkMFMlH#=}m zFD~WxEZ)?OCQ@f_8(ofsfrMGbI9{fC;r>fj@O@5C%|$LO+YrMWH<2-&NqS%H{^O$< zR>nBYg{ZbhYizxdqztGTGCHkVeQXnk2eeIF;(Z4emj`3;i%Y;=PKe_Ai%M+{@36$V zqG>e_L;(mR?h6{&-ICJih~}RJ>>TS815}bM#mxsYJJwF|8qM5}2r__1ff^U&SOb_641MJA@g3|F0GW7uPS&C`vYYy@9+;;^^%=Mie&X=)I@~EKNO8zAq>TP~stHHz8 z28mcJGIN3sVEev@59_x2Df(yUlZ52tmJMC}3J&U7pnR?rZMY*!=$On+$5K z_HM*l_W&&6^K&z~7CF~cx82C<;+xez)*lV(6-yNxIONRaW2xh=<%VmciG>79i&nHm zH(Z%M8+FPQ8w0dsIGiyB{P>$j6NwdC??5XL9I1LAT@330YYUpowKsrtaxzv>2gj` z+^Cpu4t@aQxT(PkL~=1|wIl{dy~6AVR@FpT2THxU7NTEl=RKs-80elkWKeRZ>M{DP z36}g1i{|djl66CWZ(pBcmW<@L?la@D2n-sLSD)BlPBM9Uc_^pj*>Gy*($xkVJw3e$ zRr~${oaUA`eWrs#=al6!Pj7NVm**(KQFik~!`|Kf7(CUmj`$w_{0}f=(6iQBG3=N= z<5idbkM}qF5iAyBVS64-0R(wO;}TUq#aU#-{P?;Nsg;%h{9ZEMslU8PiQE z4V%gUeGUcpLy9q*J#U)mWg`G{EShT)D%<<_p$6ApF9g|$(()41yCQzE;WHu7sS47A zY}&f~WewIVm}2LBpo7VxS1HTQ(^Ij-!}%}UP z4h{fB?nX^4!kC!XkObTFSk1t2FV;@BrikVYyX%n@K>qF-zV38Jr7Zw-y&Eh=dnUPE zck6Ir+rnAFj7~2@IGbaRfqdL96^hglC96qfZ(Ec z9vVoQvOP1tyDch)NrBmEtRd}tONH$c*xLoUG_NFsZ9RCi5w*}U9A>-{~WKUjQ& zbd>o*IO30cuvB+ITKE_|lyl73{45;$jA7>tBK}NC^lY<$HD>pfA)!r}lt1}wtQ3wp zb-j!{PLcw26j21+(Mr8|M=J@rns6Prr<_gN;}^ZSnHDn{^NKIEZ8Ye?0-5jll2ndG zO_FD364<=pyEyfK;&yrHh@vfQV^8T}{gG5_*j2YXAsaTTjQr>VtGSaXn=VFtKJ8AY z-LTHpZ+^qOgL(qb-*XozoyOpauk6sb&N+Fpopal&xKyyg?_tb+t+z36tB|EyX;}4s zUgn@#ziZNd1^M=>J&pxPv=r3y z=WqoFU#H?%bNH?K7zT+Oj|~}s;AdOUoU{CiY=#aGQxY*_4CQ8fJnOEu_k^TYZO9v?@^T0`#*-<+EIZXFm-pi^ZN zA(_0vYxs4XnC8_ENbnAon6WTu>^i(fr|>GGu66}S%FwE=670H$H~r6 zeX(-3j>+U4C~FM?Q*68kBmQ5u3pFC`^@ty*d4qI5d8xKQ(eBk$+Vgx(YUNkUC^NhiPZ3pY_=5V z;UaEtNS}IQSLn7i3rL|cZ6iY9>~2PBPsPoo3KAh9jfgT#xoGb z5h9bQZC$a7^s?dt%SNsO9PO%&*!Th^b>D9-iJ{SZU9+u4thp=y>YR90D)hi66c)0+ zQSBu@o7yjVf-Ow06d+R;OfB0<)@Cm4LFFRrz8;}^^&y0Zw&@q>9Ha!%FSys~B2Qpe zw?+jNOlxfEGE;4PM^+9(fL+Rx7|&%PTc) zlvet*0ae+_f*M`w1y>R8NsbBIhbmNX|F_n8njkp59FW@X+6tF`0QhDrY@^&28)kt^ox-$`TgUbh%lZSh&?6i{5;8* zF6YZ1WCJ9Vi>%JM4eLKDmBMBhHP+rVM~}eK`t|JPG*(aIi;U)_@fMZD;{1oLg_zjE z*5*O>>E9Fz@2c0RyTw{#q}Skye5DeFZw|q;!jXSnl8FOH0F<{Y{UXaG9VE&f-LpMP zxDiEZW-7lq)Rqj-VW@7u?&rccAKY7|N!Q3xj7kM%Ej)6z%35ZY(yGvabK-Qj7FQLr zC+TSJkmv!m(x|-4oA-DLz9g+IvAYl|Z|sEGEO_CLYF&;oxEJ#J%3W_yiOS&&a{7+3 zdl{0W4aSI~Y#Z?bJ=v&Kw9^gy^xnzae7D@k3kX7c3m?5Sl4s8rh;-GopfSooGJ2`# zb1tV0XfFP?*q}bhrz7F zr=!Nd(tXT3ccfGb*Rd>92r83hq^#kOO}YTMoTE&@)#o_|(c3t;ft-5w+b?I4Qgtn4 z)phX>COki`x4s(~4bsnO`5|uURlMVqj>H#jrnp3raI}J=5{^n%t@ib=(5>|jPshhQ z`v`QZfT}9`*Lz7{UxVFVO<#)jW>aJAHdNn=_{P&_3_q_S#pJtUs3Oz(MyrdCFgnS@ zPH@N_9c3$dnSNc%xiL~(DBWcgwV&2X2Rrwf%`y-%C%-pV>hWiJXTLwaUbiS-xoE?E z{TjkkCzq!NHBsZa=spr+`rL+=OCWixuTb@&-uH|#o$$ENFoRb9cxzIJwVR+bzA@4>#)rG&@E;ia4aVaFYKzbw!Ld)@G0Z$ojy>4Og$(#A?e z%N~BAOJ{8VN)+G?NxC(SiaoWf`qe?by#t6yNVEN7*t|2=QU9RVpVsP1JdVxW;fw9j zRr9IVNQ&w^IqDql1!U`;A!Ujyk2XUG%I|5YnCrS+(R*;3@ifQiGRoXP0IDVD;;l~@ zXg*|;pWO6m;~Y-}IPbXGQX9u-y5MWK>xeaPxfAFs0PTR%kf)>NP1KHir#ueE=Qqz=ISyrO3FrFJsgJ9YyIut!zD(hzu^PafTc=FZ<=`;g z{0w0ML=8$fF1VJ|`a9%imyaKR{!fuYNTHdQ{`24dIZx#-A8#mRLLRa4bXHrL*C@x; z%oOSqj7kjx`z}bTB~p(xJV+x#Sc+Cc(vLuSJ8xmMCMuNr#%(TtdJnSq4)N z-I0wUY=*sGE)V2x-p@D~E3Di538&IJv)(t>CT_BN=Na^M#|EgCE$s& zSxWwaJO=sf*JMJw+1Jvi=0F7zz8=%CvwI|{SCf3V zCJPXTuPI0;-NWti8=hpg*#3U+oc%2?5KrehS83wJo(P%;TQrt%?}SK_*?O7fb4wnm zKisyE+nYU*RFs}argNZPV1^STDJ)RdXM`1dV1$vEQjbyaK-kNOXguuIvq#SKu8*0h zfU8p=qjArUl~duUCAa=rpQUQzDZCMsG3B-_+P?SjE};;-y9N?(h7Xyt64K@pzB90| z7#m_8wevLo8b|N6DHYERDSf}0mAsYcX+vCPb<#JcQ;~Lp`+e<`vAOcnfevBuvm6GE z%KMCQKqjZ-TV!N%-A=F5^^S~Jqla9b$@qh$4ScuIw-Zh;H)mKu^4t8ie$qz?HvPj= z_Cvhn)f$3`&hFX17Fvxn z!KQ!NI;|@AHYBXVj|J@Gim7D@jCmHYxfW!nIVd=;7I~>yp(bF`nH(Y%g*CLrmwn^3 za5a}vSb}cn1jEvgpN|`&RT{Y5^zt{eGEg_(z`2$d+%w%R6|bxo!ZF| zoDeHNOWVLY7R1LLc;x$jH#%kc6OQ2^RVb0Wgv;m8o|tFtuJat*H#}Aps)=;ZutmutDLVNuJ2QW$n~)=DIqnzA zwczq_-r{*Q(MB(LpZUNW`qM`AZFG#65fN=#wZm2Yh^WtGN~-)~^11GS*q;c{v>Tde zs~&LlG(5?3^8mju_3Yn=g=T+6BXs8&7iGKm#1B5_ZZD;_-npogl?Eb`CI0rrNFw!$Fsta=iyVpKLIfVM&8paOj`!>da+>~kd4;j{w3 z_B1WsI*(BbSl}(AL1^TA>Y_K5pG<50o#Wbg&wkV=%z6#zqBz;{ebKi4g+79bpT8XK zVexH6Onv0Zl~O@4$6FH*==EJzi(lK^CNzM!ti=39Z#6g>jr z<-bZqVYq{c6t+0%wGa?hPV9}IGmOIX&wKUj&3vbn{u+-@EdCA|8Ej7m1-1G8!0z7s+WKYoaOGLN8Ry?R(fVOE!2fD% zmMkI434aw>a^`NJs3(q`EH1YPN)?M@swAPIpnRcHT=u2^x-|a3X|q?Ec=ObuMdAs& zJNT^iq!Q$e_`h}kdMo#uq!(6Mb`#-Ge)+4&m&I{^Y^rI)NAtMF9|pnV)$V=JLi`U< zHzKAk*57}-A#7&9KYzgIxJcXy%6J|BU#a`{EeFhB`R7C#WKJ}je`xN96ga*B_jj{R zngN*ce}~%a)nk^PSzz5ni8=WA+Qg5)7EL=7vi=V=6y5ve5uH~fFm=@eP1&3W-Ej|5 z(40lm!iln(S@GW#_`BD@`;cB!W0NI0t#;kI+FOA=F>LN=4(bgPp1V3#d6PQ@;D( zr|R$e3AhaNc-w!&{qIsc{px|i!H3rWE{FO-io?mtS#S5>6?OvEuO7Xr1=fEX)K0)+ z`d4_B}HuIl(`=551j_T^_7K_!n@B4nNoY6UIElrvJ)5HJdiiuw-Q>*s%%8jRp;P&8j z)2h(&NtNihjYQhHuc8A(at!Yu5IWq~z;Oi|o67k3cxq>DC#U*1FfhvbBGHaYf0OMe zam1U69YFNVt2<@FEdEtlI;m({FRjfZ70=GPKLm&0GrVYY+?~5MIH+u`nnd`d-ISPk z+RXmwQr&9*XBem)E~mpE0RaIlZWo)(tv*}5!CYQ<3}606{vtQe5A@pq^_1@O)dOON zbekqeL(^1EtTkIkxk}lik0sTaHEG$LhSOu5C>@n4jv^Hj;X*T3@}XU$qz+E)0~|F= zYYc8vtI*p0hk3u4nkyQgaBg+aTNBEeq@N_gg&LgEr5%p{VACy3!OpI_pye1XHN%sC z;t4)2!C^L0vRD4AiQh8^A3>QMw)xRX}`ea&Kc{wW| zsnyMvG_O3EUMRsC+PD)YW2s=qOqxJ{XUQi z^Iw3k?CNNDJJ&d4oV=~?OIwE#f@#~D4!RxRWidxvI&!NZT2(a`!KI1S)B-(E>2RdZ ztah?o$BU4xusZ4R4__;!hSKy0*nd!X6i+QwM|XI|;P6lrNMnEOHZ1Dh~@QQ*LK}o=_Z?nA12HSGP+@6}&oenzVhRJ#?3(wdsMm{`usGkg6u? z(L~ZFwstNh?N+TK)%g}lt)un3^bnV$(k`i`FR@a_HV}!)bw&jk53Nd@HBa;3Lp2^I z>jLhR7DfMjKNN;N@upRJ;q(D5AEwR3L>wiDBRF=Tt`<>#AUvI&}SAUlI;ZCc;;kb)hdU# z-Xe+O9bdjU;eC^0nP+4~Fn^wp40)x;(o0>Z_G6iqbnD58|I`&Tv$Nis#JKl^4XrM- zxNRqc*3IacA)bTA*}LKm;lS45;Uk&({Q{($8zfgM61&#yW3=2tZ92u>qPqJ16j=9V zwnXLl-MOus6K5s)R&cxrQ_RFvf@^27n<&yvYh}|hJSH`ne&~DCFt;4~f4)D{b0Bbp zirHi&A%VnGDQNrosXD&vUWG|o_(PipA_@5)T=mlmSk<)-t^LF22Vl{%|Rh^xiz$C61M0dUqT`7JZ| zDRLSGT<&CcZnp`o^5lJBBM>5ewC)nY=N?8OaCwPfG~Xuw;^EVdo6=IQOdG;q9*O`@ zgoN&i+Hk$Ja&wW{bUku9dUO2am~2G_YiHvK=utBR%<&X$nAXnEp1Xp(969Fw_Jy|X zaQb&zdY3^k@}sWcT!R=BbA$exjXO-0T-hIJ)cPi2f$-I z(|<77JAu4JKsL#VA45&m|Ms2A&o5~$EhDu5kF>WAXmWr1$Bly=5#*?Zv;pcyDW$Z6 zh;(kqU?56uq`-)gM+Fo_V3c&nHpb`}r6N+&8!@^YBu2+?;^+D3InVR^>&qYaZnit# zdA+ZAy{Q7{{6s_VnelpIVUuYF{DULc`o$C;J=_i+V46Z^tXIAzcL87PB|Kk+;4UX`EwSi7-HU4#06u#aKk|dAd8i zo&y}>Fh^MnVebcbq0*2DlU;rOt(mtDfB#zFM)z-VgU?%c8;kH#2Vz>FDee_sgY>CM zk6GL$Y*FU|>MBh!O!MbjE_8*jt0~hzu7yr|z_t`9P^Z7y)2jOY36l;!>2q_V`rh42 z6JcK|sIUg%5vAL=YftN4XX72b4G1YY@{~P5fJIS+p3Q=Om3v$FsA@(~Pzs{x-5{Tn zo#biKF5~q|>S1Kn=T6I%-TGK^!PCE8J!HsSM@8?+MssVL7aFEZzsxr8$#+=k@pO+6 z{;+QN))qJPz?^uhoe}?f(g3dC^;fhyS`0Wla^2vOU zG;Tr{{&5EAwN3iD%8#DXwWOUH_f6t-ErsAfM*cQsHM=hUP9gL2J|MMzEd$4=Pz2kH zvKzi@6(*Gh6*2?zB0z@9dYZkGt$gL4`2vg%d@idCe3Zkm^I+a%OO3D+U_)FF zTAuGL%Z5Bkh%7A??-^YnHlG%l6}ZGjTW#j9xkgdT$M@|v+rnCWeaD?<|c)| z-JM%H0?6UhI8ObVAon*_b@z6)!i#9XD6%+^-A@Xi8;>aFZa1$waL-$+qCMXtTuY?(Z}5AKWH~661kxRL zRgp+V5vvM3Z@i!bz4O4xB;C5@bcAB)!qDZ zK$VF@W?sp$J{|P#os2T+SZD!1zX=T$Uft|oT(qV7ZN1Ip)~(=83#(J|OmqX$YFu7z@RyQL)~UyyCE~N#jUEfGl$3JK}5< zHP~oTHW2mux=f{_tDst@)?V;^tbf%@N*e{kSSkH2$+dx2nNgKb5&z?W`h91kGQGtYuj)&Ka+&uM1@Ln5(>h`ddPJDak zth1=}uRDI8sr-)#{QD0#|N7tN+o$}@?Ck%s_pSg$MfIrRg&LvXB!pLUPnm$N!k-?8&av2}PJVICNpWw;ThKi=NOeN(`w^xI9uk4Jn=POSfrIsNl? z$C^lHxX|HuWOa?ur4uI-o}1tez*y3cr#0XIUqV=YAHejc%iqde(?Ij7_$#}@2R^A+XjTkk0xs2bVR#H+hjmNl(gS-x$HDQD zhhIQ|xPY(Cs|#dY=%6|c*IVySIUS_>rqTcSoi))(6iem1c2I-h7MCAI36#T?<1qev zF#RovQiIgp5dE2~+GIRa?~Q7i-80oC!Ew+R?pHMI7u)IX!V;A zN~Vt2II3gKb%_jev7Kp4jFUoOzJ~IcTFA4~{wQifqEk`+`gCh|BtUO+)x8Z_uy^L6 zb<qB^Fpu)}4pU2r zt{uG9wL;MPK;)KsZ(p7UGsm=W;ExAl)$etUp$4XBCei_N#>YY=Yl9 z7V*-Eai;dldn-T>E>c<}@YYI)tCu`#=Z9(;JENA^b0BYO7vG=o?}cUmT~?dN!&sr# z?{__}s{v4Vo4O!yawT;KyDuZz65S78;sY@!& zG8l@ZwV6m_s=t{5ln?!~2!gOz9cxIcEc4@oWeo%gHA(v%+o7Wlnu<|Ppe_A#+#IwM}U_4uC=tQ+6d1g$#rzgU0P z>OI2)*^alY4p=8i#Y03V?OE@)1W$P06<`KjK%S4r2omUh}Uko%CKE-FL#-+ zAmso0bwcN}Ek?VHYLx~l@jXe-`5u`k)s>~;#U}DA?I>P^Jv&+_W^bWF*ezN<)iY4S zwkhJ26voEWYG*jQg zSFwEBZs%F?HF_11sG1FK=_Lai(Crx(Qt{*HxbzM3H=SDH33e>Y5P2@VUA|LG zc&o>cZt9DMh5b;PH+MY5Z9XTz(1!zc0rNgFu4R)1vFnc$DDn(R)B7aLLp(YZ)oyUj zzArt@k;y$F-z~q)ktUZ+Z!q~*GUR>S>Jjn&oFb;@@ppRPAC{`lI@0fc#A zub}WUOEVGqHCT3QN)tC2eNDy5V-Qj-t~?@aieKru0jSN_Mio05sn&mPMVVXjiw;Cy z;7tAAl}5HC^t2~s9eK0huMdk%JK{Q7O_#&i+|s!TQ|?a;PzkMK%bz-fDE1`QWPD6z zA75$MUo5LYr0;xXVz0PRO;5 zExaWrvnXaN5d8VtXY+7_enUy%0+=tGePq9CdC?lQR>os93@8DAWLq>i`zR;xa+lE^ z)y}LC+NmgWJQx}t?S(-jDYr#sQ>PNMTjetBs|Z(RrRT26m=*G#IxSyU2hDv3$@uhS)-oe+}SRJpUTs zC**Wf{hX<*Bvm)(-Pzemq`ZugIN#e@?A5xx>Ib%03+JT{?=&`f?hfjAQ1ZR1@d&og zdD;A;eVGAD=fJs0*BgSq2kbdIf>`7DUigFxjQmo=ri5e%8oI$SB{Rf1d;lquP{}g& z7SDSgWwmGAIy?>@+&-FLh`BMBW%f$kz0Xv<9BR#Xx($UJLa-Z;U>0{A=Bsgex((%S z`vwkeEs>eSe=*b&eRj{bGTDtJ-NL8m&G(k7q886rnzLZ?^G|U+Vcr7)1K}>aSnlM* zBG)``t?L*b;$6lAqje{s>~B?$Y`Xo<8}|;(Cfq zY^h^)V=zX##Qb^TGRI%3)o(p897}lW2f^X~>u6i`9%s{K;>&DLeaA<^^Ml)Ahv1Qp zL&mSOc;Ta5ruI2}et#}17QOLp!py`|nt_A-39IP*2 zqA*G_UCmR@=W&EV1#_own{8n5m%%xGr#YhVLV68=%kNfzZkz02IrQpOIAT;0IeP^da?MLJB zsZ741%+Gz>@|V~2j-#`wBD7XAGBnx zIs4*!8{X;lsR_?-3XKsq4trf1%3e|CzqG;Sw;)i^2yt0SRNOaS4Y%x}u~p39&n#)v zbdKF~?-_{Eksr3M&18IthbM5{pl<}hM@ZJs^lHMi%{BWU;?)dQoijqSQAi7mPo zm`^Jufp_)Rp9HgfLuy~=xlL*ARwR9oicr0{F@zp%>O!pc;P>_dl4R1ISCT0x?ZoA>R| zatGI-Z9N7UHGKty+)=!sp#O0#v4N}d(v971qEEpNSWt0+jk9)biAWD zYjvFEo}j;-QhY$-SSU0yAs!qhq+sD(S~myCvw!1j!e(l+H^$PAW-ElDg*2~kUCVke zRE;TO|ASL_a9C-pcJGbr5GBtiq4t5H7K7lynGi>Ww{>0*l#*)Vfrzs_D!-q67$)rb zkgH_zi1EOAe26gB3~@?Ark)yL)NM~`jgz!^FCw4=_u5&angcfxYI`F_vK(f;vzcs1 z;IV24_;4V8fmXSg9dRfR$lh3PdPK8@eWpG|^A#v``zb?ny+(4L%3aW-TO&Kxv-b8Ot)Q>HK49?*Kxd0S7uBPH%Ad%Lp;F?;ZL=Ii8R zyOK4I8Uv=%DR&6Rm!A+~rzX9V&wS-OV%k1ljO=r%f-ANP@2Mf35EW>+TZ+WnY~Hn&gBFHno1MmA36CoHCk*OR=}1{<$~5Y49Xz6xdg22n~?S`zZN^jXV>OK%|ri>zfs2JDpyCjs*PH* zi*j+ooQ*zK<6WHb(1X@MH-m_iT>4mx*M+`FNc?ghzUqLZO^1eiYROA6u;(bntITkx z>CPsFmq2 zmTRIUK8s3=WH1j)aPk_M&w46Vmc=P3*qJ0PCUsY&e)uusiQs=U9vW3Z5sKkb&I*}y+}+gR0f zP-CFC$Kc>?@-4E@jo{qgze59IwTG#jz7>j^$;A;8Q;=@c)uNbN!=+{`MId=)rX|HF8z~jS7MdV@x=g)+8d_ajH+x6 zx1;XTS1r)L{Dr@MM>Kgt*xJH zAD8QnO0H5CDl5YPO5BoFk_(%KAc{gP%oNCQyFRW#K8AkA6B_y!4&Kit$0;7 z2CGpPUAqz)d(*APd|f4b%DLeU9Ctq+9hsp4yiMC!JA3F9$s(^)YuBioQ-c2-?B?d` z0CL3`J))G-?WdQ{{R(p(m)I|Z?vI3-*7)pq@93#`vq#{C*!tH)o?!lB4UJgza@zB( z%KMgN?uxsTnxl{=7=n{>qMDr-5n*Ynk{Lq3(nN7|OzZMRJO zb~$btkaypuQX>u6eW`;KwLRB}v7wY#rh{p(_FQwW2x~cg1?CTjUq`Ax1>U$?J3_o{^QiaJwhPN}s%0u}YP@*~5kDQK#x~s+xv)&az40 zXM%23x?34k`?AFOZ#rQP(~S~|h+aUiMR+=7;dukFa4Shr)p*T;tN#){A@a0Sg+QUd zNh%@Tl3!xnfGc4=1NGh(WU^~kK?fB{C}Ac#z8go5WPcBHGL`t(M7pQQtO}>5-PDbZ zjg7l)_HuuJA6WfH`Z}mB<&17xWuH#)w{NdR5J(&x|4E|ap8 z`_%R3zphN`CcqKwuJH1Tv^7@v*3p@T`>5Je9HH7FxAk^BYr0bVWh28yl^->#xrZChQ1-$DC5 zzbe<6&Ag||u=xEn_NHft8IvF$jAiSQwD&!7m+BpZ;hZa2UPE)Np;iDdn=4zJ6dkNn zQBxi()3hE{PBA5;o?({yZZaF^UcSB$AuV@M`YzQu0&jo4(FARNmT8|M!oo<5jtZO{ z`7Vqh)dalT|6|I0d+v!u&Hai!gPfErYQqNuQ+5WX*PqA99e8xYUknKda>Qaxo#cVpt`+WX&LbJWzo zmsLScHYvNeSVYCDRWeZ{9cZPhJOwtE;BS{`)kDAKo?hd%kFwPSJg==%G2*QYyKwpX z^_)0?fZD1G7`4v^Qxh^|nuc|*iUYf{D#ZMoA#ysj5&O({o@PQ^tz86o7b=Ws<(Dzg z)k}yJ5?{x$2>Y8VJ`mE%8 zz3fyMr}ah0DbXIHXLpv0eMs4=QfoOcp9eEv>QWS!)`~28_@wIPNvjo!%q23Pl6;C~ z`e9~@URTS>pv9dEcF;(=AGlhJ;jS7gfezCT`MR4NnGzjo=yX`W{4Mky~`v znwCkUpq2@0FzKHE7jT4*qc#nV1+yNVvK6Ts76PHLWos`;aT$uK+L+koP@G5fdH^<2 z4UvW)t{K#%rbsQBuX5`?h|WeiCj?yJQ%-?el4ZDtobP9XtX^+|TZJZ=z?SFCgE_^e z8{2PbZ+@ECTQheNIAvkGv)R{6lu6003$)lZO&fg^vG*)_YB)x~ z*sK-VlE*Z~DeG?O{NJ(s^CZQXd3jVog_=;8UE0-liuEim?{lPifA@K{yphV214vmw z1L#P9?4|PL;n>_W*1pNj%Tz4R*v2J}zYEC>fV+yzy3W|Ws6z917oEQ5Xmo2jB_#Mp z@ow2qSs=}c4%m+oZAQniPkD7%%NDnfhKDqC2?I_nbKJLR-sfSKFM8wJ|d$P)4 z>MA92I;O(uvjxDR>f+IJvIlmFpTVXV5=V3%X0t}sZs~DB4vWv{abqd87m2$LN4kwo zT=81dcV14ix&_ah*6OxG8k#-b3pedFgl5ugGri@t2YgI~ zt}hFTmoJ|yxx7=rUTSYru{k8dThYSsr;*Jt4qWD-kM()Z^g-IlvvxUybW~vgtB886 zJ0Qg`&;t;KWfrcjM;5@c==N!EW%<0}4OEC@j83+SMU^ha+`VIB=ntkLEdeW2oy)dR z=6&x2qcvTEungT;>2Jm>RQ%j9UgajMMpDQub(dR!kT9XvHH8tl$?3w z;xH#S+Sv28v805O>(Rj6O^Gz-;hZ9Y;Uy^o@&Ow(p~cMR%F$ogZ(mB9S0iPnG>oyv zc#uyxgI2B1w2uXkCd!sF#RHFul`#OQ*zZ8sOiN}(RY-A+VEy%4VBsTclFNZO29O3b zFpR|S6Hhk~&KfPE3~zNicinLJ1vS4v(538=y!yI>>}2(IG?a57by+t_&tlBNCjkO{ zH8zdYJU|ad?3DrM=6=0<@wdhcdx`U#T=4EC-Pk}=Qj+)pXiPZtLS_d+(4u@Is%A!- z&t6(UIbwl%`JRuIYjN83!REegbk~-UUd=cY=qYXebO`+tTCBWA9;c~1SPizV36(-q(SsI2gU9(4d?6T$Bhb2Y^w$H4DNj$44I=KpEz&QepB%DZ1n2Y8- z-xN^|VguNtb5@Hr4)17Ktoqo=%C;E%lrHRo-Y3Qc7QznBM(2O6UO|Vzhr2`vxcQXj}y@ssvb@mn7D=L74m2@N|aAG7(++{sDUZ##Q!r zLCgQae*d>Wg&t3xNxtW`qMOG2u10%*V5tVG8)Hzwph zQCVBaJabnt`lzb`Vco(iwI6RDJfGF~Kr6?7?|ot7pIig+{Am`Z73XdBn+Z{CgQ&LKGd`)L+a&=)qvChMT{pZ<<-lS2ysQKO@8<)n1JVj|45zY%vuMv9Y)%H%@ z_yO*Vn3suqQAvq{-RwXs7XuRee&l%EYqhmoDVnU3uJ+)^OEMuT@mv%VLJmmS`p8I)X97azK44SeYyR1%R{2wkWgBT&G zdE7LBQ6-aGewE5+g_PRH3RNzO@QnBq)0G)bW3&NOSUJ^EMU52H2+@>Ve zzuUGoLchJ>#EDy>Bsc|eR_=Mh6Y~)~=P2@}kCcPBQaq^x1>)Hc#edZ*^kFm}b#x+7?jIXK{ zKvzb+SgP#H&ht&d-LjMfIcNc0-w{eb%HkJXFI>ByM&(n85+uaL^tq&5a>j#>OX-K7 zoSfVyyjGRG@a0>3`xXN5QK^m^&Y4*K(W+s+3sDdMx|E}OlkjETl1`uIR9k(l{XwC7 zo#kx7I}0D9!ZMskNgI#`N{kVI?KR->nNZ6=B4DnojCDZTzYgrf7@wwsM2lW zz4UU&klP53npr7vRmNXM1vwf*A=oWn5FAd%M|$C9Oz?$;YsD{=)2O>$;aSYVPp{ed z389}y)Q2saU4?U)fPa#g{G8jL6-4em*)s|v$lg{HZY68G{ATq1(=DWfFdO;&S)qD+ zJQzZ7K~vcpSsNQJAzad6@7;~g*Jm$HI^F}y#Kb12vdRr+_N!#6tCW5`fq-$Qo%saz zSX(O*ys8+lm`1u;bt;0*hyBHKX{b}q{k9KRNKQ$sg2z#HN0TZk&-6iVyuv>JVYS$C zr~Wu-ld4Sci>{Sa+#6o)lTyl{-#T@}hsf~o)H~0=QUi8Ll$WAbZNveGT0s@$JUaU@ zxq6R2G|hJ4o=;n}dAA~aYM{wQByHxObX^&AZ&L7#tuN`)(w^|tzhu_ech7xt;z8K8 zlq+dh9y4dCo#nfqGly`SIr!_Nw!*1DqSubNl;2;k^lbMw6^-!vkm!sD9qdy0RHA^O zE^1E3jczS@wC~a3JT*i8NlVcZ=N)?uNz^6#O<}0&#EM`hS+1g?JnF*@nxsanco-mV zN4bh+QN1T?o1Uxbwgti+tzM5pW-Gq|YZ>FLN(mOLAsvBQ2HHiJDi<|Xddkji&JJh* z$PqV~-+l)Xs8pSrpO;<4 z{0-;%1|`8_y8($G{ypkVW>1fzwq$>i)k2Sv1L)Nm1~EACmiKBs zD{{GFhM4l;Rn<*I_ChuV-7Laq=!Gz7Kv}(}B6ZTPjQH|YoagB*S6U@cw2AWy>J`KW zyj+9pCdOuz$@gbyF%l3WU0$>I3(rGm9~^h)=(S7>si_6;U5ot>hQ4a3GbK3J9-II6 z^9e^B@cU5v4|r)wuSqwR^ul!cviqlV8c8ySb8~ZXqE_#1CE_8))~RK~NHx7|%_!ay zSofp40EP%&aX9fYw9=JCO&`+60w9-yGg3OYg_uBoW>FxECK;ET^ax%i`4e&-^Srij5Kd0lI` z)wrW)v>pS_HSk&Ut?9564nspPmwzMk!)*wm0>6~%BQ=x zxg`GV%b!1>vPNb0q#twF&+mly_E;dK!YOmPX3ze|Jfg-3yVFDEki(L#0x`N;#rhIn zc64&rQxXoea*^#S+FA4gEv`!=fx+v}U3dyO?#@*Y{l5 zKyKt?>bmsJO|#BEYT{u|zq&JU>|Jg_Y-}c1U{|CW`hoO*JFO-`*6X=KX8^a7Xd<8G3Ch9aEgT56LP2cs>=^ zz-HDam3x(XsEwIVErS~UQ$3PMnd3R*Xh;HbWZ7#p0|dL#o!y7KWuDFhaF^f6fsR9f z4rs^M5DqMLq8CDN{)N`}@B96zI+YYY+i#T|#VfnkcpcuGH{`EjzS=Da;@q9oCKxY^ zdCT6^#H|3()+-8t^)KwhK)o+vFTPPFZdx>_1gJVk=gm(9H}rxc zt87A-eeOOeQ=-M>)`Id*!<Q$nbrN<&{v&h#iP<|EA3SokXO01aDOZ+lph}hF&Uqel!@m}oQ6vId zjHC+!qK{-RW*GW%62G;okevk7RQge^_Mpf4p}?p=iFVA@=HZis4>Y+o1gt4T6qF^q zy_dU}P-m$6f@6(B(OvzE2ZX+y^H}Zb%1_3q)%QZfja}Ig8R&28voW|=>7yaa_VDDq zlaU``FuJ{5L?=!jI6o-N?uw`^3nwHlh-1sxNAxvA90*?&em0BWHKibHDp;DeTJYB} zG{)w||3}m6jiAzv-3h;;CBOd}oc(W@4;7O7AIj~ohny&f{~v&4(v{I)?ep{EQOtw? z4GjkU9|1;eKx;Qm%87)2GFuD=N1b`x7gB{RY(?_iFJyJ0M2ioe5=0b&avsb^;g6qe z&-+6(J$p8;WXHk8l!2toGdmrtSU=zEXyGnKWzNS5sfZ-6t(vo0i6%lQEnwM0PmC9T zOlO~TFs6#+Jaunk+~sKdfIK0gkA=RG^1L#dP+}1X@$q=9LRH+5M7;xTt=G9fT66Sk z_=gWU)b=tamfG~>0w#agZJH~-O5ckoA2zTI)!x>j?H+Q9L)AYEuWQH~H}k<5@Ttpk zyv78r&^&qpRoS&yNjq<;N_M<2U;3sa>>2Crz&Rp0>cy^^Rh+8@?HpRJ9#rqNoEm%f zZQP-9)wI1@Pw9lAs;eOr=VJP7p%O9ACxaYQYWid;Cd8v{=KNAnZ?+nvjgD>HdCL!L z3>%;&%msFLwG8+UboJVC$q5&knDkR#D5FG}SZ2$=k$$$&kK@Ovu}(i{GZ%YJmB+n* ziXEIuC zaZd_NBPP@h>%5{o@@(_fmqyCf7&T;bTG=X+-R5RHnGRgVl(2f$2)&U%nHOC*qo%v! z{Np!1em3WuCfDXp03aL6LDBV=bHRIR*stQ;smD`JtMJL%cCoDxwv5Ulxyx#OKOTdu zQp53UGyf{Pv5A3z51iV=b0ga8v7zh8ywP({K-n)~2>O^V-7d-up>Fr!japmAbL4t< zI^5gf16_ii1Sg@$)Q&Wi3|RToH)^BiyVF_(TbUN4mRwG2KZ?HT?!EgVY5V$vX7jV* zOt}6;G`qM0)3aH9_r3XNpt-c+wL7RNF5QQT3oJT(D*^|b4L*WW^Wd+4yK4;V=!yep zd_|AF9*(PDzwH`n#u)uAXOblJo2f%r4;nDt`drt>0?N6FHeq(w{kA3Xz1#1u+ia*U zz``x9w7ibk2W(2r1hs6z_M4wWJih>9%3?6!KYL|yK?^;OSSon3NZf85E?Yzr40d=e z=S6rKXPEh=?=<^*!wb82TD>)2Z22tW3ni;SXs-`vN&#qas#Tx|RC%1Z5L=!=+jB*B z-Mx7C4@+2&)?Nv~2xX?zPhh6hwxt5?TT7siN>R2FQ}IngjfaiI`F=Nz z>vzlN#LaJT5xpH2iB8!}y0vjWOY8!kZ5csBO)76CJ>*>!GCein47x zx)(&F?2<0ee(Q)scv5rbxwKrTbZFCQL$cu&xhiAqc@ zfz4co_vx2eHo^wDHJY0x#qhX$@_zpqo?=ucLWiVM$uA}ql<*p&=%Zlz4;)I*hs9(F95H!UN-Fky*v4G&)mD@rz{z*>)=gt;psJWQrKQV1 z2Jw}<4wayR@rxxhjzMw<9>L2Ftbzc8t!atQf2e0rNrzx)d~4QK#ef|3SP@hPb=x`X z#;~h}{X)xM(W~%X^k3^yPq(%VdNoNKkDv~QgKXp%Um^ib7uj==pKhKa2WXVE>`d`i zx2i8m&DW%e=YBfREdPS3s4KA<_)#KY2orH(nMhoeQLLLm#BSc4a?g4nkD^zMQrk`B z?rBpbAD%{TM?fJ7=Bg5bQm%N+*pw}y{7;#mRrsml@~QCbmp`Dr)KzS$thqJaaUyWH zIA?Z@?pVz@p0Fv7Q}Oz)_c)P@1r1_8`|i}l9opvuCs3@dLug62vS}(d(hIJOg%br+ z2d?F=Q3|jR%ah^J8#-YW&gZRF*#!_Gv1prHTQ_cI%aKOOGM;zTaza%NGoA|po@=Fn zE&S1j4^Uq`03Q$c2VM-|1gt(~wYnx+jbBPo9;ftK6+lo_vvrwx9g+@rUoZ~j`cWvy z7w{+sy|NoqVoRZk?6OP3TpDd*ybN%okbf9H(lbk=Ub;`8rUWqZBkTW*Hm`e9cCU%!Km6NUN8|pxtP3X}zgP-n!JnRR0dQ zzWl})sas;x=XboB6# z?I+GzFRWk=3d5f)j{XW%5J0Jy_1LLtkMD@IExUM&3xb37)SJdL2MGGzEkD68qlNBO zHiA1yD)w_n=%D6Kw&yyu^&h(F?nJnRmWO|Wvzx1sO8~Tt2uLd{;{m-CRax<-gzB>Y z(fnfjjhs=kU>UDxr}hww;pLN7m1zoggkbu}?G!9!&!`_!SQGRer5n**0+29_ElC%zg!<7t#P2hxh)~)wvg|xMs@2c; zg{-MFXiG0F9FuNYI(<~EH>LNI36+%LzBQLQpyof{Gx{pd{Ts0pAuZmRl)7wDo#D;a zEcN_u(KE)`U|FG9)G5`#1s3Hv76;Y6t=sp!i21pp`*dSrKRhlULxiq1Dl;N-@;bYF zR8eO}G`B2|2jlUfHygXFX>CTEsA%(W4y^%TuehoQpbed^j#bvIwtTUTJ>sG&TG!^h zpuy+9r0pU;>(Ap)lb4)ebwN<1lRs}=me2(yl2}LDclIetPpW`y)h)xfS&>Kq6?q;t zDLa;htaNh6jr%2^UlPTL9n*?g#%CMEmhbwOyxr8Rc)1+Pn@kr@z<#+DrY4zWL>$bW@|5pU=vgKC%)Xxx&dZ-?(Tl7$O?<*YjyePPq;g~sh_WU zSM2Be3?yb%H)&dMu+W^jr(fU_1|bD$dj#`dzt6ad<87(B*Gi7fDt0twE_>WXvl!ZH z`f3Gz<7mfI+(RvBGlRez4|;Go4CETiMn-W;h5LiURV^s32Zy`nFRFZoV=>-n`zCw6 z$0=oLLAzK`hEhPrJKL>Ht53($gl5{JXqMv1?(rY+~+R4&D4dGv&4ILrC2H9RY@ zra~!y7-+gJAIMXCB@EtusQJ$LEgyfWL+y)oS4VhYR`mr#$xm!&xo<|7c>x zd@I@EXQ;*&J!;d~bon@mkH)zw(j*)WRwz`n~RFLml-aB6$C0}3AN41c~&hhNlCkL%WL@$yAM*T2M+l3oZG&VoPPr$ zsj18Ev(VO&*y*|Xf4$z3tJ3ULo9IzoX621R9NmQ}aYBO)oy#ASMM?y4m3utoyt{$( z))}l%b|u1eqzw*{Qnb0@n^(UIRzbzGXXB2(@RJY))xkqj1n2ZkUUMkdP-u70LOM4> zf2GZeQlE?lcIO5!&kvbU6wX_Z1=dkv-FmWOqMG(vy+1wK|1FT;0;)A4Sc~dJqUvXn zW|w2^7`ny8J*Jo#;$@6wIR?>g$Qn>SgPw1f=L#P5sHrB7uhqmU8Yv;Y zdT#R@v)N-%adTvXD&pvV_g6;n(rCn9VrKb{aE{eVuXx@F6j*DU8UUuuCLhy^{`>Y5 zC-M}zsqjXJVVMvfc@v?Sg+km5k-@>#M|&>=3|2X`#E+gPPE3r;pox; zheQ+?;bFfB;`@ZrR6a|0N^+5=kwa_IokCAiXA6fWx3pdZ*emA&4g>5OF*1?+1T@J+ z@A{VL38`3q)!w(X6UH!q8Qa;55tI&xsWAx~Kqpwrhduj+NJZ z36r9-(i0w_x4F5j((=9!1|SOjSk>2{+QZei!v`hUMqErGW5=%Vp7^ zI==+Re0;0g$vaCf4h@bw<}1C)-PH7RwB!ZrQKZH)R6qOLm(BV4bp?6ST63&$j(z`n zuA9WxaJx(U5+kg}O_9R69|@$joFAR0Qtp_-l~A5Xss}YwAKtUo!YEhE;%F0M?c8j7 zbJ-vfFoU|2j5*;W6UBRqJq75HZA)7A=!&^9ANL8j1&tU2^ z?vT#k+}}T{J_;FM{lU;1EZ6zrxcm{Upz0+GvCf^*rsBwDjzXg)WOnZWkVSv-^9{#h zVg!DxWAG?Gx3dh~8Jc*QPJ4#21B&BM>Z~?I3DDUQ4eA1VB^Ug5OV~1F?GC*ceToan z1{@iZBW=B_CI?JTB4f6=ob#dd2Kerm^&X{<<4clEWqvJB+#t)TPqAC{namKq9k6Z+^uRD(r5A3i&j3r~Wm|Iz)kc*UC zz{T@CI`GGe;zAC3n}^;~vo&uD*PaTqqqWrnz+PJ=JvS4tU$*-LtGQx^EcQguT(+te zsE9-*2z6h~2uoStH@sX!cYZT^OjF0Hc}{wCP!x1pn!ZzJC27}u+Ir}sQ=9+K;rZXA zpA1y|s6w>GZO&~I-)QP4c$|HaNgAa;cNa|5<%e8aGVMvRFxAK3B4Mir ze!k1{$pV7za}P8I*)oLip*rndJu=zNvDv#v zSr${!+kAv>SGyzz+okv3YKkCaT7P1!G%I-Q)EsNdPS(|h%0X~AUoUic*`CePb}HOd z76NT>5PDh$s{}UahqqR1@q_J%2e{q$s4J5~-9i3y)2$AapBSm~ zdc?{jYs@r3^5%=pTp{mf>FaCj1}PF+X`R}vV8uIp&$Q0jLS=$&SM+NHrK-2~@~zAg zYL`mej6n|l7e*6wc&u+5g}pz9Yz``uTxnq}ban<54qGV@zP));HtL?*e$(C|YtUmb zF3dA-$)R+snUCWgcUfvA0B0c@Oo#28?Y>@l^QNyIW<#tcJX=arwU_e;@nBqqb8hLj zbyY`Oc#Vg=b3Xq56A^sAbOvft#Y1}%t&Y14?e7KsVD9>*pQ-~TCq^pV zEWTS;AS8hCaofoh{nS?T^ZkT8t$Rq7jxF(1(^LGuyuB425y>G+*3 zZ>>tzlJv!DEWE-{eYq0rwV({0@I_;D@Lb@h7LaPnt0ZEzh6|%po(xp)fJ9a}Iu8c) zmCNBpI$`J6G5uO~9&AZze__6zGZH^rzBL@MxkA7vXR3?!YaXGFGlclvE+K0el&kdQ zw?Pk5ra~cV3cOj+{KL|VEikzo--;SsZhR|XfSWi&fZ*`~(l{l=O=jcJKl^U};l|7q zvr3#GVSB{|f_WD5Y!gB=VZU%LP{T)t!G%Oej}dYsqy3CVBO^~0-=I%8(CZ((_Ahu* zNG$vawo5(tRhcLKxYOL;8C>14>?o+S`y*=&kUDz-f&lW5Uc6-^!3##~YRSQ^PbisX zdF=$|XbJjz^JRd`@m2;NwaC-EBL&l=T!r^Zx~QJ4bjA8qWuZ;t)vU4p(Y{LtiPujO z;TjjVg@AIQgZ!1PSqN#jxd)@0pl9ilsDi0|!`{xuba}wtF@SlY#@ovS1*Zv&Y{&9` zrz@_^n*g;@j({ zcB+9L(E+j8n!*Q;yWXkU_sX%^rSo&;=A&>`#it)xVvCS-(k2ST!-F-8C)4*r^DYHG z3a{s`v{Ylpp=$aN=Zsje=Zr9VVTKNC{M0Q%&gOOyT)gfGJ1DQ#+;_1M@-Y0G(PAjy zx#YF7>#=DCk1lX*ho=IwR`NI3kg-BTf@ypt@|>V*`S6%F^-5=7)o^9_v9L;WoqBF$ zC4*KMY9_DKW_apoN?{(ykxTtY8Ym_;ETP*M>ka`zLTkf2+zL!=0`K$sTD^Y=L?e{| zKgD$C5;OeHq&tJPeLv^PDxu9ZD6D=&KH``>E$r;l!}C!Nq}9_$ zjN$h$P&2DcQl~3!96SV8Rk5%OC)sIpHn2Y)uF1bg^TMkE&-ff|ft&VvDDz9tS>^nc~2UZG` zxx~Eq!P6oT`KX&?dVzLdtv2wWMAjwxoPIT^hhl3d0hqIYO-{`cV2cVu;XaIW0MPCA-Yr%MJ zl0sI)oe7?k@m^f$j2=qVHymg(@U+>7Nc5AiF>aennjS=7_yQ4xZ4DRtFf1a9{{sm2j~&|sC=U45 zTC7El^&hdy5Ge31+^bz)XA?w|R2+l^x_o?AT){YaS7{kB6f(m4!vEE#}(G)dcepsyvo?^wZsA5*>? zevM{8m!S%E4C<>1Qx;Hcx&HQ_QN%8v@!qgGdLglogIqV7qvyL#1tJg^rn8yRFokj6M_A9ICj}S0ALdd|k`>48YfAI2*i_^PcKc zusD1sEBRu*wZw{Wd|BPYRN;5!?xY?=zUL^-5pkQu0{r`xVQpcnZ5tvrVJ2oEPfxKs zfULDJr&~vazrbgzZy_JUSI-XMIaDh`O;v_7-}W&F*b$a*th)1A!*TzoLCcg)y#@{z zXrm+ZXA#LQ$oWB%&KjA+sR`rdZ5BCW-hLe^teJ4vb?vZ63v*56D%hchK^pDy{}X_ovisqI@ZTGvJSUX+pUMK^^VcdA1y8AXchAZ zH^UT&uHD)^Y;csn!f|+!M**A1o~p!LXny;3y@fT<7lUi#cT-0qR z08>eV&j9j?aAM!i!beV`TSE|dF(}4$2_36c~` zn)h%J+Rwf#=y1OjM4ad5(2 zj_5#Th*nPFWh*USB$VTkPnUzqG(W6x4c=Uk?K-U2Gg`1P%xg=Xcr?qPGs{4v@5JsZ zHwc;Pi7s56UpVKY>i5{L3bLJ5;* z4z=%xIDM4+Xf6z|%A0;s$OY#M4mDSz)W48q-&GwE`4utz9tnecy1Eu!*M936c)iOy zAKq8d@`eP1F?_C!+|(EY0#@N;f|FxK@Nrb4MAwN^M+p}YCdZBAN_OQ!HiG74)T;yN z?*!T;&h^e}u=0%@IFWDs-ibA$(xp_ytZGPh{{7aHhPf%HP~TQuPDwMQqu*8R(hY- z?E>TK6b57jtDs$Q5t370v5*hM!lg=YzT>x2cN+AEMFQZlT z66ueViTFuFLtAu7%HKzio7)u>+@Q`RI%jMy7yC!XtS0N}zrCV-*6E?L3Y%2c1fe z^*HlV{hYyr+2-f5;YkAkN{PHAZnQ5H*k9xLxx2r)-QWCrl)6a%O+ zg3yv92=R0eZ(n*OoBkLbAmd$ zGrQ0#KYbb?an(rt;`*9cXPwyhCFi*@RM_BG|fpxO#Rn*!yNQM9t-~Jzd6g8S|PctQ&*gPG9puec}YyKLT zE?d-x_NM;GbOPBE5 z>r3-TJ>7U=V_9lW8WSBPMsFF|Kt{WN#&2hDkpbRsxf_02CBYfDaUvumGDlv2nfL8= zlhJyJgC%$4J=vrZAB1(VZD}uyp}zIdjZ+tP!*bcx$Vi%h`cqAzsr#HuTbI7xyiIQ8R57Wgx%H3IoKJ5Oj z*l1k)N_FM=E;}V9GE>%gP_~K@XW4%~`OQsF`Jc#<0h!q2ncULuMf>#KHgMe=>5_}H zz>@dCGHEn%+>Gw)gO;mH~8sg-L8(ptTJe*Zk zO=lHt5#LZeggtqW&>1sI3-E{#a0a!fQOK$DGNE~(IPoS%%%6GB`V)|wRJ^R7MVaU;x< zL@d;iLfRF;ZgeCw7JN#6db=*u_)>i4Mx-)M^})*t?X{SiWj_K|>*$3be$sXTNQkd% z@YJ9ys72cdJk)rxawF?1@`~2IR?^6OY?xzq$td*Fqo~MA_k43}_|A464SU@L=^Ow` zDfOX5)@939h+baa))Wn^GFS}k46KKAJ%}~l2n{HV>_Dj;KaIQt`}#`1=8`b`+nvNQ zhEtvRHH`wcu0XxBmFbZr2#jlP5b|^6N^`~fd#(_X1MKE47OdG9kr8tvxnifKL0PLFdR-0H61Uw#t_43~RCxmkcUr=zxz0{Wp_>RW@?`+-f+DCmC*U zF1QZ0f5a`Keg`<4>on4#@3W!+f#7GgF6H`(#qvSh9B=9>Wc^+-Ltc1jXXO$xtJ2u; zRccbbJ8J!P-M&!qOIgX&-R;{~eS<3faH!1O=iL5CQk#Ti={~fU{o#%B|HB!VS;-as zSnqVla*^283;_pseyoSSrlMJMx&5R_HE@nlbv>Zm=(BX9WT_uFeG~<6JvKC>xF1m= zds4qMuruDyD0-_>h!h<_eV8-sTWfKIU1Jmuz!~*52jG}<0wr&ne=IbYje;-iX9X1o zWsq1j#|n@3%{$jCF(R%4o@%EXF&xgUfNqw zRZx0Y|E#l$;qtmlgNM7S+`BbmD3OHvvfvMy$}-t>?P8f!Tv0F#zxM-xtN*uIm@e_nC(r^3hSS5JDcRTVRFC38{7{~t(k=5zxodbdN=4VwiJMQ&%Rk zE9L$D(8V*tE#GMv=XM&5rxEvNk|}FJi0J}rtUT=U@|S^?J~}gy#ZN; zi~_6O9}B*XVU2)d$@wBm7q22$H7kz3odqVRo$!Z+%Ry_x^n_}^Nju~`a|~A zqR-5ZI)nSRCEm2H@Uc@|u&{IF_8W~bNn9L&WxcGI&N;WApI}!X?=q94* z(-(^a9r61cy?gR6K!j&WM7f@TJse=36Tq|am|V;@wJ{OM{f^DUobWy4SneUt=7 zvJg4%@!rMizL|E--tcjJPdoiYYw0jY_fd0eK6V)R$FrQy#q)w+9tyzS^ZDVuVzj`f-x1(#@(uXEgZfX} zV*Ulbuex%xk$WM=os|jnXGuKsuC>w^Xsh8T0v-M?6=qLs{J#Z{e3iHQ z0Oa>W)n5cyhoxL75_=A|4mo}!C^mH0KOD3(UZ7qBiU)K(bzjb+6^x~)pe<|yb(b5W zg-ow~f6#;>${ef7)rqd6CbW>&b*r?yCQm{IhViRD_bLV^wl)g9q z$H!B+hE4W1%%w4^axo>f|3;0IFqT9xgzlC4J#IFqi*5TPQ+D6uOg4O@`QM%xstZhw zQH%dkP;92lwpvj!_2=9@#5px|`ZjF;J#EYe`6eL*z$_C(y6Bz>X-V_cc7Dos`iEQk ze;&>JJE3g3fqFM`!YfkCs|^Hw&GqsEtj^&8pb_-8KzKabn6_hY{JHruBM(R@Wta*p zSjNS)9vziZshN9Yh<8Y4pQOa;Jum<|5wxcJW%Q!I>@1&2F5wbCr4r7kAL3v)x73El z0Ny#XC;zb(pE{a5VTdJoeXAVG^!Ep(ao2a#-E56-ey~uy%Lha@=!a~XJZt}L>9x>) zKs3)+bK({H?5aSXxL*wk?mV1i@WkzB-yXcgleWcl%7p6)RFU8r5PheaA3_^Ia}mWY z`+Z{Cdz(rE3b(s$?BPUJ`X%Hwa?JJ)X+xdp{|J$CGgK2$w{8x7H!O>#CuW1CoKj-g zQ5d!WtdTS2+VW_oa8Ng1!^NVy6XNY@bd)>clm{?M#*3>KwSEEvliLX}Dhx>Xr^~7` zy2e5x)D4!I#8K@jo63SG04M4=Pw43?l)HE2AvAAx96hfBfx6 zUA}SrnB29?bsqi!p<(*>{)jvDFmW|hLGO}O&3xvz?gM$i**3U@C8o1 zKBGNb#8m4$YLLyS6YIL>s0&K<$cIrTg3kLlqn$$MfXI%k5}Omi0q3Q91P=0r&UHQ; zJ&xbj%y&119~mzqa2~m0pIPz?OYngJ^>M8sAIua_aEXy19aSL-Y5^$BVhDv0LOV6k z?LyjfqdL$&VkD<*HthU^Y_wpb$RXO|!2^@JX!gxA~S|$uUMy`WD*8?kAM$1-ofAOgA&#S~C z=3kGL=Ds^TUA{JanFVmI#dzl#KLI{G44KWD_S?`4KxoFh_;5OH7piZrZJi%ww29XZ zLlaJE%w4sTtQyqUfzY)S252XU0U85(=N=~RGql1-C zTP{MEj`m5)jmo>-(=eQ5(b;#8AQb1Ik;$kdyRj>6Pe09(MtZegl2e@RJC7#)gYo2$ z<-2wKv$AU~h*ePK!g!)b&q)mz>PA%nwRM59xUJY$?ml9ugM&wIxeh~>1H$WhK_=rl z{o{EHR|UMaWJA_$O~iI_z5h_pTVwM z4qm&s(YdusO|&Q0dQs`Vs2jZC60Hs$RvBf)2L-Pkk0qmK8!voFTJ&#A5};k+@MJ20 zms`e24@1`W04(xUAFa1s5x-Vf{IMv^8&^Hq@T!mAg*(zYsl#(_L$k%C)~{Tp=~2l% z=P}lG$V{>4!4Rph2vQ@-1)*liI%pY1ozD>vw=faO%d)ceZ}Gi7bK718E!;<)R)g8D z>}rqW1EICdx&tg0>tT?Z+lL)#iYV*En|-ikQh%|gclKBlCfxQ4%9~dV2zBxB+Y)K2 z`b9e54?pl3@28Ue_?^iGcI?^f6_4iSg-0fn_)63Bmcy^qY#GRn2X}<+@^xr?=LE`U z=t!ltwtSK2I3wb2qjF|+7x~;Kd#;um>A)*sd%@nN9HC}5J5;YmE{z&PU*)Hjhsaba zFQ>2S)os)m2OE}ULxDp#iBM-`$KqO3|kv-NRz>3{|tn-MmNv!otm zA}M?@DWggiDN(c7M!5vCLfXBM)Nep=&}Ek|jINf$D{U?m4mB>hz`bh59zRS#Us`(# zkv2nQ*U2G3#TL$T{cW@Yft?2rSp6tO?XH_y?}KnS0Hf7OW(x&`%*O)u(Jn+-OB7^( z!-635s2J^bQGi$LX@#(EGTa=t9ME4o0NC5Fj$HQ<3~X@K+4V~-%{#U*J%Bc;x~w5Z z1Y6oDcA7!LzFHwR=eTkBkXN`j!CKOEabp|BF;FyY3sjjxoS|qBj42HWkXnvHFt9E@ zhTKmN{SQ&al+~|(Iw|@X_v+*n58_rBte1u!phR&vP4*IpyuU&hz8!|Fc63o!gsHxg zr7kAPYz%#TlN6tu8C2EB!DTD~I}|?${rYW%)R$kPESyk8B-X~mg@sbUJ)K}KarwJF zDYje5ItI(f;T|ece^nOsej4OlZK$V;>{m;0>|j(k_h&gXw^U}*u6R2kLHH{koWkXBLk-%u5%OM9_ zb>V$xNegIP+@FKXTYpg{bc_m|1!ZK+hzOt%loUyc60KkLJ;66OI}82vDM1N;{!R}Q z#K43pWa`3TT89Ns#RyGIO;_P+NBxK08o`x5^SVHkIgm*%TeQpsTX#h1|ER-Sb*CnP z0@BugbM1SL9ZfAQIgFRGvNC~bY($yZXMg89k!3Bp!#4h5No$*^sR0(FPqR=5 zkF0-A$Qe(s9x8K&^(IKUY~&_vi4dMS4&S&Ad3Aj@$+zKWtM!AW^f)~y*Ee^gMhUY} zqF~X8r3p<(-;crMMl#KZCN{zQJFZF==Gx6&>`rle?Omm<$9d3#J7RBJ^@fo23+}`f zdfblGYKokwl}6BjOHTlX6tkA&G&Ni%N&R?zU0@|n?S=bAS_ar{161~y@>l;fsI`-I zD8pJO)9l}--=P~ivq}@08^|%ngXneSXpx6Wv=QTv>Cft&o5r)p*muQ64_a*>SBb8A zl%z&u2*oXZ-G;i?uCs;Emi~z5-7H&qBh}f69LDNEz! zkNqY~0yfI0BN%<%Y*_Xc%2mdyEXi|PYscAfUqj&}cBw_SG!WazJ#5vCqoZjaWK>KC zSOAfbQ|sox9o__A?hbS551n7+W`=z(A8zhMvS!%wS`{g42!4e-cd;4=cl^2iwT}JI zGe`~v>;AlvUb@-Ot}T4rN@wXzDTW|;or!zU98%Wyz+&=?Kg_yD%nb(Q->cV{D5Nh{ zG$C}Lvflm}*gQzIHP-n9ElyObP;n*hbCA}cYV>?}IBf^Mk-uT@taztV z-rA&}2fu*yiY;sozbI_I`X)Uv`O}Xwf+9WzmLdbM2Mlv7VtC#QQF3zI!C8_MTZ$|i z7EoT8JZ66b1YXLc_&TEU!j3+eb0f6B?!)GJt6PPs=)DYN|Gw$aZ+pGpac}MWWG^bP zKNE3vFk_*K)7`*FRHO99w@6d7WDMWcpv9d^Hbg&GnzZ(?r}RCgKPM<;rYrDggyqR! zg0#bq+t-{v7m@+fTN+%W*!lumoe^zR!cqkT_h}_Debr2rG=oWRD$J;uep!bGE+IXf z=k$=qZ@aDiHCh=uCquhZO~^>1n7-<<%+cfc-dABAiG#}_!dd-6Vo5LA&l- z8y!6ESfnOTkKWO}l=sJU`=evN7jpHQw-PF^rCmt(3)8Za+cF9%b$UNl17Q%m&DHC8 zLzSQFDUSM~iK2Md)WKC}owqv)=1Gk4U#MzV-}PPjFdO@S>FDZWYQ>d15yyyt@_88C z+;6F+zSHj{Rk7k+2_7G)em-;KRdcQr6$fpxdFFxNa0!0$fN$Bi49RE2Z5%q%II^D+cxS~2TlqprwpU~ToyMi) z7*^8R_;cx>&=$PIjPVz-c=$!_D+Ipur``=~n!TElalM3Ma0kgdYNaNY#1po(R~Tsf8T(?}%K$&vFdvU*Fw%?pE>`E#>n1mEns#O5J``Q>?7GVZ{D1& z|B0_-(nHg_O)+2QxK;`Cq@KD8rj?;1&=+UV}F1y5%GuEOuy?15P z0ULU0tl1!nY`?^o_|0&;*Zofn9{H-%jfO9*qX#XwqKfstch8fyw`U4-jS>L$cv>Kv z{wB4b|$Mnd7R{>GfuFOXbvf)DV>LYwZY@i>eU?!gr~Jja-`KqXtk11c$XmjuXprTn$?KV}52@ zdsYiE4m$=URJd#Q!}aR?mNH>4j)vUcj(Go zQj|*GYiol9800F~jK5pC%n3P(1{whK?fl#c=}IR%#|W30L6c3RkPHirh{VPVzc8gF z+@9X~Jp0mTIS7Yd=GH{?>GEI-^9%1pt+RRb<_$(+CFG1v@ZPaQLwrZApkrA_s12fe zs}A>P_4+uqiRm2BwhD zoh?P(5;_8u^M5<`*u4~|CB&a**MFHPrFV_g=BWGkFn=V;m#Nr_Kh7mE}uuzP*zt| zTxOOzDr{j_tYb59JOd!QBZ!SWnP_r1Z~xm`nE7mEceDvWgn~2o~RXV9vL?Z=^b6fg-xt@`;6Wj@d1cYPq zxGdogXyvSLVy3o!8wv^l?~fQ9DTdp4V}^=aW>Og~-FFLfE#lZO)io16oiu|KQfu$- zmBo-7E3Z3sz86bhSv7dtIbN$Um@&2hwr z5M~WA44D$?T*L=Na7r#dKc%p@V;r)PGb=9Gh#)EzwMs!(5g&&n=#M%y+Ee;26@gjh z7IM3+`=jW}z8?pFArVPsZ;;g480io>+iA69cgJP4av9WNu@Nr&4TAgoyHGyN+A-O# zB458=^ZlWB8=v=?Yd2tGUV=lk{MQDS{o9uPU6{4*!F>ff0zi{sCb>YiNbcu7Iz2ft zae7hw3CqiAma3{BQ04WF4FxL}{fC~GR%3G=874*kWsY5-;NaR!-FdU&@C|%H)9lhO=YL zcNE(AW_jpP+1s0||APhiamByBKO7O+eNqM;LZ#QvgP1t#|M=&jLw6GXHxIa11&4>o zhVKt|&K<)lA)tCu#Q(76us3mcC|DibXd<}y+0Uu<|PQ1NWq!q!o>{6I0tmPqmACxCxrkuYy_Kpk8^B{RNZbYQgd;Q{2ViNo%_i5*; zeoOl_^Kg@pNxQI?g zV^EzD6(mHC(d_M6pD2%a`#tdRZ~~it5)nSSn?M~ux(ncs_PPB-*x$crwT}LA+k#MK zr9!XF!n?}I?1ZR?vvG2+7I% zEym--Z~;c?YAc>CSvfEzHk$<7sK$1^fq)DiQjese!m~txVng3SyyZ@#9I8iQax6x@;b*mPZxZSXHWW4^{a-4;St-c>2DZ2Meh8sJi5yT=;TBLeFCD$0Bji z`c{NDuV=;MAc0;HnX_f(D-;deYL?7anXRGK*WE!h0w}Q~gXrdv&T>SMod3`Z?4}T+ z-Q17Dtv8=zzhC<8=wdh<(KlrI4v^|C1mH802p!Ikt(eW(o+_Tq7joIwa6S%Df}U?v z<(wmBU>CWpCA4)AJFU2@>d~^&1M|WssVno`oAx+knBUcqo*rg(jcp?uBVLqNvV7_i zGl4?QZs8@vttZxusfBBgf+6qxs>~w>?S0NUHN@NtsalBZpUXo1fdoqzq9djo2v-Oq zHErI@UqIqKH)Jg zuK*sb5-Qn>hkUdRf6MAD<2ILj%6mdq#HJ6p${oX9P!J`K?e%kZIY==$kld3E;L4HC zl|A|8P5=?1`QE)K8*zGzokQrc3x^$fST(5p^X>f@RX;9cAm+Z2#a|mUNp{~ry?xSz zz7KaILdSzm%QlL@meR_V)D!wMvE3T1Y78>!&m2shjH=jODRZ#b}gwY{&dC1#ho z1&6yK{TDZ6qy6+E&Qk}mW_{wUK)1h;LC6gAJ+eDJ)34kEl|rR10`GeBLrE~;w)fHF zNR#RFA?MwDmJ`{W$QMMMjuRt^5d-0Eaxy@rqA$SohejQLAXzSkE$3bp)8fuF09yg> zjJX*3_17NI*iAf3I|_#c29tU`mc~@2OLyQ8U#OzXUERJYErtYS_w!fV5vV5gL(Y79 zQ$H6eecdGH%AI*(C)glT*7x*)+kmu5^Rh;It%!ld){M}+YZO1{oKrs{^X&LB;wvI2 zkFe%wiAq<|mt-vtfEy2zEXeM(9zX^_Fh&K}9s$FxYp`e>HnKacl9w=crQ+d4pKsKEQ8OE(3*+zLZoi$9H;K|+Q=I_>f* zxt+}Jl_bi1HZcekU`)uCf2&)GP%m?(z5V*9vqE1n ziSeZDy-G#}xryLAIwGqXGL2Xml;@3P0Ff~^pDUIv}JYF@V<7b8*lP*p|4+zi`%_0JU(||?)u_H zN%V`);c#rKg;s^bm&ti(Yx542x1DfULNhu)#C|l*Xoh9LS>~m;#a>eP-}?ByY-o8N zIw(UII-`;Dca8FoApD)Q2d2X7OxBYTS?W3Bq_0+KOO0|S{ihJBEREx|G7EaoCQ|of zTXw#5*<^94x|jx6t?>L=h?D4d`CRbq%Cn~C^VXz(K2Y6nESnukqv<(8OCdF}h;8oD zVY# z$<8+a&6~yVZpU)|Vx)=ZJ^MYAVfZ#9zgnomrDa7vM7})yuOSfVxo{A6?bPyBQu9I! z&VSjeOoKv^32C%oD09)ix%j67Jjjwtx*i^e%Lx%vW(B zHRP(wIbNqPZkk@yD+F8n7|^AYW*G$nX>1)dUs2%=#jED<`t!Kina(@{T!UF0E&9P)X#cz~cjmX2DGF3yrB&Xm-r>g0 z57(pQ^j^zke*QVJZzu^`e%P*hcGcND$=oVhCB&GBxN@X3+~)128gb)~&Jk2X!l~KJ zy@wBMd^t?zz?Y@Muc0zC8N4rF$`Val_#>Vbm($_$u|?C7Xu>MgwY# zgKW+?XX|ipJCbL(ipW*{&=^r_!p~cm%{VU4b=h0AdIJj?w&bA6K&gZ%rBYL8=PN zo9@-Q&~=f!8t6^SWp6ITr4^x^zn0qvO_@nAnc*P8?$0v2l3{)B(L<(%Tpf@6JOIdR z0&aSUes*&LDH05(1f=AS6l5j@*P%)|M(-RCxb9+BA&`+{^|AS{p72V{)NiNk3uXlV zgGd+;v_{yX#bZx5vPIw*DH6oLij$`IMq)>Xg z#QX>~K952yHNEVH2ukJjcc zb!wgX=E&)Y^5&#==HA&ZMMQ&iqDgiO(T#8xa`*k%m$P7?;nPxWWL};MQR2RAxdM|I z?qymC;&*sF5enEX13sRtIdC{s-A|CF^i^HIi^GH*iH_1H^0IkgktQ1PgX)``t=d@- zy&vx2gY7!WepYe9)#3fZG*rrpoAZ4E_Q*M~^vn%UCra+MkgBaGO&(pTMhRY;Nf(QlLTb-HaXYe_D&vAS)<2Po! zDr-}Bw|AIx8l((weq1kl#Q6yYw!kDjyLchJY*>K9^Sh7ZiTLNV{4SWgVP`TxvfTd# zx=a@9NI4vBT5MBRreO6GR(dGuP0wC5)DEcibdtNkpmM-~OdkfUMqJfg^S#UY<*##4 zvC786xw#ImZ!S1*d8_X!kcW)#Orni>O2Q%kV&V~eBb`1k$mHFrudnAL&HLBP`qyB+ zrq!4v#sx_Tp?W5Ryk4rl?f(9LYs+M-xTlzxe4x<=c?-~B=PebC20zM$bx zeBff(z}ZV7sgwEpZlBogALFt&98W|OR(Jf}tgse|eWt5F=!5@t*`4h{r%L-mW?A zywXe|l`V27JEznJO}2_bR^vIT9pS-Q>H+__;*g`ki3g+jxL&@pagrcMsfX z#;0D&HM=-vrv4VLZSWKp^>e3qVrcyFw@wka{k()VaVoC<+sEV%dvU(EP{>KetbCAO5+GH?YX8r_#|CdnVgt)$!NOXDx zb<|NwpsvXcS7Y*m1U)@K6g@pa%b^$cC`1U3+}5%Qhz#A`5~A1E7yPxuYCySFvwpg$ zr|5zQsWYt)OR6~vVGMcF0WaX0u2Dn27mAR-ZD4&SPwxa0Sa&4o{HT4s0489{E|JK= zgsq(h(hBb^e&OA5o-%g=DXMV!wz+K`AH} zG>&AzV^_iqjtt;2zvHKcmr0V|i2549jMIWl7|ME~Ta6(-iBI3BxO4qwd%qMp`lN;(S`r|XtNS*Xu6*vyg}ir=SeFtN z@9J0oqsj6#dswJxVzGkTr4Vu;yQ?8&(tBDtj|`Fa4&IU2G}(IUph6b(6pI{G6Nj`HzvWPYB)RlDE++ z=+G~vb4AnFd{{BA7g2lysy6Zx8r)jO{}h_%_6^42`K9Weors1~EJQnhpI!ydNmmwm zi@d5N(*0H7EOv&dOR}wOaY$}2KV_c|tLOk#s3g!ADpx+|P@7<3U)UAzg$$=&<8u4r zP^RgC_V(7%XbPnKQX^<$Z+mA4@`H@}&WYsRCq8pU7^+Vxu!DCw|7%`~>6SZeUm<_9 zr+J)A-o_xcV!>d--==dfL^r!Tk^ws%FrqNY$!K6KmVjS_P*-|1dxl`pzR>Q-&-zw! zbAeR2aY9^azcpf4Qt0lxA z+Y^z~)tkGJ4FP}pO{X5Yb)iY|tjgpOMt)B7NIqLA_vUhqDETEL2X`*G z+jAYy*^^aLvT++K7Z|+~#Vk?(v5zn5Et4(4+nc%3AJfnEWbV?u&Fr3DW+)J|tjX;B zd=T#3;}8G6OAj-5=^u0G;IXCG|Ni^V@^B@S#GSwX8hyDduRg}2_Hl_i=|DAU%lc2> zttUKFfDpW%I=sB)oA&(%o@S4ZI%<^m6OGzQ9@&n;aK7khMpYfmmw`Dvo|3 zL^25Gtzc#Qx(Ykpv9&IB>Vo6$Iv6z|RWqYImKPl%Q6A98X8+d@m64@6t5lo!6uAgD zxxdbeK+Mszdjf{n<*hgl-hMWnIW#VXY#My839wG1(R^jTpMPTX9ZvpIA~~nrWLIJY z(KmmYig=VLq@?m%j?taqq3+VeNm=Z;>p>d+e@J`puqK+QaTM`I6e$)ErM?O%1OcT= zN0Htkp%;nf6llCDAfYMi3vz4bkeCGac@@l_#l#?fEpd4xqEA39i2IW z#%cKA1Vf65T+T6|Sphq?S|u@qnCAC&5jf^|nMkAqzrT5o^+bI- z*4Bl}!*Mp{G3Rmf;{<4cv^%LN{aFb`r~N~T-3U&L_ieM1;7ApJsm9_g{l}-wA>4ao z{uJ-Myp?x6g-;u`;28#)9CldDQkfUd()XBS3koi=AcX*KZRb0vVu}IjgRqg+xl~)+ zmuI~Jh+01jP|=Qqt$=kyxZv6W_WequV&LK1Ux}(&4AP9a$$Z z4a#^&RoM?cJ+{t|(BfeZ{o;70M-sz|I`BKIM4&~CaqwV{=63FSr%$#Xb<#WiCPf)0 zXr-AHjCvt5(XYi8zGrlXS?|%>k?+GSJEdbXerxY(yQjJ~yXG|Cte$m|e;zpN1AIKP;6Ii{4 zM#ZU2;8KT1J%=IXhC&%O1G( zCt#$i8W`t@TA!^Ch8aLp?2WVJ0$$B(AIVl~qD>=hzG@x9yu!^1_|e|=qpuGw6tL*> z0uj{(g1Y5(J&di7KunHpe1ky1+kDSqJ|ytU{W8cB3HTt(;v}eYm6d$(0!ln>u}) zcs3JMZjFjN{nz5%oTpLq6h2DRp^dE4hwz^I%#Es-7+mT|tI@WjbY=nlGcaI*8x0_)??SkOoMp|k6-^!U2M!}!x= z-opok7<}srEvzE#~@A_HtgNmtReUU9=%t1_UbX}1#X_fDqQKRU_ zUFc{xnjdt&?xjB5$)wD$wW!Sw0iA8N>DFh%0KZC++>616n)a<|uk*DuFtqbgSm@As z1$CdWBtEO;mEUd{M2ZHMmiceqy!l(b_e3E@&_T@T&5av3#EhPOJUTw+eDI)s*n)_L z4A{bUe{r15?U*HCx%O_g74ki>Z*6byUUN^cN-KGo8ussk`x^#b=cn9d@titc z-Q62+O#a<}rDXncoeNYd29j0LE(!btIwJ6Mz*_G7XY*3qyt854*uVGGub2HFD<1z( z6_o$qpKH0VFokl`(bi7T)YKF+q9P)C^0u_}5eX?NCpY(YszYo{3|L(~v!|y=>DSiA zUX+>n=h4rf?Dy_{PjyHF{E^s?KTTaADtw~Ii##72#YhJrBM{(*qGRL{Utk9e>Po2( z&US0OO#0XEXO@zi%c}SAmVo2*&l|sXKSkU22u4LkMNM<_#XD1vfJW5)AEAJw3$>N; zxuzwK+W_dEh}ZVRUqQKmC>l?KfxubTpWl#JImBjUAc5pHe7`ERwYIj}0D-iu99kME ziKLD`PXotRja2XRaNp{64>>qE(h)$1;+kuhw~LF5mB0WmTBE*_j5_}iliwfm3H1vR znk(#Mbb-uWfn-6oi~xK07HB0fVD?nUW)5BsX;L&AhA<(ELgrZ1rX-goP6c32;H>8E7A0BFRZLmGOAysy} zEh+Mw)??JgC4;Av{*3Z2aLryiAjf$f9Z}xve|i%blEeDz?SN05`*`2XA5z{rHK%;y z_yH@}@c~8Mnmu6O5@OlplaW5{S5G%5{ma|4|8abVk9_bA=%NAPr!Tj~rg4Faf+xm$ zS{`yz({aAJ0qx~=+Ah7}=(-i!s=0k?r2kONkjWwiu&57dlXiBv=Ln5|cO1JFTxlFWc>X zP2JS=cWg?Hc(!z_#sY8La4)q;w9?-y=#4E(-H`3gu#_GE{y0iGtTv&RPliPG@T2hD z@)GA+<~12v9gSCkTMyNwhy(Z9rzs8ndNzo-Ndb}6xgo^KiI~wB5>C#~4Bu+X8NQ0$ zj9~e8LUZdDz;%3UpuTl0At?Y2q%utBzCaro$fvIQ=?))mp4MQAe`fN>#O+?_Psw#U z^`55oNTfQn#GI?tk|x zkyOzm^Q$46%E|*KZY68#ZJ!w@tA#YC1oh0FZot1O5dwwoTQgPP*4QjeU`a1*=ttqQ+N^uV1@Hf9rXv5zSS_ z9k#~9I?=sjmb4qhm#zTLU;SdN^?Y-}d@1vreW~ILT5Uo+>#u`NhTGBhnq_?2jlq;! zhA;>pB_qRYC|xb%IP^e!CYHX2I$=O%26j4v-6wbG`GEQS@iQ+g#EN?ixzSBMeEi7c zfDXqJ?|38~kWXhD(DB)p*}rxjMVu*`({SCzea)FDjiiq$htrf z2Zel2dDFow>rvDte^xk(vK8qkbqAKeDuTs85*6Rb$7760_t!nMbif3y}Ey$T_73x$9!IlgG6Z0bi*ZDH*l##8fR z%E=(wkZvb>*GoYl&|`(imRY>Ku3%mLBHO8~=2GjbolnK9e^w|Mo|ZG@IV$L=Y9zrN zf{DehhuCH0dYU@kDTg%d3UPHuP2z;XjMDUM-@C}Ujvd~1<@mw^#x5tt_~q#-PQ)Ol zv&oJY!7r?HZ^XpX+Tuh1^SX+Y&?a*~+Rm0q`JZ3=* zmlmYI044rwJ!g<-cfNFRAzrd6&nuzUV_%E5(CbwgH{+Pz8R5_%8Q=cL%otK*qhlT7 z<2}7ww*lIsq?Vn2O44#av znATey4S;ySj>cu=YH`_LjCi+f;}=&r%(gTwIp?c3AP#&=`?z|1*((E%4~ zPTfV0v9we#an5EhacV)fFGI}j8;Cbum#nO;x3FY-q=#Vp=DCWD3-+PYl$A|JT^r?) z^fJwE!CRe|KZ4!;GQ&cMm&~0;LU_^meFbpo-AGe;d4k7`|cAH4wPhudx##iSU{`Q9WDr3VXw

o#{D9R}qVJbu(9QAp!Y2ll*_2k8zU``CYe2!zwtJ^l$27e2W>lYtd-x<^EGd;=xN zgv!ds^2SfWYFBGR8D^h*tT7;x?cx$Z<)gMoL52>K3`IX2HMjy|jnm-0DSJy-?F-VO zB3<>3Br_W8<1DawFH!BM-KPTy(+o6TKR^vlcjAh^6~1cqO>vAu|0$D#^&?YQ&zb#r zSK#qf8JXTufuLm`C(m8w$J`f)O6N*B-QtbD#iq`al@Px7BbKD4(`zEuskLH1ZF$=0 zAFNo$zxNpVEN*7I*I=SSe>%`rY`B!b%E8|gwMk~-s0=Av($LJ9RU|J`81j4>G0JUJ zkgCEFLb=0=Y=^7MC6JMkLDH_VqF6gMT};bP^5y1@3(ONa-L&eu7zWpUoONU{Z3)-P zo(3R#H1#b%zKjw7E=x`nNSHam*1^iFY?Pv@XEmTcUyGJ6DSQl3)yvQ0xTDAurjr;% z)$RI@4dzC$dW9wvI?0Mp((3}L#0RB13wU zarFm#Ow2g?J@^p#=sn48Pzg*u&!XE@K88b0_d{3@F$Db6JXpj+XORQ-HHHuL)aA2m z3l<^I_BEG-M?kGsrju+hh~r*QR>K!!8gMIyTHBx%#J=CT|GZmPHq@wAVmyn6ORjq?Wr;dxBnYb!3q!Q++7KBZ~$_8~7!oWt!?(g1#nmfP> zE=doaK7?)g2MN*8&Bycc87$>N%3G=(Q|voU926q1c@vYD&#s04oho#f??5#QqYJz(boC}H^9+Lu>V4Rf zdMQ9>3E`8QUND25ZL;ZwDS$&bZR5!>iBT3#R;%T*`h%VID_guaEW68bzTVv+eu<`> z0`=yNXG5ToUgk(IM;AA{R=kB0uSIgTJ&7P9Y4$Y;7&$h$e9GC0N(#z*Hm=`FY5xN; z(PqWN_@#VU@gPf(s9~qL2;8U;F4#h7^|OAmw?W8KN>JSmi2iDS0|!aJVk^r)d~snwE7ITstk~{m~`@J4E&nS_|vF z1m&ef?Jg%JUgf0nyg%!YB4_LOC0+x3)~`bO(B1jcBrhj~xuIT)?UYwVoKIB?mGpU_ z!G@XBs;4%j+Kwl0vbwmWj%RYpJ^7J&M}mXEwpf-!y&`swxU~Ns>S8@ofpmF`Q7*m} zR8(p42MK3sHD5(Z5T&w8BJv2;#OF!?AM3X0vk5F>>mJ+rJKVO~Xir}Lx#gf-q^X0{ zwta6fJI-2l_(#Xx3`JfPdt>g}6VDtErN@pu6uqv#we=?(_K|msGJ8eSh1~o$Sl}NFknP^4)=eHpoC<6?Ygr{xELrN@oQH~Si#kq z_2+%ajR?6iS$%KZnbZj<+_ZK~T#o?PaR=*|+itD*f;``W@`2p+#Az{TWnm5*ko`2_ z2-%=k_%ZD7@nxrea?#;am3Q^*G2&UYoN@MUdmG#)w!^jr|4q2}bX^>3l#su$G-ulu%u!BV{Mk$vG>Qfz#eP(e zYHzk!VJ2iSnS5$j09XqOIVc z4l;<+bwIPh2X{`tlUvZ}@k+PQXd5s)+zw(z`<*gUtzv_^&GbQC$~uDw+nIJFGgY5$ z1?NN!9fcQly!BeO_marMFUJmZ>v-ySS5puLLX$-m8Ds7(!urM%;)pT1W9SFWbQk7B zEWz%r19hD3FPG!OFKmmtE_Of-l(q~4v^^JG-~ zi=6U0vL6FdJT4G9ON~1kCmNaxWaNeN4S{tDV>)IdvyTVM52k}HU4IKoo?OEi9cG&S zF);d5$8NNT4J(tLHz*ARC<>zsk=!+B^jx_|c(QQOq0aA(NV+qMNpi!$NSJVmf{|aT zfLv0y3_)gbcJv;*E+R8tZC?RLy!x&U^qt&cb~C|V>2zH&K0dCnVKU~91Xjq(XW;4y z_DG|3C{nO$s|!Fi;rxsk1okem-{&wsf@{TByA~@BoMcX+?tUq9W zJm&;GGFT&d&rAH0hS5?`-zw^Rj9EPTzLpI<0X9H?KXU3WkZ77mfEv>no4wvoMr_Ts z==ox2BEEs!t1{*Wwi3jqWS5Z8LBFjLI2;8r%Hj?9B;xT=>xIh8IZHnQ{~Ezy(Pu47 zF4UlaVZ{>e1JKv4C{vxH!mb2EilZ~+`9upq8Fg-)&o=S5!;Dh&O9qb(+!BsxT-rE9 zM9h!(K5eNDt)3pP9-CO&9@N1-v{28}PQNFHF#mXWAC3Dc;k`#6ugmS7eFL*GUM8~p ztrSn3`|T8E+jp|6t=h}FpJ$#ibLPc>3#M#^bZe^_&o=o`_CxLyoQ<9!=E*wmbQ$+eGhW-*Jvl?7#VN zhXL`Z!tiK<1lwICrB*Cbtp;{?ZfQnz94K;6mbIv<{iKXt9t3}^kD3AYZr!)H0pA{P;7p(mO_Peil{ z$+xiug!OcfUw)-r(W|yk!XIoYIg(D^GeL}=mTBZg8+pjf@uWq*zL@$eIgt5B{Qg=+ zi+2ZrD4U`kTfk9LKW6OA5s2?RHFbBh9EgVypOCP<^(c@4XaolEPY{8l?JgeQ0G;pC z(B)%nH;=%JW}+j%Cd(B!#c(GVAi&mSdBU=ttLT92go=~+)o;zRfF$e1*)xC*d~x;^ z@k=Wa*cj=n_^)2z7mgAUS@Qv8K2fv8J4f|qiN5PaeS~{<{?!gHam1v8SU_HTO#5pQ zJf?Cz*BWd>0n+Jr#ea?imQPsj-80uqAa9AX(DM}qj3G)d=G%0YKa_d?oL@Afec>*! z{S35WmOLWchd2Ee0S)N^#V;cFfSIfJuc^|#hV!ZNJ8}hrGbja_Zf?B-=vGSIgghX* zd&dS&P}BrSY&kSEM9s|ni?PiNFMp^6sK9~r^Y)$+=iR(?-p$B_WuSGSZu-*ZWEFh0 zSTDyUfB*rcp?~%3`t|ErpT_mcD!Yn3Kn%~p!Xgc*Vl-`R*5;@Ik@+|cU|In1c|eQ` z!-~CVKy5HC6a}aa#sez(f2$1+9u}~AY>YZMwFA<3eGMR<#epZFCd`bF`t>mS*Td)K z#Y#`(-!k~$SAHEwvVKP~{PzlxRLaxW{|~i@;9Fv=|2%Vk>Trpq?|)vKBqvM#>xKW^ zs=Nb`U%!6+5c*}vFzt9~a(b?y`u)U#+&{PJ#a=nXPyS>2cg(Uf`o)~ zk>Bn9^QK?elM2@^nVkC9Nu7vj;6843(99|L{4r97|E&@r#QIMozfK1%)&FCM_WNdL zuk-d6QJ{maFn({31V7_a*eBWqXE=xC-_?)fDl7TpGGDLYinHEo+jT> z-O{Dlb0-J6xC(ur?n|(yX~z}KjcOYe7-etn`$2*Z20NmmG!A&Meq0Gxz)9}mS(SQ* zpJ&;9Nv}M7(0~Zt-w*@%Q62zTDc>#O*_uZgeL8)W!XSfk!x-vm6zXN4xXL_BWbB>W zrMOBclFV8WBziNhfrLDEsZrE+nRm5E$_1waeW?MVjZD-gKyi;dVOs-;bR+|9c zAGHxu8PY&#kB12MmW(q6vwKn@Tf^wHLmwDtM|jALXs0)wq2ahls{HjNJr>;Ld&ZIF z^T)w6jdYbF>$6cDr}^zfa&__l5Fg|VFpEu zLEcLgJi9klB%L@bf}j3a=PXsTE)k*cjka6v*5cnt$y4NV0l|h%MdoAd1pIZ&r^6Ru zc>P0i`dnYYaOHb@W8od41BjBu=%ftuMnWv}=+Mpdk@iFKXr-9=3f&#CvykPJQpKda zpf}k!MjU=t`M7`AAVbo-lWt6#c5js=Mbo+Wv3n3!Er0+|;5=G)^}@Rf)ge02+%aQs zwY`9;+caJWFd)E{qC8BQAk+AUfc~VUA z8w>o4E<2xq&&-pCtlpygm{PuWyOW|u8f~G0K4YGGdCuh~SYiRs0CUP!HYZX>-kL_& zk}Z2JkD$}TJ|!PQ3v(q1{_J(xjDYq2E0r4O%$JM;6}mQa>$tO?(X&(CJe4~npo+KD zGg}YE_lM#|%+Wmgq<;gM=uZJIXYNmj5EU0Ug(AbjXjoroENgAHt$&{njR9XjYL``xmC>(!*H#xIz@m{Q*~Ndh%F)N1C=z~f8{vKm zfi7<#KDS3go=H_L>x8POJJS*hJcy6#XE*yt6}E`M z(N(G&GZ)Bg3?DbX_1L}L1aWQi7T7Z*x=0uQTiLP$s;TVckr91 zoVagqc-g2Vo-U|f*6wr4*w{;aU;`|7K7=4?nund}Q_jZ2K`K{w#^S63*3J!fNHxY- zBf==4=pT?0ZKlxCK3P#sVF|DSz}nuvt=U%`$u_0EpOjOzdk_psODSkLlu-X#^k93b z@O;91tY1w9AZxWqi@7C4&r4pETd7%|+fjN=M(!0D4CcTUa=50u_g-de_tt+vSCONN zUU5k?K5Mq1JMEE4ene2}HG$Up9M}|UQZT)$WoodKkG-cWdZr|PxQXhDq|cKxu2pK6 z9i!gB>onzF<<6M2?z82B9@{{pZXo&6y;X#mnE?M3(QW4$=;uZ}HcicaVqh;GtfOIn zf346BNNQ<-aXt1jyIHc?iZ_MC-&3pAQkxT$614|4y!EL5WK^8T?4O14FQ{XfR$`Kl zsZ!uO!&Pg)XF>)Wqt#k+?7Av>ZsT*gYfY>3`}DK45F0GP@vsRswL#`4iMsEtRvvoD zlDCDUSkwc%wjd&ke*QyOy@X#bX`Z^qYG)hO>}UsGb*zV$2you3`6?IN`IX zzO#m88iR(;-R*&=3){mp4}z-;yZ?>w5=c;5AYK__>t-_m=AzcYeywf59wdf5PvY1X zDzsA0*1fTEK7BW#IF;8MAt`Plic78{w)cajl8C~!}5>!-D=%Uz4pxV28uJUFwD($N0KXVN(-YhIfMh@-2T zxvJ6v#n9UFit@Pl_&j?PA>7VED| z)upZX(u8p_o;QI@r+{DZWX+RL}E--H2DDD9d^RqhZD) z@$~ViEL0$%SCy>Uf#zhtrp=O>>s7!<8vjAY3scpSRH)k^a_TM>kK7Kc_IL@iYMQXRys1 z$pBpgXk-&DrndnY30dKA!BxbDnsuW!NN{y8F#{7I zL6AuygPV7Pr2@4eyo*zM(29q7PKp}w*Wu~nIT&T{3UE3sjzQ@ZhVs}NN1>pzklZgf zl*lFsDie46)s0*Tk4j#BXPJR+qkP;t*wg&`Cg?n@Q>Oz=bvak8dQ-6#=AU>e3=+1q z4~LltrN=0=f-{qCO#>!x<>@7mt;`~ZmmNieSa?ljs;R3i-fEsuvUzM32W|mjU?C}d zT*8s7`F#denVufohzLq0^sk=zVBGa*{l9j}_eNQ?!L$m}-1VznETvM%uYZ8CrIpSEBxD`LCk#I@SuHdF)$#k!oF!a zzC6sC4%N;3Fr^xftz6RGZI_~!Rk{7XdGu<99v?s9tqp$V%OP&N^Kf-SG?)`H(Y49w zcF>@&WrBXrsA3=^DW1pam;?kK6oQxUHa()ag^$U~Wxn+eN24XuPh-Dja7|8YOd>HU!msjYrfIleTe448=iS za9V!T5UEURL#q~Ol|y0J3C%rdke9-X6H_|A`A6YR&b6n$JH0;hv9$bKBWCU`cLO}q zg1$t2%Jl6w$+nw4iDdG%i!x@K({faZ82_U+sd@;`GICa!<2jx=X`7honQvk+TC9_I zgQgNkzWto7H5uUPX4}JsMOBk z{&fI<6fQn}`P`Ph)NKkJBFOE^%kwgHe?E zA+(KosI!NI5lsR1_ZjnYL{mT~c$LPA2K%X_RB`v|Qu8}^GFHQ>1dAlPU=+!?W!f%5 z(e;{zy3RrSu%L#w5yOE|wgh~il75_nK)pCXb!4jBl~}4A8Ll;@?fg6Yh)5B2lzr6> z-Itv?u_0Hf&wew!;aS7ND{oslPW+OQIBtQ=5 z@(EAM)F@LitK5?u5+4h=Z*?ZIe(er>z~Ftt&xw~u(wA0C(nA4_q)Gr&(^Ij z^WiY>4);ghnAd+6sA@Ijr1Uke*>lz5j2eaK#Ry{NQIsKv@)p9Ar9)X7{nPMhV`*3S z!J3pl%$Jk`+b)5XwSt@oaE9k=Sl?WBZ`lI>(RvH!INQK|^bob)SkShSy%RY&|FK%r z-#C|9=xAi=#K7JEaO>1Y!1Q_K$X7e`5cYxOpb>5HNVGJS4k@w-yJ>;XQMg`_^ED96IH&spN7?(@=Q*-B1~fH zjb;Yw6L#-xo5RmWwaU&$;ciW1R($?3oON(K^QfHn)dbE*k4pWu`FuWY`z?9nda2Ht1b&gP4?4LNTp4+dBb7meT00L%P7V{hey|pfeOQ1v!mFDnG}n@m z0(QNlWq)jZZ9z^{H`fm3jITa};yUZ`*_Ha1&T%om8QCd_8vTN=Nuowpp;uGcNN|n1 zI+Q5|zD+(_PN(kKj?C1>11%5MTNCS6!^f=F;U>#AmLJ)?bW=qb-5VMt3}Wtfs&`}o z*@k&M2R4vsBr@O>%-5A0wR*7bT@GgJq!E!CJ3F3JOvl1zO@72LpFI4QDRw12H>bhcNF?TCf6tKQrJ4gzseh@F zKyg+90U&g%fpidgwCUzEQVxu})9H5o4%o=31aQk$(2Qgf_beYt7qTBOZDjnyef7!} z4M1`?OL=h|3Hbk%L@tn7Lm6~P5hPb{Ra!UkpieX}ULud`U$OISV)S%I+@!yrYqi5X zRla&4XcxLHaZr3KWs7pY0(}WG(=O{urrFF;8Mw}C1|BeY!v*Y8#-}V6ixk#iQ{J+Qt zgDT{J%}Vrtiq?pto|9VrxAL!Zhs*yjg^B-Zz?$#>RDPHF|3lgtRKdnqVpOjUNNKxz zduN7s|LFlgfNhG#NS!oMui52V=719yp67oMjne|@#GU^VJC46jyY&PK)DALT9XE?4 z(0}=7&ls=$B@x~jEzwHkHmde^{P|rR?)hzuQ=Xn4F|GLCfI!wGWJ#840^7jj+Qesn5>Sx+( z5f>`MOmCMvq?rANP^IwlU&7YE8~pWueY5gy#q)yyi3UUgk+*1`?4+7-GBFpoFtLwu z%@JV1c+^lSDYZc>=ZZ~R1J}Cq!7B#gO<2HC%w47_+T+#oQa;y*9tLby5{d<_c7 zvur#o*mR6_pZrXz`eyT1hM+Rq;3iXr`*Ep~hhf8DUCSQb-`{Y+5;WMgGB`+_FnVV9 z2|s%v2@w!V*>Dy=>Ap8J*)q6kO+zn%si2Z9IqN$!qId1G@Oe41mid~_6EA>o$4JwR zO*XzLo!cY$72p{~_3Zq5ducLn8tWI-Cbn6(pM}O*PwIWF+fTXRV?ArAvQFE8*{d!; zbA#0x?uE;uQ;NJ)uUd!yI3v#Bz15f-obgI&?-o*9wyfk^p*fDuxmdOFWeh^H?5&}% z@U!y|_k@I!rFtFoI-Ftkk{f%p4;9SZqgu2L5NTC{O+}&Yvq%c7p3$+xeY=udqb1GS zGmcX?=i;33bP$_)@fP)%I}9(`FtE5INM^hRSg)q3CVJby4{h zWACc+;^euKIGJSpuA=v)^qgV5x82p`v~>)pdO1C!*8#pP%z0)oBe^Y$)BPEv`cWWR zZ0^Ux>})_a7G0y)(*H_kBXvvQ#keko6K!T!4@UoF2HZHdqd4RI%x&tNijDJLJPXDo+ z1sU1Lw4{YQ9JH&NJ0ehtJ%uz$UKuU4w^2d+@cqAc59driYL88dWIy|v9SOogvrzJ$ z@B4^G)ACc{!aVVp1bsf79yDrxw3(FFdbR{gt$P?}glO>Nh#AI?Q&?iHXO2cz@pJHH zwE@zMVht>Z*J_c%48~7wck7X|Udr4kM2CDJ`>-9ZWYBQU*2=EW&B-PWqb1~5DIZBe z>9DG76kpH)`(QNZc#b2Jf#})K6DZ{hE1pE3Q)#o~CzB^a4fNmP6ZzFQ9di1{N(d@D z4#q5V+B4Y(P7vR=(U}qhUq7X_;qBqY3_p?0Z64fF8kC0BVB$gKSoDhOuu*LLM(%?k z{#3)i*ZN8u2ZDa6PHspP@UWET}N`mkXRmP2|wM zp%$MLN#>0ekE8Nu-$y(KUa9!+X;bWO4lfo<2WkU)R# zU0OPROC3M0#NrfS)Soe>5K)JAID9nY?3R~*vPWrjIzj~X*|=LZ7P{%smcVMaz;EQW zW|oY4S>dYaK+=vIh~je^WI0SPN&hUccdVm~={;=BV@^a4=I@KegXzc|$F$m0eS?`A z?ZWB=YyY%>Td%nj=A`>=+rBJy?FSbP&p+5G7u_BdkY2Fk-p3Ec#~5>wFy=lbh^dHb z)!(C@xAlQmemg|%cf36tJ)T2oH(f8{eyci6K{ZowmGX*KEEDDky&f*dJlO5lGz{Cc zC6VH62qyL@)y!epYWRF_qx3WPK{hGs+>y40HVWn2ZWY#WkiP&Hb}rnNTjpGwT<0 z=}=kSyimtwCUU4%4GOo14~oFg2Cgn#f_u3ZH>9h}d_5e9a$_E8r{|S9d` z_JBHRYCrwc@o4NHmq3pmslT2b^bzm2^%OM_tj^n1a~!)u zs4p}!FBCH!Tpw_XyWfNl#g^nRfbD-ik2LlR^J$f1e|Ya{V`QVQ8Z?EozVnoO*efz} z^t$*B8pdS}Yja;l{u5X6#zz&FCX?0nQ^+1<#vsm$O6Lr*8$!Ov{;)cSvVP5sX8VT# zOq@gOu^g=oX8UdPHQcBDG?=~xKpkz7IpANGBgD!wVscs*uY_v)jY)g-jPLq1{k?pxD0k0Qg{ykK*oMSKId; zY_1xs0mEytHk@=7Le2YZ%+RBh*e9kmvTV852N$i@<3!OKE;D}G`OC(lh6N`JDqJr6V>S!Okyf)v_2QPhRE)}{ zG@MIZ;gY!fja9scE$wqKQK!adX2(IGC+yj4ty(PVq$++Yv1(UF`y-7Jq-f6B!6*S@ z2C|SfXO#w zn_8@dY*4mhN@Eo!rjd0y*EWB1!qPhBE)EY(xK%1Px=($Yb%o8pYo@($(S7-+0Y0;0NK2d3kUo*qu&V;2cCc4lI?3W2{^4mHwPuu~KW_F7{izmxdg30D zKL<@v%%-)&zrP~TP0uYX9n1eS%q(uzqtF^dn=EnoI1M#A`o?JoljW$Oop7sZx7?CT zWgsfHf0X0OUF=dmXA{(YOW}%^OS=(#BT}vSXl793q8Qf+|Lo>?(3@1p_XkWxSLI|l z3q_11`_qcX9B;#?OIwqDJd4Q{wAabQB~N)9Gv+Z*AEf4Wi#~}zYS+O#Yb2joK95ao zpC^ZmnJ)0(>tk6uEmE^;fQ$A|-#etrSe@ji1Tsv2ItmHYAg78wDVGE`fZuQ zpm)4~+TnX%hPSw{VJHt3&EdU`YA!aTAAyePg0hjlO|oxqp>y2YOtQLpL?FSfwJBjH z{5wx)cAqv;Hrh2wH0C(#5H9@!BI!F%cc z;XR$1Jkz-oC6+HJMuV6zPpkFL!#?}laJ(jt&OevwRX|;n@5z(2+qz@>(?u-^ALD+L zYsPMj#V1~XM5)Z@q>&@}u-Q3{(NX@i%Ex190YB(fvweDEHsfObfwl82^3Z+v@dBZ(N7t;Mz^k6GA6t z4^Jh<*w6T3Rp@vvL(=^%%DDZ^15;t6PHJMl zij~bDOINHQqJ3uaA2%`pI{B3cf7nXyCvVBF^;t0wUguWud@XA5`W~lmEb!2i`$$J(t$Xc6rCEaE{1|Kx)Ug z>n<*q=gC-g(hWFS-HUvpcGGEf%$l_F$D%f$8IZ~L+x0`cwhuw=#T%E_D^JI4W_>d_ z&wBP~Oyg`mFL>E{>Q}Zkm8(0YCxYpvYyE4WQL28Q5#g-~izC;C)G#Bmk7r#^Ug0DU zp(~irIb*s5{P6K*(4IBVHL%a4U|BUx> zdzWKCQ+{87MnT)y*Tv&4e+seXHQ4~tc>Hds0S;eBS!cUF=7ZHmk}Di|w6A8fa1Ztr z85og{yDY5%tfcIQ*vV&?5>xXe^RohmVZ3j@ZfV876-`_%?nGhtt^DVRj6~9#x-SJS=*MmWscy<)M3~dnX{@ zTFJP|uPn$=A^aqB zUcgpJ7G=n*=XQ3KW$AZZ7(_`GH{sAQdz_y*>$j}eDCm&Dgm$gFKR07yHFNTTsm8YS zC1XqghM^ZfQ}A<76@u>Kf=Q-|kPppABW(`)flP1f>QyLzOphMi0*Hkh+qc6S++RT0 z`)x@zFiOZvsBB`Zzew6hUU{vzV`HOnRZWa;o=(Iskhs|0LDA+( z^qM>!EX#-iHd`u7k2+ekhu1w(6DA45Gfn7RICamn{CU>3T*(c8_FlLa6n;DNby_M+ zRSgovR)iOV;=Sv_xL4NNDq`tqbnB_<>K1%+_2Ol^dO5UToUvf0mULtl>-5X3rhLQo z9lZ|9O5X6yjwQb5rf524O1pu^T}hLL1q>d$jVg(&4SwolQ&duc*xJH|U{r&HglU*D zKF6PHrgOcAy(-kB6TRl9ax4OYh$cbnuj_zeLkZ+wnbQVoXtK-hN}lh#IDc}VdqM+< zTA3fgD7rprhm3C-bY_~EcU}d~A;FZ4r$gf&;Rc^hBZ~YBgnW9yNKPiq*OojdW)Tfi zW}k9|@A^fq-a{cH!P2)uCWn>FC*_)G=zc1K`TGD5Qe~uLkZPk{)1X??XhSH0AnEJH z$kd7AEvcdL8q4M)IC};EIXIKH z6ZvZV9ntGQSD@+8%k>p}UY6TQX}&9ccj8Jfo~VOpjg5^pkcK}Aufi^~eUMZ0V8@dh zHr)7Q)OfM4@RYpzV}nG24wxkTF#V$%Rh!@*t2I=uYw=*YepYM3^N1#>W-i=I>_WY( z^ih?H_BPjc>wtq=_9ZE~rN@zY)$#D&lkpnrbZ*t${-Cr)hQM^FvV8%GcV|-V6OZGK!U*Qc;qE^E3|Hal@N5$1F>%$2I z2m}cdT!Op12M_M}Bx)t|I%w2!W3c<4yhI)<#Rb&7;ASdx%~yQY zQ(Z=6TWri?(hw3a75WenFqwmZ--Jc_giK>vTlr=b{tLDL`B6$wNx_;(XE&Y%a(`g6 z-@s>NWIT?2K`6l=V|urgx>g&0;rNf6JYJg7Whq7WjwMg$*Qf?YR1T|@;gI^!C>Drl zYSCqn{&6MH)R7O7LZT^Wxq006M(CafRriv2QyctX{!kXI=@IfXcqOSv(wln41IhU< zb#l!Ux`g-5z3jCky_KGinf;C+iM|j{K4f=7znJ88J0*1D;jxZ(e>K`9 z+}-TVV=xXU=;38)6`?>le>z9F*C5>YzB4BHpbDds_t)dcLL7}Q*jY?~v7@^GN~vne z-}p{2+pO8&e_{a`qbssr0dyKxr#2=tU#~IL$$;+!`Y$L7>h6iQ@EzmXPpfiA*?;xm zpDazOR(*Q)`ZWtsXElFfGn+b=IB!iT<*=i_*7h_i6J;MvdI(bemV}FB@E6bMu+V~O z8Y&Xab?C<04W&XhV_6wF+z@A)yi#nvTv+ zOme$2F2f+Y6VkGabKJBr+&i#a;WNFpT0dkG`FS@E+{@gi^C&{Yj&#;||h?Q|* zP>OvOJDDk5G-{hWA6?l-Us81ENutlMmLUImW2_q~)Xiq@y$*wzmIbRj-bf4cQdnuz zl|yQLN==8mAB6J(m5cB-f_f;gdbiWFlI0HcV5(|9Dvk+=8GCyjq9teLVBTMFJl=dm zEvuunUSI>qBMlhu%Fa76Kpc-@)$K%c+{S*w0s=A&EvdeJ{c7$9Zo-aC zbv8tzGIMEY{s$v4n7o6VbD2c$b)e0f#%Zx6<`C~iw5Y{{(_jn85An93Y0L!GIW95U z_`ev2kndpNHLrSM!d3ZFA-j9U{nM^aPeztWh?tKK@^axNm)N(vj>nB_ zBT=cZ#!_nTYz3#5FW$N0Q5;pDHo=lGp&E4IPsxp*J_ixzt~11omG!~tGU9pBUM%!_ zuUTBGPjPi|Z1U5J$Wpc;NAxRZoWs^rn4K{@gB?T3t$T~ZvFXg}QeS4Y94?|f#>}&7 zk<R(1Cbso~5`6*VrLO+J|HJl+t3->gEuQw{8Q|-Y5++rNyydQe3E?BY7EL4*a z*F$c{Cw8ktpFMY9kOJyIl=&BVz?kphF|i4iUAFHy_tt-w{k9WxVO$;i z&{k42`bgmFW22xaxVK$iP-RzIL(BP_=#&e*wea$=n9HWsKotxJmw=|KkkE?2j*xa` z^F9&4=+5D?_Qv?^!)yu1N^yE3=kI~uSd3u4ZL!*|w_4Bif(a?Y08M8|8!_`Q9Zf0o4#sn-v>f+TwlgE6Q!FmFQswx>cSts_{mo6}6S zI#5Hb+Ia04n`oh?}H~ zE?%5;V4b2;L!t_VH_&(e+D}VV@I2a-_+$^CB;_5i_7bmsC_>F?Ni)GJNrG;icfY)d z%UYXKzhmxzyu6km)eX0;JDzZ}aC!A4q*jg8$L3DmL6F}pF_*IG(N;qGQ6x;sR6=4w zFe0;=N7|ESA9pNOkXK<}%y!h9+pr3GcQnqN$|NF99&#EG!SAd3(Un6Ba52%QmH$Xx z!xmQlv}5U)O`6fGdsViX)dmwGkPHN^a9MGDB&Wn_bSIQnAi&0b{ZS~HaB+j%z3i8I=i z9i6@oM0)QSeOo53v9kSY=E(C24S5fS6xt&HE#|pPQh-K%bod4*!BXRvqjA)1sP~ib z+jH1u%ciUe&IgT@JS9nMj&pqB^Fi~=v5KAEc%h2erT$;N}42uc0dYNlvajm-Txm9J*jYsTc`;lB%=Q9xC$`U@+4hi2ehlgtvy{6cWvMbo`(C=f z=3++qmp}EcYGihP6VZZ5cH$U+rgI0TzqZ!;y2kLIx;v<%JQ|PM38e|-mv-l~OT#|x zbmp?WKI+!a!8ksj`4^lvr8$0^NMHc{>7XmyO!j3cq)uE$O}Gq$G<#AP-&mHakA9Iw z3j!IJI+U`eUR=|#TDiE=081sAPp!{%I-|UgPnn9XnaAVViT?Rs{MR&OM@kh+os)!% z9{(*G`{mY8VP@+s6K)h5K=33w#*(=1j5Kbz zKT_;usZYK(`Zq3HaM<(O&H5iK4y-OS`7`EPSp(}23SAz#ER`EHE%>}?CzXe;PG>SJ zvb)1RE5ofhKPd~u6^lgLCkcm}da;C_n@!xf@_kV@j^jXow1)Kj$<-ZBi>53s)9o_0 z0EL_pI`G}e+7h-g>iqIM;z~Z(?WsO>v7obYa2WlOJ0mt?!#5@$Pls@8vVRaAO~jg{ zs*UNWVJ=ZAyt zt+JGa(;F(=n#yEH;eW0_Sb+sQj?c2CS-=s)14A;)nJc9p0-v$?+x*M}(`J1zPlVXw zTo+8GrGN$n|39ccm~5QBu3YX~FFQ!fW*r2W#4ZlUo_zhhK2TQbKj88iql7tlGt{+T z8k)?9Z-%!v=O%oAoC&Y5y1bd`G({a-hQ8KSCd`~!5TTWP_rkjo58$8KKcUyJ*K zApi6A_%D4<{-{+y?dQj~hvyL<22J{g)xJJKJ?BS}v4Zy;6PTB}tylD|f3(3!gTy(e z8AWy-e9D8TMz@hnT?*{Wku0$xN$W+OdR4!lCrASeX zS>C!x@(TG-(Rsq;B190{#a%xPvdW~IvG^c{i}cf`6g+C5QvIYGsetb zI&6tWT+7r)0TI6CU!>2<&{-$1z@YsfkYJR{=WUkjLaz45hP>a7rt>|#y^EDfgCFWj z=B*fXT7HFvNmyZth09-ny5EX4YK=;DqfM@FZ)ML(I#_9GY4y7OGFJw^?v#@_l8cTe zw4jmfOX~QxyMZ<`D~{dX2RNN4Hht_ODR+NC9n~KLUL52txo#}dYML_KvKdv-+dMp3 z$2v;DzNl<+BhM&zy{d;QPM+J4c%mH#aiscMxzF&f808{wZx4vrth?bR-8-y2`IPle zZ1c6d21yW0o~b0^ShARr0HT}!tvmkL75MLe4|HVKzns@3ltTzL$BNo*`sab+aErm@EQ$GrZkHt}Iy5k7x3)>9>k*B}O1qsnyua+SOF zEtrrUJ3h5c8y=E$WypQw_zr(NgZWa03i zxB%ErJw|5Ie;^5;iYcfBb$hPT~*1D^og! z!SQNOGK=5)j(U{rKbr`Dj-!HugF8Dr8-9QKPV)Z%0F2t<`iu3Q{6j+wVgFYu(MSah z^2Vs||IyXMhm$#mU;o`~=hPYU;3y+2EBIjlf3)d;J%*TM zNc_J9BVp*&ixtlos$MMqH&XgJCZ-N|_xEp0`(Jl59Jc#l`1twXSt0C$Nk$kPP7eMq zN*4h~Y$VC|8C7~mC|m;#MflHq74^w~5#xV{y+f){?Dp~hJG_76NupK9!Znt^7X0Aw zZZwH0l4S+|c<-*||Mw+(30(hPBEesG#wc)r1C;qFev=79v7V3z=2#-ZZOEtFFF_<`7 zYMG8%H| zQ432zyqW!A#$Y9SJ6grqnE&A{{dZ0V4onT+!y==_R>(EU_D7!9*?{d4LqB`vWPHoY zni|*qAApY)Z5Z)O|LZJ~AmeO7su1tFIy?||le4$`8PIWCI&ZPOT(L)rB=n!ikwQ`q zIa$qT5ZyMUE3{RImcjdu?ydv#^WW4L5fiZ;`3B$`LWqvUkiXzT{Mxfb;q1AdpT70b z7ty7C1}4wl2!Aldvq&Ltn{3%hZ-pPrA}4Gg-JPvSV-A3k2;4Z%E8M=o?;68s$8TQa zUy8Gct^7(YbJF^C#JFXuqb<$Icwj!NY89=U?zO8n@Ir9#v2BQ9sFN&TZsfB$aj-{u zINn(rXM|(Sr?>e~x~kek56$$-???Ic z&!kF(&JJGwJV-i|jZ!l-xQ$6HRVn~@^UZBi1doVyf z?b3EBuIcq+kkN*Qk(;NEL)J{6$*Vpb4HCH+nXKdLZ?HEU$6Sr-Tb{r^S#Ni%ZZ@6c zL+dA)r%)h-hwEAX;4OtWx|rQd{?aZlaYQ``3;WmhRnumaBVRUitz+X6{dTO`bYGWS z>falC_W8cgWLH$p9(^ca?Jz={iYv;^#fhNM#WSKk>CO;j#I?EzhE}!_U|bAsMiGmv zqFNmiZg`&0i1CE0jy4!Na|rwBa1~7uD=E%0arh%YMaXfJ0a?=7yoSkmgt(#-ld&we zgj(fpauby<)Vd-$k3BsM52KNCr32#q;!N@R+VEAOg=TbuM7Uos28_b4&b7H&;}k$G zGgOBof{3X9Ekh)>%K0)?BX)4WCc&38g2vW$u_MQ@_y?MTUVyg;>NE6Z=FCL()G*96t>pRnfK-?YW#F5pF;-=-A)K)`j{)vx{jK_^jA|I#_{QNkF8g2mzNZzupJtHI8_3f?II{?hAIlmdT# zo7Ikz*UL*(FXwC-TYfX}CWAW-5G1WU#o*M`_GPw2zmd`V+=}&hONHl~yVOo#QNXix zSMlpnM&ff9@nKP=mvdy!VTXbZ^{UU;pz?HbmhA5wG5CGS=G;de=S&Gc=L*z}7Ax(a zUK2uDe02FS7o2`1ogE{t>GGv!$DUBJ*bsU9QT>8JKq+s|`I#wrELg=qPmw$bdAW=H zNAZGXAEc@Rf@>-z^mNWEnK(K7*ZL6J8*qjd8%QQ#Cl9t>VjspO$x|~9tKTF3U>Mfk zE~DW`$LcGvSFktNE(#hO`v#{0_!~)<%pM;pH+X}F%tgTfw<2ag_;^f+Xy}D5TNkSIW%a&EJx$0-Y_;F2rQ*SRhZOABR z!Qz}R-%l38!mOy+fgZr-OKt7AXlAQ=v{}NOKDLCUwRD~9=KaMo1?h$3b{~3{9`{t` zUwP-rg1QkYM}0wv&)8Pdo$jO+24U5)Oau_ev8lPQZw-oewZY`_h9YPAhZ%v_*R(j|jXb4Jb|<~bRMfN~Pr$&oi+ zmdzVFQ3pel};&&X9{32xnpPh*f1 z>#$Z+Q>YDRqADGmS}}Fkh^7!uxqsh|>Mb`y@tpo#9sPU32@0)!6@}=40V79XJin#_@2x z--niO2WqQ_#(7 zNkdC8rGJp~SYQiWnhEj&wN=XQBHFk zG%m4DS|Lg#w#If-T1JX3HzLJyE`tVW-Bc7B6+o-a;VcJdu=RfRzN0732ZnV3S&d^v zYFb#XM40euOH2j8v1Y26-Fx<#zBk;}e};XecOs`-Alr>V-DuU7**U|MndfNp>rM1` zd||&GuJheEeONUHLhkk(XGpEv|RpGbsF~ zMq$byEU#&J4kZJgbBvqBTwtRc*iu`wD^ezgwg21@G^yH{g{M}~wtbPQJe3FWGuBLL zhDP497#DwXy!MyS5H!b|_u|O?Yu-w`W3n#879`VWsnms$8>Uvf9fJw7n;*`R+F;3J zbrA(Yk8D9+5vwm8uX}07uYD!FyJb?3^smo)UFAT!snno4~&nqAO$o2vJpb*3|W6kW-m zp7jkIAJcb<->q=Ij*-mo(3-UF1?ed;Qp3)K8<3PvTJc$@5h#xFrAbI=nlWoqi2lx$ zTjNp38N&7g4z*4hjVZ99qsuvKx83|IzlaM!YtnnR!J_rtWHb*=Tle$;)-7bS(A(Tz z+vH8_uEJkmP2tchF32iQw%KN*jhDz1U)&|sexp?8ChMb37zk+;N2=Se;m$_EwLMOe!&|Q zaJxM})Y6ZA?_MC}YYd=Fs&KkE{AUW$rj_Z40Z#93`J02s08|~viC862amWB8@a-{) z!nSj%y#Oa|w-F5h9Ks81aehH1z7w-tsv$dONA2+Oij|gdyOIEPYcwVcC_^mjG@3U;%z)k{PY-?(JQ?H zW^)2;g%Dslm~N-a=T72p^EY*_{7hwC?1(zoGjFbp{6R)V4?q?!i6pViDlViG%wA?8 zU(S(iewI~NAWQKEcUczY;-nMpFj7CBsX{{IE(VRyGXhnOX);CH+186!L3y zGRwm_Tb6G)O*ZQFMy%?DI9pAYM_zu$A>5Ys9^9ehd8Yc~LGup3BaBCaRjMeK?|DIA zb3D3IsKA=VMp8QKPP^S4La86C^y5vDEUqZ5{nJ zwC<*I903m;*9EqreNr7`bzTppj-#+C${o-$qzS}*msI3nA|}l;ct!xtnBCPgE(H6T zj3KeVoYP^k0Gl7Gdt<2H?^T5>@#4?Xv_P#UnqKzyV%tYVjrkPR+j5rT6>YDhZnqWS z93CIAh*^DBq=l*TV;6t(_3l)L1xGanN2%5i@Nt@A%K-MEN~|xN(WQU)m2Sw#iVNQO z(0McEdDt!XurSWOXVXPTMC^$jO?|5Z)g57i9NA^2%*jhg)el+jYob3f83Wm-o-&@Cqi6oWu!#8H@ z84A6Y=0bPl`-0~t{kMr0Lut<~jS%Kar?JPThZf-&mZEF6ES1cG2cBca>l1*a$^y>F zUV-?1w=xjETD~@wY*KAWqf~)J_;bXE@t(eJl>YLH;@umbM9+m3A=@w47Ekxlt%RYR8T9<>Qk{f;depk!-tQZfepbZ*-c{HQERTYH zXIXNxghl)QW%KjD0v)h`#D zwj4g~#HGLumc2TLaLdGF@A=7E`bdL;NE3KoTievnox$1oOuxH!`stdTZ~xC(mI`A$ z4ka%yunwcp>)upn23qQ-u8(_0kW-DrG}S{B>sF5mZU}bg{8(H|+u8=7_4iOWJNmuA z4=ndr_$K>5ovVCI77q7!gR1DwbTkzNXG{^V{+E(wZdDR6_Ka(pXSGf5rf@qad%LXR z+j=->6X2rvqaR2m4GL%0z#J4U0ro=FbB_Cc4`jGmp%CX}j8gZ4vmwwKQLW-eN9K#j z#`&`}rs2!NXLcw*QL5JVozPBhX;s7c@JwigLa=uKk6qC%1UVa6#kI1u4a~=wpv2#b z>mBY0LaFoG<(G+^FG$azx$68|UV*1ZM1*2~R`G5-9z?irVI%)ponmg}n?Jq8dW%Hr zdjM%4X!pK5u!FV8Dnme|0gV4mx@K-M>uu?oCiDl#+IzcjDc8ej0*199p5l zTfYw;C}q4)RUAM*g%WfiA(2~uv1i-hP}{?CNW3&zH0MXTgGeoUy<&`J5lXznH)~qt z5DWN(qdQd6A00P^$T(H!qrfla!DVcJ8t(ln<&x@|zV&H#$R^L@b^?eGz*8Jm+1^j0 zU7PJBH`}{S>WrR;hlyIVJ<^zl-9J`D21fB!omNknFWtQ5jx8iFU$-mL0eCjtncT_C z%V8q(b}ur$kLE3@RmP#~TgLkF;oz>x#z=2<^oZ_ZO3q5Bi&58R?T6F;7Z>>gq z?wW58_GWh#Leq4|HO=x8YM}RIH@?7P$0>LhEFAq6*m6E-E?n2ilnUp78a$hqQu3}= z9mg8yp80aRi6Of~w?EnoAuWeNwbgrrk!ZX@9-w6m8>#g`iX$SO?GtGc$UY9Y-mtV@ zMCZ*E$l*TeW2L!c2f^;5Dj*Y@qipF7Iu*l8ezQysh&>yb`bq`u}IQ#1Z%RwVec;B$J!V@>p z&d|@X8EpkkMI}XLol(@=*CjBfKR_MzO3|ItJTRJ1`J5LEMxZ+4;w}2LFuh;*#bi=M zL}qpGwkuAB<~NSHH{O}9lTzEV{8`J3S%#(}BHt=Ylxg!>$&4i;v=*kYvnhPNdsn!i zF7VD8nUnI&wxY((h15O-8RGZA{1kjW&%gDz!A^xSJ;}vwVTp??fn1-uj2*A9?er=2 zIJ#L<-`Q{eEAE5GmW{mx?!Ax7*(Gln;V~dlaB^&^RrN?S8OchLJ$ubW#yl1PAg$74 zPlaU1nB41Afo8A_Aombw4;+3soQ%mM(2e$8#08yTQcW+3uk-@>k-k?`#YZ_z%aYD5 zRM>%@eA$;$4Jtf_7!HlqB68&b8kaQBK=aT~rk{1C>)EDj%|pyVLBX^Lxp>;UMurmS zAyYf})td{GYCA&~ii|8gyav{$FUb#|xBsreK+KiWoBG9PCO6Z={3i~o;X)r~JB@v? zvog&L-`XDb9C~{PVV_-aMsz#Ski6-3Y=C!x(+@vKuA4C;Vn1J;KLe1zU2kU%B72*o z_?(~^j}ZjLHBBDk5oMp!4m|s8GQ;ZWYV;2m?GNuCgaZHsmaHC1bKMM?MMS%*z~lJU zYO4kTG7o)sw~x9f$wR#EWCTk=>xam+u@XW#i~DLWx(=b}pL^$Q&Rv5oPRYgz>Skt!}@zmgR`M+X2&C zc-``EErn$Qb}*5f1&8yS>hNqG|2`dhcFZL$osDYjbn)!8#R^8c*>9n^9pf2iM=v6Z z%}c}K7T6XFwRIV(zcqetEleTEndWt;o6D7$_Q z3nVo!{$y*sv;|mdAe8UUlQg|n-^J$&{YHz$YJO$mH8&~t02V_m-4#j7mP5s5PeQ{L zF3IZ~AEy%vHD?{4_*J7IoaCOyaHXGA%54T8^U>_UEGHNZjmGot->Rsi7mPA%KcT;Mhs#ARdVx0@;Or)@nsWN+t@yU z{!>mz3aEIwodU7^M&fpR=uuwn{sdMVz1rXaS35&55A@7BoT+ky`1J&vbatRNPlzml z679&&%7usgMv#L+X9~4=XYQd2>Ui9hkFPzflGVH3`Wn^jBK1Aj*sv*;eA7(55wzL5 z+d#9Pw^b4R&cg|Lw7pY&dlU+Dc^i6}d+MZvIgBk$gVDS%@0Ci0^r?&%A*4O(_W2@D zowwupf|+msCUpLcFC__KlfAGg^F2)0z1HlO$*Ss;a&gCldWE#(DHd?KBY8jQ^or)( zF`3g9z{w-Hw`Ik##+mB@`mr|mAs3%eEo!iPoz(gVbX%i~&qZ;;bu*8}N}dlXe6 zALm;iW3BUqxS!S4=XPk`qgTCSmwB#d*F0;O=Ha_s3Rba7Rnb_5znzG^c@7_tUM4&p z{jl)Vkn<-Wzq*|fNNu<55+%Y_WOk>0zb|SiO-#lYs=Opvjp#nGH*zU_Du_T1Il4Pt z9)Fm(`I!?G`n$b&smW8o*GeY{8t-v~)QTSwMPqX$yXZ@`aa=v$ytbEty~pH!5Z+SL z32~M!9C|8sZ9<;Iq+F?VNY}H%VYys_9brkeo%u+gfQlgA_~g0o@ICUm7Wo60w4eT{ z-cX-P<+mT=ywFp2+HusK>3etj1s?i6Sd`q)f1m|7$D<*)pP%0%zSoG}*!xor-4kp# zS`tIXc=CipLKZMGbdoHz$muar@41@n$m`qY_ae?6G3TYRcohc8P>^6bDY~hD;jRXz zO@DwTC6|%o)s_Wf%N~lH^CbN=#_i3oZ(nL4iF@#<4SJ-tGgLQab6ua!x5F9UqAySF zhQI=N%wx_oJi{Io0`Hi)wsDuWR)ECOcxTf-g0Q_!wL@ z^Lwq8 z{DR3He2x^lU`u0mV@A>6qAqG2l((O?1%r3K`Dg?Xpo4>F-Jylh!i?*%7Our=(w(0x z^^6k_{~%{RBsCAr*mU%2{8;C&P6=uv#=7{qMqi{ z8~kdT;*e~X5tRVV{-d~fEN`I5xtI!D=g|4;hiXsUvR|+4v7ohW$F`e-Mwa5eOH+tj z`$u2%#(saZy?a$NHH{-A3%>f_%wsM#L< z(-C188C1yS;eD&~CZRc&w~V6U;l2b?^-<&LRBZmjOm8!TvpAB8VFIARRXM+|rbnmn z>wBfXt(LFi7T5-60j-gH^5%q()o6rLsZfsXo_)goKTKmnLT+CEeZ(#)x$xnzpzga5 zVPfhTC77pi`r2WYZ$Y2aU|%~BvNAlS!r=N~s+qY|Ez$62tou{HI{o36h9J~RRwg+kje51e+=?HmC3;r*}n5@POcTF-Ze2Xj)2(1Cp| zY}GhPZ54ToJ-823)qs4O==|;*!^tF>2L0wR{n2GHWU~vMWU~!=4Q@l!mvR@%c8bXop}F%EE!<0)5c7UDtAi7X!*y!u14{W{LNe$hA3fFs3QR}vPDH;t!v-n_1n z6{r?}{+r=t69AD4n>$c=(;a7GtZ92{BfsSE9}?A&92pq+#y=*BGh;0Ba;VuB^zi5>+26f2!u-Tp{OoO#T5Iv{15n0t*|07Cc}9~ zc9Rh9Df*9F8(@tWTnZk*f~A{9^pzQ^#WmO3;(b5g4=y*w`TmqP(7IK(7!i5-eoC$TuVT0oBqH(ws^K09wy&Yfygg0Z)W|RBvX3jEbEUMxy3|Bg@=nh`0Ihxaxk(ZpqneSDJzt$SrUZC0fv$y#>N zNpW*l*UaqPagB3CwwZgkBpo&}cxZ#`{QU~jdKw>dStsty?~mkAsgRbB^(YfLbuhpB zNH@hXY&s)Mtr`Bdc4MV;t}HUYMZA(8yp$x9#cTkMW-5OGIqKhw06&)6&J$_gN~qu@ zVx66AivTpQQ=M~&LLkQWmDBo~qmXrC4;O10cxRaLvRN{N533v#=JS<24X)}#i6S58 zj?2OQb0v4Q2q?*%xfbQOmLmpb!o=iHyCnZk(n2O*P*nFMKi)MjK}_=BtK%)X!Z;aJ?Y z3OzW#QA;^JF>cf{e!u9ZUYdN}@(5qc<}IUx zXxci{0i&61ikuf09BA%GjI69U=Qe`nOHT%>RamnWLxV$;7vv?}yoNqhd|I5bxAMTp zDoe35g`RHsMix5L$v#2uRm1PC?BKE6yNB?txjz>&0{MA=-nR(nDFx#SeFy5Ea4Z{n z-P*fxh^T#ElcB)5&tW4k=8hu`bjEI#MN#T=-^JHq{J{5SOXr-%{0EyT;s4s}rrv+{ zNg#j@EgwJOj|}Q#=$%G`AP%O$h9jc)AC&lu4{XiEE2KoK`K z-}naeh9<(TY{&Pk&N-k6a~Yqm8>wWyfsjmu7wJx&P_pc|@;Ygs0(;*!QMzPHKZZiM z)09hS*e2>9(>g5tt@L`9Gt zGa0ia@oS*S4q>khm_`-I2Hfv!)joo*T&jJ<$nD)mq{)g9f{)^=_@sH@@~#IrsjSIh z8|?yatm3j^f>7$;L_gWCk1Mpd#Oc{?^{zi-4-tRRip2J&L0-Rn5|3uww#+V>E$X(UiWW(^o!u-`Ye0fk@tD8f= zJArS0b^lH9%=pzrJsq|Gfb|v~*XS)p#Le;XhhdoZy+g?(9|6I~~ zPp4wu$-&Bd1=Dlkl$B$l;;7NZ!oI#yd?wM#s9Il)&hz&~Cj>mYa|0B28-;&OR&9WQ2;SGdhr~NUR*mmHzImSc80+HS+!Z)BHy<>#ts9 zN=oz_e|uB#OAQ}e7H1Rf z0h8Idzt$JuQ#Csh(~IF^eM+~uV{e~N;x3bF4YuCBpCQZo%XGOl_t{NbD!!YRbosE&jF+y;dSuz@_A|B)3uDmkq_(X{ zuUwF2+$Nvg%ir8s#GB!zhf$?EpL6hUzR(gL>`DKzA*QPaT-~2vQS2dOT?ApRgz;Hc z-AFlkg~*u9<)DXLO9*c-Yp@KtFf9OPmCrwn&)CY zIdVpkbxXf387t^?*6h4u^L4@!&A0>#UpF}ie08JW?18o=?n0^Aoqpde1(j28C7@4i zB;fNC2#e^Gntu%~X~XNJgV~^0%WDd`3UuAXGSgl2ET1c&XAKW8SB59&PZZrQ^_u9OqPznDlJ|q9!q{)J7GpiS+a4&Hy*)y)v=@rSesib{SGd1vFp86qBvJpi;gEdroyg-sktIV>_60r?mf&s z>eowR?bh%%*2D)_$CELtwUCQ7qaHTXw1ZOslYHfe{?eGveZQl+8lA-&oh!lB`rnG@ z$21!tXcKLwQNXb2JKBQMui>$eT1_v{L_%$ROQ@r-NvEylS9w!Cp(aWa)ltN~cS^aU znf_w;%q5B*Etcfo`kIPe;y4ZWc3)qL%ax1C`sJoB1!F@#H#V$wyH>{b_TyPXw?1 z90^lHQ(VB6Mo*g(W@mSmM_=k#Kwq`a_}A&F#-sb^CRMMQ_7>MU5Mk}1oZ{x<`<5h% zsmX10Q}1T9zg`()R2UuP7@ ze((EGG7sNWAE3?K?0oljw(jbIp^nwFy?JIA4~R1${`BPnjf$-0lY6rtj8p&=j1=`i z?hi+5C8|UydfVI*cb>>~V{gG=hwDRX|OM-Oq&^2!s;*Ig>Mp_P+JfMiy6?xxNHm44$?IO-) z4xJEL=Dkq%>(I!I>%Pr(JH9c)IcY3#W)xv}|KZykqvy6Uk?QH8o$|h~mFPdVh`& zCG{>lBuual)#Jbb#D&-cltcU~Af_KSxNq(6NFkG$?`2HJhY_}qi@>`e)+3$gPp{f)v-!W1G?z6rx!9JeRasa^M>2Fe zjeksdCS=4$W82B+3r$-(c5|GX^C28oaa$=6!J*njGT_zO(`ys0ZgJNTR!PmBM&g}| zBM%g>Q<-itbzEq+Ijfw;N=WU&Buj%2lZ|_{YS^7#A*bru1{K@lt{}9dI|75LV+X4w z-@aG=6mtdW!hd1`YRXxHHV_LIUww6$JrpmW^zPPGsWxi8_CQ27hQ4m$ly2zjLiJj& zUhT56Exz~PB1JwTm?|65_0tV0j2nljO14ctB#$Ehq6YR*HgnZm!$|wti4@M}Yc$t! z4%{9{hks)wiiqVWq`T(%VupRFF1y2r5Gnp~K6tPZIbR(jI(4P_w~U4c!R?NN>O>k! zFP-jrmR+0e4CoQby-fl;X8X9pT#T6z7^M~j`JAlmTWTSk zYxmsz#%mT<=tpMiP(lqI+Rzc3N-&32Vb7ADKFKhMsA`u4eEX(wRx;;~xz6X3gA0#z zdH57TPp8Wf8k!`>YuNdq{Qezj_ZiEDAqBgs7(fJWcTW&}98759e`IX}@(+@k$6u4k~sn^DmxH_Ij zwD*?hX|&{_Z?y9T(VgLfboYAQlpq zymEy!WLAa~#U6Y7I}M4Z4Y!9!`qhqc?fe+8;OlfeobY1&)Hf5T%1MEb%KNyq9>dP0 zY+|VeI>(tD;%rfITmyoxjaMd$9l0why~t_=nJ?D9{i#t{%q0(CZsx4CW#Y;3kisNC z$iK#?eTKVmZNKU275X!Zcsk9IB5mZ;AN=IFgk3-)>rS_7@Y>gn%j1;x&D)tWsWu$Q ze6z=U%`?WL2*Fz}_hUVh<#>h#_QeNsE0MI;$cklpbl2o6i##<#5y*d~Rt<6G;16N5 z+XwXV=H3~lL~#LF?{H0TC8swx=uT{o$UhAvI_)}4hSl9*dd7U6YOd=|H^$#^3`&-O zSasyc&H2@00@i-Zwb*C}#ir>*)`TwirrzYnMdvJBqB92vr?EP^Fvv513^$0tBsBFa z*9;EZO?0iku#@PA5+Kvs=~JoypxWhvJdqV|H&AIdhFvLNSr8+MI%{z3O_#pXf)n)% z2lI)l7aVQ9%~`ae!UzTJtgUjU(@G6d$seIf}_J`q|6um#TQmfmi8b;5*!D^4<09Q zMk?~B`cZ{H&!t2St55<|A99tu?l2`A_Sy(KC{7Io7b~5mFl*BgBa`#{OMlX|N|(x< z8CaLzkIVREbR^60%?V|1nxZmmz(MDb`yoHsQUUPC@RZ;}7yDVT$m96IkkFHuC}RO? zO46l#^i}eIzL3U0rPZq)h1nB+7Fg_Zp^~*~$JAP25h;S@0<2eXYb4`E`tBvWN2b2+ zQSQI5MhcgUD)QtV%X+uf~4>^>-NvfOD%H((QDFRLKvFC6DCwHGREEwXZuh8a`b0%+X7nMwjHV|~i zbG}mQ-~QlFJZOWIYrCt~;&V=vtE_LBsqn+2zHyIYFoWT_;hJH(e~F+QU0B_}(P_zF z!LF9M+*x2^&##`CJ<1$TACvzYtpb)ppGu}Sqb}U&I`*6rk@snU9m`TNAa5#H`MW^$ zdKi7zUPY(=_f__QX)KYxw_hI;DjDaZQ`6zN(P(hXB{*|L550a<-y-IrwHbT(3W=t2jsAHegphHe43xKXjh zb_8OxnbuQe4_Jw>q*eXldm-dFbVcg<57f9Vh`2WNaW?Ln!f^;hXe%`)!s)?~W;%wM zdCpClPm*hWl}If5U2lwT0}Ka3hr^K2giV8$<93J(S8T(@CA?l$NpXCCQn2r*|6*s* zW7Zey9+60P+gRGRFL5mt&i^b$YOqV$P)Fp@Jd64<_`ZW2C4GaVKy%cKMMqyLVvK%B zDPJliGkv0SwK-*rWjzk0YV~SsQ138k(=LVkuF7U7;XU`*fEP-&QG|ywHIk-)I8UOsCr+V!ckxYZhjd%V6Ryhq#ad+h#Cd63v z$YpFpiBl^H8m?`P^Ajt6bHmQX1tqCNhwOj5OD-9V?P6k=z9dvgr!qRykuAS>hjqe~ z)YnnDJL|Q#CXOe=?Ym3}+dnVe%_JX1XSj3U~Cg>wm}ZQVCCWlQ~*Fs)tt83T6T zIAHa%ytwVXPE-Z+)tTh#2KoI17E_?inD_48wxO5l&r6+os~5=hYw417;c%c$KOsRw zXNFki#M>gv?$*$pK4GI%8@;fa{%XOTl<>qp#5rlGc_}!_$KQurL9O@<|JdcIanjP3_K7GH^A12J|B-c9q&tsShp&W*LmO95EmKCjNsfxXb<}p*Qr!+d)fmS4&)Dsj zsZ=lbTk=owWq{V7*prPuKX~umYNVo=_;+1%M@0|Rca}6eAgQ`=gx2bA%+Jd{Gw)WZ zN4^@$I-E{!a7?*>HICzat~4rA5u~$9sy>*He!-lDwa59aFv%D8A;T@S@Rag$B9PC( z_s8xdc?|mrRun}Zi(6UA()GI8e97U8`Ji`MVcn`z;xKqdi`8s678Lx)kc0u`C0Ruu zl9@Pdw0i|td9qL_mV3n*+79P!H8unolb;VTVe^zU8G! z2p_$dohhGyX>v(nXOQ4%vnsrS$9`qj{{5p>>r1MSVY2i=27LeFq_;0vS^oT~x52As z!?b>|gq<2@ks1gT)a1{;l5-vLHoD*-8=o!Gp()3#QmFjF(U-RYUuW_p58<9LNb2th zSG!O=ET*DrIUBFq{Q5i0l~(%pz@Xt{`&~Csv+C4ruJ~BPpYIzGGAtJE~)Um zggzL$1xux>^E+WJ{X9FVpJQGIGE-w<)tZ-jgCi*o4iDws$FO>G0FBKQF61P+89R6T zsz?!8He)abfy8m7@gKJ0pWU&*w)vqsMbmFej`6hj&+D_q2341M+dExzIuV+5>(*ln z*N#Ek#~>0e|McW4hbU6}3#`fJCLQ?&^2v8B`_S}qf_mS<~b6C2R&P@sMoa6_Lx^4KxEFq@n9WM1(ia$-XN)Bk zkFO*eb5&q1`y!7fjS(->BJ6oin2s#U>@JXW;CdiHST9EG`1y}%y>Q+1WKyVkf0rzd z$tl#7SpD?htOH)FyxZ$Q0gnrLsk2}4o8CK^*AE>-r|24ZoJu`{0%Gih2?8P)q)Lvk zJDalkSMDkGQq`Q9=(C6dIwZVa6*Ct6a6i7&TMRw*OVjeeMk|jD<%7L6W9I55&%v1j zb;l5Kg`CV2lRJTrcY2sEXvgw%;-9Gyj^~G=ACef{w@3`=p5P)!6AR>fxyc`r8P5+C zzmm1OUWoqbY_RgR5PTYN4tIrpWGSasveL}{!ige_&m-)R=Ebh@@XSnMJ$?f>lj2R( zijH+&Wi*{9Sz-fcu0nWR7u)zL8XGOZaTM!%Mn)&GO0<$18#P&jnH)0Imte>i5^mRa zHcX%z5{{;FlANgT1Gx3xHJRoU7-5i*7Q9MnDyZNqq{}!lGYv; zl>VH?OkuKw=V`zErBSIw70z_W9bHCiI5W(3Eixe-4fg%?*%~exj`JFAP6`{7=<+0Kmx7GY-{1V)P5Xi0vbjBaXU0^*B1gX8cy`P z!c)dh&yrcGH>7`Gp>!hP3gQoh=znE0;?{NNGGK2?Yrr7(938NP!D7B)ZiNO*eN?ad zQBM#z8qtGK@&{)EsDDO+%#~olWJ(e_(H96jcqD7VYv25be*!a8R8%Ay6ZL=#i@T8z zPJ8P-MEQ}V)KFhGI1Q}^z&>CLe7M<`{!}UyB-$5MT*45snd~n=nIb==)j?}~r;q#S zj?9%+U~@5-cNNLZj{d8){;)m=qT@&1aAw~|Un}gH23n7k1=PmJB^yQsmXgHf20cvw=F5l|O5Lb7A zsf8mhKyeseO4~P}jjo4YDCqKZ-hN*8L@M>R_PCCfYVPG@qLWJY8@y+K#7c<8(gHtDhXcaFJJ$1&PWI(fn8%aD@BI&&ae|N1AnTbu? z@BAFO0DN7&7ujq@M(xvpq$Duuf$LkH8bGl=Bc__He~;1pHSP*2VvPr z>4c-GxsOU%cOf;b&if)5@)zYUFt87*#Mg*WFuR($?sQp;O}54kS@g9YykjKJ4`DIY zH5fd0HDtV+5+>*($*lQ=Jj56wM6*ubEZ8RX`pJUa)dycix zjItY#iIqzP|LGhyLuSG;u$XtcarTZfFfx@qZJXUKylH-~uw{)2kEV2N=68lZe!E($ zPXy9APTO?t=Y6xO2Tz_9v^%A^`ur!y;$D~!Mc5`qMo$XV)F${(tpsL8CkDzMQ zgGSiR_Dp84n*^MEhPIIonVOlQw9woJL<9N<@ez_3`1Vs5_=7F3>?*LX^QxDb{=P@s!ILNdN0-2U69|N_3Ht405n7y{bP)v`@M0L;M zv}s-0oRj(cF+8(4`f+}Md#af>#V zvy?cxqBxbIcMMPlfa#_!idL}Y5WWIl2v9Nd>f^^Y3I-(COx5fSMzF-*4J89|I=r3Z z92;-AT_{n?os(GerJu0xq>Y4w4+b+UFS<|=N+<11Xg|tXB7LtD`pcDcv~Zb&css|o zcsf_1Wn|~JGAZ&E<$K40Uj{hQSCaBS7G>2p_Fd20DFg!;{GuVf$$Yw(2OLvbPi52S zJ~A>0u4o!cX$p6`cQ1O&ya^AfSPDc!9+OVQ=AM=9)Y?+#$|o+ZW3?WmK9DvLaUzUi z^xnqIO^hokW)CHg_oG*eVlw?1TLG8*{VCq<3#nxJBPLdhiLCLiS1)}cv+PrT67Cs) zLU{Tv%063-9hVA{94k5L-BiWaKb}&vtfJv-w@Y^CMjj<|by|m|H{9%1C0f0RN?zeR z50&=Kpx4q$zAe*IYt{QFLW(H1Xne6wUVN#bG&1K1Tkj$;>Zv{}@o8aj=GOYwnM|e&fkz0ab|9^R zaC|?M>2xzqAKbWz`Ctow#iPOL65Ce$Iomo84DT#Q4G%4u#3r!X8zhw7mNA*yFL-BL zE6tdS766~ltP!yR$7W6gx}X&ENtHaUD?0U*rz}G7cuyc^K$D!4PuX7%gqO-n# z=?$RmZo>|Yg((MfVnU6j=c8+Sj3Xs{j%{69N!91y@QV%V= z$GCd(rlMoP8q&;#nF)d00>(`R?qe?ujIACE9EmGFdf&h&JwgO(i#VWH`Gw{a4(}y^ z(k!-_GxZls8+W(zP;;RB@mtDzsJc=zR}7M+ZtTE@{N|}xyTbJj9+-`O!~FR@Uz79P zMzgPztQ*tm$c}1vI2jni(A)_$f`9vMCHY{ux1S+}_rX-&_}Z^8$mx)1KAG}4@JMBt zM8v|~IxDHZn%;jWbac91{=Vda*{E_O0lN3z{xJT&KFZm7WBNIRh}niYy(7B9nCxbU zAbqLbjE}zz4IZmbzCZ)T0>d$?%vOW(fKKE*Uv-hs7lKPV=kT^*G$GT=c;!#m(t(q; za>xUg01@2GZqC{RkD8h#QRDz^-bo1l?o>cr?w7#%^Wx*}rPn$uoY04=-UqZprsmit zGeHmLm#v1ic@%#1e!9d)Zl~#SSTr`;aHEOZLxRKFxExQWptvZZ6`5;=AZR&W`H#Fw?MGjL^(N0RI z(?1cky38QL!+JHLYjX$Itv3HjwU)b2qHK73*?K7RGU`Jw;#?ulN0NZ&r|s-d=z#%> z(cMvIhk{KsNtFu|CpZvnI{eAbe2mtvR7LJw?K@dv3HsZ)li2XV$EAxoq^UbR?d0qW zWx6S*vc{*rx>)ie7J0dSfH!U;1%#jc8{i}E$TF^>4DZ@SYozDSy<*t`fno-rq z2QuHe8nUk8EOzP+Wm&72M;9%gs5g*0AU9}qB?kxwE=P;*sJSbC5&F7QCQbIYg3T{3 ziM)MN*?aWR@U?+`ix%XXL}9LH$SIy(pjt{YB}Fl*HrhB2wgS}jP+0Ox%sGp9OD!kG z=oZx0`nei;cm)}E;fBA2%#k%apNs58!O!AzMxO&jfmSa%Re*EJ=pXN-X&E$!TBct@ z**O1H7_MQ)m$GnhF}Rw4%O9XMSgBjGLYT>Mbs~zFq@YZqyWB@QV$BLvV}BwEG1IGJ)^cN>L#((q2>`Yf+yXZ!X8|lY7yL0c%;c%RmjqN3Lhf!D4VUp%YBEfyXo2DIO-^+5Nu4JmNYwhY^DZ=@d+FUq{~$;wr>Pi&h-X4mqHA zE_}{R2A~@Nc z)Ge1N4eQs39lki>q0AD;PmqLHmvlxRLjn8vuIBmM6~b6*PPBcw6zaSUPKr>xOGQL%{=_0^}Q9H_6xym2iIKn3STWF_)A$ zE$Zv_{TW8rTgGDIf1(ysbtZA2fS>d9>8#1E@TZp;x0l*ha`9Bov764_+He+s{|1ex z80B5}#(|ruhW+jk5{ProuzmmF0ONo~@@%m-Fo{O9sILg>s(S0>Br-X9A#@#a-Si|$PE*zMZaZsTIOHP6>dawoL zkwUAF`gPU(3NLOeo-$?AQ;bw^DE~FcXA{ZQh^-bK0mX!* z6`5MYs%235q~4+n7FY_-0zPF;8_3_Uu53{yO1g*miW?m+Cs4k?X`C`06cxDo`dn3h6q!MjYn#*Ol|3sfi$Uk+<|bdO#bH=ueIk>~e5uY@!YU2%1G}@c z)6L!8`*0j_yW{%qj^z9I?-Lw9Xv%duoV`qO9 zv<*QdKntfLRLJU^^IbS!YonoTG8}{-Nur7D))TAG5XQ>bXhbCJTQP6Yh!V-~i$@gW z{-!SjB4Yd>uUeB)Mw+(rFG9>PUy}T($0A$uf39w|K(l}we=tY|Pp+WH$x9G-GH>D7hF)K?Ib-+$PY0%5+9fshEKFF;T?QZ$nYymE->E9dvxA=cnHxH4r`#&<+f|dy^PD$v}vb5!uzx?ZOEyZ=K z|Ht6`Tg_OPp}%+4e^wSs%LNwv`v3aMD;ul~Vw-pAL4g>f)0(6j*EQr`??!+vAlcIc z)PMF5R-=p74`FU6kjh^sskcu!h3%c|`w1oGEgqhtXXtihMp$`x#wuu)DSi#(uQ)A{ z&l%B|S9N+U&|nbt3$3b2y>QR7*K1~)Np)0e{mzcARYpxv^R?2XA-lpR=nE#i zonBgwqdDiGBxyZFhRrfhmb=lH{U%Bk0m;3WFY=alzZu)cStWAQm>G2 z9l%iCP}d^^=|12u*w`laj z!AzrxYhw^vfzAqT^V5aN(<$w2JN86wv~HX(jxzo24;1V<{YQBm36}Gp7{w=6>b$Y6 zEEjdRmjv}rp2aQe0`2*#tER!d`tFbJ^O8O3PXIzMzj|n^~(H3|WWy9OdLMUkP-E2{vZ;UPsqX zu~Z=5URHGpk&!$czQA>a+Rx?^;k`J2H~mfcu0bDH6k1igdf}R8%wUTbY-hvIrs3NW zBq^fGZ82LA?8-Z`CtCszPT2M=-!fr^Z*u>;P2JRi+;y?5JJdY;#bMkjiY3!QWF5-% z+H^F5p~6ioNu#nYR@{B0U;9Ljw-rq^>(S1^g=V_&KAG^Vo;Vk|x&2LAfZ&lV7V|9A z{0|cp!2N{jR<~T;!4T@r#GkPAisO|yT1Q#rxLk5&3zqGhFC-M^>2_mKu?BH#P0}J< zVsL#Iq5H44-NrpiCraxKgmHuoJN$R1&P~VlPbXO5X)cClSe8{bYD25%>ltpX$=ZPu z`ZxHls$qRUs_{_AA8*;a?k@V+A}5dvZo+Ol``;k{vVaf;t1)-0E9cMHrJUQE2rX1U zxle-Kl0@vh?=l1Ch8TyX=k?o}lll2{`x@`9?yXN{bnq}=RP)7C=~B5aO}=bQE?O^)R0uk?oLNuRJDjdpqOVL?nX zlmHyp?f9ffEaoRkY?*TE_~kxG{nmrtUot$YEhoHgQ}9DMb-PfA818jka=P+@E` z>fQ@EJhR?dMMUxOp+@5g0oq@&W;GrCgaH3`V?2^WvN}2)QyBW5XN(Rm;7Q-T5}6wx za&0;&?KDo9Y$S}G!)x#~1oenbMX&z?-$`WvSK?IuCr05cnci(#l{rI>_P7WQ1CyOc~SXvU){G%3!YJr@3?9`mTRbmZo|%Y zhVq3uL2!-I@t|Pe)Df(@142`bZ`v0xg~!iR1k|ZwWqj;(D{m~e9pi->Vo_&hu380dab>_TJR!^q&9jLMGO0W3m5?1q(U>u_Nx6L7`7{qOXP;H z_G<$8VCQ1$D?x&&2=XGJ&}Bj99M8mePh7)PA{93RUuu&KD*5s=dQTELX?N!f zc&pc1Gz-V4f3BgB3AN29Bm1<7UM+cti!Js3;AVyn%XtH8*+X@ekvwN6H=cuMo2RA( zFCnPeor=ZJIzOcD-kqT{^&KsE+ypH6Ii`4WwY=HoG5Su?$N}g!xt`mRFzfQ`YM!X| zPEEX(SMsq^@LVYCD{&uW-0_v(?(#(DsvK~t!0>Dc)XH<5)A?br@}`Z~Jw)-l543)` zs|DmyEtFS;bmdkByM2JWwDvXuy^O#I|9{#JL1Iwi*_)@UVd^hzjFp<;bsB|zQAvms zxLsl0Wj}O`$8L@fugF!uQ1u$eWJ5rc{z#8{Q1rUp6s^ufxn+`RC#9|duaxz1 z13S&NqgUUqlm0~qQBT26;sVt$u7p;X@cKyUy~QUJqihefW7H+EtAz6IO*FvZF4g(* zpM?Omb+i1zaCTt*pgt6fn{6F(>P_W=qL}3DiL{cRwb@N&GkT|6Yy}EPS#H5USO2tk z7@!y!dwWG4DeraLfo6;PL@7J}-V+h(GJEuaw`VQr_C5)tLtqc(?B$7i!OZEy5r@LlUIyc2u& zNRhojFgd99wG&oM(hnF_J+<;h+}pvC8ocG$`V)Y5t-UP0lIAI&4pTNZjSp7;nM z-_(2HU*_pm40YOOMVUo_Z=S@D>vhePEV~c=uZwNl*gIvV0g5WBr)XdZ7kn`f0kKD0 z-mlWwb0FN2&g@slXyQstvtGVqoDqhyoF2Jaya#4+ntBeK7?&Gt+f-h(_ zX5amxY62H>L&jm5tD6`u$bFS$thM|=ku7L)0320@+n7wUZh zu`g6%faj<);=x*yACPA+4J4YUDh5Lytr)aF!y}{*Ssq|**7kupmPkfEKrt$6Kzb9@ z-tP+aN9>5{yA=o{`infF41`$%0O!rsTM3 zc*ZL|d%lqK37L&0Fml6mk2c~yE|6{aC$5(Vl5@veCetV6iBQMhu1`na9qk&L<2JJX z``$9Y_+{h&(ATzSvm-8q;1`bJC=sQf%F&>749K#x`rG#-gi&gq7vo08($8tIX&N!A z`jipTaICe8L5rX?AIQ&??=T`3hg1T};5azxYD>aae^x%}=LVJKgowOXs-5gq^orPm z9W&_!kC0GY#mZTgavFh`^Lh^Kw5hVU_!5_^O6Tl6OJ`gy^%hu6T$$`lp<4^LF`{6# zH`D2&Dq^bf5i}AawA7eV3<~nsy8f1_{f9CWkq0fx6?js*79&^KWPx{+8*1~VUu1Pp zO$4in)bf$Bu_MaZ^8jsMtlYeH{C^ZyAQQ2uB^GO^d%a%oShYTkjLz!J4dudZP8>;B zbeR1Fk-JSm)AQ^u-+ixfAT|w-@#3oaR;5D6-sA!iZ|Yj0BgZL2ZHD?LcK0>d&O?Oj z{bAG^`gVC}*W+j>#J`gf44tm%y~7fB?UKv)eKq4+*4K1n+hsRl7?y~phS_GFRFA3a z-5cj*gzri?T#evcOLqe#Df5K-Q-QH3M8a5%^(9N=cBo{>&elDDej#nn(_$_eaXm z_r*!Yc!AHJTt}Q?^@N4X{OG`(kN-?Ffhf>U97)PfmJ+Q_;;?;nQZXJ*+ut`cgQH&e z_?kYrZm~K&W$u7xbq8&shN)kRfru_a4(-9U;s!a4rm1-wA)%(GR^c3qgblH{n5X)4 zO7y)lBow&_+3?y}%?y*=!^+wiQ^$+?bV#ul$zA8;p^X5u$rZ8TL|T8})$wuFm0oze z4ToPd$o5_1cl5k&?dA$73;{An&)7DURDjUCDkB!a(NGW4aso)pB#so=^)%o=C)cg9 zv`Q)CL*R_nPv*S#^KzQz@=NrC26(rEf{_PKZX}>DQV@spinmLQ$J!T?KHs!$y;<&- zM?~{9il8h9w18m8v){i2N}JWO8qbdDD@CN$|EUjVn?Q*CW4bh1fwl09wklltR5jzJ zh2`$~VxVeIU|#l~)Vtla$EX+R?#b;>=iw{7V`FUIUc<-dWHnape5UB~5G;lcvqLIR zIob3+UQ~SV<~tvNTWdmD-p&6t^>@|4r~N3K2&?2zWkgrFg5L`su(^xzfVek3wG00$ip+DfO$dq%Xz+!%L6dn@09Sq zg^N^8CRk26@WQ7kn4M}>rGj`0_>jDTk)-^L@CK#gY&4!kvJNAHyEMz%3d4X zI)K`U(95jG>%#3C%v5|?Y&ECy1ZeNC$~M%{?9L&1Ez*s-16+}#h!*GfS%5B3)KpynBT!x;qeMKG;AWbdY3 zkdK(5F?uK${DS|D&ZP-{r~IvY4B;ZpN~t0R(s~h%R!eqM9QTuu-3|bL_QQiJEd;n! zcj&uYyZgP$s6b_~Xjci}(d>f+Su+svB2m~rKINxN)sl=~C$jWOOJB$E^gO&KIFU|A z&nv}+M98%gZBeh?-WOGp??M(5E}p|ZF2A1r@X}?Gu^s$!by|jEi6J>0cE7v6Wj9-d z{kAo7ckqnav=ibkN8I+7Jad!#RNp+8-Pfu4!0u|tmELsPbMdO2R6puxpd2BQ1z+0a zEAV5Et0|B=cI-b^XCZ78X6z{oQT{7V@WdH48aVP)5V2G+&J^ghC;(3_u`w(6mgF z2sUi!*89Y4#{3CeOVa(9G)kX+*Nq7Zqw<#+g1x%#G-Trl^?Nfg!gU;)qt#KlN*Qen z6{mxN>VJS3rB~pUYr+4R5c}eL&K{_?TrYZ=03__>=*tX31HF4h_iEx%%oiM4_!9?e z^~F`8mwu=*(;9w-_?aKenjmJmj?5Mgb!Ysto_shmpRcmtT$|6nOQ@>?7h;(lW`E&_ zEhSeIVQ_&+99V)#LA!KD0<*%OHpYzI6#|FD+V==_@vwBTa7I0A^<#nQDrja-5z_dz ze5Ln}go6>GR3g5{IY(i=*DE{vR$D#qpL9MAk8D29RUb%wDf9PZZ20u=L`)j+w8p;P zV}^2**WvLJD#?Kr$&{93Boz|Psn9k$A|X>4}<#OjuLh zqnh>hRClmcYDf4<^+hC<_weXtN+c7{(m(~@q`uv4fx+-lf`W>%<}^28WR9;0cy2%Y zBdq3T?8Tj`8-C7gjowm&odFt2b&;nr+M@fzrzKqTMI5&3)x#rzCK1PD$B2C_Z(|Y( z{jTiU03mW=!{2JI1SzqMX2O2MDLojB)M2#>is}6s9ii>(d?f_RCF6Vx(KhR-N#(wO z8rEb4_};*$SXL5DHmIgRSXKC)2O+_%Yn|qPSAiNz!9Y%Rc{*C-E&tzabX}ZxY@?Hy z;<|I`jB)*P1x2oAbn5f)(>pqyydd>PT@~{eda;vZGon`VgI(l_#p@P8mEt4Rrha1w z{-TYBtkb+R`V$1d`)eXltQ^@2vVSJKF`@A9iUr+I5C|*J1+9n4llm*z7ShaSLh*bQ zyx;OFm39J(3Yjz1y8_<2!H;-y$%N}aQ6gYGVM24~{%L_qnBkbxdn7-$I_{R0 zrn1XdhO6UUAB}*+urFgtzrZO3jQlA7zv2t>WcM3kVjD}ipW0Z2ML<|82XTkOg{$K& zbr)Nnp|hG*C+vmvX-+>xFNmhRgAIS9_LNLdm}C9GaIO`To54<;Rql(y2|S-ws7Vn} zF1n|3OPxG|0ey20!nlzhL+8HF1K!Kgsjj!Dj_u>E@K{jyPjT%$lL~nf9MG-H`d%*4 zy(_Mc=cUAnWKjikC)63NI=9(>vJ$P|^9=h3A7@8pYc43~aTgR^W-)n3X_-)kmi61) zlS)Tp>@J?o;m;SxheM&CR>t)AR`-qEnQEm74I`0YpWGn>MdtcnOiZ!&nH*g9xRcf= zq~bR^^CR%Lxz07$)JHd70;bUF_MUBbFbz8$`Xh*Fo@d&Bq0fELX`tbc^X-+(ak`RP z^$<87{bs$_f$A%~;)Ym=ONApktD&~pwuBUh=Jkv#7ooDikTu)x#AAVoDSA(%9kY;6 zB-7SV=-G$B@zw6bYNM3Gnh&~VyizPE+igllHHQobOn8Pt-a$cPypPOBHnq4pv2np` z6O(%jLsV#We@DO)M>dZXKFfLB?(W%3r#|KT%Xt-%g2ejAs$xb7uRYZXh|v3y4ky(Y zRx5(dP*PzrensF-VBuG6%y8He|aMn<6Nry7)+hh`76zi^dxCtms00)J#9w@DEArgCR^1k zvrfLmLbel+J?cDBJAZpPq$iQ`*W3Yj78(q4s@b2R%<&m4Ha^6K_WsM`XJTNha}ht` zpc+OSH4T{%qnbm-{C=U=o)-0TRy-xibZ(Bp*xq=tGC|#_EnX-AL_i0OyJVB$?SkOZ z0(;kzG&QzX`lR9D^r_cNFOkXwm!I-I}dh>Z)9dBoN<<$$ajfLHUg1c(b+ zrr5@*WDEacY8u3i+GWEP(;IRmqU1Et9`G{I#@1q~1jPjm zk~cM=QLHU=&h3mv$zTC5U8tfizdtvf%Nh(an~rVB!O$+cH$7Bc-~Gh_O9WT@PrZM} zY;nDzMM{%0noPPBTy1FKsx?Z6%ZHHNzi7!b ziBdG|bl)Pp_+X6!7MQkmc2SlASdt60;}nVV*guKRYD@4?ZMoG3rvGCn{>KG)tU|)U zWHwov+tTDD0v%no5slZ&{aL-$5~F%H+P2~D$w~UD8}hax@&DP6Rb5T@`SWKt503%2 zwaH1k2}|*<)6>_gbW%|AFkQWq`N|8YPPdK!gKzprRgjoFvZ_Dtw|Vy z-oyDCdg4m0A*AtWQokPk4~>aD*om^VLtL}J+`Rt9CD~Al5_r1M%vkt?KR98WWSLL#F9|Mylz=r@#G%m@{xGj4(w+ z7Qp`Y?Nz4k^D%QPA+(vraOMF|NB`@Y&iUVZxC#MJTqOU~sZBi}Lf z-(T}5E^@}_zZDu`%fz5E!V>47{Qb$Nu}#?jxAH3!t-`-!0sdL~{pS1s?9ZbAU;XKa z^*>(+{|Ecu759HpsRCah(0&Jl#=8xeMT_=5n_7KOGpGI7_2sAL!~kbI{7Yg-+Hyxy z#KCPsn=3vzD?y&IuMkI#QGE;zK@mFIHD!5Qu>-2N#2V?v)W&^%5*TChA_~lGZcSwS zGTlO@P!|>(yyexh5YNRU!jzxHYvM@%xR8aw66$|e)lmXn) z_vc&IaqO$OG$o26KU|JE6M450m_=H%K{6htCM8<;meygeoC@sQw5mT;!`uaiU1fo~ zva>kW7Nu7HS|jrI1wNg&QJ)avb1nHM_>gSU*N_YR;GTeT5 ziIok^z~2SJYNyES+6-&KFs5cGI}9Nhh{65W02GsjAK!dMc*#zit7=?dv{9Ja^srFn zEAK(Dnq3Yio^|+ewqE2=QRX=Z#vFQMe^`Mrq&=w4pI?ila=2J{uCo<^Ri%h*G}khe_;7c>(pL0*uP%+hP_eH81iwN zpO(4)Cnb**Pm@hm7v7?RfYy5Y0mX8JX_#}-$xDT6&d0dJ3T?S`GE5t;W`iDK=8|53K3wAaz2Y#ay1xo^K3 z+WGkCsa5#Ss5SvxrMVHIqC6yChC;U&gXOaSlQ5n}E(eom>H9nV**dS7Ec;+`qwZ=! ztTpG+Tc+x+dO_{E6@~3V=apVp&K*J2 z+_a>!QkS&s9<%n8?S^+giEY#TL-K;fM*Z{k#Gx<5`;NlQgmpwzGsV-~ba}@Kg^!uO ze0Q08;%aJNbEo8t$mCo%^4(m!reVt}dsSxn!eQWq=UuUJ7kbl;tbw|qukB&6Nj2>P zR(dxk7=mmFpwt$q{Un}!cTv`nf(7#vz_`t!Ju1K-B6J`)Au@j>j(ZMoLxm$(iZ zm&IjGj*$46i}ot7rlYGUm2GE6X}0*k*B(Dq_JmC5m zCey>8n*?sVH-kCj%RA7|Qma*3q!ez;v2~luLZmT^+_mRRMR|ccdwxkRE@y?q z8<~lodhTeg^|BZ!7>pRRH*f2))<#?%8Z#F%r`mt=T>Oultzt~9@d}TnZ3cCALjZU3 zCCYPTHdFge5o_?*O`K&yXVBQpmJ##t)upWJ@g-t?5FK2{n%Y!rx+_f`)fPH&QM?w9 z8pbS-P6g{Li#k9Y_mSO)dXH%L=X2vq(L3=siioi#DMem49S(6jk+dae7kf4qk0;Be zAeJ`ONY=T^sb_yB1J+E5PBdXiS%9s0qIggAav=WNeP{BgNmPf@9&;{pL_3f z&fe#I>yNCJWUg7p7;DTi#&68IqBld5$R+cVm{fZ-(GnYjb4O)!PkF)J`;;U9J zJ#2%@e760tyPZnVS+>Mbn`pB}EQX!8!XUb%LbpzfRcyG?V`U^Pf_)MDMb@yk(uFMcnyH9t4i>U-B^MOGn z^EtCbPX@CiWMCLXyp#1oFN`Izn)tY z4%QeiZI@V(dJg@G?PNdwWwy_)^!89rhM}4j_O}MSP~%0k zdN#pIj&CS_30qs_DP?kJZTWT;@6tHB$dj++GAB5#m(3daSgt9hwkI7**$yA6oY$<7 z1YL;|OYk?eleY^S4tm6^+!U?HAmjT`I1Kuhy4{m~t7Dx@>!Db&!i~DI^hFIUI8sTw z1C1-)ukL7);1c!fEwfxU$5Pvf#A$G7~TQ+2t^;brm^4 zXh1J4JIhT^JbH8g?@K18VzMgTez_k9Ps3*eb+E*U_eR1@72_~-g9|a*_b4H?CN;+7 z3RsjId6#rt45A**HiMS%>S6gRw6I%q^kd>A<7Y^;?a7FOs}k>yW3!^qFP zSJ{xkqN4|`0!O5Tq8q>SUk=yOcl0!uiK^SvF`~IkhPh4{ylHdRbm7d2=@N8V zP15qZd?D0G!PdS%S!R06%7u_W>yLHWek~4j!!Ggfld~kvbQlm%2Nn)?EiU;O{Vnui zu_1Az5E4KgwYc(#wCM}uuF=v32|xA8kjxqSA%~l8VPfJYjW$HyGPp~wSNP5n|8^yr zV2-PLO7fVphKIj?Sef&ee)aCf8kx4d@!~*bUTi0a*@Ky)#~$wEw?mg&UEjZh zynkEC?s>_?NI=OgqC9tY5uI15Ail~%w9KF`w2r(zlf}$L&INFBeds_8DE9?QMRx9@&uvLl#H!+K4y^>w(muH%cQ20 zT&aq9P;1VOFhedxSg3!P9>y&I=CFO%p%9^V$7W9RZ0w!PH2F~>*Qzi>HKI1zi|Q3l zODSz|GdwvXwW)W~N9(2#zrSkA`&jZ`gQTg`-t^f4k_;{H12r3#my^T+w+8s} zJ?J-u8=vm}Wb#ciQFnzgpqlut`atuVy^xt49hPxTnR*+A@$EQEvvj(LFbK$bkqq zS+$h?N@dn}Rxk_v`r5D|_1@cB6JdEi?zis&>TTn|TycH%z&H<;!~vk$LI8!qx17pY zA$!fK3{ahqX`QoC7Bqtu42zfio6k`OhPFixP(yQkODrFlV#3HRWzd!_%q(-KX3%4D zhv#DB>NY$WOn2X~sV`>8Um4r;=_+b_Z^i7X--LzP)h8L!UDN)nsu%>oOyXf`$0ghaSj{y zXkf^ayu@}Cgd}Fg4)YU%(L{)*O7sXVS_wu*|XR;v;1P2{8Da%!YewCc(VNI=Z6>wV2Re)jz)0)F@d z(k7Ln|AWxQP0(7E3kz*Lc7ec#wzuuMg{ua=Y%?21q1nQFa}%X>xg_PQ^y@NM*h$%` zdgHrp?ip$>oeS80Nq0P#Z1wPnWs#X-6qwGM`NOwo@BVzH zfV1uzeQ3!>sUI$(R@JoOG2>QSY-)BOgY+)TtK4Vr8CZe|)@>Bg1#myUDoc~+MbyE4 z+kF&%UBbvI_3f92nvH((dTu|fm$xZwr7(VPo4vNHz;%7vohswnL+1oG7n1*~+0~+O z^`nVQg}i9t9+(zb7JTZdfl2Y$Hv%JIBTk+M%2e9KDpR3lRD+OF-cvOtDN}5_haqA; ztPiu@*ahDw3|w!ri(}$DMaqj2+Xb+rB<{cx9Z9Fy+^->a6ah@TRu@s~k5Pd-Hj&=EN*H%++<2)zx zc?Ub%=>AIMW>aX-28BLXZ78qRX@r#a^j~Ggcntx=^WJ;Q+aLl{1@F75$7zo*WD<&@ zh{9NJ`5NibENk>NOiB3E=30bND{4I3&aZQ4;hp;Gcsj+Ru-$&7f`_+qKt+-yHI?x_ ztzMYP92VI>maqi;HqxiOlAZl*YGh{8Ir@r+j@J1N=MEn#dgI4&Ms0%NNql=) z>(#y18~hi$*L^*D%u}S+GD}fMdJxZ*z5>!aF|6)!C}5t%stP~v&G1K7&C|L-)R)FG z1-7zOq%_cV1odK1KVfz>`;p1~9)-NoQNKh&HKm?~Qw_<_*w_ zFP*VEKc1PgZ^>#v7~Z20zv2f#nDW35cGo$~YW>^v%QI<+PFN%XooAIEvNx>=6h4!s zO)>}s3fJ$8tGG#?ip(sIgn`{PNSffOlR<%!xwBAz#(So#M<;G1zbgJ}a(I{_1`Uzk zZPH+{;q4hN0f`3Q8m@T98S52Gu*(gsPMrW&5%dF&++KDNpTncr^EeY{m>xgy>A14T zu^In|l3++f;NAlTBrm6aUVbt?FZsbm+H1x6UgT<`2`VPD$ex##Vyod&Q%PHg?#9B~ zg>cQ=<|^CTnl<=!Vcx}^wMFH7L4DKd&p<*1)lAz>-G!$-$)%=O#GrsVwxQLr)GIm5 zkcZS$0G066+cmTc_0bAV7yR1Fw?YH!V(!X*)U^ptD_bV?_$xTdA3L?=tl z%mAYu2Xxt|jF6;%MxAGAs24;51 zbUbZe%Jz{=sjk|8aQ;!KUEkIX5WH8B5I}qX7kAX*tDBFOiJHvuN66>^n}y&UVxH0S zR*i5YY@FA$yjn`2W=}MWY&=%Ir#ds_LaAfs&1*`9i(gkN_MYIx8R|?Fy8woH*5X4BIw}@iFeb zHFJL!9bBY|sya;GS`mfsh_z9ej8*{1^J!-IjPKJZ#eJo~=Zl8H*KnJJ3pFVX?4ilTwGef{bjB- z2?S6-oqPFyr+oFP+d2!5Dz4? zB%XC#8KAq<^(b|FGdRO#US2f=X*!mhw{f{WiB<9AObTn_v`I!Born`W=e$gKaLhP> ze~y$DrUr!PUV9_``97t&D#d|=qBo$C}M*JP7eyBvy!aV>Z`b8O2 zMA{R8^@ay;T1_q8U)&-}Z%4DeB)0me`l4aSjaJ)=yaILe1naK-2d#6l` zx0eiZsAUXvtveojwE4}wt;{4zK&%n2a2`21#WHMRX4V+E$^|Fz!6JfN#*5==?xtuqm zqXBo zaW>yJb>e}-iAXgok9ycKs|Fo3+q#7WniW`ql)V|03UI(kF;m=axL(n-+QAqzjo6J^x2aa{qd0*QA1zaY-`vFj zDYy9K4ZYrrOySs@_MkmE|L{E2`4KIMjor>;w)jso!hCUZ`TEO9e+DgMd*VhsY1r-YrfYTsvW*2VS-*(~sg*|wuW;h}a*3F$zcyS(Nt zEaNs%;6~vA9skzFfO{)Oa(>f*rqZjMO)o_NDGQMIZyrZ-_xVlfxAJJX#-jIgq?d6z zDT`Dwehm-V_yBfW$!+Sc%So?DW zsCkBKb=pf!dew@`K=HZo6{aohhcS=XNbo8Cq{iiu9LW+Kyg9EESL6@leWYkglmk?> zdlPP~h0xKwbI5-)^-O#5nK2_5p)3+1Jv)g&7$cp}KK{3(~oji#Q`G{F>|L;T8S+d(0?eRjKnR zUbCVTB7#tkTjWowIFJyhl!V($SN1@2g!c{gW@h&R?T`M*_e9e6#NR8&lgC&8qj{`hzJ>M==D6W8!Hns&f8SIG6K?(#MDq@x zFK)fj)-noM8CvJ~pyi@QS(C9Z1^>&#AK6^@SRorkTC9dq36w+Rb$+I<6p>`!Tx>WE zG?b349+iqg-nW(#@qQl|K4Jc+B^N%m#W=1 z3;tGjYzx36Cq?URsNe9}<(;fhd|VqVpT39>c?=-fw2#`C)pb8RWlGCUkg>P7jNjc{ zKA>Xss;n!MZ7ltI@K-;tdwXu9qBWYCxgg*2wo&#vPT^Jb+0ff7e$J7(h%7H$QHmQwOs4Oh-t~&H34(>aD3_M^yTQzorGETB)(?m5|WxfG7=G)MyMzA%$ zN%Kw9dL%)-WR85Ir~R9QYMDBaFh2m-u2*1O8M|-?tBCI0)53~=V+Jd^$=unh_UvZN zEfrGcEGvT;OS!={W9I~)el&k|!~PEWPdUFY?rL{#&bwgGZD@b*X|SBoVzCYn6M~m< zFkfgR1YbdR1y^nPlCxsWmbzzOkT`UXZY>yb2I8T&o!?Rt*t!oiTIJ)x?PnXFWr=rl z!oHf30-%@uJC(kX@(gaCQhM}2*QCo#0aDS2P*WbZ1h!-%G7$_V& zHcqwQ$X26AnvKN6>*Dd*_~l|zekgpvCDS?Zo_M8oY%Sxk{5aGk9cn8A@C36A{U?a3 zlJC{}0J+s0=p2vGMRN2L4hLedHy?hgLTh0eqw6~cC?{r1)a--g|-J^MND ze)@<|K>|{B9X_ZP9D0^jS-WWQ>()?Gm4u*>TZZAq9bc(Gs`@Mw;6||M|PxW-H?_>!~FePa=TYrAMccvtm9H<0f<%Te-K}<{2O&s<~Zt>6|1L z)r zo8S*n14O!spZ&U*?F{2%(^tI9eN8bmuW_*L;ktalkl6s&D;xV}wAaxRz%OGf$GMX^?8jR@Cau(y%o(&qNKl_GzCk+0ub&&Rp9n6~x$)->7-qDk?!(GRWK<#}Ut17>mzs=~s&yqK2@ z3e#&#wz%4iA`paSfkKGVTU$sbA!9*eA85#M4JXDZ6*_fmIe-hzX(CkFHab4k&8rC+ z(x1_?e37$x$9>=5eBT5bd8BMhX4(&DDC!?2ep|+`0W4=Hbttz9l(O?r5vJG`Zz77}p{CPMo+h22##mb>45#WAtt{0MUMz!X?_c zGAW%)Vobk`ajF)gT6_QU!Lt0tb zVN`|p)y6IaR;+hU0ByTn+ogTtt~fT8p0}K< z4A(^2c6BdnpJ%V)H7i#gzd+laK2@s}NMWWAEze?9;-Aw#l#iWuq{LRZiNy2{_mOZx zsvO6*RG#dsVM?hvi07bpWmSX+_Rrg&{Y*Q8O2r=L~xD*Hqf`2u<3bm~oegXmS?!J|13o!$Fc`RDz4Le|n{Ug8y*6UlC z5x;b8+hKet%Q+9{VSW^tQsS3qp_%xHz#mC5B^K1wUT?pnrTC{}H#hF?7Jqs7B|K>l zNO872%U|S(InLCIp{9e$O; z$m0t>6JK&h4t0aym@aZZ8qgA%8rAs~W=8j<3etFcSRY-DT@%K6}6UI?k40TWh2Umu2D14nWgwjAxKl=_LBvidt> zJD5eON8f#K5WN?8NKfG`^AIuuxBrr6v##Xui;s*^vK0{_<|Bs%DVTV^82#O}J^Wp( z0wU*OoJ~N#wvU=ue3e4KSW1;m{E*E3iWOX8(E-_kRY3}NXhUg~uJAYHGfVwHBA?(l z7chPS(wJDb)x}1=iq)&tdJM!5&y{1~S-yPldhoAdLe68NLZ1_pxaq69xEbM*ve~^- zrXO*k)aq zMg#nA@Qz&5j2@16;eZw5%nd~5^D?gU7y`NpDX7tF+JP^dVluPkFXi!W2Uud#JT=q| zE7TBUPMPWgjk+7lN_eduPph7;wOlcJO8XTfRvM&<4vh1Yp}f?dP{lr`clIG(Jg2Pf zaarzo9|gv%xeQlo6=hgmY24K*)BkcnY!%9VS~6FVaoaLN9s41%t{sWLfj4PneHATi zA|9kwItUfw|6+nN*nk_?py;Z;zP{b-rSXg$JZXvl)Smq`@DyXorAYFyb?Odw_F;}? znWqF)sF|v%!L&U;m4^UlQ>eu=h1RveFDdI1p`5voXwM4aQE!G#`hn~5bbn39&Vo+V zuVn7NYK1=plO*a|uh4x7iZrN$VpeZ)2^}r2`IdH3^XzzL;Aa$x5wI%^NIO~nit<(= zt$X?+`mN>g-1#hL3fi|35pm{ix6Ayl#UNOi#g%(VI5rEv>$g>lzSTZ*yS6+$U0q?y znU#IJ7jkmqs=Y5PTHNv9^a6yu688q+2!}-x2VH=Ivp8*Ksauv|&3Z{g@Yq1xd%$Y- zihf~?J#s5{3>$UU1#V;jJ}1P>xeb{kESAdcaTxOZ__hY`JTw&5*V!+X6Pn7j_s!P0 z5->PtKU4H_Ve`3%;VuNgc8!!>q;}OIFHPEvR|mWpw766dj4N`k&E) z@_K!ngBLUP(_E4Bl4*kU+skv<`S3Wh z5==#UPFH|Qwzea}X2y3*iiZcJrO%h#`<|(;PlRjM!3qJu?X1u^(d#~NrY&`QHpL&P zimYmB<49$Croc5d^)Y{>+f%bWp7Pe4zHOSbQZY0HL?d!4oeSLkg4E2Zc6SD6NS=!o9{%ZCeUU z5E*T3ZRd3P$Rt;^#jlAqbasZj(GWKn1tb1;^Y8#TI_58VlHN88bM^ z*a=8W%Hri)Y=Twh>Y*#>Br9sRB2WoS%4*IeXj4gEwb+@ql1pq!ZnL`!Iup?( zi`&;bPZIV?E@ai$yvmeR{aU}SEBE$hz;lFy;y+6g{1n}AHa&a@8{o*d^GSnQ5gFK} zffkPd#gzxm$}_Ixfvz=s!j6bUTQVWX&NDT}2Z3)A*{pd03Y{uVhflC_R&*#xurs$HsD7q3s^PRgq&PB#42da6zBv16&=G?-< zZZ0A!D<=Bm*T3&6T_@9)C#5X22@7u#Uui!ncuaNms_bnxVqZpPW}ioZFhs4Opdfkb zTYay2msHq#u^n1Gc)(81F1Krli!-S3s_m@aec_^|Yh4Q&CT&~YCTTzMQG*$R27Vyw z2R=HEcDsg*{>s-e%$tlk3o$StI}_71ZC61)?l58g_Ruv&*z_G{w|f}AGxsLQBsbz! zeBRimOv#${5zEyMV-*iQ*n~N*ARzQ1^B(-Q*ZS~V@w-ahA~!Ob{3RTSWnj#wqp@e6 z95_>fKp;vhG_ZHFNDH*V#c~u(2FTv0IeS*0%B|{Fr)2vgMlKZNdJuT%zgd`{O5|KB zkuyPD?q3B21Nev7?Fw@rLa~^gLnp&Zhj?`yF!#~lFfattZ2zSV;R{?>tuf$0ba29K z$ZB;uY>+3X`E-wYf-bcfQOT~LJM%i2ryTUxz4YPxp`bg$fCnD zF?C-V>dA3S1H5T9++%1eRF)L8noT=JGmpg8fLD)B)82YDRqGl63lVY3%wt!EueM?6 zbeNsa@2LBv0_spRgqd$OxLuum-)UDhtjVcf78160K3-|};FKhYl9iGBf}P|83E~pk zEJ!@JZ<5Bk+e~v#2A&>gMxz~mQ(-LX4@t=d3}v)FwTHctI@9IvSSw~B(Q4Mlv-mha zu2;^=YC043Fez&AOcq~Q(?jFa3mrB^txTSY->oGfAjNe0B{)G;me>ClHk?+MUVidTo5!4ZZgx+rY}F)`!I zJ6^7rmymq=$N@YFHB`aWC53fJQ*3U%ouM1PV{}0TnO}KWpJc#Mlh<5c0FcE|3<$^D z?2Y3Rfw6qAvP8k5XWB6R0^zAWI@ygSPjS9-)BbuX5G(fG)0CfYufB-gbPo=JUo+NZ zw^75II@~H*G*(&R;F(?G;L`_N6|spD*{%BWpxXx{kBUuW#{na z3SHrsuC>pj?2Nr5Wy&|jA3;jTqjX~B;j4Zw?WK&nTKkQiob)>{tFIn7wi@XZlnto- zzEY-GD_grjQ$r4Yr(@pBL;LyUL7x z`w_n6x<8zt0}(t7Ho$obuXv&Wq0$R5jiW!ms1(iNn=&FgH5_V+^}*uB{Z;$b{ohi` zFp?6jl#1+SU3OCmbA*O>;0yD2AIJimVInOf)roiB48iN-I(u;K(JtAXoc`=0M=PGr zaX}x?fXbkKV+;x&i%{#|K-8P9`l@{-7P4NWyu6K!7GD{+ISfEQB|aEpf)o_4k=2qEOLd&eUY*{#Dg%tJk`40B;4)Yz#}P= zF|jZ^%5aBvQU=&{z(loZ_~60w4*A!rUr9LC)X3`hr|=%5a}n3lgt3Qi4y*EaZ7kl^IGAPo0zt$)izRxk~+qsVF)e4}aiZbv_8531A zTM`qq}E*g6d8*R&z~_L&!Rn?LdbwR-gL1vz8%%^bfBEvX42{3cSaGB49d zrdqB|JQ?TAnZb%X8DeJmezINlTX%5M5IH)BJ>Uc`P1$wpkg^(olZplYtGH)LFWp^T{% zxRGl4_A^cXb2C27#0BR_(A@J!^h@LhtKp%aOZX6qXj#tfelX|c>aAgnC9cXIaoMaj zBWX$jK}az;V5aB(B~QLeqXEibSepe$T&g(;!Q66Lpb$Z0#V30JFlGlDSC-70e{AAQiS5%Qv&q(n*=P;7P(V7ULA zi&l5ZNef{;Qp7#fjv?t(No~kgWRuv_cc}pdIsQCKpMw3wgzQZpjysy6&n}`k281B% z@%9;kQz1aR__uA!%nCNqlcaR_^bN8oS}S+S!J~l)+NsT+HG0m+m4)K(7+{Q}Mx3NZ zByWRV%b8+C87~c8=m)eI&Jj%JMR0!7#_O9p@82#Hwr(_T>J?ddef`+;%Y)2f>ML=; zMnj((XxrK4!u60zIk7IdVkM+uiE>|I{nQ;67M9MnKO~)hpmhIkZDVy*)L*Y&z2dlY zXCAdGD=WLY%PZvX@6T8aJoPN-IceFxpKkkY*WGb(93DG5|a*sh`8v*aso&boeuXLDLFsny~Sn06JPh_oON;IFzn>Z$+^Dq zfARuH()!U-L*ze4Jcn$GtpDjE)w$6sFPIM*X{D&WDUCP%m8&OfOn+jaKdJk3P!q0m znlIdHd2$-CIQvXCL>Q5F6H(JrZS+4(0761IK?2B6;U1_fm zV(-5=dpZP~Ze2m6&;PN@!?iA(B94}pzr~+Dsue%U1SS>w?T){? z)QV2k%YB709*^h8@&D{OcxK=v3<3FbE0Jy@GS#V_+)X=f6uS_^w;k@ zApF<6jeATqB6|Sm_k9MvOZJnrAG{myZl-=8Z->>W-;aUUqYNEt*uP&3xCZ~=!3Xat z(Kthg)$h}B{iUCLs{cyS_{H!0nz_4RkJX=?tO6nlKkNKN@q?lDU&E&!1Ccd9=5~P- zT7`*Rl3hK2+)};jKn?ki=9l0l13&A$D)N)4VImQhc_mw^-&^Ro|C8|CV|Oo|bktz` zC)+H_}XsFRORWcAdk>BmUDBB^H2s?pto zC-xDM+iv4ekRE)I7wu`O+g*p1a~%)){_mVq1k%O-wdQURJVhPo6D zEgf91YosZEJ?l;RQEq_wEtLgGG4OB?L)bmr)gkvwPkpQnIvVq92-=ePMpasWP>p^f zUFTxF9eVzh&(?;_y&uot_fI1EZ_4-oR$S{J{X;8|tNm)`>QAju|MBXHQmlW3Ea^3b z_!F0w^8JYiK9R>x+U544p~PRK$)Rg0=r?3f8Fdt%A*H>}G?Ly1XL|P3si)UT(1OqY z7V@`}A?Cdm1BO1k>(<8!q^Z|PdVxNqudi=?kFdB-Jlro_kvee|;xbCM(6)gGJ6fjI z-dfUu2i}*D+m2f$ZRa$DLFmu)!8EdCzWz#oO#srjXgeGZcLyErl}P$+sg98L)4AJI z<}%*4G1qc%BrRUuR1}l*ENnGR0MSt*-c7A!$%^Q86(NN=C^$UMnLUi({7G`FQHo6AnWM za5qX10XiZcl3x52FU3nz*rN0Z41A=@tNW*dCJhmDtRuyD4|;mEDoC=!_?@V6nVHPL zBtcc^r@AJ0IhiX?o#K{rKyLp*vbKWf{y{^#V;U|?ktXViwDTu^+LH|P>%JPKZi#v? zj-AZm$KCs`!|5eYl>PUP|JR#Azjy0jT98DB|6Z2Qzxei@0{`3bZOO4}G!6sA_?;s^ zF$n*~>i?Y8PbVGAhDqy5e7jFg@co)nNca8AT|Oq>|C<=vv!}z$rTKb@F_N#;_3D?I zLaOb*Z7}MY%wScwXkJ?tMg4Y1A=PQ~CR0rgPS2%JcW&n1+I ztsv|1)vAK9N8uT1FPdp6?g?{08|2D3qwVQ6dw8GPo~=H@*97{cOTd;mx8x!%DY1Pr z`)l6&>~Ylidyz}GUr}D^LyZ+>8}&p>bNLp z$g_XM5l;P=YLZ(wTbly_08kuTtKWoJ{|_5Ji8=oVF!^|t@8l_d?Mqsp4~N6)eE-N5 zZL+vWV*bTV;vE_f#)cQUaJaIEhX;Ofv2IiJ+jt)7E0|5KI&uek{zUZepLH0k_K}VJ z7E2x0q^qxgg#8#d6l_yJ5}e@nRqBr;2o8q}VLV-1N~%Q1%nYgoCcSy)j(_KG6+rHq zKRm8Ljnd*mX?=qZ0Kj_p+(m;tUFF+fE?tCd+0dLDSNJU^_kRe7{`Xfl|BIfsck&kt z=UdsK#{F)j9*_=hDrxNT`5C%w_gu2bxc^4ey&s{!`lF7y?~7Z%5%eABf0MyeIamLG z(&&PQQF6@k?>?8iPVw7xB*;mfEQIC$+ld5hBlM8Hq_w{xj3n>-nNNaCz0arDS2(CH zEDRurEw29zP@bYmF>eg9p8ovae!Mn7Hj?B{*Bf_;Oh`J9l)EqEgl0fKt{o@-ZJ6p@ zSBil9{Fe|$(ofHP?sU0)Ot@!B({i%Y+=s_I^rY*w!p^dfVsEx=j!E<5cvA3h=P~($ z^phSO7f5h^PM3U@=Xm1#7Ov?l5;@*4b7WWS5wTD;_TtFmxJd1-3$I8IJL#(4-|m=# z&s@N`mW@y-Jy>9`E*Te+N*d?!@#Hd1Zf>42ufuVniDB3lRLl(`6j~-$%4Bk zm6@_RVR3?^UNWKzjQs)#A&2=}bs4n#`+0r=RRKS0N$dSSN7s+UNOulr%5;1hfY?9- zN;@t9N@%y&s(c7<$U#G{LG1*Qlqd;eAh5P*8at10I{VWGcy^)e{`V<=M;Kvf9ePkb ze%=59#E}u0tR~(|6=GxO=3chf#ouZ{Cc=Gwgn~&UI-C7{L*rSSJ=1c@02j&SwXggO zyM3#+qYfJFZjpxq(AWXRMSIpR0+VEtiiQkVP{lsfXSqn;z!QlY+J7nF){A23b05%& zWQap_OLN6jcnk6cJ%;3{pi{%QrJ40pha}o*qI(lypqU}tnRN-qZiFQ`dtgW1Q(}5L z*}c9wFVXb62~qH<65nC`w7t=1Z&%A_wT~kYWxx~Awd;o(@tUD(w-i`{3%KpE9&YUP zgR@l7o<8WnI0r*XufKoL?#c7-I=X(O z%a*G1>Je$}BtsnZ$ShPawMMRDYkWaw0u!Sz#ocmbwy&!pGv?h%|I~QgSah>(v+i){ zz~V5x*RI(#U@K$+B<(+uDk*0F#?ftXawtpAW@XWcJ2B6|_9SX|-@5m^&A6d;v=U`J z;G(E~C+G1Un67gYMWDM0O4<^e-(vw307)~YXsu#k&b_+}n1usAXx3WG?oOY!_Vq;l zv3wPeZ9<{vlvwrPG?xD>a!=RGOlGmevswv8D6+}ilib38R_&7C80^Q+bz;X<12AtF zif8-T?0@naeerv5?uztnHDFSLV%bCJp+bl@+WiUFg@U;m+O<{vbsr3O=Vy+rs4U;i zM$j%_6|8A#j*~aGB%U+NSU(AuWSpQ9yuO6&FcZ~H4YZTDbn_`a>VB+whh=6jM!9Ht z!8WKX$j9MFgQsYyziWvEh{2h9(w3gcsw44u27(aYj+%4=i z-=NjT`mq3URBChIHeR5wt>};BFoWzvU>+|;r$Bc#bWcrB)iur`>0a20YoYo4?S|Pg z5Y|!rNO*Ub2{i4SeX!qP>9!VDqQit*Ngf+UCscdr1a8DnCW@B9^u5%fV_dB0@hCTR zAS<}m-T!c@QYDmXtol}6%^pTImAI1?4{BOcFys|U9|7B#JW3)i5=}6 zqTRM72uB3Wahs%r+xcSuMDnBWXx+H9z#_y}P?TLM$uS0cI6E;?FvTji`pKcFWtlw3 zslcFAniPhY+DRMnw%B&`^jh5(pxf#v_J&OF*VKe7zXGvxOJw zcOmo@ftmKpoo3Dnsph-2VvCy+{7dCG)*E@dvuvTrqGs(Tf8t8ry47-jSl_W2*OzIf zYue3|g4q){5Vf_^Y7k+k`FlI(zI>PQqgSkz^boM8J$OwvFn)uP4$8uT`k+D-oJSpO zrSaOY;SMW^y(O^}G;zz|i>v!afo}CS_FMRXij_hYH$sZWOr~~b zOuJIL$9D4JcHP`Tu!s_-hz!&z6x6SJui~;C6^K2KW(Ln#SYtXQbV!m!7nEU z$Z@->u#-*ypSew`AN}s5ZQ%?&h^nS|)xZjlE66~g?rly>&O|l-8vwOcLe1~XB z_0UvW6eMWp#Uv#q{li46AZ?N2v(|L2FHZ+Xb>UUhy{pGfk`8Wnl6Ol&aWqI)6`d~? z>6cma+S7BF8N{ba*|wb@%p3VVmj-_?FC-*nkAVZkN#@d*Oj7x~lp7QzF>Z-qxJEd! zmyT=Z5Z*jKog96?+?(TH{y&5U=y*P7Tw#{C8Yy?B6|m{ZNIkK)Xx<2uc7P!b)Sd+E z{IK{Wk1alnPp?Tsc3&KDy7%sc;9*_IBLhu;E_NBOO+R*}p774zc*-c^Y+UKNoCK<< z7M=acuV->OZgX9<;_h~`k))sMC8_4ho^&MK3$wiZb8L^f{V$WQHHT)0NsqVRZ-I;t zkN<5zB=g^~yzD+j*BcsJQawAKcWg&g$lMm|MT+oaLR_h-Tk9e^|wn&b z{e>yX0JXa0jd+QToo`<2N+#g`{9<`w958e#sN>#Hjn2k#JxnXUhNi<)5tqcQ8_ymk zWxUEs-gc3`X%bn@?BXvjM&QV*v~TavAC$h~I3%&pu+_J@Ji-PD3qT#oiS-4M-96ks zO<<}{o?Hz|5($lLv&{wp4=R4=yX~$&X!A_& z$y&V8F)t5PuP2A``LKcYa3UhoYw=6f?&i(ul^W7rb1K44^^>z%O2T7xW_!ycR?W;% znWO!sf@QwGqd8kEC<9s%8b={Ic9d_ghaX|(6571}lk#ORzGG~h>I>kqjjkPSI*+m2 z5T01RB_)I*CTpfRZW1KM0psP{T8ySS%;B*sbm9#pxQIPTd>H+P)?@pu*kN^@&9@>K zTkXEsB4X+O%#IlYm_ZLp8;uIuojv%9#ZLFwhT8TITk@y(bE}k%iw-Zl=?41jY#BJA zeDH}*%`^V4t0Rsn!EW=Owzi+0G-jC^9f}%r`bsBs#y%fjOO10wRq%CJOWo_#GnN@9 zew$AAaO}<(T;#1;sgVRNB#O*n&_Tj~I7jl~^ZpLSKv?l=zJR$7*z1+CG3|97Eh zs@JZfqz}2;BSx6>vssSoBb&_jzq_d+w)jQ+L|aFBC$fgO3LU7Jy5#3)T2<|plocbgA}Lf? zzL{SAt|w|| zEbNe9t6fer(W98`|hHqeWe15+k{)g*S}rWpNo|BYPC0sSI5u~#OkPP zcYucJ2^P`1$T&3!`~St>dj~bWeet3P8!8GaBGRQxmm(b^BE3oPp!6O(gsRe| zcc~F+(xnp!pmYd?-b-j9gerud05^KhJ?H#>_s+X--pu>w&6{yB-?q!zYp=c5XRW;# zaz6>`(%IB)aka)^(s$FFHUU;OZufiTGMFNL<=NS<6 zJIDPMf|ZfV$psN8FcOOG;esF!BrsrJFROKkVZLQT(!yX?*kRA5@ujRmd9|ab*jMRv z{8C>LprwpqK_+b?R4%3Kdfy8*NG67o^u5Cz4Gwi9dYZk?IjICx5*ni@ zy+P#-*!G&;7U`pT4~Rh4Nq{8!n^}4?tSAsWK@HuOf}A(&=v&V=yDk=MpDseeTqoOi z^IE2SHnv8k;r!gynXViA@Rh5ss3BhTm_2H%-XQW}S8F^g;X)blUI*fVb^+cg>Y>w^|%Wzk-b%^ zQ;TS6x9&wmfv*a^f=J;VNzwV^1_oB}2tdpPA*3|;mAD+v5@wRF)PnG_%W$5bg=~f| zoL^<)9;GI*K~#FZ)hmC7k_wzr?pT1VCvCnjO0{jFC!TBB7^iL^b?*9c(``7VC&yUyLMu!b~O^hyUVNN~VYE@-?E6!_geK+EZt zNsAuS0(=xW9e9{y7VPG!+F*A)=eBOgk18|Zz?z<*sOJMFNd2=32PN3Npw;f4&3-oJ z(_YE8$3QdM%g#sB7t7ZhdWxS{?Lx>0gn{!tk=2^1D{h0PXQ(m>5~W!)jfR45nLbR>vw$PNY> z8m|W_07h7G$x1@v!&#wXL@#!Z&O30@SB2m}p>sZ73&0wen5nl#ez*z4Q(=XXr&Rv+ zn#G~SFaS6!VHc>`ms>xd?Ddgqt;TdKlk6j2-YH4)UN)TXKy_=S0zBGEyECj;7-Lj- zBLhD*0b4nMxRalyqML5kh}lVESo3jf#!D=t+n5PQpLNl2jInse>MhG zqBF}Y<{`-&3q5fNolL1#TygCpZj=ZDl&Pj_s;YvKk^B<@5VF5cczeVCTS?RUT3j=2 zgUAe+ZxKPaTl4=si`>t^0Q=K?CDTwmfzKubfXN{7ddZ4bK6cGw9k|bCjl$ar=}yb) z9UoZX$y5&%=i@)(vtzjOav&59HPGInIQPOb~PYpr#f|lysFfVVjJtR_qBrWeZ zyXssf*Cxbe%q{J!dI`_+cvC6>ph| zFID^Lq~^K!n*>@~u#oF2qTsN={2LB`E_I8uO25?$vI-ycVb$nxYJqjEC%Sro0@r+#bB!E_PP!pg zRT5@&-A=P5T<79Y`(TnjHdSy*W?tOGbgzM1fs*1>x`P4b#hk5gSCU|dY?G{P4_kz1 zqf$AU`MdBvf@Eq~N$6xFRsBFfQ+W;U$wC2ab4GLJsnRjX3B{FHtf#D@2oX5kn`u1D z8+tmfecHA;*z8aBXJ1b0eyTLlP7O1yHn2L|WAer!K(U23x@ziH9R^lb6ZcYE5S@RjK23O)8XfpXS>QL2Mb$$Ta|viY@8W&B?3wphYH1F4jCp{YeVqNyiCh# zyICu?%gs)4KqL38N2a6k+vytMBp)8Q5*I7xo-Gr>c!TCJASW$jN{@}W@shQB%Grlk zC@WHqICPK;_2agHkfo|s2I!giAghxEi_`Yp zPF!vNW@ZF2UJ}1RviX0y&l8w5GfkV#ceW%hTFl*PsnfSVt}xEWVR5>lvEaW0@zYE9 zu%uTyoa35L$;`|N#5vNQd0Txt%Kg#W+Zj7vP=KOEPd7e;x%H(z3&3$o%|?JO_5sLj zwUTP5-R+Shj;+s;9EStD@C7!dR=^Y1EKguTi(j<^MEbaN~ z8I9IFy)Cmidb&CUr?H>|7-{f`fA2gMGbJ5seGr`PjvaqLou@8>e1uS`;4)mzCR82R z!Ahh$>Ts-{lOuZ43l~1E2+eRI*aqGf! zN50xD?~QCP#fv@It`$tG88aWlwLcvhUu3%Z4RB~ zVXNyIYJDPD4;Tbt%%HTrUxGVJ>2^Dy0raNu%zZL3o`hFL7p|^MW)DzpW+jWM&Iybw z80>m0!l#yosX?1kr*Mo=-Z4HG40^c%dODKle%YQs-HK8`*Q180{WfE(#yRQ>2Oq(# zmz9F>i$5?=A$4>Fc&V-VX`)8F`YGrLXl<9N5^&Un^By{O?M2U8k7DsUeHTYQI;j$5 zxxSt>;@Rb9CCHhI$2bO0q1A}kys4${nT?mGqsRLJ(?zqR)3x2A`mVU2cOdr8vg52& zNzZ?+OW(Z7Zik%m;1QG0Qe4h|ssgEIv&ODCp03q8EN!o5;H9->=4-_j9aw%l3wAAu z?vfL*JxV{Wpkc&@J-_IKx@@5#0X?;lygJ(yLpNBdu4zV|z9_Z3|BW)|w{Y>xE^+7f zZ_0Lc8WV`qj?BP5b#(L0mf^CjezkQ)>Cd&RkewV}HZF*r;KJ@!=0OSA0>*q9Ng^3p zVu2VXhLK6Yd&jL!vZOBp^k$yhf$2=JFLYW~GmU;uN07J)FhZJ?4 z!Q%?bB;RDk#AlmSXwc z!-Z?BE64JM1w?{oIR(CFccFky@bN4T^gRf2QKY6h`4wcBVklv_QzI>?Z$3?_*K~~WhnK*4b)E=^&F2VyXBi58Uy8HgJPfBl_cgJK|D~v4u2pTQX ztw>VL2XWy^|E{8}_iA9m^Oi|~p%G5eX{NsR`!<7apV;KVfK@j%u6f6sh1}h7Wauj1 zbo$Aq!TE^adGY(f)^v4_ocd_F!819zB7rg`kNSXMEW&x=3F@_FR9 z^JUSnV(%z*wKkR~?F{TH;`yCOJ=eqad%hR)9fbM_i}$?z@kq#59Z#*k|8{?6{Qr>5 z|ED0CUwqMW@n6olKbZv|u+nwqxo|4X^0)HG>6agiIe32V3OC*9Uuj45vU;d!RF6Sx?S>SSYDRMB3BeV6mmodQc8PWODa+a>UXkQ2ro>1D#kZT zF0Z@HS3{g9cab0V@1J%Xhgl_8w1b}nN{R+mK%b>9_?c!uzVPf)Ems}D=fqlZ5<`ZC z(WTE%*e1W+*k5Q*UF%1fWV}~vO*rmKuErmDfv&Nw-@@gtxUL>Kx?W1zTMkm)K9#ym zbp`E;oJYYx$2?+I+wEaiS^Qy^>n`?rc9o`_fA(_d_3y|ZnFx8NmPZ z%ZeL@8CBS=Fo~K02eK;pCj%R}{1YZkDYIgA%fNNJCKlx1UXQi|!`x4-oNDY%dv*hz-*EfZsW;-5%ZkzbqWR9kmz`lG-bNwJu{q;xH2+hND!13NcOCul_=ZT65@b*gYG zqE+ZBZN{e!c$4+yQDerR;N;@0>~979?w5n!S&+3KTeK)Jejuff{3uJi%x;8l)G!)$ zy1qbKjp(gkn;xdK@H0-tvxC0p1)AdYP>L$w!`3?he?*dq<3TnA)R8=G8q zh(0H@EPF0T$qiz z(sNConQ%jq7$~IkK85>Q+Nm#squOorrN*%l_vsI{{lae9)$Lf;f+^R|(s{?$%&Fbr zt#5WKXjY{J<L#&ZSSg4w}17 z6!}+AJV=X-0By}RyY*|g^KHzl@k7)%OJ_h>YWIz45wlH8&F9-bU6Ocv!?mvyvRO3A zSJ$FHQ?s39(%QfmIAeY2C!%Tum%9q@1F1y~y80SrP^oRlTN0T%WR{yW8qct>O*UuL zFO;dImt}AXI>h(SK#hzO(>H7Zs7LcvC}P-Z*XE6a%eXystu%%Qx_~_Ew5l(+4SmiYO9rh*={!*p8v{G4{Heh)J=d#W%Qnoqbc5_m7yheScM$Z?EdlP0k zQhGEm?tyYVg{e1LDZ>g~jSXvSO3U_2PWIM-Y+IBKUfihnmroEpv-(;0Pp?!LQl!6?>1E!D1U1@RMZ0I>*{Yj6flQp*cAX$K)@7d+jcj(VkjZ@UFZyu6* zS4;b&HrHqlb^#4Bg01FSyX}?;S!UPImBy@w5W1drwvTLog5!a} z!Vo2k%@#51&drLR?*!8P2^dr&G(dAsF~DDl7C9zUaxqH$|RzXbe^ zbkBiG>z!;Y34{x^+aPu0Xc`bk?f2r$X_Q_Gu2V1vMcG2iQ2m#w#0c>wM|bZV3w%$( zTeYSWo5Nf%V{dI*pP%_-9{RuytNNp9@q?dXMH}w&jb&QO=y@u)k&3W_xfPta`)2G& zi%UXgod3iW%lw&fQY5W7XX=q%c15|Z;DX<|mMO0=PxDWo4NqgC=;DdKAF1=7f~-qV zWsZb%lzdEG4V^9rc}78_X|sFFipFk>>S312)8&wcHWQKElx8c**S;@A57!e$v553; z_;&nu2HZAf!y#bnaN4iy5+>r=6jVJdS&vF-G99FstA%y2?!boB(k;VEcKgYE2SixT zuX|Liou;y|3<&jEZR!mAI_7wIik#}A_ty77i%C1vZ@xQ;{Ol&QzLcozXCG*3sF_Z| zTEvc*_tOzB#LIOZtM1y~LhXlL5s0pj%9WkS7cB|?31UI=_@T4ZVMsp_;7gv0gxJcw^2*kiPky@)EnbcfEk$AEP! zE~ZmMlG@uhGzOUM=(U-`LI+K*FUYF08r`)RUq*s9dUZ9M&TqI)Jsq4QNkt7UX5te> z8S#yWxUxi1rH+tOhQW$x0D|C&=dd$Fhd7o%O8in*rUWrcPGe;sJcMeFTeeN9@#VYB zI@I-6v56mh{&GdQCW`1V4nnmP0kA2T-UnIr@`W3Q`!j~SdF4w6oRd$` z+Yh?@{8;qqy|G>EvQjcD_%wFf7yh>FJwhBao_pY^8S7e!au}GHLvHd-ezPL6kL3xxLq2!;Xr)liYD`IJ zl*{AxWpj}jO$Eh|J}%Num-Qllo5%GZ)x!MxivI}bT0EyW*Vp~R@86hWAvA2SkihiU zzd%h-=agR;G!K`RXk?E|vh)3$Hr(xf$?4{V-qEQ+gF-RcsI5dNWClL*1$KhUR=b2L zzF*-^%ekbi6FR^sJXdX9_Eguza_Xmuk?Y=#g}_U4;Z+u&iCd)CKvaNbDsH*hCR$|w zOuVBNNxa_av*o&t7F-iobBfoLtw`7{#JRH5*PFGQ+Vl@B_%>2Vg)cjk$Ivb!B-E2} zHF-~AvXX6wR|_9F6sNrzZTLalHIUVFwJ;OzKguz*^uf2`{A+REw~xT=<}}u>-O`wM zmO#_KTe{712jP-)L#+~rFqWzS__K>q;8T%|g;~O!+wOr5oTO@jVebbe+as?6SA$ct z7aIt}_FNI7vt9!+TDhu+-k-3fq%5eB=3&}%%{JKxr0odykqLV2W5x`1_h`jj_aeuv z3#c|4Tu(f?K0v{>gG`SH?l0|=3VUq7Uchmu-nPzG2>ap*{7u;3guW=cBdqj`=)~+H z8y>ml+rAV4#~W@F-SSlD^a#tsq0Q6!b%X?HMQS)*+4qbIZZdl6UhdA&yM z)JBmuna4Zy@}ls1#2>2(X9LaRA_3hVFNhI$=ze@W5fqnPrNF1Tb@~40RMDi#QJDayhp*@>#Zo`eLR1Jo_;2Tvgi*MKwEPNiP{&t$HHC zZrbfJd0US5$S*1)<361($10-z1d#9bVah& z{{+dZ8!R}J&VLMhC%oKtZ`C4!X1)_0@0!FzMK8K(9nd?o25AspzS%R-#{!Jqymg

y#Hwv#Thi=A9i_sPSBe@KGfP(w*5rHr1pPK z--NtYu*8LlzSy7Kb(9YUgO_URVymIDnlVm#K~*yCtDISV4a10MtR>gVfSXDy!r|1j zA-Rci`@^;PbT+f))aoraL7qE& z-PfOUYZp6caC=fn`#k$7E2hB8j#>m(z|WgYGf2|%DLtM>yAgfvyzp?L1tS~4Ma?K= z&x{GgX1f63jQm>Z=1z}$l*lI-9$dTT5;mIeW|{4OaqG<8@I{5Wy#@pA#Q8oc)#5QR zJV#*0Lo{i&m8vg!-aN`yJ!LK=QEznlmWgn^MAjw(7I?!{zOa^cq|(IpK|9qa5hpT& zRYSLcTLRlN@gvfquH7!(82dphEjCK}x-+o?1{ufl)J;BBR)J_*Q0f&0S60Y_Khi3F_Lj43ZE-)d#F z;jqoVp~g^UnSlM+@_QV$Qxle1(*OLHY$=K6SDV}UeS)i>ayR21^a0is4z>^Iy8Pq% zBT()I9Xgk$`kz8|TibgmV_gu5(kEu?kx@O-toeRil%8w@#MJ{-a?G`6mKvm1dq~*e zPiB{giriA@;zP9a1?WH&OWjCkAdb*wA}c^LC^a||{#py#{wm4s2^eE&_4dtQ$xamU(b^^)H=O`$I@k6j};jFKMY zbGTTP6ln2O<%&utZB2vgvE-;aR4D&e8m|T6EhaJ^g=y)G(UWf@!MA$YG_w0PWqA+K z$9lDr%1avBHdB~OZ`=__Q9VZGNzo4(sAL@lP~w~^C@dD4u>^>_ukzU&vN5*nj6c0B zndPBw%qZ5lJJd_|nbVf9U$Y$zQ_AO;+bIXl2O8xPt#@r_{ZqBX@4`h>bF&*GfFBPR zq1l#ut!aOYmb}2apRTJTwE%06B`_~gWUqRdctC|^F1YC(78B0eeUm5z>%R4V;>nYZaVe>AOxPizd8 zh%1vyx&S>74=}ZRTb&T~1~Z9L{LK`<8Rmd|?b83(nlbVN*u)c>{I9xy^Uwz~LhHXp zAzlK8ULJG(x+VntB@F)cfvC+^U65PE1Lp8fv*4HXW|dR#zy9-WLY_Z2H8E*q=Tr4B zucT5Lem$89nZJ>#siE;n9K?s;htBx$Hcfc?ze=1znN>b+JwKviV`IB+{PEWlTXIh- z=W_jO7W@u*R5x9q1wJ&3@C(bo>N$cuU{;JvNO(Dr{+y`s;jbqn+*^W+cV6Q|zRr!q z{#E|3E;8NcUcd6+_iXw9nmPX}mzeTK=HFw7{~#~ONPv?0LBvCMieCf?CioYjeiy7j zc=!KY%CDMf1pZpL|J4jpo5z2uO#fVK8> z>p@;n=>J6nY2E;EKd;`pbt~}9>z@kF#Q6TKZ-ih13c~pBH~mxSIZY>-JHhWN&qp1m zzP$zGxc~VwQ0^~<@1I)FHKZlk+xLPEk*(-vGnvGT9C zYFP1{Wm3l;)Yi`7oeQf0CY+Tjm7 zg<#cLyX!RB#Cl?DQr!M0gp>!q(VOWVyL)L6j)1jXp@r4l3Kl-MJ<5rY#HYp(;=6|K zUyj*~znbFSsO-^hnU$uUQAjU5hLe*Pe0yUl_>fz{V4&S*Vu|U@9q?hq_kwRbM7-c` zX0uA0$=ab%Y(bOkZGK065v__Lfh{mv6m9Q^j>~(U6w$E4E96I zzqEy`PsPMC@Z#s*wI6h%t;S8B(7i4yYyKxjLkLO&{oZFd zfg->Yub!GT6R6B2=gPZ3Cn~sT>(L!$Llp2IM(z$4UzWRmI=wl^8#N!wQbN<=>iPC_c=Gi@Vx*Evg zyXQpK)dIP90=K{p|BNaAP-|E!klZPz%y6(c7GT{;)!uVq%lC&2lHZJ7Q%iFr6BCwU&1oX#XB6CSpI_-doep^93O|jZ2dbF+r*Y3=_sgg= zDz+U3%(*rb9$Xx}y#3OlS8fion|fmFucF$31sE-qGlbNMQ!$(Wc<_ac;kw?EsrL7c z%2?;ol@&ehma9VZURNdTSgMi55th|9>cp0$UeCM0-vVw$j$FMhRIHG{y%XoHIPUbK z=v?4mqXyu)`GJcbHPv{?>3_zYa@RZBMn}-WM|@>-w>SHQLxkT-^C-csJ~&f4CurZ^ z=$9x&(^)p1SY0?{GA%hGVu?r@t`R&`mH%v)W#>!d8e_?A4N{GgpKliyu-p_1ivQ9n zKZ6T9OayJdCqH%Qb6De1U^O?6I(eWiT(t>0kYI@%2DWsQ1K@8ItiqFuRn`Oc#xoI6 z>I}w?N*S;#!tpAFkS}kE+m+kNrHbuG)~?ebG(`qB7+!OVlaVGrEJkaMTVKWV^(T#5 zAGgVB^0*uKl&q)7xG3sCK^rC=i|O2X{@*!)mujrq1GS%5W4Q zu^6960nb07Oisgh3wX@^&GhY_Z}v@-XaC@}Z6$=7R|8gatV1!d(o;^8me4Jm;4ije z!%L+^XpMET1xnF`Jx%f|(RAg`&@AEI4W;$h%uDaK5h)@C@V7q_$Sf>S_Z8Wd%5r^w zR>0tSwrRNcJ5M<-go06ocUDRekK)O66DZ{bSUmI{Cdri-+!uU~%u|9lofiVnhO5^E z2~M2vvuklyrTS8t_mU6(JQht+*>3B5W@$85`$!>!d*DgBoXNeo zy(Nzt9DZbw!ly;`kb(*M@?9T70JSd<Z|*nUV|3-NyK^g^acjWE88iA2nK>++tdP@|_7N&Yw}v{k&dZ zXWLaqMgHPc6TDPbLV1r6uT1v&^0a&(8V2wKx$?AZUt}c0Q8?N|wz|_t16c#%DAToe zx`4N5P|H$dI+miX`v?AuZ&iz2hUzN*F@NiB3s+oNjCDD?Sv}gz*XT8_eDLlhfhy2c zaPj$rVqN-LYt#qM-}5kOP=^48TUxu0E{TYJbu&aT;HAg-h6Ckzg|dms!#5Q#;Y&$< zT5R{%x)tbtcEvh2ob)VjJ*A~61rG=@cI_D!F|JQR$U2uNt1Xtvqd4>BfNiG?Cjl6DEP$TK;!8` zh-RY`mD7R_EoPxPEs_=&TFQ6V*563!qm}a8t#yLAXG=m(K0A^=d5)Y<8lA6z{SQea z!fFboBNLd`@-dsbxgcygk++!9r`vbaN59yU>YV{v9%EU&79OiXbh(k=g0EHw8m>K^ zepk1hk@x`Iy`hi5j9U-7%x4~oW7}H4g8#Vp?Wjo(a&T6k27aB!Qs(;_;>_a4;@2yL z$$jmLY9h-LOo*?}eP}n4L2AEU-gKP3;~0fZl*M!gKi2{Va2j(wq)%!NR#@rUJCe{% zpuN29<;9u2>v2c@>w-(>WXncZcU$jRS;LC1NDnT)kf%B2$7s&WTpf3@I^mqHeB9aL zV_6cl{1r0eqB~pzm&|1&T8#ypmY~)<)~dDXk(fzd-3=tUl-;ie-g8{^{TkuMy}%ax1V9d zP=7=|4tUWn?q$((HOR<1Jwni4c!|t*2&# z$g8K<()2g!ZxnSVJk@4M!yk1lofS=w+T?apLss=RWiv0y!y9X85OWdA-5PtxNP-VeYChMoBXuSN%X#tyN3wrZuvnG&a^9KZ1be==fGCVd z%U%dXe`_+YwB%2#6_m{z&KcvVfl1#Qk^9*(ibzn;7m5}4dam*@M)98OlXq8& z3MC82C1}`M@;}}5@HHMh%-D!L3J4(@^b19+l$$TM&reNV6U(SO26v6``gd8kUPQLX zoJf?kTpp9$rUS8@JIx5l#q}POWDjV!OD>*A_!l7rXuphtR`$Hoz|KsmB;LW2BpyoOQTd`F4*Iy@<82} zmNPEs?Npa_LH`L7F$^s+)}K(gdYa|{a_S}h$NZ~<8bL`D;#}WGWcYb?{qv2 zWber^Q11JlQ1xq#i$A20cQu{J`ye{(6xf{#`F6CM_()_!d!x%&ZPb zzeBKEuGhOyzpJ^I9!Nm{NK*2Rk`QVO%mNhot=ek+th1mO3d_(f9bk~;uG(XL@b>&n zT&J`@PpVl_t30kRHgWAf%d6xO<|2baN)icv*VqEKNi?yE&xH=$F0m`!rDE^9cA+ya zt^V214Cd9Hjj;|N>hWjStH`S@R2)Ww=rt&x=jbr?wSgkToxC)XGHXlpGYqq(Nfbg# zk(`5b^+4I6El$@D_m)=8n0EPsslKhvsz(h*p?V~(M;oTrf~4~VB*GG@Ug=>6P=581 zXAH^dBTQV%?r4S-$Av2&hd%GoGu=SFF2YUu3*UGZEyzhB;(qn_c&_B(kPwfgL+Cg?p## zkPbz!HJm1%G9*!YPAnz5*716~&c$+HO7$8ur*>5PGWxy_V{Z0&Av1T914y{Kb&)64 zVj7}?Vd`Kt#E<9nf7>YM9uCC9Kym}(kay84iFKj@x+wWy<^pj8m!m;NQ-j3h0&iRx za1-{yvLyUE0W8J(TR?l)JGWjlg;Jw586#okmuA$O?N7^xjjnqV z#v*~^0xh%`EI~H{``_8K@~&LoaP~sEZV4Yz7U=Dn1%GhhtKOGLH%eN4{XI03djFmG z6R$nJ8xlw2yZ%B!2bqt9R}`XR@4rr4cS;2NvTA*O7V?syvQ)Y1iu|0dl~C6*h^Xgo zYQ9eNvS9^prs6<){!JC5@0p#vPbsH+EjpiOKVZ?Tb15HS=|R`Q>mtoeM)SP>60^L@T~b`Sg3iOE zMwPv@(|$v0#*qfe+GD4jK;^g}!1nCrh)G#qTlE_d-tdQtOqqm5l@bj-LYx*0BadBF z?A84ip5$~!l_ggj`f8cm7AbempWkqUPfel@^u`PGO%8605z zBEI8VKzj8Xr3Q$DU3_!4K+7vf12Bj~PN<|K9|h=64$w+L zE_ZEe|ILEdjd^GOtEiNm>4;Rfy|=axEx7>AhmR{Rt0tLubQ+Y&*vW|ZX8TRk>RMO_ zE}SXd)fSk-ZiT&nQg=9+~Zl+Jm+lQBtsRtHwkFJY zGsN!^>Y^woe1N7~w>mdzcRZG`d`r5%uFPhuW5`8kIQ81|2?6E4C0*|6VU%O?i#YVm`{Rd%3%Tz0lfs8%=Q4FtF zpFq{|{#=9TfJmcqc;+qwnF|^=rUu>Hax`P>dq_l@1;{W?Q4DYE?d`a(&uN-cD>uBk z?YM~IUD2blZDS@m%mr4&)Hsc&6KBQd;RKbUA|r#I#NGwX_9w;3=JUPXw^A`*6PyI? z^cVF2iG8}!2mG!==Dnk*7lzq;hG5^AYg{cGR5%cS-qBq;mbTR>}xSx*xX@Zt)(z0rA z@KO{%!$~a_A1;(Ad>KWo7GO-wE%V!L^y(iJ$+VTKf!jOw0F_S*A4l_uzL&nV_%33! zXA@Jjcjam*0xqLZBi!i29HLf`R~so4Kx^CxZJGCP^%ZI zZezp-GhLGsVZKf#-)oPf7m+1C81?y3fv-C0ZKdYO4{SJbkuXmZ5@c6FRs(K19=AU< zYveVdWl;N7dbn2eNhFMb@*Dv-2}+ztp8Hd{;RA+T4$(OGeqI52 zC59A8cm)3!G01*hrgA4KaODUz={h@956K_2u@iKVFLUjEHBn);6a_xDw7q)P?8`%= z^ypxLWfYf*vDrUt_w)2MeH7@zc^CGh%CyC*zr*Nh5>T70$ypIL3GsIi5;|%N`A|0Z#5NK(=r5 z&5RY=z!?fgVz9uS7w6UG`Ns{LAWS?)#D1<)K$S@ES->5{z(8&ndeYTr8-TUF`nM1& zdgDl?Ma<0dy42A3qlbO#=!)0DZ}_n2&6Ys#C%~#vt!gcR+Uds4WFQQJs(9Nm3D}2y zQYh`eB`?n{lP}%4Uy%r39@9yV2x{KkZz_}Lf;V28n5jWKx&hF^l3YwU6N@@$E%hN4 zonmK)#Mf#YrE)0N%oY5&ubz%%sr%%Cmgtsn&#fnK<=CdZ**zdxsT*}mWtYU}V<){) zSt(LZMtnuc64zJ9J2moG!*lm<9rJ!ZC=tKx>-NJgJ)0nBm)@=;cWw`{c2=H|8shPy z+d|aco&J^ zN2xA;N9{LW$|$~WQIrtPn#rcTFZ}pOP~-I4j<0A03QXH?ZA!9Iug7N_Mk|wR2RpIS z&Oz|Qmo(hhkA)%m*{iL&E#@b2)bjES`RS%CcZzD>L+txGS5rVvjj%{RW5;90~ z!e{OWPeY@_lGyJG?{yIgw_5ur5D7c*{5^!{6wFE~Oq9_NZij?-9_^H9w=X>#wn<80 zR@y1t_&uwA84kAV5j%XkPzP;dFTfGor14yKpJgJ6mhp(GAzV$|6V7~x3q&TJy`=*A zxuX{Uk1RlO88yTO2VXO&v5|UO<2CR9;mP7=MJtPtQ0i?m!2lwAeDawixisH={C@lE z#%(5%uNXSIyQ`h%8$WQ%oEa)8Dl%|zlzfK8UFbk7^85#}8(`am^qZo6(?kB8Ko9x&QVKTJ9A zCtpeZ#?JaA$A*o4(jI0xd6e%p`tWFnf9Y=sI^m+Url#ftx74pY2dsF2|03xbv!PMH zG#5Ab`pdtG^XHF?M{U=Q-~HE3CP%CP4cyOI{u@Qdr_}wYu3x_i{x>N6J>LJ9duN~E7+P>EStDppojQmJ{ZIjeYgd}5-4k`l+d#(&aRL$c|vaA9E~UASmoSzckG zCe+)dShqs;=|hHxx5?ZU&ZusEc=zO{-nTadM2|Q>n{|G?Zv0>M&sgADsOYm+sb2i+ zr>{64;p;dMdPp2rq*uvMZ8gCDzgD?~_j1fov=7XH@vgC)*WvyB{r^k1kkxWDnL$sc z5FYZgw?bax-76Ps(5`voN6!%?ZEt;FT_kpPcazf5nGRXvEKj`> zJehcT<81^CeqDOgZBNl&|F`o?s4Z(Rg$yw|~KMOax{TKa+eZG{ZO{pFRFyY})}J*EeHEeS`w zL7zri$Rj&(Kf^BsT1}VK3uE2l0 z^_UdS#AaFvP*aLst=?SCF~w48Uqa-cX1;_NsGvO;XrK}xp4OMFyR5W38W}ZkH9lay ze%CwZ3b4Y!7(<5~LolNY6HD@Ezik$Gw69pj`6sw3S0wd0lADsbOTBTDV+$JLN}IR~ zRMp6PHgBTHDjav+j`d5w?=E1@c~Z$Q!|A5i|E@)`1Ssm3)@o8m9>1hm6nUXSEdRRi z+Fs39Xbc^~FO64;(O1amTRNz9fW?14`x?d739gJ^xnb?xo1!+$TVpujfRLC&M%>w& zai+&Xe5R!LktzEswQ=L8{NcxFx`p=k6<1GhOX%6hRh*p6>v z1ji+$;$Kd%))X57MW(7$$nR*H878OJ=*;IISiv~DP4?_wLjbg6FJIa)yU(yWVaqJ! zXm+esDbEE#=)HK-!4+$v<`bM<23*|U+*v%x4q7)k_#>&3q|~q~SeqbDDCqrhE4+39 ztMRtP+lMwW8v^!9?S6L;&7pHISMU;AA4yOmcf4}KPsl4)ekIz#b7iV3qSRC{F#>US zX}*0Bx$Jq}cqQgqDfRIaRQ4ozSEp0GN>$U~@aroL6H&K-)Az^OMvD1PtRv4nE(MKK z|C8m|ZLnNi6o$=lA!)qJ8?-9b8aZXzksR5Im1S0Nt3Jc?_4yk1BAMHoHAWIMCO?Hu zc@Qn;+o8O=>d(2A@$-jTVJYhE=5cX3Lzr<#zVXNVd4cUyy&x*Oery`6uTZ|u=`!A{ z!c?T?5hHr)89F%qZD1P2c~J!*uPKv*dUhKuz3U8<@A3LfPr5+xcn3U+6@khfcx%{tW`;@u$S{06V9wH|~dC~9tg;`d%J zasRL#b4TxdaK=ngD)yd)Bimm?uc`(({a;d#N zY1%1U5TUV3s%iDfMr4Lmuyp?f>V2icFF9bv_U`3Ro8L5ADgc;Pgal}c5xr0`tT5xW4Yb8fKm zV9@?)!Bpa&nG%J>Pqu|Kk?0hOvmr*VG$>i*Q`4dYVht4Uh;AM!QEIMnt6Kz}7s1uD z*1_jNY7Eb7_D-jH0By4{cGn{!-PfyqYA05wxB0Hh<6%I)ZO8((?{s%**;IlF%CoSe z_?F*K`1S#%#Cz**=m6-s;EuV&530=3GtN*>ZundLaYAjyE}ZAKOzkat@&ZO?CB=NL zkgS-jowpi$xgw_@Hj8SO$QJ?++2Fg+g64Jsiy!Q+4><}qM#(7ce}3(sE+B7JV&m`U z^06Bg_~gyNUeZ9Q42sg*`5I-tE=IWB3}NKZ7plR#I(%z;ftWGY)@SB$h7{}7 zd(lccefP6Oj#CUpDik(!DkkwM!S`01WB0qhn(Eb*KeG+1{o=CBjz5i8-CfWWaC(n% zG|?8c8#y56AOYG{48Br_Q=+$`v;M z7&wOh2rjDr)auQwKP;?KEVy(61Ag|(;Q_e}J?m0VhxI|tv>ZLJOwP~8uGl+mcxD6V zM^T(+GF_q{+ANC@YYt8gtMY3tht$BB$Ae>?`bZ-M>C;ou|eE|7+zKF&&`I530ZR{#e$`zPxppNpeRlm{4?L zC3nXka`FX(9xb2Hna?nfyy3Run0rf996t4yT%Dg_@sVoDe8M9y0NfmG439KUd~);V zJLk@c%)kMp7F?+7=gb%;MCNk#_4)mo%opIj|)3AcM}Kl=sbG*Q}Oi z!?FV2=X@>zBZtlhNT};@tFb;Rmnjl$hHUgVojQL{go>7s>uQm-hwggsOuKZX&$S~R zIrvInebPJQ(|L7OgYh0GC~FgV5v=XOz0%Hu9Tj|j?b@8@nkDt<3dpGu&DGcnV$YYJ zj%q~7E|}=0lbTR=2M&IPqObHWZEjKyA4NphUYGh~m`&Vc;3}@-gbjB*t1DcD>l!-o zkl-$~O+|s$({@Er7r95K9|EiyY{!b@uW7be3=si__eX9#B-%b1Dy5@cTur32bX7F> z$#!8Qb1nRdHoOWs%bQ+}e%w!y+YWYE zs88kJ<2}pt1CV|hxAB-ub63%8JH}g{b&0KO^(eq%e7WV#tHTge%t9d|aq25!cRi0% z4m2OPJ4!;~-RW}Y4y*d<*CTgfq@Lch7!m;0cS{u0>phI2ZD!BzX0}1HpoAK-!Hk~I zDrTvjWCvMu{G>(8-=JP1yGwyW`NBaM9}q8?#@xDy)Pw==Fo!KiD5^7I-_YW%8sSXn#?3Sz_Uv3NRH`4AA63u_-0nWA4 zkhZTPOW&fmBK&yGIIF8ThA@y>5vL|2ix*B^iaIE=rSM0075ugsA8|%pad}nf-`}nI zB}w$0l6&qK2tb~%7oWvs0Pz3yO+C+>#E$IyrY!ykQ*@7pLxuDzvF=d*J|M9JXzLd}dBd1{aO!8kXUl!nJ7wLUR=* zyA4;mtDky~=|~-1WzfoWnncKN0)fcLrlw&tZ!fs;u>*X4I;zHxhiVv&Kj}t+C7*h* z8Z0goTSawsCe@=QEvB%gO*4qab>s5+OcmjhYZhcL{&JC^&6;$~Oc6MfDGbAgO+E^f@sKmVEIUwPNjAwPrIzIZ~ z@P0s##0RR-=7HxKs^KPw#N-~$QS|4u%fS;QLv}FX`@{gOUx}1i;N~ z0Q^Kxv=oE?;6n$TS7si~G~L1Ou~5>T`_4!j)iF*=e6yYZVJB)l{LwA!(b9)h0J5%& zDmKz&E-o>qIhhA>8ig#(l$pMFuc&i6_U`Hy7bE`6u}k~z2%eU1Y+`x7R4$^T{2WsM zpB4_f!Wz)6#+YRHKgfH_uqeCsUl;`iX#oYKyFr>E1(Yu7M(M7h(;%d!8>G9tkP(togF=RI0VNs*r0Wl@r5a-3ktaVi&dtdx>1@qzBC> zwg=vq(ho67I#bp`3$QEKW_N|KWyI#$X!o@_TVi$A#B4aWs=@E?Xx664^ZGcG2rCGb zKD=N~%#Bqbo{>6Shrb41T5zGMb>_sn zrxmP}PtWj59Es4X4+SA}D3Lz|BT|NouNqJ1RYj)>VE^#gZ+h5xAccN?$mo2G-k}C7 z2V~1JGYS|_Bnjhyb>kL9LY#|~Pn`61o>IlNdKtAhB6LjyA~Ym1H(Jr=KJ#xOUK=$5yjo+FYL;}zm{<(>1jE-en_3M&453%Tb#aCa0$`pNEvF^AW>}l9 zj8jVr+DT3Zm4#6KZYaOsQ{SO-$Q0!Cw%)RLtWw5ryThG%&XI){s5&S?-4n-YJf zJWa}|5Hb}e^@-)}UB`kKueoSm62EnMla>pQ?89T`FIBwo z?vfw<9!r9&(pTQ&j@QZ#1V&pa+swzG zAOy3ya&0X*b8VgK4EbRppUA4I9lsj?r-QlVT^hisq})G>SHJZDwuMeIGOWf z!zjumR!Q&FaN1hFySX0f1G49yo2Z61V=jU(>XCAk#gRg$Y*E|o_?tA@qr~pbY5|bi z72;EqWR&S;BqW~Rd&NVF&sxi_+9nvXKa9L7x3=hMw-s5}%K_Z*$b3n!N*{ja_vwIj zy$$Qn*&;ryf3qs?`7P%l)r;4JAIS64T&n~pa>a@xgeTXk4pjg{T}<%N5w`VAd%$9@ zovV`v39CnjNLDz1Aa7}N(t%`KPya^eXMy(@A}NZOp9I{XXUPR^3^7e<7xlshCq7Bt{%5Y+Ol`1;l z(Ik8qp?h~_N`?2(@avRpNCX`wipw;c5HT%Wdv{gz2^$|7evp`}BmnkW=w2UNS~@p< zYT_qT&{mGw$Vyv})5rshhTYiyAw!PTHh{e8YC|pBSm^$8HM#!4&Uu0oUm(?R`C|{r z(^_@*y4qg!YP7~*9guP#8+i2zbV(M?0n?OT4fb}s%~)e-F{Ynh=14h3AP=ucK>{Qi zLo%zZvn8-RND|u%FAi2qM|YY~v=3(8JZbtUsW{11>rwo9^P;Jo`ECrr^v{BoRAwqK(!MuA{d*Uc^6IT=Q_8)O#SV8m63H!AAwZ6e zJkDL8o3H5~^alCtt)%cCJyNi|dp>B%o%Je9JBH~Qtyw=_kB@MiR$@VQ%Z&k7NT7Yq ziCg)yj??aiU@z}wxPo3phD$$RWxT?MuayADHkc`&g{x=^By?o>ms(Mmz0 zO-19giXX0r5*li`-UMw5(o~O-#31A(qQQ6%UU@*sT_#5HnOrIacvOjB6PLdgXU2Oh z`al*>>9Iim49ROzq#c^-^^_Bz7uodK^<1(W`&*O0jGxJ-i}Q}o|<^0YspaG>&~5VTMDSo^cPJ*>su#M0k|%W8}3nQ zl{mK}aR7Eif;jC-gcSM*m1?yMq??^cI&!iG-he~4A5NJ`xMK3*emM<_c%FC1)}?0g z0(HI&pHcPG3u_juX`3(-WSR87@{BciSjWxItQ)CNBNw&JWUpNEF=^XVNY6*t)2x>W zfg}Jg55>5`tyLdRZ?e(=S|7O=-zsU#N zHO}MHAl#k9wl`0^!q3@XR;5^(u93GsIyrZ-_v4AS!>f-aYL)o%rk5(q*i1l1p=3JZ zzUcK2&oi*QcuXrPPyt>5SI7&{Z*M;m$7ALd;^KvPD?3e4)wt==-NePEjdzS+HHWI5 z$FsT=5x)?RiA$mO#FuMK2Aiq7@R{>W+ZcX?#o;Y0Xt81WEnlaAq%x9XS648gHx7L> z?uhO9+X8*TlkhJ_P4YK0nluVT9*?m|y*VQmE>X7H93J;B3j5RHmVOt()!%$S-}^XB zF;~ii!IEq-jdr7Uq(k1;5o6qJ`nyP7=$qT*5e~}%+7JH0%8g^APIjKmPs9-X9h(ip zUvcy=Ann7W$>7MmE_z*{_Y|2vM)}hVrw3M3wzBa(uZ_L|oAu6FZJUA2WkOdJL}+SX z-lqF(PKpt_Nuzi6S(aVeQvJ=N(3 zG!?RKbHF&+={%do@vmd@5LX2&EAHS!3?gSEXLohSqQq( zo3*lk9<94rpWzi4YkdpAsZu|J>WJXx+@?WT~@q!8gI~8vEM?Cw>#o@1_f5)puD!~^R#|expzig=-l=`uW9*E zgBMJ#RQ)(_@rpQav0*wE&&KIlXPQVDG4bNp$Az7b#91k=c9WYg4rH5~JaDPAU)Oq| zDG+ge3IXxORf@htc%{A6x6V*Q$bQSN@3jRWHNdB#C?TFCy2#x2L8?ZyD1n>xt75i6 z^htdko~{Y&%ev4fRx8JvFXd2$1w$AXNF^ulvfR!-l?q#}(T%(lAb} zmwP`p`Xzi;oQ8LHk6 zhkC3!lajF~YU)xbhs1u7h+Z>Sa#{We`IF*GIGQzQ|^edTKe*QU6iY>vXSaKOL*cgE&Q;BHo1u4p$j06-#K+j46weywxV66Kf< ziH*7OD!WUB>#8ENoZ(s|E{ie0eRvS_(!o)rElukPLi1mAVt<{#2cCSrwSDp5y8r%A z`=?5-p#4u*pMrLjEmy>`gO`+#DI=wP>VDd&{nbqN$G&$}sLX%39Ki%1rl`GnmGv4P z`a|XY3-UId-yqbc8LM^x0Xk`@aCT}8T+s#qZmzo$T?h8TFUZsX;s#Ei;kKx(e?JWl zz)evjuYr5i{94^9FSq;g`mOC>3eIX|PYgcEtkI97zqwpB*e)%k`8G~{S&i}9ei;>` z@&`?_n-4WsH-+Fp`xEqkJ6%yr`wDoXvBOH{!#H1I=Adt22H{;#&7ye=`o()#~(%ggdotR9nhEnP>e91xg6;S zLG=GSN&oq9w@Mj_lA%Q3Hvf&{;2S2N+3?%0FCh(AS7rSJf80z>QZ9(X*Q?2Kz-5W2 zNI}6GZm%mSU9b~VG#SGRYYZ~mEG3V+d3EwlLcgV+HAfjYC@bc}eaoP|#B zik#DDDPusUR*S=XZsC9ZqtWV@XF(SkhXO*Y06_AC7+Xqqq zx4teaTU?hEDWy*O%Tc1MquGd`NU3##FII~-*4wcsygT1W|ir`x- zp)*r_wv;1f5CcuY=q|Ga=sLjy1_%UU6e&^C1jR&gTX=)aH%r67-!42_-L4%Qd5fhg z#H6Y5StLs~dpUQjO4=gi$(9D#O@dV}QVMQs*KB^H%9!ZqK-?6V%x8N(l&(+RK8hm` zJN#6b#xf182J-whPtJ-$eOJ}PVLUza5LmLr5dzWWN?fT^^9B`Vto9i6l#0G~71>nL zJ7}be{B17|V1_O3ib65MEg*46a;(LUjxpzzR>O1uft(9&2nmfqvbSg4wz8?9i^zz# zet6uX;up^byvlgCTse9pXLx*gas=s@qN@HlNRJ+);^#^v&COk`d(tjt#Hd3djZf&3Ruy70m$b!Ue8JReC@`@V>%>&e0fBeEC! z9?7M+l7uA%1l?T{Xe^&S*1{!~zt7VDsZlo=r*iQ-8Ar2RnR^ zJY#m(Yj_+3%ddz1BaWioBFK${DNa};)=51{n}`ImYh2k0U;yb^`>dNGKJ|YbHzcs-Il& z^g5xY-*rqnR&^zwA!xEY_eS z(CCiAG%e=1mQ{eu8&38VD&t3TA0+TdIal6ux3{GSON5oW19ET6ud&)zD|nvlifkE* z^FE0}CXQ8<{st{q5GssVDj1BDp;s$Y`YHm=3Oqmi`(E5Y4Y?1h7#>QuCpvkAjq;HE zDUD_>nrrjrbNm|mmX^Z+HbU3VSafd>+GXbDmwwpN(hk;?FIa~A#xE29gSg_XMJvHG7zy?K$KR4v>Y02 zCST3$*mv6EM{RWKuijbpYVxlVHyRw$pNuy;4EI$CUfjM+t8bu-bxp0j)%ZXm_JaA@ z;*KLn%RNrUrdycge{`okF5d$TfuG^#z96%f|+)+zOGz0VemhMWGo;%P(! zC9upSPB;l%k8+#@b{WFiaQ%uE-HtZ=k%(@S&C(l^_}h@(c{yX5Bz>Vb!xW6_MRK}M z57WIWW6Z}Ln-op9%-aMV+iQ4_4kk1-pH9ai=L!yJ<<$1%8nu4CbMgp3_(y%XY{7r(3ss-@jrrbkOc4^mJIGspNxfsH> z6=-4UjIeoeQ5s7Ku;lZeW6AbS-o*?1D4#xTbb{&na3F1{JR|zj{7_TD`t%WrXLW|U z$LFDLvgdSGf&LDFc{W92doWV??r37vNch%ucxvKu-h)^b@s}DStMmH{mK-6jWmbbv z3??^bs2G*0tKYwZC~oeMA*w!G2rkSZXcGpq)9EFNx`b^^TszUrV}9rTD=ft?q~fnX zntTI4#_}g1N3{A&+Pe9jEY*Kf7dLn#*D-l()-fn(f5V@7)Q>04_NpXn4rqL3gP6OP z57-8nYBWU5-*Lui&m$#AJVuOf_FFrFB5S8(8&mUwvVPOuuAC%@!`RmK3Ry z;Iu5qVe}{)Pd?8H8pl;)K#AXDWA<31l5(|Q#r@432TvCcgL(leNq}G{%XBsQWBR!- zG#J6YU4=$TuNj=$AN($Hc>j8ySZun0pC^94CbI?MVzBXCjaB@z&AR5^RLMz`KQt;O zMGkIL1{d3*C71fr4I>va1KvSFLB=K~kAq$wH$5SF3D54*H`*8)ik`$}A?D(8PCC7@ zA!YRY8Dfs^e-a7*Un_IRwhyl`Ua**;PZJZcPSY!H;i$od*=_Ov8Oxn$4ZsVwz{)0(Bvjk_>J&==WE=!AX^;uE{Y#+TBy!1iCC zzQ1{P2Rjb=-j)rHxl<2#VU%+LM7fZ3fnFmEV^*tgT zGCWdKd}H4hj5O`rzTcqL{{JJ$_0=XDT3v2O4)Rs#Q5D82Pys5iEllC01b^g&LouA3sO{8_pFu2rKbPl_iSFRvou;w_5xv_*YbqpDawhlTL?4#|Mig zh?H87fML89TkV)I2U3#A=5-t^y1UrU>O;Rt($p%wa*H^vY~ERF!vJ$I1G$*oKF6Ffku~!r-i!za+qXSNeiMmq zjJll4y+jTOfXKt&U6wc-I$4^(y}cP3{W`p(57EsH^9)l%RLIeMGf(&S8OAjml_FCk z_o>%XDzWFfv)7a<5-=B&S_q*$ymgEF%Y4=vA#8P+ON2ID34G#qc|^SwY&DXohQa&C zn}Pug5tN+ByZNj%g@oF3?OB``>~Yo7bxMwwMRolZj{-v*P?PUZ!3KP9t0mah@GSVu zFPJ;aee$^-tA1A$JsukL?AZS7yt>4LDxLW@(tz?a=|icUSIM;0;XaX&Rs-?>NK6 z;Cvo6t=Z+i0r>2WU~tJR5|C(d>gk0_<(XsKLR7>l* zojv?rk6~>42|SINVW04VIT<4{dA5zj5l%t(wF8r`?5pCzD#~A$+h3z6H=yIAvsaA( z#dx_0PP^_8-3qhhr#z!<^uSy;g*&An?ASDpbDVMO6E6hlLtOG4X2tv{L;5di?&kpW z2KzKFfaip~&)MwpA|F=OpO$+K`TfpvzQ8L2drYO~5h;D**dA`GyyrWuiN-xRQVdB7 zJJ&20+HGC>y|TzmFfyZD>y;!T(zkOeor$ds@UteDOpI+;Mejte)Jl63dYnxMJ9o%2 zaG`=&YwQ=J`TtNMCjLG=)=n_k;)e})i|2)~CiE9>i^-!^Op|MJ0UtMo5nI7+gMI4C z4d6D`{cv;*!js+hWSNQK;tKwXWP_U^7Z)@C1$JeAH17!|1Zc-cMvB4{Q1^jAOKbd+ zIKK~&@%iuI3bi!j^FLu3Bn146Y?A4A^!`!?%h@r|U5q)SnY zL9fq%p1*`=jB=@b^Ywn~<#)8*sgmU75-B*M(p8H9k7_LBdXorG;kx0`?hcQ$MC`iY z(9rU$C6TXku_n7IC?#>(=Ep-y9|KgR6clJVIXT;OBB{ZY3G+m(2Cag1bumBpXN$U9 zpydyKzxM1u`whZ_7lYaUAa*vq&-8c$5FTpjroOy)z))uc`L)PZtf&gUBoP)oV=WPm zwTjgRz!4KAa)I%BQC|Iew!W@__o8TFzHTfao~{fKe?oR0vwwT=6W9G~@$De2tF!|; zK0KPXKlps(?wNRRORsxscwJ;m4^(a;LR?*Lc@EPz8>-j1+^@4XL@rl!`nq;npcJFM zC2zFx-a1C3(#Ld89?@K%J5}t+f%-|2*w$kM;%f4%)}V^bHA%iQalL`33gmd`pY8Wi zd_t|)7x%)m-3p8d&v)R7QLTq>1Oc~iX-9Md?0%up59090_@6Z0gSNbk_wJ0BojN?x zfEn4K2S0H1Fbj=U0p$(*+kHE(7$KZx6~<~DG(7mGf7-Gm8(b%tCQ7GHX|d)QJi(G~ zAPo}=W`RQuwjUGf3osWIS`)6jKN^#`FmHSyN<5joDArADpAM;Qf85&h@6Bij(rKLS zs8+wz*6-FPP{hQQbu644P{(`~UgoPMTh*L&n{pf`>fXhECwWTakAE`mV}Ri*kdg=8Kn4-H`^* zUDpSi*UH)?qBZwPY#)AtM_@?r!&J)X6X!@IR z(Gi>Fr()E2j0!bR>44KZOfwEjcE)!lT)`1*hkGIvo`HKh`eZK?l_j04f=!fxqs#ccBp(-g1idFJ^HrS(BNzB&!2 zXXVw9$r!%Z0Uw)64eVsQ>6MAEci%^jhF$MrgDff;t z&sH4GaF9Z@KfQ^(3pJ?13XFm>RY{;{LRU=~QWB(Ojt01PeFW^vmRqTTn{5_4dCV5l zM{u5!If)K9zRuj&;|Z>~j_$3mpMM;~lp>`Z={T_`m_WB#Vlpk-R}o8g)JL;up~@bX z-DMoCmM}O0P#}fS4FRZIXx@M_(S_Zr2Fp?-oJQvNfmgkW;`EAbm{TE=G00# zC{sEpJEri}Ue$roc_m5G{4LFhzB409vTB}FB=z^TXa*lme2Jk5>_Ird@YHBB;eh(C z)t6j1F=T1r!~O`tY}unp8GH(M)-WiF@CL~))!cqOBbz4A68kT z&Ay!ot0)=n8>?%8z~)}(IiUtgzbcrh$I?)|j*|xnbcpQ2Pf@so9_dV0elWg>u5hd> zuDIbqjcH2O*2i_Ah<%fE;*`XnThNaMrhG4I3pXVzq=&tHvOw;VJIo_hVFkt*sC8}e zkZtJJU#fiD$GSdBF;`*zj14nu?I>@Ym!)scjx&Mlh`%v3@G|PmV%Y*gGN*W>DxU6W zU#&$`<2$E5UkkA)`Ar~UXgYs#muW9hY?_1G1Ui7Ml5RG!!$R;xE<2DuJj|d0g z_T0W)^+?_3&F5zz!ao65VlxD_LlWoqor$C@#}ZZM=qk^P&~roE!buHm)=L0&->4n- zlFop(+1`Qkmx5sWaFH8SM(f0piHfXCjV4I{^&t(Yw354%REIN~!lv;keWY{3eEwtA z^%JVSI>;qOj8vpvFCwlHIK_8-YsgH?cVTgeU^1HHhQvRj{BluRF0JB2qn;;wxeVib zXAyR@IWCF2BC0mpA(Pu6lUh13VgZ-PjrO%V);(-SZ}glG2s)SFThpo=jcLC=Yyp5P zpZVQgFe(Z;u&1{6t*2^f0AC7rafqxGc&3|5c;I@R?#bm;(=*}cDqTe&qbP0nan`?m zVIzj{m6A)C8RZ=a2x(Y z-~Qk;`vvctHek7&tF4zk!SLF<8OFwR{di$TI?hXftcJaOJ_O2m?hKoj5O-)|ye7Xr zw#gkzK!Al8i2i^~GX~+a_g9i?Yd4JaS|}S?vlG8gRrcPttAbFYAV;_Z*}}l<-ncxK z>42^lC@mXER}q%RfMD!>{uEM*`npb@NoMOgQnT=y1naXKsvJd+IM?3OJYDmxkva@+ z)-i7aHld|hq<1sg9IWOq^N`6lBJ0Ysq;HTuc@5{w2C(yjk?xv{Io>xbCtTMvCFEM}9=NO1N;u5m9mvtP`>L7G=XoIA z=6=IDy=t^dV8rIJr4AX-&CSjBw?jjHFMCQfWc1uIva2=Y-HRr_!FfnZa~P{nFa_@r z`P6D#v%rRKVK<^~F9WxZ{R9gY!O`^_(!HeH-s=fW-ow)@Jy#FV%s>fDL9iJM-(bl( zo-=)FDj61T*0DfjzQBw=3OoAN&C4!OM94er5w;g0H@iW>%ee&# zA%uFHfP9@XsphgDBN*b>t@=?Z7~bkBI(kP87PJmRJR?4sn4gu&!uaY+TvES7r_ay+ znEMaVw83O5EwYob({7}~)PW5;^#uxf5=qO|?1ds+dYL`UVX057o4x)zclE@DZp0-; zfqmDjI#2g0aG#YfrPZp58?))QXZF<=6;xZ#$8>Egx8C?*u!|8-xgyA~sUOe9Xc^zf z-q@Oj9IC85=XWU<1vwTayLsNC-QrkxHB4Vzsnok)jA$kpdDdl7GbO;T*j~QxtBZC& zh_)VZ*_Dj$GlWMT?8%MG&WCC|V)7kmfLr4DZ2E3*WOb9o1a?ad zn+A*NOB1wbsRWMZ&Ik_^fhz1L^-pbyC8y%kk2myB8rk9bLEDq}l+7p0NP^l}uAy4- z(M!!VY9E*`S6b|V1UHMGCB@E6nzf8CI^ovdpO{TY%XHfCMjxmo94^rYpOJRZ_@eS6 zYLRig9fN&QP`oCtO*43E13rl_epn4xK2DhdFX=fol7>cs#Lb-1|6XYWLhb@z-PaVE zHJ?!|+}T@h9u;qQeeafj^is3QRERz55du=kXLUX)>m3gcBhPw(W+={%sA0%dxl5q) zDy2m>lA&?w@(Xkn^@G76ma^53_@1NdxzbY^Xc!^k$tP8Um+{vCul8-6)+<}?Y?ln5 zSZ~4&w68ch439%AZO^nbUpRerW&ZS1^GJ%UQ1E!`Y&B|7lh8kysBLX8y)wwk70G!G z)@<9vV!Yre94YnsT14Q(y(bqXZQeM{qB~I(hLEziHaz9Mt(3Q?i}x!ttrEP{F=%1# zoCC}TqIix3956JZ*7eyv)~%^L)5GCo`Ijh>F?hYS_l;qs9wT>mOsylBDlI;GsL)B$ zM3KWb11e*-`sk@x$nDA25tCL0Evo;?Ipm3T?8)zhW0X4PaUn**Mlh_P_Z+}S#74(P zs;r{&)M-e*`RMn~+^JXQ?f38RG_Bdr#F0L};A#Y}aI%I!*ST5N&Ju)<><>BTwRWkn zm3@)SBb4)XMcYsSgCafAw-4xLm{F0=y*V7o@o4ehvG|_ilD|lJ26wG2ZQZ!z3KvMw zPGzL16@lr?1{5ssAsLnl4`-t(uBYv))K{+>NVo${_TEBF z(XyH*0KW5+!T2-}(VvQTc%`A>ZBJ8kqdU+dMD&`1rejRw!1%D!z{cQdhz->5-2+#QL{y{F3WxqT|hejSLItrx@O2o|P2M*xe2B=F=-luSN^< zUYY|Ri!V~IgOMniFE=zQkDDu?Prke?0|GK`@p?ji0un2&c1r`j)eKrznl7mM_+=6hp=vzfy0zNZ;J#FCCk&%>VMQW%HEJqweiKxk=N~ zVDv|(v4%Y``VJ5?)>K4vxe}Q!h6tYwxq`)dw$kc5;H5v~lSkc4Z@n#X8(o;1=8Ii0 zE604}&e&B9w57^dheOF+F`Rv1vDT)j@epi#OtnIp93`G*@9PIde4#OV7YwSA12p0< z<9q4nTZu|=&hru%qW(v2Xm~dLNw}rxu_j*}5#%c2%+oU4nCh7tdL_S+ARF6!S;Fqu z*V}v`p*@t!<<|K3buAs&!7YHhd~fN>r{8DvQ>7xjIuLn9dOP-^b~LJ0OnO%Sn%ol*U3U5#DNY??Ll^@khZ);b6goj-pesMTwwe&up- zXTO*}B5)wp=*ogDBGO%g<@L2k_rNit<84P*pKjIpMb+Tm?`vRy$X$>g@P1PR8jqHH zVc1pE>v(xe>SUw+A2Y1!eUk>_pRrF z>A(j<5P`%X1Ed01=!8YT0lx@X{x#Ye@q+60s-Jj_LL}6gebm)Mo$1V_MRY5J>eOhYaaBm ziPTJaLRlQoO6?;JCD**Lk1+>l20i*b5iYKJgM_X%hMU}ypQjOn){C;+d>kGsHiclSfxe4OD}I62V2xHSc{=TSpmUFPT5Dcoq!)wRqoY|fd+snh z!>yzuY-6t=eN8))rWCz(1)>#hGnYHMJdk=;-G~rL-GOyhc>G5-A$`bFQ0|lH+2i>- zFP%Fa{l*dun^GbWLs?o^bUgRgA%5d%#%uSeDvgtqt@PK|!CDK`G`&@=7t&wMZFXbO z;BT@bLVLAPPuo4&nr1=H9}@V_zih#%-g{;!cvd5abxXNl!F3KWVA)BRXHh?Do>H-# zS~z&|qbW@tMkMCzwGWTv&~%4uE)-1$sH$d(6J2hw}=hmw#bTx2od)nHxvO_YoQKR3_`cd=tMV+BO%C;#*v$dTRsHMCe0#+lH_}xZTW= z>y)_TBStbGba_;>d+xaQvJ3*r+pi0J5tsOFzgX}0f|tu#;DbeL`vJUFoX% zSvR+-v7Ed^5tJQh=<0e|Sy}0FJ&1UHlgw@;5k6&NZ2T=-8W$eg`J$e61g^Bud)ev} zm)vvr!qA+(syA$P5`)C;FrZYxKbiOL98sifq2mB|?H+0@e`xS4tQMn)5?Cz6S4-R& z9`)~yC7>`~mgRYLEm|&1@vX(ZHk*Y`(T6zn`VFYvxS0AHKbaOD%UDDd_1j}NXSO|f z9KaGdPDbn@J?|BDwaA=Ca>gfO@+8CZQahojdc~)gh$G4u^JY-^cAbDkEQPdy%i~8YhPO>?ZLfTO$NB7o!k)b z0h=&ypr<6Sk`|?wy_dyws!%~87EF?)EHg*K8iMiD!F3NMC z*I=Q6?|}c}3*>#lFFmZ&Pb;}sZs)$*Nk&y8B7z!dUtB*<-SK?sa}mk=!6bRC%5MDD zcI_L!RE}w~@Wc>A_}BFg|BRZiOGc{;Pvy0+r2Lbn*^9>`1wV$j1EHBl1i{09c-p4{$Y4k69p=C zKVV6C^&6RRG!${7M2DBH_D?M#{t)EhFOUD#Jqx1WU`hB5sOZ0!fho&Xj(^1`D zHA^u4Zb_)<@c{S_nvzsH3azA!HL|6KbXIE6vhT6sfGTLl69he}9Kx72WlrW4E>q3d1L%ChQN zSMQSDu6kKKnQ^ba^MuREWZ#7W`(?C{@v;8gB+VmO{1M>pO! zV1AG)9Hh0^G{$YRcQ#`;?tWK-L0!imxwPRsq8@0;xjh<$e!X^Jwc~pgSxp3ZA9PZh z^?Dr9n*Esj!oUOnWbEPLX$t!(6E2dW?vl~-;YPusMJ(^G9ak=uA2_j>{h}XEP}X}rTjQL%^I`8PV^erD)zeWeRDqmx7egK%S!4TP zQ2l|qy%Qo1Wr)_P)%rV~Ag`PI(VM0!wMGWvq3|PP<|}6HQ?$Lp+Amrjq3Obx@48>V zBhLvJ{x}GN$klWqvNHX~6&51v^6iPw&lCg`16E_@e9xb#_q^K{(;xiHviGoH3maG|wEocU(@8%tz z+P%(XimPJuSaJS+Ga#wA*S8@qbfC;512W;a-l4Ox?2YtW(H;+_Fb||U@TUe_>(r$2 z2AsZG5oaoxyuk^$FqiU=L6J2e>FLgDTLQw-RC4TD9aMgTA15Y6$Qnp^<1S_!Ggm#! z(Hxfc`sa@LSJTP|16A)hzaF0oWZ_N^Cx8-yU|9#1bXWApu>D2%m`M{T^5I1);hT4& zaiX(auYriXa=I#_?88rVIXF3oS>l=HImfFfCJf>>Ae&{=faIw`WCc>ID9MZ=A5%=bKA}?vKBZskRareHioOKK&sgz5! z#rjXqwjclL+uV_##lNOF6Y!yHI!}m{WEB<^xm!ak(Dz;TDl#Z)n3~AW^I|K}w+Y-Y_i(0Na5M#7_ht|Iny}l6 zIBNMguadZ%%xyKoa~J<}eUVGD`v8oZu!;THTI0bg;;nh7u1Pze-mIuzl(u)JzGsq0 z;<0s$=98+2+!85NtIeINLo=S{&Og4Tt-jrCdVN|rAXIlt?MY%VP^K`;ZD3s^+6tW6 zyn?=-Hg1z&8j_zcNhbx%Bnle3(SjBYOSO2HMQ%PV2wv`|2%9gW&-=_~j?n*)_9&e27u#6zb0dPpB;;d0AF%w=ArZ zD_7uzu99p*9!7|YZZ!X6dc4uL2t-I1#=;#N}tNzbLkNm*wpU?1Y>)lF!Wz7D& zL>vA8$dCCJ;qsE91d)$$X^j`^9fm7}{%$|pYPz%lp3pm8*qf2$0X*9_2czd#_pVQm zEi5eu`1guc4od!$0T*G#NFwZ6Y$TOruHABLY&d*?FA`%~Rs`X>#?c9$e_5FSd&uo{ zPCH{Xoq*Z4Y9kl^RTn#|0ZA5JDh8==|OZC7=`;ryOg zz#sV<|GJn(lai8@_4M?1;ExQK&Z2?3dF=)rK2Aw3lPC^GFHZH#a1VP^{&PD5LV3OA z`3GQzttqXXzR-=qbHS0No6h3Al^^5#`x=t0nhrxtg{L%@L>{?*I{>fX=Rz8qew`CN z=6h+?V7;;dCtbT&Lf(I$ZO4J^}^2eZAY{a%})elMBWK-@irOc?`vo6ZtAqOOMqL`!h|lb2YZHN$MqI zx!zk&do2pJ3um8iZ-XT{JUmROe$L$sSv8eAmb}dhmD<5CD(M45wtJ>UsSl0)&pA&H zm=rf4;$?k|%Yr;jXAH0c7U`Xj6;~rO0TZQ7lC1*vSE|D)QIG6eqUgw4Ir0`9EkFQI z*zNfouxblmM}wd7CpD|-H`w?T8|bzS4xMsYV8iIpt(;kt*^WR(ZUrwkGG-N>b1I!& zu|{hLP0(fA@R%h?oU>>Bt_o|QPT^Yod_IR~P}s|*c2`yN8|}|p%T)^)F9N!QvN#(v z5|So)`z7>5^p{F@CTIq|_Pel-JDlk@t%yoeN}b`aDzjy4?{Dtz>xdDe#mzGdymzx%>`7-TiL z*AWf$Je9(d(D{E!Uf~`x7UQ2jx`9H{f~S`c~VOimOGt zI>lsa2Kj+)&#P=}d*2ol= z;VF*YA^pjy%&Y^#UjYRJ!Jc}NzJhKRK3v8*p=~D`0PCBY zN|`nx;BIP}+0>g&<)xOjxdq+^R-OG?XUk=GPP^7C(;*2ewI;^)EXAaQD_@;A9E&jIGQixgYKE8<2IP@T5|>&$ zeJ^VUFt;|A!@A`Nc!j$kJTR#BY*c^3={~lO7hSz{JCg!U<>uJQ?Hu=wb*@~C+}Z@i zKjX;TT{zthA)Hi=W-Dz{pYyfOODe8C(6-R=U}I~!1l=EDPX3-P=hc=VCa=d|&BPpx z`;&p*RD9cC`=G;CXZw)sB+$AE%t%;0E8TE~kH6I~^B6y8O}3)2 z5~Arv$0iK3H3gj8n}qaf6LTHC~YE zURlxsNg;>x{)zkcQs9ZDc)Ydqfaq+#nsUvU>+xW^ZnBMHGqw2Cjb!bj&q=YmK{VFV zookwxZ}RQY9K@t%gnjYyV;gA_i;oa{vTd!YN3|ktga^5JS$YDGm0hBI)6=NkNyom~ z-mM-RMG(VBo<8v=>uBK`qvLNZbsGlJ9$PvZsR<=>@h7qLn=Pwbn+aK^iWv@;v|-*f zio&;260Jf);OPYcd;?GQ)-iX`!Y-EMjpF&x>a?5!6m4+pY}qEBXCw4)QTGS^LxL*t zQ;O6VSVRC0x}^=!J3)^@kz)mMb{qb)K78I=bswMY3V`F*voUKQ-@UdOarj7 zUvyHJfxi(>STbHPU8v>TYkNh!xJjKOXS2-Nl7}()4QSWrIbJwsI~zM@SEq73Kkkzt zT*Yfu_ca1I4{ZTn_iwGU)#=9tK8x=kfL;u6vp?hv5athB$64L>xnSZ?*sl}l9KAt;|ID!nt8 zdt+l`^TU1JutM|e%ks;D!fW$W6N{k)FQe1#zs_D8(bdUTU?S;U+6ICCmKKkV)HES{ z6IFAE%{$1q4okREXmGb7T#Qemc+4_M;<`|wv=@Lu6n6)`$*ZVvc)thVVE;Kx(5J&s zY$N&;_u)`JV@*vBOpW2;Wnc3~`R=YItaJsaTM zu&L8<`~KuQc%5+H;Cc^CW4x7N4TduzS(hZpa? zxp$v^_Sxlk_StuBoBW}#kKb}of5*og8Mx|*r8GDisolhM8-nb9{z@k(E@Tkfz0K}n zy^UF8?C&hQluo4?-gd*9%M~^$dUB$IaVNf`WU>#_y-i1-VYJH&;%t8svi5x9d8^Lm z>h?+k=xKw8?78G$6^|W|HfaN#W|Uj>XA&L5X_Npw9EAm@cIoL z6kU*dV(3iDSr7~bi1}8CiN#_|D#;p?bRfq2*mOL4pI#M(gxpwLnR8&C0zEw8ZC5!q zE>u-&B6w)@9}4h2AqAO2-~J;YqB)=~x85GNZF>j)%;(?3E+D~9O0d-rMy;T@B9+@}$zg zi#m-H&WOYo?k0l}mX^%Vj{pwF4+;&POTvBv*)_u;BHP(6QvC zPMo?nTHPb8V|qIQae%Vs9pO+t*D9ixMAjx~Ny|9H4A9Vmw8?%tco#avCTXLCMW$H^)5jx=>VTx{L8b|pYFE_PSrZ)8b+Q?Lc@j}NdI9*2D zz$JA&mK%g6Ia8PZ(cf}%dsgHK?b|snh`nTfXuR&t*qT881@PLNJJ7O1+`>;^h9Iul z+R2G_q1@l=EK~IFUr_i_$ER7DyHjl`nLVaIDz@wg$1_0Du)vM`fYF~s4JPFHe@=JAn@wb2|RY-(`$Lqq&G z1cI-*!!xeKYx7oUK@)EEO?~KQBq1AJ3RLOznrhQpBrf%qH2$vkUS$A<(xC=z)CrHo zYM3X2rMX8aT8l6-htjM>f|cgL&T3}un1*-X>Vnqd(!^B5wv8Y4r@vWiZEiYd$c4$ zWla0DD`1@Id>`u4H2rj@lA7B{ZvB{JM}BRKhf$%lc2v0W^0A~Z7#-+kO1rRUoPN2x zaJIuT3EA(T+5*=_waSpK9RpxsKCI%XHEqC{;B0L;=$@lcnu*FZXGocwWcl9qhEBhM zyL*tPx!rY}3tw~(2sA|j9++MVJaBKPJ5PJ3N2Y8fWBoq5y<|E>c7Yz@yt%Ys5w);Z z?boZZg-?#sddmAWahvM!j;Ag5NOgRyH5tD-S9L8idA1JAC4KFCS^}Up?mGj>2hjq7 z9yzDlipZb?gDv@Ft1iH1Y-jdOmKv8uh@fC4oJmf43*-!R^yIXgn(^E$qR;nmin8E_ zWsNQ)ntFY7yJ&;6H5xZLsCCYL`EYQ{V`kpS_XAy;uGj=I^x;juAkYz^jn$W=X}nfP zrKQYX!S$>SRcYJ)az#J)=qHMLfXFi5T9Bf0F;#X#t8m>1h2gFw4f))|UAbh?wwwhtBKi=>agB zy!Cg6+HQJ_4I$sL;ic!MESfTj9OK5+OK;G3@TdH%q9Ra&vfFFj~`efI!+zJ5Wi zb>;I<9=ao))ST+V3_l~Zc6(G*R8Hw{mp=v|Wn0!dF)@*P{r;H_JixV&4Mt2g*U9`2 zsFjZg#=5(!>)91wkq8M8zaFsEGG^HsB=r$3j78zF!)FWkvUO=@KtV`n)pd)zpevVv zHxPL9^^pAGJP#WF@JvN6x(RZZ`E6=c-2}Sj?d8>G z&^)y*R9lllk&%Hw1O)B@QgH7(HX7rgog}sfq>Z2T(^K`IVipr10%2 zT6D+XKp7;NVu1QCKNM@QT4w6QxI)LPg+p=@p9W>sYWtxm%+@rx1Uw#$Fp}Of_*af5 zit=9SLza=Y6XaGG;@fsiRWbiU|E%s2O{vvau)v{%JwA`zW!=g3<6MF*8dVQ}_IqOt zwHO+B&CTMeVb)4ch2w$_)oX?p`f_Z99CvU~zT)*q9zIhkEH36{+xlfr+?o38hnJ2Y zMab?}n$j3LuVOg>Ie|b;_P|F+{b+boEMeoiBz%>^?Tp$r*;Wp-(r^}r8cC^UGuX~J z#qp7K^A^hc%u>O(svGIDH`aLLN^2whHf@GP<_v$8vA){k5c-dF=WB&w0NMxm!zwP0 z))Ej9m!BAvK|usShRO%GK=!|n87)j<*=22V&8i_2r9u-+rkXITJ?KSede$3AAA(qW zM77v6ITwxINY6=qA?voV>fFexHV*Aq6!A>vCAW*6QPcX^Ir+vzHKUHUoSW0rk}f~q z1)bgU!sAXFj5|QtfJqywu2_r;uf$4Ipk>yKumA*(UY@SB$dn5iq$sp43*j?%-vQgZ zj~|7w(o$KZa1V21a3WZvU)TY*KZ3o8j?IbSquK zW7({S)s`7OwF{}8X*+^SW2)v}!0hBMJpRG4i2(-|BA!dCS!$j6gCv zMIu5&`M7348f}I5TY9ddQmu3NRYC4_XC}8xfLb1D-L0ZyPK(l;k130+5nErLeOstu zITEG884iXfQQfUrqot6rK6^LB{k(G0wjr3zK=NEh-N716arFu&9nZv2|)yq+w=h~KYWNfnH~k$?{OKFqg?S}HPsoYvc4W#*LYUrAZ%#Lf|GS#Qq_OmYka z$*Y3NljbfC;5#Rj4QRQ(fg902yoGe_ni+JBa_iLMPyktfmmpE!I-H4T)^Mlk+f&sg ziKIx!huc^Dat=yDRK=N}eEDY?Ywtvah;N_o0#^F;bQT?*XyZ)!#`T`8ZHFEMF%U5S z&+7|oxFZjkb@U5KrAC_{&Ik__OW6?8I5I-_uPo_`C<`~`lbc&NHTcsn48ZUYLe%PL z>lBNm!NpxvKcw!&?1=WG7_%AvSk_dLq~_G?z2=?qr78JowF$Ax8yvpxW>8-xJaI-2m zUso$q5HE9p^HwuQSN_j|{E=;p3H6cLvd3h~vc8x-GLcdo z&?dS|fK+a_YS9?6q!7{(soojVXV_z0JJC`g-s85=WKRe-0YJ=^W;y?qO{dsgaY?wm z8%nKhk5psr8B%Py=1jq4%@8E38ZR5E&2tnpn!%0}WkOqNftY6&(oo% z(;B_fvfxoXYqnL)rDM5ZvH zYHGxW8W~j@@6ns()@^r9wsb0$d*EJ=5)&_5IA8Uf+OFG$9%(QnN%bApyexD|*Jj^Pj@#Y^hATQ^S zhUD36@4oR)$OobV<7IAQyKW#(o`Hr2lxYMMXsvata)%%;hBRLVMl}}Oz-h&IGm>)~ z8a=4NnO96~GF%*LO>4tu>@Ekh@=d_f5(W5219WdAl1)tIAe?7b&s-jkZpU#QtWB@g zI!Jed2~jmVAD+Qxx)vsii~C8Z1(DK|?Z)P9iv*lvauO;-v^gK^G-O4&obG=bOgsu@ zG_ga5%@xRV=J-ePnV5X*`YKbm3J*8bp)hYiJ(rdnc`xyx@UreO)7B(!ms69sHnM6-9zB z#Cz75w0o5dIiwOrWunN+S|sJVVl%Y|wb#%HgB60K-OGFreQ?I5o$%i|xh@hwtVM35 z-3uyAvoL}(>RwgMa01ON3HXp%>h10Vhb$BL9CrQPpEJtUOK)CJnNzY=@KJ^Y$c95y5Pl~XyX=NFoNZ48q z1X|n<%Poh^wSD0CSF`7y0o5#+x&W4)SvXyN-R3EHYMJR&$&DDoyee>3;o;{D{Kt|H z!Wqt%J~YkZr4q8l@m!*^CE*dtmoYg0%6N+745k0Fv>tHXXESz&COY8bN|sm~f<@!( z_1|~bFHCl%mQnUf9ZF-QLNE={BmU5(+exA!?bVRzf;xL4^%zA3=T*39e_FCgK7-_l z;yCLpTAcaj z+hDA!BLsEF9}d?rxDek2fzXkf+ui)VohJkWC+`&auoAPtWVF*BcFr}e1r>$`P!#{% zbjjf`$^d&P*FS4Ba^c}zW3ODbvh+kV&&62LB?CX-BXf?zb-p(GBcq=h#4Eo+eLTSM z)D$GQIjNEFNfcRTuX;KA5fgaGDI~;@afX00osOSe$*b)g*nA$dw(NzR#@2?6yvOGA z3>ZiwDaz7f2F5&h6j-&~ie{`XKECoaY%31wD4~7?&7QUOEs^Ll>t~e%UT7w3g@sC@ z&z|w_0oGiHw0Kexc1b#}u2I$}4UbCHYN^(a^r?I1K!XFKMisa;o~d^alv_fFbHXz1 zjaXcr!)L-IGkO*pG-uYQkzAT7yfarS3vdQjn8W@UznY#Eswod zqPQ&S;(|QN?N1?1+@ZhE0vQ@R1Z~CC{OscQiB@!p({GL^QUmJeEaVUI89|@M7xe6i zwY4>lP1e-qFb07v8J`xbN!5>8GQbUXe*?6xZTyFUErIBU!RNrA zpOBVJ!2&N$*W%ACw0`tAKV3K_{?Slu{m0Ia>-RDB!|l5$0FbS;n2*c)0HnL;&IRCK zT%M{6Alu)rgqQxc)o? zh(33eeblL62t+vng(6skzU3IJ(-(MhNmZQbER#Goc$; zm&xqtqDpF1~*=mTES2jz-^$V3S6>q1LmDGoa~$h_`(1V?q@j|%d9l_ zisH67a@*3DbVjF#Bi69qLyol;(o+3pNNh^z7Zv)Mzn8l;d}H`4T5zkOs+^wLGkBzf z;NS@!Ele*Ub|qtJ$hH4KvtlG8O)r_OFVujj@hwLjY}HPUJoN5Qth#e&mZ_>ed`{JJ z$d7YX$NIZP69A*H?hi#|rRH}X)sE`LJe;DLNj@3*gy8mm!I zC7ZZ;N6qW_O@=XtAvv0nX2?mQw$h$dEV8U~ktaZYDbU|`PdmM{f<}0#swSHKiXxgm zP!QvXG`ab%d)*Z&P#Fc((k$cMvv+&t&&EG4#}w{UXd3oOvG2)Z=r-ZfYWWo|HS6?5 zE+wDoZFIEMM>9W^VqG!s;XbTp&=2)|us}m0f=UVpZ2IG5SDi=oK*1<%Ec0{weR? z%du(NN$n%o;IeuvBdWy_8R%O6hF_77CL-n?>w<9h{meBoTq(*zQ4YRbPYov3$eQM4 zL~gQ8<_Rkz)P-rekeQR52^K!eHh;p=@7Ej=mslBP)V<32ydSADWxcE79Li{B^S zLFjfSmk)yn76=!x+EM0`8FpE7v2Z;wy}Hctu}&Z3#iSayyVjh-EXYY$j*a;ZjGu4P z;*E-mUQyRjKOAi|pFIpa`c2eb@7naK4xxh#!8(kp!}x)n-n{b4ikS%A4*a;>+09z4 zXAPfum0CpG1)ZpKV0$PQ+6Umm3Q=g8fI79~GC(=hqKUlSWHujF{UR+{mtM25jXQ6v zk-tRGgTCixN@=TaEDwiI#frWy@YIN$%|`nMWX4cl$OMwJd28*W!F`IN!*Gmztw}-j4(A=pmI{dk>3N0>9Ou9wQTJze`eMg(#8cclCa6{au`KQPNU(pkFTYJ zL)KuD=45x|y}b=G-^9fW;?onI>cpy!5hCptp`(8%P>+TyIHgPF@~y<=9%8$ow32~( zjl?`>0LRW>#_G0-j$AvlFcKBEv!pV3<=o1XebMels62#2>V&cp0h27a`MT~xk#CVl zsVw=lZ~-&Xv2w%)@*dl6A6~B=x;ik;>c6e0yyRKWa2XG5-|!4T3(C5`n=^1{Y%lMq zYSd(88I&W|u#3>i%=q4jQ$!uNOK3t+vR~-z_QGqPjM^TrKv_wIPNcK&n;^Gnm-zQ2w%-#aEYZKv?o zM&Gq0{O5ec{lpzj=YLt5-}UpsCkKS@7E%^^(9{{)0z8KuPWqPi-uu%@uZ{7?*}Aq6w@RQOWW}o7Yzo=_VrY5j=$IZa@9hQW7Bjvck`^*Tlz!n-@b8pL} z;<3tjf`aou@fW3H9X3IEAuIgmJfSIzka4AVw;Z62>mrAddxBK;hB)I(BShDh&^%oI zQ!aY?p^bJzFgGK$(O&Nx^&gY=yCa**#C(n)*$3&ZB!OmcBH<;)C!sKhkQKrA*bpnu zQOBMQ7+9Qh7MTm*u{WR&fzg}CzMwYM*TsrwyT$p?Pv>@!0{`r_@ptbTR9|JM5T0RA zXZ_J*d`d@NI!X8O6WD(7)Pf*tX6aK$0=h$cAgpud;&tlC&1I4g_&xH7vRvxLIio}5 zm^ z`X(B@UP&(Yin3!<1e6v==OFI#H1yx5$@4d2W)6@Qhid(0u#@xtq*>QVV!d6%$vb5I z?bB~1CAu13x$fjNrgP2xJbG$=MeW#i#&knOvQ^Wb`&Px~m!JRK_Im&CHv26l3HOb8 zhpTydZ+7-KaCR?}MNTnkf23?gdH<7us6KyM=0SGLL1XY}P5buuTAImCy7hk=D@a~u zq#u2DKb-GqY+8l5lUH96L^ylYo?m$4hhKR3|I`jh5xeUY7&`Fxb;-*sPiz@(UYT#3 z;t>iThFP3KZ_RAOJTslRKSs)nQ6k1H$Q<<;D=Dz4zt7m-Y7ty5aY>QOm@@=fn>!i4 zSvs?%RlS{hW^|n6Jh3QK^KcN7YzYtg5TEt9Q9S$ZQLmA^=No-uyRQb7+?jwOG+caduIZmPlicIE!==#LQu%$+-LBOwMy~xeK zW;!}?MbTn^p3i9hJ1fBRA}^*jV|#Z<{lf=tPw+U}e?Q=ze@WVlEOeiO9amPU^mE=J zWi4YENPD#Y$W2r^;zw;Iq4^I%w3I4^Qzv*E7%jW2hG93w>jdgE?+zs9Q^vOaY}qHD zHJn3H=Fi`ORVn8)_xrz(B8Lx0ymAlIY7@Ud18nr8_I^Ou-OvQ16%+5RKT1o^Iv-52 z-$&ka^jyktHul2+KczbWq@OcwR?jKBxKl<@tTX5KCB@h`ec6#$MSB9E5B5rm|2Crr zIq?qpw*QIv9ervqci^>Ru+bjF>os#vr9=Klv9v_P4CApsnZjo0UWSs$?&SE;8Ece{ zT?eY8yZq_pu81z-DM5dG4iUVql-0^U59Chl<1YW{!gHNDx;~%&$KmI}+fJsUpD6A0 zG8$2){5@G#`y$W>GUGGNtCpTPB#1epneV~AbUH7N7~8z$S9e-K`{6pCTlAc|Om8;CcPNvJ-tccPSEB~m30bTGYeV4%-@V2V9yr+SCH>;MS z$P$gWV*R(Pm0dGPm|-Y2I#iI8ZjD|knf@QU#QsiswlKqt=yn+lOUX2c zU$)M^bcuXd_`#X+wMG2p`)=1!UExHn^uv+6EDMm8e)JeE%hU@|5t?SF$tNCgCiWzG zyp`ZQUny$WvQkXwMoAy0HY&*U+Z<@UTc^3!?fm_2RzPv)FCMvhAEB8 z|HKRaxA-KJH&;F2d|XxaVB8I$aN$+q{XcHIDy$k*73lJ7{KcymFI~E%XYijA?k6Kz Value: true - Alpha: 1 - Autocompute Intensity Bounds: false + Autocompute Intensity Bounds: true Autocompute Value Bounds: Max Value: 10 Min Value: -10 Value: true Axis: Z - Channel Name: radial_speed + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 204; 0; 0 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Selectable: true + Size (Pixels): 15 + Size (m): 0.009999999776482582 + Style: Points + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /smart_radar/can_targets_1 + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: heading Class: rviz_default_plugins/PointCloud2 Color: 255; 255; 255 Color Transformer: Intensity @@ -60,30 +105,56 @@ Visualization Manager: Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 20 + Max Intensity: -999999 Min Color: 0; 0; 0 - Min Intensity: -20 + Min Intensity: 999999 Name: PointCloud2 Position Transformer: XYZ - Selectable: false - Size (Pixels): 5 - Size (m): 0.20000000298023224 - Style: Points + Selectable: true + Size (Pixels): 3 + Size (m): 1 + Style: Boxes Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /smart_radar/targets_0 + Value: /smart_radar/port_objects_0 Use Fixed Frame: true Use rainbow: true Value: true - - Class: rviz_default_plugins/Axes + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 Enabled: true - Length: 5 - Name: Axes - Radius: 0.5 - Reference Frame: + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 1 + Style: Tiles + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /smart_radar/port_targets_0 + Use Fixed Frame: true + Use rainbow: true Value: true Enabled: true Global Options: @@ -92,6 +163,8 @@ Visualization Manager: Frame Rate: 30 Name: root Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true - Class: rviz_default_plugins/MoveCamera - Class: rviz_default_plugins/Select - Class: rviz_default_plugins/FocusCamera @@ -110,7 +183,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /move_base_simple/goal + Value: /goal_pose - Class: rviz_default_plugins/PublishPoint Single click: true Topic: @@ -126,43 +199,47 @@ Visualization Manager: Views: Current: Class: rviz_default_plugins/Orbit - Distance: 66.64474487304688 + Distance: 197.11245727539062 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: 29.421253204345703 - Y: 3.1301658153533936 - Z: 12.849743843078613 + X: 33.84825134277344 + Y: -4.720839023590088 + Z: 7.3445963859558105 Focal Shape Fixed Size: true Focal Shape Size: 0.05000000074505806 Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 1.5697963237762451 + Pitch: 1.5047965049743652 Target Frame: Value: Orbit (rviz) - Yaw: 3.140397071838379 + Yaw: 3.1354000568389893 Saved: ~ Window Geometry: Displays: collapsed: false Height: 2090 Hide Left Dock: false - Hide Right Dock: true - QMainWindow State: 000000ff00000000fd0000000400000000000007d7000007c4fc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006a00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000045000001b8000000e800fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000026005400610072006700650074004c0069007300740020005200650063006f007200640065007201000002040000049c0000010e00fffffffb000000340053006d00610072007400200043006f006d006d0061006e006400200043006f006e0066006900670075007200610074006f007201000006a7000001620000016200ffffff000000010000010f00000383fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b00000383000000be00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d0065010000000000000450000000000000000000000722000007c400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Hide Right Dock: false + QMainWindow State: 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 Selection: collapsed: false Smart Command Configurator: collapsed: false - TargetList Recorder: + Smart Firmware Download: + collapsed: false + Smart Recorder: + collapsed: false + Smart Status: collapsed: false Tool Properties: collapsed: false Views: - collapsed: true + collapsed: false Width: 3840 X: 0 Y: 33 diff --git a/smart_rviz_plugin/include/smart_rviz_plugin/smart_download.hpp b/smart_rviz_plugin/include/smart_rviz_plugin/smart_download.hpp index 6622182..7b2c464 100644 --- a/smart_rviz_plugin/include/smart_rviz_plugin/smart_download.hpp +++ b/smart_rviz_plugin/include/smart_rviz_plugin/smart_download.hpp @@ -7,6 +7,7 @@ #include #include #include +#include #include #include #include @@ -16,21 +17,55 @@ namespace smart_rviz_plugin { +/// +/// @brief The class for the firmware download onto the sensor. +/// +/// This class provides a graphical user interface (GUI) panel for downloading +/// firmware to a sensor within the RViz environment. It extends the rviz_common::Panel +/// class and includes functionalities for browsing firmware files, initiating the +/// download process, and displaying responses from the download service. +/// class SmartDownloadService : public rviz_common::Panel { Q_OBJECT public: + /// + /// @brief Constructor for the SmartDownloadService class. + /// + /// @param parent The parent widget. Defaults to nullptr. + /// SmartDownloadService(QWidget * parent = nullptr); private slots: - void onDownload(); - void onBrowse(); + /// + /// @brief Slot function to handle firmware download action. + /// + /// This function is triggered when the download button is pressed. It sends + /// a request to the firmware download service with the specified file path + /// and sensor ID. + /// + void download_firmware(); + + /// + /// @brief Slot function to handle file browsing action. + /// + /// This function is triggered when the browse button is pressed. It opens a + /// file dialog to allow the user to select a firmware file, and sets the file + /// path input field with the selected file. + /// + void browse_file(); private: + /// + /// @brief Initializes the panel's components and ROS2 client. + /// + /// This function sets up the GUI elements, initializes the ROS2 node and + /// client for the firmware download service, and connects the signals and + /// slots. + /// void initialize(); -private: rclcpp::Node::SharedPtr download_node; rclcpp::Client::SharedPtr download_client; @@ -38,6 +73,7 @@ private slots: QLineEdit * sensor_id_input; QPushButton * start_download_button; QPushButton * browse_button; + QTextEdit * response_text_edit; }; } // namespace smart_rviz_plugin diff --git a/smart_rviz_plugin/include/smart_rviz_plugin/smart_recorder.hpp b/smart_rviz_plugin/include/smart_rviz_plugin/smart_recorder.hpp index 84e9494..3b019fd 100644 --- a/smart_rviz_plugin/include/smart_rviz_plugin/smart_recorder.hpp +++ b/smart_rviz_plugin/include/smart_rviz_plugin/smart_recorder.hpp @@ -1,8 +1,11 @@ #ifndef SMART_RVIZ_PLUGIN__SMART_RECORDER_HPP_ #define SMART_RVIZ_PLUGIN__SMART_RECORDER_HPP_ +#include + #include #include +#include #include #include #include @@ -12,17 +15,19 @@ #include #include #include -#include #include #include +#include +#include #include +#include #include "std_msgs/msg/string.hpp" namespace smart_rviz_plugin { - -struct RecordedData { +struct TargetData +{ float range; float power; float azimuth_deg; @@ -37,44 +42,152 @@ struct RecordedData { uint32_t timestamp_nanosec; }; +struct ObjectData +{ + float x_pos; + float y_pos; + float z_pos; + float speed_abs; + float heading; + float length; + float quality; + float acceleration; + uint16_t object_id; + uint32_t timestamp_sec; + uint32_t timestamp_nanosec; +}; + +/// +/// @brief The class for the target and object recorder. +/// +/// This class provides a graphical user interface (GUI) panel for viewing +/// the sensor data within the RViz environment. It extends the rviz_common::Panel +/// class and includes functionalities for selecting, recording +/// and saving the sensor data as csv format. +/// class SmartRadarRecorder : public rviz_common::Panel { Q_OBJECT public: + /// + /// @brief Constructor for the SmartRadarRecorder class. + /// + /// @param parent The parent widget. Defaults to nullptr. + /// SmartRadarRecorder(QWidget * parent = nullptr); private slots: - void startRecording(); - void stopRecording(); - void saveDataToCSV(); - void checkForData(); - void updateTable(); + /// + /// @brief Slot function to start recording the sensor data being viewed. + /// + void start_recording(); -private: - void initializeRecorder(); - void callback(const sensor_msgs::msg::PointCloud2::SharedPtr msg, const std::string topic_name); - void updateRecordedData( - float range, float power, float azimuth_deg, float elevation_deg, float rcs, - float noise, float snr, float radial_speed, float azimuth_angle, - float elevation_angle, uint32_t timestamp_sec, uint32_t timestamp_nanosec); + /// + /// @brief Slot function to stop recording the sensor data. + /// + void stop_recording(); + + /// + /// @brief Slot function to save the recorded sensor data as csv fomrat. + /// + void save_data(); + + /// + /// @brief Slot function to check the data is being published. + /// + void check_data(); + + /// + /// @brief Slot function to update the table based on the topic selected. + /// + void update_table(); private: + /// + /// @brief Initializes the panel's components and ROS2 client. + /// + /// This function sets up the GUI elements, initializes the ROS2 node and + /// client for the recorder, and connects the signals and + /// slots. + /// + void initialize(); + + /// + /// @brief Subscribe to the port targets topics publisheb by the smartmicro_radar_node. + /// + void port_target_callback( + const sensor_msgs::msg::PointCloud2::SharedPtr msg, const std::string topic_name); + + /// + /// @brief Subscribe to the can targets topics publisheb by the smartmicro_radar_node. + /// + void can_target_callback( + const sensor_msgs::msg::PointCloud2::SharedPtr msg, const std::string topic_name); + + /// + /// @brief Subscribe to the port objects topics publisheb by the smartmicro_radar_node. + /// + void port_object_callback( + const sensor_msgs::msg::PointCloud2::SharedPtr msg, const std::string topic_name); + + /// + /// @brief Subscribe to the can objects topics publisheb by the smartmicro_radar_node. + /// + void can_object_callback( + const sensor_msgs::msg::PointCloud2::SharedPtr msg, const std::string topic_name); + + /// + /// @brief Subscribe to the raw image topic. + /// + void image_callback(const sensor_msgs::msg::CompressedImage::SharedPtr msg); + + /// + /// @brief Function to handle the data recording for target topics. + /// + void update_target_recorded_data( + float range, float power, float azimuth_deg, float elevation_deg, float rcs, float noise, + float snr, float radial_speed, float azimuth_angle, float elevation_angle, + uint32_t timestamp_sec, uint32_t timestamp_nanosec); + + /// + /// @brief Function to handle the data recording for objects topics. + /// + void update_object_recorded_data( + float x_pos, float y_pos, float z_pos, float speed_abs, float heading, float length, + float quality, float acceleration, uint16_t object_id, uint32_t timestamp_sec, + uint32_t timestamp_nanosec); + QTableWidget * table_data_; + QTableWidget * table_data_2_; QTableWidget * table_timestamps_; + QWidget * widget_1; + QWidget * widget_2; QSplitter * splitter_; QSplitter * horiz_splitter_; QComboBox * topic_dropdown_; + QComboBox * topic_dropdown_2_; QVBoxLayout * gui_layout_; + QVBoxLayout * vert_layout_1; + QVBoxLayout * vert_layout_2; QPushButton * start_button_; QPushButton * stop_button_; QPushButton * save_button_; + QString selectedTopic; QTimer * timer_; rclcpp::Node::SharedPtr node_; std::unordered_map::SharedPtr> subscribers_{}; - std::vector recorded_data; + std::unordered_map::SharedPtr> + object_subscribers_{}; + + rclcpp::Subscription::SharedPtr subscription_; + rclcpp::Publisher::SharedPtr publisher_; + + std::vector target_recorded_data; + std::vector object_recorded_data; std::string selected_topic_; + std::string selected_topic_2_; bool recording_active_{false}; }; diff --git a/smart_rviz_plugin/include/smart_rviz_plugin/smart_services.hpp b/smart_rviz_plugin/include/smart_rviz_plugin/smart_services.hpp index 9abebe1..40d30b9 100644 --- a/smart_rviz_plugin/include/smart_rviz_plugin/smart_services.hpp +++ b/smart_rviz_plugin/include/smart_rviz_plugin/smart_services.hpp @@ -1,11 +1,19 @@ #ifndef SMART_RVIZ_PLUGIN__SMART_SERVICES_HPP_ #define SMART_RVIZ_PLUGIN__SMART_SERVICES_HPP_ +#include #include +#include +#include +#include +#include +#include #include #include #include #include +#include +#include #include #include #include @@ -16,39 +24,98 @@ namespace smart_rviz_plugin { +/// +/// @brief The class for the sending instructions to the sensors. +/// +/// This class provides a graphical user interface (GUI) panel for sending +/// instructions to the sensor within the RViz environment. It extends the +/// rviz_common::Panel class and includes functionalities for selecting, viewing +/// and sending the sensor instructions. +/// class SmartRadarService : public rviz_common::Panel { Q_OBJECT public: + /// + /// @brief Constructor for the SmartRadarService class. + /// + /// @param parent The parent widget. Defaults to nullptr. + /// SmartRadarService(QWidget * parent = nullptr); private slots: - void onSendParam(); - void onSendCommand(); + /// + /// @brief Slot function to send a parameter instruction to the sensor. + /// + void on_send_param(); + + /// + /// @brief Slot function to send a command instruction to the sensor. + /// + void on_send_command(); + + /// + /// @brief Slot function to display instruction set of selected sensor model. + /// + void on_file_selected(int index); private: + /// + /// @brief Initializes the panel's components and ROS2 client. + /// + /// This function sets up the GUI elements, initializes the ROS2 node and + /// client for the instruction services, and connects the signals and + /// slots. + /// void initialize(); -private: - rclcpp::Node::SharedPtr client_node; - QLineEdit * param_name; - QLineEdit * param_value; - QLineEdit * sensor_id_value; - QLineEdit * command_name; - QLineEdit * command_value; - QLineEdit * command_sensor_id_value; + /// + /// @brief Read parameters from user interface json file. + /// + void read_param_json_data(); + + /// + /// @brief Read commands from user interface json file. + /// + void read_command_json_data(); + + /// + /// @brief Populate the table with the read json files. + /// + void populate_file_menu(); + + const QString current_directory = QDir::currentPath(); + QString param_json_file_path; + QString command_json_file_path; + + QLineEdit * command_value_line_edit; + QLineEdit * command_argument_line_edit; + + QVBoxLayout * main_layout; + QTabWidget * tab_widget; + QWidget * param_tab; + QLineEdit * param_name_line_edit; + QLineEdit * param_value_line_edit; + QLineEdit * param_min_line_edit; + QLineEdit * param_max_line_edit; + QLineEdit * param_sensor_id; + QLineEdit * command_name_line_edit; + QLineEdit * command_comment_line_edit; + QLineEdit * command_sensor_id; + QPushButton * send_param_button; QPushButton * send_command_button; - QTabWidget * tab_widget; - QWidget * set_mode_tab; - QWidget * send_command_tab; - QVBoxLayout * send_mode_layout; - QVBoxLayout * send_command_layout; + QTableWidget * param_table_widget; + QTableWidget * command_table_widget; + QWidget * command_tab; + QComboBox * file_selector_combo_box; + QTextEdit * response_text_edit; + + rclcpp::Node::SharedPtr client_node; rclcpp::Client::SharedPtr mode_client; rclcpp::Client::SharedPtr command_client; }; - } // namespace smart_rviz_plugin #endif // SMART_RVIZ_PLUGIN__SMART_SERVICES_HPP_ diff --git a/smart_rviz_plugin/include/smart_rviz_plugin/smart_status.hpp b/smart_rviz_plugin/include/smart_rviz_plugin/smart_status.hpp new file mode 100644 index 0000000..4ab2e1b --- /dev/null +++ b/smart_rviz_plugin/include/smart_rviz_plugin/smart_status.hpp @@ -0,0 +1,127 @@ +#ifndef SMART_RVIZ_PLUGIN__SMART_STATUS_HPP_ +#define SMART_RVIZ_PLUGIN__SMART_STATUS_HPP_ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "std_msgs/msg/string.hpp" +#include "umrr_ros2_msgs/msg/can_object_header.hpp" +#include "umrr_ros2_msgs/msg/can_target_header.hpp" +#include "umrr_ros2_msgs/msg/port_object_header.hpp" +#include "umrr_ros2_msgs/msg/port_target_header.hpp" + +namespace smart_rviz_plugin +{ +/// +/// @brief The class for the target and object headers. +/// +/// This class provides a graphical user interface (GUI) panel for viewing +/// the sensor header data within the RViz environment. It extends the rviz_common::Panel +/// class and includes functionalities for selecting, viewing +/// the sensor header data. +/// +class SmartRadarStatus : public rviz_common::Panel +{ + Q_OBJECT + +public: + /// + /// @brief Constructor for the SmartRadarStatus class. + /// + /// @param parent The parent widget. Defaults to nullptr. + /// + SmartRadarStatus(QWidget * parent = nullptr); + +private slots: + /// + /// @brief Slot function to update the table based on the topic selected. + /// + void update_table(); + + /// + /// @brief Slot function to check the data is being published. + /// + void check_data(); + +private: + /// + /// @brief Initializes the panel's components and ROS2 client. + /// + /// This function sets up the GUI elements, initializes the ROS2 node and + /// client for the status, and connects the signals and + /// slots. + /// + void initialize(); + + /// + /// @brief Subscribe to the port target headers publisheb by the smartmicro_radar_node. + /// + void port_targetheader_callback( + const umrr_ros2_msgs::msg::PortTargetHeader::SharedPtr msg, const std::string topic_name); + + /// + /// @brief Subscribe to the can target headers publisheb by the smartmicro_radar_node. + /// + void can_targetheader_callback( + const umrr_ros2_msgs::msg::CanTargetHeader::SharedPtr msg, const std::string topic_name); + + /// + /// @brief Subscribe to the port object headers publisheb by the smartmicro_radar_node. + /// + void port_objectheader_callback( + const umrr_ros2_msgs::msg::PortObjectHeader::SharedPtr msg, const std::string topic_name); + + /// + /// @brief Subscribe to the can object headers publisheb by the smartmicro_radar_node. + /// + void can_objectheader_callback( + const umrr_ros2_msgs::msg::CanObjectHeader::SharedPtr msg, const std::string topic_name); + + QTableWidget * table_data_; + QTableWidget * table_data_2_; + QTableWidget * table_timestamps_; + QSplitter * splitter_; + QComboBox * topic_dropdown_; + QVBoxLayout * gui_layout_; + QPushButton * start_button_; + QPushButton * stop_button_; + QPushButton * save_button_; + QTimer * timer_; + rclcpp::Node::SharedPtr node_; + std::string selected_topic_; + std::unordered_map< + std::string, rclcpp::Subscription::SharedPtr> + port_header_target_subscribers_{}; + std::unordered_map< + std::string, rclcpp::Subscription::SharedPtr> + can_header_target_subscribers_{}; + std::unordered_map< + std::string, rclcpp::Subscription::SharedPtr> + port_header_object_subscribers_{}; + std::unordered_map< + std::string, rclcpp::Subscription::SharedPtr> + can_header_object_subscribers_{}; +}; + +} // namespace smart_rviz_plugin + +#endif // SMART_RVIZ_PLUGIN__SMART_RECORDER_HPP_ diff --git a/smart_rviz_plugin/package.xml b/smart_rviz_plugin/package.xml index db9598a..0c7949a 100644 --- a/smart_rviz_plugin/package.xml +++ b/smart_rviz_plugin/package.xml @@ -2,7 +2,7 @@ smart_rviz_plugin - 1.0.0 + 2.0.0 TargetList Recorder shahrukh Apache 2.0 License diff --git a/smart_rviz_plugin/plugins_description.xml b/smart_rviz_plugin/plugins_description.xml index 21941a5..d7a4f89 100644 --- a/smart_rviz_plugin/plugins_description.xml +++ b/smart_rviz_plugin/plugins_description.xml @@ -1,6 +1,6 @@ The Smart TargetList Recorder. @@ -17,4 +17,10 @@ base_class_type="rviz_common::Panel"> The Smart Download. + + The Smart Status. + diff --git a/smart_rviz_plugin/src/smart_download.cpp b/smart_rviz_plugin/src/smart_download.cpp index 226b7a6..e776f2f 100644 --- a/smart_rviz_plugin/src/smart_download.cpp +++ b/smart_rviz_plugin/src/smart_download.cpp @@ -27,6 +27,10 @@ void SmartDownloadService::initialize() start_download_button = new QPushButton("Start Download", this); browse_button = new QPushButton("Browse", this); + response_text_edit = new QTextEdit(this); + response_text_edit->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding); + response_text_edit->setFixedSize(1200, 100); + QVBoxLayout * layout = new QVBoxLayout(this); layout->addWidget(new QLabel("File Path:")); layout->addWidget(file_path_input); @@ -34,13 +38,14 @@ void SmartDownloadService::initialize() layout->addWidget(new QLabel("Sensor ID:")); layout->addWidget(sensor_id_input); layout->addWidget(start_download_button); + layout->addWidget(response_text_edit); // Connect signals and slots - connect(start_download_button, &QPushButton::clicked, this, &SmartDownloadService::onDownload); - connect(browse_button, &QPushButton::clicked, this, &SmartDownloadService::onBrowse); + connect(start_download_button, SIGNAL(clicked()), this, SLOT(download_firmware())); + connect(browse_button, SIGNAL(clicked()), this, SLOT(browse_file())); } -void SmartDownloadService::onDownload() +void SmartDownloadService::download_firmware() { if (!download_client) { RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Failed to create download_client"); @@ -56,6 +61,8 @@ void SmartDownloadService::onDownload() return; } + start_download_button->setText("Downloading..."); + // Set up the request auto request = std::make_shared(); request->file_path = filePath.toStdString(); @@ -67,14 +74,20 @@ void SmartDownloadService::onDownload() if ( rclcpp::spin_until_future_complete(download_node, result) == rclcpp::FutureReturnCode::SUCCESS) { + QString response_msg = QString::fromStdString(result.get()->res); + response_text_edit->append("Download request sent.\n Response from sensor: " + response_msg); RCLCPP_INFO( - rclcpp::get_logger("rclcpp"), "Request successful. Response: %s", result.get()->res.c_str()); + rclcpp::get_logger("rclcpp"), "Request successful\n. Response: %s ", + result.get()->res.c_str()); + start_download_button->setText("Start Download"); } else { - RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Failed to call service firmware_download"); + RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Failed to download sensor firmware"); + response_text_edit->append("Failed to downlaod sensor firmware!"); + start_download_button->setText("Start Download"); } } -void SmartDownloadService::onBrowse() +void SmartDownloadService::browse_file() { QString filePath = QFileDialog::getOpenFileName(this, tr("Open File"), "", tr("All Files (*)")); if (!filePath.isEmpty()) { diff --git a/smart_rviz_plugin/src/smart_recorder.cpp b/smart_rviz_plugin/src/smart_recorder.cpp index cca346e..2b8acbf 100644 --- a/smart_rviz_plugin/src/smart_recorder.cpp +++ b/smart_rviz_plugin/src/smart_recorder.cpp @@ -1,46 +1,77 @@ #include "smart_rviz_plugin/smart_recorder.hpp" #include +#include #include +const double radToDeg = 180.0 / M_PI; namespace smart_rviz_plugin { SmartRadarRecorder::SmartRadarRecorder(QWidget * parent) : rviz_common::Panel(parent) { - initializeRecorder(); + initialize(); } -void SmartRadarRecorder::initializeRecorder() +void SmartRadarRecorder::initialize() { node_ = rclcpp::Node::make_shared("smart_radar_gui_node"); - // Retrieve available topics - auto topic_names_and_types = node_->get_topic_names_and_types(); - std::vector available_topics; - for (const auto & topic : topic_names_and_types) { - available_topics.push_back(topic.first); - } + subscription_ = node_->create_subscription( + "/ip_camera_front_right/image_raw/compressed", 10, + [this](const sensor_msgs::msg::CompressedImage::SharedPtr msg) { image_callback(msg); }); + + publisher_ = + node_->create_publisher("/ip_camera_front_right/image_raw", 10); // Reorder setup gui_layout_ = new QVBoxLayout(); topic_dropdown_ = new QComboBox(); topic_dropdown_->addItem("Select a Topic"); - // Create subscribers for selected topics - for (const auto & topic : available_topics) { - subscribers_[topic] = node_->create_subscription( - topic, 10, - [this, topic](const sensor_msgs::msg::PointCloud2::SharedPtr msg) { callback(msg, topic); }); - topic_dropdown_->addItem(QString::fromStdString(topic)); + // Retrieve available topics + auto topic_names_and_types = node_->get_topic_names_and_types(); + + // Create subscribers for selected topics + for (const auto & topic : topic_names_and_types) { + if (topic.first.find("port_targets") != std::string::npos) { + subscribers_[topic.first] = node_->create_subscription( + topic.first, 10, [this, topic](const sensor_msgs::msg::PointCloud2::SharedPtr msg) { + port_target_callback(msg, topic.first); + }); + + topic_dropdown_->addItem(QString::fromStdString(topic.first)); + } else if (topic.first.find("can_targets") != std::string::npos) { + subscribers_[topic.first] = node_->create_subscription( + topic.first, 10, [this, topic](const sensor_msgs::msg::PointCloud2::SharedPtr msg) { + can_target_callback(msg, topic.first); + }); + + topic_dropdown_->addItem(QString::fromStdString(topic.first)); + } else if (topic.first.find("port_objects") != std::string::npos) { + object_subscribers_[topic.first] = node_->create_subscription( + topic.first, 10, [this, topic](const sensor_msgs::msg::PointCloud2::SharedPtr msg) { + port_object_callback(msg, topic.first); + }); + + topic_dropdown_->addItem(QString::fromStdString(topic.first)); + } else if (topic.first.find("can_objects") != std::string::npos) { + object_subscribers_[topic.first] = node_->create_subscription( + topic.first, 10, [this, topic](const sensor_msgs::msg::PointCloud2::SharedPtr msg) { + can_object_callback(msg, topic.first); + }); + + topic_dropdown_->addItem(QString::fromStdString(topic.first)); + } } - connect(topic_dropdown_, SIGNAL(currentIndexChanged(int)), this, SLOT(updateTable())); + connect(topic_dropdown_, SIGNAL(currentIndexChanged(int)), this, SLOT(update_table())); + + // Table one layout table_data_ = new QTableWidget(); - table_data_->setColumnCount(10); + table_data_->setColumnCount(13); + table_data_->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding); table_data_->horizontalHeader()->setSectionResizeMode(QHeaderView::Stretch); - table_data_->setHorizontalHeaderLabels( - {"Range [m]", "Power [dB]", "AzimuthAngle [Deg]", "ElevationAngle [Deg]", "RCS [dB]", - "Noise [dB]", "SNR [dB]", "RadialSpeed [m/s]", "AzimuthAngle [rad]", "ElevationAngle [rad]"}); + table_timestamps_ = new QTableWidget(); table_timestamps_->setColumnCount(2); table_timestamps_->horizontalHeader()->setSectionResizeMode(QHeaderView::Stretch); @@ -58,31 +89,56 @@ void SmartRadarRecorder::initializeRecorder() gui_layout_->addWidget(horiz_splitter_); timer_ = new QTimer(); - connect(timer_, SIGNAL(timeout()), this, SLOT(checkForData())); + connect(timer_, SIGNAL(timeout()), this, SLOT(check_data())); timer_->start(20); start_button_ = new QPushButton("Record"); - connect(start_button_, SIGNAL(clicked()), this, SLOT(startRecording())); + connect(start_button_, SIGNAL(clicked()), this, SLOT(start_recording())); stop_button_ = new QPushButton("Stop Recording"); - connect(stop_button_, SIGNAL(clicked()), this, SLOT(stopRecording())); + connect(stop_button_, SIGNAL(clicked()), this, SLOT(stop_recording())); save_button_ = new QPushButton("Save Data as CSV"); - connect(save_button_, SIGNAL(clicked()), this, SLOT(saveDataToCSV())); + connect(save_button_, SIGNAL(clicked()), this, SLOT(save_data())); gui_layout_->addWidget(start_button_); gui_layout_->addWidget(stop_button_); gui_layout_->addWidget(save_button_); setLayout(gui_layout_); + + RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Recorder Plugin Created!"); +} + +void SmartRadarRecorder::image_callback(const sensor_msgs::msg::CompressedImage::SharedPtr msg) +{ + cv_bridge::CvImagePtr cv_ptr; + try { + cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8); + } catch (cv_bridge::Exception & e) { + RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "cv_bridge exception: %s", e.what()); + return; + } + + sensor_msgs::msg::Image ros_image; + ros_image.header = msg->header; + ros_image.height = cv_ptr->image.rows; + ros_image.width = cv_ptr->image.cols; + ros_image.encoding = sensor_msgs::image_encodings::BGR8; + ros_image.is_bigendian = false; + ros_image.step = sizeof(unsigned char) * cv_ptr->image.cols * cv_ptr->image.channels(); + ros_image.data.assign( + cv_ptr->image.data, cv_ptr->image.data + cv_ptr->image.total() * cv_ptr->image.elemSize()); + + publisher_->publish(ros_image); } -void SmartRadarRecorder::updateRecordedData( +void SmartRadarRecorder::update_target_recorded_data( float range, float power, float azimuth_deg, float elevation_deg, float rcs, float noise, - float snr, float radial_speed, float azimuth_angle, float elevation_angle, - uint32_t timestamp_sec, uint32_t timestamp_nanosec) + float snr, float radial_speed, float azimuth_angle, float elevation_angle, uint32_t timestamp_sec, + uint32_t timestamp_nanosec) { - RecordedData data; + TargetData data; data.range = range; data.power = power; data.azimuth_deg = azimuth_deg; @@ -96,10 +152,31 @@ void SmartRadarRecorder::updateRecordedData( data.timestamp_sec = timestamp_sec; data.timestamp_nanosec = timestamp_nanosec; - recorded_data.push_back(data); + target_recorded_data.push_back(data); } -void SmartRadarRecorder::callback( +void SmartRadarRecorder::update_object_recorded_data( + float x_pos, float y_pos, float z_pos, float speed_abs, float heading, float length, + float quality, float acceleration, uint16_t object_id, uint32_t timestamp_sec, + uint32_t timestamp_nanosec) +{ + ObjectData data; + data.x_pos = x_pos; + data.y_pos = y_pos; + data.z_pos = z_pos; + data.speed_abs = speed_abs; + data.heading = heading; + data.length = length; + data.quality = quality; + data.object_id = object_id; + data.acceleration = acceleration; + data.timestamp_sec = timestamp_sec; + data.timestamp_nanosec = timestamp_nanosec; + + object_recorded_data.push_back(data); +} + +void SmartRadarRecorder::port_target_callback( const sensor_msgs::msg::PointCloud2::SharedPtr msg, const std::string topic_name) { if (!selected_topic_.empty() && topic_name == selected_topic_) { @@ -107,48 +184,195 @@ void SmartRadarRecorder::callback( auto timestamp_nanosec = msg->header.stamp.nanosec; // Create iterators for the pc2 fields - sensor_msgs::PointCloud2ConstIterator iter_range(*msg, "range"); + sensor_msgs::PointCloud2ConstIterator iter_x(*msg, "x"); + sensor_msgs::PointCloud2ConstIterator iter_y(*msg, "y"); + sensor_msgs::PointCloud2ConstIterator iter_z(*msg, "z"); + sensor_msgs::PointCloud2ConstIterator iter_radial_speed(*msg, "radial_speed"); sensor_msgs::PointCloud2ConstIterator iter_power(*msg, "power"); + sensor_msgs::PointCloud2ConstIterator iter_rcs(*msg, "rcs"); + sensor_msgs::PointCloud2ConstIterator iter_noise(*msg, "noise"); + sensor_msgs::PointCloud2ConstIterator iter_snr(*msg, "snr"); sensor_msgs::PointCloud2ConstIterator iter_azimuth_angle(*msg, "azimuth_angle"); sensor_msgs::PointCloud2ConstIterator iter_elevation_angle(*msg, "elevation_angle"); + sensor_msgs::PointCloud2ConstIterator iter_range(*msg, "range"); + + table_data_->setRowCount(0); + + for (size_t i = 0; i < msg->height * msg->width; ++i, ++iter_x, ++iter_y, ++iter_z, + ++iter_radial_speed, ++iter_power, ++iter_rcs, ++iter_noise, ++iter_snr, + ++iter_azimuth_angle, ++iter_elevation_angle, ++iter_range) { + double azimuth_deg = *iter_azimuth_angle * radToDeg; + double elevation_deg = *iter_elevation_angle * radToDeg; + + // Update the recorded data + if (recording_active_) { + update_target_recorded_data( + *iter_range, *iter_power, azimuth_deg, elevation_deg, *iter_rcs, *iter_noise, *iter_snr, + *iter_radial_speed, *iter_azimuth_angle, *iter_elevation_angle, timestamp_sec, + timestamp_nanosec); + } + + // Add items to the table + int row_index = table_data_->rowCount(); + table_data_->insertRow(row_index); + table_data_->setItem(row_index, 0, new QTableWidgetItem(QString::number(*iter_x, 'f', 2))); + table_data_->setItem(row_index, 1, new QTableWidgetItem(QString::number(*iter_y, 'f', 2))); + table_data_->setItem(row_index, 2, new QTableWidgetItem(QString::number(*iter_z, 'f', 2))); + table_data_->setItem( + row_index, 3, new QTableWidgetItem(QString::number(*iter_radial_speed, 'f', 2))); + table_data_->setItem( + row_index, 4, new QTableWidgetItem(QString::number(*iter_power, 'f', 2))); + table_data_->setItem(row_index, 5, new QTableWidgetItem(QString::number(*iter_rcs, 'f', 2))); + table_data_->setItem( + row_index, 6, new QTableWidgetItem(QString::number(*iter_noise, 'f', 2))); + table_data_->setItem(row_index, 7, new QTableWidgetItem(QString::number(*iter_snr, 'f', 2))); + table_data_->setItem( + row_index, 8, new QTableWidgetItem(QString::number(azimuth_deg, 'f', 2))); + table_data_->setItem( + row_index, 9, new QTableWidgetItem(QString::number(elevation_deg, 'f', 2))); + table_data_->setItem( + row_index, 10, new QTableWidgetItem(QString::number(*iter_range, 'f', 2))); + table_data_->setItem( + row_index, 11, new QTableWidgetItem(QString::number(*iter_azimuth_angle, 'f', 2))); + table_data_->setItem( + row_index, 12, new QTableWidgetItem(QString::number(*iter_elevation_angle, 'f', 2))); + } + + // Update the timestamp table + table_timestamps_->setRowCount(0); + table_timestamps_->insertRow(0); + table_timestamps_->setItem(0, 0, new QTableWidgetItem(QString::number(timestamp_sec))); + table_timestamps_->setItem(0, 1, new QTableWidgetItem(QString::number(timestamp_nanosec))); + } +} + +void SmartRadarRecorder::can_target_callback( + const sensor_msgs::msg::PointCloud2::SharedPtr msg, const std::string topic_name) +{ + if (!selected_topic_.empty() && topic_name == selected_topic_) { + auto timestamp_sec = msg->header.stamp.sec; + auto timestamp_nanosec = msg->header.stamp.nanosec; + + // Create iterators for the pc2 fields + sensor_msgs::PointCloud2ConstIterator iter_x(*msg, "x"); + sensor_msgs::PointCloud2ConstIterator iter_y(*msg, "y"); + sensor_msgs::PointCloud2ConstIterator iter_z(*msg, "z"); + sensor_msgs::PointCloud2ConstIterator iter_radial_speed(*msg, "radial_speed"); + sensor_msgs::PointCloud2ConstIterator iter_power(*msg, "power"); sensor_msgs::PointCloud2ConstIterator iter_rcs(*msg, "rcs"); sensor_msgs::PointCloud2ConstIterator iter_noise(*msg, "noise"); sensor_msgs::PointCloud2ConstIterator iter_snr(*msg, "snr"); - sensor_msgs::PointCloud2ConstIterator iter_radial_speed(*msg, "radial_speed"); + sensor_msgs::PointCloud2ConstIterator iter_azimuth_angle(*msg, "azimuth_angle"); + sensor_msgs::PointCloud2ConstIterator iter_elevation_angle(*msg, "elevation_angle"); + sensor_msgs::PointCloud2ConstIterator iter_range(*msg, "range"); table_data_->setRowCount(0); - // Conversion from radians to degrees - const double radToDeg = 180.0 / M_PI; - double azimuth_deg, elevation_deg; - - for (size_t i = 0; i < msg->height * msg->width; ++i, ++iter_range, ++iter_power, - ++iter_azimuth_angle, ++iter_elevation_angle, ++iter_rcs, ++iter_noise, - ++iter_snr) { - azimuth_deg = *iter_azimuth_angle * radToDeg; - elevation_deg = *iter_elevation_angle * radToDeg; + for (size_t i = 0; i < msg->height * msg->width; ++i, ++iter_x, ++iter_y, ++iter_z, + ++iter_radial_speed, ++iter_power, ++iter_rcs, ++iter_noise, ++iter_snr, + ++iter_azimuth_angle, ++iter_elevation_angle, ++iter_range) { + double azimuth_deg = *iter_azimuth_angle * radToDeg; + double elevation_deg = *iter_elevation_angle * radToDeg; // Update the recorded data if (recording_active_) { - updateRecordedData( + update_target_recorded_data( *iter_range, *iter_power, azimuth_deg, elevation_deg, *iter_rcs, *iter_noise, *iter_snr, *iter_radial_speed, *iter_azimuth_angle, *iter_elevation_angle, timestamp_sec, timestamp_nanosec); } + + // Add items to the table + int row_index = table_data_->rowCount(); + table_data_->insertRow(row_index); + table_data_->setItem(row_index, 0, new QTableWidgetItem(QString::number(*iter_x, 'f', 2))); + table_data_->setItem(row_index, 1, new QTableWidgetItem(QString::number(*iter_y, 'f', 2))); + table_data_->setItem(row_index, 2, new QTableWidgetItem(QString::number(*iter_z, 'f', 2))); + table_data_->setItem( + row_index, 3, new QTableWidgetItem(QString::number(*iter_radial_speed, 'f', 2))); + table_data_->setItem( + row_index, 4, new QTableWidgetItem(QString::number(*iter_power, 'f', 2))); + table_data_->setItem(row_index, 5, new QTableWidgetItem(QString::number(*iter_rcs, 'f', 2))); + table_data_->setItem( + row_index, 6, new QTableWidgetItem(QString::number(*iter_noise, 'f', 2))); + table_data_->setItem(row_index, 7, new QTableWidgetItem(QString::number(*iter_snr, 'f', 2))); + table_data_->setItem( + row_index, 8, new QTableWidgetItem(QString::number(azimuth_deg, 'f', 2))); + table_data_->setItem( + row_index, 9, new QTableWidgetItem(QString::number(elevation_deg, 'f', 2))); + table_data_->setItem( + row_index, 10, new QTableWidgetItem(QString::number(*iter_range, 'f', 2))); + table_data_->setItem( + row_index, 11, new QTableWidgetItem(QString::number(*iter_azimuth_angle, 'f', 2))); + table_data_->setItem( + row_index, 12, new QTableWidgetItem(QString::number(*iter_elevation_angle, 'f', 2))); + } + + // Update the timestamp table + table_timestamps_->setRowCount(0); + table_timestamps_->insertRow(0); + table_timestamps_->setItem(0, 0, new QTableWidgetItem(QString::number(timestamp_sec))); + table_timestamps_->setItem(0, 1, new QTableWidgetItem(QString::number(timestamp_nanosec))); + // } + } +} + +void SmartRadarRecorder::port_object_callback( + const sensor_msgs::msg::PointCloud2::SharedPtr msg, const std::string topic_name) +{ + if (!selected_topic_.empty() && topic_name == selected_topic_) { + auto timestamp_sec = msg->header.stamp.sec; + auto timestamp_nanosec = msg->header.stamp.nanosec; + + // Create iterators for the pc2 fields + sensor_msgs::PointCloud2ConstIterator iter_x(*msg, "x"); + sensor_msgs::PointCloud2ConstIterator iter_y(*msg, "y"); + sensor_msgs::PointCloud2ConstIterator iter_z(*msg, "z"); + sensor_msgs::PointCloud2ConstIterator iter_speed_absolute(*msg, "speed_absolute"); + sensor_msgs::PointCloud2ConstIterator iter_heading(*msg, "heading"); + sensor_msgs::PointCloud2ConstIterator iter_length(*msg, "length"); + sensor_msgs::PointCloud2ConstIterator iter_mileage(*msg, "mileage"); + sensor_msgs::PointCloud2ConstIterator iter_quality(*msg, "quality"); + sensor_msgs::PointCloud2ConstIterator iter_acceleration(*msg, "acceleration"); + sensor_msgs::PointCloud2ConstIterator iter_object_id(*msg, "object_id"); + sensor_msgs::PointCloud2ConstIterator iter_idle_cycles(*msg, "idle_cycles"); + sensor_msgs::PointCloud2ConstIterator iter_spline_idx(*msg, "spline_idx"); + sensor_msgs::PointCloud2ConstIterator iter_object_class(*msg, "object_class"); + sensor_msgs::PointCloud2ConstIterator iter_status(*msg, "status"); + + table_data_->setRowCount(0); + size_t num_points = msg->height * msg->width; + + for (size_t i = num_points; i > 0; --i, ++iter_x, ++iter_y, ++iter_z, ++iter_speed_absolute, + ++iter_heading, ++iter_length, ++iter_mileage, ++iter_quality, ++iter_acceleration, + ++iter_object_id, ++iter_idle_cycles, ++iter_spline_idx, ++iter_object_class, + ++iter_status) { + double heading_deg = *iter_heading * radToDeg; + + // Update the recorded data + if (recording_active_) { + update_object_recorded_data( + *iter_x, *iter_y, *iter_z, *iter_speed_absolute, *iter_heading, *iter_length, + *iter_quality, *iter_acceleration, *iter_object_id, timestamp_sec, timestamp_nanosec); + } + // Add items to the table - table_data_->insertRow(0); - table_data_->setItem(0, 0, new QTableWidgetItem(QString::number(*iter_range, 'f', 2))); - table_data_->setItem(0, 1, new QTableWidgetItem(QString::number(*iter_power, 'f', 2))); - table_data_->setItem(0, 2, new QTableWidgetItem(QString::number(azimuth_deg, 'f', 2))); - table_data_->setItem(0, 3, new QTableWidgetItem(QString::number(elevation_deg, 'f', 2))); - table_data_->setItem(0, 4, new QTableWidgetItem(QString::number(*iter_rcs, 'f', 2))); - table_data_->setItem(0, 5, new QTableWidgetItem(QString::number(*iter_noise, 'f', 2))); - table_data_->setItem(0, 6, new QTableWidgetItem(QString::number(*iter_snr, 'f', 2))); - table_data_->setItem(0, 7, new QTableWidgetItem(QString::number(*iter_radial_speed, 'f', 2))); - table_data_->setItem( - 0, 8, new QTableWidgetItem(QString::number(*iter_azimuth_angle, 'f', 2))); - table_data_->setItem( - 0, 9, new QTableWidgetItem(QString::number(*iter_elevation_angle, 'f', 2))); + int row_index = table_data_->rowCount(); + table_data_->insertRow(row_index); + table_data_->setItem(row_index, 0, new QTableWidgetItem(QString::number(*iter_x, 'f', 2))); + table_data_->setItem(row_index, 1, new QTableWidgetItem(QString::number(*iter_y, 'f', 2))); + table_data_->setItem(row_index, 2, new QTableWidgetItem(QString::number(*iter_z, 'f', 2))); + table_data_->setItem( + row_index, 3, new QTableWidgetItem(QString::number(*iter_speed_absolute, 'f', 2))); + table_data_->setItem( + row_index, 4, new QTableWidgetItem(QString::number(heading_deg, 'f', 2))); + table_data_->setItem( + row_index, 5, new QTableWidgetItem(QString::number(*iter_length, 'f', 2))); + table_data_->setItem( + row_index, 6, new QTableWidgetItem(QString::number(*iter_quality, 'f', 2))); + table_data_->setItem( + row_index, 7, new QTableWidgetItem(QString::number(*iter_acceleration, 'f', 2))); + table_data_->setItem(row_index, 8, new QTableWidgetItem(QString::number(*iter_object_id))); } // Update the timestamp table @@ -159,31 +383,112 @@ void SmartRadarRecorder::callback( } } -void SmartRadarRecorder::updateTable() +void SmartRadarRecorder::can_object_callback( + const sensor_msgs::msg::PointCloud2::SharedPtr msg, const std::string topic_name) +{ + if (!selected_topic_.empty() && topic_name == selected_topic_) { + auto timestamp_sec = msg->header.stamp.sec; + auto timestamp_nanosec = msg->header.stamp.nanosec; + + // Create iterators for the pc2 fields + sensor_msgs::PointCloud2ConstIterator iter_x(*msg, "x"); + sensor_msgs::PointCloud2ConstIterator iter_y(*msg, "y"); + sensor_msgs::PointCloud2ConstIterator iter_z(*msg, "z"); + sensor_msgs::PointCloud2ConstIterator iter_speed_abs(*msg, "speed_absolute"); + sensor_msgs::PointCloud2ConstIterator iter_heading(*msg, "heading"); + sensor_msgs::PointCloud2ConstIterator iter_length(*msg, "length"); + sensor_msgs::PointCloud2ConstIterator iter_quality(*msg, "quality"); + sensor_msgs::PointCloud2ConstIterator iter_acceleration(*msg, "acceleration"); + sensor_msgs::PointCloud2ConstIterator iter_object_id(*msg, "object_id"); + sensor_msgs::PointCloud2ConstIterator iter_status(*msg, "status"); + + table_data_->setRowCount(0); + + size_t num_points = msg->height * msg->width; + + for (size_t i = num_points; i > 0; --i, ++iter_x, ++iter_y, ++iter_z, ++iter_speed_abs, + ++iter_heading, ++iter_length, ++iter_quality, ++iter_acceleration, + ++iter_object_id) { + // Update the recorded data + if (recording_active_) { + update_object_recorded_data( + *iter_x, *iter_y, *iter_z, *iter_speed_abs, *iter_heading, *iter_length, *iter_quality, + *iter_acceleration, *iter_object_id, timestamp_sec, timestamp_nanosec); + } + + int row_index = table_data_->rowCount(); + table_data_->insertRow(row_index); + table_data_->setItem(row_index, 0, new QTableWidgetItem(QString::number(*iter_x, 'f', 2))); + table_data_->setItem(row_index, 1, new QTableWidgetItem(QString::number(*iter_y, 'f', 2))); + table_data_->setItem(row_index, 2, new QTableWidgetItem(QString::number(*iter_z, 'f', 2))); + table_data_->setItem( + row_index, 3, new QTableWidgetItem(QString::number(*iter_speed_abs, 'f', 2))); + table_data_->setItem( + row_index, 4, new QTableWidgetItem(QString::number(*iter_heading, 'f', 2))); + table_data_->setItem( + row_index, 5, new QTableWidgetItem(QString::number(*iter_length, 'f', 2))); + table_data_->setItem( + row_index, 6, new QTableWidgetItem(QString::number(*iter_quality, 'f', 2))); + table_data_->setItem( + row_index, 7, new QTableWidgetItem(QString::number(*iter_acceleration, 'f', 2))); + table_data_->setItem( + row_index, 8, new QTableWidgetItem(QString::number(*iter_object_id, 'f', 2))); + } + + // Update the timestamp table + table_timestamps_->setRowCount(0); + table_timestamps_->insertRow(0); + table_timestamps_->setItem(0, 0, new QTableWidgetItem(QString::number(timestamp_sec))); + table_timestamps_->setItem(0, 1, new QTableWidgetItem(QString::number(timestamp_nanosec))); + } +} + +void SmartRadarRecorder::update_table() { - // Clear the table when a new topic is selected table_data_->setRowCount(0); selected_topic_ = topic_dropdown_->currentText().toStdString(); + if (selected_topic_.find("port_targets") != std::string::npos) { + table_data_->setHorizontalHeaderLabels( + {"X_pos [m]", "Y_pos [m]", "Z_pos [m]", "RadialSpeed [m/s]", "Power [dB]", "RCS [m^2]", + "Noise [dB]", "SNR [dB]", "AzimuthAngle [Deg]", "ElevationAngle [Deg]", "Range [m]", + "AzimuthAngle [rad]", "ElevationAngle [rad]"}); + } else if (selected_topic_.find("can_targets") != std::string::npos) { + table_data_->setRowCount(0); + table_data_->setHorizontalHeaderLabels( + {"X_pos [m]", "Y_pos [m]", "Z_pos [m]", "RadialSpeed [m/s]", "Power [dB]", "RCS [dB]", + "Noise [dB]", "SNR [dB]", "AzimuthAngle [Deg]", "ElevationAngle [Deg]", "Range [m]", + "AzimuthAngle [rad]", "ElevationAngle [rad]"}); + } else if (selected_topic_.find("can_objects") != std::string::npos) { + table_data_->setRowCount(0); + table_data_->setHorizontalHeaderLabels( + {"X_pos [m]", "Y_pos [m]", "Z_pos [m]", "AbsoluteSpeed [m/s]", "Heading [Deg]", + "ObjectLength [m]", "Quality", "Acceleration [m/s^2]", "Object_ID", "", "", "", ""}); + } else if (selected_topic_.find("port_objects") != std::string::npos) { + table_data_->setRowCount(0); + table_data_->setHorizontalHeaderLabels( + {"PosX [m]", "PosY [m]", "PosZ [m]", "AbsoluteSpeed [m/s]", "Heading [Deg]", + "ObjectLength [m]", "Quality", "Acceleration [m/s^2]", "ObjectId", "", "", "", ""}); + } } -void SmartRadarRecorder::startRecording() +void SmartRadarRecorder::start_recording() { qDebug() << "Recording started!"; recording_active_ = true; start_button_->setText("Recording..."); } -void SmartRadarRecorder::stopRecording() +void SmartRadarRecorder::stop_recording() { qDebug() << "Recording stopped!"; recording_active_ = false; start_button_->setText("Record"); } -void SmartRadarRecorder::saveDataToCSV() +void SmartRadarRecorder::save_data() { qDebug() << "Saving data to CSV!"; - if (!recorded_data.empty()) { + if (!target_recorded_data.empty() || !object_recorded_data.empty()) { QFileDialog file_dialog; QString file_path = file_dialog.getSaveFileName(this, "Save Data", "", "CSV Files (*.csv);;All Files (*)"); @@ -192,13 +497,15 @@ void SmartRadarRecorder::saveDataToCSV() QFile csvfile(file_path); if (csvfile.open(QIODevice::WriteOnly | QIODevice::Text)) { QTextStream csv_writer(&csvfile); - csv_writer << "Range [m], Power [dB], AzimuthAngle [Deg], ElevationAngle [Deg], RCS [dB], " - "Noise [dB], SNR [dB], " - "RadialSpeed [m/s], ElevationAngle [rad], AzimuthAngle [rad], " - "TimestampSec, TimestampNanoSec\n"; + csv_writer + << "Type, Range [m], Power [dB], AzimuthAngle [Deg], ElevationAngle [Deg], RCS [dB], " + "Noise [dB], SNR [dB], " + "RadialSpeed [m/s], ElevationAngle [rad], AzimuthAngle [rad], " + "TimestampSec, TimestampNanoSec\n"; - for (const auto & data_row : recorded_data) { + for (const auto & data_row : target_recorded_data) { QStringList data_str_list; + data_str_list << "Target"; data_str_list << QString::number(data_row.range, 'f', 2); data_str_list << QString::number(data_row.power, 'f', 2); data_str_list << QString::number(data_row.azimuth_angle * 180.0 / M_PI, 'f', 2); @@ -215,6 +522,28 @@ void SmartRadarRecorder::saveDataToCSV() csv_writer << data_str_list.join(", ") << "\n"; } + csv_writer << "Type, PosX [m], PosY [m], PosZ [m], AbsoluteSpeed [m/s], Heading [Deg], " + "ObjectLength [m], Quality, Acceleration [m/s^2], ObjectId, " + "TimestampSec, TimestampNanoSec\n"; + // Write object data + for (const auto & object : object_recorded_data) { + QStringList data_str_list; + data_str_list << "Object"; + data_str_list << QString::number(object.x_pos, 'f', 2); + data_str_list << QString::number(object.y_pos, 'f', 2); + data_str_list << QString::number(object.z_pos, 'f', 2); + data_str_list << QString::number(object.speed_abs, 'f', 2); + data_str_list << QString::number(object.heading * 180.0 / M_PI, 'f', 2); + data_str_list << QString::number(object.length, 'f', 2); + data_str_list << QString::number(object.quality, 'f', 2); + data_str_list << QString::number(object.acceleration, 'f', 2); + data_str_list << QString::number(object.object_id); + data_str_list << QString::number(object.timestamp_sec); + data_str_list << QString::number(object.timestamp_nanosec); + + csv_writer << data_str_list.join(", ") << "\n"; + } + csvfile.close(); } else { qDebug() << "Error: Could not open the file for writing."; @@ -224,10 +553,11 @@ void SmartRadarRecorder::saveDataToCSV() qDebug() << "No recorded data to save."; } // Clear recorded_data after saving - recorded_data.clear(); + target_recorded_data.clear(); + object_recorded_data.clear(); } -void SmartRadarRecorder::checkForData() +void SmartRadarRecorder::check_data() { if (rclcpp::ok()) // Check if ROS2 is still running { @@ -238,4 +568,4 @@ void SmartRadarRecorder::checkForData() } // namespace smart_rviz_plugin #include -PLUGINLIB_EXPORT_CLASS(smart_rviz_plugin::SmartRadarRecorder, rviz_common::Panel) +PLUGINLIB_EXPORT_CLASS(smart_rviz_plugin::SmartRadarRecorder, rviz_common::Panel) \ No newline at end of file diff --git a/smart_rviz_plugin/src/smart_services.cpp b/smart_rviz_plugin/src/smart_services.cpp index c4c456a..ca5449a 100644 --- a/smart_rviz_plugin/src/smart_services.cpp +++ b/smart_rviz_plugin/src/smart_services.cpp @@ -18,7 +18,6 @@ void SmartRadarService::initialize() rclcpp::init(0, nullptr); } - // Declare node_ and clients client_node = rclcpp::Node::make_shared("smart_service_gui"); mode_client = client_node->create_client("smart_radar/set_radar_mode"); @@ -27,64 +26,219 @@ void SmartRadarService::initialize() RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Client node created!"); - // GUI setup - param_name = new QLineEdit(this); - param_value = new QLineEdit(this); - sensor_id_value = new QLineEdit(this); - command_name = new QLineEdit(this); - command_value = new QLineEdit(this); - command_sensor_id_value = new QLineEdit(this); + param_name_line_edit = new QLineEdit(this); + param_value_line_edit = new QLineEdit(this); + param_sensor_id = new QLineEdit(this); send_param_button = new QPushButton("Send Param", this); + param_table_widget = new QTableWidget(this); + + command_name_line_edit = new QLineEdit(this); + command_comment_line_edit = new QLineEdit(this); + command_value_line_edit = new QLineEdit(this); + command_sensor_id = new QLineEdit(this); send_command_button = new QPushButton("Send Command", this); + command_table_widget = new QTableWidget(this); tab_widget = new QTabWidget(this); - set_mode_tab = new QWidget(tab_widget); - send_command_tab = new QWidget(tab_widget); - - // Create layouts for each tab - send_mode_layout = new QVBoxLayout(set_mode_tab); - send_command_layout = new QVBoxLayout(send_command_tab); - - // Add widgets to the layouts - send_mode_layout->addWidget(new QLabel("Radar Params:")); - send_mode_layout->addWidget(new QLabel("Param:")); - send_mode_layout->addWidget(param_name); - send_mode_layout->addWidget(new QLabel("Value:")); - send_mode_layout->addWidget(param_value); - send_mode_layout->addWidget(new QLabel("Sensor ID:")); - send_mode_layout->addWidget(sensor_id_value); - send_mode_layout->addWidget(send_param_button); - - send_command_layout->addWidget(new QLabel("Radar Commands:")); - send_command_layout->addWidget(new QLabel("Command:")); - send_command_layout->addWidget(command_name); - send_command_layout->addWidget(new QLabel("Value:")); - send_command_layout->addWidget(command_value); - send_command_layout->addWidget(new QLabel("Sensor ID:")); - send_command_layout->addWidget(command_sensor_id_value); - send_command_layout->addWidget(send_command_button); - - // Set default values - param_name->setText("dummy_check_interface_file"); - param_value->setText("1"); - sensor_id_value->setText("100"); - - command_name->setText("dummy_check_interface_file"); - command_value->setText("1"); - command_sensor_id_value->setText("100"); - - tab_widget->addTab(set_mode_tab, "Set Radar Mode"); - tab_widget->addTab(send_command_tab, "Send Command"); - - QHBoxLayout * mainLayout = new QHBoxLayout(this); - mainLayout->addWidget(tab_widget); - - // Connect signals and slots - connect(send_param_button, &QPushButton::clicked, this, &SmartRadarService::onSendParam); - connect(send_command_button, &QPushButton::clicked, this, &SmartRadarService::onSendCommand); + param_tab = new QWidget(tab_widget); + command_tab = new QWidget(tab_widget); + + QVBoxLayout * param_layout = new QVBoxLayout(param_tab); + QVBoxLayout * command_layout = new QVBoxLayout(command_tab); + + param_layout->addWidget(param_table_widget); + param_layout->addWidget(new QLabel("Enter Param:")); + param_layout->addWidget(param_name_line_edit); + param_layout->addWidget(new QLabel("Enter Value:")); + param_layout->addWidget(param_value_line_edit); + param_layout->addWidget(new QLabel("Enter Sensor ID:")); + param_layout->addWidget(param_sensor_id); + param_layout->addWidget(send_param_button); + + command_layout->addWidget(command_table_widget); + command_layout->addWidget(new QLabel("Enter Command:")); + command_layout->addWidget(command_name_line_edit); + command_layout->addWidget(new QLabel("Enter Value:")); + command_layout->addWidget(command_value_line_edit); + command_layout->addWidget(new QLabel("Enter Sensor ID:")); + command_layout->addWidget(command_sensor_id); + command_layout->addWidget(send_command_button); + + tab_widget->addTab(param_tab, "Parameter"); + tab_widget->addTab(command_tab, "Command"); + + // Add dropdown menu for file selection + file_selector_combo_box = new QComboBox(this); + populate_file_menu(); + + QVBoxLayout * main_layout = new QVBoxLayout(this); + main_layout->addWidget(file_selector_combo_box); + main_layout->addWidget(tab_widget); + + response_text_edit = new QTextEdit(this); + response_text_edit->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding); + response_text_edit->setFixedSize(1200, 100); + main_layout->addWidget(response_text_edit); + + // Connect dropdown menu signal to slot + connect( + file_selector_combo_box, QOverload::of(&QComboBox::activated), this, + &SmartRadarService::on_file_selected); + + read_param_json_data(); + read_command_json_data(); + connect(send_param_button, SIGNAL(clicked()), this, SLOT(on_send_param())); + connect(send_command_button, SIGNAL(clicked()), this, SLOT(on_send_command())); +} + +void SmartRadarService::populate_file_menu() +{ + // Add file names to the dropdown menu + file_selector_combo_box->clear(); + file_selector_combo_box->addItem("Choose Sensor Type"); + file_selector_combo_box->addItem("UMRR9F MSE"); + file_selector_combo_box->addItem("UMRR9F"); + file_selector_combo_box->addItem("UMRR9D"); + file_selector_combo_box->addItem("UMRRA4"); +} + +void SmartRadarService::on_file_selected(int index) +{ + // Update file paths based on selected file + if (index == 0) { + // Clear param tab + param_table_widget->setRowCount(0); + param_name_line_edit->clear(); + param_value_line_edit->clear(); + param_sensor_id->clear(); + + // Clear command tab + command_table_widget->setRowCount(0); + command_name_line_edit->clear(); + command_argument_line_edit->clear(); + + RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Index Zero!"); + } else if (index == 1) { + param_json_file_path = + current_directory + + "/src/smartmicro_ros2_radars/umrr_ros2_driver/smartmicro/user_interfaces/" + "UserInterfaceUmrr9f_t169_mseV1.0.0/instructions/params/auto_interface_0dim.param"; + command_json_file_path = + current_directory + + "/src/smartmicro_ros2_radars/umrr_ros2_driver/smartmicro/user_interfaces/" + "UserInterfaceUmrr9f_t169_mseV1.0.0/instructions/command/auto_interface.command"; + } else if (index == 2) { + param_json_file_path = + current_directory + + "/src/smartmicro_ros2_radars/umrr_ros2_driver/smartmicro/user_interfaces/" + "UserInterfaceUmrr9f_t169_automotiveV2.4.1/instructions/params/auto_interface_0dim.param"; + command_json_file_path = + current_directory + + "/src/smartmicro_ros2_radars/umrr_ros2_driver/smartmicro/user_interfaces/" + "UserInterfaceUmrr9f_t169_automotiveV2.4.1/instructions/command/auto_interface.command"; + } else if (index == 3) { + param_json_file_path = + current_directory + + "/src/smartmicro_ros2_radars/umrr_ros2_driver/smartmicro/user_interfaces/" + "UserInterfaceUmrr9d_t152_automotiveV1.4.1/instructions/params/auto_interface_0dim.param"; + command_json_file_path = + current_directory + + "/src/smartmicro_ros2_radars/umrr_ros2_driver/smartmicro/user_interfaces/" + "UserInterfaceUmrr9d_t152_automotiveV1.4.1/instructions/command/auto_interface.command"; + } else if (index == 4) { + param_json_file_path = + current_directory + + "/src/smartmicro_ros2_radars/umrr_ros2_driver/smartmicro/user_interfaces/" + "UserInterfaceUmrra4_automotiveV1.2.1/instructions/params/auto_interface_0dim.param"; + command_json_file_path = + current_directory + + "/src/smartmicro_ros2_radars/umrr_ros2_driver/smartmicro/user_interfaces/" + "UserInterfaceUmrra4_automotiveV1.2.1/instructions/command/auto_interface.command"; + } + + // Update tables with data from selected files + if (index != 0) { + read_param_json_data(); + read_command_json_data(); + } +} + +void SmartRadarService::read_command_json_data() +{ + QFile command_json_file(command_json_file_path); + if (!command_json_file.open(QIODevice::ReadOnly)) { + RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Parse Failed!"); + return; + } + + QByteArray json_data = command_json_file.readAll(); + QJsonDocument doc(QJsonDocument::fromJson(json_data)); + QJsonObject json_object = doc.object(); + + // Extract the "commands" array + QJsonArray commands_array = json_object["commands"].toArray(); + + // Set up table headers + QStringList command_header_labels = {"Name", "Argument", "Comment"}; + command_table_widget->setColumnCount(3); + command_table_widget->setHorizontalHeaderLabels(command_header_labels); + + // Populate the table with command data + command_table_widget->setRowCount(commands_array.size()); + for (int i = 0; i < commands_array.size(); ++i) { + QJsonObject command_object = commands_array[i].toObject(); + QString name = command_object["name"].toString(); + QString argument = command_object["argument"].toString(); + QString comment = command_object["comment"].toString(); + + QTableWidgetItem * name_item = new QTableWidgetItem(name); + QTableWidgetItem * argument_item = new QTableWidgetItem(argument); + QTableWidgetItem * comment_item = new QTableWidgetItem(comment); + + command_table_widget->setItem(i, 0, name_item); + command_table_widget->setItem(i, 1, argument_item); + command_table_widget->setItem(i, 2, comment_item); + } + RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Commands parsed successfully!"); +} + +void SmartRadarService::read_param_json_data() +{ + QFile param_json_file(param_json_file_path); + if (!param_json_file.open(QIODevice::ReadOnly)) { + RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Parse Failed!"); + return; + } + + QByteArray json_data = param_json_file.readAll(); + QJsonDocument doc(QJsonDocument::fromJson(json_data)); + QJsonObject json_object = doc.object(); + + // Extract the "parameters" array + QJsonArray params_array = json_object["parameters"].toArray(); + + // Set up table headers + QStringList param_header_labels = {"Name", "Comment"}; + param_table_widget->setColumnCount(2); + param_table_widget->setHorizontalHeaderLabels(param_header_labels); + + // Populate the table with parameter data + param_table_widget->setRowCount(params_array.size()); + for (int i = 0; i < params_array.size(); ++i) { + QJsonObject param_object = params_array[i].toObject(); + QString name = param_object["name"].toString(); + QString comment = param_object["comment"].toString(); + + QTableWidgetItem * name_item = new QTableWidgetItem(name); + QTableWidgetItem * comment_item = new QTableWidgetItem(comment); + + param_table_widget->setItem(i, 0, name_item); + param_table_widget->setItem(i, 1, comment_item); + } + RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Parameters parsed successfully!"); } -void SmartRadarService::onSendParam() +void SmartRadarService::on_send_param() { if (!mode_client) { RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Failed to create mode_client"); @@ -92,23 +246,27 @@ void SmartRadarService::onSendParam() } auto request = std::make_shared(); - request->param = param_name->text().toStdString(); - request->value = std::stoi(param_value->text().toUtf8().constData()); - request->sensor_id = std::stoi(sensor_id_value->text().toUtf8().constData()); + request->param = param_name_line_edit->text().toStdString(); + request->value = std::stoi(param_value_line_edit->text().toUtf8().constData()); + request->sensor_id = std::stoi(param_sensor_id->text().toUtf8().constData()); auto result = mode_client->async_send_request(request); // Wait for the result. if ( rclcpp::spin_until_future_complete(client_node, result) == rclcpp::FutureReturnCode::SUCCESS) { + QString response_msg = QString::fromStdString(result.get()->res); + response_text_edit->append("Request sent. Response from sensor: " + response_msg); RCLCPP_INFO( - rclcpp::get_logger("rclcpp"), "Request successful. Response: %s", result.get()->res.c_str()); + rclcpp::get_logger("rclcpp"), "Request sent. Response from sensor: %s", + result.get()->res.c_str()); } else { - RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Failed to call service add_two_ints"); + RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Failed to call service!"); + response_text_edit->append("Failed to call service!"); } } -void SmartRadarService::onSendCommand() +void SmartRadarService::on_send_command() { if (!command_client) { RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Failed to create command client"); @@ -116,19 +274,22 @@ void SmartRadarService::onSendCommand() } auto request = std::make_shared(); - request->command = command_name->text().toStdString(); - request->value = std::stoi(command_value->text().toUtf8().constData()); - request->sensor_id = std::stoi(command_sensor_id_value->text().toUtf8().constData()); + request->command = command_name_line_edit->text().toStdString(); + request->value = std::stoi(command_value_line_edit->text().toUtf8().constData()); + request->sensor_id = std::stoi(command_sensor_id->text().toUtf8().constData()); auto result = command_client->async_send_request(request); // Wait for the result. if ( rclcpp::spin_until_future_complete(client_node, result) == rclcpp::FutureReturnCode::SUCCESS) { + QString response_msg = QString::fromStdString(result.get()->res); + response_text_edit->append("Request sent. Response from sensor: " + response_msg); RCLCPP_INFO( - rclcpp::get_logger("rclcpp"), "Request successful. Response: %s", result.get()->res.c_str()); + rclcpp::get_logger("rclcpp"), "Request sent. Response: %s", result.get()->res.c_str()); } else { - RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Failed to call service add_two_ints"); + RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Failed to call service!"); + response_text_edit->append("Failed to call service!"); } } diff --git a/smart_rviz_plugin/src/smart_status.cpp b/smart_rviz_plugin/src/smart_status.cpp new file mode 100644 index 0000000..73237c0 --- /dev/null +++ b/smart_rviz_plugin/src/smart_status.cpp @@ -0,0 +1,236 @@ +#include "smart_rviz_plugin/smart_status.hpp" + +#include +#include +#include +#include + +namespace smart_rviz_plugin +{ +SmartRadarStatus::SmartRadarStatus(QWidget * parent) : rviz_common::Panel(parent) { initialize(); } + +void SmartRadarStatus::initialize() +{ + node_ = rclcpp::Node::make_shared("smart_radar_gui_node"); + + // Status setup + gui_layout_ = new QVBoxLayout(); + topic_dropdown_ = new QComboBox(); + topic_dropdown_->addItem("Select a Topic"); + + // Retrieve available topics + auto topic_names_and_types = node_->get_topic_names_and_types(); + + // Create subscribers for selected topics + for (const auto & topic : topic_names_and_types) { + if (topic.first.find("port_targetheader") != std::string::npos) { + port_header_target_subscribers_[topic.first] = + node_->create_subscription( + topic.first, 10, + [this, topic](const umrr_ros2_msgs::msg::PortTargetHeader::SharedPtr msg) { + port_targetheader_callback(msg, topic.first); + }); + + topic_dropdown_->addItem(QString::fromStdString(topic.first)); + } else if (topic.first.find("can_targetheader") != std::string::npos) { + can_header_target_subscribers_[topic.first] = + node_->create_subscription( + topic.first, 10, + [this, topic](const umrr_ros2_msgs::msg::CanTargetHeader::SharedPtr msg) { + can_targetheader_callback(msg, topic.first); + }); + + topic_dropdown_->addItem(QString::fromStdString(topic.first)); + } else if (topic.first.find("port_objectheader") != std::string::npos) { + port_header_object_subscribers_[topic.first] = + node_->create_subscription( + topic.first, 10, + [this, topic](const umrr_ros2_msgs::msg::PortObjectHeader::SharedPtr msg) { + port_objectheader_callback(msg, topic.first); + }); + topic_dropdown_->addItem(QString::fromStdString(topic.first)); + } else if (topic.first.find("can_objectheader") != std::string::npos) { + can_header_object_subscribers_[topic.first] = + node_->create_subscription( + topic.first, 10, + [this, topic](const umrr_ros2_msgs::msg::CanObjectHeader::SharedPtr msg) { + can_objectheader_callback(msg, topic.first); + }); + topic_dropdown_->addItem(QString::fromStdString(topic.first)); + } + } + + connect(topic_dropdown_, SIGNAL(currentIndexChanged(int)), this, SLOT(update_table())); + + table_data_ = new QTableWidget(); + table_data_->setRowCount(16); + table_data_->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding); + table_data_->horizontalHeader()->setSectionResizeMode(QHeaderView::Stretch); + + splitter_ = new QSplitter(Qt::Vertical); + splitter_->addWidget(topic_dropdown_); + splitter_->addWidget(table_data_); + + gui_layout_->addWidget(splitter_); + + timer_ = new QTimer(); + connect(timer_, SIGNAL(timeout()), this, SLOT(check_data())); + timer_->start(20); + + setLayout(gui_layout_); + + RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Status Plugin Created!"); +} + +void SmartRadarStatus::port_targetheader_callback( + const umrr_ros2_msgs::msg::PortTargetHeader::SharedPtr msg, const std::string topic_name) +{ + if (!selected_topic_.empty() && topic_name == selected_topic_) { + table_data_->setColumnCount(0); + int col_index = 0; + std::uint64_t ntp_timestamp = msg->acquisition_start; + // Extract the first 4 bytes (seconds) - most significant 32 bits + std::uint32_t seconds = static_cast(ntp_timestamp >> 32); + // Extract the last 4 bytes (fraction of a second) - least significant 32 bits + std::uint32_t fraction_sec = static_cast(ntp_timestamp & 0xFFFFFFFF); + table_data_->insertColumn(col_index); + table_data_->setItem( + 0, col_index, new QTableWidgetItem(QString::number(msg->cycle_time, 'f', 3))); + table_data_->setItem( + 1, col_index, new QTableWidgetItem(QString::number(msg->number_of_targets))); + table_data_->setItem( + 2, col_index, new QTableWidgetItem(QString::number(msg->acquisition_tx_ant_idx))); + table_data_->setItem( + 3, col_index, new QTableWidgetItem(QString::number(msg->acquisition_sweep_idx))); + table_data_->setItem( + 4, col_index, new QTableWidgetItem(QString::number(msg->acquisition_cf_idx))); + table_data_->setItem(5, col_index, new QTableWidgetItem(QString::number(seconds))); + table_data_->setItem(6, col_index, new QTableWidgetItem(QString::number(fraction_sec))); + table_data_->setItem(7, col_index, new QTableWidgetItem(QString::number(msg->prf))); + table_data_->setItem( + 8, col_index, new QTableWidgetItem(QString::number(msg->umambiguous_speed, 'f', 2))); + table_data_->setItem(9, col_index, new QTableWidgetItem(QString::number(msg->port_identifier))); + table_data_->setItem(10, col_index, new QTableWidgetItem(QString::number(msg->port_ver_major))); + table_data_->setItem(11, col_index, new QTableWidgetItem(QString::number(msg->port_ver_minor))); + table_data_->setItem(12, col_index, new QTableWidgetItem(QString::number(msg->port_size))); + table_data_->setItem( + 13, col_index, new QTableWidgetItem(QString::number(msg->body_endianness))); + table_data_->setItem(14, col_index, new QTableWidgetItem(QString::number(msg->port_index))); + table_data_->setItem( + 15, col_index, new QTableWidgetItem(QString::number(msg->header_ver_major))); + table_data_->setItem( + 16, col_index, new QTableWidgetItem(QString::number(msg->header_ver_minor))); + } +} + +void SmartRadarStatus::can_targetheader_callback( + const umrr_ros2_msgs::msg::CanTargetHeader::SharedPtr msg, const std::string topic_name) +{ + if (!selected_topic_.empty() && topic_name == selected_topic_) { + table_data_->setColumnCount(0); + int col_index = 0; + table_data_->insertColumn(col_index); + table_data_->setItem( + 0, col_index, new QTableWidgetItem(QString::number(msg->cycle_time, 'f', 3))); + table_data_->setItem( + 1, col_index, new QTableWidgetItem(QString::number(msg->number_of_targets))); + table_data_->setItem(2, col_index, new QTableWidgetItem(QString::number(msg->cycle_count))); + table_data_->setItem( + 3, col_index, new QTableWidgetItem(QString::number(msg->acquisition_setup))); + table_data_->setItem(4, col_index, new QTableWidgetItem(QString::number(msg->time_stamp))); + table_data_->setItem(5, col_index, new QTableWidgetItem(QString::number(msg->acq_ts_fraction))); + } +} + +void SmartRadarStatus::port_objectheader_callback( + const umrr_ros2_msgs::msg::PortObjectHeader::SharedPtr msg, const std::string topic_name) +{ + if (!selected_topic_.empty() && topic_name == selected_topic_) { + float_t cycle_time = msg->cycle_time; + std::uint16_t no_objs = msg->number_of_objects; + std::uint64_t ntp_timestamp = msg->ts_measurement; + std::uint32_t seconds = static_cast(ntp_timestamp >> 32); + std::uint32_t fraction_sec = static_cast(ntp_timestamp & 0xFFFFFFFF); + + table_data_->setColumnCount(0); + int col_index = 0; + table_data_->insertColumn(col_index); + table_data_->setItem(0, col_index, new QTableWidgetItem(QString::number(cycle_time, 'f', 3))); + table_data_->setItem(1, col_index, new QTableWidgetItem(QString::number(no_objs))); + table_data_->setItem(2, col_index, new QTableWidgetItem(QString::number(seconds))); + table_data_->setItem(3, col_index, new QTableWidgetItem(QString::number(fraction_sec))); + table_data_->setItem(4, col_index, new QTableWidgetItem(QString::number(msg->port_identifier))); + table_data_->setItem(5, col_index, new QTableWidgetItem(QString::number(msg->port_ver_major))); + table_data_->setItem(6, col_index, new QTableWidgetItem(QString::number(msg->port_ver_minor))); + table_data_->setItem(7, col_index, new QTableWidgetItem(QString::number(msg->port_size))); + table_data_->setItem(8, col_index, new QTableWidgetItem(QString::number(msg->body_endianness))); + table_data_->setItem(9, col_index, new QTableWidgetItem(QString::number(msg->port_index))); + table_data_->setItem( + 10, col_index, new QTableWidgetItem(QString::number(msg->header_ver_major))); + table_data_->setItem( + 11, col_index, new QTableWidgetItem(QString::number(msg->header_ver_minor))); + } +} + +void SmartRadarStatus::can_objectheader_callback( + const umrr_ros2_msgs::msg::CanObjectHeader::SharedPtr msg, const std::string topic_name) +{ + if (!selected_topic_.empty() && topic_name == selected_topic_) { + table_data_->setColumnCount(0); + int col_index = 0; + table_data_->insertColumn(col_index); + table_data_->setItem( + 0, col_index, new QTableWidgetItem(QString::number(msg->cycle_time, 'f', 3))); + table_data_->setItem( + 1, col_index, new QTableWidgetItem(QString::number(msg->number_of_objects))); + table_data_->setItem(2, col_index, new QTableWidgetItem(QString::number(msg->cycle_count))); + table_data_->setItem(3, col_index, new QTableWidgetItem(QString::number(msg->ego_speed))); + table_data_->setItem( + 4, col_index, new QTableWidgetItem(QString::number(msg->ego_speed_quality))); + table_data_->setItem(5, col_index, new QTableWidgetItem(QString::number(msg->ego_yaw_rate))); + table_data_->setItem( + 6, col_index, new QTableWidgetItem(QString::number(msg->ego_yaw_rate_quality))); + table_data_->setItem(7, col_index, new QTableWidgetItem(QString::number(msg->dyn_source))); + } +} + +void SmartRadarStatus::update_table() +{ + table_data_->setColumnCount(0); + selected_topic_ = topic_dropdown_->currentText().toStdString(); + if (selected_topic_.find("port_targetheader") != std::string::npos) { + table_data_->setVerticalHeaderLabels( + {"CycleDuration [s]", "NumOfTargets", "AcquisitionTxAntIdx", "AcquisitionSweepIdx", + "AcquisitionCfIdx", "AcqTimeStamp [s]", "AcqTimeStampfrac [NTP]", "PRF", "UmambiguousSpeed", + "PortIdentifier", "PortVersionMajor", "PortVersionMinor", "PortSize", "BodyEndianness", + "PortIndex", "HeaderVersionMajor", "HeaderVersionMinor"}); + } else if (selected_topic_.find("can_targetheader") != std::string::npos) { + table_data_->setVerticalHeaderLabels( + {"CycleDuration [s]", "NumOfTargets", "CycleCount", "AcquisitionSetup", "AcqTimeStamp [s]", + "AcqTimeStampfrac [NTP]", "", "", "", "", "", "", "", "", "", "", ""}); + } else if (selected_topic_.find("can_objectheader") != std::string::npos) { + table_data_->setColumnCount(0); + table_data_->setVerticalHeaderLabels( + {"CycleDuration [s]", "NumOfObjects", "CycleCount", "Speed [km/h]", "SpeedQuality", + "YawRate [rad/s]", "YawRateQuality", "DynamicSource", "", "", "", "", "", "", "", "", ""}); + } else if (selected_topic_.find("port_objectheader") != std::string::npos) { + table_data_->setColumnCount(0); + table_data_->setVerticalHeaderLabels( + {"CycleDuration [s]", "NumOfObjects", "AcqTimeStamp [s]", "AcqTimeStampfrac [NTP]", + "PortIdentifier", "PortVersionMajor", "PortVersionMinor", "PortSize", "BodyEndianness", + "PortIndex", "HeaderVersionMajor", "HeaderVersionMinor", "", "", "", "", ""}); + } +} + +void SmartRadarStatus::check_data() +{ + if (rclcpp::ok()) // Check if ROS2 is still running + { + rclcpp::spin_some(node_); + } +} + +} // namespace smart_rviz_plugin + +#include +PLUGINLIB_EXPORT_CLASS(smart_rviz_plugin::SmartRadarStatus, rviz_common::Panel) diff --git a/umrr_ros2_driver/CMakeLists.txt b/umrr_ros2_driver/CMakeLists.txt index 2c1609b..1958e2a 100644 --- a/umrr_ros2_driver/CMakeLists.txt +++ b/umrr_ros2_driver/CMakeLists.txt @@ -26,11 +26,12 @@ if(NOT CMAKE_CXX_STANDARD) endif() if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic -Wno-unused-parameter -g) + add_compile_options(-Wall -Wextra -Wnarrowing -Wpedantic -Wno-unused-parameter -g) endif() find_package(ament_cmake_auto REQUIRED) find_package(Threads REQUIRED) +find_package(visualization_msgs REQUIRED) fetchcontent_declare(json GIT_REPOSITORY https://github.com/nlohmann/json.git @@ -61,12 +62,13 @@ install(FILES "${PROJECT_SOURCE_DIR}/smartmicro/${SMARTMICRO_LIB_DIR}/libumrr9f_t169_automotivev2.0.0_user_interface.so" "${PROJECT_SOURCE_DIR}/smartmicro/${SMARTMICRO_LIB_DIR}/libumrr9f_t169_automotivev2.1.1_user_interface.so" "${PROJECT_SOURCE_DIR}/smartmicro/${SMARTMICRO_LIB_DIR}/libumrr9f_t169_automotivev2.2.1_user_interface.so" - "${PROJECT_SOURCE_DIR}/smartmicro/${SMARTMICRO_LIB_DIR}/libumrr9f_t169_automotivev2.5.0_user_interface.so" + "${PROJECT_SOURCE_DIR}/smartmicro/${SMARTMICRO_LIB_DIR}/libumrr9f_t169_automotivev2.4.1_user_interface.so" "${PROJECT_SOURCE_DIR}/smartmicro/${SMARTMICRO_LIB_DIR}/libumrr9d_t152_automotivev1.0.3_user_interface.so" "${PROJECT_SOURCE_DIR}/smartmicro/${SMARTMICRO_LIB_DIR}/libumrr9d_t152_automotivev1.2.2_user_interface.so" - "${PROJECT_SOURCE_DIR}/smartmicro/${SMARTMICRO_LIB_DIR}/libumrr9d_t152_automotivev1.5.0_user_interface.so" + "${PROJECT_SOURCE_DIR}/smartmicro/${SMARTMICRO_LIB_DIR}/libumrr9d_t152_automotivev1.4.1_user_interface.so" "${PROJECT_SOURCE_DIR}/smartmicro/${SMARTMICRO_LIB_DIR}/libumrra4_automotivev1.0.1_user_interface.so" - "${PROJECT_SOURCE_DIR}/smartmicro/${SMARTMICRO_LIB_DIR}/libumrra4_automotivev1.3.0_user_interface.so" + "${PROJECT_SOURCE_DIR}/smartmicro/${SMARTMICRO_LIB_DIR}/libumrra4_automotivev1.2.1_user_interface.so" + "${PROJECT_SOURCE_DIR}/smartmicro/${SMARTMICRO_LIB_DIR}/libumrr9f_t169_msev1.0.0_user_interface.so" DESTINATION lib) set(LIB_PATH "${CMAKE_INSTALL_PREFIX}/lib") @@ -93,12 +95,13 @@ smartmicro/include/umrr9f_t169_automotive_v1_1_1 smartmicro/include/umrr9f_t169_automotive_v2_0_0 smartmicro/include/umrr9f_t169_automotive_v2_1_1 smartmicro/include/umrr9f_t169_automotive_v2_2_1 -smartmicro/include/umrr9f_t169_automotive_v2_5_0 +smartmicro/include/umrr9f_t169_automotive_v2_4_1 smartmicro/include/umrr9d_t152_automotive_v1_0_3 smartmicro/include/umrr9d_t152_automotive_v1_2_2 -smartmicro/include/umrr9d_t152_automotive_v1_5_0 +smartmicro/include/umrr9d_t152_automotive_v1_4_1 smartmicro/include/umrra4_automotive_v1_0_1 -smartmicro/include/umrra4_automotive_v1_3_0) +smartmicro/include/umrra4_automotive_v1_2_1 +smartmicro/include/umrr9f_t169_mse_v1_0_0) # link smart_access_lib-linux-x86_64-gcc_9 to the node target_link_libraries(smartmicro_radar_node @@ -112,12 +115,13 @@ target_link_libraries(smartmicro_radar_node umrr9f_t169_automotivev2.0.0_user_interface umrr9f_t169_automotivev2.1.1_user_interface umrr9f_t169_automotivev2.2.1_user_interface - umrr9f_t169_automotivev2.5.0_user_interface + umrr9f_t169_automotivev2.4.1_user_interface umrr9d_t152_automotivev1.0.3_user_interface umrr9d_t152_automotivev1.2.2_user_interface - umrr9d_t152_automotivev1.5.0_user_interface + umrr9d_t152_automotivev1.4.1_user_interface umrra4_automotivev1.0.1_user_interface - umrra4_automotivev1.3.0_user_interface) + umrra4_automotivev1.2.1_user_interface + umrr9f_t169_msev1.0.0_user_interface) rclcpp_components_register_node(smartmicro_radar_node PLUGIN "smartmicro::drivers::radar::SmartmicroRadarNode" diff --git a/umrr_ros2_driver/include/umrr_ros2_driver/smartmicro_radar_node.hpp b/umrr_ros2_driver/include/umrr_ros2_driver/smartmicro_radar_node.hpp index 4e733d3..f5cdcc6 100644 --- a/umrr_ros2_driver/include/umrr_ros2_driver/smartmicro_radar_node.hpp +++ b/umrr_ros2_driver/include/umrr_ros2_driver/smartmicro_radar_node.hpp @@ -17,7 +17,6 @@ #ifndef UMRR_ROS2_DRIVER__SMARTMICRO_RADAR_NODE_HPP_ #define UMRR_ROS2_DRIVER__SMARTMICRO_RADAR_NODE_HPP_ - #include #include #include @@ -25,36 +24,46 @@ #include #include -#include -#include #include #include +#include +#include +#include #include #include #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include #include +#include "umrr_ros2_msgs/msg/can_object_header.hpp" +#include "umrr_ros2_msgs/msg/can_target_header.hpp" +#include "umrr_ros2_msgs/msg/port_object_header.hpp" +#include "umrr_ros2_msgs/msg/port_target_header.hpp" +#include "umrr_ros2_msgs/srv/firmware_download.hpp" #include "umrr_ros2_msgs/srv/send_command.hpp" #include "umrr_ros2_msgs/srv/set_ip.hpp" #include "umrr_ros2_msgs/srv/set_mode.hpp" -#include "umrr_ros2_msgs/srv/firmware_download.hpp" -namespace smartmicro { -namespace drivers { -namespace radar { -namespace detail { +namespace smartmicro +{ +namespace drivers +{ +namespace radar +{ +namespace detail +{ constexpr auto kMaxSensorCount = 10UL; constexpr auto kMaxHwCount = 6UL; -struct SensorConfig { +struct SensorConfig +{ std::uint32_t id{}; std::uint32_t dev_id{}; std::string frame_id{}; @@ -69,29 +78,32 @@ struct SensorConfig { std::uint32_t uifmajorv{}; std::uint32_t uifminorv{}; std::uint32_t uifpatchv{}; + std::string pub_type{}; }; -struct HWConfig { +struct HWConfig +{ std::uint32_t hw_dev_id{}; std::string hw_iface_name{}; std::string hw_type{}; std::uint32_t baudrate{}; std::uint32_t port{}; }; -} // namespace detail +} // namespace detail /// /// @brief The class for the Smartmicro radar node. /// -class UMRR_ROS2_DRIVER_PUBLIC SmartmicroRadarNode : public ::rclcpp::Node { +class UMRR_ROS2_DRIVER_PUBLIC SmartmicroRadarNode : public ::rclcpp::Node +{ public: /// /// ROS 2 parameter constructor. /// /// @param[in] node_options Node options for this node. /// - explicit SmartmicroRadarNode(const rclcpp::NodeOptions &node_options); - + explicit SmartmicroRadarNode(const rclcpp::NodeOptions & node_options); + protected: /// /// @brief A timer to handle the services. @@ -100,42 +112,70 @@ class UMRR_ROS2_DRIVER_PUBLIC SmartmicroRadarNode : public ::rclcpp::Node { void on_shutdown_callback(); private: + /// + /// @brief A callback that is called when a new object list port for + /// umrr9f_v1_0_0 T169 MSE arrives. + /// + /// @param[in] sensor_idx The sensor id for respective published topic. + /// @param[in] objectlist_port_umrr9f_mse_v1_0_0 The object list port + /// @param[in] client_id The client_id of the sensor + /// + void objectlist_callback_umrr9f_mse_v1_0_0( + const std::uint32_t sensor_idx, + const std::shared_ptr & + objectlist_port_umrr9f_mse_v1_0_0, + const com::types::ClientId client_id); + + /// + /// @brief A callback that is called when a new target list port for + /// umrr9f_v1_0_0 T169 MSE arrives. + /// + /// @param[in] sensor_idx The sensor id for respective published topic. + /// @param[in] targetlist_port_umrr9f_mse_v1_0_0 The target list port + /// @param[in] client_id The client_id of the sensor + /// + void targetlist_callback_umrr9f_mse_v1_0_0( + const std::uint32_t sensor_idx, + const std::shared_ptr & + targetlist_port_umrr9f_mse_v1_0_0, + const com::types::ClientId client_id); + /// /// @brief A callback that is called when a new target list port for /// umrr11 T132 arrives. /// /// @param[in] sensor_idx The sensor id for respective published topic. - /// @param[in] target_list_port The target list port + /// @param[in] targetlist_port_umrr11 The target list port /// @param[in] client_id The client_id of the sensor /// void targetlist_callback_umrr11( - const std::uint32_t sensor_idx, - const std::shared_ptr - &targetlist_port_umrr11, - const com::types::ClientId client_id); + const std::uint32_t sensor_idx, + const std::shared_ptr< + com::master::umrr11_t132_automotive_v1_1_2::comtargetlist::ComTargetList> & + targetlist_port_umrr11, + const com::types::ClientId client_id); /// /// @brief A callback that is called when a new target list port for /// umrr96 T153 arrives. /// /// @param[in] sensor_idx The sensor id for respective published topic. - /// @param[in] target_list_port The target list port + /// @param[in] targetlist_port_umrr96 The target list port /// @param[in] client_id The client_id of the sensor /// void targetlist_callback_umrr96( - const std::uint32_t sensor_idx, - const std::shared_ptr - &targetlist_port_umrr96, - const com::types::ClientId client_id); - + const std::uint32_t sensor_idx, + const std::shared_ptr< + com::master::umrr96_t153_automotive_v1_2_2::comtargetlist::ComTargetList> & + targetlist_port_umrr96, + const com::types::ClientId client_id); + /// /// @brief A callback that is called when a new target list port for /// umrr9f_v2_0_0 arrives. /// /// @param[in] sensor_idx The sensor id for respective published topic. - /// @param[in] target_list_port The target list port + /// @param[in] targetlist_port_umrr9f_v2_0_0 The target list port /// @param[in] client_id The client_id of the sensor /// void targetlist_callback_umrr9f_v2_0_0( @@ -150,283 +190,310 @@ class UMRR_ROS2_DRIVER_PUBLIC SmartmicroRadarNode : public ::rclcpp::Node { /// umrr9f_v1_1_1 T169 arrives. /// /// @param[in] sensor_idx The sensor id for respective published topic. - /// @param[in] target_list_port The target list port + /// @param[in] targetlist_port_umrr9f_v1_1_1 The target list port /// @param[in] client_id The client_id of the sensor /// void targetlist_callback_umrr9f_v1_1_1( - const std::uint32_t sensor_idx, - const std::shared_ptr - &targetlist_port_umrr9f, - const com::types::ClientId client_id); + const std::uint32_t sensor_idx, + const std::shared_ptr< + com::master::umrr9f_t169_automotive_v1_1_1::comtargetlistport::ComTargetListPort> & + targetlist_port_umrr9f_v1_1_1, + const com::types::ClientId client_id); /// /// @brief A callback that is called when a new target list port for /// umrr9f_v2_1_1 T169 arrives. /// /// @param[in] sensor_idx The sensor id for respective published topic. - /// @param[in] target_list_port The target list port + /// @param[in] targetlist_port_umrr9f_v2_1_1 The target list port /// @param[in] client_id The client_id of the sensor /// void targetlist_callback_umrr9f_v2_1_1( - const std::uint32_t sensor_idx, - const std::shared_ptr - &targetlist_port_umrr9f_v2_1_1, - const com::types::ClientId client_id); - + const std::uint32_t sensor_idx, + const std::shared_ptr< + com::master::umrr9f_t169_automotive_v2_1_1::comtargetlist::ComTargetList> & + targetlist_port_umrr9f_v2_1_1, + const com::types::ClientId client_id); + /// /// @brief A callback that is called when a new target list port for /// umrr9f_v2_2_1 T169 arrives. /// /// @param[in] sensor_idx The sensor id for respective published topic. - /// @param[in] target_list_port The target list port + /// @param[in] targetlist_port_umrr9f_v2_2_1 The target list port /// @param[in] client_id The client_id of the sensor /// void targetlist_callback_umrr9f_v2_2_1( - const std::uint32_t sensor_idx, - const std::shared_ptr - &targetlist_port_umrr9f_v2_2_1, - const com::types::ClientId client_id); + const std::uint32_t sensor_idx, + const std::shared_ptr< + com::master::umrr9f_t169_automotive_v2_2_1::comtargetlist::ComTargetList> & + targetlist_port_umrr9f_v2_2_1, + const com::types::ClientId client_id); /// /// @brief A callback that is called when a new target list port for /// umrr9d_v1_0_3 T152 arrives. /// /// @param[in] sensor_idx The sensor id for respective published topic. - /// @param[in] target_list_port The target list port + /// @param[in] targetlist_port_umrr9d_v1_0_3 The target list port /// @param[in] client_id The client_id of the sensor /// void targetlist_callback_umrr9d_v1_0_3( - const std::uint32_t sensor_idx, - const std::shared_ptr - &targetlist_port_umrr9d_v1_0_3, - const com::types::ClientId client_id); - + const std::uint32_t sensor_idx, + const std::shared_ptr< + com::master::umrr9d_t152_automotive_v1_0_3::comtargetlist::ComTargetList> & + targetlist_port_umrr9d_v1_0_3, + const com::types::ClientId client_id); + /// /// @brief A callback that is called when a new target list port for - /// umrr9d_v1_2_2 arrives. + /// umrr9d_v1_2_2 T152 arrives. /// /// @param[in] sensor_idx The sensor id for respective published topic. - /// @param[in] target_list_port The target list port + /// @param[in] targetlist_port_umrr9d_v1_2_2 The target list port /// @param[in] client_id The client_id of the sensor /// void targetlist_callback_umrr9d_v1_2_2( - const std::uint32_t sensor_idx, - const std::shared_ptr - &targetlist_port_umrr9d_v1_2_2, - const com::types::ClientId client_id); - + const std::uint32_t sensor_idx, + const std::shared_ptr< + com::master::umrr9d_t152_automotive_v1_2_2::comtargetlist::ComTargetList> & + targetlist_port_umrr9d_v1_2_2, + const com::types::ClientId client_id); + /// /// @brief A callback that is called when a new target list port for - /// umrra4 T171_v1_0_1 arrives. + /// umrra4_v1_0_1 T171 arrives. /// @param[in] sensor_idx The sensor id for the respected published topic. - /// @param[in] targetlist_port_umrra4 The targetlist port + /// @param[in] targetlist_port_umrra4_v1_0_1 The target list port /// @param[in] client_id The client_id of the sensor /// void targetlist_callback_umrra4_v1_0_1( const std::uint32_t sensor_idx, - const std::shared_ptr &targetlist_port_umrra4_v1_0_1, - const com::types::ClientId client_id - ); + const std::shared_ptr & + targetlist_port_umrra4_v1_0_1, + const com::types::ClientId client_id); /// /// @brief A callback that is called when a new target list port for - /// umrra4 T171_v1_3_0 arrives. + /// umrra4_v1_2_1 T171 arrives. /// @param[in] sensor_idx The sensor id for the respected published topic. - /// @param[in] target_list_port The target list port + /// @param[in] targetlist_port_umrra4_v1_2_1 The target list port /// @param[in] client_id The client_id of the sensor /// - void targetlist_callback_umrra4_v1_3_0( + void targetlist_callback_umrra4_v1_2_1( const std::uint32_t sensor_idx, - const std::shared_ptr - &targetlist_port_umrra4_v1_3_0, - const com::types::ClientId client_id - ); + const std::shared_ptr & + targetlist_port_umrra4_v1_2_1, + const com::types::ClientId client_id); /// /// @brief A callback that is called when a new target list port for - /// umrr9d T152 v1_5_0 arrives. + /// umrr9d_v1_4_1 T152 arrives. /// @param[in] sensor_idx The sensor id for the respected published topic. - /// @param[in] target_list_port The target list port + /// @param[in] targetlist_port_umrr9d_v1_4_1 The target list port /// @param[in] client_id The client_id of the sensor /// - void targetlist_callback_umrr9d_v1_5_0( + void targetlist_callback_umrr9d_v1_4_1( const std::uint32_t sensor_idx, - const std::shared_ptr - &targetlist_port_umrr9d_v1_5_0, - const com::types::ClientId client_id - ); + const std::shared_ptr< + com::master::umrr9d_t152_automotive_v1_4_1::comtargetlist::ComTargetList> & + targetlist_port_umrr9d_v1_4_1, + const com::types::ClientId client_id); /// /// @brief A callback that is called when a new target list port for - /// umrr9f_v2_5_0 T169 arrives. + /// umrr9f_v2_4_1 T169 arrives. /// /// @param[in] sensor_idx The sensor id for respective published topic. - /// @param[in] target_list_port The target list port + /// @param[in] targetlist_port_umrr9f_v2_4_1 The target list port /// @param[in] client_id The client_id of the sensor /// - void targetlist_callback_umrr9f_v2_5_0( - const std::uint32_t sensor_idx, - const std::shared_ptr - &targetlist_port_umrr9f_v2_5_0, - const com::types::ClientId client_id); + void targetlist_callback_umrr9f_v2_4_1( + const std::uint32_t sensor_idx, + const std::shared_ptr< + com::master::umrr9f_t169_automotive_v2_4_1::comtargetlist::ComTargetList> & + targetlist_port_umrr9f_v2_4_1, + const com::types::ClientId client_id); + + /// + /// @brief A callback that is called when a new CAN object list for + /// umrr9f_v1_0_0 T169 MSE arrives. + /// + /// @param[in] sensor_idx The sensor id for respective published topic. + /// @param[in] objectlist_can_umrr9f_mse_v1_0_0 The object list port + /// @param[in] client_id The client_id of the sensor + /// + /// + void CAN_objectlist_callback_umrr9f_mse_v1_0_0( + const std::uint32_t sensor_idx, + const std::shared_ptr< + com::master::umrr9f_t169_mse_v1_0_0::comobjectbaselist::ComObjectBaseList> & + objectlist_can_umrr9f_mse_v1_0_0, + const com::types::ClientId client_id); + + /// + /// @brief A callback that is called when a new CAN target list for + /// umrr9f_mse_v1_0_0 T169 MSE arrives. + /// @param[in] sensor_idx The sensor id for respective published topic. + /// @param[in] targetlist_can_umrr9f_mse_v1_0_0 The target list port + /// @param[in] client_id The client_id of the sensor. + /// + /// + void CAN_targetlist_callback_umrr9f_mse_v1_0_0( + const std::uint32_t sensor_idx, + const std::shared_ptr< + com::master::umrr9f_t169_mse_v1_0_0::comtargetbaselist::ComTargetBaseList> & + targetlist_can_umrr9f_mse_v1_0_0, + const com::types::ClientId client_id); /// /// @brief A callback that is called when a new CAN target list for - /// umrr96_v1_0_3 arrives. + /// umrr96_v1_2_2 T153 arrives. /// /// @param[in] sensor_idx The sensor id for respective published topic. - /// @param[in] target_list_port The target list port + /// @param[in] targetlist_can_umrr96 The target list port /// @param[in] client_id The client_id of the sensor /// void CAN_targetlist_callback_umrr96( - const std::uint32_t sensor_idx, - const std::shared_ptr - &targetlist_can_umrr96, - const com::types::ClientId client_id); + const std::uint32_t sensor_idx, + const std::shared_ptr< + com::master::umrr96_t153_automotive_v1_2_2::comtargetbaselist::ComTargetBaseList> & + targetlist_can_umrr96, + const com::types::ClientId client_id); - /// /// @brief A callback that is called when a new CAN target list for - /// umrr11 arrives. + /// umrr11_v1_1_2 T132 arrives. /// /// @param[in] sensor_idx The sensor id for respective published topic. - /// @param[in] target_list_port The target list port + /// @param[in] targetlist_can_umrr11 The target list port /// @param[in] client_id The client_id of the sensor /// void CAN_targetlist_callback_umrr11( - const std::uint32_t sensor_idx, - const std::shared_ptr - &targetlist_can_umrr11, - const com::types::ClientId client_id); - + const std::uint32_t sensor_idx, + const std::shared_ptr< + com::master::umrr11_t132_automotive_v1_1_2::comtargetbaselist::ComTargetBaseList> & + targetlist_can_umrr11, + const com::types::ClientId client_id); + /// /// @brief A callback that is called when a new CAN target list for - /// umrr9f_v2_1_1 arrives. + /// umrr9f_v2_1_1 T169arrives. /// /// @param[in] sensor_idx The sensor id for respective published topic. - /// @param[in] target_list_port The target list port + /// @param[in] targetlist_can_umrr9f_v2_1_1 The target list port /// @param[in] client_id The client_id of the sensor /// void CAN_targetlist_callback_umrr9f_v2_1_1( - const std::uint32_t sensor_idx, - const std::shared_ptr - &targetlist_can_umrr9f_v2_1_1, - const com::types::ClientId client_id); - + const std::uint32_t sensor_idx, + const std::shared_ptr< + com::master::umrr9f_t169_automotive_v2_1_1::comtargetbaselist::ComTargetBaseList> & + targetlist_can_umrr9f_v2_1_1, + const com::types::ClientId client_id); + /// /// @brief A callback that is called when a new CAN target list for - /// umrr9f_v2_2_1 arrives. + /// umrr9f_v2_2_1 T169 arrives. /// /// @param[in] sensor_idx The sensor id for respective published topic. - /// @param[in] target_list_port The target list port + /// @param[in] targetlist_can_umrr9f_v2_2_1 The target list port /// @param[in] client_id The client_id of the sensor /// void CAN_targetlist_callback_umrr9f_v2_2_1( - const std::uint32_t sensor_idx, - const std::shared_ptr - &targetlist_can_umrr9f_v2_2_1, - const com::types::ClientId client_id); + const std::uint32_t sensor_idx, + const std::shared_ptr< + com::master::umrr9f_t169_automotive_v2_2_1::comtargetbaselist::ComTargetBaseList> & + targetlist_can_umrr9f_v2_2_1, + const com::types::ClientId client_id); /// /// @brief A callback that is called when a new CAN target list for - /// umrr9d_v1_=_§ arrives. + /// umrr9d_v1_0_3 T152 arrives. /// /// @param[in] sensor_idx The sensor id for respective published topic. - /// @param[in] target_list_port The target list port + /// @param[in] targetlist_can_umrr9d_v1_0_3 The target list port /// @param[in] client_id The client_id of the sensor /// void CAN_targetlist_callback_umrr9d_v1_0_3( - const std::uint32_t sensor_idx, - const std::shared_ptr - &targetlist_can_umrr9d_v1_0_3, - const com::types::ClientId client_id); + const std::uint32_t sensor_idx, + const std::shared_ptr< + com::master::umrr9d_t152_automotive_v1_0_3::comtargetbaselist::ComTargetBaseList> & + targetlist_can_umrr9d_v1_0_3, + const com::types::ClientId client_id); /// /// @brief A callback that is called when a new CAN target list for - /// umrr9d_v1_2_2 arrives. + /// umrr9d_v1_2_2 T152 arrives. /// /// @param[in] sensor_idx The sensor id for respective published topic. - /// @param[in] target_list_port The target list port + /// @param[in] targetlist_can_umrr9d_v1_2_2 The target list port /// @param[in] client_id The client_id of the sensor /// void CAN_targetlist_callback_umrr9d_v1_2_2( - const std::uint32_t sensor_idx, - const std::shared_ptr - &targetlist_can_umrr9d_v1_2_2, - const com::types::ClientId client_id); + const std::uint32_t sensor_idx, + const std::shared_ptr< + com::master::umrr9d_t152_automotive_v1_2_2::comtargetbaselist::ComTargetBaseList> & + targetlist_can_umrr9d_v1_2_2, + const com::types::ClientId client_id); /// /// @brief A callback that is called when a new CAN target list for - /// umrra4 arrives. + /// umrra4_v1_0_1 T171 arrives. /// /// @param[in] sensor_idx The sensor id for respective published topic. - /// @param[in] target_list_port The target list port + /// @param[in] targetlist_can_umrra4_v1_0_1 The target list port /// @param[in] client_id The client_id of the sensor /// void CAN_targetlist_callback_umrra4_v1_0_1( - const std::uint32_t sensor_idx, - const std::shared_ptr - &targetlist_can_umrra4_v1_0_1, - const com::types::ClientId client_id); - + const std::uint32_t sensor_idx, + const std::shared_ptr< + com::master::umrra4_automotive_v1_0_1::comtargetbaselist::ComTargetBaseList> & + targetlist_can_umrra4_v1_0_1, + const com::types::ClientId client_id); + /// /// @brief A callback that is called when a new CAN target list for - /// umrra4 arrives. + /// umrra4_v1_2_1 T171 arrives. /// /// @param[in] sensor_idx The sensor id for respective published topic. - /// @param[in] target_list_port The target list port + /// @param[in] targetlist_can_umrra4_v1_2_1 The target list port /// @param[in] client_id The client_id of the sensor /// - void CAN_targetlist_callback_umrra4_v1_3_0( - const std::uint32_t sensor_idx, - const std::shared_ptr - &targetlist_can_umrra4_v1_3_0, - const com::types::ClientId client_id); + void CAN_targetlist_callback_umrra4_v1_2_1( + const std::uint32_t sensor_idx, + const std::shared_ptr< + com::master::umrra4_automotive_v1_2_1::comtargetbaselist::ComTargetBaseList> & + targetlist_can_umrra4_v1_2_1, + const com::types::ClientId client_id); /// /// @brief A callback that is called when a new CAN target list for - /// umrr9d_v1_5_0 arrives. + /// umrr9d_v1_4_1 T152 arrives. /// /// @param[in] sensor_idx The sensor id for respective published topic. - /// @param[in] target_list_port The target list port + /// @param[in] targetlist_can_umrr9d_v1_4_1 The target list port /// @param[in] client_id The client_id of the sensor /// - void CAN_targetlist_callback_umrr9d_v1_5_0( - const std::uint32_t sensor_idx, - const std::shared_ptr - &targetlist_can_umrr9d_v1_5_0, - const com::types::ClientId client_id); + void CAN_targetlist_callback_umrr9d_v1_4_1( + const std::uint32_t sensor_idx, + const std::shared_ptr< + com::master::umrr9d_t152_automotive_v1_4_1::comtargetbaselist::ComTargetBaseList> & + targetlist_can_umrr9d_v1_4_1, + const com::types::ClientId client_id); /// /// @brief A callback that is called when a new CAN target list for - /// umrr9f_v2_5_0 arrives. + /// umrr9f_v2_4_1 T169 arrives. /// /// @param[in] sensor_idx The sensor id for respective published topic. - /// @param[in] target_list_port The target list port + /// @param[in] targetlist_can_umrr9f_v2_4_1 The target list port /// @param[in] client_id The client_id of the sensor /// - void CAN_targetlist_callback_umrr9f_v2_5_0( - const std::uint32_t sensor_idx, - const std::shared_ptr - &targetlist_can_umrr9f_v2_5_0, - const com::types::ClientId client_id); + void CAN_targetlist_callback_umrr9f_v2_4_1( + const std::uint32_t sensor_idx, + const std::shared_ptr< + com::master::umrr9f_t169_automotive_v2_4_1::comtargetbaselist::ComTargetBaseList> & + targetlist_can_umrr9f_v2_4_1, + const com::types::ClientId client_id); /// /// @brief Read parameters and update the json config files required by @@ -435,54 +502,93 @@ class UMRR_ROS2_DRIVER_PUBLIC SmartmicroRadarNode : public ::rclcpp::Node { void update_config_files_from_params(); /// - /// @brief Callaback for getting the parameter response. + /// @brief Creates publishers for sensors using ports. + /// + /// @param[in] sensor The sensor configuration. + /// @param[in] sensor_idx The sensor index. /// - void - mode_response(const com::types::ClientId client_id, - const std::shared_ptr &response, - const std::string instruction_name); + void port_publishers(const detail::SensorConfig & sensor, size_t sensor_idx); /// - /// @brief Callaback for getting the command response. + /// @brief Creates publishers for sensors using CAN. /// - void - command_response(const com::types::ClientId client_id, - const std::shared_ptr &response, - const std::string command_name); + /// @param[in] sensor The sensor configuration. + /// @param[in] sensor_idx The sensor index. + /// + void can_publishers(const detail::SensorConfig & sensor, size_t sensor_idx); + + /// + /// @brief Callback for getting the parameter response. + /// + /// @param[in] client_id The client identifier. + /// @param[in] response The response batch. + /// @param[in] instruction_name The instruction name. + /// + void mode_response( + const com::types::ClientId client_id, + const std::shared_ptr & response, + const std::string instruction_name); + + /// + /// @brief Callback for getting the command response. + /// + /// @param[in] client_id The client identifier. + /// @param[in] response The response batch. + /// @param[in] command_name The command name. + /// + void command_response( + const com::types::ClientId client_id, + const std::shared_ptr & response, const std::string command_name); /// /// @brief Callback for changing IP address. /// + /// @param[in] client_id The client identifier. + /// @param[in] response The response batch. + /// void sensor_response_ip( - const com::types::ClientId client_id, - const std::shared_ptr &response); + const com::types::ClientId client_id, + const std::shared_ptr & response); /// - /// @brief Send instructions to the sensor. + /// @brief Sends instructions to the sensor. + /// + /// @param[in] request The request. + /// @param[out] response The response. /// void radar_mode( - const std::shared_ptr request, - std::shared_ptr response); + const std::shared_ptr request, + std::shared_ptr response); /// - /// @brief Configure the sensor ip address. + /// @brief Configures the sensor IP address. + /// + /// @param[in] request The request. + /// @param[out] response The response. /// - void ip_address(const std::shared_ptr request, - std::shared_ptr response); + void ip_address( + const std::shared_ptr request, + std::shared_ptr response); /// - /// @brief Send command to the sensor. + /// @brief Sends command to the sensor. + /// + /// @param[in] request The request. + /// @param[out] response The response. /// void radar_command( - const std::shared_ptr request, - std::shared_ptr response); + const std::shared_ptr request, + std::shared_ptr response); /// /// @brief Service for firmware download. /// + /// @param[in] request The request. + /// @param[out] result The result. + /// void firmware_download( - const std::shared_ptr request, - std::shared_ptr result); + const std::shared_ptr request, + std::shared_ptr result); rclcpp::Service::SharedPtr mode_srv_; rclcpp::Service::SharedPtr ip_addr_srv_; @@ -492,9 +598,28 @@ class UMRR_ROS2_DRIVER_PUBLIC SmartmicroRadarNode : public ::rclcpp::Node { std::array m_sensors{}; std::array m_adapters{}; - std::array::SharedPtr, - detail::kMaxSensorCount> - m_publishers{}; + std::array::SharedPtr, detail::kMaxSensorCount> + m_publishers_obj{}; + + std::array< + rclcpp::Publisher::SharedPtr, detail::kMaxSensorCount> + m_publishers_port_obj_header{}; + + std::array< + rclcpp::Publisher::SharedPtr, detail::kMaxSensorCount> + m_publishers_can_obj_header{}; + + std::array::SharedPtr, detail::kMaxSensorCount> + m_publishers{}; + + std::array< + rclcpp::Publisher::SharedPtr, detail::kMaxSensorCount> + m_publishers_port_target_header{}; + + std::array< + rclcpp::Publisher::SharedPtr, detail::kMaxSensorCount> + m_publishers_can_target_header{}; + std::size_t m_number_of_sensors{}; std::size_t m_number_of_adapters{}; rclcpp::TimerBase::SharedPtr timer; @@ -506,20 +631,30 @@ bool check_signal = false; std::string update_image{}; std::shared_ptr m_services{}; std::shared_ptr data_umrra4_v1_0_1{}; -std::shared_ptr data_umrra4_v1_3_0{}; +std::shared_ptr data_umrra4_v1_2_1{}; std::shared_ptr data_umrr11{}; std::shared_ptr data_umrr96{}; -std::shared_ptr data_umrr9f_v1_1_1{}; -std::shared_ptr data_umrr9f_v2_0_0{}; -std::shared_ptr data_umrr9f_v2_1_1{}; -std::shared_ptr data_umrr9f_v2_2_1{}; -std::shared_ptr data_umrr9f_v2_5_0{}; -std::shared_ptr data_umrr9d_v1_0_3{}; -std::shared_ptr data_umrr9d_v1_2_2{}; -std::shared_ptr data_umrr9d_v1_5_0{}; - -} // namespace radar -} // namespace drivers -} // namespace smartmicro - -#endif // UMRR_ROS2_DRIVER__SMARTMICRO_RADAR_NODE_HPP_ +std::shared_ptr + data_umrr9f_v1_1_1{}; +std::shared_ptr + data_umrr9f_v2_0_0{}; +std::shared_ptr + data_umrr9f_v2_1_1{}; +std::shared_ptr + data_umrr9f_v2_2_1{}; +std::shared_ptr + data_umrr9f_v2_4_1{}; +std::shared_ptr + data_umrr9d_v1_0_3{}; +std::shared_ptr + data_umrr9d_v1_2_2{}; +std::shared_ptr + data_umrr9d_v1_4_1{}; +std::shared_ptr + data_umrr9f_mse_v1_0_0{}; + +} // namespace radar +} // namespace drivers +} // namespace smartmicro + +#endif // UMRR_ROS2_DRIVER__SMARTMICRO_RADAR_NODE_HPP_ diff --git a/umrr_ros2_driver/package.xml b/umrr_ros2_driver/package.xml index 511291e..cd8eee0 100644 --- a/umrr_ros2_driver/package.xml +++ b/umrr_ros2_driver/package.xml @@ -2,7 +2,7 @@ umrr_ros2_driver - 6.1.0 + 7.0.0 A node to publish data from a smartmicro radar. s.m.s, smart microwave sensors GmbH. Apache 2.0 License @@ -14,6 +14,7 @@ rclcpp_components sensor_msgs point_cloud_msg_wrapper + visualization_msgs umrr_ros2_msgs ament_lint_auto diff --git a/umrr_ros2_driver/param/radar.params.template.yaml b/umrr_ros2_driver/param/radar.params.template.yaml index 501d612..35ad64a 100644 --- a/umrr_ros2_driver/param/radar.params.template.yaml +++ b/umrr_ros2_driver/param/radar.params.template.yaml @@ -11,13 +11,17 @@ sensors: # As many as 10 sensors all named as "sensor_" in increasing order of numbers, # e.g., sensor_0, sensor_1, etc. The list must start with sensor_0. - # For sensor `model`if using : - # can: 'umrra4_can_v1_0_1', 'umrr96_can', 'umrr11_can', 'umrr9d_can_v1_0_3', 'umrr9d_can_v1_2_2', 'umrr9f_can_v2_1_1', 'umrr9f_can_v2_2_1' - # port: 'umrra4_v1_0_1', 'umrr96', 'umrr11', 'umrr9d_v1_0_3', 'umrr9d_v1_2_2', 'umrr9f_v1_1_1', 'umrr9f_v2_1_1', 'umrr9f_v2_2_1' + # + # Sensor `model` names if using link type: + # can: 'umrr9f_can_mse_v1_0_0', 'umrra4_can_v1_0_1', 'umrr96_can_v1_2_2', 'umrr11_can_v1_1_2', 'umrr9d_can_v1_0_3', 'umrr9d_can_v1_2_2', 'umrr9f_can_v2_1_1', 'umrr9f_can_v2_2_1' + # port: 'umrr9f_mse_v1_0_0', 'umrra4_v1_0_1', 'umrr96_v1_2_2', 'umrr11_v1_1_2', 'umrr9d_v1_0_3', 'umrr9d_v1_2_2', 'umrr9f_v1_1_1', 'umrr9f_v2_1_1', 'umrr9f_v2_2_1' sensor_0: + # The link of the sensor either 'can' or 'eth' link_type: "eth" + # The publisher type of the sensor + pub_type: "target" # The model of the connected sensor. - model: "umrr11" + model: "umrr11_v1_1_2" # Adapter id to which sensor is connected dev_id: 3 # The client_id of the sensor/source, must be a unique integer. @@ -41,9 +45,12 @@ # The pathc version of the interface uifpatchv: 2 sensor_1: + # The link of the sensor either 'can' or 'eth' link_type: "eth" + # The publisher type of the sensor + pub_type: "target" # The model of the connected sensor. - model: "umrr96" + model: "umrr96_v1_2_2" # Adapter id to which sensor is connected dev_id: 3 # The client_id of the sensor/source, must be a unique integer. @@ -67,7 +74,10 @@ # The pathc version of the interface uifpatchv: 2 sensor_2: + # The link of the sensor either 'can' or 'eth' link_type: "eth" + # The publisher type of the sensor + pub_type: "target" # The model of the connected sensor. model: "umrr9f_v2_1_1" # Adapter id to which sensor is connected @@ -93,7 +103,10 @@ # The pathc version of the interface uifpatchv: 1 sensor_3: + # The link of the sensor either 'can' or 'eth' link_type: "eth" + # The publisher type of the sensor + pub_type: "target" # The model of the connected sensor. model: "umrr9d_v1_0_3" # Adapter id to which sensor is connected diff --git a/umrr_ros2_driver/src/smartmicro_radar_node.cpp b/umrr_ros2_driver/src/smartmicro_radar_node.cpp index 9b6489b..2f5384f 100644 --- a/umrr_ros2_driver/src/smartmicro_radar_node.cpp +++ b/umrr_ros2_driver/src/smartmicro_radar_node.cpp @@ -27,8 +27,8 @@ #include #include #include -#include -#include +#include +#include #include #include #include @@ -37,12 +37,14 @@ #include #include #include -#include -#include +#include +#include +#include +#include #include #include -#include -#include +#include +#include #include @@ -54,6 +56,7 @@ #include #include + #include #include #include @@ -121,7 +124,6 @@ constexpr bool float_eq(const float a, const float b) noexcept const auto maximum = std::max(std::fabs(a), std::fabs(b)); return std::fabs(a - b) <= maximum * std::numeric_limits::epsilon(); } - struct RadarPoint { float x{}; @@ -160,6 +162,51 @@ using Generators = std::tuple< field_elevation_angle_generator, field_range_generator>; using RadarCloudModifier = PointCloud2Modifier; +struct ObjectPoint +{ + float x{}; + float y{}; + float z{}; + float speed_absolute{}; + float heading{}; + float length{}; + float mileage{}; + float quality{}; + float acceleration{}; + int16_t object_id{}; + uint16_t idle_cycles{}; + uint16_t spline_idx{}; + uint8_t object_class{}; + uint16_t status{}; + + constexpr friend bool operator==(const ObjectPoint & p1, const ObjectPoint & p2) noexcept + { + return float_eq(p1.x, p2.x) && float_eq(p1.y, p2.y) && float_eq(p1.z, p2.z) && + float_eq(p1.speed_absolute, p2.speed_absolute) && float_eq(p1.heading, p2.heading) && + float_eq(p1.length, p2.length) && float_eq(p1.mileage, p2.mileage) && + float_eq(p1.quality, p2.quality) && float_eq(p1.acceleration, p2.acceleration); + } +}; + +LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(speed_absolute); +LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(heading); +LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(length); +LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(mileage); +LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(quality); +LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(acceleration); +LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(object_id); +LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(idle_cycles); +LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(spline_idx); +LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(object_class); +LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(status); +using GeneratorsObjectPoint = std::tuple< + point_cloud_msg_wrapper::field_x_generator, point_cloud_msg_wrapper::field_y_generator, + point_cloud_msg_wrapper::field_z_generator, field_speed_absolute_generator, + field_heading_generator, field_length_generator, field_mileage_generator, field_quality_generator, + field_acceleration_generator, field_object_id_generator, field_idle_cycles_generator, + field_spline_idx_generator, field_object_class_generator, field_status_generator>; + +using ObjectPointCloudModifier = PointCloud2Modifier; } // namespace namespace smartmicro @@ -183,7 +230,7 @@ SmartmicroRadarNode::SmartmicroRadarNode(const rclcpp::NodeOptions & node_option } // Getting the data stream service - data_umrra4_v1_3_0 = com::master::umrra4_automotive_v1_3_0::DataStreamServiceIface::Get(); + data_umrra4_v1_2_1 = com::master::umrra4_automotive_v1_2_1::DataStreamServiceIface::Get(); data_umrra4_v1_0_1 = com::master::umrra4_automotive_v1_0_1::DataStreamServiceIface::Get(); data_umrr11 = com::master::umrr11_t132_automotive_v1_1_2::DataStreamServiceIface::Get(); data_umrr96 = com::master::umrr96_t153_automotive_v1_2_2::DataStreamServiceIface::Get(); @@ -191,221 +238,16 @@ SmartmicroRadarNode::SmartmicroRadarNode(const rclcpp::NodeOptions & node_option data_umrr9f_v2_0_0 = com::master::umrr9f_t169_automotive_v2_0_0::DataStreamServiceIface::Get(); data_umrr9f_v2_1_1 = com::master::umrr9f_t169_automotive_v2_1_1::DataStreamServiceIface::Get(); data_umrr9f_v2_2_1 = com::master::umrr9f_t169_automotive_v2_2_1::DataStreamServiceIface::Get(); - data_umrr9f_v2_5_0 = com::master::umrr9f_t169_automotive_v2_5_0::DataStreamServiceIface::Get(); + data_umrr9f_v2_4_1 = com::master::umrr9f_t169_automotive_v2_4_1::DataStreamServiceIface::Get(); data_umrr9d_v1_0_3 = com::master::umrr9d_t152_automotive_v1_0_3::DataStreamServiceIface::Get(); data_umrr9d_v1_2_2 = com::master::umrr9d_t152_automotive_v1_2_2::DataStreamServiceIface::Get(); - data_umrr9d_v1_5_0 = com::master::umrr9d_t152_automotive_v1_5_0::DataStreamServiceIface::Get(); + data_umrr9d_v1_4_1 = com::master::umrr9d_t152_automotive_v1_4_1::DataStreamServiceIface::Get(); + data_umrr9f_mse_v1_0_0 = com::master::umrr9f_t169_mse_v1_0_0::DataStreamServiceIface::Get(); // Wait for initailization std::this_thread::sleep_for(std::chrono::seconds(2)); RCLCPP_INFO(this->get_logger(), "Data stream services have been received!"); - for (auto i = 0UL; i < m_number_of_sensors; ++i) { - const auto & sensor = m_sensors[i]; - - m_publishers[i] = create_publisher( - "smart_radar/targets_" + std::to_string(i), sensor.history_size); - - if ( - sensor.model == "umrra4_v1_3_0" && - com::types::ERROR_CODE_OK != - data_umrra4_v1_3_0->RegisterComTargetListReceiveCallback( - sensor.id, std::bind( - &SmartmicroRadarNode::targetlist_callback_umrra4_v1_3_0, this, i, - std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register targetlist callback for sensor umrra4_v1_3_0" << std::endl; - } - if ( - sensor.model == "umrra4_v1_0_1" && - com::types::ERROR_CODE_OK != - data_umrra4_v1_0_1->RegisterComTargetListReceiveCallback( - sensor.id, std::bind( - &SmartmicroRadarNode::targetlist_callback_umrra4_v1_0_1, this, i, - std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register targetlist callback for sensor umrra4_v1_0_1" << std::endl; - } - if ( - sensor.model == "umrr96" && - com::types::ERROR_CODE_OK != - data_umrr96->RegisterComTargetListReceiveCallback( - sensor.id, std::bind( - &SmartmicroRadarNode::targetlist_callback_umrr96, this, i, - std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register targetlist callback for sensor umrr96" << std::endl; - } - if ( - sensor.model == "umrr11" && - com::types::ERROR_CODE_OK != - data_umrr11->RegisterComTargetListReceiveCallback( - sensor.id, std::bind( - &SmartmicroRadarNode::targetlist_callback_umrr11, this, i, - std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register targetlist callback for sensor umrr11" << std::endl; - } - if ( - sensor.model == "umrr9f_v1_1_1" && - com::types::ERROR_CODE_OK != - data_umrr9f_v1_1_1->RegisterComTargetListPortReceiveCallback( - sensor.id, std::bind( - &SmartmicroRadarNode::targetlist_callback_umrr9f_v1_1_1, this, i, - std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register targetlist callback for sensor umrr9f_v1_1_1" << std::endl; - } - if ( - sensor.model == "umrr9f_v2_0_0" && - com::types::ERROR_CODE_OK != - data_umrr9f_v2_0_0->RegisterComTargetListPortReceiveCallback( - sensor.id, std::bind( - &SmartmicroRadarNode::targetlist_callback_umrr9f_v2_0_0, this, i, - std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register targetlist callback for sensor umrr9f_v2_0_0" << std::endl; - } - if ( - sensor.model == "umrr9f_v2_1_1" && - com::types::ERROR_CODE_OK != - data_umrr9f_v2_1_1->RegisterComTargetListReceiveCallback( - sensor.id, std::bind( - &SmartmicroRadarNode::targetlist_callback_umrr9f_v2_1_1, this, i, - std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register targetlist callback for sensor umrr9f" << std::endl; - } - if ( - sensor.model == "umrr9f_v2_2_1" && - com::types::ERROR_CODE_OK != - data_umrr9f_v2_2_1->RegisterComTargetListReceiveCallback( - sensor.id, std::bind( - &SmartmicroRadarNode::targetlist_callback_umrr9f_v2_2_1, this, i, - std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register targetlist callback for sensor umrr9f_v2_2_1" << std::endl; - } - if ( - sensor.model == "umrr9d_v1_0_3" && - com::types::ERROR_CODE_OK != - data_umrr9d_v1_0_3->RegisterComTargetListReceiveCallback( - sensor.id, std::bind( - &SmartmicroRadarNode::targetlist_callback_umrr9d_v1_0_3, this, i, - std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register targetlist callback for sensor umrr9d_v1_0_3" << std::endl; - } - if ( - sensor.model == "umrr9d_v1_2_2" && - com::types::ERROR_CODE_OK != - data_umrr9d_v1_2_2->RegisterComTargetListReceiveCallback( - sensor.id, std::bind( - &SmartmicroRadarNode::targetlist_callback_umrr9d_v1_2_2, this, i, - std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register targetlist callback for sensor umrr9d_v1_2_2" << std::endl; - } - if ( - sensor.model == "umrr9d_v1_5_0" && - com::types::ERROR_CODE_OK != - data_umrr9d_v1_5_0->RegisterComTargetListReceiveCallback( - sensor.id, std::bind( - &SmartmicroRadarNode::targetlist_callback_umrr9d_v1_5_0, this, i, - std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register targetlist callback for sensor umrr9d_v1_5_0" << std::endl; - } - if ( - sensor.model == "umrr9f_v2_5_0" && - com::types::ERROR_CODE_OK != - data_umrr9f_v2_5_0->RegisterComTargetListReceiveCallback( - sensor.id, std::bind( - &SmartmicroRadarNode::targetlist_callback_umrr9f_v2_5_0, this, i, - std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register targetlist callback for sensor umrr9f_v2_5_0" << std::endl; - } - if ( - sensor.model == "umrra4_can_v1_3_0" && - com::types::ERROR_CODE_OK != - data_umrra4_v1_3_0->RegisterComTargetBaseListReceiveCallback( - sensor.id, std::bind( - &SmartmicroRadarNode::CAN_targetlist_callback_umrra4_v1_3_0, this, i, - std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register CAN targetlist for sensor umrra4_v1_3_0" << std::endl; - } - if ( - sensor.model == "umrra4_can_v1_0_1" && - com::types::ERROR_CODE_OK != - data_umrra4_v1_0_1->RegisterComTargetBaseListReceiveCallback( - sensor.id, std::bind( - &SmartmicroRadarNode::CAN_targetlist_callback_umrra4_v1_0_1, this, i, - std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register CAN targetlist for sensor umrra4_v1_0_1" << std::endl; - } - if ( - sensor.model == "umrr96_can" && - com::types::ERROR_CODE_OK != - data_umrr96->RegisterComTargetBaseListReceiveCallback( - sensor.id, std::bind( - &SmartmicroRadarNode::CAN_targetlist_callback_umrr96, this, i, - std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register CAN targetlist for sensor umrr96" << std::endl; - } - if ( - sensor.model == "umrr11_can" && - com::types::ERROR_CODE_OK != - data_umrr11->RegisterComTargetBaseListReceiveCallback( - sensor.id, std::bind( - &SmartmicroRadarNode::CAN_targetlist_callback_umrr11, this, i, - std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register CAN targetlist for sensor umrr11" << std::endl; - } - if ( - sensor.model == "umrr9d_can_v1_0_3" && - com::types::ERROR_CODE_OK != - data_umrr9d_v1_0_3->RegisterComTargetBaseListReceiveCallback( - sensor.id, std::bind( - &SmartmicroRadarNode::CAN_targetlist_callback_umrr9d_v1_0_3, this, i, - std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register CAN targetlist for sensor umrr9d_v1_0_3" << std::endl; - } - if ( - sensor.model == "umrr9d_can_v1_2_2" && - com::types::ERROR_CODE_OK != - data_umrr9d_v1_2_2->RegisterComTargetBaseListReceiveCallback( - sensor.id, std::bind( - &SmartmicroRadarNode::CAN_targetlist_callback_umrr9d_v1_2_2, this, i, - std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register CAN targetlist for sensor umrr9d_v1_2_2" << std::endl; - } - if ( - sensor.model == "umrr9f_can_v2_1_1" && - com::types::ERROR_CODE_OK != - data_umrr9f_v2_1_1->RegisterComTargetBaseListReceiveCallback( - sensor.id, std::bind( - &SmartmicroRadarNode::CAN_targetlist_callback_umrr9f_v2_1_1, this, i, - std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register CAN targetlist for sensor umrr9f_v2_1_1" << std::endl; - } - if ( - sensor.model == "umrr9f_can_v2_2_1" && - com::types::ERROR_CODE_OK != - data_umrr9f_v2_2_1->RegisterComTargetBaseListReceiveCallback( - sensor.id, std::bind( - &SmartmicroRadarNode::CAN_targetlist_callback_umrr9f_v2_2_1, this, i, - std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register CAN targetlist for sensor umrr9f_v2_2_1" << std::endl; - } - if ( - sensor.model == "umrr9d_can_v1_5_0" && - com::types::ERROR_CODE_OK != - data_umrr9d_v1_5_0->RegisterComTargetBaseListReceiveCallback( - sensor.id, std::bind( - &SmartmicroRadarNode::CAN_targetlist_callback_umrr9d_v1_5_0, this, i, - std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register CAN targetlist for sensor umrr9d_v1_5_0" << std::endl; - } - if ( - sensor.model == "umrr9f_can_v2_5_0" && - com::types::ERROR_CODE_OK != - data_umrr9f_v2_5_0->RegisterComTargetBaseListReceiveCallback( - sensor.id, std::bind( - &SmartmicroRadarNode::CAN_targetlist_callback_umrr9f_v2_5_0, this, i, - std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register CAN targetlist for sensor umrr9f_v2_5_0" << std::endl; - } - } - // create a ros2 service to change the radar parameters mode_srv_ = create_service( "smart_radar/set_radar_mode", @@ -432,12 +274,327 @@ SmartmicroRadarNode::SmartmicroRadarNode(const rclcpp::NodeOptions & node_option RCLCPP_INFO(this->get_logger(), "Radar services are ready."); + for (auto i = 0UL; i < m_number_of_sensors; ++i) { + const auto & sensor = m_sensors[i]; + + if (sensor.pub_type == "mse") { + if (sensor.model.find("mse") == std::string::npos) { + throw std::runtime_error("Model name must contain 'mse' when pub_type is 'mse'"); + } + } else if (sensor.pub_type == "target") { + if (sensor.model.find("mse") != std::string::npos) { + throw std::runtime_error("Model name must not contain 'mse' when pub_type is 'target'"); + } + } + + if (sensor.link_type == "eth") { + port_publishers(sensor, i); + } else if (sensor.link_type == "can") { + can_publishers(sensor, i); + } else { + RCLCPP_INFO(this->get_logger(), "Link type for sensor unknown!"); + } + } rclcpp::on_shutdown(std::bind(&SmartmicroRadarNode::on_shutdown_callback, this)); } +void SmartmicroRadarNode::port_publishers(const detail::SensorConfig & sensor, size_t sensor_idx) +{ + if (m_sensors[sensor_idx].pub_type == "mse") { + m_publishers_obj[sensor_idx] = create_publisher( + "smart_radar/port_objects_" + std::to_string(sensor_idx), sensor.history_size); + m_publishers_port_obj_header[sensor_idx] = + create_publisher( + "smart_radar/port_objectheader_" + std::to_string(sensor_idx), sensor.history_size); + m_publishers[sensor_idx] = create_publisher( + "smart_radar/port_targets_" + std::to_string(sensor_idx), sensor.history_size); + m_publishers_port_target_header[sensor_idx] = + create_publisher( + "smart_radar/port_targetheader_" + std::to_string(sensor_idx), sensor.history_size); + } else if (m_sensors[sensor_idx].pub_type == "target") { + m_publishers[sensor_idx] = create_publisher( + "smart_radar/port_targets_" + std::to_string(sensor_idx), sensor.history_size); + m_publishers_port_target_header[sensor_idx] = + create_publisher( + "smart_radar/port_targetheader_" + std::to_string(sensor_idx), sensor.history_size); + } else { + RCLCPP_INFO(this->get_logger(), "Unkwon publish type!"); + } + + RCLCPP_INFO(this->get_logger(), "Inside PORT publishers"); + + if (sensor.model == "umrr9f_mse_v1_0_0") { + if ( + com::types::ERROR_CODE_OK != + data_umrr9f_mse_v1_0_0->RegisterComObjectListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::objectlist_callback_umrr9f_mse_v1_0_0, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register objectlist callback for sensor umrr9f_mse" << std::endl; + } + + if ( + com::types::ERROR_CODE_OK != + data_umrr9f_mse_v1_0_0->RegisterComTargetListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::targetlist_callback_umrr9f_mse_v1_0_0, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register targetlist callback for sensor umrr9f_mse" << std::endl; + } + } + if ( + sensor.model == "umrr96_v1_2_2" && + com::types::ERROR_CODE_OK != + data_umrr96->RegisterComTargetListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::targetlist_callback_umrr96, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register targetlist callback for sensor umrr96" << std::endl; + } + if ( + sensor.model == "umrr11_v1_1_2" && + com::types::ERROR_CODE_OK != + data_umrr11->RegisterComTargetListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::targetlist_callback_umrr11, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register targetlist callback for sensor umrr11" << std::endl; + } + if ( + sensor.model == "umrr9f_v1_1_1" && + com::types::ERROR_CODE_OK != + data_umrr9f_v1_1_1->RegisterComTargetListPortReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::targetlist_callback_umrr9f_v1_1_1, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register targetlist callback for sensor umrr9f_v1_1_1" << std::endl; + } + if ( + sensor.model == "umrr9f_v2_0_0" && + com::types::ERROR_CODE_OK != + data_umrr9f_v2_0_0->RegisterComTargetListPortReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::targetlist_callback_umrr9f_v2_0_0, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register targetlist callback for sensor umrr9f_v2_0_0" << std::endl; + } + if ( + sensor.model == "umrr9f_v2_1_1" && + com::types::ERROR_CODE_OK != + data_umrr9f_v2_1_1->RegisterComTargetListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::targetlist_callback_umrr9f_v2_1_1, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register targetlist callback for sensor umrr9f" << std::endl; + } + if ( + sensor.model == "umrr9f_v2_2_1" && + com::types::ERROR_CODE_OK != + data_umrr9f_v2_2_1->RegisterComTargetListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::targetlist_callback_umrr9f_v2_2_1, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register targetlist callback for sensor umrr9f_v2_2_1" << std::endl; + } + if ( + sensor.model == "umrr9f_v2_4_1" && + com::types::ERROR_CODE_OK != + data_umrr9f_v2_4_1->RegisterComTargetListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::targetlist_callback_umrr9f_v2_4_1, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register targetlist callback for sensor umrr9f_v2_4_1" << std::endl; + } + if ( + sensor.model == "umrr9d_v1_0_3" && + com::types::ERROR_CODE_OK != + data_umrr9d_v1_0_3->RegisterComTargetListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::targetlist_callback_umrr9d_v1_0_3, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register targetlist callback for sensor umrr9d_v1_0_3" << std::endl; + } + if ( + sensor.model == "umrr9d_v1_2_2" && + com::types::ERROR_CODE_OK != + data_umrr9d_v1_2_2->RegisterComTargetListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::targetlist_callback_umrr9d_v1_2_2, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register targetlist callback for sensor umrr9d_v1_2_2" << std::endl; + } + if ( + sensor.model == "umrr9d_v1_4_1" && + com::types::ERROR_CODE_OK != + data_umrr9d_v1_4_1->RegisterComTargetListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::targetlist_callback_umrr9d_v1_4_1, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + RCLCPP_INFO( + this->get_logger(), "Failed to register targetlist callback for sensor umrr9d_v1_4_1"); + std::cout << "Failed to register targetlist callback for sensor umrr9d_v1_4_1" << std::endl; + } + if ( + sensor.model == "umrra4_v1_0_1" && + com::types::ERROR_CODE_OK != + data_umrra4_v1_0_1->RegisterComTargetListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::targetlist_callback_umrra4_v1_0_1, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register targetlist callback for sensor umrra4_v1_0_1" << std::endl; + } + if ( + sensor.model == "umrra4_v1_2_1" && + com::types::ERROR_CODE_OK != + data_umrra4_v1_2_1->RegisterComTargetListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::targetlist_callback_umrra4_v1_2_1, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register targetlist callback for sensor umrra4_v1_2_1" << std::endl; + } +} + +void SmartmicroRadarNode::can_publishers(const detail::SensorConfig & sensor, size_t sensor_idx) +{ + if (m_sensors[sensor_idx].pub_type == "mse") { + m_publishers_obj[sensor_idx] = create_publisher( + "smart_radar/can_objects_" + std::to_string(sensor_idx), sensor.history_size); + m_publishers_can_obj_header[sensor_idx] = + create_publisher( + "smart_radar/can_objectheader_" + std::to_string(sensor_idx), sensor.history_size); + + m_publishers[sensor_idx] = create_publisher( + "smart_radar/can_targets_" + std::to_string(sensor_idx), sensor.history_size); + m_publishers_can_target_header[sensor_idx] = + create_publisher( + "smart_radar/can_targetheader_" + std::to_string(sensor_idx), sensor.history_size); + } else if (m_sensors[sensor_idx].pub_type == "target") { + m_publishers[sensor_idx] = create_publisher( + "smart_radar/can_targets_" + std::to_string(sensor_idx), sensor.history_size); + m_publishers_can_target_header[sensor_idx] = + create_publisher( + "smart_radar/can_targetheader_" + std::to_string(sensor_idx), sensor.history_size); + } else { + RCLCPP_INFO(this->get_logger(), "Unkwon publish type!"); + } + + RCLCPP_INFO(this->get_logger(), "Inside CAN publisher"); + + if (sensor.model == "umrr9f_can_mse_v1_0_0") { + if ( + com::types::ERROR_CODE_OK != + data_umrr9f_mse_v1_0_0->RegisterComObjectBaseListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::CAN_objectlist_callback_umrr9f_mse_v1_0_0, this, + sensor_idx, std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register objectlist callback for sensor umrr9f_can_mse_v1_0_0" + << std::endl; + } + if ( + com::types::ERROR_CODE_OK != + data_umrr9f_mse_v1_0_0->RegisterComTargetBaseListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::CAN_targetlist_callback_umrr9f_mse_v1_0_0, this, + sensor_idx, std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register targetlist callback for sensor umrr9f_can_mse_v1_0_0" + << std::endl; + } + } + if ( + sensor.model == "umrr96_can_v1_2_2" && + com::types::ERROR_CODE_OK != + data_umrr96->RegisterComTargetBaseListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::CAN_targetlist_callback_umrr96, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register CAN targetlist for sensor umrr96" << std::endl; + } + if ( + sensor.model == "umrr11_can_v1_1_2" && + com::types::ERROR_CODE_OK != + data_umrr11->RegisterComTargetBaseListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::CAN_targetlist_callback_umrr11, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register CAN targetlist for sensor umrr11" << std::endl; + } + if ( + sensor.model == "umrr9f_can_v2_1_1" && + com::types::ERROR_CODE_OK != + data_umrr9f_v2_1_1->RegisterComTargetBaseListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::CAN_targetlist_callback_umrr9f_v2_1_1, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register CAN targetlist for sensor umrr9f_v2_1_1" << std::endl; + } + if ( + sensor.model == "umrr9f_can_v2_2_1" && + com::types::ERROR_CODE_OK != + data_umrr9f_v2_2_1->RegisterComTargetBaseListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::CAN_targetlist_callback_umrr9f_v2_2_1, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register CAN targetlist for sensor umrr9f_v2_2_1" << std::endl; + } + if ( + sensor.model == "umrr9f_can_v2_4_1" && + com::types::ERROR_CODE_OK != + data_umrr9f_v2_4_1->RegisterComTargetBaseListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::CAN_targetlist_callback_umrr9f_v2_4_1, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register CAN targetlist for sensor umrr9f_v2_4_1" << std::endl; + } + if ( + sensor.model == "umrr9d_can_v1_0_3" && + com::types::ERROR_CODE_OK != + data_umrr9d_v1_0_3->RegisterComTargetBaseListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::CAN_targetlist_callback_umrr9d_v1_0_3, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register CAN targetlist for sensor umrr9d_v1_0_3" << std::endl; + } + if ( + sensor.model == "umrr9d_can_v1_2_2" && + com::types::ERROR_CODE_OK != + data_umrr9d_v1_2_2->RegisterComTargetBaseListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::CAN_targetlist_callback_umrr9d_v1_2_2, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register CAN targetlist for sensor umrr9d_v1_2_2" << std::endl; + } + if ( + sensor.model == "umrr9d_can_v1_4_1" && + com::types::ERROR_CODE_OK != + data_umrr9d_v1_4_1->RegisterComTargetBaseListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::CAN_targetlist_callback_umrr9d_v1_4_1, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register CAN targetlist for sensor umrr9d_v1_4_1" << std::endl; + } + if ( + sensor.model == "umrra4_can_v1_0_1" && + com::types::ERROR_CODE_OK != + data_umrra4_v1_0_1->RegisterComTargetBaseListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::CAN_targetlist_callback_umrra4_v1_0_1, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register CAN targetlist for sensor umrra4_v1_0_1" << std::endl; + } + if ( + sensor.model == "umrra4_can_v1_2_1" && + com::types::ERROR_CODE_OK != + data_umrra4_v1_2_1->RegisterComTargetBaseListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::CAN_targetlist_callback_umrra4_v1_2_1, this, sensor_idx, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register CAN targetlist for sensor umrra4_v1_2_1" << std::endl; + } +} + void SmartmicroRadarNode::on_shutdown_callback() { - RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Shutdown called!!!"); + RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Shutdown called!"); check_signal = true; rclcpp::Rate sleepRate(std::chrono::milliseconds(100)); sleepRate.sleep(); @@ -679,28 +836,164 @@ void SmartmicroRadarNode::command_response( for (auto & resp : command_resp) { response_type = resp->GetResponseType(); RCLCPP_INFO(this->get_logger(), "Response from sensor to command: %i", response_type); + uint32_t value = resp->GetValue(); + RCLCPP_INFO(this->get_logger(), "Response from sensor to command: %i", value); + } + } +} + +void SmartmicroRadarNode::objectlist_callback_umrr9f_mse_v1_0_0( + const std::uint32_t sensor_idx, + const std::shared_ptr & + objectlist_port_umrr9f_mse_v1_0_0, + const com::types::ClientId client_id) +{ + std::cout << "Objectlist for umrr9f_mse_v1_0_0" << std::endl; + if (!check_signal) { + std::shared_ptr port_header; + port_header = objectlist_port_umrr9f_mse_v1_0_0->GetPortHeader(); + std::shared_ptr + object_header; + object_header = objectlist_port_umrr9f_mse_v1_0_0->GetObjectListHeader(); + sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::PortObjectHeader header; + ObjectPointCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; + const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; + const auto sec = std::chrono::duration_cast(timestamp); + const auto nanosec = std::chrono::duration_cast(timestamp - sec); + msg.header.stamp.sec = sec.count(); + msg.header.stamp.nanosec = nanosec.count(); + header.frame_id = m_sensors[sensor_idx].frame_id; + header.port_identifier = port_header->GetPortIdentifier(); + header.port_ver_major = port_header->GetPortVersionMajor(); + header.port_ver_minor = port_header->GetPortVersionMinor(); + header.port_size = port_header->GetPortSize(); + header.body_endianness = port_header->GetBodyEndianness(); + header.port_index = port_header->GetPortIndex(); + header.header_ver_major = port_header->GetHeaderVersionMajor(); + header.header_ver_minor = port_header->GetHeaderVersionMinor(); + header.cycle_time = object_header->GetCycleTime(); + header.number_of_objects = object_header->GetNumberOfObjects(); + header.ts_measurement = object_header->GetTimestampOfMeasurement(); + for (const auto & object : objectlist_port_umrr9f_mse_v1_0_0->GetObjectList()) { + const auto x_pos = object->GetPosX(); + const auto y_pos = object->GetPosY(); + const auto z_pos = object->GetPosZ(); + const auto speed_abs = object->GetSpeedAbs(); + const auto heading = object->GetHeading(); + const auto length = object->GetLength(); + const auto mileage = object->GetMileage(); + const auto quality = object->GetQuality(); + const auto acceleration = object->GetAcceleration(); + const auto object_id = object->GetObjectId(); + const auto idle_cycles = object->GetIdleCycles(); + const auto status = object->GetStatus(); + + modifier.push_back( + {x_pos, y_pos, z_pos, speed_abs, heading, length, mileage, quality, acceleration, object_id, + idle_cycles, status}); + } + + m_publishers_obj[sensor_idx]->publish(msg); + m_publishers_port_obj_header[sensor_idx]->publish(header); + } +} + +void SmartmicroRadarNode::targetlist_callback_umrr9f_mse_v1_0_0( + const std::uint32_t sensor_idx, + const std::shared_ptr & + targetlist_port_umrr9f_mse_v1_0_0, + const com::types::ClientId client_id) +{ + std::cout << "Port Targetlist for umrr9f_mse_v1_0_0" << std::endl; + if (!check_signal) { + std::shared_ptr port_header; + port_header = targetlist_port_umrr9f_mse_v1_0_0->GetPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_port_umrr9f_mse_v1_0_0->GetTargetListHeader(); + sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::PortTargetHeader header; + RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; + const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; + const auto sec = std::chrono::duration_cast(timestamp); + const auto nanosec = std::chrono::duration_cast(timestamp - sec); + msg.header.stamp.sec = sec.count(); + msg.header.stamp.nanosec = nanosec.count(); + header.frame_id = m_sensors[sensor_idx].frame_id; + header.port_identifier = port_header->GetPortIdentifier(); + header.port_ver_major = port_header->GetPortVersionMajor(); + header.port_ver_minor = port_header->GetPortVersionMinor(); + header.port_size = port_header->GetPortSize(); + header.body_endianness = port_header->GetBodyEndianness(); + header.port_index = port_header->GetPortIndex(); + header.header_ver_major = port_header->GetHeaderVersionMajor(); + header.header_ver_minor = port_header->GetHeaderVersionMinor(); + header.cycle_time = target_header->GetCycleTime(); + header.number_of_targets = target_header->GetNumberOfTargets(); + header.acquisition_tx_ant_idx = target_header->GetAcquisitionTxAntIdx(); + header.acquisition_sweep_idx = target_header->GetAcquisitionSweepIdx(); + header.acquisition_cf_idx = target_header->GetAcquisitionCfIdx(); + header.prf = target_header->GetPrf(); + header.umambiguous_speed = target_header->GetUmambiguousSpeed(); + header.acquisition_start = target_header->GetAcquisitionStart(); + for (const auto & target : targetlist_port_umrr9f_mse_v1_0_0->GetTargetList()) { + const auto range = target->GetRange(); + const auto elevation_angle = target->GetElevationAngle(); + const auto range_2d = range * std::cos(elevation_angle); + const auto azimuth_angle = target->GetAzimuthAngle(); + const auto snr = target->GetPower() - target->GetNoise(); + modifier.push_back( + {range_2d * std::cos(azimuth_angle), range_2d * std::sin(azimuth_angle), + range * std::sin(elevation_angle), target->GetSpeedRadial(), target->GetPower(), + target->GetRcs(), target->GetNoise(), snr, azimuth_angle, elevation_angle, range}); } + + m_publishers[sensor_idx]->publish(msg); + m_publishers_port_target_header[sensor_idx]->publish(header); } } -void SmartmicroRadarNode::targetlist_callback_umrra4_v1_3_0( +void SmartmicroRadarNode::targetlist_callback_umrra4_v1_2_1( const std::uint32_t sensor_idx, - const std::shared_ptr & - targetlist_port_umrra4_v1_3_0, + const std::shared_ptr & + targetlist_port_umrra4_v1_2_1, const com::types::ClientId client_id) { - std::cout << "Targetlist for umrra4_v1_3_0" << std::endl; + std::cout << "Targetlist for umrra4_v1_2_1" << std::endl; if (!check_signal) { - std::shared_ptr port_header; - port_header = targetlist_port_umrra4_v1_3_0->GetPortHeader(); + std::shared_ptr port_header; + port_header = targetlist_port_umrra4_v1_2_1->GetPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_port_umrra4_v1_2_1->GetTargetListHeader(); sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::PortTargetHeader header; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; const auto sec = std::chrono::duration_cast(timestamp); const auto nanosec = std::chrono::duration_cast(timestamp - sec); msg.header.stamp.sec = sec.count(); msg.header.stamp.nanosec = nanosec.count(); - for (const auto & target : targetlist_port_umrra4_v1_3_0->GetTargetList()) { + header.port_identifier = port_header->GetPortIdentifier(); + header.port_ver_major = port_header->GetPortVersionMajor(); + header.port_ver_minor = port_header->GetPortVersionMinor(); + header.port_size = port_header->GetPortSize(); + header.body_endianness = port_header->GetBodyEndianness(); + header.port_index = port_header->GetPortIndex(); + header.header_ver_major = port_header->GetHeaderVersionMajor(); + header.header_ver_minor = port_header->GetHeaderVersionMinor(); + + header.frame_id = m_sensors[sensor_idx].frame_id; + header.cycle_time = target_header->GetCycleTime(); + header.number_of_targets = target_header->GetNumberOfTargets(); + header.acquisition_tx_ant_idx = target_header->GetAcquisitionTxAntIdx(); + header.acquisition_sweep_idx = target_header->GetAcquisitionSweepIdx(); + header.acquisition_cf_idx = target_header->GetAcquisitionCfIdx(); + header.prf = target_header->GetPrf(); + header.umambiguous_speed = target_header->GetUmambiguousSpeed(); + header.acquisition_start = target_header->GetAcquisitionStart(); + for (const auto & target : targetlist_port_umrra4_v1_2_1->GetTargetList()) { const auto range = target->GetRange(); const auto elevation_angle = target->GetElevationAngle(); const auto range_2d = range * std::cos(elevation_angle); @@ -713,6 +1006,7 @@ void SmartmicroRadarNode::targetlist_callback_umrra4_v1_3_0( } m_publishers[sensor_idx]->publish(msg); + m_publishers_port_target_header[sensor_idx]->publish(header); } } @@ -726,13 +1020,36 @@ void SmartmicroRadarNode::targetlist_callback_umrra4_v1_0_1( if (!check_signal) { std::shared_ptr port_header; port_header = targetlist_port_umrra4_v1_0_1->GetPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_port_umrra4_v1_0_1->GetTargetListHeader(); sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::PortTargetHeader header; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; const auto sec = std::chrono::duration_cast(timestamp); const auto nanosec = std::chrono::duration_cast(timestamp - sec); msg.header.stamp.sec = sec.count(); msg.header.stamp.nanosec = nanosec.count(); + header.frame_id = m_sensors[sensor_idx].frame_id; + + header.port_identifier = port_header->GetPortIdentifier(); + header.port_ver_major = port_header->GetPortVersionMajor(); + header.port_ver_minor = port_header->GetPortVersionMinor(); + header.port_size = port_header->GetPortSize(); + header.body_endianness = port_header->GetBodyEndianness(); + header.port_index = port_header->GetPortIndex(); + header.header_ver_major = port_header->GetHeaderVersionMajor(); + header.header_ver_minor = port_header->GetHeaderVersionMinor(); + + header.cycle_time = target_header->GetCycleTime(); + header.number_of_targets = target_header->GetNumberOfTargets(); + header.acquisition_tx_ant_idx = target_header->GetAcquisitionTxAntIdx(); + header.acquisition_sweep_idx = target_header->GetAcquisitionSweepIdx(); + header.acquisition_cf_idx = target_header->GetAcquisitionCfIdx(); + header.prf = target_header->GetPrf(); + header.umambiguous_speed = target_header->GetUmambiguousSpeed(); + header.acquisition_start = target_header->GetAcquisitionStart(); for (const auto & target : targetlist_port_umrra4_v1_0_1->GetTargetList()) { const auto range = target->GetRange(); const auto elevation_angle = target->GetElevationAngle(); @@ -746,6 +1063,7 @@ void SmartmicroRadarNode::targetlist_callback_umrra4_v1_0_1( } m_publishers[sensor_idx]->publish(msg); + m_publishers_port_target_header[sensor_idx]->publish(header); } } @@ -760,13 +1078,30 @@ void SmartmicroRadarNode::targetlist_callback_umrr96( std::shared_ptr port_header; port_header = targetlist_port_umrr96->GetPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_port_umrr96->GetTargetListHeader(); sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::PortTargetHeader header; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; const auto sec = std::chrono::duration_cast(timestamp); const auto nanosec = std::chrono::duration_cast(timestamp - sec); msg.header.stamp.sec = sec.count(); msg.header.stamp.nanosec = nanosec.count(); + header.frame_id = m_sensors[sensor_idx].frame_id; + + header.port_identifier = port_header->GetPortIdentifier(); + header.port_ver_major = port_header->GetPortVersionMajor(); + header.port_ver_minor = port_header->GetPortVersionMinor(); + header.port_size = port_header->GetPortSize(); + header.body_endianness = port_header->GetBodyEndianness(); + header.port_index = port_header->GetPortIndex(); + header.header_ver_major = port_header->GetHeaderVersionMajor(); + header.header_ver_minor = port_header->GetHeaderVersionMinor(); + + header.cycle_time = target_header->GetCycleTime(); + header.number_of_targets = target_header->GetNumberOfTargets(); for (const auto & target : targetlist_port_umrr96->GetTargetList()) { const auto range = target->GetRange(); const auto elevation_angle = target->GetElevationAngle(); @@ -780,6 +1115,7 @@ void SmartmicroRadarNode::targetlist_callback_umrr96( } m_publishers[sensor_idx]->publish(msg); + m_publishers_port_target_header[sensor_idx]->publish(header); } } @@ -794,13 +1130,30 @@ void SmartmicroRadarNode::targetlist_callback_umrr11( std::shared_ptr port_header; port_header = targetlist_port_umrr11->GetPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_port_umrr11->GetTargetListHeader(); sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::PortTargetHeader header; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; const auto sec = std::chrono::duration_cast(timestamp); const auto nanosec = std::chrono::duration_cast(timestamp - sec); msg.header.stamp.sec = sec.count(); msg.header.stamp.nanosec = nanosec.count(); + header.frame_id = m_sensors[sensor_idx].frame_id; + + header.port_identifier = port_header->GetPortIdentifier(); + header.port_ver_major = port_header->GetPortVersionMajor(); + header.port_ver_minor = port_header->GetPortVersionMinor(); + header.port_size = port_header->GetPortSize(); + header.body_endianness = port_header->GetBodyEndianness(); + header.port_index = port_header->GetPortIndex(); + header.header_ver_major = port_header->GetHeaderVersionMajor(); + header.header_ver_minor = port_header->GetHeaderVersionMinor(); + + header.cycle_time = target_header->GetCycleTime(); + header.number_of_targets = target_header->GetNumberOfTargets(); for (const auto & target : targetlist_port_umrr11->GetTargetList()) { const auto range = target->GetRange(); const auto elevation_angle = target->GetElevationAngle(); @@ -814,6 +1167,7 @@ void SmartmicroRadarNode::targetlist_callback_umrr11( } m_publishers[sensor_idx]->publish(msg); + m_publishers_port_target_header[sensor_idx]->publish(header); } } @@ -828,13 +1182,34 @@ void SmartmicroRadarNode::targetlist_callback_umrr9d_v1_0_3( std::shared_ptr port_header; port_header = targetlist_port_umrr9d_v1_0_3->GetPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_port_umrr9d_v1_0_3->GetTargetListHeader(); sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::PortTargetHeader header; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; const auto sec = std::chrono::duration_cast(timestamp); const auto nanosec = std::chrono::duration_cast(timestamp - sec); msg.header.stamp.sec = sec.count(); msg.header.stamp.nanosec = nanosec.count(); + header.frame_id = m_sensors[sensor_idx].frame_id; + + header.port_identifier = port_header->GetPortIdentifier(); + header.port_ver_major = port_header->GetPortVersionMajor(); + header.port_ver_minor = port_header->GetPortVersionMinor(); + header.port_size = port_header->GetPortSize(); + header.body_endianness = port_header->GetBodyEndianness(); + header.port_index = port_header->GetPortIndex(); + header.header_ver_major = port_header->GetHeaderVersionMajor(); + header.header_ver_minor = port_header->GetHeaderVersionMinor(); + + header.cycle_time = target_header->GetCycleTime(); + header.number_of_targets = target_header->GetNumberOfTargets(); + header.acquisition_tx_ant_idx = target_header->GetAcquisitionTxAntIdx(); + header.acquisition_sweep_idx = target_header->GetAcquisitionSweepIdx(); + header.acquisition_cf_idx = target_header->GetAcquisitionCfIdx(); + header.acquisition_start = target_header->GetAcquisitionStart(); for (const auto & target : targetlist_port_umrr9d_v1_0_3->GetTargetList()) { const auto range = target->GetRange(); const auto elevation_angle = target->GetElevationAngle(); @@ -848,6 +1223,7 @@ void SmartmicroRadarNode::targetlist_callback_umrr9d_v1_0_3( } m_publishers[sensor_idx]->publish(msg); + m_publishers_port_target_header[sensor_idx]->publish(header); } } @@ -862,13 +1238,36 @@ void SmartmicroRadarNode::targetlist_callback_umrr9d_v1_2_2( std::shared_ptr port_header; port_header = targetlist_port_umrr9d_v1_2_2->GetPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_port_umrr9d_v1_2_2->GetTargetListHeader(); sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::PortTargetHeader header; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; const auto sec = std::chrono::duration_cast(timestamp); const auto nanosec = std::chrono::duration_cast(timestamp - sec); msg.header.stamp.sec = sec.count(); msg.header.stamp.nanosec = nanosec.count(); + header.frame_id = m_sensors[sensor_idx].frame_id; + + header.port_identifier = port_header->GetPortIdentifier(); + header.port_ver_major = port_header->GetPortVersionMajor(); + header.port_ver_minor = port_header->GetPortVersionMinor(); + header.port_size = port_header->GetPortSize(); + header.body_endianness = port_header->GetBodyEndianness(); + header.port_index = port_header->GetPortIndex(); + header.header_ver_major = port_header->GetHeaderVersionMajor(); + header.header_ver_minor = port_header->GetHeaderVersionMinor(); + + header.cycle_time = target_header->GetCycleTime(); + header.number_of_targets = target_header->GetNumberOfTargets(); + header.acquisition_tx_ant_idx = target_header->GetAcquisitionTxAntIdx(); + header.acquisition_sweep_idx = target_header->GetAcquisitionSweepIdx(); + header.acquisition_cf_idx = target_header->GetAcquisitionCfIdx(); + header.prf = target_header->GetPrf(); + header.umambiguous_speed = target_header->GetUmambiguousSpeed(); + header.acquisition_start = target_header->GetAcquisitionStart(); for (const auto & target : targetlist_port_umrr9d_v1_2_2->GetTargetList()) { const auto range = target->GetRange(); const auto elevation_angle = target->GetElevationAngle(); @@ -882,6 +1281,7 @@ void SmartmicroRadarNode::targetlist_callback_umrr9d_v1_2_2( } m_publishers[sensor_idx]->publish(msg); + m_publishers_port_target_header[sensor_idx]->publish(header); } } @@ -898,13 +1298,30 @@ void SmartmicroRadarNode::targetlist_callback_umrr9f_v1_1_1( com::master::umrr9f_t169_automotive_v1_1_1::comtargetlistport::GenericPortHeader> port_header; port_header = targetlist_port_umrr9f_v1_1_1->GetGenericPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_port_umrr9f_v1_1_1->GetStaticPortHeader(); sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::PortTargetHeader header; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; const auto sec = std::chrono::duration_cast(timestamp); const auto nanosec = std::chrono::duration_cast(timestamp - sec); msg.header.stamp.sec = sec.count(); msg.header.stamp.nanosec = nanosec.count(); + header.frame_id = m_sensors[sensor_idx].frame_id; + + header.port_identifier = port_header->GetPortId(); + header.port_ver_major = port_header->GetPortVersionMajor(); + header.port_ver_minor = port_header->GetPortVersionMinor(); + header.port_size = port_header->GetPortSize(); + header.body_endianness = port_header->GetBodyEndianness(); + header.port_index = port_header->GetPortIndex(); + header.header_ver_major = port_header->GetHeaderVersionMajor(); + header.header_ver_minor = port_header->GetHeaderVersionMinor(); + + header.cycle_time = target_header->GetCycleTime(); + header.number_of_targets = target_header->GetNumberOfTargets(); for (const auto & target : targetlist_port_umrr9f_v1_1_1->GetTargetList()) { const auto range = target->GetRange(); const auto elevation_angle = target->GetElevationAngle(); @@ -918,6 +1335,7 @@ void SmartmicroRadarNode::targetlist_callback_umrr9f_v1_1_1( } m_publishers[sensor_idx]->publish(msg); + m_publishers_port_target_header[sensor_idx]->publish(header); } } @@ -934,13 +1352,34 @@ void SmartmicroRadarNode::targetlist_callback_umrr9f_v2_0_0( com::master::umrr9f_t169_automotive_v2_0_0::comtargetlistport::GenericPortHeader> port_header; port_header = targetlist_port_umrr9f_v2_0_0->GetGenericPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_port_umrr9f_v2_0_0->GetStaticPortHeader(); sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::PortTargetHeader header; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; const auto sec = std::chrono::duration_cast(timestamp); const auto nanosec = std::chrono::duration_cast(timestamp - sec); msg.header.stamp.sec = sec.count(); msg.header.stamp.nanosec = nanosec.count(); + header.frame_id = m_sensors[sensor_idx].frame_id; + + header.port_identifier = port_header->GetPortId(); + header.port_ver_major = port_header->GetPortVersionMajor(); + header.port_ver_minor = port_header->GetPortVersionMinor(); + header.port_size = port_header->GetPortSize(); + header.body_endianness = port_header->GetBodyEndianness(); + header.port_index = port_header->GetPortIndex(); + header.header_ver_major = port_header->GetHeaderVersionMajor(); + header.header_ver_minor = port_header->GetHeaderVersionMinor(); + + header.cycle_time = target_header->GetCycleTime(); + header.number_of_targets = target_header->GetNumberOfTargets(); + header.acquisition_tx_ant_idx = target_header->GetAcquisitionTxAnt(); + header.acquisition_sweep_idx = target_header->GetAcquisitionSweep(); + header.acquisition_cf_idx = target_header->GetAcquisitionTx(); + header.acquisition_start = target_header->GetAcquisitionStart(); for (const auto & target : targetlist_port_umrr9f_v2_0_0->GetTargetList()) { const auto range = target->GetRange(); const auto elevation_angle = target->GetElevationAngle(); @@ -954,6 +1393,7 @@ void SmartmicroRadarNode::targetlist_callback_umrr9f_v2_0_0( } m_publishers[sensor_idx]->publish(msg); + m_publishers_port_target_header[sensor_idx]->publish(header); } } @@ -968,6 +1408,10 @@ void SmartmicroRadarNode::targetlist_callback_umrr9f_v2_1_1( std::shared_ptr port_header; port_header = targetlist_port_umrr9f_v2_1_1->GetPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_port_umrr9f_v2_1_1->GetTargetListHeader(); + umrr_ros2_msgs::msg::PortTargetHeader header; sensor_msgs::msg::PointCloud2 msg; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; @@ -975,6 +1419,23 @@ void SmartmicroRadarNode::targetlist_callback_umrr9f_v2_1_1( const auto nanosec = std::chrono::duration_cast(timestamp - sec); msg.header.stamp.sec = sec.count(); msg.header.stamp.nanosec = nanosec.count(); + header.frame_id = m_sensors[sensor_idx].frame_id; + + header.port_identifier = port_header->GetPortIdentifier(); + header.port_ver_major = port_header->GetPortVersionMajor(); + header.port_ver_minor = port_header->GetPortVersionMinor(); + header.port_size = port_header->GetPortSize(); + header.body_endianness = port_header->GetBodyEndianness(); + header.port_index = port_header->GetPortIndex(); + header.header_ver_major = port_header->GetHeaderVersionMajor(); + header.header_ver_minor = port_header->GetHeaderVersionMinor(); + + header.cycle_time = target_header->GetCycleTime(); + header.number_of_targets = target_header->GetNumberOfTargets(); + header.acquisition_tx_ant_idx = target_header->GetAcquisitionTxAntIdx(); + header.acquisition_sweep_idx = target_header->GetAcquisitionSweepIdx(); + header.acquisition_cf_idx = target_header->GetAcquisitionCfIdx(); + header.acquisition_start = target_header->GetAcquisitionStart(); for (const auto & target : targetlist_port_umrr9f_v2_1_1->GetTargetList()) { const auto range = target->GetRange(); const auto elevation_angle = target->GetElevationAngle(); @@ -988,6 +1449,7 @@ void SmartmicroRadarNode::targetlist_callback_umrr9f_v2_1_1( } m_publishers[sensor_idx]->publish(msg); + m_publishers_port_target_header[sensor_idx]->publish(header); } } @@ -1002,13 +1464,36 @@ void SmartmicroRadarNode::targetlist_callback_umrr9f_v2_2_1( std::shared_ptr port_header; port_header = targetlist_port_umrr9f_v2_2_1->GetPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_port_umrr9f_v2_2_1->GetTargetListHeader(); sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::PortTargetHeader header; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; const auto sec = std::chrono::duration_cast(timestamp); const auto nanosec = std::chrono::duration_cast(timestamp - sec); msg.header.stamp.sec = sec.count(); msg.header.stamp.nanosec = nanosec.count(); + header.frame_id = m_sensors[sensor_idx].frame_id; + + header.port_identifier = port_header->GetPortIdentifier(); + header.port_ver_major = port_header->GetPortVersionMajor(); + header.port_ver_minor = port_header->GetPortVersionMinor(); + header.port_size = port_header->GetPortSize(); + header.body_endianness = port_header->GetBodyEndianness(); + header.port_index = port_header->GetPortIndex(); + header.header_ver_major = port_header->GetHeaderVersionMajor(); + header.header_ver_minor = port_header->GetHeaderVersionMinor(); + + header.cycle_time = target_header->GetCycleTime(); + header.number_of_targets = target_header->GetNumberOfTargets(); + header.acquisition_tx_ant_idx = target_header->GetAcquisitionTxAntIdx(); + header.acquisition_sweep_idx = target_header->GetAcquisitionSweepIdx(); + header.acquisition_cf_idx = target_header->GetAcquisitionCfIdx(); + header.prf = target_header->GetPrf(); + header.umambiguous_speed = target_header->GetUmambiguousSpeed(); + header.acquisition_start = target_header->GetAcquisitionStart(); for (const auto & target : targetlist_port_umrr9f_v2_2_1->GetTargetList()) { const auto range = target->GetRange(); const auto elevation_angle = target->GetElevationAngle(); @@ -1022,28 +1507,52 @@ void SmartmicroRadarNode::targetlist_callback_umrr9f_v2_2_1( } m_publishers[sensor_idx]->publish(msg); + m_publishers_port_target_header[sensor_idx]->publish(header); } } -void SmartmicroRadarNode::targetlist_callback_umrr9d_v1_5_0( +void SmartmicroRadarNode::targetlist_callback_umrr9d_v1_4_1( const std::uint32_t sensor_idx, - const std::shared_ptr & - targetlist_port_umrr9d_v1_5_0, + const std::shared_ptr & + targetlist_port_umrr9d_v1_4_1, const com::types::ClientId client_id) { - std::cout << "Targetlist for umrr9d_v1_5_0" << std::endl; + std::cout << "Targetlist for umrr9d_v1_4_1" << std::endl; if (!check_signal) { - std::shared_ptr + std::shared_ptr port_header; - port_header = targetlist_port_umrr9d_v1_5_0->GetPortHeader(); + port_header = targetlist_port_umrr9d_v1_4_1->GetPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_port_umrr9d_v1_4_1->GetTargetListHeader(); sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::PortTargetHeader header; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; const auto sec = std::chrono::duration_cast(timestamp); const auto nanosec = std::chrono::duration_cast(timestamp - sec); msg.header.stamp.sec = sec.count(); msg.header.stamp.nanosec = nanosec.count(); - for (const auto & target : targetlist_port_umrr9d_v1_5_0->GetTargetList()) { + header.frame_id = m_sensors[sensor_idx].frame_id; + + header.port_identifier = port_header->GetPortIdentifier(); + header.port_ver_major = port_header->GetPortVersionMajor(); + header.port_ver_minor = port_header->GetPortVersionMinor(); + header.port_size = port_header->GetPortSize(); + header.body_endianness = port_header->GetBodyEndianness(); + header.port_index = port_header->GetPortIndex(); + header.header_ver_major = port_header->GetHeaderVersionMajor(); + header.header_ver_minor = port_header->GetHeaderVersionMinor(); + + header.cycle_time = target_header->GetCycleTime(); + header.number_of_targets = target_header->GetNumberOfTargets(); + header.acquisition_tx_ant_idx = target_header->GetAcquisitionTxAntIdx(); + header.acquisition_sweep_idx = target_header->GetAcquisitionSweepIdx(); + header.acquisition_cf_idx = target_header->GetAcquisitionCfIdx(); + header.prf = target_header->GetPrf(); + header.umambiguous_speed = target_header->GetUmambiguousSpeed(); + header.acquisition_start = target_header->GetAcquisitionStart(); + for (const auto & target : targetlist_port_umrr9d_v1_4_1->GetTargetList()) { const auto range = target->GetRange(); const auto elevation_angle = target->GetElevationAngle(); const auto range_2d = range * std::cos(elevation_angle); @@ -1056,28 +1565,52 @@ void SmartmicroRadarNode::targetlist_callback_umrr9d_v1_5_0( } m_publishers[sensor_idx]->publish(msg); + m_publishers_port_target_header[sensor_idx]->publish(header); } } -void SmartmicroRadarNode::targetlist_callback_umrr9f_v2_5_0( +void SmartmicroRadarNode::targetlist_callback_umrr9f_v2_4_1( const std::uint32_t sensor_idx, - const std::shared_ptr & - targetlist_port_umrr9f_v2_5_0, + const std::shared_ptr & + targetlist_port_umrr9f_v2_4_1, const com::types::ClientId client_id) { - std::cout << "Targetlist for umrr9f v2_5_0" << std::endl; + std::cout << "Targetlist for umrr9f v2_4_1" << std::endl; if (!check_signal) { - std::shared_ptr + std::shared_ptr port_header; - port_header = targetlist_port_umrr9f_v2_5_0->GetPortHeader(); + port_header = targetlist_port_umrr9f_v2_4_1->GetPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_port_umrr9f_v2_4_1->GetTargetListHeader(); sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::PortTargetHeader header; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; const auto sec = std::chrono::duration_cast(timestamp); const auto nanosec = std::chrono::duration_cast(timestamp - sec); msg.header.stamp.sec = sec.count(); msg.header.stamp.nanosec = nanosec.count(); - for (const auto & target : targetlist_port_umrr9f_v2_5_0->GetTargetList()) { + header.frame_id = m_sensors[sensor_idx].frame_id; + + header.port_identifier = port_header->GetPortIdentifier(); + header.port_ver_major = port_header->GetPortVersionMajor(); + header.port_ver_minor = port_header->GetPortVersionMinor(); + header.port_size = port_header->GetPortSize(); + header.body_endianness = port_header->GetBodyEndianness(); + header.port_index = port_header->GetPortIndex(); + header.header_ver_major = port_header->GetHeaderVersionMajor(); + header.header_ver_minor = port_header->GetHeaderVersionMinor(); + + header.cycle_time = target_header->GetCycleTime(); + header.number_of_targets = target_header->GetNumberOfTargets(); + header.acquisition_tx_ant_idx = target_header->GetAcquisitionTxAntIdx(); + header.acquisition_sweep_idx = target_header->GetAcquisitionSweepIdx(); + header.acquisition_cf_idx = target_header->GetAcquisitionCfIdx(); + header.prf = target_header->GetPrf(); + header.umambiguous_speed = target_header->GetUmambiguousSpeed(); + header.acquisition_start = target_header->GetAcquisitionStart(); + for (const auto & target : targetlist_port_umrr9f_v2_4_1->GetTargetList()) { const auto range = target->GetRange(); const auto elevation_angle = target->GetElevationAngle(); const auto range_2d = range * std::cos(elevation_angle); @@ -1090,29 +1623,135 @@ void SmartmicroRadarNode::targetlist_callback_umrr9f_v2_5_0( } m_publishers[sensor_idx]->publish(msg); + m_publishers_port_target_header[sensor_idx]->publish(header); + } +} + +void SmartmicroRadarNode::CAN_objectlist_callback_umrr9f_mse_v1_0_0( + const std::uint32_t sensor_idx, + const std::shared_ptr & + objectlist_can_umrr9f_mse_v1_0_0, + const com::types::ClientId client_id) +{ + std::cout << "Objectlist for umrr9f_mse_can_v1_0_0" << std::endl; + if (!check_signal) { + std::shared_ptr port_header; + port_header = objectlist_can_umrr9f_mse_v1_0_0->GetPortHeader(); + std::shared_ptr + object_header; + object_header = objectlist_can_umrr9f_mse_v1_0_0->GetComObjectBaseListHeader(); + sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::CanObjectHeader header; + ObjectPointCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; + const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; + const auto sec = std::chrono::duration_cast(timestamp); + const auto nanosec = std::chrono::duration_cast(timestamp - sec); + msg.header.stamp.sec = sec.count(); + msg.header.stamp.nanosec = nanosec.count(); + header.frame_id = m_sensors[sensor_idx].frame_id; + header.cycle_time = object_header->GetCycleDuration(); + header.cycle_count = object_header->GetCycleCount(); + header.number_of_objects = object_header->GetNoOfObjects(); + header.ego_speed = object_header->GetSpeed(); + header.ego_speed_quality = object_header->GetSpeedQuality(); + header.ego_yaw_rate = object_header->GetYawRate(); + header.ego_yaw_rate_quality = object_header->GetYawRateQuality(); + header.dyn_source = object_header->GetDynamicSource(); + for (const auto & object : objectlist_can_umrr9f_mse_v1_0_0->GetObjectList()) { + const auto x_pos = object->GetXPoint1(); + const auto y_pos = object->GetYPoint1(); + const auto z_pos = object->GetZPoint1(); + const auto speed_abs = object->GetSpeedAbs(); + const auto heading = object->GetHeadingDeg(); + const auto length = object->GetObjectLen(); + const auto quality = object->GetQuality(); + const auto acceleration = object->GetAcceleration(); + const auto object_id = static_cast(object->GetObjectId()); + modifier.push_back( + {x_pos, y_pos, z_pos, speed_abs, heading, length, quality, acceleration, object_id}); + } + + m_publishers_obj[sensor_idx]->publish(msg); + m_publishers_can_obj_header[sensor_idx]->publish(header); + } +} + +void SmartmicroRadarNode::CAN_targetlist_callback_umrr9f_mse_v1_0_0( + const std::uint32_t sensor_idx, + const std::shared_ptr & + targetlist_can_umrr9f_mse_v1_0_0, + const com::types::ClientId client_id) +{ + std::cout << "Targetlist for umrr9f_mse_can_v1_0_0" << std::endl; + if (!check_signal) { + std::shared_ptr port_header; + port_header = targetlist_can_umrr9f_mse_v1_0_0->GetPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_can_umrr9f_mse_v1_0_0->GetTargetListHeader(); + sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::CanTargetHeader header; + RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; + const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; + const auto sec = std::chrono::duration_cast(timestamp); + const auto nanosec = std::chrono::duration_cast(timestamp - sec); + msg.header.stamp.sec = sec.count(); + msg.header.stamp.nanosec = nanosec.count(); + header.frame_id = m_sensors[sensor_idx].frame_id; + header.cycle_time = target_header->GetCycleDuration(); + header.number_of_targets = target_header->GetNumberOfTargets(); + header.acquisition_setup = target_header->GetAcquisitionSetup(); + header.cycle_count = target_header->GetCycleCount(); + header.time_stamp = target_header->GetTimeStamp(); + header.acq_ts_fraction = target_header->GetAcqTimeStampFraction(); + for (const auto & target : targetlist_can_umrr9f_mse_v1_0_0->GetTargetList()) { + const auto range = target->GetRange(); + const auto elevation_angle = target->GetElevationAngle(); + const auto range_2d = range * std::cos(elevation_angle); + const auto azimuth_angle = target->GetAzimuthAngle(); + const auto snr = target->GetSignalLevel() - target->GetNoise(); + modifier.push_back( + {range_2d * std::cos(azimuth_angle), range_2d * std::sin(azimuth_angle), + range * std::sin(elevation_angle), target->GetSpeedRadial(), target->GetSignalLevel(), + target->GetRCS(), target->GetNoise(), snr, azimuth_angle, elevation_angle, range}); + } + + m_publishers[sensor_idx]->publish(msg); + m_publishers_can_target_header[sensor_idx]->publish(header); } } -void SmartmicroRadarNode::CAN_targetlist_callback_umrra4_v1_3_0( +void SmartmicroRadarNode::CAN_targetlist_callback_umrra4_v1_2_1( const std::uint32_t sensor_idx, const std::shared_ptr< - com::master::umrra4_automotive_v1_3_0::comtargetbaselist::ComTargetBaseList> & - targetlist_can_umrra4_v1_3_0, + com::master::umrra4_automotive_v1_2_1::comtargetbaselist::ComTargetBaseList> & + targetlist_can_umrra4_v1_2_1, const com::types::ClientId client_id) { - std::cout << "CAN Targetlist for umrra4_v1_3_0" << std::endl; + std::cout << "CAN Targetlist for umrra4_v1_2_1" << std::endl; if (!check_signal) { - std::shared_ptr + std::shared_ptr port_header; - port_header = targetlist_can_umrra4_v1_3_0->GetPortHeader(); + port_header = targetlist_can_umrra4_v1_2_1->GetPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_can_umrra4_v1_2_1->GetTargetListHeader(); sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::CanTargetHeader header; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; const auto sec = std::chrono::duration_cast(timestamp); const auto nanosec = std::chrono::duration_cast(timestamp - sec); msg.header.stamp.sec = sec.count(); msg.header.stamp.nanosec = nanosec.count(); - for (const auto & target : targetlist_can_umrra4_v1_3_0->GetTargetList()) { + header.frame_id = m_sensors[sensor_idx].frame_id; + header.cycle_time = target_header->GetCycleDuration(); + header.number_of_targets = target_header->GetNumberOfTargets(); + header.acquisition_setup = target_header->GetAcquisitionSetup(); + header.cycle_count = target_header->GetCycleCount(); + header.time_stamp = target_header->GetTimeStamp(); + header.acq_ts_fraction = target_header->GetAcqTimeStampFraction(); + for (const auto & target : targetlist_can_umrra4_v1_2_1->GetTargetList()) { const auto range = target->GetRange(); const auto elevation_angle = target->GetElevationAngle(); const auto range_2d = range * std::cos(elevation_angle); @@ -1125,6 +1764,7 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrra4_v1_3_0( } m_publishers[sensor_idx]->publish(msg); + m_publishers_can_target_header[sensor_idx]->publish(header); } } @@ -1140,13 +1780,24 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrra4_v1_0_1( std::shared_ptr port_header; port_header = targetlist_can_umrra4_v1_0_1->GetPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_can_umrra4_v1_0_1->GetTargetListHeader(); sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::CanTargetHeader header; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; const auto sec = std::chrono::duration_cast(timestamp); const auto nanosec = std::chrono::duration_cast(timestamp - sec); msg.header.stamp.sec = sec.count(); msg.header.stamp.nanosec = nanosec.count(); + header.frame_id = m_sensors[sensor_idx].frame_id; + header.acq_ts_fraction = target_header->GetAcqTimeStampFraction(); + header.time_stamp = target_header->GetTimeStamp(); + header.cycle_time = target_header->GetCycleDuration(); + header.number_of_targets = target_header->GetNumberOfTargets(); + header.acquisition_setup = target_header->GetAcquisitionSetup(); + header.cycle_count = target_header->GetCycleCount(); for (const auto & target : targetlist_can_umrra4_v1_0_1->GetTargetList()) { const auto range = target->GetRange(); const auto elevation_angle = target->GetElevationAngle(); @@ -1160,6 +1811,7 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrra4_v1_0_1( } m_publishers[sensor_idx]->publish(msg); + m_publishers_can_target_header[sensor_idx]->publish(header); } } @@ -1175,13 +1827,24 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrr96( std::shared_ptr port_header; port_header = targetlist_can_umrr96->GetPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_can_umrr96->GetTargetListHeader(); sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::CanTargetHeader header; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; const auto sec = std::chrono::duration_cast(timestamp); const auto nanosec = std::chrono::duration_cast(timestamp - sec); msg.header.stamp.sec = sec.count(); msg.header.stamp.nanosec = nanosec.count(); + header.frame_id = m_sensors[sensor_idx].frame_id; + header.acq_ts_fraction = target_header->GetAcqTimeStampFraction(); + header.time_stamp = target_header->GetTimeStamp(); + header.cycle_time = target_header->GetCycleDuration(); + header.number_of_targets = target_header->GetNumberOfTargets(); + header.acquisition_setup = target_header->GetAcquisitionSetup(); + header.cycle_count = target_header->GetCycleCount(); for (const auto & target : targetlist_can_umrr96->GetTargetList()) { const auto range = target->GetRange(); const auto elevation_angle = target->GetElevationAngle(); @@ -1195,6 +1858,7 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrr96( } m_publishers[sensor_idx]->publish(msg); + m_publishers_can_target_header[sensor_idx]->publish(header); } } @@ -1210,13 +1874,24 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrr11( std::shared_ptr port_header; port_header = targetlist_can_umrr11->GetPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_can_umrr11->GetTargetListHeader(); sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::CanTargetHeader header; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; const auto sec = std::chrono::duration_cast(timestamp); const auto nanosec = std::chrono::duration_cast(timestamp - sec); msg.header.stamp.sec = sec.count(); msg.header.stamp.nanosec = nanosec.count(); + header.frame_id = m_sensors[sensor_idx].frame_id; + header.acq_ts_fraction = target_header->GetAcqTimeStampFraction(); + header.time_stamp = target_header->GetTimeStamp(); + header.cycle_time = target_header->GetCycleDuration(); + header.number_of_targets = target_header->GetNumberOfTargets(); + header.acquisition_setup = target_header->GetAcquisitionSetup(); + header.cycle_count = target_header->GetCycleCount(); for (const auto & target : targetlist_can_umrr11->GetTargetList()) { const auto range = target->GetRange(); const auto elevation_angle = target->GetElevationAngle(); @@ -1230,6 +1905,7 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrr11( } m_publishers[sensor_idx]->publish(msg); + m_publishers_can_target_header[sensor_idx]->publish(header); } } @@ -1245,13 +1921,24 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrr9d_v1_0_3( std::shared_ptr port_header; port_header = targetlist_can_umrr9d_v1_0_3->GetPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_can_umrr9d_v1_0_3->GetTargetListHeader(); sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::CanTargetHeader header; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; const auto sec = std::chrono::duration_cast(timestamp); const auto nanosec = std::chrono::duration_cast(timestamp - sec); msg.header.stamp.sec = sec.count(); msg.header.stamp.nanosec = nanosec.count(); + header.frame_id = m_sensors[sensor_idx].frame_id; + header.acq_ts_fraction = target_header->GetAcqTimeStampFraction(); + header.time_stamp = target_header->GetTimeStamp(); + header.cycle_time = target_header->GetCycleDuration(); + header.number_of_targets = target_header->GetNumberOfTargets(); + header.acquisition_setup = target_header->GetAcquisitionSetup(); + header.cycle_count = target_header->GetCycleCount(); for (const auto & target : targetlist_can_umrr9d_v1_0_3->GetTargetList()) { const auto range = target->GetRange(); const auto elevation_angle = target->GetElevationAngle(); @@ -1265,6 +1952,7 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrr9d_v1_0_3( } m_publishers[sensor_idx]->publish(msg); + m_publishers_can_target_header[sensor_idx]->publish(header); } } @@ -1280,13 +1968,24 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrr9d_v1_2_2( std::shared_ptr port_header; port_header = targetlist_can_umrr9d_v1_2_2->GetPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_can_umrr9d_v1_2_2->GetTargetListHeader(); sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::CanTargetHeader header; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; const auto sec = std::chrono::duration_cast(timestamp); const auto nanosec = std::chrono::duration_cast(timestamp - sec); msg.header.stamp.sec = sec.count(); msg.header.stamp.nanosec = nanosec.count(); + header.frame_id = m_sensors[sensor_idx].frame_id; + header.acq_ts_fraction = target_header->GetAcqTimeStampFraction(); + header.time_stamp = target_header->GetTimeStamp(); + header.cycle_time = target_header->GetCycleDuration(); + header.number_of_targets = target_header->GetNumberOfTargets(); + header.acquisition_setup = target_header->GetAcquisitionSetup(); + header.cycle_count = target_header->GetCycleCount(); for (const auto & target : targetlist_can_umrr9d_v1_2_2->GetTargetList()) { const auto range = target->GetRange(); const auto elevation_angle = target->GetElevationAngle(); @@ -1300,6 +1999,7 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrr9d_v1_2_2( } m_publishers[sensor_idx]->publish(msg); + m_publishers_can_target_header[sensor_idx]->publish(header); } } @@ -1315,13 +2015,24 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrr9f_v2_1_1( std::shared_ptr port_header; port_header = targetlist_can_umrr9f_v2_1_1->GetPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_can_umrr9f_v2_1_1->GetTargetListHeader(); sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::CanTargetHeader header; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; const auto sec = std::chrono::duration_cast(timestamp); const auto nanosec = std::chrono::duration_cast(timestamp - sec); msg.header.stamp.sec = sec.count(); msg.header.stamp.nanosec = nanosec.count(); + header.frame_id = m_sensors[sensor_idx].frame_id; + header.acq_ts_fraction = target_header->GetAcqTimeStampFraction(); + header.time_stamp = target_header->GetTimeStamp(); + header.cycle_time = target_header->GetCycleDuration(); + header.number_of_targets = target_header->GetNumberOfTargets(); + header.acquisition_setup = target_header->GetAcquisitionSetup(); + header.cycle_count = target_header->GetCycleCount(); for (const auto & target : targetlist_can_umrr9f_v2_1_1->GetTargetList()) { const auto range = target->GetRange(); const auto elevation_angle = target->GetElevationAngle(); @@ -1335,6 +2046,7 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrr9f_v2_1_1( } m_publishers[sensor_idx]->publish(msg); + m_publishers_can_target_header[sensor_idx]->publish(header); } } @@ -1350,13 +2062,24 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrr9f_v2_2_1( std::shared_ptr port_header; port_header = targetlist_can_umrr9f_v2_2_1->GetPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_can_umrr9f_v2_2_1->GetTargetListHeader(); sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::CanTargetHeader header; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; const auto sec = std::chrono::duration_cast(timestamp); const auto nanosec = std::chrono::duration_cast(timestamp - sec); msg.header.stamp.sec = sec.count(); msg.header.stamp.nanosec = nanosec.count(); + header.frame_id = m_sensors[sensor_idx].frame_id; + header.acq_ts_fraction = target_header->GetAcqTimeStampFraction(); + header.time_stamp = target_header->GetTimeStamp(); + header.cycle_time = target_header->GetCycleDuration(); + header.number_of_targets = target_header->GetNumberOfTargets(); + header.acquisition_setup = target_header->GetAcquisitionSetup(); + header.cycle_count = target_header->GetCycleCount(); for (const auto & target : targetlist_can_umrr9f_v2_2_1->GetTargetList()) { const auto range = target->GetRange(); const auto elevation_angle = target->GetElevationAngle(); @@ -1370,29 +2093,41 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrr9f_v2_2_1( } m_publishers[sensor_idx]->publish(msg); + m_publishers_can_target_header[sensor_idx]->publish(header); } } -void SmartmicroRadarNode::CAN_targetlist_callback_umrr9d_v1_5_0( +void SmartmicroRadarNode::CAN_targetlist_callback_umrr9d_v1_4_1( const std::uint32_t sensor_idx, const std::shared_ptr< - com::master::umrr9d_t152_automotive_v1_5_0::comtargetbaselist::ComTargetBaseList> & - targetlist_can_umrr9d_v1_5_0, + com::master::umrr9d_t152_automotive_v1_4_1::comtargetbaselist::ComTargetBaseList> & + targetlist_can_umrr9d_v1_4_1, const com::types::ClientId client_id) { - std::cout << "Targetlist for umrr9d_v1_5_0" << std::endl; + std::cout << "Targetlist for umrr9d_v1_4_1" << std::endl; if (!check_signal) { - std::shared_ptr + std::shared_ptr port_header; - port_header = targetlist_can_umrr9d_v1_5_0->GetPortHeader(); + port_header = targetlist_can_umrr9d_v1_4_1->GetPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_can_umrr9d_v1_4_1->GetTargetListHeader(); sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::CanTargetHeader header; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; const auto sec = std::chrono::duration_cast(timestamp); const auto nanosec = std::chrono::duration_cast(timestamp - sec); msg.header.stamp.sec = sec.count(); msg.header.stamp.nanosec = nanosec.count(); - for (const auto & target : targetlist_can_umrr9d_v1_5_0->GetTargetList()) { + header.frame_id = m_sensors[sensor_idx].frame_id; + header.acq_ts_fraction = target_header->GetAcqTimeStampFraction(); + header.time_stamp = target_header->GetTimeStamp(); + header.cycle_time = target_header->GetCycleDuration(); + header.number_of_targets = target_header->GetNumberOfTargets(); + header.acquisition_setup = target_header->GetAcquisitionSetup(); + header.cycle_count = target_header->GetCycleCount(); + for (const auto & target : targetlist_can_umrr9d_v1_4_1->GetTargetList()) { const auto range = target->GetRange(); const auto elevation_angle = target->GetElevationAngle(); const auto range_2d = range * std::cos(elevation_angle); @@ -1405,29 +2140,41 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrr9d_v1_5_0( } m_publishers[sensor_idx]->publish(msg); + m_publishers_can_target_header[sensor_idx]->publish(header); } } -void SmartmicroRadarNode::CAN_targetlist_callback_umrr9f_v2_5_0( +void SmartmicroRadarNode::CAN_targetlist_callback_umrr9f_v2_4_1( const std::uint32_t sensor_idx, const std::shared_ptr< - com::master::umrr9f_t169_automotive_v2_5_0::comtargetbaselist::ComTargetBaseList> & - targetlist_can_umrr9f_v2_5_0, + com::master::umrr9f_t169_automotive_v2_4_1::comtargetbaselist::ComTargetBaseList> & + targetlist_can_umrr9f_v2_4_1, const com::types::ClientId client_id) { - std::cout << "Targetlist for umrr9f_v2_5_0" << std::endl; + std::cout << "Targetlist for umrr9f_v2_4_1" << std::endl; if (!check_signal) { - std::shared_ptr + std::shared_ptr port_header; - port_header = targetlist_can_umrr9f_v2_5_0->GetPortHeader(); + port_header = targetlist_can_umrr9f_v2_4_1->GetPortHeader(); + std::shared_ptr + target_header; + target_header = targetlist_can_umrr9f_v2_4_1->GetTargetListHeader(); sensor_msgs::msg::PointCloud2 msg; + umrr_ros2_msgs::msg::CanTargetHeader header; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; const auto sec = std::chrono::duration_cast(timestamp); const auto nanosec = std::chrono::duration_cast(timestamp - sec); msg.header.stamp.sec = sec.count(); msg.header.stamp.nanosec = nanosec.count(); - for (const auto & target : targetlist_can_umrr9f_v2_5_0->GetTargetList()) { + header.frame_id = m_sensors[sensor_idx].frame_id; + header.acq_ts_fraction = target_header->GetAcqTimeStampFraction(); + header.time_stamp = target_header->GetTimeStamp(); + header.cycle_time = target_header->GetCycleDuration(); + header.number_of_targets = target_header->GetNumberOfTargets(); + header.acquisition_setup = target_header->GetAcquisitionSetup(); + header.cycle_count = target_header->GetCycleCount(); + for (const auto & target : targetlist_can_umrr9f_v2_4_1->GetTargetList()) { const auto range = target->GetRange(); const auto elevation_angle = target->GetElevationAngle(); const auto range_2d = range * std::cos(elevation_angle); @@ -1440,6 +2187,7 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrr9f_v2_5_0( } m_publishers[sensor_idx]->publish(msg); + m_publishers_can_target_header[sensor_idx]->publish(header); } } @@ -1490,6 +2238,7 @@ void SmartmicroRadarNode::update_config_files_from_params() sensor.inst_type = this->declare_parameter(prefix_3 + ".inst_type", ""); sensor.data_type = this->declare_parameter(prefix_3 + ".data_type", ""); sensor.link_type = this->declare_parameter(prefix_3 + ".link_type", kDefaultHwLinkType); + sensor.pub_type = this->declare_parameter(prefix_3 + ".pub_type", ""); return true; }; diff --git a/umrr_ros2_driver/test/radar_node_test.launch.py b/umrr_ros2_driver/test/radar_node_test.launch.py index 52ad86a..7fcab34 100644 --- a/umrr_ros2_driver/test/radar_node_test.launch.py +++ b/umrr_ros2_driver/test/radar_node_test.launch.py @@ -121,7 +121,7 @@ def tearDown(self): self.test_node.destroy_node() def test_smart_node_publishes(self): - # Expect the smartnode to publish strings on '/smart_radar/targets_' + # Expect the smartnode to publish strings on 'smart_radar/port_targets_' data_rx_s1 = [] data_rx_s2 = [] data_rx_s3 = [] @@ -137,19 +137,19 @@ def data_rx_s3_callback(msg): sub_s1 = self.test_node.create_subscription( sensor_msgs.PointCloud2, - '/smart_radar/targets_0', + 'smart_radar/port_targets_0', data_rx_s1_callback, 10 ) sub_s2 = self.test_node.create_subscription( sensor_msgs.PointCloud2, - '/smart_radar/targets_1', + 'smart_radar/port_targets_1', data_rx_s2_callback, 10 ) sub_s3 = self.test_node.create_subscription( sensor_msgs.PointCloud2, - '/smart_radar/targets_2', + 'smart_radar/port_targets_2', data_rx_s3_callback, 10 ) diff --git a/umrr_ros2_msgs/CMakeLists.txt b/umrr_ros2_msgs/CMakeLists.txt index a6f7494..69e4984 100644 --- a/umrr_ros2_msgs/CMakeLists.txt +++ b/umrr_ros2_msgs/CMakeLists.txt @@ -15,12 +15,22 @@ endif() find_package(ament_cmake REQUIRED) find_package(rosidl_default_generators REQUIRED) find_package(std_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(sensor_msgs REQUIRED) rosidl_generate_interfaces(${PROJECT_NAME} "srv/SetMode.srv" "srv/SetIp.srv" "srv/SendCommand.srv" "srv/FirmwareDownload.srv" + "msg/CanTargetHeader.msg" + "msg/PortTargetHeader.msg" + "msg/PortObjectHeader.msg" + "msg/CanObjectHeader.msg" + DEPENDENCIES + "geometry_msgs" + "sensor_msgs" + "std_msgs" ) ament_export_dependencies(rosidl_default_runtime) diff --git a/umrr_ros2_msgs/msg/CanObjectHeader.msg b/umrr_ros2_msgs/msg/CanObjectHeader.msg new file mode 100644 index 0000000..f32938e --- /dev/null +++ b/umrr_ros2_msgs/msg/CanObjectHeader.msg @@ -0,0 +1,9 @@ +string frame_id +float32 cycle_time +uint16 number_of_objects +float32 ego_speed +float32 ego_speed_quality +float32 ego_yaw_rate +float32 ego_yaw_rate_quality +uint32 cycle_count +uint8 dyn_source diff --git a/umrr_ros2_msgs/msg/CanTargetHeader.msg b/umrr_ros2_msgs/msg/CanTargetHeader.msg new file mode 100644 index 0000000..0d519e5 --- /dev/null +++ b/umrr_ros2_msgs/msg/CanTargetHeader.msg @@ -0,0 +1,7 @@ +string frame_id +float32 cycle_time +uint8 number_of_targets +uint32 cycle_count +uint8 acquisition_setup +uint32 time_stamp +float32 acq_ts_fraction diff --git a/umrr_ros2_msgs/msg/PortObjectHeader.msg b/umrr_ros2_msgs/msg/PortObjectHeader.msg new file mode 100644 index 0000000..6b71d49 --- /dev/null +++ b/umrr_ros2_msgs/msg/PortObjectHeader.msg @@ -0,0 +1,12 @@ +string frame_id +uint32 port_identifier +int16 port_ver_major +int16 port_ver_minor +uint32 port_size +uint8 body_endianness +uint8 port_index +uint8 header_ver_major +uint8 header_ver_minor +float32 cycle_time +uint16 number_of_objects +uint64 ts_measurement diff --git a/umrr_ros2_msgs/msg/PortTargetHeader.msg b/umrr_ros2_msgs/msg/PortTargetHeader.msg new file mode 100644 index 0000000..f82cdbf --- /dev/null +++ b/umrr_ros2_msgs/msg/PortTargetHeader.msg @@ -0,0 +1,17 @@ +string frame_id +uint32 port_identifier +int16 port_ver_major +int16 port_ver_minor +uint32 port_size +uint8 body_endianness +uint8 port_index +uint8 header_ver_major +uint8 header_ver_minor +float32 cycle_time +uint16 number_of_targets +uint8 acquisition_tx_ant_idx +uint8 acquisition_sweep_idx +uint8 acquisition_cf_idx +uint8 prf +float32 umambiguous_speed +uint64 acquisition_start diff --git a/umrr_ros2_msgs/package.xml b/umrr_ros2_msgs/package.xml index b4bc9b1..3bc3fe0 100644 --- a/umrr_ros2_msgs/package.xml +++ b/umrr_ros2_msgs/package.xml @@ -2,7 +2,7 @@ umrr_ros2_msgs - 1.0.0 + 2.0.0 A package for smartmicro radar messages shah Apache 2.0