From d5d19013e43824718f20e409b579f3265d0d076f Mon Sep 17 00:00:00 2001 From: ifm-csr Date: Wed, 10 Nov 2021 10:00:47 +0000 Subject: [PATCH 1/6] add latest dev changes and fixes --- .clang-format | 65 ++ CHANGELOG.rst | 106 +++ ChangeLog.md | 50 -- README.md | 425 +---------- bin/config | 24 - bin/dump | 24 - clean_emacs.sh | 7 - doc/building.md | 124 ---- doc/dump_and_config.md | 183 ----- doc/figures/rviz_sample.png | Bin 1044402 -> 0 bytes doc/indigo.md | 65 -- doc/kinetic.md | 68 -- doc/melodic.md | 66 -- doc/troubleshooting.md | 36 - ifm3d-ros/CMakeLists.txt | 5 + ifm3d-ros/LICENSE | 202 ++++++ ifm3d-ros/package.xml | 22 + ifm3d_ros_driver/.clang-format | 65 ++ .../CMakeLists.txt | 44 +- ifm3d_ros_driver/LICENSE | 202 ++++++ ifm3d_ros_driver/README.md | 72 ++ ifm3d_ros_driver/doc/building.md | 93 +++ ifm3d_ros_driver/doc/distributed_build.md | 47 ++ ifm3d_ros_driver/doc/dump_and_config.md | 407 +++++++++++ .../doc/figures/O3R_merged_point_cloud.png | Bin 0 -> 763340 bytes .../doc/figures/rviz_ref_frame.png | Bin 0 -> 57878 bytes ifm3d_ros_driver/doc/noetic.md | 64 ++ ifm3d_ros_driver/doc/rpc_error_codes.md | 9 + ifm3d_ros_driver/doc/troubleshooting.md | 50 ++ ifm3d_ros_driver/doc/visualization.md | 28 + .../include/ifm3d_ros_driver/camera_nodelet.h | 122 ++++ ifm3d_ros_driver/launch/camera.launch | 31 + .../launch}/nodelet.launch | 31 +- nodelets.xml => ifm3d_ros_driver/nodelets.xml | 0 package.xml => ifm3d_ros_driver/package.xml | 18 +- .../pylib}/ifm3d/_ConfigClient.py | 18 +- .../pylib}/ifm3d/_DumpClient.py | 18 +- ifm3d_ros_driver/pylib/ifm3d/__init__.py | 5 + .../__pycache__/_ConfigClient.cpython-38.pyc | Bin 0 -> 1114 bytes .../__pycache__/_DumpClient.cpython-38.pyc | Bin 0 -> 1235 bytes setup.py => ifm3d_ros_driver/setup.py | 0 ifm3d_ros_driver/src/camera_nodelet.cpp | 628 ++++++++++++++++ ifm3d_ros_driver/test/gradient.jpg | Bin 0 -> 1363 bytes {test => ifm3d_ros_driver/test}/ifm3d.test | 0 .../test}/test_camera.py | 18 +- ifm3d_ros_driver/test/test_threshold.py | 41 ++ ifm3d_ros_msgs/CMakeLists.txt | 54 ++ ifm3d_ros_msgs/README.md | 24 + ifm3d_ros_msgs/bin/config | 12 + ifm3d_ros_msgs/bin/dump | 12 + ifm3d_ros_msgs/msg/Extrinsics.msg | 11 + ifm3d_ros_msgs/package.xml | 26 + {srv => ifm3d_ros_msgs/srv}/Config.srv | 0 {srv => ifm3d_ros_msgs/srv}/Dump.srv | 0 {srv => ifm3d_ros_msgs/srv}/SoftOff.srv | 0 {srv => ifm3d_ros_msgs/srv}/SoftOn.srv | 0 {srv => ifm3d_ros_msgs/srv}/SyncClocks.srv | 0 {srv => ifm3d_ros_msgs/srv}/Trigger.srv | 1 + include/ifm3d/camera_nodelet.h | 135 ---- launch/camera.launch | 31 - launch/ifm3d.rviz | 225 ------ launch/rviz.launch | 12 - msg/Extrinsics.msg | 10 - pylib/ifm3d/__init__.py | 18 - src/camera_nodelet.cpp | 680 ------------------ 65 files changed, 2472 insertions(+), 2262 deletions(-) create mode 100644 .clang-format create mode 100644 CHANGELOG.rst delete mode 100644 ChangeLog.md delete mode 100755 bin/config delete mode 100755 bin/dump delete mode 100755 clean_emacs.sh delete mode 100644 doc/building.md delete mode 100644 doc/dump_and_config.md delete mode 100644 doc/figures/rviz_sample.png delete mode 100644 doc/indigo.md delete mode 100644 doc/kinetic.md delete mode 100644 doc/melodic.md delete mode 100644 doc/troubleshooting.md create mode 100644 ifm3d-ros/CMakeLists.txt create mode 100644 ifm3d-ros/LICENSE create mode 100644 ifm3d-ros/package.xml create mode 100644 ifm3d_ros_driver/.clang-format rename CMakeLists.txt => ifm3d_ros_driver/CMakeLists.txt (69%) create mode 100644 ifm3d_ros_driver/LICENSE create mode 100644 ifm3d_ros_driver/README.md create mode 100644 ifm3d_ros_driver/doc/building.md create mode 100644 ifm3d_ros_driver/doc/distributed_build.md create mode 100644 ifm3d_ros_driver/doc/dump_and_config.md create mode 100644 ifm3d_ros_driver/doc/figures/O3R_merged_point_cloud.png create mode 100644 ifm3d_ros_driver/doc/figures/rviz_ref_frame.png create mode 100644 ifm3d_ros_driver/doc/noetic.md create mode 100644 ifm3d_ros_driver/doc/rpc_error_codes.md create mode 100644 ifm3d_ros_driver/doc/troubleshooting.md create mode 100644 ifm3d_ros_driver/doc/visualization.md create mode 100644 ifm3d_ros_driver/include/ifm3d_ros_driver/camera_nodelet.h create mode 100644 ifm3d_ros_driver/launch/camera.launch rename {launch => ifm3d_ros_driver/launch}/nodelet.launch (65%) rename nodelets.xml => ifm3d_ros_driver/nodelets.xml (100%) rename package.xml => ifm3d_ros_driver/package.xml (54%) rename {pylib => ifm3d_ros_driver/pylib}/ifm3d/_ConfigClient.py (52%) rename {pylib => ifm3d_ros_driver/pylib}/ifm3d/_DumpClient.py (59%) create mode 100644 ifm3d_ros_driver/pylib/ifm3d/__init__.py create mode 100644 ifm3d_ros_driver/pylib/ifm3d/__pycache__/_ConfigClient.cpython-38.pyc create mode 100644 ifm3d_ros_driver/pylib/ifm3d/__pycache__/_DumpClient.cpython-38.pyc rename setup.py => ifm3d_ros_driver/setup.py (100%) create mode 100644 ifm3d_ros_driver/src/camera_nodelet.cpp create mode 100644 ifm3d_ros_driver/test/gradient.jpg rename {test => ifm3d_ros_driver/test}/ifm3d.test (100%) rename {test => ifm3d_ros_driver/test}/test_camera.py (93%) create mode 100644 ifm3d_ros_driver/test/test_threshold.py create mode 100644 ifm3d_ros_msgs/CMakeLists.txt create mode 100644 ifm3d_ros_msgs/README.md create mode 100755 ifm3d_ros_msgs/bin/config create mode 100755 ifm3d_ros_msgs/bin/dump create mode 100644 ifm3d_ros_msgs/msg/Extrinsics.msg create mode 100644 ifm3d_ros_msgs/package.xml rename {srv => ifm3d_ros_msgs/srv}/Config.srv (100%) rename {srv => ifm3d_ros_msgs/srv}/Dump.srv (100%) rename {srv => ifm3d_ros_msgs/srv}/SoftOff.srv (100%) rename {srv => ifm3d_ros_msgs/srv}/SoftOn.srv (100%) rename {srv => ifm3d_ros_msgs/srv}/SyncClocks.srv (100%) rename {srv => ifm3d_ros_msgs/srv}/Trigger.srv (62%) delete mode 100644 include/ifm3d/camera_nodelet.h delete mode 100644 launch/camera.launch delete mode 100644 launch/ifm3d.rviz delete mode 100644 launch/rviz.launch delete mode 100644 msg/Extrinsics.msg delete mode 100644 pylib/ifm3d/__init__.py delete mode 100644 src/camera_nodelet.cpp diff --git a/.clang-format b/.clang-format new file mode 100644 index 0000000..817fd6d --- /dev/null +++ b/.clang-format @@ -0,0 +1,65 @@ +--- +BasedOnStyle: Google +AccessModifierOffset: -2 +ConstructorInitializerIndentWidth: 2 +AlignEscapedNewlinesLeft: false +AlignTrailingComments: true +AllowAllParametersOfDeclarationOnNextLine: false +AllowShortIfStatementsOnASingleLine: false +AllowShortLoopsOnASingleLine: false +AllowShortFunctionsOnASingleLine: None +AlwaysBreakTemplateDeclarations: true +AlwaysBreakBeforeMultilineStrings: true +BreakBeforeBinaryOperators: false +BreakBeforeTernaryOperators: false +BreakConstructorInitializersBeforeComma: true +BinPackParameters: true +ColumnLimit: 120 +ConstructorInitializerAllOnOneLineOrOnePerLine: true +DerivePointerBinding: false +PointerBindsToType: true +ExperimentalAutoDetectBinPacking: false +IndentCaseLabels: true +MaxEmptyLinesToKeep: 1 +NamespaceIndentation: None +ObjCSpaceBeforeProtocolList: true +PenaltyBreakBeforeFirstCallParameter: 19 +PenaltyBreakComment: 60 +PenaltyBreakString: 1 +PenaltyBreakFirstLessLess: 1000 +PenaltyExcessCharacter: 1000 +PenaltyReturnTypeOnItsOwnLine: 90 +SpacesBeforeTrailingComments: 2 +Cpp11BracedListStyle: false +Standard: Auto +IndentWidth: 2 +TabWidth: 2 +UseTab: Never +IndentFunctionDeclarationAfterType: false +SpacesInParentheses: false +SpacesInAngles: false +SpaceInEmptyParentheses: false +SpacesInCStyleCastParentheses: false +SpaceAfterControlStatementKeyword: true +SpaceBeforeAssignmentOperators: true +ContinuationIndentWidth: 4 +SortIncludes: false +SpaceAfterCStyleCast: false + +# Configure each individual brace in BraceWrapping +BreakBeforeBraces: Custom + +# Control of individual brace wrapping cases +BraceWrapping: { + AfterClass: 'true' + AfterControlStatement: 'true' + AfterEnum : 'true' + AfterFunction : 'true' + AfterNamespace : 'true' + AfterStruct : 'true' + AfterUnion : 'true' + BeforeCatch : 'true' + BeforeElse : 'true' + IndentBraces : 'false' +} +... diff --git a/CHANGELOG.rst b/CHANGELOG.rst new file mode 100644 index 0000000..009df7a --- /dev/null +++ b/CHANGELOG.rst @@ -0,0 +1,106 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package ifm3d-ros +^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.7 +=== + +0.7.0 +------ + +Braking changes: ++ Restructure the ifm3d-ros package into independent subpackages. Please check your path declarations again, especially for the launch files and messages and services. + +Changes between ifm3d_ros 0.6.x and 0.7.0: ++ Order of axis changed in 3D (cloud topic and extrinsic calibration parameters): This wrapper keeps the axis orientation as defined by the underlying API, ifm3d. Therefore, you may see a different axis order for the cloud message compared to older versions of the ifm3d and ifm cameras. ++ Extrinsic calibration parameters: now conistent with SI units, e.g. translation are scaled in `m` and rotation parameters are scaled in `rad`. ++ Added publisher for 2D RGB data ++ Use CameraBase for compatibility with other O3 devices ++ Comment out methods / publisher which are not available for the O3RCamera (at the moment) ++ Comment out the unit vector publishing ++ Changed services trigger and softon, softoff to be compatible with new JSON methods and schema. ++ Changed service trigger to a dummy method until triggers are implemented for the O3R platform. It only has a status message at the moment. ++ Changed service dump: coverts from json to str for displaying the message + +added: ++ Added pcic_port to the list of framegrabber arguments + +known limitations: ++ This version of the ifm3d-ros package only works with the O3R camera platform. + + +0.6 +=== + +0.6.2 +----- +Changes between ifm3d_ros 0.6.1 and 0.6.2 + +* Updated maintainer email address +* Added ifm3d-core dependency in preparation for submission to the ROS index + +0.6.1 +----- + +* Added support syncing the system and camera clocks at startup. Side-effect, + is we can now stamp the images with the camera-side capture time and not the + host-side reception time. +* Added the `SyncClocks` Service + +0.6.0. +------ + +* Added a image transport plugin _blacklist_ to the nodlet launch file. This + prevents many of the errors seen in the terminal when running `rosbag -a` to + capture camera data +* Added the `SoftOn` and `SoftOff` service calls + +0.5 +=== + + +0.5.1 +----- + +* Added support for Ubuntu 18.04 and ROS Melodic + +0.5.0 +----- + +* Converted primary data publisher to a nodelet architecture +* Provide the `dump` and `config` scripts to call into the exposed ROS services + of the nodelet. Removed the older "config node". +* Added unit tests + +0.4 +=== + +0.4.2 +----- + +* Now requires ifm3d 0.9.0 and by association the more modernized tooling + (C++14, cmake 3.5, dropped support for 14.04/Indigo, etc.) + +0.4.1 +----- + +* Now publishing extrinsics on a topic + +0.3 +=== + +* Added `Dump` Service +* Added `Config` Service +* Added `Trigger` Service + +0.2 +=== + +* Updates to CMakeLists.txt to support Ubuntu 14.04 and ROS Indigo + +0.1 +=== + +This file has started tracking ifm3d_ros at 0.1.0 + +* Initial (alpha) release diff --git a/ChangeLog.md b/ChangeLog.md deleted file mode 100644 index ceb694a..0000000 --- a/ChangeLog.md +++ /dev/null @@ -1,50 +0,0 @@ -## Changes between ifm3d-ros 0.6.1 and 0.6.2 - -* Updated maintainer email address -* Added ifm3d-core dependency in preparation for submission to the ROS index - -## Changes between ifm3d-ros 0.6.0 and 0.6.1 - -* Added support syncing the system and camera clocks at startup. Side-effect, - is we can now stamp the images with the camera-side capture time and not the - host-side reception time. -* Added the `SyncClocks` Service - -## Changes between ifm3d-ros 0.5.1 and 0.6.0 - -* Added a image transport plugin _blacklist_ to the nodlet launch file. This - prevents many of the errors seen in the terminal when running `rosbag -a` to - capture camera data -* Added the `SoftOn` and `SoftOff` service calls - -## Changes between ifm3d-ros 0.5.0 and 0.5.1 - -* Added support for Ubuntu 18.04 and ROS Melodic - -## Changes between ifm3d-ros 0.4.2 and 0.5.0 -* Converted primary data publisher to a nodelet architecture -* Provide the `dump` and `config` scripts to call into the exposed ROS services - of the nodelet. Removed the older "config node". -* Added unit tests - -## Changes between ifm3d-ros 0.4.1 and 0.4.2 -* Now requires ifm3d 0.9.0 and by association the more modernized tooling - (C++14, cmake 3.5, dropped support for 14.04/Indigo, etc.) - -## Changes between ifm3d-ros 0.3.0 and 0.4.0 - -* Now publishing extrinsics on a topic - -## Changes between ifm3d-ros 0.2.0 and 0.3.0 - -* Added `Dump` Service -* Added `Config` Service -* Added `Trigger` Service - -## Changes between ifm3d-ros 0.1.0 and 0.2.0 - -* Updates to CMakeLists.txt to support Ubuntu 14.04 and ROS Indigo - -## This file has started tracking ifm3d-ros at 0.1.0 - -* Initial (alpha) release diff --git a/README.md b/README.md index ee9c3b8..1e76efb 100644 --- a/README.md +++ b/README.md @@ -1,408 +1,45 @@ -ifm3d-ros -========= -ifm3d-ros is a wrapper around [ifm3d](https://github.com/lovepark/ifm3d) -enabling the usage of ifm pmd-based ToF cameras from within -[ROS](http://ros.org) software systems. +# ifm3d-ros wrapper around the ifm3d library -![rviz1](doc/figures/rviz_sample.png) -Software Compatibility Matrix -============================= - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
ifm3d-ros versionifm3d versionROS distribution(s)
0.1.00.1.0Kinetic
0.2.00.2.0Kinetic, Indigo
0.3.00.2.0Kinetic, Indigo
0.4.00.2.0, 0.3.0, 0.3.1, 0.3.2Kinetic, Indigo
0.4.10.3.3, 0.4.0, 0.5.0, 0.6.0, 0.7.0, 0.8.1Kinetic, Indigo
0.4.20.9.0Kinetic
0.5.00.9.0, 0.9.1Kinetic
0.5.10.9.2Kinetic, Melodic
0.6.00.9.2, 0.9.3, 0.10.0, 0.11.0, 0.11.2Kinetic, Melodic
0.6.1, 0.6.20.11.2, 0.12.0, 0.17.0Kinetic, Melodic
+**NOTE: The ifm3d-ros package has had major changes recently. Please be aware that this might cause problems on your system for building pipelines based on our old build instructions.** +We tried to ensure backward compatibility where ever possible. If you find any major breaks, please let us know. -Building and Installing the Software -==================================== -1. Preparing your system: [Kinetic](doc/kinetic.md), [Melodic](doc/melodic.md) -2. [Installing the ROS node](doc/building.md) +ifm3d-ros is a wrapper around [ifm3d](https://github.com/ifm/ifm3d/) enabling the usage of the O3R camera platform (ifm ToF cameras) from within [ROS](http://ros.org) software systems. -ROS Interface -============= +![rviz1](ifm3d_ros_driver/doc/figures/O3R_merged_point_cloud.png) -## camera nodelet +## Software Compatibility Matrix -The core `ifm3d-ros` sensor interface is implemented as a ROS nodelet. This -allows for lower-latency data processing vs. the traditional out-of-process -node-based ROS interface for applications that require it. However, we ship a -launch file with this package that allows for using the core `ifm3d-ros` driver -as a standard node. To launch the node, the following command can be used: +|**ifm3d-ros version**|**ifm3d version**|**ROS distribution(s)**| +|---|---|---| +| 0.1.0 | 0.1.0 | Kinetic | +| 0.2.0 | 0.2.0 | Kinetic, Indigo | +| 0.3.0 | 0.2.0 | Kinetic, Indigo | +| 0.4.0 | 0.3.0, 0.3.1, 0.3.2 | Kinetic, Indigo | +| 0.4.1 | 0.3.3, 0.4.0, 0.5.0, 0.6.0, 0.7.0, 0.8.1 | Kinetic, Indigo | +| 0.4.2 | 0.9.0 | Kinetic | +| 0.5.0 | 0.9.0, 0.9.1 | Kinetic | +| 0.5.1 | 0.9.2 | Kinetic, Melodic | +| 0.6.0 | 0.9.2, 0.9.3, 0.10.0, 0.11.0, 0.11.2 | Kinetic, Melodic | +| 0.6.1, 0.6.2 | 0.11.2, 0.12.0, 0.17.0 | Kinetic, Melodic | +| 0.7.0 | NN - in dev - placeholder 0.91.0 | Noetic | -``` -$ roslaunch ifm3d camera.launch -``` -We note, the above command is equivalent to the following and is used for -purposes of providing a backward compatible interface to versions of -`ifm3d-ros` prior to the conversion to a nodelet architecture: +## Organization of the software -``` -$ roslaunch ifm3d nodelet.launch __ns:=ifm3d -``` +The `ifm3d-ros` meta package provides three subpackages: +- `ifm3d_ros_driver` provides the core interface for receiving data for ifm 3d (O3R) cameras. +- `ifm3d_ros_msgs` gathers the ifm-specific messages types and the services for configuring and triggering the camera. +- `ifm3d_ros_examples` provides additional helper scripts and examples. -Regardless of which command line you used from above, the launch file(s) -encapsulate several features: +The name `ifm3d-ros` was kept even tough this is not consistent with ROS package naming conventions. +This ROS package has been split into three sub packages in an effort to facilitate dependency handling on distributed systems and simplify deployment on embedded platforms. For instance, the package `ifm3d_ros_msgs` can be installed independently of the other packages to control the camera from a separate computing platform. The `ifm3d_ros_examples` holds our launch files and examples. -1. It exposes some of the `camera_nodelet` parameters as command-line arguments - for ease of runtime configuration. -2. It instantiates a nodelet manager which the `camera_nodelet` will be loaded - into. -3. It launches the camera nodelet itself. -4. It publishes the static transform from the camera's optical frame to a - traditional ROS sensor frame as a tf2 `static_transform_publisher`. +## Building and installing the software -You can either use [this launch file](launch/camera.launch) directly, or, use -it as a basis for integrating `ifm3d-ros` into your own robot software system. +1. Preparing your system: [Noetic](ifm3d_ros_driver/doc/noetic.md) +2. [Installing the ifm3d-ros node](ifm3d_ros_driver/doc/building.md) -We note: due to the change in architecture from a standalone node to a nodelet, -we have seen one behavior whose solution is not clear to have us provide -backward compatible behavior with older versions of `ifm3d-ros`. Specifically, -if you plan to run the camera in software triggered mode, you should lanch the -node as follows: - -``` -$ GLOG_minloglevel=3 roslaunch ifm3d camera.launch assume_sw_triggered:=true -``` - -The incomatibility here is that in prior versions, one would not need to -explicitly set the `GLOG_` environment variable. While not strictly necessary, -it is recommended for keeping the noise level of the `ifm3d` logs low. - - -### Parameters - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
NameData TypeDefault ValueDescription
~assume_sw_triggeredboolfalse - This provides a hint to the driver that the camera is configured for - software triggering (as opposed to free running). In this mode, certain - default values are applied to lessen the noise in terms of timeouts from - the framegrabber. -
~frame_id_basestringifm3d/camera - This string provides a prefix into the `tf` tree for `ifm3d-ros` - coordinate frames. -
~frame_latency_threshfloat60.0 - Time (seconds) used to determine that timestamps from the camera cannot - be trusted. When this threshold is exceeded, when compared to system - time, we use the reception time of the frame and not the capture time of - the frame. -
~ipstring192.168.0.69 - The ip address of the camera. -
~passwordstring - The password required to establish an edit session with the camera. -
~schema_maskuint160xf - The pcic schema mask to apply to the active session with the frame - grabber. This determines which images are available for publication from - the camera. More about pcic schemas can be gleaned from the - ifm3d project. -
~timeout_millisint500 - The number of milliseconds to wait for the framegrabber to return new - frame data before declaring a "timeout" and to stop blocking on new - data. -
~timeout_tolerance_secsfloat5.0 - The wall time to wait with no new data from the camera before trying to - establish a new connection to the camera. This helps to provide - robustness against camera cables becoming unplugged or other in-field - pathologies which would cause the connection between the ROS node and the - camera to be broken. -
~soft_on_timeout_millisint500 - If using the `SoftOn` service call, when turning the camera back `on` - this is the setting that will be used for `timeout_millis`. -
~soft_on_timeout_tolerance_secsfloat5.0 - If using the `SoftOn` service call, when turning the camera back `on` - this is the setting that will be used for `timeout_tolerance_secs`. -
~soft_off_timeout_millisint500 - If using the `SoftOff` service call, when turning the camera `off` - this is the setting that will be used for `timeout_millis`. -
~soft_off_timeout_tolerance_secsfloat600.0 - If using the `SoftOff` service call, when turning the camera `off` - this is the setting that will be used for `timeout_tolerance_secs`. -
~sync_clocksboolfalse - Attempt to sync the camera clock to the system clock at start-up. The - side-effect is that timestamps on the image should reflect the capture - time as opposed to the receipt time. -
~xmlrpc_portuint1680 - The TCP port the camera's xmlrpc server is listening on for requests. -
- -### Published Topics - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
NameData TypeDescription
amplitudesensor_msgs/ImageThe normalized amplitude image
cloudsensor_msgs/PointCloud2The point cloud data
confidencesensor_msgs/ImageThe confidence image
distancesensor_msgs/ImageThe radial distance image
extrinsicsifm3d/Extrinsics - The extrinsic calibration of the camera with respect to the camera - optical frame. The data are mm and degrees. -
good_bad_pixelssensor_msgs/Image - A binary image indicating good vs. bad pixels as gleaned from the - confidence data. -
raw_amplitudesensor_msgs/ImageThe raw amplitude image
unit_vectorssensor_msgs/ImageThe rotated unit vectors
xyz_imagesensor_msgs/Image - A 3-channel image encoding of the point cloud. Each of the three image - channels respesent a spatial data plane encoding the x, y, z cartesian - values respectively. -
- -### Subscribed Topics - -None. - -### Advertised Services - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
NameService DefinitionDescription
Dumpifm3d/DumpDumps the state of the camera parameters to JSON
Configifm3d/Config - Provides a means to configure the camera and imager settings, - declaratively from a JSON encoding of the desired settings. -
SoftOffifm3d/SoftOff - Sets the active application of the camera into software triggered - mode which will turn off the active illumination reducing both power and - heat. -
SoftOnifm3d/SoftOn - Sets the active application of the camera into free-running mode. - Its intention is to act as the inverse of `SoftOff`. -
SyncClocksifm3d/SyncClocks - Synchronizes the camera clock to the system time. The side-effect is that - images can be stamped with the capture time of the frame as opposed to - the reception time. -
Triggerifm3d/Trigger - Requests the driver to software trigger the imager for data - acquisition. -
- - -Additional Documentation -======================== - -* [Inspecting and configuring the camera/imager settings](doc/dump_and_config.md) -* [Troubleshooting](doc/troubleshooting.md) - -LICENSE -------- - -Please see the file called [LICENSE](LICENSE). +# LICENSE +Please see the file called [LICENSE](LICENSE). \ No newline at end of file diff --git a/bin/config b/bin/config deleted file mode 100755 index 1e2ba9b..0000000 --- a/bin/config +++ /dev/null @@ -1,24 +0,0 @@ -#!/usr/bin/env python -# -*- python -*- - -# -# Copyright (C) 2018 ifm electronic, gmbh -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distribted on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# - -import sys -from ifm3d import ConfigClient - -if __name__ == '__main__': - sys.exit(ConfigClient().run()) diff --git a/bin/dump b/bin/dump deleted file mode 100755 index 9d4c8b0..0000000 --- a/bin/dump +++ /dev/null @@ -1,24 +0,0 @@ -#!/usr/bin/env python -# -*- python -*- - -# -# Copyright (C) 2018 ifm electronic, gmbh -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distribted on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# - -import sys -from ifm3d import DumpClient - -if __name__ == '__main__': - sys.exit(DumpClient().run()) diff --git a/clean_emacs.sh b/clean_emacs.sh deleted file mode 100755 index 1e3781b..0000000 --- a/clean_emacs.sh +++ /dev/null @@ -1,7 +0,0 @@ -#!/bin/sh -# -# Recursively removes emacs backup files from your source directory. -# -echo "Cleaning up emacs backup files..." -find . -name "*~" | xargs rm -f -echo "OK" \ No newline at end of file diff --git a/doc/building.md b/doc/building.md deleted file mode 100644 index cc55955..0000000 --- a/doc/building.md +++ /dev/null @@ -1,124 +0,0 @@ - -Building and Installing the ifm3d-ros Package ---------------------------------------------- - -### Prerequisites - -1. [Ubuntu 16.04 LTS](http://www.ubuntu.com) -2. [ROS Kinetic](http://www.ros.org/install) - we recommend `ros-kinetic-desktop-full`. -3. [ifm3d](https://github.com/lovepark/ifm3d) - version >= 0.9.0 - -or - -1. [Ubuntu 18.04 LTS](http://www.ubuntu.com) -2. [ROS Melodic](http://www.ros.org/install) - we recommend `ros-melodic-desktop-full`. -3. [ifm3d](https://github.com/lovepark/ifm3d) - version >= 0.9.2 - -### Step-by-Step Build Instructions - -Step-by-step instructions on getting a fresh installation of Ubuntu and ROS -prepared for usage with `ifm3d-ros` is available at the following links: -* [Ubuntu 16.04 with ROS Kinetic](kinetic.md) -* [Ubuntu 18.04 with ROS Melodic](melodic.md) - -Building and installing ifm3d-ros is accomplished by utilizing the ROS -[catkin](http://wiki.ros.org/catkin) tool. There are many tutorials and other -pieces of advice available on-line advising how to most effectively utilize -catkin. However, the basic idea is to provide a clean separation between your -source code repository and your build and runtime environments. The -instructions that now follow represent how we choose to use catkin to build and -_permanently install_ a ROS package from source. - -First, we need to decide where we want our software to ultimately be -installed. For purposes of this document, we will assume that we will install -our ROS packages at `~/ros`. For convenience, we add the following to our -`~/.bashrc`: - -NOTE: Below we assume `kinetic`. Adapting to `melodic` is left as an exercise -for the reader. - -``` -if [ -f /opt/ros/kinetic/setup.bash ]; then - source /opt/ros/kinetic/setup.bash -fi - -cd ${HOME} - -export LPR_ROS=${HOME}/ros - -if [ -d ${LPR_ROS} ]; then - for i in $(ls ${LPR_ROS}); do - if [ -d ${LPR_ROS}/${i} ]; then - if [ -f ${LPR_ROS}/${i}/setup.bash ]; then - source ${LPR_ROS}/${i}/setup.bash --extend - fi - fi - done -fi -``` - -Next, we need to get the code from github. We assume we keep all of our git -repositories in `~/dev`. - -``` -$ cd ~/dev -$ git clone https://github.com/lovepark/ifm3d-ros.git -``` - -We now have the code in `~/dev/ifm3d-ros`. Next, we want to create a _catkin -workspace_ that we can use to build and install that code from. It is the -catkin philosophy that we do not do this directly in the source directory. - -``` -$ cd ~/catkin -$ mkdir ifm3d -$ cd ifm3d -$ mkdir src -$ cd src -$ catkin_init_workspace -$ ln -s ~/dev/ifm3d-ros ifm3d -``` - -So, you should have a catkin workspace set up to build the ifm3d-ros code that -looks basically like: - -``` -[ ~/catkin/ifm3d/src ] -tpanzarella@tuna: $ pwd -/home/tpanzarella/catkin/ifm3d/src - -[ ~/catkin/ifm3d/src ] -tpanzarella@tuna: $ ls -l -total 0 -lrwxrwxrwx 1 tpanzarella tpanzarella 50 Mar 26 15:16 CMakeLists.txt -> /opt/ros/kinetic/share/catkin/cmake/toplevel.cmake -lrwxrwxrwx 1 tpanzarella tpanzarella 31 Mar 26 15:16 ifm3d -> /home/tpanzarella/dev/ifm3d-ros -``` - -Now we are ready to build the code. - -``` -$ cd ~/catkin/ifm3d -$ catkin_make -DCATKIN_ENABLE_TESTING=ON -$ catkin_make run_tests -$ catkin_make -DCMAKE_INSTALL_PREFIX=${LPR_ROS}/ifm3d install -``` - -The ROS package should now be installed in `~/ros/ifm3d`. To test everything -out you should open a fresh bash shell, and start up a ROS core: - - $ roscore - -Open another shell and start the primary camera node: - - $ roslaunch ifm3d camera.launch - -Open another shell and start the rviz node to visualize the data coming from -the camera: - - $ roslaunch ifm3d rviz.launch - -At this point, you should see an rviz window that looks something like: - -![rviz1](figures/rviz_sample.png) - -Congratulations! You can now utilize ifm3d-ros. diff --git a/doc/dump_and_config.md b/doc/dump_and_config.md deleted file mode 100644 index fd14135..0000000 --- a/doc/dump_and_config.md +++ /dev/null @@ -1,183 +0,0 @@ - -ifm3d-ros: Dump and Config -========================== - -`ifm3d-ros` provides access to the camera/imager parameters via the `Dump` and -`Config` services exposed by the `camera_nodelet`. Additionally, command-line -scripts called `dump` and `config` are provided as wrapper interfaces to those -services. This gives a feel similar to using the underlying `ifm3d` -command-line tool from the ROS-independent driver except proxying the calls -through the ros network. - -For example, to dump the state of the camera: - -(exemplary output from an O3D303 is shown) - -``` -$ rosrun ifm3d dump -{ - "ifm3d": { - "Apps": [ - { - "Description": "", - "Id": "322089668", - "Imager": { - "AutoExposureMaxExposureTime": "10000", - "AutoExposureReferencePointX": "88", - "AutoExposureReferencePointY": "66", - "AutoExposureReferenceROI": "{\"ROIs\":[{\"id\":0,\"group\":0,\"type\":\"Rect\",\"width\":130,\"height\":100,\"angle\":0,\"center_x\":88,\"center_y\":66}]}", - "AutoExposureReferenceType": "0", - "Channel": "0", - "ClippingBottom": "131", - "ClippingCuboid": "{\"XMin\": -3.402823e+38, \"XMax\": 3.402823e+38, \"YMin\": -3.402823e+38, \"YMax\": 3.402823e+38, \"ZMin\": -3.402823e+38, \"ZMax\": 3.402823e+38}", - "ClippingLeft": "0", - "ClippingRight": "175", - "ClippingTop": "0", - "ContinuousAutoExposure": "false", - "ContinuousUserFrameCalibration": "false", - "EnableAmplitudeCorrection": "true", - "EnableFastFrequency": "false", - "EnableFilterAmplitudeImage": "true", - "EnableFilterDistanceImage": "true", - "EnableRectificationAmplitudeImage": "false", - "EnableRectificationDistanceImage": "false", - "ExposureTime": "5000", - "ExposureTimeList": "125;5000", - "ExposureTimeRatio": "40", - "FrameRate": "10", - "MaxAllowedLEDFrameRate": "23.2", - "MinimumAmplitude": "42", - "Resolution": "0", - "SpatialFilter": {}, - "SpatialFilterType": "0", - "SymmetryThreshold": "0.4", - "TemporalFilter": {}, - "TemporalFilterType": "0", - "ThreeFreqMax2FLineDistPercentage": "80", - "ThreeFreqMax3FLineDistPercentage": "80", - "TwoFreqMaxLineDistPercentage": "80", - "Type": "under5m_moderate", - "UseSimpleBinning": "false" - }, - "Index": "1", - "LogicGraph": "{\"IOMap\": {\"OUT1\": \"RFT\",\"OUT2\": \"AQUFIN\"},\"blocks\": {\"B00001\": {\"pos\": {\"x\": 200,\"y\": 200},\"properties\": {},\"type\": \"PIN_EVENT_IMAGE_ACQUISITION_FINISHED\"},\"B00002\": {\"pos\": {\"x\": 200,\"y\": 75},\"properties\": {},\"type\": \"PIN_EVENT_READY_FOR_TRIGGER\"},\"B00003\": {\"pos\": {\"x\": 600,\"y\": 75},\"properties\": {\"pulse_duration\": 0},\"type\": \"DIGITAL_OUT1\"},\"B00005\": {\"pos\": {\"x\": 600,\"y\": 200},\"properties\": {\"pulse_duration\": 0},\"type\": \"DIGITAL_OUT2\"}},\"connectors\": {\"C00000\": {\"dst\": \"B00003\",\"dstEP\": 0,\"src\": \"B00002\",\"srcEP\": 0},\"C00001\": {\"dst\": \"B00005\",\"dstEP\": 0,\"src\": \"B00001\",\"srcEP\": 0}}}", - "Name": "Sample Application", - "PcicEipResultSchema": "{ \"layouter\": \"flexible\", \"format\": { \"dataencoding\": \"binary\", \"order\": \"big\" }, \"elements\" : [ { \"type\": \"string\", \"value\": \"star\", \"id\": \"start_string\" }, { \"type\": \"records\", \"id\": \"models\", \"elements\": [ { \"type\": \"int16\", \"id\": \"boxFound\" }, { \"type\": \"int16\", \"id\": \"width\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"height\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"length\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"xMidTop\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"yMidTop\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"zMidTop\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"yawAngle\" }, { \"type\": \"int16\", \"id\": \"qualityLength\" }, { \"type\": \"int16\", \"id\": \"qualityWidth\" }, { \"type\": \"int16\", \"id\": \"qualityHeight\" } ] }, { \"type\": \"string\", \"value\": \"stop\", \"id\": \"end_string\" } ] }", - "PcicPnioResultSchema": "{\"layouter\" : \"flexible\", \"format\": { \"dataencoding\": \"binary\", \"order\": \"big\" }, \"elements\" : [ { \"type\": \"string\", \"value\": \"star\", \"id\": \"start_string\" }, { \"type\": \"records\", \"id\": \"models\", \"elements\": [ { \"type\": \"int16\", \"id\": \"boxFound\" }, { \"type\": \"int16\", \"id\": \"width\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"height\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"length\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"xMidTop\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"yMidTop\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"zMidTop\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"yawAngle\" }, { \"type\": \"int16\", \"id\": \"qualityLength\" }, { \"type\": \"int16\", \"id\": \"qualityWidth\" }, { \"type\": \"int16\", \"id\": \"qualityHeight\" } ] }, { \"type\": \"string\", \"value\": \"stop\", \"id\": \"end_string\" } ] }", - "PcicTcpResultSchema": "{ \"layouter\": \"flexible\", \"format\": { \"dataencoding\": \"ascii\" }, \"elements\": [ { \"type\": \"string\", \"value\": \"star\", \"id\": \"start_string\" }, { \"type\": \"blob\", \"id\": \"normalized_amplitude_image\" }, { \"type\": \"blob\", \"id\": \"distance_image\" }, { \"type\": \"blob\", \"id\": \"x_image\" }, { \"type\": \"blob\", \"id\": \"y_image\" }, { \"type\": \"blob\", \"id\": \"z_image\" }, { \"type\": \"blob\", \"id\": \"confidence_image\" }, { \"type\": \"blob\", \"id\": \"diagnostic_data\" }, { \"type\": \"string\", \"value\": \"stop\", \"id\": \"end_string\" } ] }", - "RtspOverlayStyle": "{\"ROI\": {\"default\": {\"visible\": true, \"filled\": false, \"use_symbol\": false, \"label_alignment\": \"top\", \"label_content\": \"\", \"label_background\": \"black\", \"label_fontsize\": 8, \"label_failonly\": false}, \"model_defaults\": {}, \"specific\": {} } }", - "TemplateInfo": "", - "TriggerMode": "1", - "Type": "Camera" - } - ], - "Device": { - "ActiveApplication": "1", - "ArticleNumber": "O3D303", - "ArticleStatus": "AD", - "Description": "", - "DeviceType": "1:2", - "EIPConsumingSize": "8", - "EIPProducingSize": "450", - "EnableAcquisitionFinishedPCIC": "false", - "EthernetFieldBus": "1", - "EthernetFieldBusEndianness": "0", - "EvaluationFinishedMinHoldTime": "10", - "ExtrinsicCalibRotX": "0", - "ExtrinsicCalibRotY": "0", - "ExtrinsicCalibRotZ": "0", - "ExtrinsicCalibTransX": "0", - "ExtrinsicCalibTransY": "0", - "ExtrinsicCalibTransZ": "0", - "IODebouncing": "true", - "IOExternApplicationSwitch": "0", - "IOLogicType": "1", - "IPAddressConfig": "0", - "ImageTimestampReference": "1524246144", - "Name": "FooBarBaz", - "OperatingMode": "0", - "PNIODeviceName": "", - "PasswordActivated": "false", - "PcicProtocolVersion": "3", - "PcicTcpPort": "50010", - "PcicTcpSchemaAutoUpdate": "false", - "SaveRestoreStatsOnApplSwitch": "true", - "ServiceReportFailedBuffer": "15", - "ServiceReportPassedBuffer": "15", - "SessionTimeout": "30", - "TemperatureFront1": "3276.7", - "TemperatureFront2": "3276.7", - "TemperatureIMX6": "53.1839981079102", - "TemperatureIllu": "60.6", - "UpTime": "3.13861111111111" - }, - "Net": { - "MACAddress": "00:02:01:40:7D:96", - "NetworkSpeed": "0", - "StaticIPv4Address": "192.168.0.69", - "StaticIPv4Gateway": "192.168.0.201", - "StaticIPv4SubNetMask": "255.255.255.0", - "UseDHCP": "false" - }, - "Time": { - "CurrentTime": "1524246142", - "NTPServers": "", - "StartingSynchronization": "false", - "Stats": "", - "SynchronizationActivated": "false", - "Syncing": "false", - "WaitSyncTries": "2" - }, - "_": { - "Date": "Tue May 15 13:38:32 2018", - "HWInfo": { - "Connector": "#!02_A300_C40_02452814_008023176", - "Diagnose": "#!02_D322_C32_03038544_008023267", - "Frontend": "#!02_F342_C34_17_00049_008023607", - "Illumination": "#!02_I300_001_03106810_008001175", - "MACAddress": "00:02:01:40:7D:96", - "Mainboard": "#!02_M381_003_03181504_008022954", - "MiraSerial": "0e30-59af-0ef7-0244" - }, - "SWVersion": { - "Algorithm_Version": "2.1.5", - "Calibration_Device": "00:02:01:40:7d:96", - "Calibration_Version": "0.9.0", - "Diagnostic_Controller": "v1.0.33-92f88d349f-dirty", - "IFM_Recovery": "unversioned", - "IFM_Software": "1.23.1522", - "Linux": "Linux version 3.14.34-rt31-yocto-standard-00009-ge4ab4d94f288-dirty (jenkins@dettlx190) (gcc version 4.9.2 (GCC) ) #1 SMP PREEMPT RT Tue Mar 13 16:06:07 CET 2018", - "Main_Application": "1.0.33" - }, - "ifm3d_version": 900 - } - } -} -``` - -Chaining together Linux pipelines works just as it does in `ifm3d`. For -example, using a combination of `dump` and `config` to set a new name on the -camera would look like: - -``` -$ rosrun ifm3d dump | jq '.ifm3d.Device.Name="My 3D Camera"' | rosrun ifm3d config -$ rosrun ifm3d dump | jq .ifm3d.Device.Name -"My 3D Camera" -``` - -**NOTE:** If you do not have `jq` on your system, it can be installed with: `$ sudo apt-get install jq` - -For the `config` command, one difference between our ROS implementation and the -`ifm3d` implementation is that we only accept input on `stdin`. So, if you had -a file with JSON you wish to configure your camera with, you would simply use the -file I/O redirection facilities of your shell (or something like `cat`) to feed -the data to `stdin`. For example, in `bash`: - -``` -$ rosrun ifm3d config < camera.json -``` - -Beyond the requirement of prefacing your command-line with `rosrun` to invoke -the ROS version of these tools, they operate the same. To learn more about the -functionality and concepts, you can read the docs -[here](https://github.com/lovepark/ifm3d/blob/master/doc/configuring.md). diff --git a/doc/figures/rviz_sample.png b/doc/figures/rviz_sample.png deleted file mode 100644 index d76f6b62d8b322bfed3d26a42cc65862436c9de6..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1044402 zcmZ5{1z1#D*Z%<|1PKA@5R{e%=@2EPySt^kQ%YJSB}D|Jo1sCvhaPHZ7`ldz;m>`) zd%y3#|MNUk=gisrti5ut^;?n3iqhDaWS9T|V1JbPpb7x!i2(4V83Xz84EHn4$j6VT zPBJ>K0D#l|*9$3`1&15}UIHIKyi@ne+=qG^6Hd>g9bXRHvCo|u%1FHYHTE<&ERN@0 zl%etpt)#Me6t-A%KdPkorwPJ$`HYfyzg|&3`E`jeBZK^!X6|){`NHruB5lOHrkRH3 z$>$qHxeH$nx7DcnaLrLRjbyl=I0j89p2RxqznO4n<&U0JnBm0y}j3}5|gZe@ic z^%3{pgN(L-cMcAMQnYl>-rIewykYMG|95%(OB5Ul``SUm8D50I^lS-VS=`@_M{wD(NzQM2QC`QKyFRUd!2?#8eyfU zNSK6-?w7}k3T>M2??3#DI2!fFjr77K6YX#ll5i6`eB@A7L-`U^2}{;rbMYlL8j=`D zc!HYvl?%+>Oeg>$21}B@8d9G#?}Ev{Xu`YUD^Yh*U}FE(B+jIqjgNfMrH=xj8h_y! zQqy*^$C_lKdv=_J?`%4NrVL1U8~z?fy8#Da()};X9#>gplli;;0=^Aq5;C5iHy0Br zBpn$~LM{h#)gY+nZYn;4LCN4jF5Zp(I!Rd%>K=PR^luI$rkPXq;S#O9xJjznpRfGh zH#6`=)eVbhx6OiHH?T2bf?jA~J*_)XFd<;d2a*DB-Xi_i?YzuJt_nyPN=S?rve{mY zEgxlVO66!*`o_W1rbbT`nJh4nfHrfC=P$eKg9$P4FokFI|BI>E#drJ=aV8~3+>YR{ z_o_c6>=X`)OLGSMAr3qa5={9?G{6%t*&4$5No_#6Q7gZ}=$N#`?g ztq1f*kBP}7Hy3<)q&4aP4kNdaGEi)?*0Son)96F4`75&x5p<5+I@>0-f7nMQRKUeO zmpy{fq4q-<6*H+&SSk3k?0WgcHlq@g5|cC&SgiHIDaoaNRL#(9_w}*xi~29HP?M$} zn)l2euLQjRd=A4Rdef4SdB@ndVpMLjUeJ1bCgiiw819RCH9Vf?g)Z9| zzs(SG+qQn2VcYa-+h_wbu{wOtaI#fA?zlnyOS5z1@g!%;`mJ?BFnFMvVp;2I&TA+^ zgcr*GkC?<8tEIB$Z(p6*Kh?Q64>IPXqM`y{b8?iJ=r)-Aelp!i54`-IGmt_7 zG87)YSASgYe8l&@{3gfxDf2h!4^ML{*ty3|*$hQ9$_VvIY9EUCmy5A+*lSk7kqz5kK}$ebJ2Fp+#A z=zFnv=SYNxhQ@0*%fZNal@S&V&S^j9*9^r2Homq*POzJ)-v@9X+;%nnDri>2{@r8F zdTpFAw0J(=?+MA*DV~~GZ|Y@P&+*j%fE!p-CjMtj!+Y)$lYf*#MTy%s`6ik=Hn7*y&uu&h4SA1w)G6XFB&0y*$zTR}0r4m_*x+*BCM;%i{aPmQ2^EwBB_jFLvg@_|sHMAD1jwToV_mJEAE?Z}Gd#m?DVDzw>o|5@v`2NsYD!3;wNE)Jo$w_6Gxa^&Dqp99yf zuNBL-Fay;EiJMF$?ji)(*-b1)7Ad1#(Go&!b){BtdXCIGCvkP*b z=w7I#mmhzcEDWqMfwFsGk+RwAR-3P%)Y2N)zIzH*B7@MaB*@*%r?!2s6~EmoeYZNT z_tXDmEq_CgX}z~KU~h&sS$6t|N!Jos1Qc-ZlVY(q9qrL7e=a&uN zkLE5)VT4(0;3?!qiN{^?H!y*_c!*VaysxO#Er^w&G?c;luFHQh5j%X%V+$XSW2jfs^lA{_7-mM_hhJmCV?_YCt``+E&8(h zA-dD;I^!e6_q&ehefRyQSm#?oQVcoAi~$GJzF1UR+n7GQAYnY}<_MTO9<}cwnBZ-%LB%s3If{N!pE3OS60N897ZWD1lvbgih`rcDf+_ua9 zqFNpCi4Q2V{j#4>-@NNGO2K(b0c>aQboqFp1hsV4G!9uJ2W`$v;-(G>cQf5|=%=~I z+b#?UNx+@>^lkVrdiIR6xsU;wMTxb<8=ON3m-3;_IsP&|rC^4BJ9^60^pSkCkl#h9 zcF+4V>c6!U@p15OG{@!s=apcoN6b}v)O(xbsSAFoM++2JlT7POA$>ilfkw(coL#AY zxdrR8X}*$78$zrnUOwy#xVn74$p!rqmMpYX)Yf{aQ4+l6BK$JuY=}{8?|NL{$AusM zJi0n-;S;1BDoyR*?Y!85gmQ5NU5CLy4;@IWW$!`^Wo;(6&YjI3j#_aw%M3@V6|0DO zx3{{S_gyqR05L1;=JAFwcDq-)QWTY-j=f)&&RXR0#5UNmj?Ur zoHW}95*bhujhyWcqITwY=WJCoT5opr#&sv5dpomIsZdrC`x%~lR z+6^9(dmHRI{I@ls^S0ue%&D_g@)+S)z3?- zOq`wD(})Ub>*33CqX7t0_RZ`~Nkw~8LZ<4#_gAkv>0@$~Z{X|guWd0=1?6tm<#(cl zP0={iqMbulGh{S=!!!N<#A1b=qXi1n4!d0Rkq*J^9r^Q=@ahPO2G;0@DX76ji>*Ez zkj=^ECgEN9$B&|GY^x(^iFy-4Y7gWepIx#!7_@9pI=Z|%f; z^TwTzzwoAx7@OGrMgFBW8;2<$*JYlF0)FF8Znc#FVq+&gycFH7h8ms;D9P1NfDGpR_>r% zYYjaSl5)4+BbJKY$G4fi{u4^c+J4t!1z@G%H7wi7aNuW=QRljQQP9$3E&b2~un>a75r9A~~*mSw; zPw+cKK9iesZDYUMUR1Z3)BonIe$N+q&(PUxcjn{S@2=*+JNXcll`(Mmga#18vts^&1s{;Oc@?IYON*h zDC4B{RssrNY!U$EVs(6ZzNry#xZB<7MJ2l(3daAGiAE|yuLGORqI5P#HgCpu;XX3hf2}Ac7MBAmwbiz`tSF1qtla zdq%;%dhNxB7#(diy7Lok?Lbyt?#;?5DW~FhF;Eg&zfnpXtB8vVx*iRt-l~`nADz#DU)=%b+6r-Q;eN!uFfxsd5p4oe3$17q;D2}tHo!in$y7JHATMqmg_7*Ma@fo7I@8%buE_=0c`zkjOM#cFHS}G*&7@Zxr z8Cl}S{7zO`($E)?a`fMeXc-yPk`sQN#OD|wca;PoDmlbD$${fkuMu>8mMz9%RZ{Hh2X-tS!44(Fa4U0 zN80qzyu}kmUm1C`Ny*7GEf5XsT*D{{tk)y_ZvqYOv|$U;_a~l$)2x?+nN{~1K*3Or zR0{@>khi5|?{bpo++LT)S=W5ATU`XdTFuf=H^b~mVBy7P!J`*v;zWfI2!Zx%^ zH2rC8_D>m#xgx9Qv(gJPkLU;^lX(Sz@#-E{x<~9?lK=8L>NsT(TDaJgsWeVoVYHkT z5IChpVEV$ig&%e<*)+f%?uDYw6_E4R@;b|}m!%%|g%gFWF*W#rO2uJBLSW z15sx)vsR{c`g^Lq>p_A1Ig;_nqJTxWWyr@}wRT9Fvp;3q&rZfEvNFY=)9%|4i-iP# ztuy^vrQk^%p5-gV$fxT(SgRp}R!bdMQq657~+%MFO68S^7;$`5zsp_t@eZfl(jm{SC>-i&8#=1#A6A+56N^OIN11TA4&@ zh?H(GYO_%kKHR>mXrJm%MAc1evA;ewink)LMlDb zNmM7v{+!}xpiOfBf#gMxWU&JenNh&Cg+%|^&LjZ=0c<40^I*PiJWm>>qj*{@=W1_i z_Vp>Igc|OSag~NoU&aOXD*EVC2?ywR9w< zEfL0(nt69oT2f@O`yrAY!%T7ob6XskW&3Ye!yLax*=dg(J^r=p*SEOc1 z^3dk}&4ssebopqC3g@DcT-z00A^eKeF@oz_QkT_r!29F+bWWf!DZk%nU+gsM9KFF# zAC&;HqUCMfCxTrk3c4j$!|aK{_qL7o9=oMIdU~Tb@kS~>)om9nM)BoV0w9~g7O|hw zZTHhpBu|@mT-z3wEp4>GwMJq_el!955AAAhY-mXu=VXL~hnWG8){jl}9$er%ywuJ#} zQRLBBmdH-wD_Yr61+^T8HXiY5p_pi^Do^0bDY_JwF7&xJ`z$V;PuCi;oo5PLczs>% zU;M-}^O~2En8i~t(Z2&h#^5cz#ZP@`gP8b3Aiy^9!>YHQ@ydEMKGrhk&HW6aiqx66 zYp=1A&PA@HsKH5Bk!1yM{6@Rbcaw5zChh_%ISmN)w*9RVlCIafc5(55abfP~hSFA7 z%LC2Fz571>>E50ddv-a_wTpP#RPJUdh~P*1Co-P)R38H``v$*W1nct62(#||AtCG0 zE&qq-GZy*-y>-M(@o66_}tA?M=g&tJ>U(v#?i%KX-l(}9RC1sb!Q*hoUlYDCn{F553$#di5 z#{=ZqpDgV|%r-(ziZ`3zYB|9CuYDM>l%57%m4z@>c;Mxz-LL)>nXbx?I79)22Si`~ zPxb>L#muLR!5;IIM%_RSm->N#LD7i<~#u31sGAS`WL!9KTyi!GU?cM}hyQEF*kvGVH>&pTrFy|gp2w(RrCrqHzKDk*Bq;JF`; zm%D{#A*AmUq!h|ky_Fx7#J0D)l*26;m4a987gPnUF{#;#uqO&@e6mzZBCXaAJxNkEEVq|hk606y|1TFO>=FR zee~MIvOYzAL*kHiG*Zg4e@5K*Hm?LR;^tL5E}{M4@W3Zo=W*WqX+7Z7;bQU2YU^5> zoX}{ApxU82D4E3I!vg-^YT9pN;9f5U9pp&CC+Qf)z zzAPyThf)w(yel001*RnE5Q_9N*W1+3PZ-#M!K5M4MOqbxUS3x_lZ8meM@wQ987pVa zqJG}Q05D$XbGerrHflBWb?j$ZAz_wSK>5cngdOAnromZQ|J1}QTyTvdHyM0?*T;swms)>TV-rjYi;;v7=nOW=FDj+bl zCMtfi&G~CDJH9@Pue&5!-o!^Xg{i(g5D#$DVRK*~&&_8L-zmZ=Mk9c=>MgIvYyz@u z3P1!+ROIkT7ZeJ~^N$#d_4SiLX>FCsh@;s9EwZhczEHHP#+@}-=UMKt&(&$QxfMSg zpd<#2Tj%3$j;cI~?$fT?CzLu!6qJ9X0d8f@AIc1q4S#Hp(YIJ1?D)>ew4V`Z%|5Cn z-437QFt4(L{?158(g_Ta5x|;JqO{+#3V}tljR(BBYUA1NnBBZpy~T-4O12ls3E3sz zk;7Xo@7qxj3o2okK&?MeIW$!){7syA=%W~EWtZqf(`F|FdS~Dn*Z@;~M-Fpr$19Sx z98etTFZ>hyju~J?dx@Fz^`#?wku*f{-2(0}66*%2*IJ5@So`@J7ywE={VGn_`II*f zovKg{#9CjL4h{`X%B{{_&&_9O8je&+p#V%G(2~eM-TCG(R4|2=yfGy$2c4$|)v_Zn z9;7RF5esL3C&v4CnnV$01!0Kx`1}TpQbU4x;X2sxO8|>j*XlTWE%ou>Q@Kx9Bbk) z3HN;@gTGEt;j1ng)3rNj!(cFUKuz@e>h2o8%w}*3t1`<85JUw;?~X&Zo<60V2a#Xp zz>r=tGFneokPp5YCdVc!lFE(RT{0AOpQPG>o^2E3x8{SURONyrS%zoeO`7%JIEtjd z&iK87FcvKo7wrb3Cr1Co#Qk+k$Lj(_X{9|5in8W5zit^R8}fJW=$ zi|XWo!7{6^@0n$}4sCwQSaqau-dMj^-nc9hNuwr?X3ezj*H4wd%F{TU!tANCq&aad zWLc>fEnf(CTGIgHQ>zDvTZe^U9jmv)w>N=C{Z=uXaD}<{*4yP}J8l_rGPxScHpYb= zgOZ*!d-c9Xv22FAu&{8$Ca>HdKVFKkmKn+qr;KF0qV429Tto_bjH6Id(dZeL-CSLp zy;dcBe9|*A^sHsROlsQdDc%_yH#`gCz|1OjDumCenlp~Un_k|kwAtr$%_c$+;O;+S zeqx@BnxHLkJk@w>d6`U_N)yWuj^?i@@my9)tI5km>`Q((9-<5u-d{Yoll58ZEOi+H z4$Rn0aE=HJ5m?TooteT=Mh#f30P8=oc6kLGwBH)go8f_$q=c;D?bnOd z7L$excw-)8CGQ2Vnp;|DnM9_86LzK^L!pBxP(*_5rZF3r8X#4WKrm`oc3kS}uIKbD zv}8Y$>d^`t3lm5`6TO;Q<8>FB9hH>ZN}whxo%f_`PD}ngEtHOLV7H(v$CopB_&jj` z8L?P(O4@`FLPH{!ul~*Q?3;3DJ4>WJ(v@Ch0I#vIy?WbF6t?K{;zAkKEjPhXVPR2l z_bS0qCQ&o{`KItJQKpg#5Pcv(y!lAL&dTgPEwNGKw$8u|i6-VC4fAe$d8%^Mv|AhvR70Y8PSDAHtggR6*%n7iD)Q>qa2>8~mqrp-!38U$gpbQEETv zKNhc)2VE(Y81Xt$IBGYDB_zIZT=0JVrh6lCulI3DbO{?UGZ z7ED1%X#ViZk(ooaNOe%Ab>8FhdxLpmJ)EIRSK^oKj2%bt{6f}%+@#(gHB93H1@^Dr zO)OvD)Y`jlp7}E<5f)t4QE$>ESo&Bm3bnxNN=#BC1%FlrB971SCwy~D#AttAW8+v?dI7H~sK0!3pZ~qtww>uk-8H{J91$%o zS57z>+pf)jaKLRsrgBi(@B8Xz_GzR|Fgm4?#xJtG7D+M~xPIXyms z*HOC5>SwYt*Qv{$PQXJSYx6Pk1B82&*}O7S3E-IQiIXty5(J;?OnQ@RIE1L}{7{Eo z@p3Zv6)9NMQR~5GWVXu5-g4-2E5K0tdz-_lG=#F5?pc|cFE-Fo+{#njYX)nF&X(^_ z_;opakDB-6Pk3$;m!~D>WO+-?((u|KlfiG4derJs5O)HX>?c?(h<7g@kpusO1%P~3 zBJv~9^mO?uYdS^j3T*n}Nc?j6OW9ZSv~Qby=r=!Q!Iu{9+TdEZpFJ&7)~hc@b6ja{ zhNp;kiwyeAQ-mTwP}N>+Mxg-Cgx{@qcm6&0FIBTZonI4J^gn3&r)M{Km*~u}mS0}6 zH!lfQ+YK&O)JrPauC86E7R+%K3IgJD+!rNFZ%{P3rKyjZh>`HbYMvv~UEF7q8+#3w zh>Cj>McLk#YL%FvTq+_0B6`-a0ZCX2yU0GL-Ay$SB1LVIq4WvxGx`X>(R6*B`^GFK zJdaj(NdG^A@@FPwphx9A$)m)wu8r(aUrH1rGl0wsZPzP(=4NJ4d&kccV6t)D)l5nM z_8Pp6&bsauh5YE*O$Ye28I#~=I<^kQj}$cCQAGBKEVSI23?a1Mg0Ge{^Hp5?1pQ>U zKdfyLtQ@HcrtVR0HyymWUpB__w=w~SVcL}i|%v@HbV1NTqRxuy~Iui1v zS&4?`YGAtcHrRj_IGeyjCi(+JY4PWl1c6MlDsrio=|f!L;nQuZT!2F^xl~~J1Mhj$ zTaHl!gkFfsM?+5!zrfIsUWN6@K~EU!G}_zUP{~F2U$7I&ct!Nyl^#KONv7#!`(QBb z)-Dtcx^}Y~qyu#Nd(m|`ds0`9qsBrO=i*02Exs7yi{xp$dd>2H=yQh&Hm`HA*x_+t zn@&*aRX`i_FoJw+4aqOt7$hh?qdv8AUbWTNbkB}YfNZW1~$YWh}=g?LRaM32En?B>%Z z63FmmDP}bwp*I_g9GBrRxMv>2VgL8|6eD$FZ7EraZX#NnCzydCyW$ zYAW5+>@1*FL3|zVU4kqjOb5dni78o-`_2`(r2Yduy)YpasX9`~u#i*rVe>J!L?IYZ zV(1@<L!IRh+~OZdDOK2OU?kk z!M)Wk+xHr`i1KOa=NGpL*w$i|BS+k#Ik^-Fi44JPyNgy+DnJ`tko8Kd{Mtl%W2GQ! zZ!fTEBb(>t2Q(j8N>4^vVR;i;<8kb7;@LMlQ3iAF>NRf>?rT)#FCw*|jB`y23!|ZK z7-5+bar4Z+-f9k-ifnp*{pXJYr(YzL#9K(o#J36AcAI zVSg+CJ~OW_#%52;ckzL3yo>x9+};JP3KsxK$`e+Siz;LStNjocz;t0}-#W};aD>E} zVEq|t|MY5P7~2-tHaqgdJjx}yj^+>9f)ll{wD%8TX{P+lIXkX7*{Y(S9;(pJO%~8h zK$Sad7-!Dq8RUwk27H&i*w9!#wokQR@fsOZTsC`@(T;*63CLaX$+Y#otT}q9-@JVO zN~*i32PueSmSky>BJ0F$eCySBQGcHW_pD$>Bobrf;K#iejJR}*w@}jC><~KHUVhEg)q%7} zHSRK-asP_2_?XktobASACZi-e_}q@?ERj#>rYO&sz6j=5Q$4L!QSWl%uwUtk&id#q zpb+erxVsliRuA@#Og zqO!75qeQc(uXn0Uudo`sQCROwagVK|1)Hwm(Lrp_k8+`vE?i#_rO4Gp>5&+T74p|c zX%DAVJlE4~x=9a)3 z-51#@g479Ss@8%uh?X2r``1v#{J9jt!Cb%ggmRumv(??~YVHF5#EK#u7%X0xt)Cy#Vk*UuP7r8N63C^ijb>OE(5SUoCaS zMgq=91S^E6s%LJs%6HF6bK2{buIBzztfT#9Q+M6D7- ztnk*8V|&J3Y>M;Y{hrCCS@B>MbRLId(=SupwB2X7Nhjn;Q-4N`ysW%_3cbJjrjVw? zrQW~`?~hl57_cKNKcQ>kD9=q1KD(6ErY05|yZb@+rF^F&+t+f$+l<>*h4IcjIpqqxXy#>z;h|zLO@=tZ(dS@gWfc`gOf)9uC&r`_-z~?_S5f1firilNHmCa^dq_KmgO`Lh zYq&)U;~am!Ej-eBYXuFXFnlp>b@yx3a4yh6`(iI)Lzs#%n6g)%LOY}J9B$=`iKakK zMTh>Q2UH&b@`GRB5&=>>3x3<(se2_wt2g!3T8<)#pPp!#ADuXQq)-|mMsWMMS*trn z3FupueK+nryB#4g-V{+rneUdop;FsW;wbru+c2&LEPHfIzC$j zWVht^c*(;)(bRNz+O2(Tc{*qKnoZ~ZjEj-`g+lR8+YePQ{bFdiMNNIVAqD_Na2G3S ze6v;W?bo?2UmQgVYNBakj$b+1fDR33^4{)!B$&KO#e|oh9JiW`R_cBD)+63-MfwU^OW_=a^ z&BcG9hS{dcWV^wtn1n&VCKJboqRr{qcOzVC(Z#N=^*>ma78X0_H&Ift0sD3#pOs}X za>bu2uLPsNOgir14z047PePYqR2Lqt`(Xv9dQ2nhc%5k9#v@EZIX!B1?ZaGYL-CM- z@A@Ybw$uR7JM;IXXGbbU8|m!c60cA(AK{ITN)+VkEQ3(!{U5B|^PAcXE#L|rd@-9G zW2xYst(uJ=jt^jVJWdPqei@2xjKN|)J3rViYHiiKUa6ZbN7 zY*`APl4a9`^}iJU9-P*P3kNADJgdjcn5fNw0A7PwxPq?%aUh64ye+xZD4^6X9>|jj zRj@;y?VO}9s#FL?qMb=mYb(g}IE$aDaLkFa`WK{i+o*IRFDwZmh6>0cVc@>(p6Rru zRkskUW6T#1LRJdOO$z$jje=?{J2meI zGz13c0CZ0t)ei-)6VuF)067UCEeI2JSjprM7ZT9>_5(=S#h#_PAPL_j@iE09!XPxM z08^=fO8&!~M9^(L3O)C`88WoEI}O1wT7ELTPSO++5r3i0}XG=B+#^T!J!K6{)l0to6P+_Xf9bd zN9kzStNH+fhaX?l53&AD(!H<7+eWE>Jrqr7c1)pzIqp9o*Z*94a7p_wa4?=vlgwy# zyY{5NIL7_^srYE`ZX(@!#p0Cgzso~-#Y7Rfhk@Nh96k~l8rc60Eq=V)*ySHwn?QXe3zkQp-&uJ3VKDu#+>bS_^Ya~s;;HiQW>ukj;8Ep)tH-u#*(GL*}oxLmS5{UBr|D|B`HT&)Hsh$fe_?eqM` z^S8v<2FX`dS+Og>fkXd3s><{@dxE7Lj$ciJ_m@4J24bH19FddSPrmR{|eZug_Z=&c#;qtvflC?Af17`Tq$T`oZip12e!-8%gM_>3EJ2oPh~gS8P7w{ zPr?g_mHwXu7Qd!Ru79C9WUk62ldo#>=+9A$)K!0GqQ&sduxh&(_0Oaaa=)xqybtY0 z%O#t6D;Z<`*dCGa$YVB}a=JGsQ$->73gG%_uO@Fq0OK{7+vYC^!qT_w{geD0B%ZXI z^&lkSWnVT|{!-n5KO5x-g;lH9$;6-c=<=4_fOgqT*+Tu`=IQaV?)dol8DA~8`)78 zyuNsjEwRm{8unwL#~{drq)d0|%?#o5u{gX>s)?V;i?&Q(t$I-b{G&aLugg`srVsW! zjoN&djnRNcrPglxwnpMn!^SLImelT@$(TeJKx zGvP*cqRI`PAR9ZK=UYaY9UQ?XYTycl;=3x%I&hBl)D)BWU!pRo1!cgU8GgT`^gvG^RW_?Ah{Mi#AXqXcI073y?9?v~xmtMZL zxM222*P|5V&D6P=cAS7MQ|N0U0hx%?r7~YcQ-T>sBG&nTba3sr`d+%YxR9jiw3}pU?pao)Gv$YcNj@_H82g<08?gV; zO4)C7vFNmkviYibA$GZ2x+ELv7SvbghK*Xv+G*%0fC^`9`t)+EUC(NrP-pL1ocgRJ zPj}h{?5Lf(ElKCYyDh3Yj}EMn*6*FRLNiBAY0m9q$l^&$3D}8EuY0@%QQ7>KzMqR7 zG<-Ar*

mzHs4JkN{fU{)XCYF4Bi<|C{cyCRgM72V`Z7?cJ&sgqXS*xg9Ma_xfu6 znZVGi=>1E2ehh)X)StPLzFUC~%vVWo8=f@1x%J}r=Ap~eV+ofLEz!oe%k9bOdG?bP zT4|l>{w9!m{{;uB+WliYTgpW-kZa$CJ5_Gp{O!jtiwp(s@!Dm&rUPvaR(s_}Nq@|m z(dB|6Id_}Q%WAFUp1Y7~J|U!L=)OGDwcvpI_F%TGG4=JsAhq6Q8I)4+aE^o2 z$mzD%z;=rJp4>}T{<4C4q1jc^XSMSA3uv$~KKfb7Q7@3tB#^&&Azvh@0*W1 zjw;!afp81o$OTTStKE52R(Mm^jr+528=1@Jw*|>DkP`5d)ht{QCgDC60CTL$OgbxL zVQ{*HB;4G}>iJ7{#AOc}Hn}Pw5e#ccKV+RUEbla+aU3%8C#`2eq_0oj7WkS+9 z`u-={vZ?(|`O!Mu7v)fQs8G?-S4K(_muI@zDB=opd}=PWW!b)O)dxr?z?8G?0iWLT z-CTQts;{y0o)s_GdlHm=<6IJHHM>o5Z(7mPm6Y<`7xZI-&T{BJ?I2!k`wm8vy5*Sb zo3R%dq8Aoo9F1n3fyqIg(Nh`?sP_`iaTwN(vwikXjT84!% z;q==~v^7C(8tea}%k}#O00G~ZR!mo#)H0wXAZFxXfvo|}m03A)l}-KHlmHNVRRbEm zPfOSBK=*a=j5}=qXmd$9%POS+@Sodn9=ZWQdZ6>s&e|8zS3hT*z+z_lh%K`bLW7ax7@bWRw+=Ao3oA3Sv03WW&uTvb zn8OB*Ih3=}k&`MZ=pp~OEas86EnVj1LGuqW#ra%%Bj+g6Sk97%1cy&kU605bngpF` zt)_@WCd9b7c*N2080CLG0>CeI-EAU<0NOm8Pl1{37RyFDoCp4tH#-IlGmi~^5`Lwr z;0mQSEBUCnxEV@*XErE_fgVzCGo+g4C5`wW*yf86VPRUXH_DQ-Ga+~`%8yoC!(}8W zLl-BMkf;a?t4JPMl~-BTlL}g@-v9ZPX~~R0Wbb=aPk6L9fF@o%KDZM1ryJ#Kr=GOu zp-8fymQlCdrZHMpSY8LQ<>K2QBmK1bD)YH-89vnfli_n}d`XIKVAid7d#A5hmn?2^ zwCf5nqu^2A3rdHWGE6)IVhWmD#FX@60W2Dh{!T6i0yB5DZxo3LS9jbqy= zs;zVjokwq$JU^{JWUkKqVu^MmA*bjyuEQkPb_B}MR(|i>Pbp)s>1Ea_C^+YjeMBoo z=q52N5^dRzc7rKz!TIK!r0>{Zj8D=8m`~#3FZo^e<(sNJUMISr;~b?D7SO9&NbL1T zFKB^>N*5YF)mWa}?l>v`tr^ZtI;<&cck(CFkG+1!Nyr^1t$VBmYs?pM$sFQg9stHG zlOWYciFUXz7SVZr(A-M0O2=JzS7qrNS814yZmiuaDVOw_s{kDRF(99Yt>o0{ULnS1 z!Lvg~`-gDSS=}~vbK-&YtH*vt6E8Q#GiXikyQ{SY9SZ%^=gy|e6)LzD{G&5578O_GtnUnY6Cd@ovVJT zp}~9iZ$J0+G!aPufj+#-2|-85vf@nZw^^LoknQvW97`i;F%|xM`;mFl^$4#sW54#) zoU%gqWNVr;N6km6lyu25GQK)2RHz41kiqcqpQa(X4FPyS$4r^tyDb%e|N31uZUK8g zRk#llJ`mmW9!=n}ur}ByjmB58#5ohKoTMYMMzxDdd}PjfShe&bFkHj%R-=1!sm1=a z;XA>nL8O44j^FoMUE0K;#xYf&KC>i2y2X}6TO@GxrF10Ql(Y-a!6~KM2kkjelDeFB zd^RYXYMooTp!9Ymo)~5cCFxv|Szp8KY-J?};Pq)GT5~jgwnbpmTbAknb_>PAh3U37 zV*7PFq>!VK`UFs> zIH&l>s-L`kbXb0Z^t@&313=m{-KT_)eZA|X%d~dODQ2k-*M_`ayipz?_f#2?&I~sk z$JwiX(DJ^hTb+R$0cEcMMzYG|Lb{)^Bn&X2#;w1hu&PsyR96vW)be8KpyY}wt^${` z^+#t41Ri^7!#Vhhc)6ENecw|}{49d?bdkSp@cj5YpL1CxPzM(e6Nq7>XF_zOhm-{5 z+LK2#%9WwcdGGot(ALG!`NO_#7V>0Cw@eKumi@kuNbt8=rtxkSXZ5@s&PHiW4~PEb zc@mUh`{Jw1&RyC3NY`{ex1304%j#WGYaep@%{Sx_VXn3mPdfvUSs%zwbSn2<5GE#9 z6cDPCnzVYLd&MSFY58J7lygve6bfcURz?E)KkLCS z0n1NBIFnB6eKGT)&7LTjNvFVAgY&DCA!Lfa6XAau-+brwUWFy!if`O}wlk%Rmoal7 z$E9IZIp@Q_0^HGG-;s6OW_xlk5}E@KKST|K!3vfm&E6mqbF#29ym^EU--yZ3!H8Q!VUe1lo@k~TEN%%-h z#@6Nm!=m)Q^1=f~qBlcqCI5xsKe3LiPNi{hS5i(O!h5Dv2RL4hp!PUgYQ?w5Ym`C- zDLLr6;{)3HR^r ze~FT4DnbGP<;SC&UDB$jWx$W)7`t(hZKQ1-TW5qN+N^Bq6ep|*zA9#HI z4SE|VV$4dpK;I%}(x2&Fvq0xwx`oY{BVaMPNIj7eACO;n*%fHNp)!+kH?*HDU~feJ zeLE6`FgK9cOyymGhg3)b>mBlE((tNV;bNov-i$$`%jVWd27pION=i1*k5rSMjqyxHD?Zu4u)Jebqv%{z(HPox-;KDb0}*$tfa~ z2G=lAA8|$fqMvw?-@CDYWXOPZ{d7|CNI-9Yvfe=eZ1Mp^LnurZ%Mi&*k;462UsK|X zdbt}M2k(gfpQuOKg5+6vEIFT)q-5*;#e#!_!`j*6;^JePq1>RkUOJviHoqFpcN?E| zv?)=E=HUjhT;2?#pbD$vmB7uze5dxNqqC8D`~+6no?E1~pN;-EmeSwoomZ?U3L|AZg8adonu@zx$c!2B`k?6veZNL)rn zX1UGZw$yc#MG*?0WQWM(Uw#Qipy(P)g^j)Uo&8ZXY)ykfbH?aYi}!ab<|e}1?=Po0 z7P2}!@(*eMNepMRee3T202q@<(K1mAgyNY#r2o~&k3pkal!VvmoH=dtqHU1oXHt|J zW4>m|v`yVS-_LPtVPRo&uJ8Qu4YabK9)UE5hE#pdol&9Rk;E$?k660sgWuCOj*gCX zx(Ah{ovLq!9&ZrE+YKF3E}8fNj>uFOg# zXJV2&VE%2uoH;qlLZ`~23iX!hLP4NZeYW*4lXz75v`Z=a4&q}D3J5abm$^N zX}_}TGfu>UNxXo*QD<(Im^@Bl1jl%z<0!12KMUp^w;mN8eeU!BsCw(5IJ$0ocz__m zgS!QHcPF@e@Gu0o;1ZnR?iL&d3+^5QgA?2}xD(vr>*u|{`#$&Unm@XVVhZ}4v-jF- zt-ae7lKjooftM&t8T45JQxbT@AE^F#b=A~Nh>p6+UA;jMBtlKP-EVnhFB3*g_NtkYA(d&+q6WO_`FFZ~F+p!+qGRbU{Z8 zsahJRIMr}+T=tNP*2$+n!tn_A#R%Eg;b#SB+I8bOEuREyfiQ17TBO0kjI6fZ#W#;D zeql(qIO}eA-+#8!-RRY@$JOBFzkwtgJf{_`a~{JB<)=Gdd!ckb-z*F7~(yXAUI zZ`nR(f)EK(Sg%d@5c3G~Jfx-ghFm4wU(n>kFE5(^ka?3~zeKiW_+aAx@imCPtlAA5VAt9CnF_rs7CG2quP$uKJoyWgU?ZuB=e ziH46pD}m2cYFH-#?5mPaZ#+)UvW3#b*hTkcP3(P-ZomL|w++$XEIDGo2E0q~I;#)VXmu;Wg<}B}^pR zSUK_5R5-Kn{k3_BTz zd4xNxX(s)RxtDF{zqBwg2WG`kfv$pop2S;4wbr-bqQ7nN#USN$bwYT=N7wzqA6syxUN;Z?K|^Zkg6A&qT6vQT2aEmy|=eTk-nqYRG>}A|Z#cE7AwxMiypA*+3W6 z?dBOxaT27?_Ine`B+EU11-+YUyx4Er zkEi@jZseN@?vS%_>Ww%)HIhU0>?ZQLKN?p5T@ncQ&_l7yb$b!}x<|+=oxrm(Es{^S z@&>cOGczE+Adqceq@2k)Omrs9{PB zeF-F{4Ldy>Fh%FlUKQ!3X*tTdMf`oGrF%$}yVvEmo1Bg*^?mjWKS_)X$E&BjygYA~ za z!CUAiT#9H)m(UcoBHPSS(^p)LC~i!BI{w*BO!jOMni{;l7~^T|d>=N{UiSa@sh9P7 zU0+wpXv78eXD<+ds)RbXwsq5{p+*`DyQ$;k*@Ep?E5yH-=FfDP>#kzY4BS-Wpgtc6=(QT$<6-|xZkfM-#L zh#>@`KvSziqE3N{iESE;*{%$$-w{irsGuO3AD^Q*A25p$EYbE(Qw|XpCi%Cgx2fJg z7a*HL2+_kh-i1{iMSLiztDCB0uAYygY%{K&XOF(PxcI~#&e8hk3&F`3b^>nH_n1g` zK3$24iQ*IiVImJcqDJ$Iii%FIf#M*Zs`0(vc$?#n^)rk&u%V_OQ-Ng^uW4w*Y>3s# z4wZ?J{jz3-Zmm;Ga09cR_=rcBn}dQR#68nS?=u^3?-rsKR)%|si>A;fy`qqylQ|8W zG{@yT*>@InSN5^;u$iD^VFKB)wHm;UuM1=+4Wqu=wYaDBAaa-ax3vDqCXCeuQYf#4>S1@oqh@(&2%*O zeQ9K?;F8w;zIJziED%-hVcVzMKv@GXOxV4DtuvW5)xI>eB_B;AcVMWO7#6-vZR>Ca6+)F{F3k(y|= zz-y(Cjm2gqDPE<8yG<;JtBqa&mx84n5N|1^KozLMo}rYeSWG;m7u60wa{@f*%uFIw zJoGoP2d;u7=q1zEBq)cUW?IU$hL5fx|7bb5NN>I*fmWRuQ!XB#LGdajz=GS@+H$-Q zIW{n(c;K@);L$kqlc-Q*9k>!Dy|-;u!XfxUiXN6URAik=KQVp4t#GeKzkPY1I8?NL zHt^T}2Q>kzf`BP?XO>FI^-~{FsA-V~L&Kj<-iQpThR!xjTcrXWLxI#pZW-T7l*#GM z5}aG*Lmk6!n_#?IE(f}B0r8(+J6kQxI}<8p6<2VuPA*8!wX@$oj~?(mD+F{|fi0&F zTsbqYygM_L5OQ&1@%=RdetKLS*^YhjPyFerzv|8+%5GY zx(t4J{u8ZkNxI1UapTOc-hFMos&h=}pmJ@@cbV;e*r3UN&sJw&CG?&R++L|uuNsip zw>Vtf1>XZF$?BtxW!dD6HvQR>Gs9IdCMepq)f1(at5$%KO@Ncmoc67#lVLm?GIYM6 z#w8Qe$%2^@KP+`5n+l<~ppdRr^)RW*vvchO73C~jlcFyzT@<-=p?chariKPq6qKFZ zi5c(m@tHpMeF75bO>ob{gLg92Dg#)QF)w@j%7Lwj4^;HkM~8+I8e|LJ=1;h;y>ALh*qE_&^PPgt(>|m!WsnX%0b`PXZ?WrROKY>+FZd{< z{7v~nf7JQCdroTnVOLrDcH_HDLH*i-@PU-zb;A|-d>iZX>>Ia#4GwVHcYbq({4SEPV=O@3k`RtLN#>etxc z?|PHe#Wk&1KzTL4E$Tx}Cs03yG&VNQ5MHHIe4hI0RnLrq#uwDoua_Mw;!TF_5A2c<8RbiaRxPfUNHrTx2nwbvujqRQE*^W9 z39JI8u?0aWY1Gk*dqxBb84et4r78z@GeH>(t3|otQ@Bq8}WZCRNeor{Yw7T>?JeZc=CMkPnwCF&Uimrz-XIZlB2K1nyRgBA_&uA z+HpT+{<+Mt7?Gm$r7-Nw=dX#0qg+t6&pNh4rXWO>@U?OLsp*(~o<5&il@4mHpeOp1 zwTBfK5|z#>fQghRCe0V~t|b#<%8AT)cKZlq(2?Qc!=oc8l1W1W`00nx=baCv8257q zPjXY!p9PAY0yk87DD6^7s6xdGrN=&VrhkGt5k~g5kyaWC(#{WqZdeTtsR`o0%S9J? zj}z|Z=9X$cJ3C8*6`@A|p@2NfREe9{NMAowj=F~KBW<=yltj-a?1XbGg&L+oYDk&n zM9Ee#7b;xRcX8H3!t6$Ky>m~J7%n1Jqxs27I8dqt8d1at_IJEce9Z+mL07wM2<)ZZ z2K6T*>>t>=@U$53>OpW4-=6}pxQiQuBWN&U``aI9I%bFJ*W`QJ={TCeGPFl7$( z=_b)CAFi}srgNBO@_CFbJFOm&`Y)0o1_Z2&{rx$$h2V;KcM~;x4VtLd+zIauN-{Az z^>ld(BXq2qZ;$K#J0TMSo0%jg;xdaH=Xl_|)-q(&OS~(3dArQ2XDRwPk6qrBRi?F( zSKpuA9#?C6KRutZ+A|>!_fJXP8q>O^q_pMjC{@0YH5Guh}`d~E?9DL z$=t-RyK##q={G+`x*^|d2x3mxpVU;gbq{b7%h{^m2vb%pxy$Vk;awOy5(!xgd=j{#$=01iWj`NGr1xncuict#-#d ztF$U!tmvUWXDuv`aj6$2(UN{BG4D3|k}&j{o|ljgrsQ3TVA7DnHZoBX7nOMh1q2QBkCX1O70-ZgL?hTMeH~ zPyp5Pu(=IhZv%tiNBy;_OI$vd{rkk?;%ms;p5HTq@Fj}2sLn7idE4E1x*;tMR#1hg z7>M-6(k3p8n7*O1A6076d@|m5LAF`>h)U@0m%$d#kH-H3k9J9Ob8~u}OfmnL8q;2g zYVIjjHC=aGhkgC0Zk3b+yWQYo^#I597Yi4vVz{4sVs>8EDl5gf_3k_4*Ao}*mI@^iRbM?4fpUNkXnKH{3e}Qp5HCf%^GsNOA6{2*IMc z7}d!s|6G6GMJ0CW|ZS>LSZ-vChQB#cla25x5*`y74YH zxel&9Yy<&2c;W`Zyn2osEqGcUa~dXxU%KToaLGvNH!F+hxx_R$UPDYVst;>wFuY!Z zDT6jcKYtl2ZPi{%EuaElN>)3biHWDoGvSWpW?++DrIv{U!t74eXaqCjCe9SqSo3iH zHllB+@8)-vZ6Sm6q#%GcDM}uXPM-P1b+&cyUK~i^#GxyTMU@TFtwlzax-4 z;KxEG$S^2Mpoyyvg6hFNe}SDMCS#LaTs8w$2J4uW)`H$vtNYt# z>Zq#+664b6aWI9O5_~k^CV~>OqrOj3@De8bffvGnAZiBU0e!C5>s}{E51T${0O}r9 zj&!0p%d2}IU}G&;{`m2ux_bUX)34BY{$l)7pA02k9c8lwc;_N?iwLjYM=pzGN&({C zcV~5eAE}z#X8AT^#Cj(Hla?*iS`%$kCDe1Spk=#HRFOOoTtG91b`M#`xoE9m()$i$ zU=&MCjMJtf)hp;kxOGePf6%i8vvCK1ih^=Fd;X^!TTnWu?UA}s)>ECpS{LI=7bCNu z>wjumZE~TX=f= zNgyahLBX{IWLIH5lRcl4-*a$qTT0TUkQ+OchI_`t`k!aW%fOh&HRY*BdtQSV4HnppJ+K zga%ClJGKiaxY{Z7KwNHSqBMA9WQ2*4ksTk=+a`B>zEr&sD4c=oKdgID4@LQ3HTrMw zrqjoXF4Z1=x&YP*Jq!R{y?@vRojSt%SB|c|JJ;&!IF+Z>KBuLof-@b3Lu(5PV8a3| zr5~RCR)&BLm)=XH`qUeO6E|QzNUd#sV}+o`n$!R#1WGUhtk{J4H)C|$=)~05%;g4k zwHh|~gYq_Qk|^>kPWek}TMEX+ZxC5nRhI6YE`DniZib>Ey_?>Qju0t=XKs>ve%HuT z`PslEPBXIE?7NT~Fzo@?GU9(3jZjnfNQq#C&Z{X!sFiKe_)840gJK7_6 z=j>Ke_v`%&VLcFpa=kxGd%qO2`IEaLhcqco!~W$tYpQA*OL+|Q<(Q3)f zz8|)7Cx%xg<9@tSq=MQH+$IwflseeWG1MqcB1O1Q4`+_e_OINn z-fO?~RUc1To>jQu0Ao_O^*lCf*GXC0%M=&KS%_XY#7L2AG{;hQ)Qu{EVn~{Cf*lnn z$mRwPc{bTD4F^%7RYFcEvdnMNE5aRXtdSm1LQa4RnO~t#sj?7S=q^o1&nTwGiSoX5 zuaA0?Am8q72FC|6`p_~B%NlWZf*%zXh4R?fRNmqZe*Corc-bl?#oJ`yIt#mzqw7sv z?vXn-TD0ow>RVuOli!n|%NDAChf%_?*VCcL`SrrJ3<6s;eER ziU6iE!d&mbwXLY=P25)RF=nbcO_IFQb71Rl4pIToH_3cC>L41pzyNc-^xD3&TQe~y zB9;*V%y5J}t>&xI<3-KR%;aIf_bdRDLyY*}63jA**lJ9@Q7Q8}j>rX<_>@%#~ zCl{yo#p5@w@GP;qQyLb?d$F=nI(xKu3Y89_m#CDbSn*S@cg(RkNkSSHlfBpqPvp0 zT?(L7d)`D|>Yx*gmVT}HAKKJ=)?Q@raYWja?dyF4zUH%FvUJzuo|uKh zvgI}~R}6IEi|zm)C-!>Rok=!N)tV34nH*?dOo{L?@=&#zQLju?T=V?9 z=*AMZ&Yzcn?%WkmvfET`;@{mi3-g$Ka4p8N6dzhQtd?)Lfm&a(c-{-Az!BKSo;3zm zW0BE}9KeWFP#np=kiC`*LWQS7qAaDS8VXY=5sk#lI-L22X^qLrIAOHUH)I&)RF)Z! zB8koEIDtD%$kJcB*{xN%ko1Y2Aa0enK3!8&8p8dU zB{;sUw4Z-Y7EfCz*QEc*P%*jk6i#319VV3oemA&>!a}F#0)RFdF`m@4p#o-7p6w9p z^g6f^>ZBo8!IR5-V48|qZ92fwHh&ZaU|Tun58(v4ynKWJHTq;ZYSi9vC|IA>oEOx$ z<>b1+%RYgh!glXUQP;9LLN zaI~3>NGN9NR1>_i7N6zWzr~cyv9_P+v&jrCASZ@){9TaOe*&XXJQ)YFP6^^Pf3`Z3 zG-}>1gr3z~6_lwHy+e!dLei?ddH9 zJqa-Ha6fC|+S;k#zMCYzCV%WJG|KUI?mrH5@a2F9bzP()UJ=(gMxc8qy=N5x2JD!0 z+@AL$DxI#MKRrSaPQPvxFAoTt5^1lhw!HiqQL#IP0g22sS;py*cR61+j>GO3+doFP zcwLkhW_f`!bNNj-tCPt67Jtd7{jV3m`3V;TCVB>j5(WV#UVO(xlweE~jILNC|Hcud&6;1tKT+uclpZ_DWX zua5IM^9%qp(Ihos@~~yEy6W=0yx}OiaX~iF@GeZxYbFN660&-E7tHs>l%L|pe;m|a zO}5B$oM=XEaC;f#FY11lNe_CH>G8UCR~wx5H8N8pbkSwooGjow698=dy4TrJQ4gf^ z^>lU9lxPoBIChi4VgS`>Ey1j#ufNpdWTu1{s22?v2r{?npQf1fm#55)&#lh;#|4zh zEuqJ7C}+eUhyG?jmS;kC8q@|;yLmnvKGr4>0h||?zRcRakk-|PT(uZJ2yxESnq)Gs^*W@AnY3@;I;0<~3 zre+z=gURTsL~BW{BPgIP<409`<|2DE5LnB^05!cdy7Fm@hKB~1^Wo|VsjBNGa9HoH|*IeW{^xkzyOX9Lpt!~Bsd5cTRJeJJS0eS^2o$o%@bR_ z^lo-UB{)3}awrj39E+wLeuT2087)p`2eb0;UvANsO$7*8a+|W-2D7j{hZ5U)j`<1wkoc7KxzL)1#?j0oq0CMjrkQD9h?fFTn%E~yDxp0up zIWqvEVze?)UYgyd!IWUZ1(my>z-F}d&$Typ#0M`gfo(|-V7cLC&44lZ5|7V*sMdf= zL;#MCPe08ti>9sV}~VmrW2f!)b6dahB0X65;%Aa%EnLH3m3zQ z$K&-?a4a6QJvU(XO(?_IEbnh%*~DKN7TZex7n}i$;f`W_otP>_%$}m4o@lEiM3GvX z+}Hkzt_~3Q8FiJX*%vu>D0Ft**a?`Kn0hY})I%N4isz%2^p(H?%AYW#ZRM#jo+&!< zvfKC1m|-{^BTCtzg+x$Sde=EBB!R~Bk0W(;b)Lept(@#}vJ{x&JvMrH$UDHkR=SOD zBJ#DRO86O#2KW>RP{Ho+upmH+x2h%PvH6xE_4feKZbnZNRZ7r$#orohXaoTawe=Ie zB?S)hAE}!V-;c}|1PHW{pE!R2{l)|KOC$jKPZPo!Dr;GkLRI1zGL$0k`D&K`vG)MXda*_f z5sv~j)>Lckb{?fapJZ~420EJIS8$GP-K?k46Vll)yqUx*_7iW2B#CW#% zeCSMBIw95xUBTSC@j~<(E9mc{0`u-DO$?%F4p@BQnau%K^S|dHeKlOiX+{4ANf-IkajLEoTs@tEIG8P z6a+gGHr=%+5hNQJwh`4d4H*}uCgWj2GUA1D#YaF^F3y=hiuphVz&`at8BeY3^|LrA z_#^IarOY@A2;hvY?0{NgY3~D7U>G^@lnP)Wmv1K#=4NMM!~qrC8Y4uq#Xn#%3@Ci) zaq5^+Sh&3HM>S#&pj+qsbD?o;Sz`~+FIL<(dOFtD45IMJe1IU4AXfxLO@N4PrvIYg z)Jp*@?uG5u0bm)yi!u#qFu(*v+d@}BKJxCIw8C-o0yY7^)Aw;JZhc){U0|VGe^1W* zQ_D>K1>$iObixFfK}xX7x@2iLxOZu4Igt*)T|fnp-hbdwA;<7U4eM>#0lw4v@GstS zh(d+_szQDv;;-27mfS!L^x!gUr%1^Ryexvqs<%!%nX7NZGUF}3cfrosD`2y&syySr zpN3Y`f#gawBcU_cM70tmp&`pO6-Y%@nQjeI=Dap^$l!kC<|p)AK>zX0rtFU zqbEO^v=s2KM;C>z2n2q{0Jb=k8|O1Bv=E0ORmX?bpvmqXADI=Ijg5`f5~Uc!H!ZkW zt;l;^56&-Dz(&W*!=?aMQ7{__eEFkXo__B|)qGa|eBmdHLk#Zm6n1!9y9c0rfbQV; zqQ>gMs~t}d4Tx#iV(Ai1raY7I8wz1 z6?9YjKO$y9LSzkyuIzs;LRvgKvb$>jn`!>JsW(_Ktr~);yOsl7M>77TRq`ksrGnC+ zw0HSrAxK;xnFc=;Ey6)CLrI3}9qQ8TH{tH|{l&9e+k0SW30e$PZAje@Ln{L~3S9bm z$bISN4W0nymQG0o@)0HP>aQ{HWoQ3MSV`_jEwiEDiZhFot-zr0_dQXb7D5)6OFS#i zUW_Pw&t%0bRbriM&u|=bsE-pvXM8*)`-lFLHY}%igtWz6ZwN=Rwl_7+xlMBX_tB27 zQ6xr>>fKn6H;GgXXFkvQni5#(CXDeQ>Ahng;|K*6@<5g+=pfSvO0-h31Y%h4 zVFN)jzktDloGK;LL!Yq<9iW-#a^egn?i84%rKR*NEX6bZo(a)h7E|Jld)M9^7@Ukv zT8tqKasMGspyJjnX^urrO{s6l1?&2gEsN5khuzIV8wqPG=((i~i zmd|g*ZJfBoZ3OniSVFDIHg;a2?vm%0dVz`4;#yPLfz}@Vnk-x3_-=1gT#EaDLc-TX zHoqMI<2shemQvcsUx;D{<^jf*Zg$(TS}_i%_M!D4~R0fUw+QhL)rTY8=ct+fLaO6 zXn+PTot%J+x&{z1b%0A(x7lvd85r~JDV+Ba z^++N^~b!?6hX{R7A9*B47q_T9jjPQ6>zcr%Ncn!y%ILZB9HIjmawC z{OrX8XWOdGl=!w+T;=88vdSexuYwU)ylcO4lj5v0S8=1d_ZNr5Ea{wDzB$y)Q&EVM zAK6iDc3!M4ex`Ps4!6khqo+_wOH~|I9*=_P;$IB@D{YKALWxnIAfUO10h=XtMNt6NGXnA#36f04gjYr#P&N_vfFVkVMq3rFWvFWyhd|>*_$+AD^9-Hw<&SI+f)n(_IZMgMU0g z^t`Fxi2`e@rcU+;u_F5VV~DvjMlW_oCOI{~aD&1LHf)^R=EA@3t zelBNMYH|+(oL>jT=HR_|#oEr4RISmuvGwh*rX-ujL)odAO%|1}Z(TzYYs14Y-^XT7 zxNPhq8%;W&PlBsZk)Qi*oVH}KVT+FdS#^{w9RkRnX4*LOsI5li96vLjTGCStj#=P8 zR3t%m9JQ=|1(q(5ugvHBl}}|b;x~3dtUbxfxZPC7|Km*lAD|KW`G0IF?Ha-6dTeZ- zJDF(%-zP2aIxSa>T6~`NGH%y|cOv*i4b*LejMu8>Cwr?qEvNpvw@*ccewt(P*?h1) z_4%`f+lc2$bn+-ld758fLyg>2PXCALxcxUc0*Y`2XFvkpmvwAHZ)Hq%&aYDX9kyXBjIlD*lbu zR36-ta8t z;AvO#MIm1Q-#R8e8@xY}UnmnpB;ZU!kDVN3jAHzuKu*OLae&(2oE_@c|C| zoCbcZ+5U4K?1mr zE32y38mxg3l?8NrHM^fI%?kKEU(fRZjXK7i-oS)^;ARmRfB*m=AeIGHG+s!Z)g2xt_#i(vZ`T?F-U$iK{x|=jN{!}-eC-Q=cey)e`?FJZ)c0aZx8L2y?6yDhup zkW{E17Gnk)P^>d|?cE3UJjPdp=9Yi>*=nUJbVIB&OXP3=c=$Gr33OY47Y$qh8A$Bn z%0BJ8)9_G9?$=q;xD}!AZM6@lIRFyiJ_(Rl)QrF1Da$7v5y^yDzodr6dS40UGkMXN znHa7~+H&n4on&Aiu94YUiI9Cvff=+*7dbD28|G1-?uZeL@pN!Q;OrLVX{l{qg_6&N z*Fl#A9}g2So>wlL;89Gvj}9+Gvqd)x&g1+pp1XfDz2071zSuiyko9Bui#2^%zrFCN z5J;h~e_TvpDFP^CRkaUhA&88C6B9M9s-hwZRt!d5BnACVGd+VHGvE*2JZ~}A0~~kL z*0X;U6lR8L;1Xc{j5foekl6t9*=@YnvZeTwlctyXIp+2mNGkrig5(O6r$UpuOAWVM zu=eo8X1_tvaz&lknXxcdeT7Z^4EJlJrjhf2&id9%FF5!PUC7*f`$kh-prxTH66)0 zIsaB(kwuDWtVeT|S=`ndd%v>>q6w!vye_F6pZ3GzN;;nTatA!l!oTV#H`Dt_eeRi& z)%8aA_nvw?hFm-!?*H|XBTUs$Y` zWQCwdV7cF)38nq!OIv31O2wP%a}LKBSt2pMUEteEdM z)bY_|rPENfwRUk3-!fKY0>rXV5R4(55|$%$kfCV6b8i25cs{9XB>cnv)sc?u^Fp$r zl^Buj^6`jjx7$lz`?}A?Uq~6xNE6vY9}4IbjNI?O@|TUA0|Vk*k>}yykbN7~*$o57 z)8{MmX^8LFRXE?l3(L7K?{f}aR^ih!_*=5|Z4akA>Pzx|bQdFSZRvN}`{inOFh79< z3zQZgEW>hs>lhRY^)8onq@wKi1C6HC*$#B634(Mo*aq$yG~(|Tn}QpX7c8|oq8f4a zQl_QL7$d+R${8nS32Sf{r%G(dzxOkB;t8qwjHASkK)u^-ZEu_0YjxXW?YCP-!vDhW zyv;Weo-mNN(QM%k(Xy2!a`>S#~ z2dztrw0K6=AH+pF@|vw%RT`+r_H7R^MTUG3Xm zUz(IXmyQ1ZLWxo#cGHU+7D5->+Z?HC*}lqAW-yIZZ}gvcSf#IYmETK}bp_^JzaY}Q z+&>Z4%eN3(rDQTMvB^+5hfyjtqqChOADUc`hkL;rRxlKa^IIFROk zUPSpTnibluZ)eBa;WQEmR7bqt`f$NzBDAqKo-5Yexo*!(2+6nOo6m$aT1^Jo@hma{ z)rS-;qs6T7(xHmcJRD$a!2|^W*+4zx&9H6UfK+CdLz*Dnq5jZz5S2ERxVYU8zG|dI zrNzotk^i;klW-$rNH#LRHoc8UV~x!oR6*;R1y?Pk>#EF~H1h8fIBg{=!rUDygg>1s zq{GT`&3f~p9Q%8H*#!2xNqBm3;!a*a%Skp(cRK}L<;H~kex^WRYEvzbveZHJpV^NT z0PSku5J!U$YPK^|1+n()79)x|O}+p3Jij3R<5B=RTK;hc-t{c{fJv1(O4qO-xi6&*ni;sOOf9LQOk4BBV4&zR{yq_8tQFOISq|7k`n<0H~M$b=!6evYvZm$BMY<8H$k#kE?wCS%!7$*~%_VFGx5 zb-rS9SbE8F8QgxF$+L%zRE*~_mnbCSdtgf=DyuFf#k#FG5;xgDPoH;WpS;RMc>gABO~CJU>Oo*jwaZyApVc}r)i*Tmi0kQ)I7h5- zc@TwF^rhuiHEpCQb&YF#X8CZu>$VIr){1!HX^zI9z%jxXt72M2@N*(zaaIn5?&*0s zrqDRcecebi^tz?^tZ00#`y8{KoAxDDM9}k37DlSfxV;kb_f^CFRz)39IhvcdHY zzwMW?`f5X;`=QGmp>}&X)%ni^9`5N!OG`_3=)x(iNkbc^PUoKA9n>mIX{i^WM_|7- zfc}|cNsv<`DaARAQeR`eP{e|ivo>olXuur6FEH#e?)%`7)8sXX1C^CmPU(#)9@S3K-Ycvs`L#wg9}VpwS{X zZ%Wf-S}HWo-(sJpcU<7ppvbMi+x2wVa;a_QMfzlkE~?i{o4?`Zq}!@XSyg@3T8`(X z&w~Fi=xQ*?8U!+1cgcBroH%;O=DcXZW9e?$qj$3)ut-}pt>Uv=09q8}jiWdwRVIIc zk821rY%^(h2?AHV;y`&v-pqK|jXZPJhq|?ljp}qoppS$2{_sZipWBS|-zhE$js?Y( z*RE-V6_?diN*p(}W2UuHyRXS_wxjBd#6_plN@QXhoc*wI^0+BYad*V`w+RT$!M>oefnJ7`LU`5ekQZC!EPmHl`>vYzQ4XvMLPjW)UOZ*C+N%kGv5~~haefBGR}0$P z_FGJ1-bY5A*6yqL<15Zv-#6kdSb&E5Aq&1(EdqR zE&MteQ5biCx#r-xwXX6qZ8Cq$?=GI^JKWfYORm~}fMVtSl6MoDaI((AeLwrwV$Gz$h8E&X)K~qAcYO0s3O_1LBCSF z>h`5fAZu)jvS8CGoK>dFw3E?O`oqeCT5fWx(4AJwQsx)*BHHigr8`rfw|b&APVGQ> z)JvNvg95%r^8&m7@&eWbLdBH{>TtiSky2I39_Dvb;QGFRfv3xy=jPNJ9*p)|Izv_|w!&Ke%*n#cv8)2EmeQhgO z^lW$e)8VPOAp{sRofM8RX86Wg=>=HyN$ zf`9r$pLy@=S#15wm#n$F4JHfJPRG$`Yg^W?ou#B471)644)fb-0|ahRWv$^wk$ZNv z*K>+8er)@#YRL+EUPzXQ;6-$-sYv@tSgUG`*XdFvZNOyRcm_s?v+q3U2Mo$(ft-t$ z+mw_EoA7aL)|u~VTRq)?IFs$V3~~6 z9xX|!Xjxi*Z!-aEfNb2*sT&i=3h8LzQ;YV(PibC|mn1E-zqNa$SSy&bUe3*a7%UqX z8aa(|VkJZ6#*3qI_5OV5H~xFG?q&v&QDiLCEuhJCX2Nb#b2=~{CoRUDJ&U(1o69oJ zKb-r2y#VOLM<0u-dbk3v$UW~^=YIY-K_APAW(is1+kU(l>&StNTV~0Ym|8>)*tz`T zV7}`C1%MV%soxshZi@IOD;_)@7bl3&=@JJAHM~edn7j=ThjzQfPamdMU(OU!ae;jQ58yR>Wsc!f9>> zmv92kXq&7loYG4E2#b;$lS$5Yt4(l2p4LYw&7FSbdU4IyPc21>*^pmNWZD5s-l~nb zPP{W;XYq^-o0j6+KH0H6odqLAD`t9?h@j5uM8);$e8$&W0EeAR^R{mlff?uxM0yhc zeR{y3<(@#gC>i+{CiMwI->r4d;ujfFzIEG6eS68u0r#`MCIJJ*BaLOppvP%^n#PmhJf?VZs>;|^cQ`3;^`~#)tNqpG`*r^| z`v8!|;#T9%@}=oeEz-&z*(=nCG@@yVdrX{yBGdK)YfvpM}7_t?=j0xV1~`>#LjppAqqpy358 z9gsOQEf`Zcm9brtZSViws0hK73pDZ^!&^#K_B1Ux%+IBMA+ru5+9iC$R>XYRaEam6( z8Vaszc+r)VZj6T1D&tk3q+FvE`)*Z?nom+1)U-`cPV1x>(cGEFin*W_mLUc|9qT&bK~A@o|0bcLsX(=?Q`~CB zxhxE)@@^#+)9F~tt0(S5H!VP$la=RJQw&O!QQnH1(N*uAKF)+6Ak1t`Nda>&kas?F zGR!8)QQM6~y|$%$tC7Xy^q&@8L@k=tKpCnssM|lvlrJ(s7K(FKf;=r_Y8DD`98}wR z4%1Y8Sp>Zg3hZBrCwdWP{ta&I-NaM27HhuiK`MoG-+3 z8X_~RgQPH}R;h#K)pV`s3sIP!auvxyU{P zwt1eC)gb@bW1*mmj2vMEOaQ2qxo$i8_9+Kjm{yBfitP(opZ1&K%;dSyM|R@SX&d$D z7W?%+`Mm0q5#Fh)ioI;3|HEn48+@zH<`hO4BQCUR!TVvQLUCVSa9%UlD!TMwvcc&mvvUI=*vX zJfx$OKu~A`E6d?h;UOT#Su>T*{}-N)N(_B=4rLE*(?sAH)aL&`w%#%-u5RfTCLus@cMYE4?hxGF-QA^e5AG7& z65O4}A%x)W(zv?@w{M^K-uIm6-0`g+jQ+tG4QsDmt7=xwIm>uTd{zMYT>G$`4iFC z4(t;Z7JX2_$iFWt=6{oJeKfzMv>jKs3qI^5{}c_M2Q2d3ro_L&BDY-))4liy^!QZW zPq3YLdJSVb`hxT4KXi8J*A#>s`b-pVo_^Q8QHp-y^|<9gJ#xQc9?cCyfpHUF5a>1) zRW&k{LR$PT;wDZxC4mbd8+N@q;!`o`^%{aI1uB{V$XI<$5-)jDxD%Jt_9;?CcY$7= z9HeEZpwgeToAwAho~fmNp%7YxP*k_Ai&dj=SKbUUa6T*<(U4@h!QGyZo|?BYYc$vP ztSwX>`+KmuPz7)$Um1JMeW0%v2&?R^d$6*7LFp>HDwcK&0X?5V0lK3I|A^4KVSvq{ z4Pfv~Aqfm!{w{h4wQ;jx7;x}29BKm$aX1FNprKB>-(FD#?>A1C8kjmRegmL?>x%8% zM4sEpugGgUly<9=-eeS7MaS3Oa2VHx5&?IYWr)pv@^$$6-vm4hu1yU4)j*TC*quH- zK6rW>Vrm2Wejz{>Hl0cNM5Jp3(=l;6tn?HhHGEOLS{C3|!-%j+sBcHqFl@nf%_Oz1 zJ-ca_Qo*&`>V-r=jaiG09h#)~{{0p|Y7#FsIVfOJ zGpxd2-{MSj`(8RLP-k7&+-STZ*lSZ$$ndTtEc+~lASqWf(M9j5wozSm^tb81s~$XD zi-}wT*S%4|Q~dT6ve3B$;6nZJq=uTB9=*t1zW1BqTx*`&lRrf0o4Q)4W_bT@EGgt}J8s(BO9qeCj9N zi5>h4M*~T3^>g$24-Cc9SYF~XDrGcn)w26^GEqQY4{YK{{j-0!y{LkIl7TFN{%Jaa z4TE~o7jX#PSq^$l%YpR}0q#lGOiD1ujCDQ&4&8m(sY6h7BS;vS7yqJUtg1VWCC&7w zOhP?&S%*RKre)E+g?7~kHa9q{gVQ`)(N#b?4>M@bd0u2=>^m=bw-3kl!czf!zY+cg%u$Oha2UI#o z1#|-8LIQ^&7M$fw?We~JmJH=Y*P{hAjq^4I47Y4X_Dj%SfU6v8=}x?DPw%s5E7Df9gb_!B0XPMMZ8vUC~VhvdPs zbU6wIVDM=xH5mwlY3t5#Irp>5YIznfm`*G+Be)oH8>!pcpg8B{^wStMF_h!qw_O8a zS!E?ssL1vH1SzN8BH&A%vvUI+r0(adk)CgGh5;`(HJ!K1@j|cME<1zM)6?N3-c~)q zFcgw;*}Nc|XdDKKcoKUbANP^F=w{)k0&fjonrajf|LZJf93u=Alr5XS0;8YZ)xf;- z#KiM}_815XZ*iw#VC|`L6WSu3+z8NP)YBC~c?Y?d!F{kI+_#Ok>QbV&Xwa@%ko_EM zw=Gfh*ry=UHAd+Lj7S>QcaO>u&``@x z(gu7P!gYaF>8aI_{(h0JAyD%LqY7kItU~H_L4dYp1G*mhCS~uBb-vv>$mVxh?QE2H z+7k)_Bg1FKh~9cbkx;oHyD#KJ|JIxfkJoE^AG!aJc2@3a~4(Gyu8koRW zHZ0(=TTKFz1&87HeM&kyyr84mhwFXCbmn(Z)on-Rn2P*$7xq-0OvKA>kI9&486GRA zFT?KC)O0I{5q_Is&2?SAHdDS->rsQ>1-O>g(R8=#gK zf<0t&@wRXmSeoz=0c1jA6`igHKKC zHz71<;;`qdJCf?#`%_cME7$btGJ|)lgk2fT!Og()pGfsN37^eEOQ=w{IRUtiGnP0-aXHKYFqX@*jkLXOkQh=U`|bw4L2}*QL|eQ1wzB ziTM6J<`smUDw~RB#K$g$ud6UwXU#x@y7v`40jsXT4)sCEmw6A{><1_p=pPJm{ovi- zt1(pSn3jyU?*u4SRi8rH`&2~9(qtVLZmXj^LIOZBDyUSb(Gx7mLoNLBH1@GZ-nMmt z+@@zEzx?2NkR?0xb%empi{J`I{<;eA6P!YmH0~UHT9=@LsKq~SJ%Y-r$ehQl*_o5V z@NVr%$7u%DyzaA;b_^&ZHTMG^PpRgs_h%C`Cikv}-gl$|&PS!6xXjn}^edsV?vUV8ENun9z$eY-|ds6l{rZ&-EK<-^!E6JuEKgW1Kb*{?wS_WH&Tzw*~v*Bv7UhPRXTIMC$>+M(2M-Ua8;qiBZI(hd5T^@(#I9Drfc2 z$%hv>lCEfu|742oi4%L{OML{XzHBx7zqZ|FE%Ej|M*k0#A?etVA;*uS{rd8I*?vx; z*{aPzXYJq@iQoI4i?xHTwcU!=^V5jd)Ia&rZ6My$1OubmFF2w#@~=8yV)|&ius`%s zFS|mR4bUMU^(v7Y(teO@%9fv0=7AzR86>>h=)@s5MRefg?HzWiG#zH&#ZFlTihA{G zg%sQdhIj7DbLAbySH;#qD9&}c(#q~(H4ps(PG)L3Cy4@n>EM-sf z%VD9FIv}>2S5%%Y*BCvUTKxW`vA8O+@w9a|BzcQTA|2h+M-xg~shf!{hf53FU{z+!QA;CImy%YqGjCpWeGLA_dacm=pP8S30X1Qp zDQn4_^;h3=s2q2LcUq(qjJJ%Gjyh%m*@cjcI=Q( zvhIom-wUVoXB*19bFy3hE^GYe)%HnSMi68jnrKs_)vrsrXQV>3@wlvux@KZPYSOWG zEJ!zyK3*y-Y$T+_R`PRW35JyUm+3%~80X5j^OpDbWIJPLEP;LSuz4TY+ImhM?l5+kux+5rLh&4>4G)o|~F0FfUaZ6!5gTK^ds z5XP+HT(k{Tlf5gr3X+;g5@f@s|GjxOAkE4)O-lDJGATFlNX4G+vqa1^(l!oEE>1*+ zR8xhx&G8nOwcR>SrA(&cCB+S&iEj7b??tVkb0-!)Qg9xxpZ0%Z)xVIg2f9ir_&#lf^g z9Cr19=V#*ndY4&ryycqaR;4NpDd#6qq)wg!5#Lcl0X4nUHQAy5rIZ8^gnnXQ&wkC| zEs=7CY_`a?JW^qIf@j;7Q|*PQ*cj)|*%wW4p#PK3Fgv6lI^w7YbTQ7A?h9IKoTjF0 z+d>|fy==EQc2j!q?tI)OW8a8#o&}N=s5KQksY}h5bG*Cu&{XU*mXOy2I`=Mh_xgGv zoRyuALjk9|3TM`K^`VPLoKRm0BYH*>nA&qpl8X@3@$EBZQJ1`@R{v*CBb5ns^M0i;BS0qL?>{&|p=-V=#QrKrd zN{e`9WO~1&M%N#4vNq%U*Hh4aU;T9|GM)S>c50k14+3?qYukCIJ!*z zw(X9kErj+E4o9DwSxE3P09yZVrg6*eL$|!F)9v)IG*dA){v_aG(J=2&J{L7lr6Jz= z)O_&}RmM&1v)7bzUig>d&eqRj&f(D7;_O(q{{>;}G40jaLwfTqO5v4+rD18=F!kK$ zDq=J$G}HW@O?vj=yGbZ|1~m=PmRI}=i?QnOwvB4ZfZnyUPbXtd1b%>g1oK$qcg-Lt zWxHu{mi`R2&la9P+^4J{x9Ps*7AT22%}t)g*53Ric@t?0B`j9}>CqTDy+}-c=#=ux zPSkLY5V731r1nf-@~XC69;YTc9;$c3IsZa<+Y{jT^p|XRvqOVb8|hZTR|Vzj_Fo9x zt#K){#sJ;4ObhB{=^~XyUFUmn?!uvzgiZ(}!7{wAD$>L8AL|$!0R=;HpfPp2%m@xf z9e0=QFZ$05f;0mKC_!ndt5>37&wP_A6NwroGNCr~JAx3VS%SOgI;(V2iDxS2`Z{Il zR)ZtQQlguyxZe3MUb*)7>1D~TzwR~iNH1D;^Q3Xue(`3dYqy(Pw!SVGdf`yE3?}(V zH2ZVv!gM)XL;FvMz1I!yoVM&W_;hk7KY2NKex*0j>J2+RH3R%rmZnK= z`TZnFK=w1>(DfBDqzW3v@1fOlUQ&hT)l09PG5k5Kb5#^*+$A}SI!lvg$navbM5uGP zDg2g228ZhP!$Q2XzarC62P@6-h|lJG!9f9})w$vsYhal4bnD=vi3;lBy|boX)of>& zx;Y_CC4qzzWz(s+JaNnhEaOkeieB1*Y)UK-n0kvzA!>k zHr?3Onwn$U^fxs6nNckxD$G>$zb6Z9*S)w2(i<3T43oiB^Fc3$UfWfqX$+2r=qLVv zH`ZI)ePDU^mWL!MOjhVp3V&JZDoc?XTQ%sg!Rl44Lh(VD!dCE#XW6{hqR&x)4y-=@ zzDaPr0LppYFNL?J`tyvfgq>O5jl(C6K73HGta99zJ7o4p z9?^Rq?;@_ja#!-E%~SWcMi?))s$&lg`P|n}n|~9{?5LJxAS5bqv&c|wBi1r=4zf&o z>~+cB8sF;e4I$M5X`v-+rSm`B39t4I%d6f&u>X@%{m-!I-e`vDK-?*$xyDBtVr6?- zKyE!-aST_I_LzLxY@qAA+I$#mSoPqh)R&-Q+Z%67Ghy)d+UC~3&3Ew&M-$lrq zWPks<@FW!9qxibb*W{pT=r<6#r45z`vdhCz&h(Q&qp?gn|=2RgOo((LvgC9CUk!izS75xTN1mDGs*egTVzm1$b3ee`e^zz|I#XJJ2ymKA%z%o zlom#j`n`NryULDkOkePeOHJ^9?t<)t>7tP~&@n&=o(23jSxo!c9oKv{ZRiY)ePTAI z!oL%&JIL!CayZ)_FJt%SuBjnI{SfBt+-Wyt(oXT*DStsh-Cs?Kln~TGhd@D*D3WEx zI#&2NKVm2*e;a82*}Wo=Vorj3Q1w1DRle)S+8zNav)Rv0Ys4L|4ZqxK6$1(?DZvnQ zGBkj@+O+&0Djs%?hp z2(y9ed$T&NDD>nzvo|IhFSPu4D|+GibHuo2)c0v%SBS%5*6RMSB;fK{h@MKf{~X%K zm7!c9#KfiVDt{=cvXP;DZJJo2zp-zgPzI3uzZ7kdtqNQKvN?drH98n(Y?T?tvhY7V zW4T0nd;=O5njw>t&34J<@;HMS>eTl}i1U>=N(?06i#3W^^>ZYZcH zK1bM06iNP22)1uO0{!m|j~BM2{e_NB^ylRB!*w_^A*bJ?n}-)en{`w-hySKDN$A5Rec$U{fRa#&h{+HG4)4tt&U!{MiZOx5ng+#20Gp;5rD@X)a4*gLA* z|H^M&KtI_#K>2x@^XF;a$;>Oquxn1`g9RPb*JA~22E-h3t-F~cI89xs9$BVi_g%qx zu5)?<9-6v~-Z{hDweIk3`K3_T`6{TuVT}pHsav!Fn@3T@wMGfX?`s+Ym!Zg6?{sc$ zeMDMukeW$^CbQK^c`G!(N==zC<}@7T;C(H<8Xw`!T@m9_&4^J9pEWq5qyU)hNe< zp`0syIbCDO+2$x1MvYRq*k1-?WoRW*YC(Bz2{v!q)@=r;BeyT{!V(oq0RGjmZOwwM zwgzubYFva`r%jJ>Tg>V_4AA+yh6?7TSCN--9##-Y9L7Cqn7Mv0{%+ac2AugCZZ zaC<>r`-2=QMY(nTz%DOaq+;`{sl3X5uE9HPMoaC%Vb|nsRiI{%s2mj~`OpRC1V^2P zPa6EHv;0Rz*Vz!`KY_cU0T2^42ZYW6^EF01*UsdyuY;PewPK7(mpk5FWiUHNeMG5NH^n00@gSUpeJ!5w@(Cb^t zt**zZ0?lCvC7RTtNCa8r2l1~?4_~5a8P_jIxEZf!l)HxypdBcV4!GkAx}EzIGlZS+ z-znqZiV5Sun60Pb4Z=!G0mNkQR^3ze{ilJfr=i2P)tvD#Q~vXTlDsxhg+fl%R_}4g z`BNhtEMtq^w!pg^;^uoF$5IV;@)3dklY)sMAt7%!Q8BR>nsJ|1IeiLNy9PusX{pQ? zkZc4!4rL|<4ROHMjO~K`5^t^hOW1Klgw^RIG6A63&)+_=o@ft2L&VtnajVzcw0!yr zCUpx7h1#t?1@w4;pcF5gn-DN`reHCtN|@J9hje`t@=Mw679=ZCc)0t?b zv*+$gwJma=-G@w5r`qhnlq+DppgK1}UqJ&xw3n-(Il?duk~-U3#c7e8E{vsmK(eT@ z&NP~jsq#YG&7f~KL6GRs)n%XUY^jH=ZGRiOcR6E7cS0`$21t0_ChE>?6z?a?aMh^W zWdXgL|14{!Mw_{E+9<}Z`>oYIy@qr{w%==rsrKBrzeUR}8H9FTXui|+j90&L=V^RO zEy64!r^whi363cClZ$nLNb4@l!WruGx_N+)anH^LOA-~tv~fU}(rSFt)UQm}^Vhns zkJDp{g^d^Hk^yhoT|BC4UzNT@M6kye2j$&bQl(I$8=3W^9uvJWO!{Aw0+dCM!M{nM;kv>#q43K{aBy+BcYhMEdFCt9Nlog;=pj zhOM6{@+sonO631EsVtF^6WH1#MN0kooT%)%3eSi>1&$?sJ_P$TOWu&-lUT36EKZ6t z2oq%RqMJk9|G*z2;-u)26Rf<>Fj!M3(U6jOr$%H?Uy-cR<9J6(d3qpIZol%a)TWL# zM_3(P2Cc_}yk>(R7pfPZ#bm;B>vzhzWEXjF9q;EdQD1f*+A~EMZ4UX9BVb9_-S@R5 z#K`53;fW7qzQ|K2nn#i)79S3}dmoK^bna$9gp-lxq!PLQEu*22C3(vkR7ot3{P9g_ zUnhAQqnON_hi&h#^OyDU0qxX2=WI%8F2hu+@Z`-N73rQ z^CxY9cL+oMttDMZ!AgFYWYHe7YmkYg?$PY_8?5NAdG=^c;9tT`K?&XB`&HHCZyBk8 zanKCh9`#wl6vix$$}$d z;|1?tCG)l`;=N37+Ela6*$(>O>9}rhpR*|3_gsm-S*#6mH3P-+K6KjgcMCDGft)%c z@t~6oznXK1%b}C+=`QN)^wc+fT|R=5@$~NJ$bFJqcmFM0zPIryKkJ2o$FQnyD-3jG z!LGCH5`)s6-pYn{I*IJ# z@+r83%XGW~qJQsJok%E)(d3KHylxhsjshO{qw5`ZXl#>g%6z?9ef~Z%l1#&;#V_0L z>R23Kbw^--Zhh>sp;gU*QfvVGi1bJOp6nSZXQ{LWwV?Q?Fv zOZwA~sq}4oO#69Djz^SIT=9CWZxB*#Hw!P+D5pKfmYtQQffSD6X$zabDybOO3J(;d z+?SA=j3(dWhv1;u`glF|Cy-y;B%))${#G-o4Wv-rn|_A=_2wzf&)>_uTHIP9H1`Oy z)^Xxff=f)!DjRUUR(yvXvv}nVDiWU7+3j z(RYM$iXhsAoIL8;vnBLRTvxz&;>2f6E;jq>7-y+iEx>2~Q`*~lUx3$lNP%kR$6nCB znYFtST^V~Bpv9nFdk`6f-uqcAG#?#2+H_ZSGN*Y<(4YAf`=@y&-XYy&F+@0d@$QGf|1PO(r#%WtN>mUiAa3lW;_8?w0gd{bFn0IA|xF z0T!gG>f>cFgXlEb$AtGR;>xRoS(K&wZ4Px>qxJMiy_C}TI4ecc@RUS-fu=0d3L+lF zF1a&j@v94pQ$kPGt0o7B*|Tjfn$)hZ3Z54A$-e%)W*YtuaTmiEneoWIwe*O`Xj(yo z3=DFM)4*Rst4-bagyQPze{^OIUNGM~`rPc0X(qH#r-b&wv!O%7lCh zMAjo_VM;7TtNPr0TK}_<=gbK1clgp|8|P?)7H5y#aY40HqeCP)6(nzC#`8lfV{mbX z=P=-0rB<+FSe2`&&=RIA8o!6nU3stBB){elJkrkh7CF~2=ZFod`$ukpH~u~IS6IXH zh43XA2Qr9DrzTLb=dlj!9(S_5+B~X0Z7JXXpLHwlP{(~Gv?jArWbF@N#y*P97S>ANp~{@yN;WySPo$Zi}HCp7RxFR7{ec-O@XsOBSZ zgroCm35bd9IkQ}@Y7YL87oZ&t!xSHG4i0scuCBX#h{s`{@vY{b+@871moz%)d|9Z4 zB=O@Dp7u{BU%m`E>=%6}Vzn^JfuuOszb}DL^YGDbhW9o^yCvxqZ2h$8k;Wx2NLzn9 z^6kI>h1=-w5S_z~R9$+KN-6Km%vo3YBxKC@6uFZOe8%v}tsdrEu)QFz*5Xz4Mk1k5 zWgX5PoajE6))?MxlL2SI(>jSVikvgv_Svk{~7i>K?oY25bICj8g0A*;EY%`6gNa#D5gxD(LSd9H4 zlF(U8S7v08#(4P5+QTld%836J7~9B+gI!-dHA=|QXn-jO>}frrEiVPnkVTwMq_>()fCxk!gnO ztw+U0L?m0bo##|4V}kwS1MTjhhB}7C%rdEefYHc5z9$D@=$6EHb<{9=lb*hInHHJF zR(6@i)la{f^u7l1ctF6X?(N8ABV&@kBds%)vBZ^u?;;8MvIHg`sN3dN#@aMVs_jDZ zZT;l(0S?u$NX42ni@Sd>dp6SYk{?xFBpPoet9WS5x0Uv6b48MRgJ_PtpQhO^iE1)*+=Tf(C-ZG$lH*AZH!>SYzc-c2B?& zfn+rerIJx)>n+=_6h~+MW{6S@G?^N~!~$O5UT(#)cbQuGoK2YV2VrJ*_MNt~Y#vwc zK;4-}+9tl)Sh=}24-4cgEfFy4slO44>R`64bKc*{zh%7 zz1QZDL<#uxwik@IRS!7pF{TyJiX10V3Rldq!w9FEb}@_~1P98W0UkEpG9&f*v|E0x zms8+VN@*q08Fmi&UYwi*uU=-GCIaZcv{ApAk%E8dF+#wxVZCc8a-?BDjq#MRfGq7V zHpqy5qum%!J2j}g;Oj_z;P0N@WXd{v#CaDlrJao4bX|*e%1eg~hievG+VeA7(tRx+ zkg_KMY9-CLh5V7>Red{;3`~Oz)jPT$AO=CudecG+PqRw{?z8@Xy?EA4eN*9nP1`};)xJJH&`xWe0m zH)e~7SSqOrF8M&A4jQR{e0fzO3g@P;Dq$s7TK>|A2GtZQz%m@TunS zoC+9rU6!u-XJgZFg2|kSXrz-weg>AXXUUISql-WV4>-ppHqj$)k2e9^REJbt!fnwe zFQ%RP6QnJ9PaG(>U(&zQIxOdza4kOq=PPJglo#`P|4Tzj@u5R**TM(A|9)VKR3R<* zwrQ*W``=XcT;~s&o>tbop2RDrgOp~iR^RMwO;vdJ3uWS2V_sUnp!Du{-@t3i;^aP& z*ki~x4Nmt6@we@^2LyB*5)iLEUY@^giC6Cg%`;LW_wzPICh=&-aby*1S833t$apAx zMDM{Gy(E5S2&^Hh>@mYn-E=5u9z8L0vCp)q(x4zunAFQaLKF5eN3qh@sM5Ih6G9Rl z|N8?a6RrgIj*=XZJBbFIgUPs&M5oM$6=v9xM9H>Aeoi_x8yicwe)S<9fDeX3C%SM} zrP&LPAczgK&MZ=itmAf15km&)Ghrb(6Mc(hD{7*ri!<#)ghsfn0;-3$-2D_8szw+T ztHs8DO@g4^Ivv&eGqNFx-scFX%Fl?=KnoO@Tt)nG9<3nGEdHsr*c^&h3eA6Lo%vo4 z+5i^;hWWsyl_<>kr_xts`I!&35^q2Dh39muaA50{XpOj)6h|2=kuUxNgZj=y&o}(2 zwiw0MV4W(PCWHd6L4OqFYnE8cv8&_2Ydetv6}Z^_)tClnZB7FhuDt`!2}b--S9o^+ zv9k8xI+{j`%%Nr83JR^41yBV#&32DL`pq%3pqa$B#6s;P3+qgD<)kRc z`SWTXcPkEbeAUy&nBbV;$zM#mzD;}5$8lHG)|a>29ts2XT%@H)cZ$VD&iG6SypQ_h zjAm-_jr=iA&UJS(a=fhw8f>?yUj#e(Pwa{p$NLJ|x67@cUpw9i(_YYReF7V!^}fA) zQuDSMN=FJH9taZGv9R<-nqibKj6pXb8aR1K=?=BdJe?paKq`g1wu{r#teDf=HLmT` z{}n2X_JdW2W(hw6Qw!gjT|lBd&5#*3BPxk! z7%92|w+ICnm;?_jabYwvqYq<}`5(JN^9X>*DwR`fcb{n6M6dxO8n|HE#)(6r0nUxz zx}>Yp5U}MNB;x3$Tp}Vng5PsaLPg$X;|8V&(Z}^{*+Z(;zWkUtklV0cY`!G>Vc=OR zya?#|#Ubz#brOVqa&l^4?e~W2*u2LX8z9TCfx7D{V;H&OM}@UVK?^s}vLs`~5ec;I z?U5HtHGk+*OvW^pkK)@u176hqhnV@u%1typ>SdRhNZ+r-id?zTBzr?K@R(tr-WslBg89m_4^UxtfjP3#M94MPoZ z*_=*${lAZzBJmp=j+V%>TEfJjFe#K}>UWr2SNnz(Zn!=dLfHCr7)Gp z%u(bS-+Qd1zhd})C@e;K`sTZC`G~|CZTd$Kz|?CKx#I*Tpnd-|OtSM6d}o$d{iXd$ z3@tmop>1x|@{y0&Hw)~@{r2Nf@5l#OK7z2sKlTKA5shN) zIg^V_jG(1P7_ImBaZg+TXg@SQ;wPP|)a(!MIb-k9Ywg&BKC^v^k+XLr2B9&Kac~P- z(9>UUywc)lYkmx}fE5me2S~_8D(E?6ScN_mIUTDGnt)U0Z>Jr9_k?S=g3fGaMnwyv z3$d-{uLjpYF7MMd#h8y<2zPb+`}^7D>C#3hUu=TpS2{w=68?}rJi&`SF9=92M=Any2j8FFoE7mT_nO&*nxq@aGVVM{)^!seMUl zhOWIe^OgD@p7BpfY!j~(ns>jfa9bsgSmN-B*rGqUe(#3igN{tr&%>0!*-3)?s&D;l z5Z4L``h2V)G;0AEU_*XtttjcfxM z-h5+l0BuH#GmveW;rWZ-fPOJnpy{^<}+778no2H#h zY!yM+$9MNhsGi0YQRL~FiHs^W3(nEz+GMjvTXOk483b(aI)|M%#X>4Eh)nx_gY+qr zjbMTyiRFngH7!!?^}&s(v#41{0_ej})#q z=|Bs{XDo2)A9fjrOSTpKLHqymD|MT@Byfu?xyMqjn=52_0eU_IdfQn^)R8 zvu!t3*P-LGKbjFxavDx)@6=jow3)JQjA6#Fjajzp)OPVEx`uI2wD5s)mYjEZ{OcH& zM}W|eLB6U}-}nYfxkZkTbGRs*R24V}MKkgK+(4r$5Y2ntEQY{s2THjj&?#gGTpn98 zfg>YWyFsUpoPKYSkHvuzf4jQ2qEe#Y4rlX4zr&m!JNlnZOA_jumXDtBoX>?D){Zim z_1tLIJpQ(+yE-X)yF^$>{el^X^ah#WeDU<#NaiW&7$L$r!+T6yM?q0}TEz4ouTtXf zxHj|$KRhA}XO${3b{z!}Ur*40qP+ZHtn>60#bn0?4l|Rd-@07Jb_t)SLZrBGiI)O; zvT!?!HB0`yP2CXs|F!cmrI3#--RQd7>Fv5W!oQXyCr5wi?y}zw5M%}SV4C472wbN- z<{7xv-~aUC^xr7e=PBH8`XjO$&dfQR3R zOhiOP*^ef%r6JDkkEm<&2obanhF3W> z-S=PpREXpQnu7fYckcwl{1lR*i?xmo;0l((vCExp z!Y6hJD#OWLhwp_;KzwItIi4uL-5^|Qigm*uKQ?#)ii?dk))mr=$%c!g-PAjDX+;WW z)h)kFL+)^qU>0FsbQ+EoH~J`7dBvDW8}jt7IT_19uV!Hr_m)5Y>7BeoGvxWB{EXAP zSgw+WCj5uKuJZy0W-^MlOiYDIiNCPpzZ&R6zP`djdX>q3GuB_WE4d^f?te!7dzD92-Y$JYsOy7hev?7+WjMI;(N z^pufZ?zlv}Z{9f3;w>ZScCobfM40GZB4CL+tv?@}^l_`b91sbUc{+J5>v3|_JU*mc z{MmEEO*$D`J+sTz@y#IOBo8mY{w|S>w(rL4Z>}oeUZ*SR zqrxFWsgijQBaoM%rr4hgDHXO{0UikvQKV0c_1zhCXWd7ecU9i+8rbI@yLP;U&qf2@ z{v_5gM$R=0`mdb_6P^=2?HJw}xGB6*+4e=vSpJpnHXzY&-+hEl)aW`0E;>Ig0W}M} z?m=jlBN$`n=OZIhJB<&qOR(%dVNA0hJ!?J$_Xbe!>UG~0lyuO@O6W@aL4Fy&IXO8Q znW;Ms8Z$8yzQo*B-%n69@cCaYhUZGn3$V1EvNzu?jlDhEN$hlNuMPy9X+dOWikVA! z{>HZZk?%jFW?wAz#_qMf*2NB85{@(m%;fd9Vk1PEMtnp8-Zfre2d$GGfQr|fnHRK#c>JFNRu(`UA^@3=S0Zw-EUdnXoj^?r*fa&^ghFJ z7;U)z%IP+DKyirhh0kCfzOzxGcB!Um8b=AAm7atZ=a5f!6-oDT>1z?}ct;%qQKpg~ zW}Rn`JvaFrPB4AxRD_s~DN zjuoLwgiYjaL?woUh%uI!94B;n*mMlGBi3s7?*)m8HM+mR#vZJ2<*x3Z4}$F@VBnpd zmJvK)bibXt_Z|~f0#LpuzR@QG{140nq{>|#;e?C{!kpJkGwg_=@4HN98mW0AXe!r2 zB0DKJEt1gK4s_!>UD}o4jAWAJ>RH?O8R*)rE1wx$rCUWy5kp7D((*ZLRVA3G=sGi(X-|trGKUyec9;f(B~57bDK`5<$r_ zf0zk9O!ti3pGc9}z+uzo`YT>o5VvF3R}yL`d$FjI;**t#i1EF=)$I{SoJWn7^_9y&N~zja zW9ht2Tw_UPZ`V3(h7a>;&rYwYvgi11mR5h^7UI_$A6f|4RJ=9;5j9p_5MrK-^_K}&juqOLaWU54=uF?ObG)xADR@#L^z_P$kH6?f#6)zK@rp~% zyccxGAEp!?7g?EsNe5V8pME+;ef|P00hbE(YU)CBpQMXdnnHb9hL64nabdskB}RFM z;gR6J#GasJ)T5(=XJvVR>)*?aKWIdMpH>`rk9g%WqaD1;WbiCN~O==Y=6pWaxzDGq8{88q~|s2{%^@YrupvO5af&y4|-&Q72@{o=sBMhUn({p!@&+$zr4~K~Be(7b`H{og7KKV{o7g3g$0ee!e`QB*giGyLfkMMNy zExx}wT#aG3@0NY(|In`FmI_u5TeWaRC_oONq1T$mP!>YmRWpr zx~%HabW z=|5uQQ379Zv|=Oi)>BL~e}&H3H0d!G5a{9a7y-tu77r94W?qCkdqP;J1yCp&;AS>w zQzyLywy!nH4l?f0V`P&J?NxKb;8gPesbtj*kzzt8ZtyZRH0(4O!2j_T0tO~4Kf<`mTqoVmssfmcF_g(cpfFlX^+@iDOKWzqb&<-?IAfg8m|v5vIJ^sLYEZKY^l`-#x4GFY$K{efEU1S2 zzaMVaVTdD^^cXrM3cLYQMe3GBNSwmAC4A}6d>&_%Q}PjX}mYc3`gVdObu6bdyVhO*fnDH`rdOaz9f^UrsGSL@_GFT zNt@lXe5WMw7AvUPlY%5yY#BhZ1CMp z{OkVhMfthFUsDKkzBFre!Jd%sH7b|oe0CIiJdBuF)0Uk6vEhpAM=$8A)ANU`@u=K6 z1)f*Kc&9_2fRjX_YyqX*3dxF+sma^|oaf!jy7RM-{!R~~Ldnfa{=R*w z-Tt&XFA$;ZN8Pb0@${+98lFpB%eEPPOQmI9c#O#65@-5|KZ^;kvpMIyck=Po{$Wz| zhVH)igH_~6QVTQOaWLj^9y%Yn>xF9}+&YyFD8KmG}*B#mo7QmI2L<=^?bL!Jc4K3m!;|!DnGh?Dt*ad3#JAG6s zowKn+?msQImQV&9@O}lfiqF|#R~v9=z8jD&N<#bnFG$}GvKN9$9+m&GCDjkGSV@(k znz$a`tvALqH8lm>r^!$q836{tMB+db0+tqz!(AV@6!+AIoj~k^4blwz^J-}>T0Y?W zsXRL~^X&xD)0AbHd%KO1oFj=6@T6yUF1Tu|=E{;!uS5(DHrH;_L3SeYchZBsijzmD zOF`&=&#pJae&&nUOgzwIMXs3{v2h~th8x`nH22WrJLy3Bd4TcsN~`PBpXOz zIY9Ag)kEn;+f|}r0Ej%}dJ^qMsFEr71Me;bxd@Qyq3*j-QTcGGcpvbt@Vzvmt3y&( zf{{^nc9HpYj?J!W@eQfZxxWgqKzrH4$`W7cpm#Izd|*l&YL78_9oZphdY`^WMRZ#} zk~ZYX*!G>ULVAh9ATa4Ozl}Clx<#~@6)4l$DPS@AQJKVcD6nFDOjqEuQCs&d}p3m93oNpTd;6WBG zoyStaE{ki1J0aNb@6@E#TB(vOou&Rd2p5;<_5YFfmO*uGLE9kic7Wh|Ab4;HZovrz zNpOeY?(TAM2_7uLgS)%CySuwXfZ6x0`rf&Be$CXZUl2}FWUsY*b@wBEo&V-jRmuBV zWr~68{vjuP_tK`42~@q$w=2K7A^o|j@!;S!CUe@iP?XcP^Zhdn5L**3u5`+LD ztde*m_kWN}=z%_apbFrWx2#{zQ!ZMxx+?SjAE>08HGrbR`X@3ye{kyFavk~uBpr@I zSYM^z9xHzZIH)lc-r23>asma$b&rzRTP{b0Vm0s zz7wh&9q3(z#QMGbbPW@#r`n!F(q?}@HjIOqX6f8m24MJ;4us{c-U!ptv|z(U)RCXo zR|4YYh67WaAMhdu^!m8NWa2wsBkvqyetm#CsEBGVi=Ypu2j611n}QtV+Fq-r*6`Cgi`qR>XLC4z_+`Pr-r3n=6$s%l+8@%`tM$TA$0j znG9}??z5bZEbm%r^q!xDeE=ABfLK+Yrr*Bp_3drCfcfd9P1uPc%<5TMIm4it=)2Fh z<+|o=HyhuUGwthNv|TCHC1UH92K&vf;J=giEv1%f!tRf1A>7s}CwMyZreq#HRrkIw zYf5q}hL^pCyAg#_XKl{O`yOHk>2h)@7isA%{I2pJ^#VmC{0D<-{3+3f)AFG~M@?t$ zx`3|~0eA~)VdmcZA;F-C2F#;XJo{(gy(6LQ7^a5n=jhs+E|$zRXJ}|Bfc4ESs#g^h zAQpo9PB%9V6c$5-iCTX0J+D#{!LP%hf@$)!nV;J*%gfH6(K74_iQsXWgDR|vsWUPv zb{z=c9$@+%q3oMifm?N93)2l0163BxLfk`cKC`h0gifF${k7n?M~9_gF%!;rj0Ke- z6aTe%mM&a-9-dAri=s0f(y>z1J?E_Bs)L{Bf3@wWMgbYP7SR4IUS}Pc3yWtI3G5l2 z)Q`zl)@y(u(LsY5>Rj~I5Y{=Kn$>KZ#YVJBmZTqTu5;8`ryuH9sx*s#RE80!UFC6; z-C{K%p^3}bx=5%Id-n$n@v-XOd+(Zh)#B5I%D}*aMVV0$IOQ#KpEC0OF#8SlRSER& zqb$b$rdn7`?IpimJgz=C$S*N-TK|HgP3g|w$YS%<=+f~KJ~@lA*t1gh-$jg!`J2UH zeBRsNsB(qtt#`v;gt8MU!Qn(esd1!5)v7#0#ey6*Q1UV>hk~NTc#7ZHyVa7DlpuV4 zu7s=L5(V5h-{(C{NxT+_h>{&Yz_P2>@AIj_^)v6E#e?cjD*B|<4LfgZE}!2!M8XoM zbICLQ4}W3Sq7wzBMpj(fI>aD}Bcan>aQs>TlZ~dM^Fk$g_h|5C4hm@p=oi3P44Km672Lq*zQ(Y?=7y9Kd3Z_%+-OMSgmtWe=67P&4GVkhtrU zTV%?1PH|E77Ye-?{bRcD1uygnzLk{&x{a@E50%PA7x5wa<{c|Qzirhf=SNXBFKrVD zT?zrI2?Ft2FaOF=D4CXjp_-#(wN<8CED*tJK+>No=m`X&6e}PI`F?}qWC@~6lqE3x z+Y2)|Fd*H$3V7~wv!MBjSAQeFUI*qLr^x0RrqLjfz66@fh>I*Akhic45VG>6yL_2zHY?0xS3VqkmxZCRB5^dqpTo#D9!MLIiat?5e-J-Vs%*D`Gp z89yC(uhwi<4UoLh&8U(CVHG*-1l8j~c+jy?@!LEI25<+|U=eFdxRr*qd@dsN@oSTj z6zGIV#?9aG*x&Iv>}W+OyETqZ5)sqRo0yOKFut>@oROcLEm+k08OEhhhKBobqHKuTHBa&*f9=T= z)~~>CcwibUV*!QCzJ|!VtNE|JF=9QWyr<(=d|Ljc&=0>{_0SGGYMB5*f=Q7Z1ndr8 zir|++I)62x3Ep&YfE~8Z{PHQcN6A+PN)_V3-6rNF^o@Z2vc$CfPVbnf84IrUdwYET zW+m&hC{{GV@lOk`KpVBvdRb6V@InumOkMPqb%g+?uZLs+1MiDChsg-VZ;#e!pYFLd z;1jnVg2PprnVEopLDAQTSu;+e6E-Q>OWc*{Hi@haityhQNRm=gN{)Xw{5U?dPOLb$ zX!;F?<$~ZM?H+0mcIrSh<5cG6omET?8`IGcr26iu=s{r0Z>(4#rC%*! z#y{}cn-Y)qDS?y|Ma%Mm$of6>#HOy)88=D~6;^BjVMHBJvjJIn7F&H$cM0ei8Z9a{ zva$nbaXh+?%8-oAk?Fd}9_=dn02`^8K0Pmb!DhnCr`-O%E@4~pb_Mh(bopZThxV@j z?#(~nJ zmLz90JCF6}GT?zb0u|SQzsn&8Pgt&6O!7rEgBo$H3JQMj1;O8MQ3#E5=u zX_gVY3$PNlkgK$dzWUiu((0EVd|ZL){}^2v^Bq^B*Dww;p-u^h{b2)I>J@;lvx}=n zNixQDZE14tp6iyaS+%KMb96M4W-YirGu)6#;$UT&VuWCmLZD#=0V>Ob|0aAQ<(ZSdSFiBA`HKe-DA29MbH zRNIwywDCS@=~n$a-YF~dO+1~R+xQ-ABIdhahVRm5J^rc2F!N4Gz^JKWlKUYZXRT_(GxoW309)DMP=~I|`=|gN}x%zv%9c(y_7~Dhocr zSc$TEi&kBi;Z46jh~(Mf<-F50{n!pr41~Ex>Q}d-j#|V zqkR;Wm@Fosx=OJQ@_X% zJyqdOW5*hJCH6~^3C}*Ix6zQE;b9ivZbOw5a<{ZW7DJm0HgZaDpz3sV9>VB zK8B)Y0Q3`+IIH^ozgQ#{FE zKw)d%0sCI3(Qi0kUKs8B>=56Le3C@S%yN8)V=+P3gKHHj>lE3A(|Se4zYZECvwH4T ztJ+K}N3@Y-4(0Ztl@$5>Xn2$xtk~}~qQ%8NS*%)|x!*~(V#b-`1GBUxN(YThX7w?I zpCD7?#IGMgJ=z|M4zc-v)N)M2SR7*FW=I31zlHs@bLfDA*+UBQ43&#uCix!VU8S!A z_rxP=3z8Ho$p5Yin&bqVes-g`!aPD@j>C`Uw*b#UY7w99AOP+^!v|E#H5J$_bt-V#D@mN1KW^RFBWjI=#QRQyv3oaB@h% zy0=2#8{UfjC#yX4lSQ(>oM&!+8AB{+*!!o{Zfy6yk5J8fI~>~T&s=d|7n$*#3TQuA zkEzpUYby15!}BefyN}MXGI~oa?g{U{c(nEInvDjvx=J9NO{XAI` zvEJwJbGus{qkDEOzzU1rwVEWch>TeUC~s0EKhP_N@jL2LVYNEuI5YjW8SRX{f^>+& zS~m*l!iNz>bH>QL8{ik}zcSP=pRTQ~0hcxuO255G{iaVZG!%(dg-B~hf`=)-I2b0I z8oUB|F!~C$oBd&<*DCT>pj@*QtOA3DM@h-!mzCBGQ-Wnpj~9_0m6MYrQYiBGqSYa$ zQ}e9Jrg+v+j_J+{&NP98@!~@^H7#ji)KeP^AAKKhfj|{Kj}Kfalsh>wai9!|UguQw zA@Gi|WfcDCLR;p_44x7JD7Zq>s>k*G;)`&AgP~x!)PK4>f;+9 zVT7Dkg2@8Si6&1M8sdGwbR2WGodcP4$vT!&t>!L?`$>2h2(enSZwz22yJ;X%3Jmy& z_Qu+F3&NU2aiL9Epb1JMnz{*pevSJtm3#_1G2i@N;N~Viv3%Znm0fvWUg}6P-b5xX z&s0eX!gPF<^+1LfKIojPHBC_qp^9i zfgq8H^BdF_sdMG`z4M!W^Klc>7yWfkvhWHko+|eUUIpg~=hpiAA`hMmHgp0}HW6;9DsHuDJ9w)!=94RJZC^SgS$hiiNm*^jeru_C4cPT`8>z<+1ZVyNfT-7b{G|8`UO}(NUj3 zih-Qi!1XT&%!D=rOOtYtqY_XIV|6uGBKg+?Ma}H7Gj7Dt^;|Lm{KTV2>lmX*O4;9H zB%Y#6lTMx(dwU)HxLpFv5*Pg)?Od<&QeJ%$ z<&N81v8d$GRH+1vQj6?s2CPoFD(JNKp^#v}(9#)=hf z$s|PYz6UJ}6RA!k?Ko^WI9%Sisb)D>#^2KKJ(z0x7FX=4e*@zLD{JJ)nPr?@!?fr! zYDR44CPs!1OD`j?CAqv>LZYe&C95b*Ay-F$141GS@Y^Lmc#>QDKU{!HXeu{w0|P7A zj$yfSa~U2TF&~a3^qk-Vz?f1={qMS(M<)p*`7hsLQQs*ADJ6@3*kE$5JOAYNv0HYU z^XDjy8J9D=Od*a0xG z19X!gTq!KgDV-Ju{)j)B@gf$y;vppcqCea>cwAB;A`5JU0Tf8xSl0as7Xr3(B^m^z zl;X9Tz!s*DK_7)n{;GReg$nKK_^Xg1PjyMrv0GBDN2e?`fptSX1b4a{jF^96o~By- zE&5{5>w*;xP?CsnD6(+xlaP@~#`Bowc3@((p|!<48D~J;J3REgTX=vTh;F$N+0|0u zHV;rSlJi1H9?yaH9pFq0sK*{s1F&FH8BR`2{4j{QtoG7>N8e*CD^<}GhtVPR^q;Cj zi}ej;zHR3Kll1=YB`)qX{GoouZ958I$7ymXkHz%jSFMtTsy}j*#@}2J_>p z5CNiinu@yp*53#{Vb4l=@r1`xOW*3l=PxrK;l*?BZ{MkvX#f3EfJge9$xP4p+A&#Z zX@N-PyUDnFxzOK$?>3aEW$hlb_^J_!rYtWpY7N|K?=Rb2chiPHKI9w_es2WQO(EVvU0p! z@boIfI_G{WB1Ujj!RBc!Fl#~Do0i;nxiJwYjMTE;>r!pmhd&|K`kr=M7Q^M_?_AWl zUj3YHyw5_k6Gf%TSy8KV zc+T8Qy7a(AN7v3p6pIi+>`hwWobb=u))@K zA)_Akn-l!5zNRc--heSickGkSnbfCcu`?yXr>mVu_LJSAKH z5jO^X&X5iC0Px7jc6_{0{X*6(#Nj)37-Z5=V}FNWin<{54XE{mw|d z1+C;*e_iCU@aMiefsOoh+9;rT+c-gc(V2JF!A~c3{UwCd(#K=i2y=Os!muzrdGF1= z=V*bBr=?#GJ=Ko??YvzYj zd4R3=<5hCI*Jdz21_p+LcctW4ms9Ic)i%vSNw#YoO`Y>hzx7M(XTM}NI)qYyyQdIb`*t*|Wt)%!5zqDB zI+rz}LA|GPZPz>aIsk#KX9!4NJjVVB*F`~S=~e9kMW zBenIa-H=fwV_>|;=^uIWCy7={$kahx!Ox$X=8_(hx!G$^x20d&ZKOx7dLUK-(HxCyk;FC*UUNzgzwKz_#^tbO=Ugy(@j}U3) zyeFxvnDE41HscC1Ute19bsVRyYi>9V(z@s;rqpyDx8*H?Ntlz%&(YUos4sOq(vI4$ zah4Sfk|UA!jtWO4zf3rayh7xlMBs|3=_%n<<;6Mn8FP>IJ4K9uMh{OdkTF7lyHJGN zkc6j~;1{^;xT^{ECxEQ&TLYNnnTYp@ z1$!NaSjzzY(*@mv=^j(ygg`NfqB{{YTvptSB~*y&8%Z3^0b8uMLLXG&ZU)pO<&6CU zK)o@aIoZO`u%>l)a#N8HYR%pc8>l-qtUPF9enO#w40Yp-K9Heeq8U5uNSUBEW#D5& z9e{TIv3WX(=;_3RUUw4gY7zn!W4AY-g@mriVp>SSUMuSKgk=A$zQ6nHh}l0bkuWGb zvyF0DB|JSnD>XZ+k*UT~%aeou!`U$E>ne{zhEm0#M$ctNgr@X?d+B>1F8^}h zmH6KSe*+Lr>x~EF0Tc0qQ(NEXnG4N-D5kPDMW>^lKKj3`Rg3e)O10IU-=c0$k1Z1g zS1n@A0Gg@S<_`b*q7e=#@$Ge*k^Ffij^$(6K=XIUbddS3#@kC?vhYI@PTAvyTp7>s z```aiOcVO%Y+lbOK<|X_D&N(6c`XW)*IQiHg7G=rBh&(cJIvvB&aCz!)z!wsve=St{MDz&ckOR~<=$+BlmzZt zX}gg-vZiW)>I}>o*RzmhKiYIVzvk8K^0&BVd%R&!tzDzqrgeMa-0Qe;ENRxK8X3y% z!dy+9Wq`t$nqC>|K-THK_Ap{cEeTNv76}QC+7^4?XgY3ZE%a|vVq#d8KvTjAbi@TG z3~}rY;zA&56Sx8XM9r%vkVsUo_2kiCEmYvNzQrEDYNSboS~xg3hP>!7;%0n@4kSgc zyA{}E@hPO1GAjWoT8du;grwQwVn`Uy z;&RB6%fn6s*k1kd5JhXCE78-NJxDSIV}@!q#EUJka_~M~Y8ky7>PW&7g2Zh{-~-($ z+ElcCxJL>?@9t1dbvT2A2qZ)0MsPv##Kj@P@N+nC@MFt047SM7RPgtA>A&i$vU*BX zAZ)e76-SFEdlKvJ(S-vr6c2kJC^3khc(=nL+F#PsJwjo^!nkn*5su_T)R>gIe9>1x zI}fkX$A>uQU!wp#@~^WwvhFWljyztWPK=jU zk2Y>2U2Etl>ue`#u#x2Bj&74HVl9!mEG`;`&+AcCJ5fBHUBUy{QeYk<%uL~p_}Mwi z*e1o=z3vnzuKhYkZ?W;%YL$4*gju8UAinH#!ic4|&*_t`AdYliZj^c~$-O}{8NHY({yAveqwra7c1l^FJI|lgf8D(&FI>w23VdW9{JfV7)^a=mwPV@IyUpp)l3n#C_@) z_7!q=pIi=?>Y}b2&;&z_O(*QUP)$&t&>}v9^2||2!kuCCJ+QR&^`ad`(L1$*v9dQ$ zsQNIXvVXJIReKU8nX;O}*=)dcsFuC^StT0euL@cYh_#tqG>J9E<%6cy#0Z7{5PVN) z<58z?gzy{a7y8ZHB|92(v;lLKTwV<;7i{XSml4(^3Q;%s<7-p3bCl9?w%m39vED!< z4cNsgDNm4npWxT{%NcuNvb7MIdvhkYR7mNY6NT5hDAw2FZ)2r+Q*Ck8CZj;(181By zQZmQizGnlx1RnvN;^`LXHVS(}mgq!c3UCOnaace^11u~u!igL8P*GivFE`_H|2>vD zs->FmBqn?D^#n4~k0q;bTZ?TdVyQ(nl4=FoXRne+slZK#`9BBFRwMY#@@=p|VV|+g zH9IN5LvTt*dbiuAzFgvY-I$FVx$%w8!^vl!(9vHmkGIk6mtA&C85wFZHo1yx32_jG zO^a=`o<~i=48Z8HlD6)xr}kHm{t5AUjU>q%nEZM4RcaL4zo43YUOv#IjW0!%E=e+a z8Hjrzyh((PSs}hmxfhjRkm!ZuZCuHvePhtX)wyIB__dRDU|Ka;)^t0I#DiFo^;w)1>jF;{9$ zW!E7NGxn1X-dN{Q{0tC-Mr|5^s|Q8+kLDT>kO2=h3}t|fO}<*42?G<;ksHR$JZI96 zt6|kXG^0C;xm{VDBbfj2ijJ1ycvO1xuVXgV}bD; z@Ow!^}gLJh5cC1a7}& zoy4I5ydX|$S!%Bsi;~Je-dm=mlzLVle%emnx&33l)p|8BKi}u={8!*d9j$ppv`*#5 zXf>L=aW|E{K?uhx=v$gJcoO7(nEx{30Mpam%@HWup=Esf#e6{j{)u2 zIRv<^l>)GZV+ev(BUFhU3e|78o^*bxdFKh2^c@}YO=weHG%1djwF5rw9M_)5jr5pE zCe&P=cGp3cbq^LPWCA}qrYO3%uKtJ3gbAEXlm6nI0FM`etl}7mUF3*psFRi9; zT+9gQ{d}U#7gGO$Kg?sCR-NZ>@9)niKbWRhS?Sxk{cWUrG}{;~xRYw-V@G9tI-LL6 zyQ(I1xAzD?Z(H5z*f)u~HmlWcIMaMm70OKPt8%Us+U9ze`>omtTw3x_%ZB4sd4-Q0A zKygBEvF$0vKlYe@ihjhHNFyfqjj`{_L(LsN-Lk|#st1_LPrW(AzD7OfkH=YjXSW>B zy6g43Q=1P9%WIZNl z_?jMp2ZI(p57$XOmof{Y87tw!#HXiu@Wc(Rq z_#|^1y%aG6knCtRqC(u*O3hNf=x$y8uY*-gxnfkMFt}voqMo7*mu8LilcCazzoNYt zu3IRO0M`=_WPi-;(~gyj4~`Y=(u^Kx(ESTWSUUZ8rgh`p;lv>Zz~pffL`esL2y<4^ zXA~uReiDo%GR{UiGF_QWaWcYc*)1Cxqo03ug$xJlQ1rE{_dp9x@E$Fs`5!GeV0Q;U zg6>o5?BXF_gTyy_?=2p&A$f%5k}FURA}iw3q(wu-bHg%*@~DY;8QT~}atPZd7-U_L z#MUAL6TyFqwD0i}`N6wOGE5+##7j$xLm=44Lx#Ul7X{~7Qk1>m(F#y5c$a`z?(f(Y zDr9pn!SQtw?!lRP4bh40i`4YQIEpUgzihPVPc!atwX&R_hJCz;NmcYJzPuZfaUFY( zFsgg?n&z^6aUSm%-%(w89})2_qekpjg z8RM~Z&qb+G+x41T{NvU*YN}NMCx6So!gpf=0%KJxZ}ec@8#2ysuJ=9){E832S=I(mUq&;GS9tie|&hF+PO#Mt6$n&GgUjQ%pNw?U^mbj zerS~mPhn3am)6@!HdrH!5thN%wLP|9)9E?!c75jcSfi)}cAA{8J2oi8~gh+6Z zFvYX{8*~8_7r0hYe*>?rEq$iqQ4^Kc;tuVRfowiM{sbILRyx&{bjy&4&Q5PD4ZJwq z9`O#z(jsSE=(8RA2qX}>F+T)p;G6t9mitIcQx5Bgc=(M>X==`4b@ZhQ=ccgBbU$-@ zQChX@rJ%}nLq=7W5B1Y27*~vDE!#YRe~KR}jhYl%QYkOlO0=#btcv&9jn1{mK&Uw< z5%8$)9=$wIDy0|_!IJ?zs5WpAwSvY5GGCLR+azgfB!Wqai1+KB1WLrRLEbim%FA_> zlbU$g`Dl5wPWXLwfbN5q6nWe^`miOn8KR zO@p{pToR$r%w(`#dDl0)nZC=OS4TfIH|Lm;wka%o!@t+-J{L_* z=YBD#?vq`ILP|OF5t(jVVb=Als=g(v3~!ou6W+p)a~D4t=Ul_b_kXtD-ZlIFmD6Hc z;UbD?#V+-NcfMb@RX=W=`x7`YEF+PxW`p~&B7g~oW$hil>X88s4o-#e<&GI+?;W@F zHj#e7ti?B2HXb(sPuSkxR*$5I9Y~b1-Pp2V`Q|lp_)8Ij3y&SzS+eV(F-;5=Kwu8N z`0(w!MFL8p0weR)LKTzM>IFaA%!Og(0)LG>?c`VDXxZYk?v@dn{)xtf|5jF(0XoM2(Y==3g)gL`Zu6Nz1` z-2|?P2BRp`5FTE9mLhr6II*o>OTc}lnxz4m&iFy^abo~Yg)$v3*id3+!}jh2!N(`D zA@1RhDkkf|wt^JHJ&8~C&XkpuxEP^Doe)slqE)~-(1_@^Y~*6a2?JgvPaaFZgm{O> z5?&4>&(fdDoa(d#&nC9zDl*?zh)S*A5scTy{cBC;&y_VZ^WFbFx7z9SygRRzA*KQ= zv-lhbgxVB7$Fu3RPNieTiS$d|L##5_)N<6cC)KSYf}3f^9t>KAD%$|!4hq62Qk`mU zVXG*b!P_P*jg_7d^DlfVmLCvc{Ox$qZa(KJuXQIt;>>>eQ%*l5tNE!N7}RRcN~8Oc zu1&cK2nh+5F{^nE`3YYI*b~BDWjn`7!?mb0;Q^%fZ>6fh(~y!vtf-o`=rv?pt~076 zz$G9+{DrVnG)tsdj21TyYNeqN(|#`9P5MM#;y#+j#pyQ($fe9UQ5u5!!XY2Ug33A% zDwU?E^;vlY1V~VVA*K2x6*^j(4ADFhlpB#~Iwm!>-!5FELbA`bX! zYSI$f27s$!KYmGY9KZ)R(XJLHXcY%{8j0|JXHE4cnTwMSLUU3;M2R@23qAb!a}*de z5!3HK<3;H=Yq?wp!IFagvhVAS$`jokf?`C5hM+M8Whn{U-EhWtG1u{9?8#u{#pf-J z%hHThk9}f?PzUglRnGBusN!^*i(DvEE@Cv zGJSL>+`P6&2R_B#)qL5?R<;RpGCkB zJ3Tu3qgp&6^XFRBT;@2$Bmlp&wxRl6{%Ji90l$Wr3EL7bvIX}d}gmAb22|4pGbX^yND4_#N)eQqU=cktM}T+?AL>ac;~xf0<5{r&*<1}?EhLzxkOIb0t2Jtm~%L(acgSzg0{ww zI69`rO=E7gKPkc3XTWHSyT{k!RTQe6WE~-IxTM|6H0D-%LXONYObA8IYX=siFBfDd z@CH0y^YW;aY`oZE8y$HSWRGZyYCJ3o#w0!J?L}dx%PxRU{wo7@ln60&KTn2#WD5#D z;3LJ8jEtfHLS}V+=rt*bTUq>8rl8u)IVa3(FiJ>L*WoP5O0;FIDE;QzF%{K=Jg?%I( z1Nvszg_o9=yL~|4$hk?gbjz!MZ^XM%pCNIIoR)^B0fUWZ%_5eQg(zyul4MRd#}y#0 z*!qR#s3gh;|Ave-fIVrDnp^kescda(xzQ}WYBj&}F4m1IK!uS5DvKtW4vD`0ey;U& zjSdBjUo<0tK@!dxC3t1#XN&**PsAgSI_saKWQIkT1IK-V*2}rR6`q}cRATDBYgC(# zo7je^j%M&DBaXlT_S;87k6hTAqm=j_VlxPOkL?(mQMfK*QKwT$Bi_Mi^NtRR8(N*-a%9v6YFDh?kmjUNU&vzZks|Z zhtcu#7btd!gM9xF7a;RH1{7#Z0C)+A$jMzvLc8LjEV~i_j6Xy}x~3sX>vPXTmFVwV z57I!#qOV(0`fOynqfB_oU&YM1+Edcend(y<%{c%>#e#Co;v_HDhzU>SYm~E^b=^wD zvHt5W0THHWFb#)ZnuXX8=`v|xP`O8?0LNa#A0QfYTYPS|!i*jGmG4RLo@$Q=Ls!RR zw3Xl^!jELm&*@_UeupeQ8U?V+wcB_IR?UR#PT>O}9c(C%IZPo#2TcNW8wM~z8EL;k zu$}#IskDq`kqNT%dr5@3lAK(B)+b@>IdlTe-|5L%r|L|qOn704o6?e!;s7<{_lP zU4R9k12agnn^{@0DzdsFq$>Y7!MX^B#ZzV_F#gRO+4qCBn>h58u*brf!^FxevdwSf z_82tOX^s|Ho=18sKV*D}Fk9nIPxY^rBmc)|cp zPFE|_!eLrJ>EpZkh?Z96Si#Yu)7qS)cdVzt1!>H#!JG_a!3GmMYK6Bc;t+tV;;2gH z*N9tzsYU0G0jD=}>|AKWgx9?z7tSW6y2WzA6`0A3|FZ(3A8o@))DTHpKa)!%5StcI z{q6}l>D@d6Dsr%bvLtpUDx`<3n3U3+*l$2%P0yqhF!m85g`!;`=@^hk=?HUzs?)2@I>vp4o+R0u9$4S2!GW@j8x&r8|s!Z*4?~80FCVrqcVa0DY9mrmsy@ zFk&kLQDb8Y0vl-_pO@GTdhEV%VMH9a_r1s`O2k?MMTR8obKS=c_2!uM)HaBv_pZC! z`>29p!2Rn)`VJ}DR)nLHz=8p>8sN+D2)XFkI-n+~igO;Oc$)i41XcMobOG6*i7{Z# zrI?qV^j%3c4$Hz%2*XKWjAw#3J|)4hvTzq`b7=%a1*#5^30YCQxr(YoEnPY^ex~5s zS^9JF3<@>VMRT~a=CgeGw_K)b_wj#Kwg|a!if39?xX8lk(fF11W zNG-Yp1mK|9T;(G3gsks5T103G?3OQv(4z0HgaO>(j=;%W{&`p5_+RVBfgb04G^v2v z-}na*Llf4p?v8E;?bA8N2iKg2Gl+TiHeS}B634xF-dRo&%atb1d+jf^xIa2$M%Rkx zdW;`7OYD(4&i<+6!5PQUeGXk#<<{+aPphi!GIsC7#nbdlB=Tea(&=5=zUu9{MeU^PfHGk<`OqCu?iQ3 zW}5%Mcb0~bIf3|9XB_s%*yqxQkuko4TuPZNFS0gb|6LBDi2xAc3W}STwW&|#G70ao z1OABKpYgvUbDL(&Y2mRo1~moaYwQ_JRTVDWw^8ZC(JcFpyWM`v_%WI@au}BEC<8gY~Rl?1>#Sc*v2drD^$@ zLbS4o#*%a`O)Z8cfKz%dl*HDrWdlD6WP|*}&%_kCD3|Y{qI02-8t3XyQUBHg^4R}f zHu6U2EgFlGzT+ z@_kq(Z@btGQ)`z0`O{B=Sg3FR+O|(GBrDVL^qq(-EOfrTwe8kvWb&GbCX(j8Oc@?V zD6%6(XxanM5@RwCq?TwOCfZol~aF6gj!iqkZ1KqI2gl&^vFRU?hI9wTfWLAS*t+U}|A3X8 zNURL%FH1iYaJ%`RF0+sX14=;K0pT|5b3uO-2qmwN`jx+Sc82e#ggUA1`aw+*=!^ zFK==L%Ys=8sKehCin)J4AehdA_*g))C#h zNlPNQc=jTs_NACsX(s9z_=zE;;BBn_s z*Vt$X^f7?Ok>GO_(fy-W!|<<4PO|*ZmW2MYc`zvR^!dP>dZP8C*15N<^Hv9TFXShO zH&LuS7VqSdc$Sfu$yS3>&Lp7pPpV)r>pnQ3^F(VR?TS(^O2D9b{@5hf`DZ$AzMjl0 z-L>#_-6ii_R&cdoIU_oXQLtAx zy=UHucI(9VML&8vE*E}%*iL5FX<|csW@3DYif{cUe!ZybY30;{iz&sA6UY4e{v)4H zBiBv;+luf0qfFL!K={^p&`|#NKuo@B8;arcRF8T_&j$vd&d#UT6!IHuB<*Ik_S^5T z3myGtFK~Jr7xKQqkQuIGVw`Dx(S7r|WXG~Oy)0G`_9_4zWZN_%gf2?kG3v#|hveET zROo8o;D-zBbf3@8$y)baGN6a6N;X_**S;oPO{uIc;nXq>SMj;@?0{=(WXU4b^8ZSXxou_+PH!595fu3qw&*`Nnn_fcxT00e1q-OZ{svjAWIH# zfW8hsZ6(>-umuJ3U(hx~%;lT%O-x#--yz`o3iPOigresY=lZto$v)jv1d5wNy}uk0 zOFsm(H=IC=iyFIA9}E8jjRpg=#S8)y0WFV-`l*QkS^v!t8!&1V@nb_$8!VQ$5V-_V zBJQUoWK+c-Ox~1-Vk=!94J|;X7E`1pEg==Hq$zKKGG?<}mx>QR0bHq#igq%$5*LDH zy0r+FeR7;cz!h9)4YVo`>cqa}M`oarRjfmKNB3`!)UKZw0Iot<9BalI^mFmitYenx zlUB$FK4H-@yQ(p{mYPm+tAMjtpK%|#?)cNMZu>|h$ zHLnbQb&Qj9u$%%t|NC|f3>-uiS(#(A?W^urZ?k+ky2(x? zsKK7jBq2DJDOWEieReLDh`_tOx$)X2Ugz0OPzediq^+FCmJ$EN7`ngGa1+N**6`u& zqC}i2K0LITD#n=_oDmj9Gk-co<=gE1n55V6_vxq2-|m>`GCljdf>+DkHocaerDLDx z7b@9g-@AqLH8mWNp2cLP-k7fU@VafQ%ZA(fxq{$PWZrjBT;KL0=E-g4$pU}7bMOB} z)mKJE*>-JH0!oK;4kgl!bPS!M(%s$NAuxb6(kU(7-QC^Y-QC}HKks_to5eq74HvV{ z*!$Q=IB{vZ>~O7dy6@?n5?Mp4=QQ66y&_x79k<{4JUor4cH z{omn^zmvX9{RkLs)4J{>e0xlwYio1;D%-h4K^Fh2%=>gw*3$Fx!0?M%9Io96Wnq1w>OCDWoWuGXn z=YE%<&tF>5Nc3{JOz_%s&DzTS+)>&6skg%0aahKy(G~yN{fN`t>)PC%`*S|ctH*6c zo@CSgxEvRg&iR5&S?lTI+RHXu6QAem#Y>;g_>^Ikwlm8+FYiH4TVktA8;=GFM_*4mYtmt)@8w{aX>ft3B{gK=!<22XYt5GijsuZ`Zj@14hv7GOpE7&@) zt5y@G>)BKY>2uH=6L-oE{ZBWC~OlisPouLgDP-fAi;n?j)9+%S#;1@Pa4bCtASg(6Q8(0eJ<#%_aB|bjA#+GjD2&)d~mUCP@K5ttQz~|T9 zx$H4|4cS<0e)Z5toV+lDye2i3NdT79ZNXP){QVd7bf_p8v|;7xa+2o$+N5Rd;=B zYu){|wx;oXeJh0#y?={9?AFa23p#Tj>p((X+}N)2eqOIwTQv|hz)!8|N^xHEvhOo` zc_7C^d)rP;NfTvkdF({Hxd(5bRN1@@pwtPDjkkPda0t>ITW`>QN{(cbl~t&RCkut- zef`#|APS!+=I?rO7nCdUckAP4gdPfHf^yR(=g+?ZynJ5epFI{~im{wW_GO*Ap{v_v z-LK~x@;22n{v=Asl)1-hYZQJ-t=dTPIQyP*5g-M(MG5ZGV|b914yjyJFM)@K6Hsc8 z;?u_~NRE&~s#vb{TV=*^&;RiRY!|Dg`^>EQUo^m$HB1USx2p}Zilhan=#c3j`z*Y8kU zwy!l%%guCK61c>fppF}JH%*Ze_O`WHtfq+g3m=jOgEfTh1G$u)!j{1^dT~4Loi-qol1-$_xNUhfx%hH^6+huDdTjTYh zMBUSL62gFBS@W26}_hnHUR)s7))BS__fJz0=TP#PpNYC^gZYUzW zAqF`txPxf=hX%~lwvQxB&@#}0y|T_4|El}*&M-eIjU zF4pvGL}fYn~If|<%iRIvlVVuV7%OCv*Fams{N&BFfxsS@u7R`IP0C>l}g^zd+#F|>0*W&ijX z+l8zD>`vwLNAxQ9XM>7FbDE)2dA-ZHLkHEKG>_bjdUA$0o_n!WJey zSdI>cNiHUJM6@*MA0d#qW@?vZxa}r+042Z`i6;HRo5ulZU>lg&tZvCU*L-Par4AjV z;dar2YWfDWsQWHk*okdMdQ0UFU`NmwbbrCz1uQNr5Ofe{EK zUo?UF{^v7W411E(a#@+62U_@Wd8b1ynw2JR>ckNa>1CmXGmxXxCg^^*5dQRfv>&NS z0Rn9hNAj2-*}NWBKBR=+(FAtErC)tTH+tzEwJ1OeGPSZ5e)satna4u2X>Y2%I5 zHiwUMJfuYHz6`pS&gBI{Xvo2{u_&x3Qa3Z^FqQTDBPoKJy|Vn#3A5pSf&LrJ@2)~p zHp1*`zJI2|e6K_hcNK~#U;z{1mw)5FLP&HR{siTT00S*MLIg~o3lg|Xy7d7$)f*j% zNNBgLE}jgE9Wx|KN4Tv%jQX=FhZqKQnuRvoI-%@vNT#a092ayRoa4BNE_+|QAz+EN zVtn2y0m;`c2e!(W{Ho17&aLLsxg!9LCC$1THvv^$2o(7x(*oz5Kph{&8U9%;be{>J0jI8_410J4z#EM&Z`+OX&ONT3*hRShw+4LBa;4Y zZsIEbJI2vlA;uW?xc?Y@8f#zU_sL!Ce&A^aSAhAZK6i?Ihpva~<%6=)$Zusu!cvB*tC|cfTAu!nAVYS*q$@+O~#h{Ofr{{z|`s7aIQ^LxNqV5ygY2!rFlEn`nHZ>_Q3W(>M!irsknGAKRrXAMXu7#l~@YDtO#F!b$3Nm0ZO*$k^8Ka2tl2wkKv; z676B*BYw+sc9i5YQk%2luy%~Q;)4-=+n?s+{k^vTIOfu?AZ^yM)haL+qcGxE*$Co$ zM{EA2zl=>T1$L(Pht0h%t3C)1yEZoWb9>IqoXk7F6Sy5yvY%VSDdq@W=8wL{%D^G! z7JtjY#vL=Whuj$s#o8lL1f0WcNy_e06_2E%hG1cs7HWUcyV?0M$p_VHh(Lo03|2zK zvpe(v6zyCI5kv>pv$iXQf(=*OSbnV%L7 zGw;4&DpXS&L-7oJ*aMHmP|JxdN1)xY^R?!I!b%&+6_2&twF6?U|SW zsB!LOm=GB{V5e4s?t`*F&TJZ3^)Kk|uV0!K{ABKhFq=_ozvjNkA1OmOHZowkaI7(Y zXUh%P4$T|u+W1O_8&~0n^_X&6`Ql=oW-Z}?M3$X%l{&VDKO1?gl&H_l%;YX`fI3Aw zw~C*5fcbGEhP@0Zy1%;{Y+_fck7MTI3w zc)xD?pJK%DI_SqN<2Bcb<6c}FZe@*#&k)Kfl0A-TR%^%< zwI2hy+O}x;_tw0+Oq?~#!nxVsMw)sDeI8~T-u8UPA_|>1Dq>o(7jC*}82R>!Ox_Aj z1_U4VU;Fiv_!R^$EXKfSZO>7KNmQ?DO|5RFn)ah}KAcAZHix%m?uOqfA4EK~Uytg> zo;&^qxJ0}iH99CXG`8OPc$wc7NYd40%Jf>l?3|sdIXynamlxeoe`r-xns{dk=z$L|-UWofr%sgbKW;*zC-+c7@<=rNT69y1VG%EmUkxR7{ z!N0ixBEs1CT1eL%;%9Nz#NqiwWSJR4w1^S>wd(N{QMoWdkJLIwcX0_CD8qfRB)Y{2srK5D1?xSXat z52gmk%bE{pM*!RDo32g6&s!JVRq#}E#Ms@HG}+69PA6VPhfL5Y4Y#i(LXJMMi={K@ z6KmBq#{-Q7km2(r8#_bO%v*nht^eUeaT=IiBUm2+`w4U~9VE*f;0Lb#z78H{Pja=X zRqhYpL4XaB{lld}Z>aPQu?APwMB+oz=>bkE)vcn>iuT1ol}01aBNe2CM;Zi4S2ghqp@gRIM^C} zT8hj(d1Z(Y*pq2{y}Nq7Iz}UMn~}Fbi#WNt(Mi?rf1Z<)cvg(z^|_~!AZfZ%CVjmj z&A5*odtJwpc&USc_pVz{_-zg^!yrDdc5MX6^v}x+xT%iYY7Ei+sl<0L?Wbw4D5xuh zU*pH-7Whqiy6#TOhfa?I=73D9b4BmjRNPx?cVe>`uE4GhS5IjSr5HwCJ%aa2j0t|e z=<}|8t-2ll-#_=zX0phW>#Ks3N2qJg93dQ5u#jSx>jzIH9Qyr(1HbVOQDUx7U$8&; zDSj-2CED;xe$Fh%BxNkqZ-So@%l`U#-HfUixC{XLUCg}M3>8WOO~1b}!2Be}(Z_cc zif2b;!b9%-!GegT4e&j)f@`e|s;G=oO6`;zG;uI=OCjx$mif40bRLn&?yZI(lFgu6 zdZf${APXMl*cgh%v@7n*oJA9STjlfkpFS?|+qy$y^URf4eV8<-=Y}tK=*yE9S z?sKMq;Pk5Gbr*bXOl>}4>px={W>||1s0oIEMVh+w)M4W4&9&Z}KlBxmpa%E#_2Jtx zp__yOSz^CzZHG!S29m$haF;sB`?*vxf5I5x^raq-3TETs`3xG0XD}$9zAU?57|QH; z88Ea5D3t`i1H1?euiQ;dAv3BKVNAPsQ4;?!jaNy@=K?msK11>}b5CaW6*dKHm24$7 z8A~`4LGj?ANdv-1sN|K_D7Rv+y|FOKMvklKhCnwADW)T==;f5lfSr+AqR{^g$0m03 zdrGpP-*VEZxOfHUB@KJ|WxuHJ>lh8W_dC^UD>|nVj-bI~uC^apmW&JPh4p7LP3Y9M zKvRU#iNdnn<xBVdgo=7Fz55x!Qi363#qMj2!*c9a}TN3oUjFs z|Dqdf$-1fJb>5t_=%dF&z{ADF%n@(TjyT>FX1U#gs^@(;&@X zGKEssgnv+eQ;-~4E836wr zu%_mIr%>_e225VL{Jk+zvL2>&9b05rlTs5C0SfDdE0IVznz~nIV(~@}0h)gyzW95? zJ?Bjvv+l02v?S>1XH#Q1Cg%5q+h+I6gHhnTb#0o|?>+4jmGwK*hzSxp_9>I4TIFxs$z&eHCY$>8@&G*zCj<4Ao>5Z^EU zTfpZ5_ zuFP;TkW*qE{Dy2xKX_M6t#~zXxRug^WIl_6V49V`xA<8`g~#D)nA|a4k5x>mv~FBt zx~w=&H0=49{2v8PZV}Jy^=Q#=tz^|c|HK{hCjaeXYRX5Ta%pbuO`MV1^xA%i6p>OX z?VyhM+?;EBX4#W<+ltz~|ckft-hy#<$}`j-5x6zT(41FH^Vt% zUOsN712KOiGBnL>z%5kY0|sHGk(#D7%3`+?8}=`@Tep%9#8iNql$<-Ndsze3e8|p< zj=0_t3}f*C-i-({JN+WVh>qy!?93VoS7M9P&V!DaqeM$IQfu`sfu~53{jMyg+(|}X~l)yHw6WDm9^IDsP-rIP!(I2SAOd!7lm9U zV1mA44REBzhwVi@?r(iv0;IX{s*^v(X%a8Ems$&3aa$jVeX7$D@Y2v>Ov1$offUCq zKYO|xWk9YaPI|ONVYB%`ASwJ}`Q6qVrfLMb_ijp+OSq3)x9g!lA;^zd0k1zH+o(fm zrBeM<=^Dq0ZLT>qUTu4^YZ0-eq7EU=%M_J0^dYDW3+9rmy;iUrCVX z#`pYY_!|sgH`CMo9x1`Cu0~_+ieoV=moYI^TcR?_q5(}*tYf#kySr0eUI&sorO7&* z$hiStAXWqSth=zRWc-+Pel|t#gLC!Y4Y^!RZ^oGRFaG~SF1MY*Ydu1HdkJX!D4qg} zemI~QZGA-0(Zu$Cy#k6cPVH}>*$1aDe`(`#nvs`(_N)hqj8_rFx17ruR5ncivK;bg z&Lc$^v|6fNJ3Bi)rDi68$T9{Si+<~foHh=$@U^ce)c(ph3i7{*r$mr@@Rf&Qusx3duIs{SUkzZn~tG>HUi z=Eze6TQ2pgm*NJiC<#;mpkWiw!-^)p?EADmMn|y49c^!5%#&wpX({7oN(}+IP@5*> z6jEtOAikxXcyPVmc(dgjqA4{m-doi zCkX%k`3Jz2naWj?0#AdPPUXdG)TxdF_R$)PM_tkZc||jlDRaO;LkQTP8NC(1U0jk3 zo$T|^R$JQ^?YUw6mF&qh8m~-V)kgbi6DzC358-EV9ns+3jFvE56b3c+xYxFUNZ*An zqyvj5N^($)754V(fH_fsvj~{=w>HMX+FE=JG9RlO6^Et?8bkjUYk8go*#4#&k|XMs zv=jT?z5I7S-wM+1Xluzh(-F!X=YQ$x?kFF+ZrFj-uCfWoFdR9K@7`4=np{e7K7qe^ z+^2-0)-YY`NO|BSgS1(ITwtK~!%IZVhX1*F{i?6M=tGAhi0!BcPrvf&!wUxQ%l2ZE zp*2fyvWmvUwb~q$;L(hA5A|2uz9|w%d5;F(l~G z=K2Z7LYw7J(^zkR=N{U>zi$el2-T=TNDFXF9V^p|M5w`j&Fw~ZX`|gnzUe>*rW;Y8 z(=)P*3J1e1P&^`J4xy>WjbxKr@cpijf8L164D&)nOnkDxPbM9>`V}k2K2WntsSrII zfVyVv=t0cxc5j{~mN+9v%s(?KM z-q+!(y_U)6~?}Yrk4eKMLGjS|G2lzA%`WbIgU` z|G0vQYb{X#Pv#0>L>JLy5V`6e;@-I*FS}}kx2HgJkm9)E*cMQw;lj8s8T14RJr#V| zdkm?!9;4acFnfba1HUh){Hvm%Xgi*6|8a_y@#H{QPOs}l*ug|5(=koq>wi!Ww#@0Y_bs*TXF)0EZSF5J# zDL8*rKTPjC#kj8|5OJbtYgkLyxH7Zz4XM*m6DnL()3lHwpASX@lCImIRqF1q?6`(6^#yjKZO4N7$NV#2OKxD`j)pVW9+r}l z)QN|ho;S2<{Ee9!pi9#O!BknrF zhywlnCka|>C&fqBkx1nJ-Y4X5v(09Gc4YUzps4Nss6(ECVF^GP-#k@lzqn~>XM}mX z;($@*l-OJ|`QZ@C^$f?`202fID#4XLMWN`8hsq{rIf^J^NMT( z?+B!jdQwL}oLom*XuGDh<}eX{f=KS-wk(JuB^{aETh6tWr9B*MUo9AXNTTz2(x`=_uX z3z_e>(cT9bc@f}o`GoZAyg5&41-Sg5l+J0~55Z>g77yPFVC7E-! z+IxkY0`y#c3zC8Xb?|w`;CD=`2D9ep0wR?3TnsGVQ8TXO+h42L6b!-$aNnT9Di&aT z3fCZJ$zfZG{~7~e8UT*@ARFN?x+TgK1b6{#*t|Gl(fA@20@4&BsZyTs1e5Y|v+zD$ zBUw>^!AI!_BS0&lsRl-j7_W?qqoNFijpW3q*bavvxd|7zdP`9NC{(KaS`EL@06e)YAd464GX0{R%eGX&%Ky1^z7*tpoBF&^+Oz{D2_SdpG;dyph{-+-OuP*LH zeH}px3sUJ>JXHBnP;4wL(bBotk68Nh0aCadVK6z#hXmmG+2J@>F2F6FlkSfJKe4!CCQku5_i*NTg02y`37DAx!}^@3i)}OJrdey|I}kCGF>&C8`ze2XwYleFJ1Y_L$&lpfW`_JUhea4AV=Sp z-DY}CAW%6`Ft|_#6GSqPDwiaG0_8()X53)c$O??p~E>VS;Ua1y`+ zT?|zM;_x`+*yum_Tzso4n1|O*?tU?bf=ZiO*jNWmt5Z6rG#IP)3t}X^Gnn7=1>~4F zZZR;CP+o&hm55G*y4RMJrZMl?$jy4I`Ryf)r$#Se;kGWR|Y0q>f$G%x|n!7G9g z_Oe4{muo7?{xP4?x^)r@>N2b*vSr@=u_3?yWBVIx&s-FL!MNbuZ2idq%^uEUm-FKR z*Cv9*e@`hDm8ALJWSKmcqhlJRBvOU+6ketbff}H}tkXJj*RDK^f?O-izf>Jx-*_!J z3;&7zvFWhWthC!91d2_~LOFC?Ac- z6oZTPdSbwx&ykA2U9?KERGGt%{?9Wbu!wv(aLNoxN7pYH5HJMlWvipt+m+l5;WWfIPQ^= zPx!@&)3h~9$JROD!C=A-%Ye1f8=$=3S-=nt1p4X+a0_?2hSo@-D<#s_<39$`eL+Xm zU7>2OS1#&M;(!yKAn)fOiL|H@uOz5WACO0vzuvJ(_zUBIaw6@LJs90y_DI)5^ED}d>@4Qcf%z$oP!Sw^hhh-kqaUF$ zsPu(nW$u#|fz*ZUVsFE-LOFR>02#=2@*uib$)b|2*V#DZglrT$V3>+- zBE+TzOz(3HL7cXy??wSq^0q~oBr_gd7~NVQX1XjjN8`_(9NI%rCvoh6VS^?x9P<8LU~3)63-;xm3Mq+kDS|5)L}01cOICl zIxw3H9g_+36MCFFx2YBwYM$rg?Q*dh=aXyNPZ%hc3?#-3panFX$2xBoC+xZ4lKes+ z4G$rO2Me3q%!BlZVOtyLQ^JbUy8nW07T|?b5o6$xs%*lA@56*u;P)vPe?#Rw=V>xL z34XX<0LZHiK(|L0bHaqkLIyf;)tMFC>3aJ$uMV~^x|+nHnmc&swQwQg+#Gda8`c$! zxw=*5oYiJFcF&+hQAR)X*r$bd)_AuekioQXBbHslvGraP`R;xJiCm#TUeyL^x=I;eA`}cH$(csI2hWRcY-|fBQ7EY3g}V^~DaOzFE!rze`&@_|*Xx^U20c4E?dx%-;T_PXr=1f|#77BgKU%)KJb2sl zb`Kk~J!h|TIz0vsoVHmSP=n1La5?6NznmvLX}@l^T_bC*QGgcSRM0Uha(#knRr#*w zlK#j9$%R7xyF}^!YVu~>-h}jTb}RarUW$771T%nuh5B~zs3N|*d6T)90YGgpq+UrK zt36N10|NFJOdj?#&EF}B&xZbKCeu(|={a`%#R)?Db=g@?{9nQc#CQJ!0QA`5Py|k8 zcA)Is)iVdnh;14#NRT_GpMJ&j6=;=I)DvxD)rP?qo~~(YB9tBeeaVcAsDc1XxoTrQVg?Tx1ET_DXOiE-_%y?$ym;f{ zb6IVL+w$Up4I%1#*Ge;jodjWFTIm$TAGQKb3q|$iMxoamr$G+(D zJxoko#bzfLa3$8kpL~gkl?JpF-P%~4zP!JyO>g%8#wKhdz=Q$Wmw;Z|P66w0MJ(mGovL*LFDi8_xIF4 z3CblGxw(4e=|FhB!tnr?*V76G8eu0O-APvruDI-r;l7o`xO zPWVa&2#i6b@S_Ejv|c_H{TkLS(x%+r&dJ?($cX|t%yglFIkKAhAuU+(Kix~6x(4=e zP=83aFqXtSwc>RseQkS2diq^ummJMuBKTwf%*)&6W*uuvknGQL4M2A+k;VVH#`&2jQQ zO={-O6eoSgSi-O1yJai=rw0U8<#S>i+7j2l+9hfw&Kh9#61hv2!z0O&2@W4sT2Qot zci!35mDeVO`-X|=d-L|fIE#k_O075XfLUEi1UD834bjbAYwklo@nmsD>r#a3#LucD zfrPhLl->Rq&i$_#&m(eLODDxN2(`h2c#kO!#$wz-mIV`ya$#Q@+2 zg~A1`)60oJk;E*qHYc56kc;LnLX7+R3Bij7A`J4qnX+Q z?b(rOjxs*J0G()m7ZUP5oQIq;`4|yn!xbK(y@ZUFB+}q+x7AU2sW*hE`2EoEJFRx7 z(-IRrL^xn`9DgK`p?3uaY?K{qm0(k&M_DT*;oq?hNoMYBk1VsDv35?N*M8wL>)~MF=9#(nEkI4q#{j>G7w) zVV-xWntze0_iKYP(L$hU_m_h$@Q-@HZ^GAHkpKecaXQ|J>>^1i_C$?r_2x4}||UKSUZUr4|I%>~f&wsiwt1!!Yjh^R6_x80BN z!}^?JMEeQKJ?!dQlL^+-M?YwnK_DhwUa-SFPqiYu87TuaJ;xGA$vX)zK7p@kmOSZC z8PDt4A;Wj>4hzpcKF50F_PBdfGMqkfHvcBATsNWz9XZt)mSw#%91s8aCQyM^nn*BW zr=I0Q!~1d}0APr23<4ych9`PSS9w0WV|=qI;icgp@PARo7vn3r@|W0eEqa81d@OQy zf1QpyF(${_mmBk7$tdMwvkWh7dwnb_Yki#lrmzAq6f^F0GmLWeH~yStmZs& z=L?VLBU5^_S;1GViq2^MDUEcu`{mUrh-8zw&P4(ZQ-jO%Kr-aMvB|*WbmeKKuCEhx zqW(}f$1h;3aG`@DHG0bTn6~8Qd}o@Y^>kuG!u>>Uaz=sk;<{$qKZTdC{c;tqpy_xw z9~w%L)xU(c_#pAr*Ll*r^5%KzQCBh=UguRY@9kmj)Z4ML1Sgg}13(8oWu$b1UoC6E zl$a|vWmco!d&LYelgXxWVqkN@R^5Y0u^f*gL9fcK#as#*I*`rEBSa0f$yaxrRHj{Z zS=J@@K5&;K|CiKB!wjzG%k}S}zf>0t^Uk9K64oBaFl`FzcW+J)T=u!0lG%rldw<>& zp112es|uG+ObokZG*khnRfe$@mPyPDo3^J~Tv9F@x;D1!ezvvOp>a9UaA&e=(+Pj3 zRugX@&ncLnBeGU~W<2rtp5bY?t!~UdLT{}nPu9-V<^UZbrgCYC>20efl2NDi1(lb+ zTKYt8i{5jF;~?nv&!-we4~F=E&4T2@kbq3WA1Xi)s(i2pPC5qzi3;g3q}EL-ty%r) zs{x8BJa&zCnTIeXj{0&(6tALg(F|a4kxxcKK0zQQJR;hdd1@(EgwDU*1f@>`Oavzh z>4!ci3=vd9!{##aiMk105&^<>KN8@tCCS=T$kuRMWwm&#jJq*Pl7rD5_(*~e4AyqV zlZ7@>$N}lHbxh@-_jmwa;%w6}gY8v{HzuAfT>QZRB1XWoY%jxVPfO6X%)$hx$xLtS zjM-%dRn?2*&q(u!0S~&LY1S2R9UlVjR(1l0-_k&^uu>r~$G`mHJBn8a-Fo{i!25i{V1H{ev-q8j7<04UKcCDm=oiJ8(+8>y|yC|tcL{o=rF=^Ha8CY4TwV|O+b|sbxy|{6HDnO z;T%1r*HTRv<6dK)Z=~6Df0Y$;IF*~PDMnH<%PB%sEVxVHr?8(UP6(e#BO+c4Yp}|$w<)g$fkD>#zN%YfY2|VT^5yjIX+yfX=(Kl zdtHNTjxCef=Tx*}(~r!$rD2O7NIS!hraUMMzG{s@ad>5p%9)tQaB#r4-2EWyk0od* zdiS2gk|3YW56=+YVjsFJR6|2S2jp$2um4BAq<8CLV`BrDx^dHPC#ah2r+4Zwgh@C{ z6n@8ymZZcC0RxcH)8$@4NzD@5$AKxJojVzu^KcRUE9WCnPlzUOy2@5HvmKo z8K#bfGY&0GZL*yLgZ#ME2FmKG?jco~{<&j&VdB}$5;v$@lRw7pySsmGs-$r|PgDyB zpH(D$BY^{**bcFxccMsN25W!B`4xZI~(bGV{uqd+LL}|xc!B_D?pY5=;+7><3uJ~Pjc%s_4W2;hY76@A$+!RdZ$3ag*) z0-klrqaP-=qYsL>=+^9N1I=0E-1#F5G>45z2LmP&)pKW$qy0I+Jska|)^f5}$?PwM`_?Zt&&Av|l;pu5a zk3OJb+pFj!@#y)ea(!J~H=G9yC;8~(f0T9)8PQ-z>1q=7HRv78Oh}pzow#^(+@)9D zkP0@5ZN3JhHCPrihLokf=4F@6&}7s--x}{c<`a;nU|mw}K0hBhEZ+1=HaraTM|$4p z9aas6b_G)@0d}d9$|(r$diDt@_~whc~sA^tLLQNdB9EzD3Z+mcV6R*)isaT6L;ErreFIH|>uV ztIz5D-i->=-iAF-J}i8f=dpqs3to?wqgTY|75q$#6<$|H4GPOkn%-yogD&7bd2Lp= zU6a-8*Bl6BIxKy)_Oec(Nd(+jSAQ*7=jKr0-6IxY!rvtWc&2o>bUiUW#A&{*#CPgyf65ybeMlx&0%%KNWyT#FU$cmF^~>Dgkn*UY!H`@hI;RXEcFZ&QGBWT2 zkx0NTwM{iZ<(GVZ9V&Yms_YE4<-WF&Xc2rK7M)R&La9kfG9GQHUH+w8W=24^zcZmL z(POT?ZdCGZ7{x3icy9K@>tlR^BqdqUGa?aO08UtsA?tfqEZlOKPaDm?e5qOA+qc~I zDOKQo%|l_hRoS=zGODeu#XAw^Pu|-R5vU`5WD_ue-H)C~5eIjou_-%3f4W9{+>3Xc z)sn6bG2G6jYK~v6da;rPTW5#f;IRMPPrxd|&xRm_DN*|%2mUu;NVCqmp1!39rAd@g zIr=&=YMH&a(9bl)2wDz2ls$cq%-)Jg)c{MnKot1zO9Tu5D1I{s7_1Jx&zp(GRWsCe>1X9v^Ij||wemZtF%Hj8zYjLT! zb*GkoI@rmLfefekOm?FCoY07U9t-E+gs2W+J?dk~fLg9lzTl>m=svDLU%@M=QKkO|}rKqf=6yxhj+HZ+B zS1KO^hemb6UbMgnTEBrft&*83qmoo&)kQLp&oQ&lxCq#PPU<_oK+|uCX^(-@Hp{EN zm6-RMZ1ud{BzsL>bo`l)t>X5`4&AKHz7}Iyb1(!FKScNLPpp8Kr-WHpqn(i)h1^m; z{~UexL=2YY7e)PQ<#y4Is$|(@Id5}Y9(X-D4@&+$++J<&K;b)}w;mn>#|`bQo5J5x zfu_mf=HH)eQuZlDGpqwcWSV>(3`nf^Z-}2ymLBP;?dgF*(78`T=@esMJ*Y zD|V);BRu-@j=kS27KV!2wJRT_M~F8ye^^_+`8^@`!AGPGm);JXFfmI}p2EEa!~8D< zV3q;k!*1L+B;a4bV=M7+(ZkOIC^BNTJ0Z03x!V<<2<|H ziBR}*v<67R6$l1krC}o%e40;+TN5qM+xR)+j2?h-Dy%hV}Ij zhxQ?F{-=&X0!rk-Yavk@@3xNQvm!}I!@~%1=WHRqQYC#aXR8fSUoY?dKD4MoOrsb9 zd&)9B)f%ROO3*hhshqWrtNh}7L6Hle{ni+p;}ou`JlP~xqro`ZZ+W*YJ#QqetFT-v zo1E|axz)@{-;)mg{HCS!=QGyVVT@I8OF1xY5%vMIP5M9KVKe48F*1w`>8VGW+7DAF zcWAwBra6EAD$&zQo4rzk{sfbHClYm}?FZ;q%|jsUKPWKa5`IG@XCMT*OJ|xl>&BO( ziLR?KWma8}L+PYHw+s|jKiVy!uF)cSK@;aMJp0{#9Z&wtD!UZY8oLtId~g!V(@S!A zgF$HVeGURC-r{Xz?#n_5`0!ddO6~qh6`}8M)y;IEor^1*SemQQgi{5JG^ps ztI-7ppq22QI<%IqjkW;Y2GZy@#~*V}qpKA0Fcu#;B6!gI=Kgq%b(sh?Ax)?333M?G z?vKt|ZEI*z42UBC06|VG)?BHb_xf3irZzSRJU^k8$B{Pu&|vIX5%#+LJ|-V6LL>Sg zP+$Y~^5;FUmiS3c!7Mf<{54p4mr_h z#7lE-Cj>LLF1DQ~Kt@B3G(c_05UAdd6e1Lai7Jn_j8W5#Z?=|}TQD{q zYcc=G7FOBo4R%WNWwqHA_z8c47Ee{g!rfZJ7^?FG z^LVri@DcfUS0sIZEfx9-=9VhuvLCZFn;8ilDjV5$*y?aBR{;4>yQMW_9Q}#W%&9#^ zKW5CiETSaa$`_BzAL5YCCxdtnnNO$2xQlH~pwdus;fK;Dp1ziy%RO045NM>A(dLsX z*@3)k#p&~I?&Bj|svdJ(z9;!OARI_>+zqR_Db2wsNp)hT{WYazdIs1%(<#lgXS{@ zuD0=CFB_ib?{4uX|GnG^wtDJ41OtD<3DT%$$tSn58)@#mV3O$)ZOJtUcF`&31r&Bs zYk{1q<}jBZJvBA{zhNEuk^HU8FxV&I$YM_dXriS};_d3<0Em zxwsMmR+d2`eu9By*>oRBkuMNldt&}9bT(4PAnU1j%KXs~HSE<6?Bn!C3Puh9D#?St zbRFGXf~h0nsL9BuNt)qkIIqBe5i98=;T;Fw(e1kzsRWb|+Yy~wk<*-;)M+8!+n`l< zl6OgB2J-A`O~|4fX|TEeSs3IO`zmSt6`~^M)-;#dvoW~iun;k7DqbZvwWUmQ(A^nb z1Xky66aJvoTBUr7)Q^_7w0DJz8y&B1i^;SzXE(bZ#^5biX-ZnH1nDdL#)8aT@V(}cKgM!4hcP%8fWfij&Vk>h+WGDY zc`SJ~D{~C{P%4xQWWfYYEr?OxR83`J3>WYDNma}_Y0-_WRDVM~6yyiaFmZ7YRLg1f zCr8iJ>nOKp%J6UvF+3H%4xFLmDjvEjIRukD$@9HdC%-fLuj}VO_t4==v6-3xsfy81 zdefr9i=0e35ro%vtEKQdx|{!b9vMj7#aG;3wE@YD{sf&l-SJJMhROwJRY>Wqfa8^N zx54a*==5j~we2VIhsKI>s=3kzEnbw0nRquRfkX3m{~X8fFScCwKS_BT``9+y-h0+O zsGj|rca`XHTGT-wm=?FJGqaIR=Ud!iA><><_3mIaL#k=OBESzz!td!INaMUYwoks_ zy`*SpcL?n>QlBMV6nTn56ge8!dl{E!ExZoe6nQ1vYIdTW<1rg1ZsFjyVO;a-8R6At zt`D&gu{)jC-@kt~JR0|?e?Ej)+I|m8fDUqd4kyuR71mD=K+=6@w)ZX1K167D_|DEz z@iXTQPe`p$rCw&uue#S&-fZeyzr>Da&#I0RMZWF((WK?@&d*(>BOZC`6|uNG4TVzG z@FCWL6z-26rbS%kp7dXrGWDAtuSe7bt-jQiPsX1suaWSMIqBLqa7`Tsmsc%m*Qg;YiCm5I^~l60x>q_t;VBODz!SrocxYJOIAG8Uo=t? z#YE8%>cNR{0-ZL>EY`>|JOhC+I5o1QZC{=dTWf(=;n9u5Ca1Wns;c5njCFSk5P|z@ zw5`4l#nBqI?>~QbXp(R%$Bl;FMoSzfo3Y@=(fAPBDS+vMiWF{$9K82$Pm~%4Z*+&K z%EwQ$f5x$%8)9-Sp{h!b2<0?I(+!rTXeB8(GuELtLVVL=O0?oZKdPlhDHMWMqAL=x z8)+oNIME6Hqr*YLz`)>3SJ+PL)H%C*nrr~PFpdJzDyp-h)SbZsoXL^)CkXgJ-YkGy zDH$2uHY{3sdwZX2#!&_;csQZX@rxGP8yRx|R^FtT%HJ9a(odIH620ws@Bo(yW7=b#Nx+OcAEtb)2XARW$X8MAuBTV z#&c&7`Rwfy5H76`lhoeFz-=w{LzgfpNT1~9XPhk-=5Ds~)FgcT!j7SVW$TY_OXdF= z1<#Zw|KM4#aZm7E$ny)xhCTmDg({&kKGgG7dtpH=L8K4oCf~FLGEkWvzDB@jC92I( z`U*&nuE`MQLCqHAowGk*&&y|n2GV-kr;Hovvc0FQ<-vmCWg_<5p;R8nA`sj2a)Fr- z5mz(gXB``7mZw^JT2ul=AZwm>lS@=%>qL2U>QvH-- zqLZ4Jg_?EBf5*?G^U|AN;8Bv$Ovjgw9M!;8tN6Ch!>y!NQf56|I`6?t`I+4u7onJ; z`*IH((*-B?_7?q1o3XQ}ioER2EpowV{bK!HZ17zY(l~Kw53Gur@tj;7GttQP!88R{ z=!dUX?IDYa;v%ARFcFIxU%@bD;GlKfka>9mGILuXAZ5@ygpjlnkL5szW$(truts7X zeoq<)*C^nERIwvZY3S@O&{dE;+DjN)7)2$j5wB9=T1}AvIJD-0Qsi@UjSzM|V5*Ze z2%-QY>w>^r5q9o5@*gOA%%YHR+5L&3^hnRN;x26D)!_Ic<7XccEHod-XiiDn#X5Pg z=#WBzvLeBKioYMwx6FlM@mJ3o^d-}9$>bI5HFbPX%#=OXV27={MuK#5IZZr(6V{%A zk4rBUMr{|Bb_Fgn&BXMAgjZGd>FLR_>EBF|G7#wh-2n$3n*_n;-3azEf#fU6;hd)ao1--LPpDj)SROlfS{(eI;4dWu)C!f4cGq#I?E`{#bDzQkPA|aJ zm#LWRe4L0v`iNfS^!)R5+&t)(pTB|1sdN3ej^W1oJpxB|zRU<}h?r*SRoJdHCqSbG z4hzS|#w^R5kYE{KUS3ELNd2>772#$1QY+kH1L?i5c1NktB>FTe-OQX8Hl&UxZu_Mz zb3B{(a=B!f@?SsVDsI;-qo*i0$Q*YltbC+hBN$-0y7y5ZZ*}rI;Hh-j9N@t1d!?5H z7YXKVbKquegi(#SIi|{Z%gfjhK(J3nXny?9?PxLn(LSF%y%=2nuUzo0mv?93tcNT6 z&~qI1;Qpn@CI){kF~^Yhas{{^(`kWkTu;;@-MFpcUYI^({KKAwU>uV>fnh{Z^#^Fa zaFpc2|1A91(K>f1Z3fm0=~Pl+%yh6% z!4RUrBIWWk!*TS0=ug^xBKx7%^v;b3toFuV#6<*MiRLPXa7lr%jLthWzVaVhMJi|r zaOaHh#gAUX;gZ4-s@ZOTI@E!rHaKfOXK*uz(9~(|ANh5j{#3*EQKxYpb1D*%2Ec?l7v!!xt|v8BQ>@~jT+higydB7`KQ3Q+v|{6_}IW8 zor?1Qw-x{$CJow+jfsN`D)yhmRbvS^;z{k>!N))J)8sG9k=&t9)W%=~*T*CNk|mN4UqU=0y+$`5`($85)Wym&#utJ&MX^CLD%;LG!UUD`5fTcci!b7WUMGgLK)A zLIe$DYz-f!zJ_W1ZP_;kiXP6A=5?yl$yg&PtF;Bi!78J=J}cD&B}AD6O3ZVgz{coa z4+cqLW%4I@O+p!89e2Zt-|Dr>BI|+LLYEdA9ILgvO759%N6dJnxcr_CKW3+YjrK$l zCbPw=oz|jJfAzi&Sg(6`I*J;w{oItV1+-6oGKOBJO1pM^yML3X7Z=06@pGm?MPUpX zgPA=H3}Ct@FnpVks9Q4`*!GuLC z)N=LU1)R#>>xKAsk~ZP+br*E!pA2X{jQ$e((-T_}7!IVJj%H0^M2Pj1MM+ZQzzp_B z8a(>tHZ{`v4#yJ>z}*SZdpK@#y7)KsGra#uD)@yBg(C?z+WweNZt4@7Q6~`iGsuDb zwZ|O8jtT_d+k&4o2$^p<<`<&q@LZk|zQE@fP&af) zzmJv!R~^Zf)B(uY|AEMgT=RM_9Gn91nhfXHqUhT{4fwP{?n;=4oE>Wd$VWeZEomG@ zi^@5bNJtrUwup{r3a`5HTtD?VyU;nawqStoXocJa9?5ufgCeY#uA?iwESBEIS(_4m zQ5Gzq8?P%;&v0*ju;38L5o`Hv8&E>pgTRDjUkY%{&Vc-5QSND2YTcCLy zR`l}H($5gs3>46hDh-^+jT;Z#%Jr*k!TOqLEr9)9y?!Jon`M&@ zQj0nP;`^D-KURUk14Jsg-XT;({vWYI;mfrri*ePgx-CoEHFL zXusn(dXZcEePDfK#o;#PnkguA2|3YIB7Leg+clU1Y-+g4JoiX2T_zxCm5F}t_DwpS zYb;6V%6{+rlo0xHq5$Wl99`h_I7zcn&Eikk0IbeUOfz0m1g{1SCci;wMORUP0nvo< z{hU3Y2J?D#+TRph#=v*D2(WyV)0i?gHH%=y+Wi~0jSN$(QAUPVC*w)T8oNy6<2vSm zkG+X|n;w8VK{RVj<$ZlcZnYT*B1Ga zJGYmOWY2nT8632DAx9b0QVC3)$=tUJKLbzwtuaVPmVv=!3uiU+7gX*&~L~lP&EZ zpG;N?d&2&Yc31hdPX*=EXU`pQqz7I1-)oWts<>Z2&R|KQV!pw6w z1gcv-V+<^nA%h>0SfeE}nvN@ZEBKB_M?{{bt>*URtgMG;SQ6aDfNgAXrn+gAp6H`~ z%I|}NGw?buTHCPzAaogVQ$-@!E5iAwKkaF@TV57TWnhpxZo1Nt`52ykTYeOEX zWWfc4FsQhKLsME+KTR}gxyF4okP|)3+3g%Xfsu>agQ8QWrl^XIWCt;2|9k*|QT3W1 z6xQv23Pl-({Ub>00G#+`Wte#nK*u|rBu)}wLp2ny*I)v+3&2XKQv^McW$3He z^jiL&;I}1p#Kh;7A#kYYYu(_(X`Bf|f$vUWizSOr!--@YBTCaHaaU-RBtdUI|L5D- zz2WV`M-F8X<3ayCvOt4`eA2_C0CuB>siVD+h9zF^l{S*{%Ak?$-Er8ta(_lyY3AU(*9uIiuN{@4YyA@%gy3En)mYYTm(&L1FT7xt@1q_1H-$vvDlXCm@YdA zG|+o@mx=AE^X79ImK4Wov)7NF6YBL0$y_LVVK=dGl~tVuaA8dPl2JT_)RlJa%&@gU z3*D^PEE4r*cy1a{v^uZ^fU~gf`1chlzQZKJ-p1t811^ zKm~9`it8aOq>57eNx%sUu$e0o#CF5#MY`~r1!5Cb@cWSsk!i3^aFuB=8T}&($g%CO z83X{(8ckzknjr8r*R~~10xby!5gOt(T9Rm<(uGG`aWM!P37rfa^p}W$j#em|ypIr< zFu?7d6Imo>5w*08SYq_ZPB((RdXq6jIT*$jA;y5^98Ufns|KZ9{&MF_?v~Y7VvD$r zU)2y=Y~%On(*kh&+;I$BweS!751jISXYXdYC>}0b>M#oEWQW2@maCIi zvm^^XVN_)GnmAmGB8n5F7hHR>P;_vD!D0G?Ra97SvYj}@!ja}wxiEUXC!cQk0d&SS zg~jT>Ck{sCKpDQBLW!{W)f48;%>wa@H%oitaxm54|cXAh%Wc2_NTVcwY#m0;>wnjJx+OVZ;@t8>U2E>2L(Fk0p9;O>@WekpkQOzU((>tfc4V4ko@Q8s-cbg)Om{=K9wQtYjBO1X{-# z*3AMy5Y8r`1=B6ADoKv$N3$8y<<+Lg+9F@G$YhW?z8C12D0{e}eT;@|hhUH7Eg8gh zh!C)i7T{OyW(VttEB)Kf-{~v;E*K#Ly;#~KR@@kxv#(#J0r0?0I??b+VwsDwSV=4? zW%Eby@bKiBQIj+)i&3!^vleVl@V@~BQq;XRkax1WxEQ8RM-H#t<=!q`fj$$@oLtR_ z00UfGJF)}k0@PbEoFWJEPlymn3Ieuf4zl1Td63h9E3`dx&aQz zA*VD;3uhDCQrR8_`bzSY-nU`U+(M(+C%tarG~neRgs>loudtYad_kZD8m4ybEVLyv zY60a_XePyvb)B2oYf*Q;QvZ5GH{fR!o#OLlTMGUHJCBG}HfiqGrdKk1=+d&$GN5Ag z8OQ^|`)kjC^%cd8mxYU@mVYG!qeRo#PH!uGca6}~OOy2i0?e#oY5a56X}H=_3Y-fi zm}*Be)=HQ1>@MyL3kI7;{4T+IRL{fdP0BiH=zWf!wrSGaW{*pqjDf6?7y=HzGI}o` zoUW;b#CCjuHAo*RK$_zn|F4yEGU)%hu?_n^Zcr|>Fpy2-Y16mAmoj6N-xhE#i;wSH zxG@BUr$O$g4JL0_Pv}28%oKw!nd^B;%eB3h=F&-iZk3<>8~ja6lok+oDwZN813>AWtAG`Nxmb2ouljZjTpC{uGC z{gi-kqIhR!_*vV#_WWo0B2C8K3Wd^0Fnz8+t#{%#FC(M7X#KFWHj9Me=A-sAqQmKL zkKt@+o|7|@k5TILYi(mHIKP7}SgfEaVU?L<#!~2Y=aTtgq{$xrv5Evfjvz@vBOf;cEJxAxxB>*~Mt48Mh_6H}AH;8rF;D`8Q9w0eXZq?cZ) za}W3#2UW?Im9cx0CJ;C%2yM$8&<%$~b|&$pjvn0r$@uYSfr2Ezf9W0q{H+0n@w=}S zR>7udnoLAp7bh-);d(~b>w6N#sJGo!?*Rq$Hi0-MgkzlpC|7XdMU*)g^XJ&oN1=&K z??z+|2cZZOvDwX#XwR&I>%MAq+Y`Y;X$%k|-m%p~_Sw$(2!XlA*G&_#la$#Y1qU@C zc_#t2Hn0ijdN>pK=;={Ngnhp_4E4x9kgoP~ARr)<&1s9Ar4~_kOra+OHio;OF>WRj$7*3{6P!FFu#sR_*^_?-7t~%hrP=c;QWZ^T)QT z)Og@%eW_jyG4P_l71_v8Mz(bUFf(xP(0rJzan6;86|8oSSos9WiavYyQToJcWLcEV z3Nv&2CxVU^XWK2;piS5P7y;5wr$Z{>FjP2J(0MO~tpv)XbbMJ~^DMgf_aBABf4$>o zJd0GswU~l76T6m2+`L^^*aluFHeVetXtM5eASdkhvE(cIVQDM!At4-GOIP1 zTr7J|Y_849ZbGzd3!_40z&9bcy~^KGwmlkaS7*XAq-3~kmSS=BQ=N&qe*4Iux>ri; zDr3L>WNlQISK+aKK4m6r_<43X=<>_bI;VCM-PKkV8)fbG!9LFQnW5NQ+vg%?mFvNj z;^LKh-XbSfx5j7=HM6859zmXFf_Mc+?gP$`fB})$M%Dpe`=Q$HGTBKS+zcLs)VxZJ_UL= zb?Q%Hr;D8&gcYXOpdy){yImg$hbz6M0YVO5(|d!R|Wyb7EepeB2NSpIw&BSRLH-AJoy6{ z!3vFMn1Se=VhdQZSi=@|py_wtN%S|e#Q8Xo0Ojrb_IH%VWA>8e!PF?(44Y5`E~E`a z9I1v_3phy(yT3JIxHQ?oAj^`(ev@m);@Hev8F-!qAHrjA2?jsFLkU?b^G1EnF9QmKQ+5_MPx_QKZA2GWc^*c(CK zcLBeIG{xGD+h?}Ot!(iT4RBY?PXlQL4h|2F&x!uX=;wm|F1}hQxDt2D9tzUH^HP%0 zIY$rS*@)jcA`4--O+ba4!0JQxzK#is#TqTGk3izL_YZSFY4~nMn#UhUR^%51>@S5) zT%>jBX~z=62BBrjcVELsj9aBw8hUn&@YIKkLO+0Hykr%0E!9%l|3?|YE%#N-*h(k_ zuVApq(e-82Sk@~2F)qHbvd`Pcp$Yo;sE;++4ZBo(E5+x^%6!R{WT8I^qdZRkkEWtqcEN z@gu7FPq9T#Rxzfk_0Qs8OE}~<)*a%fttW|5GB*nqzP698*e3@pXC9bWIyLZG(>0L~ zG(Rm(=UQK+)lH{kElMQD!)jM!I}4zcC!pZmoYdIpdM0{qr7#+p5Rv zP;Mw_GMqfV=g&%kh5UK4Ne4(8<4Yg2;yH3?V)9s#_+!U~E`X}cZ@_>|cW&?gnKD9e z5szG1RTY?!MJJKPSceA!F^I+~HG-tz8zC<+oc2-yD}e*)-2 z=?kRiJ`#sWq|#xxP<{@qcUwb+#M&TDG8O|lA_zbw{`8LM<6vX+lfye@Q)054@muNq z=l9e~;>Q;YoSYT&7TmyGoB+!b^Ntt+7Rv;j-Q$W8iA9Zmk3PHu~Q4N;E$a!Ung(UJ^@14*2Q@dbh6(l1VGC{QZNDzKhDWv6iDpcKZI;S z8#`&_Ua}d0q1p+l1YJ1u8xF!x50dAu3d10&5kTZ;>Ii(IGWs|s^==ft1McVVO=+(r&KCmt47H;;nzs-LLN=_j=_1D?4N#s?RrFwzNCg`{@n;ec;Czv2%r} zx=SVSX-AKJ2Z<~uYjn(DDqULR?!1c%*EMl#zf#|rk;lXB(?`3JlV(l%9o;%5oRl#_y2MOH0!{2!4)-iI)+R@}D~egc(S>_DI(F&bG`o1}g&2*W`c3s(AJH*YX|p9E4NoO< zC+{_L2F8WQGbc^uKle5jJY8l;E6+AdYUP#kugskXJZiHlwMAZO&q~`xEdA>_ZGP)& zNUHcfxhs6XHE_0ZdP<4;>xgbE*Fd^u7gMw-k_ z7(*w@40;D!WGA>c#KP0sjpU zxsAzg%=%bLzJDRyphGrdKc<=vlQdgI>HLx14cr9hgNgA_B}paWuDOd6d}X$Y)sW)H z+$6K!)60j?3zltqQq)L)=rIPtK`J=?chn;!puePk&UA4XZl6WB`G~lJ|2c}Wg2O7Y zt}9hO!s@}ZLxKaZRmiylrcq1K*^W8yL;A>=JEKS47w^|TV!@))@AIn{_qs>_B$pEk zL6HiogSE5f0g8_Xef(knWzTc>S@;7qd@Elx@vM|PBVx2?rE_V@I@%XC)G=d)vM!0x zZ|;3x$S8$kO!-5R(LX%nART}`?-*~S7%y*j1t;mKoE(yWdqHr1<)6m?8Ufqw^~RXE zd?Raec`l#G9?$>5SI$jm0xS?Ty;Wt(8IF&H{=V*=f@( z;-Cx`icp5v3|2bFnVZVLmhd$SD=Yw$hu$+{>hmpHmy9mkyyXiS6uKD`vKfPA$!{M- zexd}rOQ|#YKN$6Y*1WZN)l>bb1%x*k->l(W=FSU5kzUk`M{_CQ!z|G*=*DW%I~Q9) z`rDzTwzD^BXCbo(Jj2N?RP80JWPY*$)xa1{G_m;pS8%~WMcMpm7)VH8AoT!BhA7?E z{n1$(*MaJkmEC?Kv2)Kf{ywduyQMOJf2-9aE5{|IH$Lk^LDBN3q>2aMnA^7YrnDk_ z&11*CD3Lk!#hi^hWUSbU+Usb3Up5JUVufWY}ba-jy!LdV0UKTnFV&L4w z_!cT%$7#z&ZWBwhk6Vvh{>a}Ve?WF@8PKPhZKqY@Pp`@Vc)6c(+Cj(UDUd9oZYf9#v~9wCS-okNWi ze|wt!fja=DtG9~O1(G@b@WZt$M`t*1gnqX1FVuUUwzgfXtmgVoU%g;DO6j{ArW}o> z1(hx#I`g#KInx_0IQrt*xwPh?q^5sww|1ocu?Z=*kH=AMelau6VHlhmTzgGs>3iiB zYdlc(^lc_X*Q2{9{P6I8^lp!whDYx{)af=t^(itL+l!e?wXp5^_|P(AvH3%RW?M!M zR{HH$45B#Al*C7GZQq-Qy1Q~FVyI5`9whVMTN1iXy_)WlvJ!V$IjV8h%&p+H$k&6y zecvM4*BsSh@CP?9r}YijmACWdPilYDxGkf9s=K~%UU-7VQD@u?w+AJuxh3gD@qZ(c zNxT#9FYQ06+aRQlI;o75_ebwpL|X{`4RIj~RGG8jjvo|HHHZk$K96Cu=e*kSL&^6P z?O~`zNwfyYihJN*^8y5Y2LI-+olHeVC$zl~D>gC_dHSkgl;EF%dzIQvh@6{9;bTJh_#U9xVJHi;0Y0%^fQ=QHtTV@Z_M>?0E#ChnUD;Ji?adzJAJRq!9FY+y&AUn#TS0(90LBj;Q8N#4>|xd(Hnf3jo+ZlMVCw%m#k~b z9&HQ=_>>N#Rb9^HEe@3!oe$PIe;4V?hS>u8eZFrBFE%Zde~oFp#xD-`)4K4YCoAzV zvD+2WYQF`S{4ZR(v`o-a)Q9Qll#iEQ6zR2g|9xG$;bz_SP92XJd!-k2E+C+Lz|TRk zMxw>VO_5&K8*lfKLBd-mcS#;>Z)t8^4A5hQv|3b$O1+a5_Et%mTYnrX5`E{@lg#Cte)EV0^6Tb?Y{m7 zG#&|Po)9TnjwF_L+%5u#N|%Dl*tX5vk#>XiBy`Y%cuL!HyWZ8ESu5{(3f*D6Bc20y z7H$5`erR0pZ#knjeT<_knuUJm<#w?}6!fq!^|f}Jo^_XJ#%c>J>tngQE12}^1Cu%)@VGw7~+$gP@~?v*8Y_x37S^# z(cFh9HZ~Uhc8jmLGt}_OIorc@Jq#A)K*2k&s?~HzhHb5zZ~p2sjzM)pjA(n*x}jw& zW{0O*^B{QUzGXIY)XAb%pH{OV;LVe&rT=gna^_(y0se0-z`sPjX=)|Qn3bEy82#ab zBjYM%-}*dRS!Eux40&}2%xZyBwYqkTzJ6JsyZ+56`3(M%(zg`vNiP3k@1)NYZ)3%E z#2p&6p3C3HNknF+eo|^a=7rWX4JoFsNd|A?e`|fnladVT;TraB@_u0cG=i84>E}yo zP-1MfZlQ+pN|I5YO_AKTYrA|*eY^X2a7;PfKe=25@Z0^#1LvWLpN%KlL3i;7|I28XO7+c$MDUohY8^?{=ngo z_1&&zg<;3+ICcKWxk-ni5&0XJ5@{!n;TU3BLSxoY-szfShsCot$S$0&;mJ_ZM@V+%5=`v%-LLuvV0?2w! zX)wy}?w4ScYdeATwD(xO*dp9KTZC9{$pG{@N5VIW7#iv4P|g!pqo_zg>HhuRs0!tX z>+>0a1lCf7BJDNUI*gKEKsiijCjBuM5DSmA{0Lf3f&LdReOP~eg>icGRpwAz zY5TFu)#zJ{z;B_G1BsIZsMS){|7t&Qar1nrC0~^^Ihyw8WQ&ReAC4B>pPq3px9MM>1#ijgi9j$i(#V z11Q|dYvL>j5RZMP9G7Knb9y`|So6MH$(krE3JVB+)}u%LlC{rFz!e&GtT)AVazRXK z*Fqj=M%mc&beiJv<{sBOzxMgDBKc!j(rZVc0%5(+%OTNTv{Y?iNcWvkNokTbZUXIh(6)-;;9^FNkfqYFNvB zS<|y#+?p!-mPqCH(Q$*n3tfT4_r<|_Bld&>DbvifG=J{JCtY$|?>g#XPhnCihKc{^ zp!)jEc_`R%w~X>8=OwA4gIDSUlsJv|?D(Q~Q-3P#TYM_^zf=BK(E;Xhb#>;U+!#C5 zPxZs#nMrpiLB_NAOYn#2j$7>-tgG)iS(;i#E4M?wPpdO8wVRpv6}olhx1GxH#D5PC zYn#V~?`ZTDkKkp5TB`2Sw5JYMU-Ndt;y!5;cT7@OQ`&3Yoe}X_o|S%nj7im6D!=)f z{JAW?Y4dKxhKk|&qUvw5KB*q+)S>WI} ztfqbSrRUw;GulI=h_&9`rQ|_}H}2Lv+3b!cDEnbxwB?3|B{YBb2bj5Cs0`@#o<}It z6W8o-P#<))T>3HKl~y{}Lh0qy)H-$Gvw=2lU#uktPX)i%9F3U^p9IKs=D`T2M~$2_3e$4gbK|q zTZAnmytyy;U*S}K^}3@oMR)bioE=yEp_nsD|LGvg84tW^pEVd>HK0&{!VP0^xvFgG zUtq~&l_EW zngy>YXcUu3f;h(2U?vOvo{z)lxTVw=1Tjh2P|1 zUZz3-%o$~RZ5|ul!F!p$uOxst)nB!B? zq&}@>i<|V%jO8yf<&)GO3#LVy00mGgX2zUFTW(R4D;gmPE$Z#sEkab%rm$RJl>t}r z$5B&~ErkcK_OY_y9;Lw1T$CN8{4z8_S3z7+Jfu9HcbiIwbt`IWd2fc zA9Hd87pVB(?Etaumi(tYZWC*grh3ol<+ay4bxYY(-y0fMgz@|R_zdhYYtMJhbN|2m zs^stdsl?hv|D{+>_A^U8#lAC%tEBx+T4TT=%7w)Q2q0`4$WXpbbHxn6526gB{{adn z#caRETo6j&MymuN_TX68X-Oys@e;A&qJHSCsH|w#Vd2Z~YTr<&1-Yp#ibO}ExH)Vb z?E1r91RW8%Se+ZGR`4*Qz$sC{h#H;+(~`Rri~c2H5W@jv4_E+P_~a$r>jbk1ftln8 zRX6BZAojot2upx5mZaH6s0sXQ;-`E62eEC2@?Sf2zSHOH-8z|gZ58HazF1JKW55F1 zeT7)9*f#$P91$dB9;O1O1(-{A*x5-Ja6ug#D?oJv-@s?en4S&MV99kAx4-@#ieb3h zNwA+LM2`FIBq6jg8AceSA?&H6Mplaw3gAH=u|R3DqWL4rm;sxHt@ywv%2Vf-6)cwV z#Z3(aIPyKiuByP8D?B(!yh&OTy@F}Yj|o6^Lk5y4qAZ&YSAfAg1N)?r+4=eT$w~h> z1S^Wrz&^4q+8;U9pu}Bp##Og>Ja%+zGq!zVoC>6VTUs)?s+nVQ>xu z`{wq^FzAsq%SWokZ^r=wE}_ueoH#;K3ORa(1jrp0mioBQ!Ts{GM4r5x_5Wz2!@27> z1nd*Z)APBSK4}!`OGjj)^ktg2x5<^`ywk=`2oUkS*GKS8G-v@-*Z`su0bqGLjChLU zrPtYZ0+;518L%Iibry3)bTm*4x|OOw^z&e>BE^IN*!M09y>v8xcVMdK=(2%UvlFn4 z+O~hm*3<6^B&okTJ-q~p=y5Blsxl@LH2*Pth&U?BYy}EYC=-Sb$sr?PS%8BK$7*=Sx znc2S8dN73P>n{Jbt$CNM;zs{@#a;i9JmGlGf)w|6K=ZZ!NQHNaj8WwtKE<@fqP|FN z@ccUj(A3OjG_{)GZ%^6NKisRD>cu#?itW623UxU>5=+!wbyPmm^Hx~9^-a41h#bOA z%nQOE!(9z>dQ`qHS2d}~HtnwK8+FL5z7Cxoyj_;6vxgtJ9K5d|r_D0Fy7f<6e7$YY z9NcMzg${EE=U@z5NKg$%yQ6> zkwtDVNpfIGhH0SI!ZZAhq7F~GR>1_ea5XA1kEiq3f(CF+TDVA;64hVUH%_M2sX@1|U+V=fDeIN}p z=^P~2nWh=o^Eqxbo4HK96&5z{eB*Tq<~3 zV*?6*p>4fSo^$mtvXuo;cVN>p6|@V*ACNayk}U{0DDqw%4OTQqEePDYxvjD3U>_2O zi|}&Ebk2p14;Nk0f@Jdh7H9$oG9G8vMVSv}==CXk7sDXP1)b)N(F$s8CPGhn#3v0W z@pk{$mF$xBtE4v;xJ8XRC|Yaebr>9j3;-j;3?_4NE4Y0D6EK@si3CA>Q3ljQh(H>7&Gw9R@vMUUx~63ZPKXK#PS-zHN|F@exx?!CXL zd)^k0!2|Llcjptt*r-luQ6{XV&$rB%qn3wAK7wk>%BJqXDYELc_83w;oAiOV0t71H zT{0!x%K6IKssLI_Yj;+)E+s%secFD*3)_#PpJ%119!Tow>T*wH9CJ=JV7_=9Et&Gwh{cB>YSHP4JyY z{1Y3iSMGs3&EG~TmQVvSnx;7nMo@7vpyrmJ1~C2sFxzpz<+?~N7n_qLx*gZD6^}7d zPxFZ4eCIGw!lPHQ6_JM1-8D@e^QUSbh6fVL$5c{S4TS((Jh#W`I3AS-3$5O0!tDCp z>@)DLPaE7v>ZGNn3km4?=4ZriZU==A4484;WGme#f8Tw;pn(B%h9tiC(ru5SgY_N# zF#H#gG_iZ-Zp=`VK*HkOX=Ivj&<@i@Vq8jlUg!{w7QkUgus%j2nWi$h=x6`C>=e*Z zwxgLM_h$A~+c!H{ae;CTGo>u}nTGhR*;Z^Cw5Peqq4__;v+ZKXJ=&sc-x-Ja)m)*$ z65-jw8K?s0i#-Sab>~+22JYnzdmz2?q6lzGs&HAI@wKoy6svUZ6eps6IG%~}ewB1g`#a|wGG)X>P)e-Dpnbm8yv!L%>bAJBwr}ww8 zQ^Os68WAee&ISD*U>k#b7f26L3$`2>0HJRN5H>O1bzm;-+L%d)uXvon_Kv~j`DDU{ zwETac?8!?$eKurA{(}pc%f(5JYdEaYYg8Ps3mkhM=35DYybTv$%wwfM*?fw{EVPKY zwAxBUjA9OQ%d30bIoz~$n&FXTOFyvlh*1xq_1Nwv^?9DBO=i#c7lPLbIl>$ryequV zZHv#vu0uyH+4{{^<-uDAS#?XC4S5P_#|}wo7y-+7sSc)Wo=2kWv2OhA&$3*Zw#+n9qi?@3ogp9=Q9#AB(Surn>LRA3pK*cu)wP)uO=EN5{ubaoX;&6;Y)DEz`$f zxS)Y^t=$erAygk9y~cQCy>*kJR-DUa%&)I&)wkQ3w&p4Z@mFb%a@wh)oTkkO=}Nl^ zywPWb^cuw@*VbkJV`miAuO+N%Ymf6sRIf3!CEREb49~SkeBb6t*{A>+@a;G`p%rnV z`Mr)Rl8^oP9Ft~@koViC0o#|$x-%ws)%MLlr=RYQo>#kX_F8pxZ_jwK-Wt|x%?T4s z$tfNN23A};TtgB($P&mZ^f&jDZ^z_qg|nB$g)Nzt=|E_10&D2qRq#{NCFqHgW%;;2 zl1CH&W82RiZ*4wi1~Ch~{TcogW0}CA$rJ?yLB%%P76fx`(7VW?hxBT{#zSZ&m;Ep( ztqs92Hp)0Wj^`G2%`PWefS+jHpx*)on`^2 zh7LkyW%FZl@E0pwl>eKdTnY61cBOxf(Ex-ZHy*kK5}i)QYTH-tqN@%~7~1T9Owow6 zpe7H>X%`mkK{s3$+j4ekFnQ9k9Ul@B($dnBMKjE%J495jVjg|&%#P2`m4AXfU5b>W zw5!l6tPMViI6{I6^<3TH)O0RJxaTASSDXWh<4;v0%$KN|!L19xsv8s%$b^r(|M9+s z8bvr0`-p*0W4D+=0XiKxdbxluw@+dntqMC$4}xd_ULdyaEoB~W_|dCsDh^GdYYT%o!Og+SI%PpDD6-HmC8q`4)G@T;%O1(4Egm|g8>GA5{rlJZe0gS`JV)=n2+}X`Z}~c&ukrXtiK^Q}kzsO5f_g3GM_s{u@KsqL=gj1Ao@^Tz`BZ z+%3sj_3vGsTW)Bt|Ed=QSr)ljt{$|f>Dlhu%eW|dYP*5DCY8e8+a3F}D)6=$(tyG} z>?XzY250{~YP)^Zs(^m)7+o@*8d~S~^B+_gt(V+=KtML+)%eUi$#0Nx;=PyEXMGpL z15k~kzFU{CvChDQ&qJ(!hlePxBDFh{3QpEcG01400S~$Sl#WuQVbU0W7rn8?*%hC5 zL#igLX)+4T94B!{M=z3upl##sW9u-sY|G0=^o{1mUWu5wCbjb)Po0;V`owe>D!_FqIM@3L4FuJ=4M;3(0c|RcK>DRUjmll2ZdI*M@ zE!kWPudJ@*_u$X&y8y~AHvsaAA6ncaWOCh6a=0Tha|U< z+|Zjf7?bFfGQp-J1U6&ht;-@uy@e^lTbGErG6i#O!%w!{0nYT6U@`mJkh-!&43Cvt zy4v^io>n#^w=C-FPk#O_x;yMRZ7Z=O35E@DZE$;1udX9|0<#Dg2IX?Z^k02h?|pp) z@Or>#yi7shFT6rVW2Y8gV3moi8feUH!v_ZMXbi4OqLHOk)TRO+?4^@d?4(0wEo_45Iy+>$|tPsn*Y z___L3z&5(ypFhJHwH(l9t_7SBzteZ@X~xA30?$|eb!uT3S?kih#XUAYbyN}{$5NB+ zOGmHsj;0?#k!DUir%jOh73BliSsAiJ$g!i@9Yix1f#Ee^FUA>MMbB3tP6<&ev!?XA zoTd_|b>h-5ez(f^2z;sJ?Oa7 zl*fP5l4GkZeV0o9pK z$q&9zg7W*MosLQ!U=PAMifs34q^lpZ7;$ksB%}zmgxdo=Q^;Kzf!WQHp!#{rNI?my z#E}nCS$WOQWH-Nsw=eVM1@PFZPr}G&5+SzsHF~1|w<+bO<^T67Wg|%Q>kKb{1)Ya6 z>p>CC!paitY(CE&{jhKDO&V4D!oK$|&oyeycAA|w!R}7 zJ7cciLMPH}tCAh(W1GQ;q_h<$Qos0EY}b=+u`enNuu07O?@qE~z$z8kNCQ)(c5!dYqP`_M&T`m%DQ~ix0uk zM1>e7e8B>y2>`*wgUNA=kZD=0MY%RFm?jU&x-1=0-5EJ7L?BQOEbhc{G@080cZk6u z?$^SdQ)KCY8EpUU?-CLo60HV7|FK(d(?qiV^)3Q>Zwbp@;3Bb+w5r$-B=I2=&LnwL zU~jNy8bD96rZA<9p7kI+1+UpJ)P`R6IV&x@wXFbZdUo1idD?8GKhEG)V7OLE+zSmC z*z`Syiq8H`>9ocmR=vjqsO(vp_piLfE7#oylOyxjK7xYwvu)R;`o#YPQ3J{RTIA;H z3K+dp+c6o#40fy0l*(~LU0cy)59rT;H5p;Jx2;6x=XzTNYKan}HQKFM2@P{}1yK@j zTzS>JE+>SGrTrKx&X2K4JNa9Wbzl}KSJNT+8@a=LwN_Fq{jw;l5sOL9>rYZ@v5id7 z!B%|P;VDN!!#ArG^8!4opnSQL>@F&#MnFC@&rUb_d4y4#bR}x1uz*7T=+5B)21te} z=Xoe%g=%)O{|}|G{`Wls(~MIAS7@Rx)4*Sgj*l*3zwvW&rLjLwZG2bY^WMKK2uER`qF;eG-G92Z~IET zdWj;?@S!ujB5yXW?Kti44|KUjr^7$G5SdK&Lgf+~TF<39~wOaPY@A z-Acfy_ZLt;DM&H60ig%+pOJEa2#{kJlc_E(1s1}2!0(Y@Ab+@_0H{bn=Zo%F-JCxO z$k9v2fk{w04T8PRTx`wH5vbnqIY{Oq#uOa1rz*itK?8siq-%9j96w!O9NNOg@YX!o z(4GDC8)XrPlSd3Ls|=l;Vu;}{Z28yztW-`gJfs*+4~x4_M@r`wU04PSee1TnQNd1M zoJ3x=C5)~Zh6dvfXn^fA6QJvQ;tBI%(Iztlv)x5kjp`}kwcBRtq)(ZkYZSrVr>GAfvKUzWMlsrX|EKP4z@%xgw_)+4Bk*^d zCL0}!)2{ChCDH1h1r#Me*S_(4&%1}W&#xvKcVXepmhB+RppJWc@mHAg*mE@^ufItPuUMC#7C+hcOXY@WhxA@mCY+=(sEb-~u z1ZR`(BN?@9U`6ge+n-@duVY8V{$vy>9xFI`3q3G?`=f+OJ7<%!KOL8q;QR?$}#95+Sslm`W_*)xj9DVg_{5o@xhA^+f;rr590ebJE=r_3XQ*di4*CA6A-9 zKsJN%;_w;$Kjb*VUg0IcX~`iE)T9A=`1r_lICzYZckDJws5CgU4sS4N;1PT1Fw)r5 z426Ob(R32k#OEQ98ZSWWPEtG8z6{qR@~j;Ck@q;KlR6 zGl96N*}d-z`tN;if#TH@@9glhu_Rv4KM3C7@GUPs&P+h+47K+4TheCbOSYP`onfgr z*q!#z)$wnUwXqfb&F`gL85R_Ahs(zGQ(Hf;l1sQ{~JrfC=@qVN>k1> z7lEwaaBO=UoBE|=MY_7iMr1>jUFLX>TOO-bTwILeZvXCv4t;D>-Z1O8SpmggCk5pb4K+eL%d&NZGNNZ_o0yaUUGI=V7vh1`&XCBc$wt9289QXKP^e66~UZSO(hK z2(!D~*t!SIR@AX9Nlxrftjea ztS>(65@n^4cX);Ar$|3%2#PtbPva(9k~|%lFbmvVgCXV0iAOhM?GXCp_k4eT<{BPv=k+SSa_pqOIj)%92Och@Ue_l<9jruQ;H33qavkT3v?c!cna=KKLzVH< z@pkRK4<4u2xo}EZZ#ZM_d461a-u#QgC#v=(awZ8PyDVR6S;~q#6Nc%$HlfhmIG5=q z(d49~JdLNL@ZrM;X)C&2?aR->&OOh}wKh=sU^S;gfYpqQTx2cDF= zWnyW-+B;+8V93CxBe3}CHQB`1HPt!Sz*O0Ssh>X)J`n`qE}UVuN6AOuMkGj}zY=2< zz@gK)Em-Fq7y)ZB_mDU`aZ9MxF4%OfqSU|3S7Qtf!30BlmK|$vc`4(Zuld}tm{=<* z;L7qD#L6I30ph6;&NPfQ&Sn;DvOX7wd?e->3`JlOJ8yN5J9=8fM*EUH$9ihNI_~RRb24NPA~z?B-Y2Ky!Ka>uPfh#7v5C zUt^C=x6OSLW}_P~5OmM2EpuPi1;P#%p$`v(29PFT-;LlTLKfmLN zvi)s%{pFel2tD|?%9#zcn1}O~lvmL&@B2&)+9NCuSA{F4vA9msTP%v&4dzJ&-o;(p zg_L81O8>MkD7on*P-RL;&F(5R4DuWWN=jYr9%yQMYCGRqe%wsw#9i>;o$e~qsmkQB z==vz)^UpE(=UE9?Ys)wCt&oyx7~~u4tvsu_=num2TWoq+26hQHJ^zr(oe^p0^*bh5 zv?){a&DZJuRsnYXU11pkDLww$p!XKUwK)rGU2(OLlWA0xx=xpr8rYZ!uWpNl@*8+5 z%gY}uTM1EOq680{w56;hX)-5$+B|EC_(fEoFFXhA^kgSy|Mj-#+c3emM+Pf17z2Fx zOh9`C>e{Ebn`7p^VRkm5hVlC@=;dhG_RNG!^YegD=2|hT?HU+$@&b;#rvUmw9i&~z z;NTT}*ow*-_C&Hp)M?yj(G81S#sCE^5WXiATPjhrGBz$yVKAgAHm5#EfZ*2?VQ6Eh z2k;OFj;7N5;>MhHx+M1U<4mhQB+)ku11zwJFtQv01pQJ7+ZjzP4UD5R<@jbE9TPN` zH*mTI@+5&FT9Ap+M<26m)xk)lU%K6(b%8%q9SDu_yIs`PjdBLzBxwU9?hZB?5f6#{c0)&_N3|FzYuo)WD*MA+waql%Gf ztu#h}Gf6X6|HV>y_%#uPiR?fk94&;emhtLBPfM$Z8yVL!-R*qq!+cJSziw=gA+^$D zKme`MD~?$dY|6Ky*x|ui?D^FwTa&q81hbUNW+b}SlZVafG9meg0!IfB@*d%zd_2nU z&qm?*Dg)Sb6klyPHq80^D}97F(-T}~=b5`TYH=$xvhwDjB|Ew1%338cDZe%lxUxT- z%}{8VLwmzuy*CPJ1wucS{}uI})R?6xH{ z6iWHtq~s9#yg(sGUGA}eG|T^J0#nV?_N$NHh8G0c(_(aMb|x$DdYb+d>!w5B)~!8A z#O9P(v0gJ}-DA5R(&A!ACJpkX_!n8W^D=JTQ!EK(pGll8|m+W5SIM%fOG#+ zfj>1R7&+qzg%ImZ9=U1KfdpIboXkys7lLP!#i}*)$%Pzn80&Mt%2ld?<$B z0Zs_lAqE2HQ=F%3Gq7>ANq8YCR>@xl$BpBy@px)F9~Fr_>Ou^Hnl`P81@QsisAiqf9YuVXRTuGJs}=EiKB_LCQ2W*rPf zcvKm_pC=eN%XUru*N9cl?yhZmiu?`?T(~rfB)4Rh=DMba8iia1e?hqYn~s?TN5ALE z4orULjTuo(xjf!FDjLR9)y2ZL7DCTFmaQ5*4iH#9D7PFKHeVSrnFVSYhv(kCe*IcV zsk=5}uP*{0a31NV_~Y4*65t%}O+jcs=L+9|5)6OJXGX9VJLrQwm|FctAZN0ws)~)3 zH6LY70667)RJlIwpn$f5rQ@GF*m0se_RVF(Ij7y`?LA@=+7J)6++JLwUJ9k>a!JF9 z2tJ{3^yZ4=2YxA&r;J|17wKwp~2{tjh+IxVm|;TfF$4dzNp5$ zDZ5+gjJ34<-Rn4VACZ%5E^@KfVi%e?En*Gc^S^U`xjB_461_`5{OZ>%Ew*`fYtZSi zL}dRk#-{reUANp`S6~<_<6{`kgT|b3#>&Np#Y&8U%ud9WLcm8<(a`M!SCZQl8SfU; zx2sfKa43+WynZZg7P{-npo|iaV!(*ouw?rYh~KPW(%am8202wYUm(hgC34*|-_qjN zlqDMDp8}KNJ+b2kR}W7>vImWraAvCXlqWn29ZG>5fdhNi-j}_V6R1QuC%fr*Uk&@F z{2P~j+&U-$3prRK56F`wSp}$hhpi}B7;Rk%Gp9_0a3m0{V+eoyWN*o9{J8Aox+scVlM83uCmo&}}Nel=xPMMbDA7RJOz zN4K4O_M7g@vFXXKowE1OAxosk06Z}tTv}S8!IY*5OfH6vf}?<{gAaRPlOvZu$WEmN zH$*sL*hPQ>BvGPx=0~)f+}(UfTEk8tz5Cpf2Ab(OWI{rob0@gkBwF@e!vt>l{87nE(%!`ac$;$uGEvGA6G8Pmfm zg(N0Ey_ub-#@xCm_~K{V6|d3EE)u)TVA*F2vryaR*(6Dz&CqrqLUDQj@2BLo%rzp# zruV~XfK}Ig$xFDMug{mbpo?mrddzk#NK_;~^bTjPeYxUEzqfrEsgy4NzRB$Q)0*t+ z!IwxW6Q2s3!`KSJFtQ_f>$f?UlQCEn`F>q%t%!QcS%-~4K+K>^7(R$F?sB-Q8t(-f z|G2^Noc04+|Lcjmh3dKz7N>Cz>ioJ-mtT;@cyR-5dyIi>!|#$>0o&TeMR}ZqU!v0q zK4WrvYbZ6t&61^500(&7qts4wV?tEa)m5YkgvQM3j@`UD)5wK9a5`;H#SR+H^?#gYr#!?lDL%nvLi|gCdMTOYreZbh4EPjf&4MX9RVk2!;=!Bp(WXJD>`&u=#rkZhlAkZN#p=Rh#s1h z^k&*HQ>mCi7~L4W^)d;j?Ub`X$Ip{%yZ#ivr@@wh)vU znWeP?h)qKtDfY;BE;aZ26`14U%>i>s=G-a%6_!GGf2df#c&qoekG+YS#DQL|HVIVR zZ;u!I7tkf@KQ`)j>CxwpaAk~6+K?(U;6r_*KEIS=A?SNsOG>Q^j*K;%X)M-!FZ}m2 z;SN}!;F2(Hk9?J~THXR6QRw`MscDxuny* zbJgD9-mxW!>YvnzKIH#J*rE}#7!eTg)pj6Y-eknhxN;WaVe!i4bi^>L-JdSQ$KsqK zi@FfC005~=OYLlIs6|pCIQr3v5y2?f* zu_ffj?tOLvH+f35`9flNQ)Zd(f3V{5i;+#y8!lHP_98^1;+98{TOG+p*Wpx2-#Wv! zIX``POYj+T93~oagUpJSyI|EoNJP{U@b+85@Z`dpgKZ5uNag)`GhkKI-mx~#Kn&@K z88p_LgD%8;2%WN+wrUW_!UB!bmQ*sB@=k{?u@#9%(L-ngOHdu*dg)_B_avv>SYj3b za?}_xQx1b^3#(3v5e;OXk;k4NOU2=Q!m-l|^-cytorz$}Q1-i=V)34#cct{q;{tG+*2lS~k%%ol`4tRLr}#}9UWzz?fF z`A^V%&;Hpun`2kZ3mVqWhUfeCQoyA>2=|afL5k{V%cyiF|1FuHms0DeX#}OM!^&t$8e=7P6b}lZu2l&h%=m z^mf=26}HcvrNmX89o|0dZWn}y+$oXHl`rblLT)p6dJS?Uezz098?}XE0|D%b9<0)l z!B`6RtSJ{lRlpcho8Gi)p;lMLJO*@d{jx^6TFwnU_>@s%2k})MV|&y5n^T5dHxLxA zN6MkG@-UJL8jS@{6>h6h-xKMJbcv=^aSKnehw>2yNP!ern^}R4Q(d(W#CH>0#u}3s z=%GIs7fDMW*Y^TOb;EI-ky|T)iVP4>nPLEt2s2tSSApBtVpz`$pIC2dh?oePb`S%x zN1)?+wN9oQUBbFsWJnf$y3k~BPiC)?SU&EXar#vG?}nGiyGRRzbi~?QU(k_=0P`nT zsR;B|_&X%(fyUVLy6jY}8w|tNam{U3aLbmh0 z@=R7F*iWYJ9ttSm*f4iuY&IKtv0HX%?gCif{rhpvv*NpRon8Ig^*-0Mgrt641HP(l1&y64dGy}cL+(<#>nKZ;&%x&$ue(u$=RH|_>-1~a z8THE}^VO?zb3I^Z{qWMu)lh*N-q6(wcZbES#diy$jJU2;h{b6I+YW=@Q1bzrGQ(Qi z`V9n-ARX0wdAbaQ36i`od4k1;9e&mZ4rjFlEt;Hwp%?QQO_K?OfU1431g6x zW2h7eI&5VAs1%eNN7#ir3k&_ZnyXsN%pKBeMaDMpy2{ipMQibfN&QZk;X7AFZkX+)3_C!rFPF}1rp}_a~sZe3>k$7a45kI5FRH=WgF7ljj5YgfMQ-5V)(X|SM$d>IzGSVH%&>NIh_6L!*S^!0vy0}TJ{bt2l z_OYO&jBu86nHqF>jmKpHv@E0kL)Vydvj$04U9ERN^d5S{?i`4=7N0XeH@O~4zXO$a zbQtLwfbthJ$Y#sr-!@n9x#Kzg3;Fvu=yS|)@jGh;`=YwxF88>x;g4GBqkICSl#ggU z+@|8aMq9~~9pW3^qdB0BUsj<5wXNYmYgFk#1t(o?By1X+{gHUM-@n>}uM+(XkYR!c zM%do-EAFdLMSLCm=c8=?3#0lP%zxvxD@&*C+?)JPULH>2Q@%f+W23+hi@CED>G9JQ zqr5#tJp?G%Ps~7{zMgp;1wAHwIru~Sp%Pd$@ahxPMC%bl<+U1V_cBz6V|Sy_IMT@+ z(VY%2LLv_ig-I~is6Q0Vi!+USDFxEH^0y}#C1aer;AOv9a+r zvsb?<<)}~CA33Ka;ZTR(3)r#~Q^&vy5y9YW7L@1`#7?7;iY2c3d=>&)3~MzZlrr=I zafl;aO&`C1!f+;u_)2jeEU!`weHS$BRibIE!(VH z%b_!T*AwWxnV6W2@cF#gJ^3X~KvoUfLjyg!ujh=VbQ|&+0HBH2nR)O-&-H{WGoSzu zG?W;ubl`{Ub8K#AQwkF|2H9KLy<8t=HgSp&nmTw?Dq9-xMU`3u1z@s4#WumJztBS| zR;1b2rdcztT|CwAzjXC2W)1Rn*s@=zRCJvS(^V~N%l6Hhd0yo1^y;P79ybX{nY8PQ z^_zIjaSIIl{*{MqxorQ%;2H$k;za5sa zh1In=e*T#^Y=iqc>Bq7TP}yG4M)w#EWBZ87BWIYe*9}wwFIG%g%m%f-_)s9;g)!;i z<^gi6@(77G;Vda-%xuqH2bsU68Rk31r(8eP3Q$96IUk`Ox{Yk%;?nB2Fx17fX#{^Z z8<$E1$eM*CL-sWSOEr0N4CHEi<rucvG zF917CTF4prn{dG1rlv^z#1<@H^$7_HXJ==tm377AVK%%=Rt-40(Of?XetHNYTgWK# ztFR3W06E>*&Jp#DJ3^B&Ucn&07rueR>HbLs!F(+mIIer3S9xoYgyC2GQve;9ByY3` z*Hycp3Nds5uE3A$2uVX{@OYr_lxwuh6c_wtE!Z5t8P@}6Lsv~5SQr7OecP(|l>X!N zGp#m?USz?V((tyER0sw>@sAq(M;+vBN-#IpAQ!_|TXjbaW8zaalu4>(cax{8IwSH* z3OgLAtIu;(%)X3o`4^NaY-bJkFEQn5m;z##OKQGWj(1ZZWhSpPC_tS0>Ww)&0H*Re z4RXZCe|2&=o0DSY|4-O6eFs7S0F&kln$46)l*^N>lSBjg|2zj0M50B1%}ggof*I#{ z%lPa?RHLf&YD@h;mp{iC5bYwb?w^k@Wc6jtoQ)Z`@US5LPO7kpfJ6sxFUkZ%4&JY5 ze>>2?G+eNj*Cd*l|BJ3<2>jl zLvtH1!x(MOKJ)%Nu4Qr(?V*+`!RhCa9{_UfBeJ^hVrWYTqINy~h;t2qUER_0*Bk0msjXI4ry33#jw~flxLjc&xgtNvN0FRx8d5*EP80H+d`nW$)D*VG z@WBD&nur`L_7s5hST+2T28R?`9=nmb*}EVm7sD*)%N+HAk@N0A#CaV4DM;qdK90@I z$qm1xkl1>^Dp98(d%f5rhk3BLl9Z5Wk0m4cu*Wcf337v1odfI_NyTF0B^}Y@^Ar35Yx|TtK_iRYvg$#M=L_iJSlzLDTRP|N!gU)VW}w?G0i)NFRBiXUb@Zp)+o`V*) zPp#zkc&c#v_^K64?1Poi3||S>M2Oti!|KlGt14{d;JME0hPJVm3A3}CeSeL_In{@6 z^JV_JqsLMFt*6u%BTS|f4bz^q`z?Q7HG}Lnv2k*QGV~YDk{B z)5FlvP)+7A_HetVsC<6_v9h(rMEwTomW*IXQ~YT)Qb?wx=~jU-v%WhWw^gJyLFo{s z{Iq4@mKXVydngd@YDgo?2WJ}e7qD)gPTmqpyNAc!LXppfS9}pqh8B)tnI65`A3()` zr!_0!NFVXL08Uot82m3E%Ugl-_jR7+^`sQ@hgZPlL{K#V@HVq3&ffVv&(|3LD2F^5 zW>Y5&15$%ZCcwL3LPnq0FW;ycy&Cz(OLz-h0Byd1OT8kt+p9fc=1kd5ju4w@4$hjA z1C4Au=`P@f%h4sIZW)SXC>3)sbtl`F!^ub8+S_5k@tMhjg}gX*yb^KQz1X__5vRfI z-M_+gSy6;AYjfnkvkOc5m11m&uww`MoNAP9dr~?z!S*jlM&tnlvbT5;Sy^H}Y>6|C z?Y4{rooWP`_v1=$4R^#cU%+2Vm9JqlIxn5E0YVo&Iu5gss!i9+fY$hmx0cQQKyRg$ z)~jhCOORT-mu2p9;QG*}YNR(~2Y0U7^-wIyoVSdM84s$yWTn1+Zg!<34Fs{na05|} zeB0Tp?~6-Ki=Xdi%&w{;rPLl`!mfxOW?dV;_F9b;`~2@nv78xOi5YDG%oz&BW*S0X z=QTkz?)3@(m7vSv03PlPC#K){6tUDvA!Q01b#_qpWg)#D(8QkR9GB0`xOeVuYz

uHm(+&a5#t@4&d&m$9t0W2d)47Sxzr7H-uD zL{10X<6*`j6-5p$Kh@FqFf!BS-XaIX*WzxRH6OMDzQ=~7;Tei_*}L$xAYWo`!tXD< zyu3r^LAqq|uk0Ak1vQAx>zGI|RS1wo#mxYetJ+2&%T13c=?sF}fXQ#fpEF7Oom2|X zhCsxc8=GSsY#nb=nTpa2mUHh~opa4vr@f{tVgdR+a1k^kuhgn)F4&qlkqY{Yy5EOK zl^Dl2b=<55Sbm{c3|q1LqMGQ|*3sOI+QxCNbIYjwBxHJoIfpeDstnK0ou;^RaR&g? zy0j{)E?|g|GFg0_mm}B(d@h5qX$~fD)Mmjz{s`+6bC&u2_^l z{76=<(@umljCmWCw0Q9p1?AATE!nk0022+iZ>16s~LkFLi1hAB0^+)a^>3vRnUn zuE@&iJ{EO{40*(!ES=sU+UR*(1fQGuI_~0^luG+a*Y5C))mZPH2l8rDz1$AQk@MFs zHQ2ZGKegmMOknbn>v;Sj@;309I+d=P=(sbC)R7INw*rAJ#3;vi@Qf| z<0X*w^LC6DeiaW_i5J*Z1hX{xc4`RhKFNIgIsHbA%FcyDOM1>Vz^NQfmiL~}&nP50 z_Ya*@ehrQ*h45tXYFb>7hhz2|R19Le6Q9?)!X5g`uzI^Dh0cYvLCTCO>A5<&Ezf)i z1gH%Kk_Q1ILfGfl0k|<~!h}(-0u)j~K;ygSq4<4G(J}pP;qqw+X4^U94FVlmck|Tl zhJeqA3uRfdg=PU{P~L1d-m{MHHMuCp_cw}Yv(v>mcH0iA<3eCx zV9xl{(fhv)u6Nevb63HTcWFn;E5i-dueOyJ+cp>1%gQ)MWmm z>9a@c{szaN#wtO#mzxFosFt6bnqwg4f~n5{$j=yEnwWN`&8BynTSQzKN10iRrKLb0 zZ9EwJ9ky@6838d*H3Hy~dq3TXSZA8G;A^2cuG|QQjPY9MKNo-`4A@u*GSQLss$5s- zCvl{a(sW#>-kGhf(S9Vy(#H{vQW#R!6B`0LkaS{h3~QF9rOzbkh`oh?Z+dnzDYcW%)O?*9wRDR-z{M0^a4=jz$`M z!b1#ujJG~YJAqaU^H+xmpMY_>*(l>^PbtI&i7DvFy4s%(5AN)#Z2} z^RVDM$DV`bN|N3i~ocy+KZD$q*p0?H2yNI#vMgo}WkF1iIY6 z5uOh#L@t-F`wxh&X$V-$R}2qF)IVOpFQw6x-y~YGrF!Z%z5M3C7mb=xwrkYFXff;M z!CkO-j!u~nf@n~#l>1rkD3a(b5eZ&(+GSxh&Wk|v% z8o0N%w%!^{a_B-58PlNzYe8M2ge4Ik2z#47Bbw816O8z(sG|DgK@_&S3+pgDvF zDyVHtLVr12f&L}3NP$0Gv*TU-0_NA)EJO}k0#kP4=E^8=6mS6w0^S2<$b{cI69Pe0 zv{T}{xB2>2;fJFMOwF2KJx~K0Ko8ElENjdey5q>t)P{SRN=gzF*sMS1 zZR~`aPz)T4&|e+`;P4%FZK;}E{6?%!;wk9u|D}2=<_FM{8jdZ2;9A9};3S@5&1+=KO&zJHrUaHMqNtk(}Y@eFaI-sMp z&hfM-Q`72reJ}pshS>^RKoS^#aO<0uQtPN_Hs*M9D9rT$h`r1K>G*Xx@JswUfO7PK zVzcERt;98*U8BJ+P_KkJZBLDFYdPuV?Qrs7F0S9rj(o^z0FuGWGal+xTxq{n$jK`pDPVP8n$v;ljo8Kdiokn%g};Y^8I* zE_&Zra#svqrEUx{;tP%6YsYR*2c�ljNKt#2DR@{FfxF8<)@zAElc6019M{%s2F- zp%JoD%;4s{PTNY@g_n^L{9*LJ^ozLUD0IA__gr`QEKquptT#8Q%?aH|=v5?tRQlT1 z^?FX?-YwW9Lx?X?WDv%urkm!Qw1J^B-~bmHvA_Fuc-39L?ittrRY5@k5Sst$Od_Qrs|D!Z^IpR)49UDbIS zPfa+*DUmc8zl=#9AUNUGE|l+j&U0ma01#MCVSsUm6WAlm?263quFV=YxpnC)LiWQv zb)j>CVsJ03aw{a$!vC13fwHXI_Lir)gDQL1c;Fm*O@wNn)>462FB?m)s_qIVF9K>P zjerC|jj?4P@R61k`Pyfz6$f`i>XZgBvEhl%IUNOh%11zm$$oYGCwsRhEz4ZCF=f63 z`p7LrhWoea^qhi(53Pe@Uia*Ro83vfg79c-UFpxWZudRZCRh$fZE9Y2+@;3Sm z(5nJ|RW1V3m*{`9fEC~0k|JL~NL~E!G=C9q7N`B!;i%YM0|g<&JUQo+3W@g_gH9OXoK-11VbYh*8!`&C=$|6QbV zJN^CrO4X7V`ae;*`NGQzfN#b)9|XQ=NR{V2=@&oit$2k~x!oK}EM$nHi`0_Z&&Tpa zoqF+=R`8Td->ESJ43+E1B4`dyf5Tnw)xd5wJnyOaBl-2~N!k_ovvflkbsofNXUMQ$ z`5a(4N=t*@H)&UV{|>MozyehgFVJ?tQx~uYC}Eh|_*Lcc@zmQp8!TQE(8lA&XV=t7 z6{kN<7qdAxEYf*yj{JqF5hNQ{fo~8hmrOW^jW)%z&qnCL0zDRX}P#W0bJ}(kb)Fl%Y#xSlfw9R@W;*Ti)kxWZ}(nq z-OU=n3;1QC#Q$TH{`=_qX&_L?V{!m}@G)$;|!1kEvwDZFK(?KjGJ|IMNw zvP`x73D3q1UMlrpCNwnkw|CQLluu5XwVC)JLrzMs1(pW0U< zYmS!y46<>0eTr!!9>fVwcrS4Zv4sfS^azTAFNhp|T?oPLX)+fbw&pWratDo}huoEx zE*`r9a2aC~DOPxTQQo8B8pNnQmKXT{euRB0Az+|U;_4JUOV3;#=XebtaYd%Jp^kc^ zzJ;`rgy@N76fw`;PFlAQB+_Fyt~88R+&a{wUVyPFpHF zsozlXAB2&4*%OnL)lncrT5FHejYFkTvjDWv#inU&ScN z`Jm-1Ju;VhXF^;x{}1y&>dn1Qy7TKpCp)H^y@ShU8PC=`G=gbbh%bb zeT&b&Wft^5ZAs#EhfISt+4WVi7%)?pyh~EKJM1M}a_{bUm%PiD?BDr8s^O6Ada7lR zhe)?sM@e>Iz1HzosG<6wcb>JoIC40jVf|^VFtF-pCiIou;KX>h#?j5Rt1p;5{}=fW z3xO<|h_293q@%Z4O0?IcA5f*H?V4~a#H4^am6^{XLw&G<@NP{5Xg8d^%|`KzCER3YXrb+Qx7H zZ>xz^FtX|P0M>3fPo&bV$WXWvyvmweqSrcMAz^!u552nn^d#uD?fCIw2KRBXxx!|d zj!NqvVberf<8KKmeL@+V{GavieV+LCFnk!vUr6@dNFF~)}}WwE9Z7CgiY`! zg!B}UKGSliEillL5zxH#%@Bz=n)f}bFNx2seTu=c2ms#&=B#Z3Ae^A-!+4rql(!gr zY-wrsuA}LwWH?qud3kq7W$6KcZvr#mG3>+`DoIcX0CeQ3bPK646ZZCR)RSkc+_h|+q`26FvuDDc`4<0Fm#sa%`H34l z0#vR52ISRpt%G?X+A^aPl|*IDD*D6n@nlUyW4UN8a`Gq>mS0=kEJTgnP94a(docJYdG2wes7OcXmig?R5`D?6NUk64?y-LG#45Fk-7EjojG7o zr==A*m+=o@EM)FwA_`&tbTrv*Uenujk`n+jx@_lZGNA0f>CmrQJt^R&l^7t=1*Ia? zAqWwx(KK{ft8gYQw8GF8}y>Wyk0);6nTdqbLWaI(B)>Z~j3vgu{WzXVM{^ob})8qjhfN zHh4wkjPyhxcygfOkaRZ2nM&|j)ZyTzQs;%XS>g#rkhrx1`{Y1%Hdau|Bzh7S?*9+o z;+kTnsukJ?}z*GM1e6Zt?PJw{S#g-!*dHz45-a4$x@97>s zfOJWBBPrdXAPo}I(kb2DDIJp1AqYr=NOyO4cb9;4y<0!e_x+teye>kx4}12+nl)>z zq9v%%M1|YifFImK;-mp`=3Y^k{@(yc?E(;_0@(osAWH*NOaCFGs3^24G>CyS4njHJ z=h7JU!Gsv$h~;NH(D?c$bgHaPQQ=dEx<0xwuwhgCZVt+Ww6M>IoU+T%FC4nn@D2)h zZQSg0T_os;hy+OekjhgErJ>DnY0QwN0pk(8qZcnz*fZqcjKTBRbue^ZD&(`A;)*Q+DM)=eJKm3J`r7upOd|EjS0DOpV^h!)k^*XDlN zF)=?_eE6&#K%`<$f|)UX;=1ZqtcPq!5#;|!z$8Zdj8=kLg5`7ICb(izoxJ@GAM|-y zUx+LAY*yx*mmU5av;&QmH8=4=j3|?;}R0XY}JOAV93P>*cdS*{GI1Q_@o`F7dimc9!21f{|g!qHb8LjmH-zb(o zpEzZ`>C(IA^;mPF+RMyO&(Wf$bF}|xWz{^^IJ(GwLN}b9gY8Gq?&ND`&u3)Ml@%3j z+W3d8B*;ewr1@fUt)Sl~WLrMlnF>IJ*mi(K1Cmk@F39WJ=p4R!HtPc6`%900V+X)w znII%5Qf%e*0MeUi+)MwF6ax+O;^Gr6mIv`&7r!koXK`8 z&*6!CRKmcJJHV3bznIluv)4o@r$YPIRxb9r9?J>O#0C&f1KxpuSUJBJF-*)EH1-TZ zSlq|^cMqg9s!*TWgw_hQDaQ~$0? z;!&BAu~+z`%X4S%_3^kbDWD64mHsaxxnNf~Z-<*)S{7WAdps5YBlO+AqkP)5)UP-G zS1Iq7)&!Jx(#(+XWZo6_f??WQ7*LF&1Q`&@(Zr|bw~zB(DpT>k=kX%XW>d)uq{V|8 zXd6aRFqnen6Q6I>EeA}ID~LR*B)1yaJVC35P?8b* zGbyk7p&yM1m=21FZ7qxus`ts;ad`;4B-Rvb^775 z0(bYTs|ezI@y0hY)|Ccid|&P)|DszKj9qG5${(oJkljLPt0-Gbh&kBhCc*SL`y1%q z@Fk%*R8F}-anKnCdpbCvK68?O$<^24P7CVRQUx!`TntQc%&;zy6V4%Qc>6y))N2Fv zcVl*hYJ^5foK^dwBG8%a)^H9~wb~fsiZp*mQ@fwUInJA^R^AY8ui$$6WcCVq zCG<^0$730sxxI{6fEG*soWA#aN5ue@=RAyM;opIsaXd3ano7Q|op|SZZDrIipF4(3r zon=;*`Cqn+tp`&+CYI_m>hF7mhAyk-@|8V*FKx>FALcBbksnDkXgcM{q)FgXc$XpY zd2RUUnE>@ZQ9v-9$d+FH+5Ci$(3Wxbbo^L-^yvGQ*t)xOsnb+*(&EJ5tIGV^IzI?3 zB_Isma5bo5v^bDlqJ$#Yr`(|Nb0SZqbV2FG4%MSDGGI^1hRZEGB)3O^0i4vfT)$6% z3%Bo-`tTY~u<`htv=O6HVX*qdDUuCM+70dbl`Ud8d zB5o*H@%3a|pKT|j*!j}$4&}>EhHz+Zu)PHw;akTHi5IG!ucC%5jg_+jreOGGtHokh3Pu&8A zEfGG0U{8#0RM!F6Oz#Y`KISB4Y*I%LD3V$jB=Vz*ap$@@`rSwB7 z!n~n{@cxkctpZJ$`|!nZzrI}(!WOYk-iQ? z#QD&P+WA}U?|7~giy7C$Y#sf}!9WPHcKKiKp9Oo0SUTEyFK`tHNja#=_hEwGsm`kK z!ASBlUcDP{gGx(%v)pUSehhyqHMi1ct#`W$FerrOM3CuwvZyX#J<9_&_W}vdF)(v4}ESMiA6@?MhfAIiv`;y z%VzYwxK5#~oxWZt~i@&FEh^oMwD+d3?1HZ;nTv2-#piVzx z!iqa_m%$X)1q-u1h;2_dfS(vW4f2{G5z1J1-VN@K@Ndq)Q>_4B0zL0q4?)s`$$c=Nw{-^eDQ2+& z&2i3&Cf;9;wCZiYG3KE@I;fl5bgVd9aWKqigLY6}wqgOwmB#$FW2EPRNyoDL^o7Lb zc%)+Yl#ZChG>^&GMFpn=OONK_w8GLVfx8sLOCoX1gL)zsJo1}SFm2po-c$z~B3Znb z!8XmV&(@pO5ri|#>~sI4QCNKWxw?)X8u-2;+B03r`4Eds=PdmUGMdwakk=tRa0=>(b)`%W+Ohg#NT zX(o?dz>Iw3vV;-92ia4$B%l%E$c!*~&mc|6H|{tT+|)<%sDBi0X8l53S7;Vp@0)@a zW3H{a+fAw8Ln@+sjr2c#PNb3`h9v@m^Zg{<5YP}-s;CsjU#TSYH%t%)#X9v+OF%`j|f6?LKdT*w{guC#`d;GO^ z+0a~ri(F?@mv~R#e(}#a&PlupLI3}OLqT-+mw*{l-Wmg`eG~-k*6ZUjlY3S0DchD9 zdAYx5^0ti0p?MIs<3&soKv^L&;)==IFl5TuQxRQWp>O?~)m5j#On~`K!AJ=+K~|v5kS3n_K?B|YL69i4!zq) zF>C1NN?n15H35ObQxN*iI9yL03y)cgDiBZ`G8>zWPX<7y$Yy}=mb}uw=v@DBwwcH# zK7M)~y8&!_&U6^p^RwokdvEG+@&(F&%#MoFakGSB6A+F>9e)v6aZYqM4Tp(64cwz7 zr&8S;rz-zToCve?@dX(lAe1RhEKE`SSoT4pkg{_2BJ~QlzL@ zJxNWydQz%R!#TcpW&PI<0XmdAcqsslNAuJaFGBDI;Hx|}W`(AaoZRHh>}(}8kq495_{I1U?_}Rp|YD4|zWhg<) zNcal`(wjs9zNHJO8vN{rjdKWPRsm}S_B(1sC;aB9UoYh*fn&MwwnFG-zC(q@Z~xh! z#nO^?CsWB}iPrO!YDXVCpgc(K7 z6fhJn9J0MaANnqV_T=a;mmDyl6j?Y$itIT+$ZjWZx&S%BH9D{i6HCKNe37zPj_53@ z5cH)$e+mY9oX|kACc2k4?q+H881#o_O2-=<_e-rjCe8F;EHpb0jvtzIl?i92cEUbLU5dCU*ec&#F<1)rX?=B zxvzAL9{=iN{WqDYDk@F4WMw%M=uw)SkJKN3g;W>z5oT-)IDD6|X7^0^kBCXkx8n^z zw(+HwUr|b|+?Y#DVHSl$tZM{p)6OSaR8-Q7+=90JdWWoj>q zdkc1F$cTNeGSO!;w7mM_NLBeVWewcnGqTcs4BeJx6b;%?9gA($h(oel^fCz!y>x&m`4Ykshf72 zERE8}5j|eZ9vzMr$0rFn^W^aNiX7NIo?fn3y+IApt_Nbq+cMQIMz{XM2iG}P%c}|K zkN+#D1oq5IE3K^Ge)67oDdQZt5)!!d9WULEyPQxuw$?&Jyl+O^9#v!zSXdvaKmtWBOP0z%JRQ&4z3kMr^`1n?r)hHkw`=7`lsq)3dNIPjS363D zD&W2D*NmHS;-dt2e%o~?CLNx!f=gYi7q;@B@e2Z~fS~3?gM%R#;)J15j@i>K=fOu& zQ5COYzX}`D!_QGw6_*#Gi8uHTW(r@PM|4>qVTItMh16@8O3uYw>t z@KPC@V0T(-ZFc?DgC!(41TQBSEaI+Rglz}3vbOx<;^Ky~3qi5hxL_s3o&+g`ZoN;L z9864*egRF%u|m-4q5~O*Iy~vRPivNZfnrUpJwsLiLTI-HT%WTao^l@&$ueq=2hgOjZ!7y7Jh5BL)YNhVeEU}EmUQY>PP)>?p({0Sw- zRb2n^2Imun^nu8v&C-mRvE2LEIggV&vWw;Udd%gYAuj(b(WEgj9_#kmo1SJH{oBP+}HNxl4rjS&py^wrYY)S{GCYEfp-1#bck0BB3p zYs;&uQnPG!7=##J!QO8GMX_Kc2PVH$`vE{seuwTcX3Tyjh;HIFw`kwJcwCcj4wNRq zo*f!tMeImaQq4V4VFM@VU?^AU9%Jq_>)J)B6Ps#H0Me;WyEK*_@|Uq&t+BEc7a>`E ziGUSZ-gi<_?N%H^krmf}2AmTh?$!zOO1P47>2TjPLUA9KT{S#AayX+oF7Cvy|-?Nil|DEybDdMHXv)7=}7C>L? zMEPc)TF70rW*tzAy>%a;>`05Q{DLn7F)>u{hKu+wOauQ-Xk~kyB>hKcXi(UDQ{97H z5*pIOGB?sX<2>mUwl^+un`PBocF0m8qgO*h*)TzeHJ%$;Dw)5l@ru&WO2^%%>h4L0 zFV?bkk(H$pJ+ZzFe|THcMzW0YET16a$-bfhe<;8HnTdGFfvX+wv3??ge9eWbidTNOo0*j$mwc4UR>ETmsa1gmB~_4}@I;TA@RyYp*5Z!94$Z zgDQ63;xXx4FMJ6T-g%5vs68;PmG1+`HgM+u{rcYfJI+5sW7G{oI@bhWTlG7kcTyNX z0xmu+AZ&br_TIBg_We%)%>&Z_dr!e?&>0U$eBIcBW*=mdHzB#44(hCHPZbh4fH{&-4AKCdNlx3f+H;&z*v+X2*G z?`CD$;hbpY$G-$NS0J|lQa+6rII9SqFpb199~8?Rg@4>~~f?tL?d4myxG!7rBn zFMQ!uWNMkeok)Kl_3qd6uNiX6#vmNhl?edi^u5=PYcu)i(8(w9V(r}TQC4C z*sSrmw-hqr?W#4KxdNIfxw}aroeiI=-l#Ux8Cu@o%0DtM-)*T`7H=9lzdrQ&JGQ8U zzi_Ti)#m?s$?u;kgML~D()1$!R}9dH`<#o#N8#^=B!$urF$PZE<^+pYK2!_pQ^zp> zrD#rnubuxG934#pBej1n7#xW4TjyQ%)5)p8r`mz`a|WC+e~Lb1;ost~aSxsN)1{$9 ziNEynaC3u5)hQ;dq%U*h8!MSUxc%FjJIz@KPoUR+T_D&9ZxW7I?uDakqmJBU1%=fJ zNE;=^f&ni+`(mvWGzV6p*2qYhqRyR*)Vu~6AK-`txqd!gyl)Pif?Ltk*P_{>mKSFSw#QliITzwmQg>3 zqb9oB5XiTKCfYM$Xf4MK#%h1vY2QaCtk?{v&_4VV7=5nE6Z*Ep7vqJJ5n826OuipRHVLKIR_395;$$$7pWVOveNt3C_?7HBNY4 zIb0NYu|8rwg{;=dY+abyqu(H}vq{_{*97ViRDvYeEm3atO zkpP4ubO@OX9i~i{oP(x5UArCIilHlTNWkJXE+aM)P@#MQrr@{q;ASG#Xj`DM(IwSC z2RK0G(4J(yKtMxba5x48ZCFgqgbz;a2wWv~;aLM2@&)bLc(}MRG(e;CWo6v3iQ+zn zgb_Bwi^1RmUfhWGFF>GCiAz{&eMP(mPF?0RPEx#ZTgiAlm}>!ZVTO?;?6L5AaKw_w zGL(QwVl@o6OhYMbz`L;y3-=}@me|DN7nwf;0>e8q_Vn2%vX5ze(ni2=v$?@9o-_x2 zglG_ySh>*QV8%?_JZ|Rg{l~;B)H&`Y{tgDxuD*-p=+@Y*tN4*?3m^E7GPVr}EQSIF z@SZ}pK$A_r$lstbUqycF)iSx?=6l@0j6_;g6y6UrWS2cGyfR1hvehi8#}rM+e_gXl zW3G&ud0mkKP0{|7y{_b+rij&Zhq)eUDU@Dyl(Fs-94|W^^%QT4z*gAVOxLQ_!)lfx z4@dRY#p5!I_o$TY(URqQS{BLlvvst0TE)&a%WTzFow9X3Jtm%FKo|C3H5466laaqj zsAF6zc2pl{uGV;7j`ttpR_Hy}Xo1@4L}r?>s$uzZJfZ{>W8V2O2s-%b!s3i?P>%9W zxcVd7ZTYH>rT+G_sesrY4v7@6gU6MH{B=KqYX!njly@b-0&Ue&pK}{-rHmfVHN549 z-3E2hOm#Q@qgU5{G1w7j#!x*h@FMq|$M8-3hbA2a%;46)wcij+=A!bTj6sL6O^7(y z%vqE8S#GFO!|Z>3`S>Y@2~(xB0Fm&#}g&`{@y2%fl+FsEVeZ z>fk7drN}A1wEvbv2Z9_P0ne}+T9?93pj0f}SMk&rF0cs2MGW}%AlPXlbBB-+DPo$9 z9voNzI)W2_kjS^y(?Bt*5`uS&fNg|`6Z*9F8tsU#+onbFF z9o>o~9$qHPAP(hzw*A@$-!tYPOEZ$M&k)p$@6*j{#2S^QEg8Gm87shA75`<5t-swG z{7~(w*w0~rp_~F&0_K1uF(|__H)so8=0(zx~EU4RRM9^_Q276jD zd!}ls!i%-@(aN)WR*5S*miQM{Vwo&QyWEQuImMCe7;jeSTFYnLzVEZww~!k*ZBCIs zL|%)R>$$sC-PtZ?)Y<=;LNo3KME)N3@A7{^5w9s409aNL?+|5=LUnRM49SW0J+ruQ z^Ofkip|LQ+XDJW@Fy@|3Plq>O(;oghJ)D}Do=!Xn;-aH8Ol_ucAMU+&Hzn4~vRAnx z`DP9UYZOf$KrS%Becuu~5T=+=nnseRp0&K#yf(Rpam$%#<9L-lDCW1W~xNX0Gv%)e`eX;}WtU%T?8Iz?;?YDs|%^jtK zwk4UjY4Fij%F{Z(8ccDcK5AckA2wlv9mmrA@9YLNHEL~iJUu;KU3pTf5o480;A1U2 z5`L}C&CQi)R3YqOzNIMOgBWtd-+C)O>V7kD5FFFpkuDm|mBSSw7gu^@G)D5|kJ}hUciw zDb}wl1$6kHRdtOL7*vZ?3YGF!Fm;G}?&}UXq6#NzZxA7is;0O&I#bTd_={zCpN&>u z_Hc42+fvSYHWs}MP|%rjxH;y%3&dEep=d4dnr6R?Ux!UoH*`i0%8Fb*POPeXfW2`! zoNc|^mZdw=H@N%<#O3|pS$8q&+45fZ_7GAR&K4+S$tSb|6T3Q^@5(NGS9F4q-P)Sf@v$!jO&^$@wY9a=Z{ntstel*`Oojb<@Q`rMsPz&0OgYt>LWUrQ#$#m4< z>%_C{(IZ3nd!JEV!do?%I}LM)A3#rPa)ddA44nn)RsA_7rQDpx{gU;C>4q}TjE ztC2}eeR;86Knc@^Y7ax8`#&y#fmP!HnX-?!r2fjwp8K81iP_+@`OKgM8W`TrDjOst zNKLWXhEQHqjPqSq&N6Pn)h}XNC|Sx5OpGD zuNO%(R#ii^_}>`6sCPMDXa)Ll39hp3!(BUlQSVviBv4C5HW#Wb!BO^y7IC;D`I0}# z%=d!T6WCtwjJ@34k_Tv&{NHB8$FZap6Dm!y@F~!Tiq^`5og!dA4rW6hy{M>Yf@6nS z+NRw3n!ukWaQX`lkj;wyjS)?<@t+pce+3J!sC*Xg|%`- zVWm)FR1!WpJU_;F`6_EI9`q`kU#vBmz#y3Rm<0;R?Q1NKaKm=v-|G327XlS7r%4h; z1HGe5D`-oF3Xk^_D5{Hy+@TS)55J;VO7l0i6F?S4EVt~>+Onuxeit{}y}G`}Ql?4sRaeJ5MuQ}L6uDhXSDc)m zm;Od@I8%CfboBkZgUot1Oq`9mRrBRcqD&Bj0vZa63Ik4qvQqi1>2Rtzc3pF`4n3FY zNcwcK`e-^|m2UauIvXpi-!GM&wKaXP*5XrkxlZHPo+wJEJtPZ7E2W%Mr($!{CH>g9+HHvB+OYp?2ym3S$N-Hvv99BtL#d9qp~@N#h3pB@$|@N-Yl zQ**mUNb%dWd(d)ex8iXo=B%##zWEWHI9Hq`r2HN{hsDK&*c=;7S0pXZ==ad}eQpD9 z4(`2yXntRfA0Kx70??(mZT%>LX@nXerr8(0GcUAyDs zlhKucx;P0+~79hrt&v=A;XD3$RjHJ>a_h(55ArGf&vN z5|)&NXH!d!!v6!DZb(Q-7_=iL{HBS+5^$*F%c0;&_@&_B;eq9;0{a_Eeg{v4e`{>*t2b~T6OdHB{myJq=V*v>iBaMMIu{P$BQBlJw93h50bJ@)vmljCH-*Thj z{DnD4<}7DQ2#AQZs!UKlbKGs&({^hA#KoZ$9`aEDm7v0z2g)k!`<8uq2yMTy`~z-n z?h1(me4@bAFSn6k`gE+uNoAL z?g{tiX_@Z(S9fbo<}e77hEwZK3y>v@ZFJxjl}q9vbn?bZEVBR4Qr|FdO~%@1n(C1C zn7YqQ8_2#jL)y;%j^?1HMb7fi;QiiZupUULnpS4tab_hd~wxjWteeY2T@<<;g z#u5<;>+>@^m3VCqMAeqEyI)2yyaJM=<;a`fI(aMta4{Nb{OD~iIE!uW{HAeZD71Ho z^JSgnR}Zzn3lg56Y1^NDt{ba#eqib*ftxe6lW#S`RT!go$P$XUlPiL>&P8N(iL05+ zNnpy6G~`q=k&FQqm9a04mwq9ftaWW4zpKd-(3_lQW~-&OI5sx+`*(!_{+l;%Ua%Er zZtd;ufy8>IR7+ByP}tSg)z|kql7Iu4s0lbsx~9_7sHK*za2;?;zsx5Sl(6UCu(GlW z3TlIF%EJSJ63Zyhn&NzMa#HkTI)m0oI^RY0tnT5-2@Qi>AcyCb)%k9mftS9%KG@rl zW?iEwa|VgKZfb2^<&={t6FxYwwzSM;h>oo9Czq|NL`^SxtMvK?{2sH$g~i3c-YoGk zUm)PT(dO1Vqg`cE52#p>lWj+`ORAK-8Fn(co0luLbq zC7VPFH~H=K#6=i&H9Ye6Q7l&qYeDXgl4)esHE#u}wz_tJ68S=cfpDR%m&m!6tN&Cw zRO8ENg~T9YA&hf2%t&$fhs9NHM73nY(yl(<$Y?m!)8RARCNxIku+ArZKaNH}*Ty&D znsXJ_^#5i3GR=~I_=M^icf)3!y;Elu_iAXi71lh|GVC(aC?)x!I zId(m9{oKoPRQJ5nIbUd#_Tc3sF7UUuaIl`D3>{WiV3^F9df+Oo&Z-LG#rg4$elV+B z`HZ9xx|}h+C|uTk#_lov+o#1xsHyX|vbGDFyyZ0%Z>`OZ8Smvpp6=foBrPMn|38nu z;1;I4Ut)cS>_)ZuRw`YzIriK$&O$+HF3+s*x0;5bmh>EzeUc!3=wD7idawX%6Xcu;!AO6 zSfsah_th>;DmKSfLugX)*-9DzQl;nq zt&LQ~wYq~B^}5(S$h}npJ+{AhZ*SsKrRA0hl3n5Im_uqt&r2kO1Vxz|)xehj(tz>RQex*=#0`vj1M4csn zBTCVfNpU_7VcNF#p~hU$Kx^@$AV<_MRv!~egoCKWKkQMC0x8hJ1i3sDb|~DR4l(-2 zkp5JXq**UKF!x$haplEHCKI|}4D--i2Bc5@!QFQIRa>h}2|w>vNJ9ETrV=82`*+jc zuYN7t=1UOJB_$=nl?6`x{_d^^IPTqq5jK#(IKM8;N|f0i=2<;DI!b3V>e<`-p%hLG z^t|%LAs;@AgFK+u!qwS%Tte{%5jJQN0Ra%?#Bji;HJ+1;Q0glLiF{3$df5du;WV;5t}Q0%bRhS7{XZmC}T)!Sj&M|1f`-rvfsX z+l|6Z+S2IPqX{LTTimB0*BB=|cIn}Lyion?Rz){%=R4XMA$Vvyn9tDV;9b!BeC~-7 zoC13WLH28$T~=UDnoc%c?u^d$s{(CV^o{d1r-S^#Q2hrtw4E%sK6vlnjb1T_6q}cv ztLdY?*Qw79)ekb5Q@t$u59VoYO3jEkglv$=4r}%3pHQLKgJxsoUBrK)W<9Y_>gqUh%q-|y~Y8@E~oX?6Rv2d=!nxw^-KtlJ&U;6O}g;B*x~3v}7kIy|Z9 z#{6I9eX40+EjrS*M*o_*OzIU@IpSs(!mX^acJhdeJ3h>s@9us7gM~w=5zLK*WAWuH z1FuR`U?HquifHc5`YC$V;+u8EM+qkdBP?m4ESK$?lZtVJ&KzUyWx48kSj$m1-OD^^ z*fXOeyZ5bR+sY9(kp&MA#UC}kj@UNJgv=5=%1RN2uOcC?`O5m6RW+S9ZJXnd``Y%2 z`u{aWUiG9_^uKm^uv}s|>P%|#$qx^2X4949b;-*p3^OVZDg0Ojll3Bkn0Lr9^J~01 zHX#uN=h%7|khDie0r^4l~1b)*x^Gcz?He_(5PRVSP5_SZU) zMCj6SzfCJ@bNTDYtdq+WC*-Iq=W_%ZP9jWN$_P*pOV?8ZD@~u0B_M~;wWL5NnH!nY z8#ZD$oF5dIySTVq{rNML%oZqvhS_?ux0hXUj)+~oi-ZT% zOp}mbEjdHjx-wb*A|iC9u;Q+PGA0@7)lBw>14LDj7osMtzv{d6J{)jDBZNue zB`k&i=h>>a4=#MpbK73ny~oem(SZC|SbtlVV;p(-YcEpPpi|tysvfD0FY^*>{DX38 z2S5Ht7Q~_EWvgmT2ie1gK~HPy2ih213^fY4Q_ia(3;b&N(O}2amm&+c zS!tQgsBmx>j4n02^Z910@+5A;t;2smQyUS+XXFIw>Z&J^IVmepg<>q+PaeQms_b1~ zHyD^AB_cXJJ|+PfDZb6XvTm&nNutux{=WNW6weQRs+0kMtk9Qw8XJE;k@#Q_YCS03 z8P-UU+bRdio~(n6v_C?QVl4rTUtpE>zZ{mtQ_n2^eE}l8}8xDo1we$wJGr@w9u>7SCY6k`I8WDdGbuG#ofYv)bUqNAgaYZh%xioiBeKF1vtG&CiWj_14b z=YzvTPZ0Q^NQb3y4lgw4J&^km`kYmdB+>$T0ed{wpV z*~^T(SZ%j0*|Q&mY1ApYTJx=^#@8>D=ODqvet`EMH8Bdje z#PjbqzHo6|{_OjRnS4=;l5ueC%Y}sp7g+0tnL22aCp?|N4y)!nsxYQ(hPBUj6Wu(=KT`{Rj zNgIx@M~Cv8e4lKljB*WC10RT@UwiBy8E-;vjV9RBnkm@%ocOOU|(&WM$PM_@tB?V!G{lmQ(!S zDSF^Bo)(zsF9&E>Wn!Nf_Tj_)SlUpch;@8r>ICS<(JodFsxWoxQjlIwX6MK(Vr98d z@+x)ya;nFzc5HXDZCdL#-7?L&iE|Wv1ALbA*WS~zWh{tB-@nZfu?%4DL&S{J4>e|k z*}?~e?s{pbH?ejnx6wJ z6-_#AYF|fa@eoTNubb+XTU^G}a3os_?3S@v-bB$~)tV(vN+HfZSlP$0GIu*?-*raa zxo$b`noA1xEg?jKrBGJXHE?UCKOZs+aidUnyH*$&KMJskAJOH$>(pZNN!hxlX_07;iR^p4|_l|P^m+j;J1AYRnIzo7_CZkR^Hy^@QiQu_&w#cSs z9fS|(hZV$olw<8p2corDErYuy1+I8HgQ4+zd9PqZ-jZ)AE^J)G?KJzl+vDqPXjsMS zzNYruj;$;x-VwNp^>I*f4$u~g$qzMF^ESZOJJEogV4ctRecaOUYzVKvb-PwdO*fsn zc-*S9aHueHT(~q6+379#z}a-)5Pl$WGC5c4i=!mbLy(EHWZrOZ+^F-f6C-22pX&BI z%OAT{U7;JXL$EonhdCD`#s0P(__`|CcumKK0+Hl6hll{a54fXf6>l}m7r ze?RkA85@Ma`}=!%IJh4Y8=&V_Wo5V|g^Xh|6a7^HVffY@d3)Yzr{*2U?+k)w+1^x= zsJogi&$#(H=~}dfcR5Das5`Cv1!Z{4Ey#oiXCU%jQH%0I{Ve&SxePY@rb&(N^{(OH937b zf+TNF5&Czn4CHfGbT?x6x0U}ezp2KLS#nT+s6^gUZs8a-{i?*>0FDut0D=pjPdd=V z%Zlz~HE>6s`j8!i4)WVM3kP!xf));@_!|Rt5=Ew)fF~1tvSZpm0r`8vDJWCDTYaZ* z5~gBZGNFYb#5!`g!EAoJl$(60)k65m7equFdm8NQ(ZA!V9*w0N`aSCoI(`vFOsGyS z+`{_VerAJ=tnIYLzw(#*pFeLIKS zZ&Tri{58qAx0K=cweDOwmN}B4u80jJK|(XNZA&!a<?z?)tZBV(UQK1b;^y9;f? zoy(I6o3L{6Tb;ZSvU_njsSSx}g$cA59-Qf+BK62?B8aYJo%PYlj}AP;^4^@c`qn<< za#Xvc@m4z3JWwxxzy*-m;5F(D+z#ISMA<9WdSz34?qd^_6%F+{srO`MfX~SgX9F42 z@1pa(a_L_kUk$q#_cwEq%)dlIw?DcM64W%xMn?pdlOPd6LIo&)<`-41$XeQ}%FLAX zD?a3kV_kX#Tm7VoyAO>~@jip1I4w>AX^;Iu^AaNbA5)@P&$=u@;$*4jIZ3`NMW3Gq z#mq>XZ?rEz=tI|0A3ry9#pi2(&p#|0Vsn$&>gg=Ex2%zS}s8JEIvz z;9yKkp%J@g(2ARZ00E7bnW==Mpn9JRvb}-jr#^F1=3K;$*XbOqc^xjP&UFO&qqQZg zFnw+Fa(U9j9mC(N)HCDub$5D1;po&E5=TblA)TF_%A9ySR8xX)??4F?IFpuTD_9kw zwK~z~l&?{hGQ55ZO6yyCq-F=BLe#H92`V921-r+>S(!gYjEY={K<+vsYhfvuGrc|o z%Y0N=<{Gp;DjPr=<#F9&^n(Ze50sm46df{wz`n^0^3oPmh?n4+-a0p7Ak)Yn`8~<3630^OXs@FoLYaMTMieKB+vx zG5*Eom=vtv#9FDol6LBZqm9^TkJeHO)3L5F`~ zkX69ja~y%E0Bz^oT0Yj{pgfI9>E>&TI1{1ma+JxkP4jxnR}Mi=q3@-tbE3^8KEu8R zb=UPqrMtd|E0%v6NYPDIim;#bwEnYquD7s8ktGO?f1*Zb(bu z(qog>@$n*PmCyc7zuo;uuZp=ZSW8A8c-$!27ousXvnNhCscaL_i4Et<|5xio&Ay^% z&0~!kz3b0mZDEL{x7;{q^%0YTfNTC?z?eWnFF9Wv=3{aVN5X_w&M1m8I7hsoGesW< zr_}v3)KP%rWranWQW`1Z3z1X%d0Or$6MlYm)A&)!f%9~|2)QHq31nj?j&os6lABuS z1sMe*p{oc+^1pf8E6ZgA1?bw1!eUm<#I{_KrHOvFRkB=^gg`sGM`JsN%o}@$)G&KT z1vLy+ftYV5A^ZteZxlGTV_$JHx3;XTHyIJ~ z@z?9VDcK#WvgLX;RCO=C&O16|C{**2wd(()=`4fd=(?^wxLa_7LvVL@*93PD?(UKx z!7aGEyE}mZgS%S@?(X(=?&o`}_%%~qGc|Odv-Voo-e&`+p{k}ub2Iq13HEx7uT;OL z$)X*?jvf&W_Vu=qziYWpZApe~(Y|=$dWx|$J|2Srvzwyn*LT&3n>)Pfl4{3{OJH&{ zJr|rM=)!{1WObON&b0&UmrY%P1d%sKb3}aZ=>M?*tHt>k6a-#KHLY9*8#WrJiiu1< zeQ1Lwv40isn3^*w2;4KT>lL$YJld~jD^DFec-ENQOO*A38n)7FlpxTxTgjsiX-^c| zzy7D_ykqIFyBx!Do?f(tAI;Mh>ryK2oaY5J$6c@kEoRV2 zHX~c#J0?x|lE9C-^~Q3PddFMn?`R_lM(VUOvxGYx+iZP4+$MTPoaCFRi*-4HgS;*S zw+h-FsZ6GyFJ&qy!desI7^Xj)7dEZY?qt!LENphkgF9vh+=vzP#UihX_)X)xRl)sD zD+&8ytZq?U#>RM?)H}XI-E$2fh8u=1tescR>$hHCE;bzR1r;({^i2JokbHRC?q8rk zB17FBmdf##ancY^uNO698;#2^MxGUQoS=Q{)wY#Ev(P}xDI@-G)kl>QzPV9||9SR| zDnR)h)xR{FmXiVTDMJuJOSAC;z3?Sce+i#lpzbUt2Km~$d804;;8+Y}-!4ziR05XZ zmq{`8tyF;rF++3c`J>zJzU{*Gf{$_6$}rT^LdB@jlIslW%f0+OI9z(qc9KPh%v;L;~OyfM`5rkU-WGvS(4 z|7kBvRtP%7xY8Peb^L-iyL+Ez>??j|@_;VvMd>-pO!U94L$^@A@4@7>;T4bytLoA` zcLJJ3`_xF~!}Va`U?PtvKUVu(rG8c%E`MeQSr_&*9A_^xQaoj2f39d}Dkli>5BNn0 z(8BY-H%7zp@8KUs#(hayhGq&6x1Bfb8>?OV9tb8OFDS@zVxuaY4UN6oZdrBAIRg8M zGBW?1_Ckpf?=D4#jA=DLZu%O8b*BySapCvIy4X59l58(|AhZdvG2K`0#$P%(zJth|a4qRPa7@`EG8m zt_MTcg>-sWdx2xf{5f)}C+csKTdb8WncDIVtYgZHu}9urN+m8uDtXq?9Cck?en;HV z8{b#H0UPzvSg`&~(|qyjf}=Lxjq>MdN7B1uT-%f-Z7HbG6s=60=tgLAgAjHTq)$Yq zEKDuefqvGX^9O`LYEHxP@2*utkvzv|2|JZ4Upg)@7q9|v8|RaJ&qD}K?Q zs;a?9yKI3ZQY4F43u-CXrh+-hCN}IYL?dU>v}(&}|xP z7jZ9t`4-v~nN_${W*pJ5=AK*vdsH)W@dGc=!$7BJx?$My)V^q~3Q_92i`Z`_wl!l& z#2Tj)cw1KI?=~oB;b%b^B>RoriQDYyCl-E z#>W{U&=>k-lb(}4P5*?^ksW4=xE|hMCi-}OD*|e`lw1XH7rGq^K$p>4KLUG7>#)T` zKj-xb;p5lF_TD<_KtS%6S?C{WBN6(b^GMqqy|BPuh?51-Py+8ro@bvdQR7aZKE}L4 zXhPsYTgI=32na`^-D8fNwazrq$a~*6qEYj586Qt_|JrRqlHDQ;dqN0wX*$#2(?&{X z7}z4-`QEK6Qx5f**y}6A20BTD%?ADX7MEsN{e*UJL17wi!5E8tBwQ47zWuy!HL5X z`slO)7PHyiAZ@91tl47!y*%n|^@6zm_jfk$g$t$y!d;T6uJ?M-4}G)a^xMA`GmptA zz4r;E3^9aVJ?2cMR3OwvrletY>7qI?g}W#ob8Hkv`S7J8(;hn?W0b>XC41jPF^8?0 zrlxw+*GbfEn+yx5FfP7N z$C0I7{#j?YJ~+%~kH%4k^O7(l0y_K8($5J|%BM0gDZfkPM*Xa|Ce02~ypulPYah!- zzk1Fr!|Kh&$$U1ZflDX)gVq)S6l8#|DZruk!nu zEF0tM)ckjLVvsz;b>Z2ukR2UIltXWMal&P3!c0fK82-*?oZ5euPEPh(nBceR(|uF? zC^!>lLz!cdH+=QwgKd+!zcqf?;}!&#N#TqMDF`Ywcv-T=r(Yt zYQngHf6MbM_?Sd=hTgF*_g?i$h_*mI^gitVuVv@!(`}7^TRfuxH2`47`dKHs7ORzc z)EW3c?q+#xJZ7B@m=|uo9}U}vNJ-5Q8tGd?!-^oc3u1@R#jzdE^X*jwtjJO{(VFeq z!oF?j3>#)fp0S_X$KLo79v5S3uP(3eUK_vpZr>UY%7%cyJ2Y`6fhJPHV`d1K09(^>mG6Pw?3V79o(2@wE$=O}_oQif3zJ_^Ta)n*1d z3@Y59qDUHWu=4`KQ~b~ZsN9}>PZo5>G4QzJ6;5Q2Rx;(rbE-=@1ga^K4;i1dksBVdaT zJ~puk{Z@9Dw{tSnGF@GPk=&^62pPlr({3mOlE%^o|I>ojNHg)#Ii?=)USW4mavK&P z4_W%yXpiV2YP|*#SEgxtFUUkx zS(y(mv>dDh1kG^enl4ghuVvt zIIop2-%Lq9E27>dHuUq%u80Rc8jTCkN7dX^BL4#B?Tb74qm5#J?h3<8$o(%`1}cvngM*QzO@vF)l$F+&7XfEuK{q|x<>N?A-|v;fxPIK5~7T{ zTjpTsi*vCzpEKNn4wa1x4Vy@j{}o!A*5CAw$|u*A_5sYPpsdu-f1E)#Cm~JS!VzC0Myj;D2fV$$@Y}H;-NhK`me$eTKYl23oaLra z|7-EGcXJeH2h6%uL57bCrblrjGOCdh0S1n2JK`#lE-pk*l)F%(x@)M zo*|@+agn3G~Vz3^muM4Pns73Kn1GnJ?fd zx6FZf?X1e3Ue1>J%Z>zUm`MOB1bQW>jg3N`l(Rp)`UHN?coYO_l`}yMr(P8AsI5gB zO0U=a-G(Kx<-=#~)DtU447; zam(F_$_F~orHtrh1{&ajbfXuGTxB~mDt?G=((eE^1ds{f4T9XAu*s}o$<3N3_(xG| zsKPi+aP!GL5M&jnIR*Bk$3XTsmC}&ck5fDw9jMCZ&$qN9jqj#BGD7AWA~EmMakmfgdJ!j5P7m?vD+>5Bl~=> z9Jt&7?_K8O7+PC|ed|VA!fpqkIu`q`z@9>EG+%-bgnMp>zy~lO2IOs@req|P#Zijy z{@f&|OVT#{={O~%CnP1&0_2nh`vA`JZ7^#b?Vs81`j7wLl8c;M#BYw>sQMXrem+{%k*q#F4_X+W9wZ=3{S}cGs(s8zWrb0D)L^%f_Xp`cXq#zv)Hao{C z{z5tDzj(vd8^@Kck?qEm8?__!`l%ZuPmH;iSp>No!Gc=X5k*cXseaku%0+X=PWeD@o&gnQyZs;Y-Yr_Vm?$Oa_TNbggg#=c>3 zr_qsdk5ARsa!ifX#ghozs77d-hXUUcq5iGl+W?!&jv#~j!Frv z8y?x=tmo_Mu-``f$UOP=2|Y*NB@RJv#sbT)@{+MVswhPmw0T~x8{$jLW^efdZdV5@ z<)Q$4J_)MA(@x>!e%Q=JCYTnJ^STbGlIRodR*sf0wvx}||!lvf|Nx}&Kb5-T4 zr!BkYe%TWTPagv|GP3uA1>VPx^sal(864uFDTjl0>0yS)r^gz{vZ9U~20E6~Ram>4 z3W%*4TRmfVd;4>^4pOGEFlRedaaJ&%C}$_^cT86b zKf-c<5Zr%fJh9k99xoRESUq-%Xb`OY35UXzgZM7Zv^Al4eqTB_TZk)9nHoL3(q*OV)$;PU#s^5*gUW*}r=|>jYIJ2HQI6bghf+OH@vXpv86N`KeO{`Z z`Z-067yf)Z7eu%DI%n_6&NU7r+p2z|q^eY3r)e2n1%ciSOL`XvDpfMQ(WLMmfPd>p z&gOtnC|ZbHlFUb~l;E(2uF2RstmD_z?-~^8WEHobWk;rF*I2A^GF_YkrTw^_O`wWzEyG@_lmg_sUit zKSpvW+FJ8PMtmRP^CeC)w5vow(qCH@{YoS#tJp2q*LO4bHjSNOC$371g`vU~E<9s( zD+-&VVeR)gfvP|V9D+;~EAnug7xllgH2MHp%u(`D(8g-qxACi;xKh(XLrDN(D)606 zn8qKeCix2Ld@2>t?;_)!jNCHydP;*#2gjL#;}m!QA_g}b{)nP(By#<3kyWPM$u1uc zlTmV>wpVAyk=or+@)6fO0JFPfKP|@P5@z%aDC)`z#BXg!S^8QTu z(9%-C65g?{tIk^gKS)J8opiBXw;`Jfip8+l%M~>Ai`3htlR@2PE@cD?;FB4lPEwb5 zQ+A7{1XjKcDAd9+qwb}j#RPN61+81;;})rQf%XrDV^^u>ibK7h*CJ50qgP(%Y?2DZbYEq+nFqE z+dMkW;`9-j)ayi|jac?NTF`(jGaM^@0-F0AexGHJq&Yw>@prudwbG>YV9HFzl#2?a zvnOW|Y$d+SN%D2pR|%zlOri|pf`v$?Bbbf}#O*I4HJi6;W>ZIlfw<%a8!{X>i!Dgn z5Ojy^ClWEOQA_tBFZrfGPX0UAUAe`zx&r-A8@N@%=I9Zum0gWXV9;X-2AlxArG9lZ z7%ICtil)nDn$%l(VdDtVB*tMqS)o=q>%A}Yg_22C(eV#yu0pE$V=6_1ZuL1YxsQI8 zoivPFMc{`Y6)(f~LV~nAC4|p2EN`I}5IlW#5PAtZhJaOeDmEA|s+D*aB-$Yf_a~pF z7%dtmngrgWB(@N+?ytaLVXQ05abFIW*eTmKL$vL6JxPQ){tj#CT)trMF&M8>M$Ihj zLF~Xi>UM7pyz@P}uDvbVLpfR;3RTq0(Zi0|;@L^W?PI}X8{^K3itb9c)H8`IX+8^e zVG?|lMXNGT6VjcTbT1iBQMnC>OpHNb``D%xpL${OkIN&Xm zY|cgXO^hqGAu8!RMzIOE`4$3?CluP1;$J(dSj|S)xaf=eMx(ru-Ka~-Q@- zoAa$T=Hw{%Q|II)s)}bw3f)f+d40e=M!_0*>-T^t_Ob^pttK&K`0PXXy4L~`YrM+Z$vIFM)uX9`N$ z=kN%g3*hzr$6=NCMl)-&And%p4Tg}nE>oCyaBM0j`Ld8D-9|@yj*u z-Qg%i>7H6@;2~3MbiDM&&|^9g$xh_5>68p(uQ_IXJjY7fB)XNtLan+^n{OiCxjhvz zS9?sBGT+}5Uy|lLgh93vKQQEjl$Mf;bCJD{M?SS2BTQb4?o-@ziAJJxwo#K(7mj>n z0Ruxg*A(GjJ4bybfWsckJoHSY@$LC#M{1Y8;3#=?{M^)iSz_R=>FUuo;iqj*1f|c* zyPB`sw!;4DwDk$!ZLXmEFikO_fmwl5QKY56hN;oSj?lrSXgr9sOHxvOQBb$!kUzQg zY{IG>+VNZM(7;zK^gOZvqTgpc0yfIBx3r2QOL%!AU}XvaZ-Csn3ca`ei}ic{4KSN{ zDkrLSu;D=NSz?GP`&p0-xXW-UzRUcwx2mT;9AhE2KH0gB7X|M{#=J@ny?Ns$mYhF} zeUK31jtZdJxy??x9Eo2<>tz85KCSA%a)yQu3aEZUY)X!{sMuuAuHQ^8#_XX{VO2FL zs@CP$)n$RAR8JFvhdOF)!l{-o64ZZ;=q$};m{2@Q77>Coj;({n*QXjmkuPn`+X zG-lGDg@r^$_WtjncfvjVKM)FU&;ucy!}ulR5IL3;;g3)QO%K0-smb3al18&=UlAP~^zj^Z^NEZI#Crh`142T=i%eoyK?qRrvGu0<9XYD|n zSt^v6%&*=Qv)P}DEzaLEhh(s$L#{^Z!H=x$3PO9JEGHIrFNM&@Y8?6x@15Jf$Gd~8 zJwqAEbfxhe!K*fB%njSm^}3}$I-9f5?k&>l$4FU>qCh(7gH_D9W;Pt>U2wCSVX$;~ z1;d2PJa^v%i}14k@doZ}WjRcYUx3kuA$y*>p9Dd$pB5+Ch2o)l=fke?i_D50UCHn! zXQsZtES_P4yR)(;Mw>qm3rTqzC|j|@-rzu6e&#&uQ#3ajPT?)JKhsXrO3QFo5bvb= z^G@f^&?ACM|1FSF2f86QM^cA# z=Lo4aA|Ct-uIZlXJDta9+c+J=6WcC)YQ{p<--@`x%$U9qJIXpAF2qV0ELr~h7{ETH z9;rCWykV=GUbcJ&zR{p=@C|gLo|dV&<(*EQi?1`CbrrM_H>40XLtG&Jk$K42V#osz zj}y+XapYAepgVIb67%otX(>sKX2WwrYA320NilEGs zC0n{eT*A8Yp{V-F^iwx1tlqRjj!Wmse63S}Qu=~-zFYnr@?t8-SE{w}D@HN9V^bQ| zDHATFv&FoAYbC3qkKH8Ialb6!?Rf9Qn`*gQ-tTit(0;+Tw8O>E;Q-y^P?lnb^^E=p z*GWXcgYYQ|Ku;Bh9}B?v&`VA9EK8OX5fuxBYD2TLr<)-!;$|l$OQTT##{!&`mr!i$ zO+L9&G`hX@490GvdY0(66yu$#0%4ouP`55PvJXhVFcj9-)i-hLQ9WZ`{mAnC9zLgu z3i^GUVq7OSb@Jf@cYzD~tse)k}EqP{gvAd8iCsPG;bIrwjqQw)3GP zrmF{dROf&B=WqTI;E#IT%8<6E@@saf`>m{z2>jLXa=E4U$sW;KcFTfu7RGX5_ZYL? zbmZDoV2hJXj@R{ysP%e&ZkQ1%jW0GPL%r+-T3=xg!Lk4!9_GYfTTwxbqHs1`7V~OH zw%=Y334Bypj9+d}T+plBOGq;cmIKpY?_AU+x0bEFmIpgWUjV)NBZURPGQ zOnHfNY6D*4TucOV=YoaMK!ZK1sUZBSun@vo=FS`rw>)U#Fe9w2jp%HG?qQyPJ^Fu$ zU7K~Lo<*Pwnd&s zkq7g2FZ`)`8kbpsi;WwBZT31z;8=&Hy&K@ZWq^)hf*{VGYBf3v3W~JVk4YTG1^K&f zQvzwP8`IOjo>>zi@^QK5L~Bu7ZxcVckgE}pVB`Y7{Fvnh#z2+@ndE8IAGeEf#;M}N z@hcgeYI>J%`)G?Q=Rb?TRq3+m>2JBSN{K#_ZL2niL+}JNKtNlYNdElvx68h*0A=xX z`YyC1$@v(u-_d*-REq=pZxBXTcIYwFyPxdEVhaU3E3@F@M-j`xpSN2t!#E@fpv-qd z64ttk-x;7l3-l`X&K@q?Z*MjC<=AH|PGm>nCj)eFf|^Y>)8Ajstc+$1{c)b9*r^zKg{IY zQ1evxz4Ka@qWPA~c-n75#%|o9in~Y%b#cqmZU3Es_I6|1S6G`ZM%VrT;#5%T{07~Q;}bK)*TNURch-+3 z{kQ8kjKWb4)988*@FN2vFtqlgB5)}P zo+^T=zSL-Yv5_Erjdf#5SKxS#rCG0ugT=~4$qM=bQu@EuFm+_FQ7R!YW$vpdgNY z>*SQ0s00Dpyr0O2S@R3TWI@F+&=9brEo~XbopkTZ$9Ct6{b`Ir4#~e6{kttb{!XpG zm`pa1-V5zh|Lff4yt3ENq=Edy`mdE2AQJubB_9_{xb5|CgP}!iJiFRhj{ldHS|b8Q za+-jiSdf?F*!6L)Vi-7hIM<19eK!5R#XNl%AFuJSl_i$pb`ifeHK;s9J}(~I+>uUP za6PD6c^Daz*BW0gKOX*A0E57I?51$}Zm%T^k|uZBQK|G#2Rz@;eZOB0O)V`ANLrg7 zPpC8amRlW9y2!F_zh#LQPKVP9=-D;aR>0sNO6Fe5hdU`~835VX)lOPquwp16Y)9KQ zKRqql1yD#|+s8u>{*h?p8_zH8`Dy8Hu!^J^1Y3zT{UK?g9V%-jL)52V6*up}r7 z)w%OJ{kn0L(! zQKT07uMeB|uZ!xIPAS{hz_|OO$tV}Rd#7mrANdH`(NXLANzApf+$?Mh&*w;wGUIFG z>d-Y-2bMb(FmRa@1-czv7}@AEPU=V5p~=rJ{JbO!T9TI@qoH-+H(TJq&(PdIXQ zzyq)FGWF}jlfRJx-k@uTWq6!7?CU$m2T)G_#Ji1;{}mD$#7luGNzrmqjqD@mOop8w zD3F;CsIehirNAzP&vPtqF&1PV;xWhr;)g?6s(Y$L&k86j<`>*SbAV1DAj<*!(dg6e zp&Jk?gbumBSqI$Do9vTs$) z1Ta#Sp?Rj1TPrq|Qmp-AW?zN#=QlADg!=5|)rW0VTE znzKa40SDSzHlorVn);@dOs2h=mFC2F+`=FQ(dG>b%qXD{g<#alUI z5NfD#gRg*E032h56j%RpOoI&^lgq}mMuYs*F$FI}7T^6#W7zT6E!SIQm_1_$`Qw-m zqZ8-aLKC;o9JWJy>Sh;wjNrM9R-nfW9u3CX0-fOe$x->n{iw|X(544(_CjK8B??6t zcH$k+3Bsx?Du+I4(v@??>T_?+gQ(EQGl7wZBmY{C6gi45T4$54_d_EQN7{&M4j$TJ zNcAwGF3feFGSBpOJ55aa)-XOTfJyTh%@QukUW*+%Yaa2Mipl2s)-nDc?j=T;d_Xtu9+wkU69;e z70;jEooM&v`)esMg~!xFGa3@;yf8ki;kJJu5^IJ6h&bpWp*3ZpFNz1S=89lx8*><* z)^y+DI<#u4_Q!bSMP`XXil8)zr}-NI?bpC-fm-xj_~kEls#VR$c-pH;_`JsAPsRr3 z?U-u#LCJ*kK_?iJbD;Z{1m3H@x$9|5j<%iJ`dzG|D7hwXa65;)%|T~+JwDoj8cNG8 zYrmWXH1rG<#a`lg|4sV2s|kM5N_;GvS%HW?2bw!9D7L$M|2NCQhmJODo0SX*)cdS^ zB9Y~WN!4C`pO~HaxCPbj+<_+CsI8}F^3G36$iNgIPQBm&b}oPgM8Qrr|y@3CwwL&gCN{m@@b3s5X5{}`ENRw>wHScQ2pQDFuwyAQ0 zHHla-&)u!q8!OvjV7i4q#SRGtMXm@Xz}Wh&d@^5)h1oM*Y3Yp?^RGIH>tL-a7+o-b zS}Xqefzz&432i$=Fmi1+=Mt06X_JQ1??AiyDcy9|u4X-9bV!dX20i4;=pZ(lRxuv4Lt1lG^Nq3G2i*O zBedgIapWg`rPKUJLUc(3#>a$+H3uZ8l+g+0IH|eihQfMJ=2nuz)Quht5$e%_HaGln z)`Di$WbSvjE>WV@-AB&bV9(N+ttG3BUn2tFmGsl@uJ#V@%&-Qs&Frxcq7RPe%jjLy z{VG=o=uf6I0d>Q1B9Ns`#|ak6w3xb&_or;+#Ca+h;OFB5`dz(3$0lYF9H@x-`qhEa zSmpx27^gZ@KaiWmL@-}~E9;kC4zyQT5!l(|FwA~!owyhSKV7ykoFTL0Ax07V0FkVQ`9mF)_Nz5> zwmrk#fJ*Daj_eTMI(?#!%-2p?8>fVyYd0=?-c!(5>g?*ln{3kgD?vKWIjxdVwcZNrciL8fuO&o;|4#z|9$%TUg1I}_hoj5ZMJ{`zrb|$+q&;Q=q`IZq4_zlO?!JH* zqi5pkc9y7EdECPAn>E4rqx`o_%t4?E+o1|Wgvq<;Rq-5^J?w(e=Kw&wTTE2ov<3$; zCFa>%c3M;5pnjdGKz$)8qTs^Ui)o+VZCN?0)Fq zI9TYq!T9FI!@ukqg_ANvcQ^xcW$>Ww+K2H&GhI;s+NWnii++B%|lb zw?=1>(7v*dNg`x`V0bL;Dc$(~>SDTE?k#9%_*iFEDi%2Y;5@8WWQ;vVW_&cwfgT zd0JqcO+y`&F^08x9YPH!oB z%2MY)tc<4=)QhUbP;4OCwk=UoM{##6>FLMn3m<5g;8{`GT@8=Md@46G?Q5Q|Xyva= zcUqoLW~gKWYLxnPEIWzr?EfB}!#LJaLs(_ibx632DZXi1ZU}eifBq3Xu}~T*y)jE- zMdx~s)On_^o08LD{Uv4Xv4-65Kw9`|I@aIUku|?9nF0CRSNSRqfz;$M*Nl}7uj@Ux zu3boI{$#Z;VhY+B5M(jQCklTx-%?lzx33^XCqFeOzMw+B3J(}80fYJ2CK>uwVyO5g$3 zUN2WUk0uR^S_NO(QJp|3rnpcYu7!;q>~bW((cz(-jXoiJuD|wLQmyNWXlSKZh^&=& z(IZ|_R#{E8hdf^@$5?MX(+XQ{nRi8%ZNSg)&B&)&yMOM&s4a54nvtn<{*uv6_$e~_ zYCLa?sh)=g?tz~r&^0f5HPJv>8w zVz`twe*t$+GgsyJ?~5Z42ax-P7}pp=Wbu)T_1=k{-39RXb`j8Newn)vYYxr2^JnOfg z3?9^U7BGaHvziG9V^%AmCE@VlpUK9r*+pO1CJ8LMr{*f({IKJG)_;|+&w6m8o}7bk za(SPU_zKZF);mlo^W@=>J#QQ5+`uA0+vqi-8qf}OM~6wW-qCworZq4*(|uC9?k(i;PuH^*7)}jlYeB0hAlAA%;t&Rt;s4p!??}1kgw7 zOY>}aRYO0)8ch}Z(c+R*bVo%D$ks}DvM75rMG6o%7MVaf)ux#Srm!xIGY=0Kde7f( zLGkak+%x{J#`$5|2rTFZ*nRg$YFk-sQD{0Z`!K8;9jt0-`ohOQ?*HNV7PhBpDZWda zVKVw{uXjdB8%CI^52>-O2-BaIq}a3Pmg3Fpi{SQVCW>t)8uf_JDv#{P$EbWO<q}flvy0VM8AqUTPAQ~3y);jT20a8}-0zDXB$ks=R=FW}9|MMpwd|r($av?S8b4`_ z8L_@WlOXGyJ(V=yfPy`~1>SC`Ek!Xc;ticn0p4g!?4!@Wema~5bK@GvX8`{@fg0KX zWx=C8Micb<1T791kzi>n1z>+w-Q!1p{oe}qt~gD) z*d-!YTtcA%eu!edS*mNqM^Y2{#>LTwH>!qkiXmmzuxFsg_&uqr;EDG7OFbl%fjFI) z6a6hAl%@I4N}80E#NUY(l!qmA%<>|W=Q2j?ABOLUClu{bP&93G%hGn)6!H<&U5t8Bft_u7O>2Tjznul?=-6gK zETGIRDdaNzmF#tKIIyr8DpB_D5^I-~p-+VSB^cjf`L@t|(bG1G<`VD4 zxB4yOtL8-nx9$I}w#8Mf422rSh`Efm$yj|)t~(oAU0Ifb{ID_doxm=J=9JYcn5-}i zm78U?Y@$aM7dK4Tf-`>TyPS_R8tbDhbtb7)+dTS+>7a0S$@rP9Z%i%QyDY|s-Nyuy z?%kiyEtT1ogk zYae8kU_r#JJ*W~Rr%AtSprWQ782Ua+&SsZOwb6Pm?+q8*w|^?=uEyLj2xb@;`s_$g z=PpJ-M84tMsl9*BWra#qpYA-Dye%jqAQ1g9RI|^Sj!J!!+)?kW`<3(BhHW=DR*C+! zBq<~Pw;AfxN^^jkRolz9dTpjNT#7r_MKO!gV;z_9LGb3-vHDM+a>U}@+t4>)VAz}i zuTtq#i@}zX4OgLxg>sZQKp9}KX$5x%i{L=-C*g>2($mD&9#I?Ck;tgv-!j_;x9m{av1Eqeg22&F=60Z$PDBkg`}EDv zSKE*+u6?=@j>nx;?c;)8iCj^rDJn6|Jm{|_R&BZ;a`MM%R|M2y5`X#>BT~_Nczz%$ zK?&?n!0VM=0i`k_G;zUEUFu8Xg@3G-DZtE#o!V|{Yr*^=WWZgq2)5}Pnbi2jHbRt@ zL6P`CV|R8Qe2=>|Mh9~ABB)B72Qm5Z*T8zC?iYP3i5VWr%0=;O;-LvY9Ku(3G$uIJ zT9F+gn$GN+%@96Y!%}4~SVLGDgN>QryP(XTxn3>AE+B{kksc=ii)w_SXw*xjpcH>_ zPK#c)zi*$g!V=cklo_Qj_641=wE-WXa(5fQcFC%pKk{}^JPQpI!QNIgqqvf%GD+aM@i~6u9|TE*`vLAnBuRuSt~Eah^R6J?D8GT1Q0wl(O?8K z&Rr$Os_Jic*H1@E+uV{hP_mYkD z9%2K--q|7JI$1{Uahh_W z;>IFwp$n+-xIRn=aB6|@&_?dHx-it3Vey20)vn?P%jP~P`Ms?Bg?q2c7{-i9?q{T- zgM7SN#FSa)KSDrwH|0`zR#9gh-GWSWah!+GxBsG%4bv|R1RKhzo;b^9bn{&8mcRTQ zI2z|WQG+vdEtK>tNAy>T0z1eax9fgjE+Oo(4)2my@?Iq+Cn<#@Y9Y zve>+d)9xVIEX|;HC%S3%2KCpbPp4;Gz6=GM|L*Hya1g4JiM!3Gw#{Kcs(A=in%&Pp zg5~(7d+i^7eq|6bCsk@*50(U$+j zvi3Ya)A3Zn35-L*>q__08&QUA+y0c+8Vk{x{enukl9e1_smqZaLRT|K`Gxe(cxWi z$Md3oM*5BnDK>b|c6N8c>uSvX{EQ0vBuf$C;!ee@oUzKcC18~OdADI;{Jv@VQ#k+1 z3n~wHcv<-<4V)3zg(r4gL?-QgMX!BPk>SgJ@pS&ksoqM`&jxiCctFLRN`mcqKUmMU zuB{`8?@n>hQwv_n73piW<#6N5fc&vghRk+<@adP2D`s7w1YY2Tuk|F%XY6un*D)8Z zeX;tzaYj$yVyEGdvY0`2`DWGVr_sRMt4PcQm3rKzt?}gy)~;E`gip8%$I*RisQeF{ zB+Yo4Hpt(WfQV_Zg&TpolNAy!e)nUfam0YqdRM~zrl0@xmu(OA zi`EO#x9*ZLM&m1QZIsE%Erjz+NLk!`>_%d7%TB1mW9%d87!CNbY@^@G(g!}aUhc5V9%3op(5~aB|+h!9VI*PL9W9zCT$F9J^=If1DN#YX8)=Y6xZ%X@?LP zIwd5B7^Fs|q`N!b`#I-5pWqWS{O*~3?Q5<7+I!pR#EXQWW3y{*i|NRIVXnP)44i+7 z<5JI=w6S%ySZ019C`K;|5cP5`8`K8*T|XzARb6!1@4E#J?i{^6{x-H${Kd4T9_ zxXjo-ll=WgvT9M}sx?HpENA03|W@g2cbr^9LWRJ=#rUMnmY%HsN$U z$^-g=f07qYvyAFDz_s2RO3(SciwO=VPPG^C--`*;8y#nx`F`@oMsHPr<|i}mRsTuK zCSxQ;8H%t7^6A%nofT$>yC++Vieq8xA7M=z(SMXAN**?^Lq~B6v6pS+6%#o& zW|GHv2)5?zwT@hxMSS-4DK(^j1wnM}d_Vo}WT@HF+{R%Mi~Nz7uI|UF==Ya)bPFEL%ZH(1l=d-yGfN9=B=|Zwl#z!hX%1uilh2ZduvB@=tBaLZax7g&gy??Cc9C@Sx{f^4bxBNaAeqPFK1kicVXEA}qzt(h4e3i0suhIoS@RRP9k*VXALdx3H)jNVOYoUGNKO-s0KhEOsuC zG?Vmw^WGg3iLsy%eD5F7ZNsSC+1xx~yKpKMQa$+fQ+R*F@NAqoyNCe1cvkJqNDL+9 zJ5K)haE4U6H(*1B*C_T6g{7IBP}EFK^wJ}4&>h2xB64w=G(A4Q8gAMfb;VyB8~P3B za9=9s#g=~xDMD#kJUi@Rb~A^AW4)uS4|IXQ`r&1Sgcdp%>zu>Xw2oUK;gaby?E&7# z);>Y&-%i*ap!f6H>2`DCma`rQm^uxc#M58e<9}t8pDCzQ+?1aWV)*6T2rhZg(2szy^xQ& zvBNE!j*3AI0^QZ&@29u7Z3`AB8-gP(u~&5^s$s-wA_CFNpt76u;8fL<75XJ=sNm3E zV62-Qi7~a>_^=a~3LWcv{hMT4bgW*}Y`N)1170YV3yNdR!GmYC?$NkHad2k>rr6|m z)|lGDITk~CQgO<)oAY+0ykkQ#=7K!^35{Zhl&&X587?q1QYkQLYXyNoTl(=v_4w~@ zr;*6&?~cu7Dc_qkwJ#!i7zWDKh2)h*3$POO7JodCm}ZG@c3k`gA%sKTBc6yacygEL zO|tCUOWm+?|G#`70qWgq%8nh0PsRZ>R5@(0qUE${Ig#9p--C4$>fkSNuZlmva54Ln z`)%}!T{bZ@`wQ>gM`MAfI2rcZuJ5lmSG=N@SU#Vc7<}sJE_xXpxFMzNTs^^;hKD%1 zX?*f6Y^r(W_1pS%2MBuS#Z*s5Rx+Mq%*OoG)O6b4H5V8_Bfps@=+qhf$tgsHgoJz# z7i-=gzJ5XZ>eDlT}EHuob+D?9m5sLAx9UKl0;<1-f>2{m9%ACU_DQY8&?-ZGCa%CV! zqI#yWX3Z6B-bvOi1g!)N;amAhnQ5idTHZ^}HAX`*!g@WQR&IY%@Y2d(w*c>Gc>gt5(b)1{yaK&`h3Hi!XWhe6Hbjk)H7hJ zyTjg*5aq$owaD%@Xn6g#X7sobN?uT;olPZoD&sE22%g6|G@|L6_FfwjaQ#HmBS3BGG3EY5LPOUgdv!q!ZVM&Y5#5 zX>|3T>fF+jT}DXU=`YEjO%ml`vJWftk7^LG$_E$9FqDZeBcRN0a zul)ReCI?S9q6R{69Zj+dCrE+f{Ih|WY%AwvHb=Rmrx8;S9G~2OU{Zd4+})8|Wmf{n zIH}+41l6}q;0Zf-op%t?qfT5&4svh%z=n`WM7oc^5pca&A$ zBhcZlSve3wR-HUoj{OQHi|~+1Tz2;p^1cg4O|>|yr>wLyZx*|sqF+AgN+DLrY-4X( zi4NN$Q@NQpx~ftqkn!XOdC&9%cBR}ZlS7em9f({+Vh^I2!T0i#uNCUXB+1V7KE^dJ zFhx%z)O20aGiDJ2D37Clp`km*zc1@)@4e1`Cg+l(PA>C;zW)SCwke;ZI#bq$TTNs2 z)IwK!`PSO=UrpE>d_fM-2KX>N)d;!?F~o%w;)Tsk#V@+Pns0^`>=Xq?du*lognK0D z{Ind=ys7lZGk@qP+sNHPiY{VHlrADhz(R&Obh1_qs!Kgw6^llZK)YI7Fx9vFjW0Rn zeu>tYtri^A4g+zj7WcvYYj8e?MURMmhyG)(rKWT*$w~5V}_>zPh?%BOvfy&Unb&gg2Z_-=R2% zn4$j*BS|f$z@{%0r-_^AwZ>|Z&H+{gM|BC#pGU0EM`c{HBoFO z+%+)-MU@hU)iRvS8sLEo1rH&QS*3AlMn@ErTM;s@uDSior+IDxkSk?6(8hx90H?uL z!Ihq_$DqiyM(i!eix?K2iQX#KYr~AKO+&`>JS#@lI{UKjxh7P1G zmD&hQGH8UdN6g0U2P-mAQOKTS{blPk-^41CPp9IhP5t4~)8~6ADSo4o0B#nI32d=Z z|7j)o8|F$$Kx^g?5$C{<>YwC5QPZ;)8a)n}Y`4X~iOgE$SS0bvr%7V3V=MV7Dz`Xc zohPMCHs)U`3fBGpD_7XluUBEhMKN&$iNO)|W6WU9`|uK+WR|Kf8)sSIB3xx`w+kMB zwm{M)=p@lgHH z>7uKV_Ko%{&t<#f_u=E9?|P`9;RHEI)l&b8&WBLE-}+IYVO|tFbspd@E@Hg5@hohe z1>a~I%aoD5I?hOK5QG(WnqZBAJT)qur-vRf_mZk=iF)MUd?^+jixR6+|7|NrLY~^M z-9T2-!3L@$34W-;=s}BgQ#_LMCc@UL8>9Q+C#^bWxrIRF2hUo*%AYdMm5aI+G|C5c z&RH7igKWqM3us*&A@bd|Oc8$d)$`O)CS3hr!68Zw8Gs74z-k_9=R-tYSKWmKDF7Jq z3mg5^KL3LNku1+Hiv0)h=H<)N_s3o&RT*>gj3>W4^1m4;$)U9i4mpCZNQ(9`KmRRh zr1!q;G!0b>bKOFizC~^q?71IbA?(i(A!EKfoq29C9wiG*uh3i7espBSO()i=;@PN^f3Fwm40dWZ8Mgw`HP3ytlZKrZXkTe zHE5#yIZ#OWCV^5!FR^y@lBQDp=rRNg(P87D>zX>35KG0xc4bVGcy(){bL>S(RKptts`l9 zS-Z(E+WRjJTe_w_`Y%RRQyJ-io0}oTPWNYotlw7wr;H#ONX7@wKW*d9H7T`m&r~nG z67xxR%%0&7UgRBXk4zPR9?RHya80|!?BapNNFKanio4uDaRaS{O?P6W4*G=={nMC! zhXh@lkW?}MT7xRy=T&u804~=-k!i!TCrSO!x&vVbI>&Akzrsgzyv=Vr+{G7T?7mZL z9jZ8ADq1#eQey;{2!P_%)`WX}LU5e*kXzqZV)8|{!QGbbP7NRbr2B-weT5t|yE>%J zT`Pz?USeFnR1GY|qGBeyuxq`d-|#ub*Yc5R1w_5MJ6cm+7LKsKoHXH~!0_h$((}ZU zPu#QoM|w#0+vi0hzJlFUUwmPpdHPzx;XObAAw`NBp?h^7X(8>tuhh`42j=Qo2VPw% zh&bVl6ps!E?(Ecsdw5L&iGEP?3z{%gC1p8U>p`zFX2qC&<^K0&dkpiPBBBBlj-Yki zZdu(F(($>500wT3(i1H7z^??v-EujD(3MO+!%~C&?9H{sU?fOiBHDLsSGiyQ3S#x$ ze3@_U)oH~+{jHK|>u-!6n>@Fijz=j%wNVGtB&DlcSGtbdy|ObueNpZaGs_wFq!GUe zviF^`$e&|vRR3$$;Ky6kw@ymqa?}seqA^4})cqng&514x&#bPA4=Siw27Htu znn<0QvBE5Ao<{ml{1oGdeH=AP^VzEugmRyEw7TAHH>@lAyXt)zB&AaJZ$w)_6h}xn zPl-j_l-e4w=4El=3!ozxJL!rMRzA;GiT`RH@nmn2gclV7RRncOCOp6cSTsdcsm&dr zy5bG|3hd7=P5I%E<^2MzLB>cn3G~22vCsXBJ>R{gRP1A-Of4_%&le?axmx)PWAOeI z)sY&e8SZiWrN`HC>GT6BksKA#Ni(}r+mc!y6O%8lX#3Xf8Oa6?7;TJ#0Oh90HecNV zJuhYNEw!%v=g2zjITu)@ zb3mq^p@V_3GjqmwV)?6~y4InUu?cuj)wO2)GbmDRE1}(OCB}>2Pikxet1|?~8kaYZ z8Jucg4Pw5!eP71Q6lAv2m~RiFpBRYDpU(Jfq^A?h3lAanBwefjD-*e!}GDN3|jSL`eauHm2|9-#ik)W}xQ>JK*%) zW`~wi0q_q|H#Z{UR!THxOo~-yPQ}AMMA)apLf*z3+~Wwf79-Q6y#7cpeCC7G5ixD_ zs%`Q^D1x(Waj9k<^%4DNnpe0u3_lc8 zdvl{wxB)gWpF`A?O^A+7ok)Dz@QU!GK$6S9a5(u{ ztZCPxQP`zJ;>H8-BT;qXr}QI#y91NpV0+%lKf3QRqHCw=yS_MSC0|QBhb&@;8b{ux zUXJBM8-|4*{IUcDeR^|Z5+5pUR<&}@DSmH#LDZCx+lX9Cd0N6u1Ud9I31|G|Dt1Ma(aqcA(@ng&4PG}0j0+NIq&}Ffen4>HC)w_ zO`IBQ0CMHH1-#pJ(o^-=^^2=&&+iLT7jj{?ZL*-91{SAXW< zub?y1H34EE;W)Ri@>>Z9N3eC+T?*|YACzumoJ2B;_pY%?nz)*=!8}If9o;X&7jJHV z2fa8q1ZKnZ1GA5g9s;u+C*Q<9U^-tP~ z84>EWEhK}IBiguL)tJ(0nz;D%2O-}6Tz$5e|1)Ro7;eQ>JM(}ULn8auy{>`Y9$AP? zJZ1@$A=cyVeTtPW!P!4f3$rJ`bThj| z#d&nkf%UoGTn16U@~B^H6^*-`v)!nAG$BOEtXP!UcwEVm9J?iO2IVI9^MZ(q%#!8y z6Q2WT=tvXv>|k##`>inD>|M^jW250zDU(3iqAW;7K(K(+cyP>$rw@T8CcF_HkRr&MteA2;$J< zDsi*@w)xOUUn&v%6t#kQ2OE|`^IMgSI}cOTdH!gw$$A zhDaOe+(7ZsnOxg{a@oW7;M4hQnmPI&dRdOhCoWu9MXzBG+u32I;kU7$N=;Cs^%rX2 z$7mT4z;|tDOOpd$_3nhfD5U3S_{gMKUD@$L>%9;QYNm)UrwGT7^>n^&ElzkB0sC^9 zZSt2)qrrMFAHzh7p;tC}PIE?i3ck30gmo_tls5JYn?r0X_ru;YkrL!jA>txcMX48s z+fauV?UMn)1lzCUQ=|-YQjz(MI6a%~7m%^*bCIvFEJriK?hTj_A?R`wW z=As+rtFH81(RvzDD~MtI_Xj(c07tL+ib#_4dpe_^L;0x@45iD}-!FF;?@nsI-4_oK zAk^c_#BN&9CD|_`V#k-s{K>Gzd>_e(!gQ@DHjAEB8%|odJ=&d2L7Qe%@WQO+j6=rC zLT@tC5f$iB@OGPRRp6-FU#*P?hV*P7WsO%`xEoc>@#ke(aPz7Fcm=~OFnb4GI&YykvlDxLDVc@z+M9^(Lg%}nzjv_&J@KUsxQ1o9@(|BZrrZkh$dU{$ z)(5v%@kqLfOP~43lrMNDd!s-0dNWd9OZxxNVG{!FxD$qXZLM0St|gQvjWRdChfr-t z;=iN`R7sJ{G)XU!#pvKb)%*vY{t{VW0<;vs9goZa@27LY?g>-toDnlDAh3S<8x7JA*y61M~)IGt{(JE~^krz@d58t@jZi@fOMR`a9?wZtZbNLaV|DV~&AdMhAW31K5Bg zMeV*_G1v77pEM!p9~rL2U=<_!_9x(b??N=~f|||C#Lv{z_gGWjruxC<55hE4Zkhc+ zPePnN74S(gE){whY`fos1j!6CY+IwiuT}FoA z>BasC4)3Z4h6HOQf**E}8gQ0o*08vSfPWoJg3*HGdkVti^?u*|3Mn%CJ?bKx`NvSz zrZ&Y3EWEWPsQfZ8-XvdtsOclIQiF#FUzXA|lX@@;i^T=J8U`;E=rhfRrh{=fp~ZUrwH zI6MGWYJp^jPz<@Wfa2Pp#s$7;@L~;Kn3>+s?<2u1(ZdH!H}~5bU7nu$i|6r@KbDs1 z%Y(z-VaIFE%)S_|EdC%#Wxjc(`M)aJzbA#SiH4)$k4)L>J zaDtn?*ZT;_!Vk;q0P(rCFa$hiLcbEI)J<)Cgc_SY_PglT0OUty|K*<$=;`wV(|J}ZtqXgfZ6C2AVFh3c+W6fIS`Q_ zTj_mk&ttc7&M*~eZYrdbnl;j+R{lAOjPnKc{E2vr@BGmz|E)1YG*5ee=IF>IgC8=H z1G}^Dt*>Ne+oU7lGzj3+bUnkj@VBw-xq~GV3gEHjW!hT6O7mLn57%i8>}3>~B4)Oc%|;+v=I?2}e8a@=cav-!sn8JT0NI?v3JAmBkf`l45-f^X>&`+rA&K^y2nF^Ecoea`oPcrRg(4 zS3R@2-&zv#nS|3LW+O00YUEmWujv^pccejitEmXeOgVaOj)Zy#n+zus)E4!ei$Lny z$jyur!lKf2NxyF%(@G-v)LTF$t4^9}_->wFh|nvYYAQ9MgU*fZ$;TvG7e(q)opOj7 zzX5T5kQ#Lev!py$U<&&Es!Qeko(=R94k$n)eD8GM7}~nhjPlptCeey2%-3r)5W$7fk23- z50N%+tzvPt@?8|G{s&=)iy5(!G&uv09=7Ripmb!;arp(b7(uX&lv}U9_k2f^7xYIm z3NjyDmgZF~l0amhC3Q}@5#W7sX_SDPg{Q2+r!o z%C4JbX5jTZHPDsWuIvd9*$61Z0Lw-v2OAW2HoYz6JUg+gJ^iJ}tNz4IIpv=f=oY8p z*0N8>MyaL51E~75YAuH1(zy#9kt-LvrJbB{^Ry97jO10oHqDglR@N5QI0e_Pup>4P zL0UfcIIf}UO#0m@{sNl7%Q0(^85c(wRdn))tOuB|SacY_)(2{*w;1$qpRnJcfHSU z?T^N-p<$y z(^`qyn3@WQ&!q;Rob!DXQ|vgh*rH!5x7)YZ$;^AtIcr-^pKppJNo}vZA^5YTXMR?- zBwAa}aDt~wchRSe8%BNc&onkTn8{eSmCE4^FZ5dPJ~krweG_~a8Ut*2U81SoIQoJ+ zaKp71nL$Dm1~xa;H4_h&&qz@Y)F5--ooImH3of{IymvAQ@$?#bGLw95q@L#V_nld@TKq2Y?*F#A@*;9W7m07(DIFNCBAd4?*{J=mHge*hzXGd!{|zQ&^q3$l4tr)rg4jR(*6quQJ`+i9 zD2`5>LYwqhoKg`Q4zOS>uLe82`>?!;O58X_`1QiPeU6+8j;a`NZtooTt`Kg4En= zu4TGp!m|bIsAF0Uz4gvih^$d8r-ucqxHs!R+n4fZ){-ehp2dDaJJMPO;}6T(ArF3B zNh)Ly6X)xnUWes7o|~zh)~)gcV5i)()cks&lXj9`m7Tcbu-m=b)&kTvKax!FU;fwA z^LMwDb^KvLrDQ#rn6<*pidIbyaS7C&46F&w4mue@3|)n=0-eJK#j13--9G}Id`fUP z-=yAv`CT#v+y0q7soSWe@efI;Zm?@xHMLo^vI$kX&vU7DyULV0?B$CdBl&r9qpZya zx(#W^R~=1ihg{=Iqrb3n(_DZ?fh#&%WKqXF10ikg_s`y)+_vh;%hBIcPDxk^O> z$uBITe1u5VR9B0C8e!v@nk^a=N1z8+>3hCMPhb2Yokj$ezt$Mt>D ztivHK;(N0<#11v1obY5DY<|%Z0>i3>jDvUjAHu1M_pt5Dl7dol6z!F72y}Dfj@}5aDr%{dK17l-jxB?YY|BZjg66g z+-eluLDURAmQ9|CY4GbEbY-0n*#;x<-K(ga`py)-8*R=alKfpZBq3rGJXig+hL48*fUMr01Hj6gM z9bX3A5VD}i>YWR8q{82RkCC`t|GzOQ zG9O19fk={?N^yj;G7GsYyL8sqlSD*K#p0zRJF!6hryi~?DM_>1duWf4Xe>EXN zu+w<-l-@FeF*E)17+2(UR1k=eI+9#PIgsk9HGmMK@+0Rnv;RL;V&MUQrtDxPj3FB@ zqBb2>_A(Rnl0}js%Er0u18Ku?)1HaQ>memdIO&VZWT4=AZjKeDjNbbZ#Mr((=!FhN zt2WeUYVbTUpJ93^S9({CrYGzBC)d1sMXV^Joh43BB!Q^o8KAXrS9~Hh;K50aCx3=l zT7)wiL+aU_+EK4*ta1u$Z>qtVi^SgvXuwibpaBWif}de=J?}y@a!`PY&HvsXe(b;is`!` z;^D}2(O5s6lOFHRcD22-4X9`L@W!{AWyML7d>W1}(a8q#0iA>DXLwX|k*n>wyW4|z zFE$FC+GOtV11x86UCYRbOQ_;O)>Jjx_jJqL$*<&}_RKi8DMc7Gyp^6B!K zvx1IbG0qol7&ZIfTwi~00qCky1MWkdz|x_F#JNm4eiWtu8q1 z;*_lCLAC|v0rRN$(MP8?Wonw`pS;xP@yN|+@(G=iu-FBnv?QViqU>q;! zAc)_Z4sargsM_q+XO`z^ zdlzSzV6H`~Jt4|Nb+BY0_V>ckoVV7j%-3fQqsL!SMe%qW&IDZ{D{@IUxXZjx<{GU1 zSovQk*{^P^KdQ))YFG$gso*bvmMOy~FU;ILGT zD-J~9zh%hX@R%$RS`%J?>v10B`K!rmA!qC2p{r+aDJt7C_CJR}7;uZLt4u{|6V%sG zVZ!{;m8D!Cz%&X(Inyvvo@j_2$iItfD@WaZH^_F!Q|DNNQ2axrWBTO{YYS%_2rymb zJ8w?;&!XJTxDJv>;AoFf97@Pbx^&e*!Xb2_KXv22RVj_~-;?qQz|1bs1jil54Os-$ z30^$DPvC-QDL&&yqtbJ!Mu?}%^;apHO?;XgcLWiqw)4aZCGh^$*dGl_6WEtpoZ75p z6?*?6;?g-0Z^--cp}<$#1J^*TcBl9OcH_@f@+S!VpM&!fU|Ae(FJv}ql!_OY3gn5@ z)!c`nQhW|hB7F?CE|=auK$ypd zwxdf;mpHgg0*U2DmE51?kt)Q^aR4Aq{I$`zXCD7#;cZjzwp-zXEW|8fl>q4^oE4Yi z>A}``>*}m|o>Q?y9nxKk$JP?PRo8NNG{+WtOg`2(0#%azp-&N!DQVEu@?(x4dR z0=YV-(p37@-k6m>r#?|iLa+lQ*!`cH~S>I4^7|(CDVPb z&CC~B$6ZiLkS6X8Qt}U7{wQf3{J07=;A5MC2c| zEZu>4-&UGu;oe`~HtB(9tG=St_m!BDlQ~wB3Ky6i^1Pw_jTA3_jdY;Uv{Oh6v6uD- z(Y))f3d=1`hCRn(xDK177^O^!)LUZlfY=R18CR1M(7F$o*~I$&HcT|p{b~X0P;Bju z2uTR?~3cUQ^rFz=S%F- z4EA)X3kM(`;xNhJ+CNO&w~Ur7(fMR1oosO6xvLJuktLrx_one~Lot)kfRMO3d9t46 z{RLH}Q7aTZG5_fi`jMH;@+{-qelZ@lbCYFWtv-`r|4vcgfY0UfTmSctry>(APeiBw zBMkCxGjE$P-bvt)8d2#Y6W9dX4YCwk|0)OSk~!zjfPAjZ0s_r)i}6C6m*s;5#btB; zCqAn15_h{2QO41QbkO4ObWQMgi)k40M=0!jHIkm-8)}akiYi zJ?e`2e;$txM20>3Zx*&u!*146hv_@4EL@1zXx9hyy-ofUuW=up2bY$4 zAA?{U!Y*1ZB`t#MGUb%8?2Cc*=k8Wy&ZfvW)Anr6vm6Hx5VRFW3HasQ<_+sg_5{(0 zqYu-HfmfmczHcwr=0$Oy8<>mhLE01_?704)wAUtqAFZ>q5Ntw57<#V^k$9H4)5NEd zo_R+$MGne=oNcjQ%aTdW+cl^KefPcWG5W<7bBycX*(}iQ==0ZMq!WBU{-kiKUV}(4 z7M>TM!7gy=y_LUbRyMfWYPdb~SN(7+fxzm)Kn9Ja>;=Q5rVrMOXj5MfXOt3Z>fI*2 zG_l_T!<`Ml4v#Fu%o7KCVL)F;H*%sIHjvh?_GP5@#QznG_O_>vq&O=`U}|%N_1cE) zfjO?r6sZnM@-RF0A$>uVnxfJu3JfJWPr{J&I9CAgh|6%!^cPM*X77{Ku5UWz@N>Fo zqE|1jt!;TUg%LS@dnfpCxKHUr>edd3l3DuFri|LY#TBx1H|#|--BtVAcDCy7v9-2` zv|0(lJJRiMKvwsWe@lr1Ut>v{^}Tk6o|*mcO>mJ1NOxjaKGqF5A=qlw6)fA>6xoBS zTFy`4Oq3mFPi<>1hJw%?ZiR{Y_sQ3O&WtS0RuBjr^0x!y?Ly$y*;!<#yu$SaG~tcy zg;+6%#*}@275po!K8Tv>mSu#n1NitI~qN`VqhbJj%yAKK6Ud1*f6l8!W2FKC`j3wr}oFLyTKY7UMeyY<&?HXF;Q)r{@=(*yUy zym4K>`6gG;ia_s>_a(&to8bewaP~sFPC3pJBb0Gh`uPk^TL*(FbhT=5t18G-9FgQb zgQhx>dL%T$N_cbSusV-DhLb+zHY>GsuoP2AAr{xMvtj^jUOVNQ(pinG+N+(BeOv;; zP_rLdGOpGTu+{Onc%M=5B&;cRC%$f@7=OT4_5XS81HgRJG810eC>;xr7MjT7#mt}J zNlr;t!SFXZ3dQ?ry+iS9*2xLaB7oo&r)i*_1|MJf5XH-hnB1bBsP z+pDI^t_FbsvhSfWtEkUDaA6+&4<-4{%(7!MK3-N%(cu*#}Dwl};HOe8g-dTExfp{A!B$>(J;mo8IFqIbVAg$Ggs(^qfyhBB2HC zCm+-X?vGR!A2*p}75xpXpnP$-yNDx>il40~>ds%vB}@hv78&=K2kI3P5D-0AqcY<}^D@gLk`Ek8`yn>a z`2run1dZyt7C;JJ?}D6KQ_&N<-Xb(NlGDfJM$`>2Xfi}Mrf@Vm2Ueq z0cUghh8HFxljW^^_dt*FqfUU0`Kk`FlqM$_jiLzgCL>ho7KrOIK<**7WAjHkjnS<> z);f545;gogn^S7f5m*W!fh zUhEEV)sI^{LW*zp7Sr0by~)Io=Rk4-j*K z+x&v3TG!x44j>`}iM*5JBJ-(}`Ax-&gZEt|>r9V{ez%H!1)6^bq>SDja!D(F2rLMV zS(+wIH&4+U=6 zC(h?YRN%tQZyQuW@a`#nYgKMg5RhqyhB;M&7qudDio1;8NRI(%L{}+82FJVgQGA0^7YNQGP%FTx~TO<>5Kd4 ze(es?)uacS$j+Bdhd8plY{fvTW$-+1hr=aIW`JQ0u z<<>@9(cm_zY62wMW$Iizogn3;t-mWslT79#?9M=L`ePNS#tBs z63Q8v7rUFUosa=-_9fjuc6*3!^9#?h2nGD1Tuai8+2LJ6b$n-A-Jc8)n69qGhsfOP zBt+TYqnit)|9d{)HT%@nQ%W9LE(Plc^iT|hoF;*MqE&d9Wl8ty%Iom;ZN2taQ$A6(%1$Kd3C>#BYPb0S8rc9C!tWxUr*L!itNxp z_x#9^b{9g_ticlPeDxbcdfQMBd=oR7U^cX8_JStRCebUveFNmxQHRaVZ>mRqg|9^( zS`5Plb>}8%rTs2u^Fv-&6w+Jg(NMHq&1`<9@8XCCS7psOZeB!CzB_{A8JQ00zt(?U zjA^lL1-psswojh<7Z@X^85zrVHGp_@dVKbv2RUzLd|UdxDdsQhQdaIvDDl}%#+gXt zmu{V(R<6S*z!)5LtVAz)B6%%8BV@vz`jN`oO#Q9kw`L}X27i)!Lt(7S>qZDn3(`JP zgvDfg!Ih)8Y?LGT@hs)qvFpImmOpD^l5dHpb~us7fDI#&oMNv}<-)CS)|V<2CxHfF z=LLtO4ye_R+aMqqjihPp{#2#1MCBqLq(6{MAzvMv1Mt1lQUMH;E|RfXfzHtRTMAV{ zKL8ZCKqge^lxpQSpD|stZI+_DnG+pt{*fJ@I?v9n8qU219K1UU(=Zyx{f)HZsQFue zv0>b-1O-c7qiK&7>kWaS-O+3yfwb$i=lLxjT;_NdM53WPvxCe{?Wf-hX(3ML%n=sh z`YL9Geig0hQfG2l8h7?i%f(>Bi6m&^-%4Q2su|8*Y7@hI#)-tZ`r8`X$f0xPlOU28 z|4m>59kTZFHrDC9#ZOeud=VIpCk7gy!RVn>WDlL&PwMx5v1)*HqD650aL6~QHc~A< zPxifoHa}}&8K7MV(3l=qDGrupb0JrK6VfFB@=>)+Hn~EMRuz&Pgy+if*f|3yA;U(9 zRwQP+5Bi3WlBGavmrM>I=2Wtpo5KzFU71dPcJWC3-fU9?7C=wDH0ZR%XUF)VN0!I2 z+x_1_h+0^*ha&)s25lJz&zAb5ndi^XR6NavBhX0Ew)^nQEn&j z`3K@~YDYVr19Z_O&8(A;&Po1H;cQO$jQcie8C;t~c}!-v)=RL6^WPMkFX9bHn5ZIZ zPR!~&KpVN4kb62^$AciP27H>mrA)Q&-@oYu4HEf$!A#Y%70=B zrV=H$o*?+X)Z+ecMUgzsS_DgA+PnhKLXewUW`tvLqDr@ZM~dpbO}_j8u>fQ7rDd78 z$7|pxg)h0njA;MTRZ`^R+U@hPZrv4xT#siMXc#EoWwQ~8Dy|cuT-{6ZR!n2$xG){_ z_+zYjafFnA>W+#ui<7xrm4r~<+^Q&UNLe0lApZM$h>F32wUhe(+nBd4U&1#JLEl8 zRj=Ot{r$P5{}*`k>z`soM)=)l`Sf`N(bdY$+f@w!uJG0)c&k$ z`PoN$wdbW3KP)ahK$2#z=NA|~vdAC?DA*}|u3z<10T7V_Z(Tdks4rD4Aswn;)9`N{N2(8if-CD4KT2zpTf)eMp!xS@If>((K!3VpIq=hnzK;K{3pnH)s-y+ zQ%nkMA`Nx@0AFA2(zPJCrZ9@hvr$0W^3#i3*c&?bn!j=~#RTm{-lzN#{n%3DIU|O3$b7%ja@ip$3wu4G|{x^I< zmIKDpV4k>LR(-<{kEirqG;xpm=yPRLrttU7|C!7pG+QS0PMtoG?j`otw}4?|i?n`x zn6SMV|29VWZM6-Hi_&?(l5pc?PUtt@7`^Z2)l(fZo3CP7uedk543Q=<@NqNiwb6w@ z;L9Sw*K#1zl8q-PVFjz9;w4sc8RB!-kI&I^dmDCKh?r zPF>UKDskHAP{YV(pWcRSZ?*W?X|`|HgF<5bhT5&~PXmtV83jKdrCvrs&IbWVlVtzM1LzALTRbdv`e>7VZY2M0hP!2pzed5{*sVmSf znXQA&A9dYoiEZu$Vok|lLy*67v&S%e- zn<*ut*GJeA9Z|k9;f#+VDlX5JN`B!eMW*2kHW@3lks9_X&28^b;b%~c$oYrP;$=W) zv>H}uin;BQ$BR;fB1HuH3Lfl!?q>6-Z{jp8$|ZztmGJl$L~z(1$8;r`iHyv7>cvwf zGiXD(*)z!5C*&c>YjJGz(s_FZRv}JFKK&{6s?f6aQg$t6Oub0W$t(_D@1VnM1`8J9 zL>Rf{dyVwOz$;R_4P8GhUCB2|8%|pk zby_kU@F}EnI%Q?pT?r?16=CL{^gE$5Y6@k08dGn4WQD*EgO#KpdD_wty+*FzcJ<$K z*msA2cAW}HS435{1bK(Qsw0zsuTJ0iaJ!q0OC{3CdTMP?5aiPIEI^&I5@IlL*wO;zo7(!JCgL6W&UkOI`;3QI z5|z|X$6<)#VHJX=D2PEjmla9oUu{H$-AJq`RZt4VGvbhM9RAK&y83Y#WXQU}+c7%| z#=2g4ei|-T?4B1R#2arS_KZ?fT(s57^|jen$MF|h86?WQ@i=MHxT<;{cx%qS>vS9F zQf+MDLty6e?BY&n?U63Z=Y}#kh9Mry8|~M%CjA58dUgUPAGxbxkCOk<*)%Gf76 z<`vRBruH2$B0G4E7!OEFF!6-qHGMRs0IA;iK>Xz$LKPc=U?gUk)thvH;VOPZX}OUd z8rjL^3yy)#E#&8VRb~jCBLAQbh#JN3T-WM5r=W5kD+z*j!eDa7jdce>XttEA!RUAN zQ8{;>Daf#D@kA>6W}WAwPI^$?mrUVs*Mam@yEh>U4F(js5k6R>oRt2{wMd;esZ%q4 zrL@+ipL&$;^i?=LAW)^L9TlU1>ILb}*YSpI>h2mblz`#ZFF8Lv=L4aI)}=5bc%N^| z#$BcHR&$s$7JAP=WGxL>iM1VHN2lqB+r&SMl(inE5%zW~#(>!(2NAP>woO;vf>gRy zyQf2~hh=az6n64?{5$yZnq@(}*$*`Od7K@1Zi9H9a-yz}E&9;G&9N|xIzHr~Tva0G zZI&$wm2ersn$q^wuxSm@t*(oQ!%66t8kaH!h&Qn|NZ`=0pE?lRyB|mwl@Y0lB1t)J z?~L1>W=VtezE{NiCY)C!5Faz^_W({$OnR)1=tXCD3WF&sx;5?wXqfFajSt=RCFyJHNMas^Ks*lS}Ez= zVRGe=bn}GNi&dCUk$?1n0!55f_Y%c;Gna~aSrEblvkS4Zh8|KjPCu(aK=0gl6OFbI zoDrU7a@X3f^6)Es=4aodG5)pkYceB+W|ZX23D{|+$)|c zg`q?H>UxlabvcF>>{Q=7bl1dJ?a?nkNR_}~!P*kx47wUl2wm8@{cz6h;_+>1L#fRH zdI+5b0fIw}N88u&L2rRq^{d>K+E>xHa*nWDe!fDSr<1T=(Qh6OQMWct&gm)3+0i%3 zlVk(&IF2XE!T1K{@Fm6g3*LOnW;VRC#%$@^$5=`Hhu^Af5D(V0A zzcg`IQJ}S)@SWI2E%vCXsHm8)v6yUUvtV2RC)g20=gyxaQ?29QFkbe0e!03cKJHza zv27gwF)V!2+REMf149IlUT2juHJYo_Y$bH(jgND?Ge?wJQ;0zT!YRz;mi_BwR_AFj zQKjV!Tg_4`&DVZ$bY5Y;$uf{vIG3iW{Sc812nNTaal;YVjPH!@^=|!~ z1Krg!+jx_(ftS+NqFI~q`9n+#vfoi0U+89l>d#^z%4plWrM0S!b! zO2RHts>X$m$?!5^qcNRvAI1*X-=Ufz3WVeH`P(nDE?J~&x@Y)O^dmu`Ha*IN{#nAc z`P8?i$L6?+D&9eH*^Sn6^dZ+zK^$VPAnA$A=Vo#fB-3nOn{AaF>c{M?S5oc#O~+`& zNW{TUOQ6m|%T|)>iuczv99QqoiMxxR-%)+;&(>{C-Csu&*LvrPjRIPg>FVwI#RuY^ z5pxzjWpJ6H!v-OwBJ<;yfA&umPujYQf45si;j$`P_dwbVYHN?0#Q)}A5YdkZ%_zeq zf{#R#X4zkoP>>*$qi=S02H$K>PDaNaa{+JkU?V1I>rjH?-9%>5$S>Nqa{N`pUV5s} zBX|Mz)Qrmu0i;ft@R?DYtK_Ub1L+yu`Y)SnE)kxYt>y|nuYCjMklxIw62_}yC<-&f zmzJXqTlT*#4BK|&@^1j&wcN^xAxY~D9jxd2O;;z#^Fhn+Dzm|JT)^+I>8*q2rMZ!k zcYZFKXU%AJK4N#oo-66~@%=>I;>%}+d4ZB5mai}*k2cPgM=c`!kVT{P$+o~22KN|S zs2oz+IEm9Qg^JR{+=<8e!jklOh7QaRH$ooRYg9&|9h&3bM=y{-Gt=gO*4V!u)YW<9 z<5zMn6HJ^v^pP)ke*&x4XX<(_Ew*Bl1s&#&6by2_U0&35p4B$gdUmJteZZ2xYk4fH z>6jz*j$ixh-4yZhR5vW=m2*6yt2eOyq1P@x@cA^5?M-b9&HuXV~a zhkoI#f?dsFcQAXz);0z>`)(OhYUwfOhC8mwW!<rRYONUM-Lp_s)C($8=z%TFFo&wI zu~jm(M-OQxfPLAV!;%T4#`>sa{w*YBhB1f(bT*v`;Y({4=4}qGEh@+TbXChHC_bN` zx2TvWb}b+;If~BIlIJV{J-cWhj-SA9HOId;_Lm+@Vn`^!D=;5`FO1DsYq~`qT*4u_ zwSqeHiHn}uhb5{53Cxi5i&nJGy91+bgt$L@)gpwy&sn#QZsMZu*XzhdbfUL~X-4-( zxma}`1raeetagF0A$bAaJP?OXcS;KPPkofRp~axXLe)IEC%rMd+n0pF7iTM8WLFoAmbu-mOa!e>E859(7lnRy72W35d#HbwLQ zT)Pz@E^P~-pWQGrM2OI*kWD2P%&uybfzALF!FalSC3@({FgGvPy2e{#r8<)jbCZ)& z3D#OVghGYJv9^IhTkD;URXtwKtd45Nt^a1;EU_s)rs5{>XRL%w7|86N@~=8KR)}XW z5|ZXQdq8-tvb#`R>g4@f(vLn$Dh!ngilDOQkdBnO~0NsJXZo2!tk>#_ul#(xn= zuXx+9D3~)JLzlPCo_zB1mC#>;qO4z+>3uZRF=!yWu4z)d)B!H>T_iF?u2wRy-=Qt< zAu^!7+q;)8OZvJgvsF$4--0e6r>llo%A8;5iOC~#REi*{EA2Mbe`{>|Ka zD@L~3yLK(Enq!}XpLM={aW5(SGYYTARm#oQMN^z0DVir=!*z!TZ!_GVhN>&cZGk%J zYe(dCbu2*i(GT zZ9257(pBFCfu$S=T!)G|gXkN3qYscj6)Ce@EL>`NQR#h5_tr#q>QkJWY69Y`1c;|M zZ;M@uX3Z~b0(XFh2GwqcV_%+@5;V-V8NT3*;+A|yU|2i%otQ3QmEuG#IN3=(da7(iL z{VZDLsU4%v0a{T($3Nzrhdx1uMG9rmSzIVLy!bhZVe8^vYV~Q670ba(Ic8DYbfA6V zvJeNDykuX0rF7JWmMuO^FCukr+d=^)F;>$x*m+ah^Os!c4&sxTEx*Q90UM3&qlOs? z$dGxn?^AXPgCqnbq*x?OtPOl=UTeN5U$}|02nb8l247nYoO@&{yh}EaYt{odH~-g+ zIwNyFJh9ynSELx(RsHor*Y-QVAup9qjku;M3#5}M? zyx@$EDXF(1Jb`o*4qHt;mN7asStCkze zNobCc0gNx-Brt&L@t9j%xI?XV1P8-4C&5UdYwH@VPlPaC-@FKDoPD5NpG}asqjDq* zs8t>O>+#Wda7DM5&gXn?U?F2eW8wIOQV<${+)Kdr=A%M-IBh1Rck^XU8;rzsKxMEZ zeb)4ks`i-5AWouvf?TM=ELLSCIcSuy^)tA(dyCYrH`4him+?V)HHL)wHh8Q&nazhW z!kNl=G-n)|6m!ZEV5|^2 zPD_K0VR`gCZH>?WU}$A2gq>sB!hE0rI955MQ{N~8J6k_kgoG8{jX-A5Q*qeG-O~!Y zplClgbItKGmb)PSnv%V4wl7Z~`RBIpcBm`!^C?ihUp{EfYdqqzGT&X}!G8^MurD9e zf}i1JNcv?Xr13Ett}rp>zcVCOQq3n~Ru|4hl$i{PFjLm&^p*tYl#~zjipOIi{X9*& zC}YV;pG4ni#>#Bh>b&eb)wP8pkHwOM_FuDVyYA`}?}9}Y@>+Hg)M=ytKI8jmUU=@B za5O!k{qp^aWa@W(o!z{DVs|TY#UCBId0ttL&h8L3MDZ2$U9j)88SI$ppih!MwUJZ# z?f1W!+iXLt+5Z|{!pxgz@G!${@U7g^pnp`=Yvuxo=E9Lrg_o!2-^#hJG%O@>idR%3 zsmi3JG1sW`N0NuaURSm(eq%WjUyh|wE8dD4nkXd~>c*qF0_OmrExwQXn(rDbK=bP^ zaU!FglFJy>hAj$Y*}8Lx8Fzw8G%>#1>Pwoj{@IILre<+mACXVR zXaMQ=Rvv+>DG?#`Da}DcvhPPsmjAIX5%e{q^YQ0)l1=6Pb z)~i1R>@GF|h- zA~MCrhq)_^QiKwQDf?mT@{(v-jzoeGoQ5?KY@#LcASmUx*sQjV#lv4reLSr`_I~DA?2F3 zeB!g7Bt)$8gz4*qTPz8@8SLXm=Cs}_+Gh4@FoZ@? zPQWm)1*H(`eJnCVSzIHx=~K_7Te zdd7fyUo13_Job(hL^{!Ob{n1Q|2I1NrT~_ruK}&U>J^bopDhVfvB+$F!gq9nvh5C> zOM)Lo0h_!uk{jYvcF@P|O){hoG)HqMP7T9BLKGRalSxUzOHkbSRZ#TJFCLki;+`Pi zJ_I2Amb2UiIHxmFD7yJBI?~Rcvx4##!Sm}A%bLBsk&eD%O#D&oNo_)khU}Zy=ek=i zdt`rEcGSR+Qt+qkj%L-obmn^$IL<`K%{`M{Q4ev-aSO;_@6JR$sr2-T4XFx`>vJfz#GErQjQ|bjg*}Kg(qY#L^B=P7_)aXXffNLl!ut=VA?F15!lj%50f+>S2*`ZeS<11D1RI zQyH$zDql6+#EO=Ph*sj#OZ$w>pIZmBpuh5UXM-H?mfJLW)tiIBgKh)~@3N2jRthGR zUzogw9=|arga3U-k&)MCNw>iC_kl^TT3-5~`RmY4U#BU^{sfY@?5N6Vo9AGyR76q1 z<>#IUxm4^EyZ89@s>IAKX*ujR2afP7b*N7TT%iyv`{F)+Ryv!(>8Gsqd;MlHbIkPM zxK&YyN$j%tS%VdR(?;iCb@<#ixpS8T)PbJog9*eP@JH#FYqK88x0u>-G1J``QG9cF zUsrdQ1u;(}eNm8S?pYO^y-fPb4p+*GQj$1=XIqy-3snlOYGjSR`cCGeRs9mc#O%oR zk>CA?Qv4#Gy5Nv!;)qRMA;Vpn4CQSd0_MwD*yl%hj9I+sIK;0P}D#Ke>p)}euxh-DGBp^adqZ}`4f2zm;7h5Nuh2Tx0{t!DO4MOcnn>;lohI*$L*jD*$McfFGBnapKEeMmYo^5w zAu|iEqAb6%tK5M=BHxw2f$6Z>Fj!n+%e!7gI+^#)BFF{J#3)e|bIT>w<0hgxT*caJ;;`EK*I+W6VbhC%#?Z zV2pe0HT^kKVhC2)<#6a;BFYr0G3&T|Rt5*}eNHB8)oyq8_0^R=hn_6wi|JA_*Ud5#3gNIfChHS7PjUpk348Qp|= z^ZodmN>R`1*t$+2`9(PG*7w~L_PUGgK3)1q_U8-f`8a7#>yi${$G_oDX-~_ehR?Jr zc~53F4h*1fSsyX_;5i|q9JEiqctd|waK3qd3!(z`uc%Dr8hynqbYB)5=rqQ=Y={;w zA>qB_3*rc48rdx!iv8*hLfB#D+*zQC+u59Pbr1MVX(-ptugJH5H8|9XjMgB~Pig4x zVKm~zRzp~I#Qp)4XV2i`k1;TT^pCS%X}w09`Z7(SmP59nk1dLWw2kSiUWmg1FNG*TX&D)?glR|xG! zN(qzFCs*S|srwKQA3d^IoBIrGrLGUciu_h6NN?DR&GXkiJtzSb=z_COE!-ekbTr+E z&XI9mc^(e=o?#)r&LPX^wM;dw??)_GKNTu|rDpd|*dX18{Ok&hZLAlMd}C!;X*h+O z#LYRE!rJ29x8g){e+?Dy41~t5e(sg!Pf;qE?ylKqN$b;7Ir%lRY^LOVAKM<^C+GGJ z`UY4ym%2A$wQ%SBI@oh9PG_j!JOnc}G;Vap<=2bANw$|Y;~XYXkE+O;y-sPHBNyLz zv9Qi@qK)q_{1~cdiDGOa#!v+`z7ft8b~^SCef8`3XnMMIaywU2@cK_zD8_1V^RUn8 z7cXl9Xz~&PZPyOv!CB)X;A(tFYK;>9gp(7|{%(0@L4Re&#D*Br3|@YrL;xS=$%6FS zY$ISG|7|3>YaXB$6M~yFVX9`B+j2`PKzHs{9szpjBpkhmp>{_7*Rb0q8R$1N`?%ow zvnM}RWb4l9rTZasqKFM12;5C5s*{Y__H~&lh0Go>-7|Ad=|xnQ*=mBZcvXYT7Gw-m zFAxxA3LY!WN8Ujm=n=rd1Kyh!4f3l0#{x9aX68nh)56l%bnPHhLke#Cafxvl2p6+f4>gp= z>L>>`q%~T*3fpe&yK%5UE*a2c3l>B z200iEXw(gfP&)|1Qcha;b|vHoR0#8dkqDrO6Tl?~kv}jf_J8)lji<_H$eR)4R%E>K zrJ=@kE%=vq&{eVY?uCeFX>0r6ckZti9n<(HYXQ|8xOpt_>Mmj>L;JhY7Ujv1c=Z_iN{9(b96`(eo>01fn*qu>32#L7-@mUsAnO?UXV z%OtGOOdSbC#@U=VXS0xlmMTZ~pAzx(N`IH@uOMVAdYFwUh%L1J29)yBY-_$f+F$gX zl7oV7YLX1V&C~Z}UjJL=pHD3%gELmjhYreqHqvl)f;*+8J}8?04Cg+)c994V26atsf$%F{4wkp7QNl`5WGWe4 zJ~&9+DZPX=waz*3#*CbZ$EqkL-A9)HjJ5u7{_SyITsZH~kP*AywpLi+&W7M!bow1s z{;d3K1$M6SE~MZ;KLu)?A*y#`ZXg&9CP+W{&}h{ZKmTEvyY=`zsU8ZGSkw^iS6&Ot zJj-YLsHfWD>5KS7S9(&ClR|5%QLLR(r2YUEobMpmE+NRB$}_*|Q^Jc`YglsW2hqtj zjnA?CqVOMqHf?pqPgG`ZerlpMZg-DboL|UKdbaPK^ys>0Ji&BXa!9;SA_(A5>b=s#ix)!2C5J$2u)2IrE}(fnhHDz(zk5}MTa|w zf{%(0x!^JQ%pMrEjo@n%Q>afCzi20)nYZ$%Mf5@UGjn|=eg&kYn_TqoS;nNLY zI58?r|TL$_dIj>Kla3uHOgAd<9u_cO5Iwp!oc7Flr8`N6k>i-D? z+-rnu*_{a5Oty(kWHSzbuc6e8NOUC5&*Ry!Ehf8}5gXc@>y$I{q7&9lgXBjIXw>YE zgJzNfdTeTghN~L9IVi>^mbJ!I&@P1eUID6vI1*7wzmK>JV)1OfT^d+p_&mm$K8vO3 z)+8tE$#ty*Eh_}XcfglA_D<%B1HN~^-#0Kqosg%U`Bh5R0JL%X+P{6!yZtTI%ue5m z+Vu_#E!jPF9a2@K9MUV0xn)hcoZqVUs=>+|Akla`OlW@J@HVnEI*pP;@sawTLnY1h9Cl! zv#k5!wA(E+9uQcmsw}2)Nj7rrpT8;J207@KIcS%w{UTC6)@%xVYO}W6wGU0yzJ`L5Dk*?OpWZ zP)d`tkNHo1MZN_nS*B7T@&GN4tlb?=NP`KQje z8-({;-O%?ehaaRx$c%jNwc?x2CRkee0`Gq-vdY^jeZmqdUQ0YWW0P*wa?tSmQIRcN z@n&1lA=2NdR7(Ci`M0J?%K`7vguSX<5J2`3Ad-YZ5`{h}UCnLw%wDpmCD(V~>l6!_ z_TzafBYyfl-IAShZyujR4$*Ml$R)+ufcHEAJ861Si#b_+VOu=cLB^4rI2tKWk>EmhrYhmnO8>r=rK~T33hw7&owmU$)Kum5RZkV>5~2u2EVZNa@R#9T zA&3(v9J-{v^G1_Er3-Ws6;iy=dLr-k&mQI*mQaUKyq|rfEq$krM`yj0zwom5xpLT> z7#zk3^TG}>O?ztp`2%yEK!X5|k9lqEN=>R-|3b0SBhv##D_b7C)v-1#x`BdYd3a?- zvAArDcX|LVIj7MLbCtW0QXdr#!JY_rz`JvqJeL<-)#pze)gyT>I>V9dimRmB5H?cn zlw8>7+?n!ulOGK^=y~-HK{slN9dsLj3le__nlsWH{&~-{3WE+cAI?cv?3J|84P!OI zhH&ITdk4x0=_E?%UU7lv$3c~Q0g)2TY-yT$v`(OfcdlqmrR-%+g&g3Ah`{8%4W53x z)evKy6WexIWR`ss&No;t8*$RCZ4@vulo0a7c!zuNzW+uiZ#af*5)Zwpob26EKHE^O z>SO`M9$J5P?U14gV5fiG{;?sc?HE{+RSWYcgK^b=lt~vR=k`ZLdbY}?SgL5bmhp3H zj`Mbq%!j|>m_VEh1ux`z#7r1pE#@4EFbQE~QN zt&E35E5%ccUQEKsI;&`aOc59dC?)^VTE3AQqMP2wOF=&!OnY4X_gzM zbZQ0J<8?oHwk^OL+Gt+JJA>@;m`8#Kk~4(*%)J;NPW;*p4OYk^jS4|jSCF;6Qh@O4 zbj9Yp+Fq=3F%0b#;@od7;uL$&QP?M5`NFH+#lVmXg~_#Kdyqr;15%X(6t8Ns;pcv} z9Psh$%RP+C^JGJgqnujA!M%M!tc}VzBwL&5VoBcyQR8G^7Vr2rQN~kXXIVX@6Q2N? zd>TY1gz}~n24SQ5e;z0(3yb8h zK`5D(SHjyTyVyDDC^4gyEz$B{OQZQ>>T|JkEd%G)-G(BKhZG!P<&I*6+s{<+4LZs>ZC|K>8NJ(v63B)A$(CW$FAT(?fz2vyi5F8pB zESzxm&40vj`!IbnxB4WhKW|!DtCEfP$RwROg7dre1!M-k#D@B(kK&AI4e8saq-@cB zQVspwHl*kyHMK~D(V!>(-a^FiZbSHaqNzaP5$(8;Ii7|=|juGpKcC5R<-xWV6` zSq4vu0x#j%{%UJ|1v7b>y(~j)eYSQcp!$2P(ROEcut-_~*#~AO?F5RF?WC^Bt)__6 zJp;;lgdcmiNwMeTpo1Vnl~smUlxnYgO@58;^S$g#{ubV`nnTNyhTKCas`yh|vrZ#% z%@bhkyS=tj$lL~8Lk%zf?*1r$bGU%XNA{(`JC#%CH*1yXPdlW~7cx3{=Uu*b#M9So zDPN=_!8aB_53M{4` zTKI~~2QZ}{JI{A}+-zKNka7TD30bu(PxZ&r@Ov)dwIvPqvj`G>jgPe&B6;rZ5p#>q z)}0^t{~aht-1V@SaE*{vV;Cl4%l$gseZt%Fk*Hiu?6*srZGe8OIFy6q5LpRuNjB@x zbF8`1nh7M-MR=Cyew55Z{d2;yiHIQ2;yB8+EfPls7&y?JH`G?D;C{*Sl4hW}FWmWe zD-{hT=x%Ydyh3Wl#}_&#3Ni!H6J$1y#E_~=Vb>HSqdxOI-oei zMhd~G=4D|sYsnc*M)QD+eb1>Wq@Cx03qm~jHphY6Wb?J5=|baM4$jm?gcBlNA|sE@zX9ZqZVKYX z{j)eW7==meQysxX{dQy>Uv60y0s?$6cEFF)MBHNego15$!yWoyP>6zn%=|pa9}uHp zs!j@LB^}|)SCdrE%<&pyIvotR!>u~t10uwc*>EJ6j6#Fje+)~KxqnapD8JXG(R5fP z$JfEeIoiM#sXVdK1NC(MJUt>lP++~Hf?F~FZ*Vi%aI$>}?ZH{Uahe^hH66Y^ah`X=`fz&){n5hd_CqyI3pLJUK13HI8h3s3cllm`+3 z^h0A&H_y*r>J-Fifhpf#$+Srcbi@O_4MfG~i>g)!AFdST^EYcFK)yd`J6QIYg9ulf zi&7HpiQsEBA%71l?=OLghZ0o37~B6{iKPcz3u^xY?#nRIQj1h&{|scTxye*oK{5R2 z{&vi9y%7IN(YFK0P*d~#i>v{ot4vz*2s)W4g^Mzd-kA*Q)LgaR?WT`r*W+3hYu(W2 z5Wg24AG+JiLz#ve*}f{&Ewqdjt=Q!`{A?34ZvI~!S^4Xl>~YugkEj@=6@g4OraolN(xw6+m6pQ!Z&dF2cmi;JJ|k>1*3=Xf{Z?j`zZ4N;|F-=)RA zTy8TT+o7W@@Q{VIt~@bmn;(lF}# zmVozlU+UICYbibYGM)1k_RO2o&0}cYo>h`E)M5!Zov87|gUEB*^H8OzLv+c&gXjp) z-?<+@=jCCGG-O+-T$Qx{{!f)_VNslPYq>vkWlwMW4E~}P6fov<&oo*FKf-{ArH9Ju zb5_oB?h6mO2lAImFv>3QoqN{8r1FI&^0s0{KsgPSUI+n+-c9eH!3YP--h!xd%8mU)8O|rjxX5ClULYwR+y-@KRX|^}f{*b#jS+07V=vjF-~%$ZupUhNfMQ95$3d1(MgLjptvr*>qZxXsQ}|Hkk5)XVzX z9Nu~iJ-+p25&YczBj86Z1Ow#QE@y=n2;cVviz+p1KGtfw`f3QGj{o~ayrO$u!jjwS zahQ0j7$5jbXE2p-Nczr|W!PomK{8Lu|9dluKFTeXiy%8A5L{NVRzl)=kZ9pjYy!Ax zA<7Fp*=Pm%K|Zlo86<$dD~8Vu`tDaC=--xHr+L|wJt7&G`YnO~G|`cr*&1FVMyI$3 zg=ND`T_qyf``x!}PvS>RtjWdD(e#s-B#ZPot&St9a?n3OC_w0uwL`PP`-1F>z-rG2 zJDoi7hB}5v<@8<7SlkFvBMOjq%2~w3$XM_5&hU1}Y|0tJEJ{57QPH6iX>ArgkjqCBBOMonUnhCSKd)_K-p(eYkBl237Z>EwD_hHUPW@=Z>F^B9E>4P@~JS(#E z(#3Px3fBwxXs{a*`z50%I2BIV zPV=wgiE3awZNHLn;jl44TXWD&7UULXE+DKpe|+01X6UTeD>?u(^~NTI#;dZ&gZAevWK zTJB|YBY(1~b^DD?%;|=oi{b`vdaWo!z_^8)yjq+Uz3?#R7jvl4++coYzj~ARB%BNN zHjqi|mK;}-r5*$mqQT}Xt(wLydw@#Cg;d{t7(CQ>gtSxF=*eMJ;%|*^Q5_;F5gqMj zhu+d;q8L$A*1xp3uc3|Tb4<~6tB=0sFyw|bq{-Qejy)u_2O{1zp7j_7JW=53?0T#{DhQ)XHN)=C;mf3nB88RY?`dF@TkX!p-* z@5c&vgd{0ImA8{L{U0Zs#P1v#*K7bf_>n;WFQ>o;Lu50>O;rRH2Khe1xIda{A0O-!Er%5Lx7))Y<*ddo^n+Sn zDJ$060>o07OZi!@z zli8ipTz{#mq!_S{UVXIamzVsz$DI!aM;c+KCTA2Izxc=5#sPf3vgv8wZ1_ z@yGU$Z}3{d|v)H%mMp z8!8#6Q%FH3_n#>ptdM@bR>`y+AjYunH9Jfckn-q z)@l^77v9U>8GvM;u?PYj`RRW@HCx*t+S(t*nYv4vL4qBVQrK;1ImC6}!+tlg)I&0h zz~v8}>$go$3-cMM{=QwHxaF9B1j)PTt+C=_{iMu{q9AsE+uXu7!n)P4cBMM40C^Z1;#-|)K{5WOrPxz05boZ=>oQhE;y96rObJK z5&?4HZ}z&FG*F~1bM(2K@;9s5aB(mrgr`csS6I>1ogg?aJ^V>!IH`?VjElL(hdkq* z0qiQ_|C0ZBNev7BJgq24vcTk2YfRoNkXN{)0L$`R&ZRoWrvaS@Qy#eVnaY0)=I7KN z2NWk@t0xA}D)rad1lznO#1qM1GzosBM$5o;r$A(o!4TC1Ut*qIc2_;X(5uWJ(e2!r z@IhtcpyZ?>5zYf$p1eX6f0GRr@RBcf1Zl;^OnBp)&|wT|p-r)s5ipPo%gq0pII|88 z===eZ>}A7v^#!SjZT@W~(kG2ERPi0X@U=SYW2`{Sni5M)IDjNF!+o=6XT4-jO^B8a zdplT^8Zkhfzag-E*w$#3n_36$G8h6&=TB$$(l7#9GQhPGVw5n6lW;oexvp zj7`;6Stf$&Jj#^=eRBA5c{hMoQO>wn>6>#WHBwpjtXop`V1j7SK$KLH0ePxAcJ^(sJ$LgOfW&D{eS(QjF#ThiSI`GT22cDJ2qSyffm`%TQbD49; zzk_chk$(J@vq-7KKddcQn_9G9tgDDyMcV&0_lrXg6)+ zd<@7?J}@ix|H=MNuQEt*?p&~nHDN-yykk99e!jrdULS>&0asiz*1W%v$odkq3ER51 zE5?%R7r{N<1U=cO%q|k~SygC5?fY7R;R%Y4ZZkuEOLJ6sN$5MQx818>-V_|dCXVPQ zekU0iHkX434X0(%DG0f#k5pZAVPDitNn!cV(0$iXhly#hXNR9?Nz?3$y zDpJvAx&FA9P1$lSH^?RAMch#e2+t-TG$p82vElBc>L*+;y~lHnO`E<2zl{JE+&xZM zBF=HodhSyr>pW^B02UTuwzOf6GCWOtzmNQXEWldmi*qq5;NgIFD5)HghX4N?p!BK27As9&f{Q-d)plQ-QL*+A>l>(GN=uA6p}~k3eHuxxhPhprqOx{f04!i z+x|VQYqxW;ze6L1y8HG}*Y|j9w}PA$DNfA!w$BCVu38M9WW5IR4xe$?&xX% z@V#iV1NCcHY_E2dxa)Hqf|8DMyDRaMxUHt77C+y{hyK`&x=V!NtNVR#vdA)BzFxgjR5Jd z(h59t7qH;G8Tx{!;ol9SN%`mD@VF>^P(IInI{=k8R|rVAx8Sc*_QPB?T`}QWQ|4zZ zl0-)(p5qT+7Fu<|fYQ7G_VFMRO=l2h8RFTMZVq2q+NG>0Zjxgj*zcg0FRT@;i8wCH zZ5d3Bl8w=H1;c%r)qP^{y$Yrkm1hI3b?z4brmBpgfyA;Cm(iUxtrL6l56(Ucd9f&_ zLqBpd%)eAME->l^?YvmIGz%#b@>WLuHJre_@Ia#oY)FATu#~KJUI4Lt$q-n%#be$} zznTd9!Gxn)kCuqz95~WRbf+EG8l@4ke1ATm)xS7)=sv{zUL&WiMcfJK_u^!g>QfG% z$EVwQD0cW*t>yV!Vqg?<4W??iMY-`4lx2q#6K1seA)@UbAWqh09W!~bZ?GJ$#uY=Tg8vbXLi){K3a?%q+jZN#MkFje z)I@~HyOqfe3}^P926hITGQOomPCtJK5Hy5ltxfz6Nbl1YpS9wVi$I`z>zaI+Hvcuo z*8{#J1D)o)BBZ6a69DPOR+VKLE1QOU*~dm!JkqD>Oy72*{5$46tFaaRc8@&k&r!xK zsA4K)F2h{WGtJD3!?kdyfiQ_-Uv@4{8WvT~d_21|&XU`ME=Fi2$c~otYz-h^WpXf4 zLQu~?KL7oAj7|wJ#zH16Km0R&O3s&7Kj~ZAqEyF2)N80%)D^hyBU_)qYDU_<>96?$ zAhXE}>?a$V}c& zUk_;SLU{?BB_|DSO-V$m+%$%5A7iVh%giAoBTuYee@aApTYq2j%u!!dj^Hl%Cab?Pey!9YG&q>AhpXTgq)q{v z6)4$u$=n^&u7fuh>ORO8NbNdbQ_wwD*R&D~|*WFmju1jCZ|= zd(L*zor&S-HMA?`_2r1 z84n;g)G;!B>ab@XC5j>9)E%qDl6A4#5VEjpl|VgvaBkW>}Z zjZSCIGC%3sq7%!hahuJ%A?}#Mx19LCOIJw_s zAry|mK0oRx3Jj%MFdCZtN%d9h4k^UqIkKWbT&I9Vpmdj&gRcG6omczlhQFwOTU z5_`_IjKMUByWF0!_IMj`qxiSCgI0!JVNlShJWrt}q|>6sSMKD6#|Xlg7O+quX1PzJ zbeN&+_il^$p0#7gsxHQ@U_Sx*u)}$F>nC}#qJuG`eAtoMLKj*LshQf)xNR-dgA$x& zyVNy#F|Z4{nIPlykxD}K1HgK|_B?*#)|~4g-dV<28*7-r(QEV*lV3Uiq0DZiZd zj1M2cyqpmH`Wt8pi#7}6*UY1zwB%%Gl(Z>d2gsIu|7NWU-yQfqv3lDKeSDf+#Lbv8 zDBRpeK34$LV3WC~YZmL{P8ZZZW?ZW0bSv+jeGQRbviu1`bPQ|6ewdNM?|59h5AFak zDMZ;3T8sTz`Fq)RS%bB?ALhQ<6;HKVOGhd{9@|8-wX`wT@Bhz4rceFNdWTz{88v8TG3p4WL@4lY!5GW_|$@69qMcH1>@Nt3(v%iHPF2-+HM>5W48nbwBg zsBfzk9of%YW-G?{c)iBG`mx7KyeJNGXb7Jooj`tstB z5%5SKCgja)wt>JL;O~Q;;7h7mkV&0j7<(1XaoUcDBawpRoeUy7_}!daI8%$dm}w1K zW;N6Jp2B=xk_O#x>xLoa$Ptu3I(akR@cma_?%G#ad`R;&m-j`}uWf+yB<@RW#fea& z8hrA5(lqQ-Af%HLpnJCS$bvF%zn-5&$r&`0;~aT;LF7>#@f<(C8%LibvD(_rCcy#Y z_&$Bc`q&oKl4^}@LLDDENmP){*5?b} z?fcd~>^h!pTlji!^vhNRmM?ey>CDW8&V=C**D;XGj@pis{59}n|2&0T>G_RO0lcPC zL-pmt*}&uE{USDDtpav-@9+Gu0QC>@n`_7`;m*mu$YV1*@v=OT4=oVtC;5Wf1;F(9 zCfI}_&PH8ewI%8|zAuX%>7QCzVHVmO(sWuHXlmPH;ddljU#rpsuV5UeA2sp9o^t|! z;4zkt-nBW!FzZ@uI0Lpfe}2!~RLmf1^ly}Ox`>r#JipJeFdzY?3LDtZVO~!XYmY+b z%akP~q!I>D*ImNpW;_F4{e4&bjeFqniCK2)qb`Mjm4)g#%5OhIX6ti(N-((>WD^+r zE>Etx3-cch@!Un%L@Jz{Fw*TxbpFK5n$DUf`4&b%Qk-&a85PoYaw>=kqhpbqy==Q! zGIHnF-*|XwKX6isT#ep;SE77N`kZm%AEsMHdirV_8+B1yohVX>J^P-Fq`(AD_?Q1=q=PvBv@}#=MO^Zl3KyE^F5<-}>tcv@HyRs`zfQs+ckLu|0SmUqE1$)1)?U zacR_{d$h;U_*Yc9JLyjKK*hYz;7ePM0>WV%{>LT0;rw&gjWBW{uPtZ{`@ls6PlqIR zO?h!tsz@VoFlI|}!w<3+zqxOhG-V=B)$IC}zDStoWZurYy_pq{XBTn}V)if;qe=#w zdYZ#lix{NJ8>xVAy}0X5$r-Wt{`3KE4i>#MmuU%-ab}J6qxJzl=Vv{P z!ErB|>3-iJN$VE;1KbZ`Zh8v*iP0KC{oH>|>Ot;v`-!lTt)o^T(Iyz$W%+Mhf?BxZhORB$!6w`xQV21l=3Hlu# z_3AuETvOgSTn>)$Qj0|ZlY{roBifEXRWoKhXl~-=_w%I-jqdU|%QT?9pF@gLvtXEG zQcRTk`ZK1o)wHkGqkeiUN_gx@@9LwNNft))ELvzwZ#_yp%Q-ql-}I^#rf;Ez)S(2cPCdDJ8- za#AIJ*BekCyAr9udPBz4c~Sp9jutMYS>gu-oM*|ja)IezWiyj<#oN5DVnjA@pT*R- zKCCE^dUZt2HU*N}{30H3yXwLKHiQespfuuq*G?CHiiD$N-`xXUk&_Paoj%1)>o|_~ z`JL^C#HRheA%Ti4f0Em^Ch_5!$R$>afRun?zfg_oomO@*IDixLqY(}Vu@NMlj>C6? z0#>aG=y1(`XEEketRYU1_O&{Y9HCLA;J+?K5{L}n%V53nZ@Am+Q(jWf!tMsf9Qx4d zV|a&ht2oU_xwfrMcUuUnkKy7wntldn?s#5lzo7O7@S}8o^_+zOSZLqoZ3zA>l5z1TX}?`)Apv4Ya8r zE`Dso&f^_rR&orw9akmj!d0G+JIM#C(|WRLA>UIaw92ii1BJcG;?Kq-=$ zEd5N7l0atO0P-~fxmHFRZ9Z5rMhJ84idZo8TdyQMUCCOVE1Sj=IXa=Tb5m zc|(ALaAY8yDpw-^GHRpCO9~*ZU{9NgK_PNUmNUm<&s5g1)x7-TtSc_3gxeJ)DVw=UaVxY&$x{XMo+5mu6DqCL<7b=e4Y25NonYEmZ@HiBty|(`Le{0D1*i zSni_5>gHIZXKY>|hv(=j)I5KbxVT$ijh3po6adcr{1}e_Ma8xiCxYddsOIHgH4WkS%O8aBq4NeW zvGg9$QYSkm<#E~W6l_>_&8Fe5^Fhsidc7>chg#+-Th~mO84~R>_LUrah)q0d{$Oxc z_0R`9oqIxObYAZEC*vT75cFH0s9*fwigAGL#9pRBBs$EL7K`+5S-}{qD)`lOf|n&l znEtz^kvU(=7h`@^WXgk?i>y;Q)>TAk-BHeLtPv;Mpu%!l8S7v7XAsC6B>e5!JB0Xe zJBQJ#l8eKhAf#lit;9`X)8b{&-)(cvimoS41YJCX?FOdWkg}g1=d8C(N1#Z=Ny`F> zLAwfO;r~0DO3>A(Y$fzkxirm_6Z3bX!MUBE;-VzyBjCopmulMI=Mv@0$iYR(2D)PgaFu{|7$=GWMeDi5o1_XRLX!H3~rl{)Sb@V)Y z?Xdvhz9~wK%ah0p`rfv5p4^)`0uH)i>Tmlg5(pKX-g{Va%?*nlboJv-b~DMm8k#4+ zid8_r>z)HEX)PcEDR~DVet?WL03WzSBZ1Jb0~cS~H8_SZn)W_c!6Y?sa>D-iVVls`hH&pbz!1058odN!Jp?iiM^HA z$6Dey-Ij4$$buJJy_GDX$GP-AqWEpPy)dVd$n)`lvDu;go404a5?L+bVy3~rd!kz- zRRR;6?u>MWQ7aU;8po6MU>Wq;Rtqgy%TcV?cP;}8OunPe1+EZ+CO=0 z0B?+;cC?{Mt3(JRS8Sdbij+h9o;P-xAS_!KPf|*uMGVuK#h~X@g=ZTl+6W-?19quz zM+oi=;RzcklO>s>HiD{^tD9#nwPovQdUL1QH{WHc$*=cF2C>ND0XM|Nl|GJ{5Fi^R zxT&3zhfdxoc6*QGr1RmqXIj-W1R_5U@PSAqbfmhLxUir^61ye72ZdTIV|Z*r8CN} zJiFEeb`DMHC67b;8Y(*{e@I*b7h=SequYytncvnQejp)Qe{Z24r*0{rrH`b%I7}%? z+mM!5WLX&=wr!rP@3?8B^bBpaek&+%$wU{B)pW;piskcfKcc-bT`qW0bv6+0@Xr4c zax&5(mJ74Q&ULCNTa8w(L2L`bDw6dG3}ai;8R`zIwUifFlycM)Wc zCfUR@aD|9RPL#uc4|(E)i$9_P;udb0AW|Q!POPXbTADX3I1r^UE2iuXKB*h@dx$vz z<0Ag`v0g6DZ|E!!B`mZcCKFx*POKG7zH;au4F^t&Jj zHh=F9Ru?sn!?|Gl7u@O9WmAw2gRN1C)Xt z$!LM&XBNW)f+GLt1t?G1PR8o|Xzb;53&(@p4!2tl!k8Tf6=@xt=ZJyjQG=!DS4fzz z^)@|aVPD@47H?I`Q>0TnE!go@FPyN℘857lil3M^ z_HvkpUuX3zYdwmU4lL_*`))gjeTtTMyJtvLN_h*^<(u27fs5lje8?H=AVqQ}*m~Nlugo^=nG_zuxwYAU z%WUU>o}zBQ~%KwUo&@AzHy14yA5^bsbEs%!mV*L3y$i z(VlCL(@J@VHK}d$rzFNd(3~Qm76nK5Bfq4{!Yd=v*0Cm~Og9UN*ccpc*mU<&;4wQ6 z)>t4_E3^O`?0M`3t?1-}hy15sWlpN-(O`FsI)hw_zZC^?rIY9wh_ z5wTw+)vdQQ+ZGc>29rDPpwupW$!vvRYJ&OcR#=4PHH+gy1e{nB53)SX0l_!jkr*5p zeqwIAdMm7q<&*B=y}2IN2}|`e?ar{$CQSRSMY#Fs*k_ymz`S<4XExja1+nc-W7MIS zTuCb7;@QyCf|?h1uka^8z}q+~>OU1?V7aj@D!MCbIDXnCw0cLLk5qwAKkmjqnw-p` zSP-Ww2`+?lfcY@SC*S&O=QOkYurq?Hm(rfPqLc8pqRV9YpFztbUo2ponIfPesLrwo zZwxz)RW6&E>X)l5q=U@dcbg>6#w}mpiUrZ})LeD@+-4x+=d7heFHr#UoxcQzI;`bY zN^1DL*(VdF$T~$5q|@$y&iZe7=y}BwHva?fkM(MC{-GTl>)x$46jxbIMk_=$aE&0` z&ebb*?PEs-P-lv(^@`+;-JeK$P$A8DSJE067T}i%5qbV}juAt0GC)Sy#P4Iq8utnK zBl7ul{=SwEdwXJ8(P;Kd&4Yh-Q9}yg{dz4RtZYf(EVZqF`R{>LC^u%4@zQ%2Z&2B? z@Fd8%AN>-7i>*CjQi)l#l#B5vGThBkm|};@iQpTqhv2E*#V{)CxFxXq`guiZT5~Y2_s<===IBTClx?x(Tyv*~9Veg` z!A7bdJjhxc1h5}B(1C@^Q=2pSpmQJh{vn9wNnz!y?85R`H@hlP*Rz)a<>k3kSl*Mc0qiQXqEQ_R&GPmpZAf26RO*c!b@@!C-s#6OGSRmxCVTgvx z&X2M^(}Rm;(Q|*isSgJtS_;>8dd33o`Rvp}4AwGrz~2}$%wnMC!JQ*n8lPAuT!0hlz(m_0YrF^;*B!~giB z)(7~!cM=q%EU#+5ADobE@Ew{$+O?-$^9g(ZCFF8LjNd(hwL6aA5OQ6dJlkx$oTk3l=0Wle7W=*N z+dW4aqs!mK+x-_aexLi}-8FVbD}pI^Q&W7O8;~7lTP1hFkkOk4-1577hsFEkN8UG$ zs?|!))6PkG2ROj@zc=M*?B8|iaP9iN{GVQAciV%08Lp0}wXY&Jl0l^}X33tGHrV02 zC^JO=a04Xga8;GkH9Yb%t2$)fjnnhz&~u)8YTo)JpHBflJjDSa#c)0}fmP%WTQ2y? z;4G{o>v6IDc-(O|Nb;Hb6M()z*PAk!d-^lRMj{^@IT>tK)k3cvGZ97}dnsc@Hc~N~ zJX8GDmFZ?NY-5$3*tc9E37@13j4=>PO#7fDRXc6ZdRcbi7+SO7@w>SwLL!)0-_gEj_D&P8Te_Pwq3^lV>lPxOEX z*FIzFjP!3|Nbw#}K4 ztD~YOwlX6RB4jkJ>YLdQ)~$lHkKQ~p$5ip(Xfi3`-W@inj@KhK#7HfBQJuI(m~pg& zOFJY~JfJeY#6Fo}V@P9tyX1vhIfc33HuiIdWGpsJ|C%?3_cjFec&O|_(Uy&8G%oOX zW42;n@v$!;B46Kz0CCtYAo)7BkDEn2t2A;ZP23T}JYc?4?a;f7{iLZN;BN%n*5S@Z z3KDWBhtPTuflJ*~kzAs5@^I{h8V9+#iwyJD9d<*)Xixs>p`fqOk*#e@tMpQ+be$+f z#$sK@;Hx+tHgDVw1;U5m^K?aXIRCgSV>GWzEVlQNw?^1$4oP)NW-LG{Ur; zdtE~u1_wh#0mToiqyBv{Ao;vG93&v9jAig4II+p^)qj|c^`EsJl4rVfpu$Omx&3e5 zo@z5r9RawFAE#pB83iqZ0`C{#%?2gNtosDw8Jpiw!I9aLKbC}Qy+g*M%Dcd`?Ztnbme;VprH4*H_Yu`3ZgriO2w2BOneuP(x1P?D4|jCeCxwB z4X$Txv}uVTzyO<4=&HCgkSD&)U)laF<&qkU=+^SBi6GwnB^sR2&Si zR(Lf1@R!l)kYtaaNA*R^65Ulwn|LC$mCX$osYeQR@Kv_YtVO>S?1{!b<7ssEl{%_= z3lUGW5df`YN9<<~x;7IIdDwCuSyRqT(AoDzF<0g!5%jJwgJ)+!`kgv$bDLbb{`kmP z1y`SZyaBQqt;XzTYfC!NIm{OixfSXch*}w%H$DsnlZS~1j21qqVkagb@%SB#o*ExV zQ{_wW7Gz7L$P+k2wg*X)J~4^*jaoqo6*yU9J%EHG%=8DRwPl>a3Og> zz2xFa#Q5^LD#7y57@i{!(ydm`OaU5+j{)9jQbf_@w+K|j(9kz22gI{6KvEkKr*D$+ z0UKa%7~1drA5xD@k5{mww6yhx>!$sq@r`1(s`o$V86lP%5qp4!g=}<43asTggo}b4+Wo|K-6B;3NS;P(EE>enB4-Vg)!% zl#MV^82ugCqE06TLqcDmtBErn6sNoL5T`-K)oSfS#ao-Xd_;zY`BlH}RsQr!U_q#s zB{WEZc7|x0CB}4)XMfRnH!X{0DmA9-)mPWKs-B#UuUu!4AH>@fF}R0zXzDM$NUpd0 zhl1?zZ+@l%jX=OG(~*TO2+tIPE`{7!j06M5+?)4ti$nA8u&K4i_59~$gPqh~^u5ua zv;_FN2!$Xkv1%I%i|O!JYjU?zY{2>CH!(0C1yq}4?FvuIEoPF7oGUS(?x!o8+^hYD z%s;4#MHUR-W3#J+w=cS^leCLLmF0Qu|Xmk zqa?Qrd36F{IHgVK6SZ=@r^G>mhB$R*xB>Msmt*K^awP3Tc#a3q0h?KRe2d+jJ@&^$ z3!Bf#JX7CLZum(&XA%UW>yVJ1)io%7o-=*0cM#Q($u=6v{ zE|Q=(j$xVx+C1Py+{!O^XKGUbZ9vXLYZlFDh6T7TS3eVmj!V{{4rHs4u-+A~Yabb; zwtOm(uet3Ik@Eg-cym?Nhlj8#>U&b6WoBR$t0Uv2CfBpbLfxQhRpA^|6<5(Tso5 zI_d6(GC2F30#Wp+1}gvqfW9r<1t-3k>rpq988o(x@`U_!>eS#LG=Yq)2}kY-zwP5$ zdZU>|7~|!)AEEzD#AH)Msz%>R7SpiK%2(NC_EgRX#M-(v>Tr1ea)}L}uv{<^*FMZv zXxl0P{TfQn&6)8OaQoTOd=X(j>q+f(^bn*Y5+B)2_haZ|^sEV$zrG3N*MntpDdh-t zz-c>7RX7vAVy{?3XHkciCa8aa{fj3rd~H1#Jm`M;tAnfyg%?hBZq zme$$t)TPI?PMkQMGg75P`O((eQ%+_bt*`}v0UaYNe{TltdUkCQm;-@LXoZcU(=i{@m*uYRHhdm_v z^)`H_KOX_LmZRz7x2@y(vKR=MoSclDwq@f+-s@vTTdJnwo;s^+#_7a2%&;%^9x*Rg z6eVopUuF1xe4}n;{D>K=a`JO@?6Wvj(tN=fp^I+M%r^=H{bOPJ?07$Q7YM7bGWE#U zA0$3PMRFl?nX|%#k7f)^u`5Y{F9PlBz6UTw2ibe^Qb1>OcE28v0q=EnObDUx4tsTs zIb>$#oy2a!1Cxbl=E{w}i2ds3iq-jKLZK%KG{Cjsx4oXi5=}Q+As3S@GLtJ2g>rb;nWX`2QZ{}rXW%E;STyj*=53()-4m;p zU zLa`vq4LH}Md<+_Tx;~sa`4~V&-@PTSv4}m7oO8qI%&-#A!SDO@g$^uq0Ze_=_QOMx z5L>1xeQOiSkTRh=Q>hmIjcjv^@kHwA(E3L4WGKqc&akSsZ=C?KNnm=P1?TAR7tBiX zka#qa3Lhmun9#WumY0xk8`|vu@r$BrVoze6;j0>e#5j(QWzJVL)n=+%iknkc3VHj* zJF`3-wq|XorjhH}zU=QBIcW3^E}rmuXtM#a%ycTE*&g&CnQ?^JPm3QpTW?ED{&|(W zRd6K}$1Y7D(_TN}UHWD*6yB3}Ixu!`2abH{$j*RGH&kNjdde!kE8K zNn7&3KVCt(62s=ZCsut?78TwfH97j#kS49L-nEu5(N?>hvUl}u$r@0?#g>HS|7}z` zWXRJ|&nPSmg&RtbOGp+XU3SJcqE#UNccX48ZMap4qO-93@X$MvPm6xrxy3}cIrbkg zY+YDhQ3LMxQp60e-E1Sh|FJ4Mlo;T*n?2nO5zue6U+DDjd?6jGp;7l8QU2Oa{=(tm z0fM?e(0}EI-Ni$xc59IKDRAXVuAbh8Cl`v##CMR36%y$?qm3{9!$KT5!%T)XDq`L6 zcxELVtex=CPG9!JIS0`MfSvkM+osF3Gxdi~sGO02VA#R8UiW(n!i8VoYMpCaCBs)j z&;q}&(P9)!>w66(8o+i)*Ti&{_zR43Eyl;zg|Vp2=c`cG-$%Z?z0o4%dC_ zW2!6U^%$nO_~aDr@I~C2$P8l%bFvFBIpVEap+^Pa1o@=1w|#u^w=)F8uGTD93*H*V zX=h?J@`2+k*?`kA$6_HuG`$sMh)QA1OxuAjsxz?ZDzt>e8V)S~tZHt@n)DplG_z*YD>2dICF~;B?jKME95*17M zx4S`&-5_J8MN-Q2(NO8K-|<7plVT7X#w&f?y6DMn zr>pni^Rv3K(XtC|f|_@6&CMVQj*+PsN5JVah6*}~=+w*9U--O_$fUiJF60RUbSA%J zUH)hVPl7HYQ1sFg2SHhV-vk%f+<(8{K0yBIH-1eK&0`?yMsENj95cFurxkcb3xopi)cTs7$lU*;ss!@ z{;`AzKmZz*;0%LmLe!S*w1hknTGYr*VEY^b-k1u}I&m zAu5WyaZN@AZ^v9&ycIDicIRV_L8!g)43>V`aJ(%=)8HAp;d-TN`xn!UBHl<{`71S0 z=1(+Z^NWFo5uMa*y!2-8(N!-}uw_e!!B4b%P+OA6^o%Dpq=RBT)L_v!GR%;GN0$`f z_gHpVXyjMUzxClI-cQ~2si=jfHwOLwi5$h~mNs3#o;3uaL<-*>)sO6j1DOiJH>0}2 z;(Gf393K9D@S@}86x%nx!xRm?v4EDS9EDy&qwI#oSX?eSi^gPwWOjbSsWjieG4N_t z;ji%AA)3h>F>418YF_7(leUrVSvz?35jB14?w24-4t0B?+v0);hdx1!8Elv22w+b+ z_`Fap=&$}&N07T|W{mTerOaQK_r3$P2H20%gt+DXDT|F;qr4|1{Ythg9{|TNoPd20 zkR}>z9^&C*nl8F~6v;Su@S@jB`_2weEtVw8elF(uqHnK&v410GdQH!rTKM>IT*SLPu%-U0 zzRx(j#@vu&fUT8e=5~3!Rja;Q@oy;oz0lFW*n1)OUfgeOHHiX_jf{_J7YiT!t#iH# zbLilLa4ZGzFEmg&b#=F%L$yPrBNta<tFg_87kf z3I%cRD+I|_+3cgby}ts_UHdzvMYMUhtp}BTcf`Z?z;(5>^GbuAS*O!@#>0AA(GhO# zZd9sx7FvGZB_HN|Nlyp;$<1psJzDJ@Oy%OL zWc6R^-I{AWsB)SN#WdV}(CL)aWNcSHKE6UF{QGDVyP?rIc&ZW@I@3CK8)u-<1)m=`vFi7s=nDK_T!y!miQCv1>8 zSG~xGLn^M5Qv*FwFB@7n2iqAI>awfrtjtudA7QRYw9DpwUlGPVB?}oLyuAYgQVSnA z3KH{BE<06JNWjEG;N(0{;36yfQWb=^kxjUVsbdm6^05(rXfrr6%2`F4hCf%PnaBp=X2od&Ej*KNgqyHmDm6n&JkQF1Ggujw&@PKt&cse zEq%XBgQ%meq6JrCB?ke|fjSps;*{MNAcJhP6|lp`V8H`NTH=aCn-~VzL(HNQoa^7N z0n1c7K&sBtd+?lc!KM~6VY$QK@0Xm!lBocRSBv5X*d7w6B zHtA-D^0d#YEwDCtv;A__crwN)B;82~mUX^e9UZx$C-wz869~GBc|G_~SKhtZJd)bZ z(HZi79A}foFzUcv{`Nnlttf`(3C^oaf$KK&k1C4-8(recj>IO?nL$*%e6Q@J{rQ0| zn>c*1IM^;=CwiKR?T%vA%w}8LX`$tH@;(iQccm(nXks&W>Y0_RU!1BZM}pJ1dAH*{ zOqAq!mRvoro$cW21NB6=%s37oD+r@d4MN6AOL7>`H{Xz)6c0EqIjGEb;F4)AHfGaH z0s#Ta1F4&`v2+qnJu2u)ZkvN#%pmwPN4tC8(mg=Xwo?g2V1~4OHaXq8h~G zQL@taJcv#Fgv*k9-IB{7(IbUMfq+G)*&%I6i{M_&K(BG@ww0R9tuN0pR?9qi&j|g8i9K1iE)}WkCykI z6}Q8y>-A6KM63_px8k!9<>%oOiA^JEN2QsO{RUEFM3z}c3;x8nt%U<;OGHknpy`>* zBN;*pB&@w1Y%iRN3l045qwHp~$pC7@I3x3|99=RWTfDk{?OFec9*^fFd!!$A($pb# zI*QT4?JBVH^H1Xh#TK&K9Fq2_izz1=HoZ)$cO~#|C!6Rf3RA}bd(=m=D~zPe!B9-i*YPEZ*hjxEgYvD~ctldh~UibU2y`K19Pb}Mqbct-&V#Dte^vqJU z$qq0+%Zk^!Cck#}S@`lXISwkpRbmaB|K|m;RrPGsVAbkYILCA|m{)K#lSbTO&aMZ( z+3Hxa;4Fm=#J*ab>UDOw6QI2tZ_KRkb%gA%U7e1ll2Zh%t8%qjE4Y$$%IVMPl(A#B z9sANjY~RoG&3DpUHC+{!F^TlneKnR z(#$uVQAKH}nwrOU`jtEsQyCo&y5mm0Dy4Jv`+r(+Y&c+sts6t=Pz%@=m%}}3iDnuT z%3HY9Ch~bALuO_=*@V*&3UjH5~@(bWL6hMl_4 zimWJlk`mSiTni2kePd_aeW}wfjoXBddQ)4`!k>#{ z{#M!U-)xx2GLrmL*RA!slUTgH_+mNhDq(kCLE#FyVkeQfx10NSE^gXMXUAV=G*@t<9hBF|@*> zm#69*8x{(woUf&4xLN3G%}D=XS-5^LM_g{y$p1Cv{rE@E(o&e4R6;oW`~gmYk-ES0 z@u$g`lejj}7S?5HzGr+2cqjY9V0;HRNE~Uvye!tY17u^I-(SVpP%B{N z)HoY-MAs6iA~(T7j{`UEP|Ij}JdgWl$LfbwLA||g}K~0Hby=JTt22uD(BNHr8c;(&g{qo4o za#IQMIIsIJE6$-QhSC_egZ~~K0@G}%{Zg>dtk$Mfq2yv8nP7-oR}>&|z|xtWoy9Te zLQew$t%Y7aIL*RL@_3jDfQ+cSA}I=_icm@Kv@0#L2LMtYv<9K%m%GO#l2La z%UJGKwYC|I(3q7L49n%`p31twr+iQ(MGv_G8sEY`mc2n!ebgjA#XF0cP<66_j(Usp z{wfO!Gx#Z|plnA7JZG9pE_IwY3bc|1n>_&VWUZOO2b7{v@0uJ9_J>b$ zJ2jIy725LQLV6{o8K3nK8i2Ul(k2cvEAn41$59I*5|l=Ib!O9XRQu3=Q?kY`$uGl0 zi6_b~kh~yW@6at`63?niIWFqcwnO_kVRk(+<~$ogZN>(2MLZ20Gu&F(%?<15Zi934 zO({_SSh45bySS)^yBheJe!AKO&=sgg%Q_XZ>D>~kVZ7c^A3UvD5*=jjBuKfLZitcp zzwlc9M*kYat8&eJ(BF?rY`#mP0+w`*F&4=>c8@IB>7=RUvm@*7Yu=+hSDI}i=2`B^ zRFr4#QaF`@(H8am7r35Du!zCS{;=E}%TX-ePx?8dXuKez*vV^aM=^{8^28$sxflV* zj2Epn?+*@Dt6t$jFnAZ+uT_~2{U)4+OPe)VM{W!YSkI96QQB;Ix1X}B_@Ai;OGpeu zaM}!5{ybt5YVBwN{;YaZhZZ;JToR=~QxOA-E@6~%d?_e*!o_SS0v7WQ$r9Zlpz7Jg z^o3QTH<=h@&+xNCe^eA`d%JJ_&Gj{pFFCPaPd!$dek3ukdyK~PRlWe2N?Hsv?U2`f z(BvnKj2tC*c%L~7+rv#2i72IhQV7JjWxV4r?%NTS8VE=<911`g{QB?E*w3G}i>JO3 zo%Mo=xB^YAk60#`9n@%P3LTi}4F0?aV&yQd@Qio&YUgI3C%G`%p}$j@?06Th#!dU6 z2QISqp(o!_&0)B1rY5lEWM{kO?L4R8 zFHNKmyX-5@Fllaf4%+1f52`Hlk?Hl6qZ6sxrmj$+DFZbmXHI#}vEU6m+y0ZJN`7~A z&rU0980Ua9!)V{6zs*8DqEXV^%wNn4n557CJH>=vl|8;KFDQwca1BQa$=jLyLWd)N z{cCvrzmD}BS@I!QDoHl|+e5QPcNUd{38&!fr7v}Mn)>?ZJ@XE29n#Ro%;p9Pmp!nf zWT)0PlH6+m%zlm29ml!xeB18IZCAmoJ3U@ZI7QQiMzD+#6Y#0c?LM%yHEL|AKUKIH z_M3j>^-1j2t(5d!G8W&zXBr)ikAPh*rEAG@YDaTH8=Y33ZzZUr8TSq*%gPyUt0m|? zm~*C63Y-7`@pRTzu-?nD=N2+* zf0`eYmKPn6X}~o`v=!_c8)wDoqyew+AXVW1`6$2XOfeTA+h#b~=;u}qPOTZ!zTyy7U@BiVm!_pqW^XkOfoYvu*Q z%*qCcN$AdjE9tHdFf(NX?VL$-qDhY9Vgx=lti7Q=GP@BJ;?GX)ot;&gw#^90zU@KRb zSaG~^SxbJT`EkMPV^QV@FQ++BHPPCGOxY*%?1iiJ^`X!ySw-6Kn|*Hf;Tv}uwGTGm z<8fX(Q*FOi`;q+NJ!hA{_xU`>h#c4^ehUgQJb&ie55j`b}AwTfsNON#6B=BAw7AiO$e10`v0T0vwbcQg3 zXe{M{(;BTyA^4}OgAkp)dm%m&ZN^9m{~7%gA2%Xe*?Z-8_I8bpW9(h7Ov=kUt}|3k z;$JqoQpkkje~efV5yka}x4NkvyGKy*F3C156evpp7EaU)JA+LfUu&57ZuyUki=MEx zy_Sw(08D@e#GKQSdY0x(aZ&2{4otR zh4(Y0g+^ZAz!?ENJZF;O6-mnWO~$Fd=IilDaXV!Q$<()4@cK#vhmuSzpdvU+4K zBzE*#FW8v7MQ%7U)<3-8RhCmDM&BSBKEXAP{T}p0{ldeDHqlkg?JRaQi$MoN5tixKe8j<0<^PBHw@ z-6Ko`*vV*~Qd5R_B(J_L!b5f1ZM{Q!vY_)O$MOo-AcM8VW*L@q6MT=sBbDDoGtP7I zc<(05bZ&y@c|p`}A;bAkd$Qdv%p=%iBKvJC2C6PJ{B3&zeqMRhb3|;X9=9Z+7On!S zYFFY=yNfpjSP=Bg>3Zw#-}nH^Bw#C!$sPi2C>VetHg{_afo?UE0^EqU#Ymvw<9jZdo(6F zS4wRbprBWD7#lT~SAk45^GUIscnT6{@Z0(ayW5B6?p|Io_{aRR5kUKJ|96H&04Z?& z?EBTn&w@zKBBsC(t!`+0w|iOSH_JCvvXL990q#x-k2+FkWEych8$q!1iT?I;3yLj# zAR;Hc_Hb-*_Gy7qJ%Jj5_TL|g>Q0pZ<06cD2Jbn;!f3X2((`Tmrrm7DM=Pv9$85j< z`0=zKH^DVij%MWFYSN}#pQT?%yH>mqAB-%w|H=k+<$YgizJqg@2`?Lowz1KzY$tV@ z)m9Ih7QyoIua&^CZq&-cqJ^j?Dv>e1dB>}ecsj`f?T;ZR%3p%>U}eu?L4|?!?K591{8dp=)Np-H z#^zmYz8zN?z1`itH-b)1LR{Az{3wOFPgNA=*ZdS((LVEYfV;DIupzY;?xw!f9|Pv9YEv zKan8(@|LifE4BY_N^4O_-Q{wVC|`HJj;UYtowcLpbK1XsGC=RkgPO8?lllZH>V$d! z6#;;fFzrY2{Vo+k#RWhAp?#%(g{pB!^n=HyV)lXqfNGwj0*f_3%(=2`3a<@x_ML7u zu4CV<4>?+&^4a(Fk_$g)`$zLUcc|RKHa&_1PyGqMEW|eiwxS3O@oqs>Z|1n|5NGr1 zhNAGVTR!(o!H?lh3df{-q}2Jjod%h4&%Q5@3@k8W8d7ED!ee^tsdxtNU-0j-P@hCt ze`U82ICN^RE2ti}{l4}0G~jV6UW+;n8&M#!=QIbuu~ITu`LC+ahUq2OYvSoF)q6<$ z?V3T2h5V8@pT`4l-<#D6h~5ebeUD`b2n`!?#ACr3ee}c_YPE)sdo;bHa7)70*c$zC zypii*<~<1O5ey{NK-<<$G^!C;^6yr??c&JL(cYu~5BUsIB9YIg2}jfI-KWk!IF)A{ zb)+^V64H+{*E_?vPSHP3=b??Tj%81-d0DJ69ihg1ALrw~`$>GSCzaL^Z!WAe;%#`} zAbpn0Roeq_a;b9qTvS+%_*3nkYa`J?+d+#nSzIxPN_z z8^G6<4F&iW(f0$q@1HBd+ADjHOtQF(-=eKwmhy)-Eqax(C;xf&%;WLCpk$a^%|;A` zU|cNd?r!PgL_k|u31RrH;iOpI>dFu@5e$`Kjz&KH5Zmy-P7QD6mJn|*Pdh7k+7A_I z-Imc-UhDjcXeF!v%ie@mS6z(73RR&GUfMSWg#5BTX9^b3Kjx@N&T1y_dslWi85jHa zgLNyDZ=6RAO{Ia4j#THW!ttl(3!eRUCuy0Zyo8q>&TYFvQgHaEty&&)f18=Zac@%X zhqn?;j^)()K)76dE~FV{XKJpv7PvXo3q0s?wKwm__jqj!Pl~9(iRf<~*skp|XBvR# zpHE=(6+U%S*GP`nMs4wo87`1B>Zt@$W|W>gGTDyD*q$1gk57s%D^_zK71*7h49X7k z3LYD_GX`KEjU`*Y54ZltUKMoR?C9l?kfcC#!HpCcI+2)XI$y1cj-9!HLWky(mC{Tn7YtEQS~Mp8C8)t6MrauNkcAj4in1-Y_OCHA)~i z@gU-L#WVYR8xsZtwnr*uO=j+OKi^M1C+eh{;w|w_=e`+$NH3))KlM-rv-HNOW*+q+ILxny>(_?0&AuOgq=^Ujj|-p6nky%U?#!J`N=mhR zZbpB?1SXX2n6 zc4(aYYd`{6-0y+SQ)${FP?7Tq6f2GxkUH!=d~5Ydm)J>(QX*7p;}3ZQcO|{P`V1)? zZg%#$J$jT%d@aGi)4=!OFWIha*Zj@}Qb=V!PyQwPTicB{Zt7QF2aE7}abt$*w#9(d ziBWuJbWC(wW~Q821>9xI?7(rUva%*4!G&vhT<&uBm9sjX&fx6q77c@-&-qd5a4DUt z6aglXR;JqXaHa1!9)Bq*>He^Lcw_ZP^3LVI!>FlTm7~sa5+e`2yV57E!|_s8;ocp; z7^8ptAO9|YyS^9fYy9CMk({1tz%EQidu`RexJ8bkWkqyxw1nmHcFyI1Zdn;?q!t_& zHa*XAZ84LUdNwa>htf{W80#K)-{h7>MYyTkeq``QHSJK;aW<=oA@S%G@*8tTHoHnePoaj zO&%};I5fep6VE5u_`Es%=U8Li()_$&CEt}FlU+dQ>eXj6kZ!H-}a z)KLDESWUsk9~^NC)nt?cqyMh!+AEtYS?p=Mvw)OzI8DkMC6}_ZyY|3rb%yFafXTr@6%OkZ9s3F5`53&h?-Mp%`u`s{ixw2zK2g+dRQ z41IO$b)^S?p;e5WAn#v|rJ(8=#l=j&6rL&pn1@>ab(%)TmNp|(^BM)DT)Bkr;}y7a zhpTKg7a*iw0#h%dw?7neP|p(|kfZ|nJokO&YIN1)YG1i?n&b(Ltx2v$NU4f3hO zh0|xKAQ%kLWNjEiJfPla^Y%aK8=Q?6_4iJU4~8*5B2QGs{+OyPBz59IrxLO0k%IAC zCU;-(ygLdH4ASYFwWpmmseV9vM2q|y;as@u`ZrAg%tZLnUPhTng#f5ea@G29EL8Rc zgG(knr2>-?5VhiFPMSnMVI>o~eiaa_mdg_T2H1!YUxMisZ5YpALCPz>8)fF@2*wwN z7#|qnyitt}Ng;XOyHsHJl#Qy!Y*@A*BUrZY@i+4^s^fx2F?NolbXN;7ffQpkLO@*R zH?ge1)!W^7W4$?JNK+nUD;@&l=k=?)z{0(8l149yTpp_ja-gtA!m1 zm|4M<{)|>zi-E1g80i`qLewc#F8b`S$^cbQFU|n|ncT&XhL|4Yp{OzyZ(a&NsUN-0 z7%M-X(*vFloHmAaO>7tUHdX3~{0tEnV6d#bE7ZjS*GzR!DSG;kK7YVRHwj&)N`XWQ z74#lIK&y}=gJ!tK*_vRIryyd8KY63O2$G{|{$T6%(=@NXBv^4e^aAAW(!k46(wQ&&Wv_u5)144{f>#e%*Cp_>_5x(!XORJ z7?YlM-f!M^Q%6^6u4|Hx$tAC?{pm}$$bRN>*PZVEI9>J4cH6ETr(kdH+%OpmPwa$0yiiW49?AJYL`FmGFig%VDk`#5xmn2D*T>7tE7y1Ick9xK z03+MhlMo4fzdmWLFQbmHBn=mbq^4^)99RC!Emku2&}A_m0_S@A-I+joIB%-)<|_+U z1j}Mgu4bMKqw#U^KKSkg-L^nW+++BM4^}piSDQ zZN1tfdQ<;{xP%hpx7xw`IUv(+QlzVHSZ6C-Yq;b6;iWA>`T3`R6FT?d0esSy$Z#jq zTFzhE+K?wyjcr#lpwjRjX@PJ!8O z5;Ze6f7KlH0DPcAPj4F`yK1Ze^}sP>NFJ@aKq~P=R(@B!6LlcCEHk`+^(? zmY{RFZ7bNF9R%o~G{F3WoXKWo-WKyXBp&4%Nxl(l!?~d8Gq$q9{W}K@Gu01R=%mRf z+TP^JV@cw2UyX8^jD`_lwMFzFRI67{28Rrc#2lqq^MOwX;FF-Z1VzczEGaPNNwag{oIAMe$~>aP3^vwY>!)X!V)<|?6N!n z11s5WzEODvAJoPO~SEqcLOof7{$lFTeJglFox|0+lJJ>47V!1pc%s0y{7 z@_O9QF64;gxZgh)s$MceF;gdg%_6z}+vwi$q7QU7N$0}gqRL0NEfI9Q_r$;xDgrTiNjMNtnLAlPWDXlrp>Am#bXcZNQ+f1? zw&!oWr5^C6C1I-lzjjydUJ1Nh`6}k4Rz-PAZf0y|z%hbRRqE zUkdT5``vqfITuUh&N5k(<~UWWk)}T8=ROVZ56w>A@xuIjX{vN^_S?pv08p$8O(;H; z{M9JAy&vP#PP3&mgdd(U9mdg4y{<7`{7>`bHs?jM&oE>zG_EFXfE7V|xwV{~-B|24 z5TQanTD3XCmPlXuIKfYK!z;3sm%9m8!Z4PB&Zu{8(!Vd%=yBNa5J8hOSzVcNv-VOt zF$^WLl=z9|?eWI@S|d5>Vz|vlDeDrrS|}OexKYM*I-gs}AzCmuYl6#RH92KH7&;tb z^UU%sO1yC6nyWW&`<7(Vev$|IQ5f>i;A>3Giq=7G=5qLJnzxiXI&lP{ESu>W#~Lry z)zzJyBWkV(T4ebxehLJJNc&#CYLjih`^JECk>s%lyWiaX0@t*P0-J~NmF5kmda9*1 ziI#I(J7Aq{Q)@b)`IS<@oYJuMvfrvz)0Slc9gpj$#0=Pzg7=QEE}ecwcc)B|+;(x9 zBJD!Y+*+NS{?_+cXZOvfv&U=EH)?5@_^g3E@&C^Ss7trn^rIe%b2}xv^b`+d9(dH; zE6O!o?rIZv{Ko-{cM?2q1Ye}-raufReudp}=kP1yq!a3@5m-0o)f0O!lHAoigNysA z59JpANGL{T=MMfzx-+CFO#i(M*lNM`1_<_*tesL6TB2Il>&zm3HIB<%!hrUmU{TjA z5)iPn-_WJ!o#bjRPvc+8|7_r~G70YB35k$fnCl#~XmYIUVyC#2Py8QKFI^M0cl!23 zaaGeyC#+DtRBz}aI5_rJ!Rkd-#m#9eArCt}d@_N}`%xx=`vZzzop)33{) ziP#UMfh$ygsx>daBv>+o&F4-v2g+7Ob*MlIA#m@zN$ImpIYwhbL-mE0>GlWRZQc20 zgin<>1>fkeZWmVqgTa(6^2;wb)0A~*h?QADUe-Qw`lCU27xNFzaDWE~bp9!-{m|Ih zd09u=3!xJreZNe=v%~Ac1KOQ~rb6;Y5G}->+`Py?l?E=dc((a`?D;`WtH!K@Bx@A) zlz<1f1Ho2OSZG#(azeXM>}bO7C2E$bx@qy1EFDB~(+BfF{Yx-mV@TH%J)Y36^qWXo zf9od6Xr)X-l@6t7VpA4ehrZCPg z5qWauu|W7>pbalOV7p>S!Ez5H4!63l$9KYK`9H{URqYC5FUD6LFQ_Ds1j| zm_osxB2I-1g!m~8EQGJMZREUn3=Q=!MCF^7j9)_O+uxLJuL_Va>|h$6IPg_GpQ3Z> zsZT8^!Z@G}OWJjgFHMOv5UrxD%JM6|5J2j;YgqT=?6ahO3O*h`Cls{*G1B*Px4r5S z*&Q0L6qLL9fsoIeP=(m>=duoDt68%sNv}gECVnvozjnES?F)p)oBxS(;X)I#Q$9zL zre-@8sVifVsNYbQvOpF44kZa+@81F zczBfG2XMXn^|G~A6PIB%UvB(2e?kV~s!sWSJa-_6=+}JNM{&h(%pU)$ISqVw*R6Kb z0?T@aIKI&&cx?H`8^rA|atOr}L}|M3ELEC(Pjo9fTvM=!s^9OH+?75&Gfyd<=?oG?ACB98k_$d;WMVq|}d0;yor+QnPR+x~B6JlH+`@rP3 zPNrqWD+b#YM&Mk>sR&Q_zCkWbheynvC%79T%y;>Hei33a6!lv+%gI+L6!54cl!iHhnT+;BmV;6XzW&7Xk35 zGmI<#d3ij=^%~*iXEZ7LDTrn-V3+z9GSNhhWYj4&G2(R9*cG~nNyN0xj5o~0hg1l7 zN;~uk>c>CF!ZSU^V8k@!bldnO966WkWhALpP^sfd3%(oATvYoEwLl#GUBK0KuLY;U|o`y$YQQ9G@HTgz&0tm%yRspYBenw_{|gK_(Qm&h@S!CLeR68Wl1;ki@8}&1uLoHC z5z?F1HaNJ1uB%Musg$UZ8_RsxmF3HYaenbn)9cF!U}u>9}DX(->>Y8!oTQ)3?jbqVABs}sf4E*ltSmM|8>23ALEuMDS^wrCMuZDa*o*rhkP|+R zEynN>DVL5H5stiU)=m#hN-o^-DIkfA0`L|1Q>{E~OoAOfxzf$rdJ$ zURv92#_G*tuV;l`x+GJ~DnJRVGYkIsQOt52HNtQx1HNp2@o+Add!r8few}@V$8$*3 z=ro#ay6O0<$5V$0i8FRhT^sMabO7h(UgzgLk}a=yhkCp4o(SFP+$%67bhC$7uQw!k zKD?ju-kFM|%h_Ke!BDi+%#Ot)`Ho%`9dc^h)LYnzb#7;Sex_!SbnUG&mT!AHLT?RL z0@1KKhMZS;yno}d+y}?S zRuB9;k=^1yDCd^1Y}~0ttaQ&QD>rZ^`7QrBg0=Z4!<@`EH>V@W5~L3NMZ38+1-G(0 zXfK`thCNjSbH{s&kOC=3&k2^(#QLR1&vou|*1ZsHx#oMbq9L**;d4yDrif&sZ>9`g zXrixMzltokEv7SYfZ4OyCl_mn449*!=w5%ubkOi`4)!_@C}7o>VNudnBAylQq=qxn=A-td`HTgL=giXDxA>Z$0U?K=xtqh=pe zxAWsyMgy+{cR5xsZUNq4&-3*dl&$3^(+4`RNUZ7CU0w>kDj)c9rXIUAnc?eQ=QZ&% z0f%H_z=iPK;WNB{o29H@4Z!@=>s9^9X#32?XZ+JkO=->T=wTsf3_em$L~Xqq%NEE@ zLGxe!Xl}<`)g6zsG6&AJWUy&^maltbFO<(Ee)apx!i&X^W#RF^5`8f{vAE{W*iKV> zG?yCudattG+7rr*cI$hbRvwAT#hlU@4o|{YYpQ2w`+0LzMplnuVi&FXLJ;KIosi*Qp&j3S z9U1X!9}XG|x%)0)G9=f7~S^%Sy5n2V@3n*13Q z{6TkwKbWI~UeBPnEi`|Ga4SYZ=G`d(c-u&yQo-lqx!zRs_sKkj&R1r+U@~Yd;wH>r z>w;Rs7pfcu_`uUKK0kJ;)2-z*gOp}up?9UzK;Y7X=j6~0f%Wf zp`Ml1AC|H`2Pl`c4SvWL%z3FS11s|pR~mvhJ&%4&+TnyIo;-Q-QQu=D8kAJKZL6s{ zy1Z7 zM*cw4BqByN$83vY?eE;sUxs$A4wDS@8#yV1J%u-==*5B1gw<5xmr2v-#NccaI}e>m zg;<-LZN1DrL9wk!(^@caX+Po$t02U<->!Vh^kUD7D_Zl+*`M|<{tY#+D&!ln1;n26 zBgm7Nnu-o4o83Q8)Z*&r-(mx6&XNzVNPzen^P~(|^v%ji;djdlL0rX3ZW*^OUO8+| zbDL@H2=QPcZ{)EYHvCNg=lIOz?!Y79+qbSksG!(#6oI!^vG>^QVm8SHR$!bCB27yQKP^XqEVDnbX|U?Le$JRLgYupHQ88U*EbhV%0y zZ39*HqE@a19cY(~pA$ok&=)V>dK&sRC5u!`PcK-A1vD zL^vsYNSzU>gBD#@Y=M_sMQMC*h}}{cQ*WGLyjA`JZSeiP@&u7pAyjd_f{+wE8~f!b zCO8KUZA~5#ebAKdACf8XOtsEI0yIs^6-@3Qh#Gx)?_4djOv>iUYhSHJ$GO?0 z6^HB;kH_EWDd5oe=R`<>MU#)DFd~_4=DM-S4K>ssH9!oZM#2OYn8n*Im@%RGhrT%A zANxe{OwK=5b2Ty*)NL?P?l3D>C!|3YOu#RIwCuP`U;T0#)sxSZVYO-COt3)Pc#43m zbiC;xzSfM}TFyUI#C@?knVGItZU^RWfp#cn1E(LI@8Zi1;*A!M^uug7tqiT3M11yt zAIYUs51B%aR5HR`jW`FxUbnX31R=e&L%$1%vz_)Qwv$T!S0syQ)jQo-p7q{js}!eI>~bx-KK|G8 zGe&%I*R46syJxcZ=q4p_`CP^jz&$r!k_3re9Aox+`zwIS;D6u1U;tB zOdfBeFRO+_a`PpNDz5X+J`(;FEZWxO#(n}ix&LG>!IN~ztjgyKr`UtRgPz?tL1gT8 zlfm?>v>cn_wA?LKXRaI=ZxCQK+?0*Jb&Yq~KIA+C#FIj;NSNQbM3+e&gf( z4=;8QeomI(L4zVhCx`I88vnIHMcXa!4-WhBoo8StuWt$iP~)cue(f33)55er1=a~) zT&Mu9M#G%Q@{SgF!@HPnjC5280n|5KD|OCL*jeIBh_b+^yVd8A(oY{ z$NUS>0&L+bKYjRDJO5NPS_*+I?X>ECObsP;XnnI1QwHRuq5~)a>h1D+lbvG%z5G52 z8xFGEZL4hl^#ld_i}_kqFZt|T&7hjg_H+rj!cuz;!P1hEfIj}LJ0NETwJuZf1QQgq zfr`%NK?1o1Z=H>f=AJ-f-jCUeq&x&82we3n4>H3-TrpB95O5ryh3DVp9k%>QMR!Zo+!Vc}#3aIH*vjKO-a*PgV|qR#UhJf232C-g^Ur*I zjY=R0H9Ht{A<9)}tgF~7n*6JmAKFEQWorH^bLYVKVs8EIm}sZXRkkyFw}GyjqlFj_ zAI81Z#V@5rC{^wD*x6c4dso`hb^{H4@8!o*p^cMT;%|2^)fSQ>oURPc=1n2p{^ltR z9z0bx+i>^w*Sym$PlAKNM?Y_09AgqYGp^qm2$)u770?=$hM_OKci)3I|4W2et>%A~ z^>aozLqPI^R)@QMt0$ee$ETHWxtOtx%J0m|ZohRU9JQmwfY(#Itl&6D)_2h-7k2g@ zKjH4o;?tSkG9f9HQ$kReoUWdl>Y-B=)4MP9^M|T9B)ZN}Y3yR5xa*5#PkvhmV6X3=98Nx4BUJT#Z8t}3W( zOriuNrpLC|dB;^p&8%X%r#)Z!vWR0pxIRF7U3B;B{;!lHOCjES-1#^CEe+c-)>=`f zJF!9avTgomTkF4qrragS5dt!3dy}jLyGMs`Jl0ttM8!2qqq=I@(pc=z_bI;>+eEI% zJvc5WU;>N46P-({GNQQ(v5Yylp8y!KTP}oLe_M&dc^%W#$N-y&dtCZWu6?axk>y2% zw|kwYQ1Guw7U`z^b#OKI+i-(lVzzu&e_#?0&2%}Ri5u~ziP=!MIG{FnW zr%S?w?DKEl2YWmVj*$Q+Sp=&)Ns4t*-nYf$#;w$MDTiW7fvPYn-A3N*&smu zGU9cs*4arRbR|~Kg$DWag;o6O5s|wyD!=SqSBK9oCzQ39WV!+}@X{T^Xq-0pu)bJx zcU<52wXO}3o^x-#B+`Hcq71r(#pY*Niy6v6DPD_es*Ob}wBGsnek{0)9PkGbRfVJN z=rSA0QY=uT??rYEU{ZX)5*TeX4lQlADbyY)I(l%?5*I&n__bh6!Y@0s!}^v%QxgL= zBq+w0mouTF*-tE4w|nx-B%HWfGD5k4c#~2o2eK~;*-*k1J`g~E!RpWHGeAps7n~>< z{3Ag{Pq;$0E#^cF|^(hWzG#xgpY@M@w9w1jx%q?x*D161SLQlBe)cpnR ze#>mVdH#{rw`eO^BTc}BmfWLmvB(`vTP1G|{6R^9uZ^U#4IOH|v8uba+5|;ak>7<_ zrP-Bloani$K0rB3u7}dCPkg+4kbfvQo&FaZmi|LK<{l%Ty*pXc_XJpr=}J>={4GOT zaGm-wADh}x`}p+i*+8Sa00^)MfTo2-R;*AK2R%a8KP z-j>2FQ|$Mcz)D4UQ9e|dAAUv=o!#)fbUon;4Osb)0=K8?wwc42RW`tQj*IZA;7Kf8Xeqeb%Sjb=7H zPo`9^(2H@yjaGs;+B68(`c3a^7SCo*5bwmGq*f95xxxNsjTX*-^1SVR7REoAx!Kfy z>3RrdZNZnGKbII0VwPHzXAE!sVMI$@=M5i>>81F8t{93%_iGT~s~3Ca8-Jm0c6sfY z5zhBO@|mq72_Xbl^vejd7azf^|K_V2tK3mh+E4OBx@uARVaxz^MA^_Oz(cDCP;2ys zko)%u48_e#fC=_GKSVf(UO(NmrJDVO7sMul934?2r(Dy!b9Q=L?QNFmxAs`T*Y-|8 zYbX=}hG$Qo3eReV1B09>QG!{}$ai0fxiAb3wSK*H`!<-yA=@ik{aW z4mCA_j+5=Q&U}1s=5(`-Xt|*r)MqOq+bMmO3kK1}UOsg=URu1D7ib{Y|NB$N8(Z$J z&gPhqTmDr(yT{v`TZijNqpu?P!K-6;px53PZv*jvWYrr6eB6R3D(z6r^?mib7fC<5 z^lvsS*)VMcdU_ZVfAyN@V{wEQz zvl6-c{MmJ1Z;e0n zDmN})p2wk2#m^baNZrK8ZP z8U)qc4w;%0_pl*^r(%s3lSWscMEiU}AP_&fA;0EdTIr8)W)|=-Z6d({G`1Xh<%Si? zXc8y5Em-3R9y(4+G%vTZ`HAou&?b$ocfagNg8fe}ad~rh8P8)r?b0E0D0oAoDa z+*wb~)qUnn$x@VrVEmf#pZjcTo^cjYpWLr|R0pd4QCccEa*986WySoe#SR72nSYKy z8g-{w(ztyPC(<_kI#r3^e!E%t{*?VTWNmzdf#e14$9cF2i@?NjNIlK;+$g+QecBnb z6SCguqq|Mm=MfVfEg~kiskq%-zMDH|o|u)J+f^@GHDeddAfaA52NE*QifP$d+cGmV zGY3aSM^Dj>vF6mb-+o0(%_wZz8IB(V_fhk|D>^F5cDg(l|BUkUsW4f}@c{mAtN4rV zZpEwF!6z>3!+>`}jk=02k?GV7j zkAU6oae3f@tepviEhj04EVw%9-=XyQCwjGZBh9oWq}+X#Ect+n@2g05CxYTbQ-`Xa zu$X3K;ms=*xmW@P^B0Rvt8$bqK(joA3ETcE@7udIo&Pr%K)T9CCw&rN@UG%@WOJ9R z4<-)L9VwP6SU!B%B1%hM_oO_Kg1&CZnp0=)o2lx|w=X`CQ0!x!MPTm~-dEUW#+G5T zl^$zL2+XF)<@c1-a%QcKR2Ur?{Fr(DbBs zH~gR8-S_W;o@943C;GBJmxANup!0XCN2&pSF|gzZ5ps{{kSm{E2-pXGg0HY6935pG zCKwa=x~ep+6psop+g)D^Dq}Q$uHcIq7zt?~QY0-NO_8qQ#|1@%G-BF}=sn@IhH@xj zob|(2b>v!+ZqbANxqbo9hfW)U1tOw^eJ{R+i2L7~O-Ff4IQ%j%Wz)bw}q(!O+S1hc-Y@ zzB#n>F_FpeFG@h{Tt9xkQMv{&Olsj)TXLEqFn_AKx;beVixb2$b>KQ??$wGq;&<7x z^mD7i=gcpm*@-msyNKTCrqeHekeASKM7o&c2S#Kdz%t~h?v}UY$ts!w|CjG$tm3?% z=rSmUm6U=e*&CQ3o`RJ888?4ihcPRTVM41L6LrFtjXj}TPZK*F2o~1!M@Cg((~_AF z@i-hu1ODxq=KdHLvg3}|?4`OQqmBz|4ZIPR-6#3>v>e82J#xwUhYlBkDchkp?QLDT zlUnIgP(}_if2Fa_+`zLJ=t5}Ime{|fN>`aU1wfU){BdxwW5Oh!b^Dw*SHjlIqTP3A zlieO(OAhO3v-jEMz~ZIw+x)rIdA^Kbu*>{9ROUgoPI%sH#`##Z7j=iUkdtk5MQp1{ zH7Z(n*Wz=XGbA@#Dd|o%vif;=$X{TX-FJZ4uCpx?6-D5aJN(1M*sLhMo0g7M{M*@> z8$(sa*wia01E$~y9jp7X#F)d+2oF0-gsrpC@PZ(uF+_o!KgCdfBe3&~Js={JiDP|Z z*4Tb&(HJWk)YYs3+d)_e)DUTY#D7`MX+;&ahq8^Qw?XpXg0JH}Ab2($lqvJz9ZM#* zTcQ^JcECopKzI5~Ye!C#1?fjKd&;r;J@h#z3$vv4Vrz~1krp<-y^SAyyt`#X1j0iA zS^PB&gR*(oL6rD42TPe&V>+qKg1Jv7Co(3M@(;_P2Y`bt$ehRbv(CH#OHEy9B6~4Dzvm++h1EHU05xliU8+ul)jcrMufqeV93&-fD|o zMQu;M?RJV#Kr;ALZEKcN?&U;Zck+9JuYSz+waua~1sn)Ew^6bGD?}N+*Voe0($}A# zoSZB%=_oBN#k&jqzElxW(Mr5S(9n3Wp{3r7_XXM|#&XWiW#;z@gvG>)bgK%pva%W* z8%s()(D^Zm+3`GkhW9{BQXa)DJtcVCdfP$tXPtQ;V`h~32vu7aotUVo^*9vi*qJ$V z@Kn5ytHqd~8j**cK1%M>T8$Vwujn^Boa;1utV|d`+{fLGH}V^s%gf8(97d(bG}6Ih zhdF1WHdVQ*eXbkzZi=wdzNDGt>8n!iVdlKPFN_r0r=5kqm1oLkyG_=?rk` zfj(0I+$TjZU;#cKXg?^`rl$w>g#KdHACVWb>Z2Z>=;`TEQc}u8qb1z7CPzm#)YV63 zXZ7%IK}&0VaPYl>fdSs9e)^QFE-EaHe@>e^TwGj?jEuGJyZSH~4F8yCt4ZW8E%xdw zo}ZOfyjxQmdkm(A!}mgF?|-L}BjN7UX1!D$&g`7lD%$Wc;f5!!IZf)j$9*1kfOQF^PJ!tfC!lioP2KuwYd0TLM|lgX5!`fTb)6`>aT? z%|Y1sQUH$|_e)wruJ1~+z3msmsJ7z1r0bH;hoG3>j)g=B z{XlcpJfA*&tM2Ly5p(22vNfp+T0FTyczRs#EDv;3L2s zW7yG!%V`z?(U{&g)IVWBuNxPpky!8*pJBbj)pxh$qeAg40x|Xi71Ho|FToTF4Hz_Y z?^%!%bG9bLfQwp9kZX?e_(cRtt8Psd9{f(M4-)YQe#aYXvUquR~8w77bL&}(C7A5ffPkzYkFXXmI+gMP`#zkkgybHq}KCy zfU&5zF)gd$EQHYCFQ=n0qFH1oUlm|adbIA4DfV-oT+gkM+4KEfW%sNGsvD=@1{}b@ z2@hbB{GjKVwGlK7zslqw@JQFK@jD1PLGx`s9MwYNkDq|&zgyb>1$rR)A{jbCwe`sum0sEzzI%nH&p|R zx1H`RE#}X1&i^%X^1x?6#$a(OkN#7LnG=^L5c6-o4N60lL`nmM;ny=2-$s!X4@Ju4 zH)@B?RR3Eq+MDMq9&YQw44!$cS<+$-@ZcUtjU}lBfx3_VLKQH0Pu$k;Y@?3?Q?%=U zGg0vK)4l4gcbuAztKz0YsG-@E3oS@+I5Yv#<}`xASgF6r05QM^CZ zgBgxXFr@TtdzuyQV-kn1^6YUZg(Bf4r1r<7)%HqfU(k;gqNd>ATLE}8Z*DL_uGV9o z1CAqOXd>{Md<>bPr)KZ$6t z=X0#kykUL)MX?C^l%jpW>iaD|Ue+Fb6L_Q@|AyDbykczLp~gDd66xcon$8{mh&}8; zN>K_PC^{Pme%9e(tv?ho41i5tv_K|!4`iYNr)pWf;v0R0jJ`)i)q#bL;YlL3-wK0)O8<8!ASI zYqK9Y>ulV5_jaMp&A;wmu+wZf18mAnb^rWub()}Ya4I&|x5wGc{53a@e2hyx(=8{4 z9L$w#;88}>56bcwZQq8ne+zN>Wu%+t4hku~b;KSy?co^QYh3@u1n%KzC=G8zyAZ6* z`@_as&o=v?LkH7~noguM0is$n=drkR+m4hWP7tU?4kc)0Z}`Ys-~kf^$4O5I#`S^h z|7R`PdQnOSfj~-XDwsA&OUnui3roTFg_5D7$E%m4xpMtl%b1_De2!}dy1I+?cG^m* zygWR_l(m2U*n>@S*}@(Tyg3=hGX$AzpfkFpz1{z0sa{WQ_3z(bULSgp$hfpGy{no& ze$YDX<=eAs(&*t^vS)n9>p&^`M9?{bUs4x~FFk z^^V_#E`H(qYf1lQ{I5gUDzB31VceCSPBP28sR|MjZttr7dAyIN_8r#M$sISCEQz^|CgIQ} zuGqE&Q|n;_@*Wypy5&R9B!V*Bo`=Qgx$vDE%bViIZ~}sifDr_9(F;3JMVV&L_tcrW zj@997#E3(Rebuj@k^J!+Li{dL@59SBEYsGRY9@rzpAtRU(0m=w8^7bd`+*F`Q%xFN%GiwGUieu{&U z0~@KGPZ&hN{qyTM5h(E6i!e>mY2Bwy)9=PfQ8{)<7avdD74DO9s1@V0KV=||qS(~O zJ6X@oYWdxT?SplCAhu@at062D{ z824MU__y=oih%s@@<*G*Yywy#gneAn4JFA+bUXZ(l5okHl+jT1k07u@0}B&B*Lx#~ z`y0ik%Gs?QZI1Ng2Z*Er=2nmba5izVKtQr`T=NzW=+N#pekCLU;g&zS2}fi{ka)y` z>r_s4&5PV?98dD(lstrYJa%Q($NY|CJOcK?gS`wibe@ZIh5C-Z~Ir`QIV@TcMt ze~rpxBeEvA(S9>W4LKsf8WrJ*JGaZgiErK)1VjMi-5S2ZsHHPgDX^a_FmSha4rX8c z;f%0$)P+|99E|L60g*#Ll4BP|$U8p1O~L>6uSsAIRxwP!noce`tEqS@H;Y>8pC&de z7BggVa5VI}24C}MlItzrlS6;KOSbyWs;vVE1Aq)=YB#3R9@;&joa8_1F5Ci`3kgFM zB|@T%bibEu+9rJvP{QQrBZeY>3c%fBOnR|-Q&oylMcyBwVQVcSDZBpRPKd(ljPF{A ziqhL?Vfm_h{8#N-lN9Zwflic9vgV25q}*thpOfa%mGdr5;*ePR;kQTXR{jJ58}4&9 zWrt2LhCbA@$s;j6UQrksqP3CuBnosH8~7KWZDMLR{Z_jJ0wiv&?4O=%$SgK|9xcA5 zNiX2LL6ef2e#{3B*#%-Z#c#N>jlzy5&G8Qp2&F(eFA11N!5N=8|+(wo1r_?%vZ0vJs+UqN8ErxIal!rRFx z_XWELJMmm_eDwu)<|r?~h5QQ9JL_F==ZGLSA{3$d?w2%T6%L1G5fFQDqwGm!i1ge22j3$y!q<56=eL*cRh2o&x7*-p)>K` z=$d4UUG9;0h&<_*$xre{Rg%QzxinV z00ib?x0qTm--Pd6Yloo|)tcs$Sf!Pg7-Vhx$c7E6ruRybZpWbli~3ok z@D63kSeuR(iFL}Nf8qhT0kRUY5^`g^Dh5sas-Z|nO zR@|(No>U@aX||N6k3bYyJC)(6#Sb-^F0eHQd#)@tD5)6di&az+L_et%H?Bp?_ihW6 z{)VphZ})wBpd|{w2UWSI9~4PtAlN<*%KmAG;ja^0c<8`5@v)MO`?r}N^c5TB=9ZM5 zBBr6g7Fd7@0^_Jj++0J5;HS&$4PJlq0WDt2m!j^Ce>1!G3cXJ7|3AM_GJoa|5q@x6Xyb?lHUSJt<@t zQ;fL0m@XLuIm^c#KaIZ_Y4*HcYasaTdSY1+NWs_3@Q$K!5xGhe;`OIa)FJe^p=4Z3 zXK$+Y=4=Vm(THYuj#z8HqJ@4Qt4E`lVXvQ6%B95Xq#8>;{$prn{}BmNR8l7jLx1iFp>qii=Mhiyg;K^9z4zMrR&gbAT#;nP58V)|t{$NFa zh$J!6`BnSMbvcxupI=)`3-5htSs93l(P)GUcPl?CC>$Og!C60D_s5XA*?=av-Bx2y z*~r_*e@bk)YUFaQ&uR2}c5m~D zwx`#FrP{pgJo^2}i4scJU|DjJXU3P$YeM&ItI4T&?i2EY5x33^+@{&Ht_M7d zHw_N`WnARNcGmS_E#WiqV+b^Oa|^Vph$4k*Q5Kl1Gp1oxf*_yOy`9a&wiZ) z7{IeEWuP-78A4hd-m^V>j*|7*98JbDiTJ`>24hWp*QNcpRPpNmEsQs^{wnt5?8I;FV}kG7^95?#rC} z^EBCzxmD@o2$&p#4;W{LxPI)Kk^&-@qyag=#`+GNiR^F%j22Iso*Z~KqohPw)}N+i zCeJxO*UoyV^Xck>m%we^JVfk__qzSK!DT#M!K{#ebfC+0KmOUyf_)>hPnl;Cj^ogd z+=&;h-Ideph*elbEnNN8`g`}|5U7~DPl)_kii_bp8z!W@9_=Qfua#h{KYkv&vvF@E zm{fh()yS^PDY1c7$8P;;1P(^gw*etgxXE9K|7x>lZj^vO;$a5->=f}7JJdkuc{_j5 z(747qC#{jn8&&^pQBpyGi=XK!0-oc*6Q^?l*SAdq72uqNApzg#6Ff!JZ(Il~>5k?S zoSyzJQZ;>E-|n*e+bcmCfD$z5C+G~E`Sm6@wpD(URK#|hZO&~u+vJV_Dj(Kx8Hs=o z-za{=f1TcoWMnpyv4-`ABT#!Ti$+Arnq6c-4>Jd`6Uof3iXti4g7*wxC~;u+e$Rav z@@G2Z|2$5pd0oT&;5NJD>l!_#KFs<0Ydks=1Milj3w}h4GXSqY;z6=kT7IT|RO_Z*2{sKk<-%kabthD)OKAGrB7^-SH8A?_RZ(4G^!u&9^ia*0WGrwQqGpnzw zJ1-I-;wW-1W$uoX_h;{TXm2L>S;IoQ{k+|=?N$1@pZ~d!a^ISn)>8!{yY#;d^H)XAoaeBO%4plxHoxKLWDj{{c9G_jQ0wEo^ zaGe}$*YF}GTE42|(9%T(!b-zXwg8`47|P-9e|5(aOquv}N}E1WeL=K5=qlqW0P?PD1aEK0 z{kHn|9d_+C_Ka7BzcB9u(dVn+Ys4dxBas_U;LMn)l}Yo6jxlgIfZI@(*Z+;Pkr_B< z5S$I@$Pf3JL)BWr3_%<2V|t-2eI_!1`wf2ytEGN2?md0G^GGKAxca8a+Oy+JC^R;R zon!$8cF;Vr-pD)F*r*7+2=cagA(0f#*8fT~VE5k-R)cht#s~9 zs~o0PVf}5zeAzQS4u^FV8Hf7|z-_b)yCq-xKDb?P8}lUY3EfQW3SLmvD}L8-dU{Cg zhcS$oIp^k#UtU$ZIscHi7&pc>#$J6O6kWQOF`B0Oo&~Lf3(1WQ3de+AFZu^m+O#Vt zw|hnijEp0NJ-8A+!v?(~u&5t3q@uRfKO+VXUN1ZT6PA+4ei84jC;)ufq5+YSYPiQ_ ztEY#`-Z&rJVB%hCWX|tut*fcsnrO#ADB<_rTTk2{o}d9QvSJsnoa-qmDgDP?axS-s zI&KqWDescR@9=-EOmak@pP!ePmk$jM&9~pwqhON{x~IZ(MN~Piwp{1H+V((2R{Bsr zh#(^IFbPh#iz`2w=tUu9IE2Wn#W1gIAI>+lf)>h8`_t-kZ4gq31}D)*(PNn}T?eg= zr!iIyIYHyQ`j$|q6oo>C!fA&_;cVqXwZ+v{Ud)13hq#y+RyMXdTizv%9oD(IIp!2} z8+(hrvRP0>M&=a&Wr5~qT^;#Eiy0QbFDmF-WQpFFK0a@ov)uiKnV5dD)FqF4TOBj@DoV zY?-O*FkM9+cYG$E@B+V=r(-KBAy;c(-z?C9qHEo_yh3{7;Ns$9ZT)-IflA!p*WUh* z0h`B?vBfHPtmAF}-V1{MZLYBYa$EpoK<>W|UiUA3$iq#d&AZ|JwXk;jn`fVj`ZLeJ z27C;e6)Fr4nqK^W&UCg7#?4NHt35`xsC>DRC2pv_g9)w=jfJaQ%YsTbv2;H(!Eb2X zckZ8+tKyQaL3OT)7|L-no{vnSIPYE_%wWH}iL>|@f%ojrzGM=&PpX%%YOnj2NgMpr zH#4h`y&V4*C-p1BcSd}9kyBh~Q4#h^aJ#ubCk}*}KQClQuR86Bn1;ioC6~`~>JHaa zdD=x22CrEn@4I?=lRe}GaKKX4xaR3!wf;za1t#sh4g%nd40!XKIX`9PM)d>~`NMoL zJq!em>v|sOfbr%lEpdv_=j%1pK$kV_38^Ncabtqa>kh#iF}Ogr@zCyMAdyZ!|I&=VZanX;&(aCc^O`K;Km4i z$*zWJtNa|Rq*5AGr3egg#OxF{_Qepb+=yiXH2S&8{#DpM2stS1_gS~S zlQn}z66Qo?MJ=W>bz4(-?lh)DuEnDshC9w#V$SpnOoq-V55*7v`TK@%C3)E1=&DxP zHa!qzV$b3*#C(Xjj6cbZg~+n5M;d-WItsIU!{i(J`~d4+GrKc`jiOHS_6=o)6!>dz z#g>WRs=L+O7(pOTF1e5uDxbY~cL=k!Pj|V2mj}x?ljr~5YKy{&tf{c-h-cQZ{djgU zgQ~Z@tnUs`9i~suhfGZ!-NvLHzHT3n6Q^q^fvPkOvjFM$%%=`~He;EaRI)GrD3Z&b z?Pb)_bkfruP(4QI(XKRi>9N*6*&e0h! z_N7*&Uj3GASPzyzN+l7aa~7-g5k4KT(DpmN{wih>zD|I|5(cZ<5ofs(gArg%zjQ4; z^gOy1hUeWpAQyRi!&M)1=0j^8+sfgvpQ2|kDiMy7t*z^B+U0K)ZRTio zxglsa$);TDZ@D~@^!diX{m%>V3fQ}Jzx{(MQDx&9r?VMO3rKk~b?gqoK~a6Lf{ zn>nAx$-Z>F@=?N&Scn8VrOv*0o$0B}cSJ#Q8>o3k$ghc*Vu+Z=C$`0<{264BPG<D>d>fF2BxW)*w~6c zenCkp}*Jy`56KX*zN zs}_Q18p3r;}I?Da+S zse7wy5DpgB$?>s9*=$M4+e8yHT;m55dx~}u^w*fsq*Pd~)>FM;LZFhRc@Y) z@EZnoPd(MbMV`*|4cO(VA+s}r_0Ua0XWa{fd?#kQk5BQirIWy~a$2Rt&b4%au;2m?(Gp{YppGy3K_RV)7Rotv<) zq=tA-U5;Xs?>cU4?eHB&Yf7Rn)bZY<xe7SyO1Xw?KIZA6$rIRL~`|m3JGz-u3+Ucv=-DT>N$ho#$UvHc~(jI*YIWBKfqo zu}-=fCj(^7FGDQvuafmI|5^TP<#Il0tJ$kLGZ22%R{eSZ{RN*BE9Uo3o zlOBqNA!4qdRn1&IGn=LTh-9mSd#j0Wo4z=W$(w+33weJ<4$Gf zc%+@4tFWBoyYKVX-7J zY^K{jd_u4rxeni@X(JH*LwCOg44pzkdS$byAGnK-mt#j+G|Dtm%HraItB@=D$WJUBoFpV%n60m`uai@?UO8!)9juNA9OCeh=mWnysBHw$*2_ZH$#}&r70OV6E}7UO!rpnLF5ZsrN_EZt{_5|W zZn42s5qXmayfitzUq7O6lXD>`!byA;Jo<3YY||R|mEr_APPY^qZBNJTtj5)hmNl-*M#VjMtRX)3ZFgA-!H1)}70Oko*$jUD%Y(ew zKFQ^;EW_o@d#ag5E%kwCYx`ba_Ss`Ss(#F&R&;wot8(%TSigw$5v<2ExppoeDy!jq zqlJBE;c;^!{EuU9SJpGAo>*rMI0BCO|MIscWNps1EoSh;g}@3i-my2i+eIdl<9cB? z7Cja?eNs;YennSO&+VGg{QD>>Wcu=5O#OS-1x-PRrK=J3$XZF$NE}Or_eE@K5j!Rw zKxKyWjn3(mU}4hc*BVJ)*_`0Sdv9$2kHm1dgK2wt3JB(V-dp7=)qYC#dUpk%G#!-g z!p#~>J^S|q#_bQrjjL$XOgGctSd(=%W|T``Drq5ZG*NZ*_X&O;REB;zR*9#qzkmM4 znIsUmRL6JgEVX3o{pOqTR7}>0kZ%AnoWS0~1Wv(D=SEF#qmNO@^R`yX=)}~1MiisM zyNhBQ!CmJqJ)y8DAre`baK-i>0jrzX z(|=ju5X0Ivc%jaNb=s>n0n}` zR0lf?&4lhKWd1*vL-rGu;7a7n;D0G&`4 z6&hHL8WyKS$&~3)%o@bbB~-0p)=@gY$7lR(Hy$$!BTB;OlKX0ix*oA=Bb`hY_>x6z z_SK3o;b^zV@(82IM}f0pZt@OCRXmk?Od^CmGDx}yPtSc#8*hi zj^0tFV%7*mO+2ZNt*C#?B}^ITQHQg62O=t}6EG9UI00Lv(Ervv;F5a{hU?X07T8B- zU$5=9b!=k_xUXwp8rQPF{Hr^@=cnJCkbO5@9N7-Et+Q2B&rw+pA<)hPL1ke+x#$6c z&i<@lXxuE#?8i1c-nrwv^&ZBOxa79{#~=^B8fG-UoIKv9xy`z%l)$x7{vYKd>07AE zmNxRo!xFKrwRL%9JT*0SZhoEw0$L)<|NIfTn*4Bic{ys%k}|xz%ebg8IyxFJmy}MF zAjvqT(dPu-<>HbQv3YiOHaGWL?Y&Zv!O&`aTJlZkh@TDn1^Fk^Ksi#j#$<2XW};@S zFVsg83O8fV-8@G9`(WtZCLLYdD)beUS`+S(J)jd267t>|P6=T8BNDec|v&`n4+t8Y!h5{yuHtE+NS9xQ{Q5t zo!U4Q=3=skC33_cETcM3AUcIz#ce!zLds3a?))LayL6Um7kdrsWTq}v_VOW)B zn`WrS#G5ipe@Dzr=QdSj$5b-QCw^?QOLrxO!E#xFm^~)UdMK{n>>O_WYeBi0VVdTK z03I2laimO}3=LB6`F9ca3-H4G#CbCijK)$@t-l65UbR6a?{jm&^R2St2RvF{sU=Tl zaVM18!QBpUP0O<14{R9|Re()6OEPwAu5rB@nl)lcJeGL*A0N7{W6F`$bP56>?Dt1Z z=Q>!9Cr)M5)G0?NDbEEnK|6~fEqZyE(k?h^#YX$`k#I7(=S%OnO}4&m4ngbUj5xAyP@(b&0&P zp8LR}z=(iOdNMll&^DGW<-N~K`84~x6UHDsv%jLyrB#}AU7?rp$^%X{x{fo+9OGT+ zU&&?EB^ghl_hQgOr0%zqkDey>zib_zq~05ypHM{vFmbG8cq=V^0FNu|%MSLvv+YV88iy#!r{=#cPO@Exmj(MpbmFlf*S7@xps>n*RATYh$a`=5mzkYka{;Lv^+hDptRzT)>r}j}e-*-t&Q{3R&7nkISRJ>PoA!C0P zY5%RRu4eK(vazw@9p(#p=7Myx<4ThxV(s!tY;-gx78V$1!KztNQ4yD()l&#x%S=P| zFy?Ding1D_vZI zLgD-P1hrR~<`JIG-=yXO(?Ul0U@@InlarHR>Tj@C4>e)Ek zT%)Jbbi$0*0yDq)(443)6w%W!<5jxA2dC+7(gX)lw^SW^(#R_qQSUknh#;6F*ZiNU zzq+>eLmd1uTCkh0c+zX+w=m&sYzptKRR{%HuejEyor-&nX>TiW)d^>JyUpB~gV#&q zgh@M2NB=C3{xPoOw9XS&z}7!{a=j;_k4nYNVBzPp#Jgu%eL3>T{+=;Xq_29aW7L~% zdUSUBW`U1l|)Z@;@tXVY@~wDhY;H!(=P!JI z;Y*Uk|GdIuZHDFka1z`4DktJokV_ZeqmEbOs!n_81~2RrbAljgEy-Qsuc@PFf%|u( zp9lP(rigiwHvFiRGN8Q10rc)=rS;Z{LhVl4@44RwQ}oMUmABGt)MRy1c?QGb5C_@4 z(HoLno{aY+rmk~+m#R}9$E$>v=wQeG{c3-YQT#+)t=yr^BAiM-;~{A-U*1~LlKS^@ zf|YD1bWeJ?=ItHZp^-~9&M;;Jr8nUmAPyb42 z&i>fNp&rSVsVB27-`B>nHItrnEUEjE4fWdy=@^*NxQ77 zKEtOcZ&b=|Jfz@ZG@}2$E^PN|5UE#EHly0Q;z!Km{hsD8bp_)=?|l)=c^DH`dRrS4 zI$tzAI+VqdX;6Rgaw?uXp;e^zo|XGf6{)k?BwQtm`Z$FeRTzNE#75UbQXFEYSxYd< z1BFZVXfZ0j1f=5TMBehiMNYh?9z(lMbbWCp7vpxOtm&zY3(}JAwr?WTJc$|G{&rki~AUWf(&jA^fw=CH19lAzOndUxLJ- zMXOzutb_t-_{?;q)npc`4DiG<#&Dxey9Tv({7Ct1xk~no@PEw4(q>ftt{Ed)Llw_A zboF^EMbwoMYR?mKQTJj3h66u-cUak(4=tO3Z@5Vm9_pH*cxF>=%gY%14|Cgf??HP} z4c}HD`Ot~DUjo#Rr*D4nx4kUGqis|1Ns4hpkA_e>1l~h0vHrhyDY?QqjI_y|sfvk% zgI{f`bbfs_uRFeY;tnEjK0dy|l>+)d9D@R;AYS+OZkd$pa{6)8+R~yB7)?{J(VVCR zSM5BEJQc+Mad{@c0XNJkL#LVs+{&YBv?KUBhF9LVGj#)lufQ-|m+J3|DST!(2sD^@z(~;DC=FyV9gxt(1T_?kuIv=ExKU z_4a(qMcosvrj7YoOedovEf^l^a9?HAq;2ItBLZ2R!YdJ9F}~R}@e?qEvnv29#L}-S zZ{Pea|3#SDm4*p)S$q(R{A>KfGr)Q_w-_$G&0{*dncbZ!`7%9VQWQ_JQ?b%}3|_)} z;!K0!583n21rWI>jt#3@>MORQcWHc=3Lp;B*Cd{n5VR&c{c%yD_q-{vz~kJqD{7*$ zOiCbCkL$f>Y0D$&Y|mJQRQxKaEyQN-p5&di?YgvC!25}jqj_kIH31U3yyaMk(`sa- zzm%pC;U)?od5K|?wllj4Sz6R>Sj^(asBvKBRAyh;=6cr`-6tsjrF}?0FcE89T9{yN z0ZFNG6BNi2sI!-y*p`sK(R146Pp?^&)yI#C;FNN_kV`Sk(<`r1BUSkD6fpt6DQM>f zWpcd}YA3~#eA2E$Z>FFz;f*q*s@4%IH&6OmZAtQ$>n zo@B?{SxfuA<}jz<;YHiFxl0%p@YwLIF5LJrM@Es{-T+M}dEzYtEAAVnUr6qztq5qQ*a;3eYb-}GR{enIK z-~IA!;~h*ra&BlQcm*=FwxJ__=?a+dl~c*fN3B~9oO23`5H=HrR`l;&Mf4n~;STvl zIh#IE0D-}J#MX58A1zA@xjZw? zUydghOJKr>G6_f;q9?Io`TY!#V>`DLUKrhJo`H$2^5y>qNdi2p#_ zP&Qj>NuzK{c?rU)|BkqDznka$^y7-=$9&)Jxt7a$C19NC0%31hTEv%PY{EwCumP$`}!=fqA-P+hV zQ1}WC)aMMEoh?*!1U*^}o$pMB8)|FSnNt{WmBjZf(&X zDemMFdvTXq%GX?-##^VXv&fhEzIuwBm(OB4XD~Bx2!Rka?Lg|{Db#JW@LhzbuT51n zinp=o>$fd2LJ|g8;*viTn+v`_OBm+UD$^9)_ItPi4{a^eDwCYlc^i`Ei|>WR3Dvks zO2d|P2^$AH7q5g8?!gX>)h4Ilzc6zKP9Y%$|3#2v1$`iDCE)V^+SV%+)>Kz_xvUAB zpJtBIepL=q;zQ3FzX)i~_iW~J-CdosO}iGsIFVzhKmLh0R)gbwF1KbVF;q9c6Z9_6 zs@cINY=>)Yaq(^12$Gjru7@w)bvBA#SzDBHaV;p}wYGkYh)Il(R}cEer~aRiH@jzG zY)nN)R-pEqxObjwrIdMaW+jr=Qwev`YX#g5I&zM`+b8$1@f(|0S&2mvTCPl877;f@ zblcbqeW3Rm-L^aJ{B;D917Fh!fkYgHuQ&G5MdESGKvn9ERNouA1unfkMOd42Zn<7H z8uNmuj+1D`JwIc)%8wW###6K%2pxnjga6)J;U*?%60c-8HcW>9#N*Aa3_%2ml%dGG zb$-whvcW(qlvmbF<3U|)39&s-dhpXf@>>y0l9)?&nX=3})JjerqKbf&Y1tV)pk1ZM z`_S#R-K?>;pcMz1Lej8;$u-cCvF#<3?kqac3Ybjy-WyS+&C{v>`_=8hYObJm_|=Th zW|VQ1*vaP%PRAje$CLn1>im5782V)YcUs0pqS zpz1@jKi{ubC-0$96mVwBuabB)qyhj#lV+inFysony%690K}2SW-6qm&7gDCzPi9Z5 zD0jyku8q*CKOLNMmn&jf8&Cd}A8+f%wzygHMuhMnIMaV+Fv`8^a~nUz8A zb*ZE9h>oloF;DV01gfRCMJoEw1o5&otqxSNtEKrXVF4cG;JLs9mAaUDUG73YEfeDm zWDK9SzU3kSky|?wBx`O_F34-VENx7*EGb*AeSB0%wlT<>3!~+wCUkB!@RMU%HC)P& z^4t>INTuA1W4J#kZn7*gY z4$nma#8H9lF(2vkg4)+L6kIW4UPoJX&+fTRmjaX7JpT7O_50&js1;8$AYQL``0)&> z_7HojNf!IfWGLp~vGFEDdu*Zd{fgr3JeyQ}Dtu>3iLuo%oQZZRyKQfeOm97URaM&b3+veHO;%kRhhU7$ z&9a5nDK^~e)!x<(E0N}H56B60!Zi&f`^Y)PP{S`mV9IN04$!+>9j6K% zIbywxxT}^OOG83D&y&b_7=wvofuFLh+RGeUkTPS1`HoH3W}0*|-e#!Ql;wRx!O^Qb zOV}n)okp})VDxCYt8l2^ckOa=e^a_+Zau+4X`*_`!|H`gF1PY55}DMBpK>~5e<`~k zg6=jjI{LC~={v3ry_VzYI9p1B-I?1h(cEiu-|>?jczZWZNQEYNYrl&TxGX^(tDhk$ z2-W+fN%W{cDP84o_Uj;aEVJBeru@x~QqdjS1i_s%=gj0-OLito4c1*^45ceuxC9#; zWQRvrICqG?k{}>{DvRGoyY;GO&>+Q3A3NTEHtJ3>#9^1GJR5y{Up;QlcRcSde{AQu z=1x&J6c@q&i1+SNbiv>0V>?dAdR!-(~i-f?lRxs7xPTULLW<3AkTBpxh@ z(A^n}=Jhx&hUS}VHt=~LBJQUXl!(FC0F$%YdKvOI6Xj#ALrn#UD^nh!!SZFNcQmV) zF^;_JEc52t0UA@+Ne!4nGG;^ogy?|0Q18%zS_riuU2-8<%@!oHF}xwIw}*+|!I&q|Kq< zX?8RCay(4;^O52&osIf z?ThPZ11o(~s;V49Rkc8%$?Aq)QSVr$wxat!TSE^H$0`-l5i;-lhihoeD%!U=abuCF zgB5$$^i70U0Nd5@R8%=e5hw77UkwWpC=b#&I`c3d)1LW1atd^V3Je$iT}X2)`ju}{ z&wKEO==Ez*9o=RD>1%_hxRun_Rfl>#hQd8?ut2kcjM3W2u-5BBccJXQK55iVZja#Y zQF2JdD_phxAOwVupm{UndTQmn2JVMjLAmPME319Gu+B{R7mEYBF7MB&up0&MLP;0N zbp3tIh|dRaKqHV#^9Te20UbM2Q>tqFD1jE(9gdqGV^ICR9 znvF@ag2y3}ej#+0g~|hT$l7Dmg^Tm>^v+V3a0?3y>+9=pzwS;$O3j}+a`i3g0@t3A z1TuS|I|)RfRTy{0k&5r!MZmZ^$w`_dUu6?-C%fK=Tb_E{+Szq5R{@SE5f^z~UHM(u zdpS}ccswCy%nJSU%V zzpLhmRf-`0a1qy+9?4ywLyatJXd#Y^g^qMw79CT* zby@tIPYsYh1x} z!>zWnR(Ku;77mo!Gc?J#f5-%Jt{OJyG`d)1i0(#nWtXHSzZ&_cIoPhohf=w;Yf?H=6pP*SI*jG{xMto;qWN z@vnVaYrD!XK**0~HimFUf7L{^=@e){gueI)NCFOliCzjo#gYTVEzROJ4P7F#n28DzSaG>j#q+J z{IWxE9{#cFa}!~ojp`m}xkEq4_FHvNlYMML_Nj@Wf~qrzv`CXCmDYcQiq#kC7g-p? zC8!d1Lst$ucwdP^PA(v>0+VCspI$yq(Z}e2WnnHWbfV4Qn?U{EsODVW_{V}C(roH1 z*3QA5l{4QeM%+rcW6(gRj^>9s)lMHZ|0w!&x-2})^L6iM@kT>*`E}pn^P4vDd@H-Q zkEsD1sp|u%`tzX8*wtB>sL2GPLmo6c*NAa54XQfwxjp}crqphg2j%Jf^9%i{n^*A- z|CiPu5ei0$%aSv=9336;X$t4j?7`r`%FYfV7}^xj%TcV7OG!%VeOx{8`t@r7WXxlt zqoZSDrj|iGLlQ~jcrk+LZf$K1ikhnq_`GIia9p9_ANW|glke4_54)Vnz^57s5r);& zFwFg~>_mZ&h(k%UgyVS50+>7)4I^?SEHCmx>}eM=uM<6;F$_N|t4ZV|(V6|iRX_c0 zz@}X`3tkS5`sG@CdwX%@g3|}CVAFl+tZkv%&krBOk3lm`Wo6Q$Q;9}CbL@$`54b32 zXJ>o+XzV#~n$6&#T(be=RvXAh`4me@muS$=fWb?clT)=^3zPvk1qGWS5G7V}F<(!A ze}8xPRIb-M&R(F)15_B>EQqTvg6J_U#fqjQS|v6yhJfb7UkTq`C*sjEyWw_-FiwcR z3wG%IE_kCV?5JyP;J~QO`2T1+%cwZoU|SFF?(XjH?oM!bch}$!!QI^!v9%GWcSp&Z#%eK51Vw3;v_ldzGHHl*)LXI94RL7P@+fIb_{j7flNJM&gTZ z(9-E=xz$cjo&fww=-kg|8(X%{b)P*BO<(+=7qf7t6JI<2D{N4b-h1&tOUb$*`Ixx%sNH>X{~*^*eWI4} z&)r@=b596sH{qrGIM#YE#xbQd)UaMfrYs>dI9;A-GBoO>MiN6D=!#_)>`S#@7>r$s zJ3MQ6rTR80#B5>QCbJYI|EOy0fiC19oB+?QT+*H%`^&YO@Hb}F={m~Jp8|vGXDNn- z${w2|2}3zQ`*p$IGbWm+W|6~LrPUoyZA6^u+b@L7&F@RXil1~!!$#a$i!fD7u(g(;Ply_{FkmaMT}-FFcSCyoS7i|ExnbLR$F0!w0y4 zcr3t;!k>R}aRF@Yyn6aNI(USI_bxmDUQQr?{`r{~OTj>2KQ}9@h&};mYszZN-M#`G z2nbdOV4s~F9X0<4iv!5*`}%^M9JAsZ01oNWZutHk;J*QJM!8bGb`_9OU@cOcp7!>P zDwoN^PWw3F)h8Y^5?K=Uh&TH==u#mC%O6V&Qv0r=y7)S%4QCLpx=71eERcQHQB`wM z8zJ{2DCT!`&2ENMQS;soEoXZoS%*)3lRPP+{9@DY1ylJ0fp*l|I?C?5d@!^28<1*M zueA-Fr+a(EBqR-5wfV}{&dw+j5FYO$%+b0E7K)vC)lzMUEKQf{aCD^?4MUMb9diHv zaYbq2?zZ|lYY&eAHiDe|p4%E)I)oG+Sx6Q)0tr)I&wmDS=ihZcuZB4ojmPS1;0A9; zZ@v$shJFVuH=sOyZqN?68K+UzUB>5ilYge$p5-z3EU;zlIj&iM?)eMdy#7y5#Y7KN zVc+M>)9d3<2V3V@&t1=?CyTz!4?ejKl8#wp;p(XeaSPgUmfdJgWSU3*=$IttMJr>E z`D)8{Fuz8!>%G6k(5ykw1uhMYQ~gzuw3;n7#ISyZDAIjM`foe(#~84jhm2EfdcT@4Y{UH1AXv;IKoiBuDIsv2Z2 zusHrTl{$e**{1F*fFyu!5CyM@h~mR-Y{yoFF7<#a)m+ksoh6eIOGgBRTTX_`_i6QD ze42IVYrjIT5hC@CnUlj_QeE+apNEp!G8sPWl^7ir&5p`av_rnL%(0<8HosKxm*tGF z5HC)}hTXFbP8j&qI^_n?qt~mtVaD1s6klmAN>Tjs^)uGS|80aQ-{;55`XL@pmz>c! zR+_Mhkw_@oUi9^{T{LIMxU0a!ba#}w?=OyJEY}5N2b|Sw*i^<}jMmc%CAAir0W&9M z4TEDeit5MxftF@Nz2t3^ISt+>nA=4$k_8NWa(Y-rQ)Qm^EyL52bb;$%N6A3{!v@ay z>awmp-^j;m%1t%^nisTHAXWb4QI-VZPmq^=>*3+J)Y9+~bSr56x$LkK^;>c@m2Tj^ zsWq>EYUhQm=ji69Xn7x6YqWKz)dpvW4Q>+*awal}^v@}0viF2Wqiw5};%kkZGn|T~ zch<}QO@IaL)4(TRauik&t&l2)%Dxb6r`yvWXgL-&+w}Tw``_r(r?x_f%*7)Qr|+WthHo(@ zLU(lvT}_noejf+57uCBuwYOJbiVLv05stjwCDY_k1T3s1jI8oQ?s*(0)l|!wYQ~fK`T6s6n=S(YCqqC$02qc7 zX>sx^ATc2(CZ<-qL0MT@ts=aX5>be@*iB%ILDyYw;~Q%_Gq3+7RAeAw9tzu`3GjTj zkcfc022PX}DkF##B6X;l;$pJXnFzbQfMUVI+*WQ2DfP&i-iEz&#!vbDGDb8aoUUv& zJK#XhwX*EqWmXbKiCQq$YX#o=eC0~LdSnz70CD?vLoh+w&pq_?eu*Jxzxs$W3YE<< z8gFK7>Zv7v*Q`We@MKbKYsB!6>Qf$-ZuZAi&$Vb|5U#Cg*l+3pVp@=PqQ^cyhefD=Y8untZE+$J5 z)|Wy>i!u7x(5jXOqi@7+nFYj*yOym>`i!+UL`g7<8u-Y=RbtKbdvRYC#Co)C1{z&` zoJX0f+#s$A16F_d?FqVDkWZ;OorPYL#8)el`_Wnyrx`aSG^=K+U8Vh{fto}HQC*+z zWGP*?zy%jMK2Mk{< z_jf&!1L^VigX-Uj2L0Uky5dS7*AA`-C}S6}36X{z_x6g$7AdW)AZ#ltM@Sr7ZzST!pvievo0%d?Mu z(=Y^)Ug>;(sm*kz~}JOBmz z${M|3x%_vPiOH6`9Lh^{s_drk?0j$U*tpvYx=xD-uuJ)!INFWIkSV_G_NyjkS*P)f zl^KEFm&K)JX3arwlbw@l@`e4iluf@gWz6AWjlDJ+Kf%Y`Fz3dct-gCU<_A|$YW(qbJa`EHk!_dOgRD^ zc!}5Dzw1o$xg7EI(B8ywSj~*d7nXk-F6Zns_GC1a%dM>%WTc)&eN!(xOZVPQX?8uD zp_IyW;@IQ{fCxbeY1$~WmnB8p-95Njr0bM9=IvKQn$lC?R=M>Ry2~tXLh5VGgnXQ( zLwsoErP6+BX$-wmbcaP9$4Y~#J>2>4UCa*bedma@lj6~~hG*gx7E zst|5|nkpl;IbcazK>}ZcV(~eH+b)bB8A*1(o&mr5zbO*41YnyQfniE*b7^TwzMLJH zvE;)zvp`O}-BeBNAv3%QK+3hQoxH4*zkiQfbrN;vChZHN>_2V#bU?ykHtzqn5)`~h zd=UZ0%ECY^t(!*AM!xI_JH|}r;HMqJC;uF+vApXYN-0E0LPA1JT#%bv>J0#_81cKn zw!Ood1f)jNP+yN`Wmz&;O4@c0q+J8y*LTMgV2ms*fcXv86D2%G_&!pExx&6*wRBl_yvcL6N5axh6>cEG#U5$rfmZK0n?io1FK0b*nYx z%h7EMfldzKa$jHl+VqI<@HRI#Xv+(Z0Xv=KCgpNLR+f&jabZCLaErC8b|*PXdEExg zDvFA&+t;hBn&c~(0LcaDX~5T2J54&E-vin?8|a$VOMn0d8mx=IQW$b} zrch@r{8TuQw<4Fe66i1)V6uAo5WsnG#1$HClW&H)9B_o{mahtfv>CYsJP^vLI3`L@ zW9dlh`wUTcE09|h>GEPhyff_sI6Wiuza)o}zy^2KZwlO~9S4X6mc2SLBNUQ393fyc zON$(QB3G||g9g8JIkgh^V|4vt-jy~_FN|7?z0ktk9d7cB)Ut7FqjHU^BiSd04i?4x zS}UFKT`wyeJlP2Mi_6*hJ45hVi7x4u?wP+0b=WtfhOj-8OgP^tyn+}VT0L0soIW)h zrE0aEsjQgMF{tm_xa{f2=2wX9Wzsmmf=YNO%5w1&fqo~G=P?n-RNaT$Za&vZ=?e_I zKmtRTc+g4Qb z(M;c8m&%;?qzVEgKY?ZAP-qy|L~q|bsvxR4#v(EbY$48n2I6R}Z*UBefmsFdExWOH z%sEa{zy|!Lg8ad$z&%6z%J?mx3v}sC0~sLB1HXoN8@iguQGNmTMete-a~sgV0918? zeY5(Z3IJRGnX`pC*IROHJe!1bpD%LK=C?S7|CQQ+rYpKyjuH3{t9F%VfWsO8^bXgu zGTVEk#t-4I%N$>0)6M1R^<_Z7){rMA9$T@)7AdI`6-BjRCOa&)lUUy01NNFpKpo=U zA?^DWpMw=p1N?I6$M%hB;0d7EyP*iJd`Vl0Lg8DhA=Mdknp3a$T za{ef>7nNfzp~C1$k+yO|D4yblZ(cE95nD=!;AJKth<8`VovFxAJ5QA>r0A1)!v6zR zm@I`Z^;@PM1yQ#K|IB3FhI;>OKFusrk#Kq^)=w%eANpZpzc`iYb4}D47L&uKsxC8b z>J$@o21LE;0q!RzL2RtwoS@qZfP~GNp>8s%*3Iz0yNz|GF|`8iX30|~R(#>foL#FS zMoUcSf7*4*k`+PIW6*mI?mN;}I*=T>ceA?9*8ct~vyjF!SOoxiaTbXoJyy*QIAj5E>I6*O z2?a2Zjq(5hSCwu#umYieOGr*m2DJW*3)?d3RSoLoaRuA}PtWx6=#>^TGqaNIYruG% zCQr4@Np~i8o((SuGIyDazEJiV$t;ts%+&!3M>_2ne_sFZ>Oth5w}((n!l2msg* zd;7S1+OTJQsfx&cGl+xj#9<)_5W9us!kqr0cHkC|AlegrJY8o}@`vZ915@sY!>R;17pRdr*gHJ;MpF>zE93(j3yuU+f^SO8fH z2V2~^fz#RK2sG}b>;h|6J&jBA<-^(VGMU$19$9Z)R?4Ysx; zIrKO&Xas-;EhKNXJ5x92Ek>Pj@*SdxnscnKx~!UP8(R*Mx&!=JW=!4gpOO`89t_jh z^oW+wymLq`o@0+F6Be9H8-+l`K&O^UOH$#YVAsSmaPXGFGZQ#5VdW`<7+g@Q8nM9! z*>@a&0*HaKR`Hk8%Tl0YKID-esyS4yK1dOpq5;LfrJnLF=c^Vum!`sMAp%Yot@v?6 zI4{vkM;~dCp`_}7O4K?$J!Yl2uexvd_CE4-C9a+RvGYSFBfl3$X>Fb1ZzI#;YNLYD z!WW`JCKxxZ;xY>b4_QRQsHPZ0-680`_FBAX#gLyq-%L$#(~wFo#I@I3XTMwhxBfsY zjQrSTn`%NBG3`{Oup4^(uK#o)seiOcN&tFQl(CDy(^MP=-&J$?yJ(PM&c2|N?tl^rKVKV$BOxO!2qUBfv8e3r-yd+ z8rD8U$X9!-?XoOSHQUirX~T5&*r@fj(rZ?5b)~sIb1JC74)dcEiBu4;INYc(RosOM zHDe_8Xj=rAhZ-X=9O~aH70GN)Hhv3FbV134DYA8z{+RXv8 zlm^*-XUl^ILSI8Z5pkHJHlQA0bkxz*2&Wf8p1}zS;&);F+-h zQ-vBje2f@@iryCiC3ZS`)lh+oJO*wq|Fe$&+zkK42f3cn20fONFlDxFKegGfr%>Vn zkwN1e1w)UHPEN>!_4*yKV<~TvgcBMq$*`nd+Nm4uq`@^b&W*7UR_?xgv3)Ok2HFZ#A7HIM>Xc{L%UE7fm)4h{$t;B3WQ>*?tM&My$I zntK#NJjGK!E225jBm)jFqVO0LKr&eVf(wwf`27I>%ErdV&fXmK`Jvz8^j}T_eY#y+ zH-LF@p{J_>|4i8)5dndH$2QRNa&U0S|5vLb*Lj?FSP{eGdA+>6I#c$5Ui##O(y_O_ zJyHX<7swU@jJ?#T?Petc?NoVC4nh1e>OIB0G-0)d=W4ctJ_ZVBn?e& zY~Ydzyo5=P|47SrCr~thsk$QvPGV3+Wu=^_vV2g<$q#D-_WijzCGnR>hasSFZf)s_ zE?d@@_YFetx>pz$tfchVf!cQB z?yA_86Y$xJOnX|Pp84V1D=4b>0LTexs>yJbV*e81Y|FCJZ}{+%RE48OJ|WTDW}YWR|Gm;St2CDYqX3~I%TyIUl4Z?&ZA`gDuE`I{w^h)Eged%f1)>P)}PLt77_&+UV$-EK~(>Yv>&!^UB2J3jYk z;4x2=$cZvrgjTQ{5=DsK`lcd{F-7K`SMXema!8;SSgrV1#ZdGexd`;e2$Kny+E{j~ zr|MBIOo7O#zcL$8+)pDg8=(TV`08--y4gyKcE>9QPSSWznh_|H8`4FHh(r0R8(`fw z-)Q2U6_Y@s_Fw#AZ7SVBErako3B$~KKsd(tvOr4Lnb=MdkhhvC!hGeg-yWlp^<^$H za2uIS9|rt(yG079PxQFlHj+Og$MRJHm8sXP{d>-#J2~j1k1aBo%qDsONYz|^vVaC` z!quTl{<1+hy+>T55O5j)Wubvc+WvmH#i_L?vsPoTcj-jav09n zq#b!lx!xy9%>*AmNT74LiucAJu9P_+?6TpoFU|g2(E4x0^*PvTAJmBCU3kRYrTNY=q|^>PZE2k_JE=;eC-t7E zCHqF(Q*=71Jl*{vquQF+IY)(Pjreh6$K)n%F$F1X^W$^UGzIe<0|7 z0Ylq5DJvC0X3YyIiLfpyvR5S&e&HK)My#*uh`Qel9hRvK;{L;IL&T3^p&S@qNv@{y z(9j#d!+wr?lSLl)Q1??pio&N0K}afb`*12+s5yY6q9pq8F4~r>jNX^umMOdSRDY%- z!$G84YTx3D&;d_vpUGQElmy&VK>+!EW4fNa7D+`ije+XB63Y7|i-TTfz~;@HSKnL> zFy=2fe&c-!msZP|6=5Zm6_ z5%j*2WkL2R0V#F z#iCfo^2wtibLQXM{e^31M@Pef!2HoAi#ax7Vdd`>0AZ|F4Zs6Qj+{@9wzk#(10OX2 z&~ZaUVq)UL!a@UZ)z@p*YK|A3F!i^#N-ir)nD{AQr)Ex0Pk)Z=<+5}o@AwuNgR(`z zFD7#>e$yKb)t1$`HMq6;S*=FR{o2wS5E~H1{Y`6c{|1tcF#x>}oDNtv$QQK+G( zP8GwBQ=|@)F$#v59PJAFCrFq)l_Jg5c0FHpAzf-o4gqBG5r+(}4}823qpADz5~ge^ zhyYR$aD%`AqYp^*-iZkbxaQxQ($le;&r^^Jkwa`IHROs_N%j5qbgr)tPmC(RKN$A4 zwtD#ZY&dm1xI?@Ll7Onu+VtYnUJqS(aS;JQ9Jt=zKaNVwnYHP$7T$oT!U*xZ8CyJD zw%mdRedJGm6J)sH}Y7f|OfOX+42S528R?=QwI6+2H(B)nnt~tHj5WS%{YT zK>xrA(e?&Mwy)ug$YSB;2?`q;)Kh>!_gNO`1%BD!QWnZW*dPrMXQHllzm@tT@M-mbWZskH>HST%r^O5&lMd z{g)^6n(vNs&Mv1OGMHp}qo&|hyjqkZQ9r~^Z;lU55zA8TZxkB*3w`STwDUz1@TNJq zOtkCpfdv~z^a5?Xl3f>R1SOwG@^4<^IKJLgQy30lCtb8B#Sabsi3EJ`eLZv6R1!x& z8tVH@+(jlUr}+GzgOjt)ad))Q-zg-1M?G8pxST&RIlEyLFS&LOb?s_!iPZapuq_DIM1Qe^4h=jSFs>W zOr*mIsx=FQr5g4$LG4HQ12fcTbTw`4FMG~)xkixLqh%P{N|q_{IT(fscwSVFxwva_ zXPw@v>Famf@8!7QR7DVk6#cn9ZVE|pTFOlF8#^eCkX#F+6bXEt4kJ|OB-y9(HIcK0 zHomKVk6x`9B`}X@La=a7r~zk-@UNB9%$w)F(UzSOxnceGd2k&gjfhQiKT}poa-IXl z=l4(R)7mrbz1&4MzT%lgKO2NHo1huXod*R>9AF(Wz)f#1UWz%mZ?@oqI|qZ6}C}8|Y%>70qS+v&eG;Fhj zW+C5#8`$fFv~C4soKYlg7&7Y?Qfa>G92?{yE-ol)(D&f0mJ0G=JVX&>S_u2&J}%~B zZ+Zy~+!cO1^j+4~09#d&B?KgDV&{i{n8F}`BP6I3(jc^k9Wq)(&Ib1w@?2E#NGB{$ z$0LONaX)9gP2;m3ESURbgWI|M)j9r>!voDRq9(s*8*`T(^Nug`tiDbck?c(?3K}Q) zK@`r-;pZs$AZY1!c&&wy@8nqWv;GTFB>M?c9I?gH<+gN?4dFivG!2@_Xcii`DMPOL zB@vWW>!szzUA(PLjYaq)6b!C~M(8dpFcWyi1H`AZ<~DrodY|DYc#Y!EEs(0EbeSzt z&YIJ~DK71xBgt!pYo#ZA(^wM<<1mxKBsJoriqcn+;^LB5#EB$#Za=gm!WHllkaB&+ z9UqvTD$MLY+)v9m3=`Nco1eX&!+z2R6q$F5ll}IFeiq|9F0XFTmeh`E4yQ&hR4`Yk zLx>lW`W z$wV$Z=YP3%##a#o6aDUZQi5YKHm;36J9lcOQCN&T*AguYt?OR#>)A{kLNmw#A4g5G zScJXOs|h-1ujnjXi$)aewIar7w$=77ZNaM130JqHHKVra(oMB(()L}&hdAXJAwTn3 z?4+7`EH2@#lJP_*wd0??IL`Ty?93*PjylkYYF>Nje_baz={= z`1r_Pia4_7E5pr+bsM$m2?+|8Au6I10!3Lti5!u$_&Y$-!fuMWLmOG%{CxvzrXCRU zx9ZiSgw8!wSDl2Ey`@NL9~!twN1Hjr*`P{`S=TmZmJCa2flGr7H?<6ibwDmEA)zV+ zbQqZKSlpOdpAk(ow`=P~8BW~T%Zu+(o(DfsO1tf!5(8$Ssx40ecTlH6&tlwPhAGc} zhOQjIpa19WJv}{Lt-7_dvlDnGC{T&HjY|A8XMQ?$_yZ69^y>oxpkCjF<^HYQ+qL-t z-vKZiKoKm%1pU`|Je(qRHQI7V@P~WtUVA-+dXk;B{hhAU_J7En#$)Ipp-=Um+~(Lge;~FoE9@op-IUab&aE0^{{;kQAS~tlvjK1fy(1xX)c3 zs@M9MjA1R$KSVwcL_hgo>A&^Ab~OD}n9S1b^c2PX!O)*wMJxe#*ET9g5NyzT_awPS zI0A-IMX_d4-EaR$1C*h8qgyu1Y#}`&{MyfTY?|SrDw(cmXDqixqLr6 z;NOdrXQfpnG)?Yy%Y3IiGxKz2E%S9{zS0bVH-guJJgbC9&rDOFUw6sRL z$3U+f5=JHgGbY472$~j4${TfMkUF5SUYjpqMjCuhR=Y{yQLvn#2>LjjQ zp4UEo{3|+Sv;d4BOJmv?vtmT---6k=y&+bLZV3XmO(16_9NgcFm%I_NMez$EW(>U9 zvNmA;EOq9^mq3|-Re>0y8z{@1x!2V17!uGH!LS#bThL_V6K`p%$ow$O5OuxoV|!2x z=CHvW-0MJ==K|0Ss#MhLjF*evNb_KCi{6OS(IT=Zd7iSUYChZ9jxDpYQ*P;mVj=JT5t)X%kV>TP?a9FW+rKNd?0~Y@VH+rTO+vV@JWqlcs#|qfb?hlk_g9Tv?)mz zM9m;5%l#1!-c+3;5*(j^E;30f4xAN5$0VsMvU0I_$o>HJwS5STb?~$$Si`w(fmQ5L zGdgoogxjvr6mhd{L+VkJww;f95L`9*L!fjE@d|aDuxF4t$DPgy1cDv}ZGagCUnYtu z=Y9Bq2t@@CXeEgCy)k%EG_5*8X(8H!_R+@fX(0$Vh?lt)e3{^?Skw)=n;jbxkF=wa zSC`q0Jr0(u(%EonvLyCB;oaN($7lHxdCv63$LUAC-!0V*oqYb7-3 zG+3(W=71YA?~7xFGVYpHjzI9*2s5~RrZEJQS z$W&7+w|4%@#ew}?>Js!SBn<|7g^>8H5}AUJUygmrMlUzLVx6411KROfd;$2BRc)m! z+6@O7i#Te-y{ma6n+jB^Pxs#Bf5I(LbU>PM5`D~Gct3i;YF_fze&*kw0lvn2z{>)Q z6p9k{3AhyO&F$^y%)q}Hp8c;6GsYkHz^u4XDDw9eAFhqEF~veU4O-k9SQG;bawp(f z$sNXheoyC1r7$SOf`R{@fdE&P0zu#RSI?eZ>X@&rxc@Dgxi8Z@du6sID0^l9z9kIR z2Kq#$|LUv#kZO2b`U8wYk{fnydbF6Z=ZbnXj-s82EW+saM}P?U`*+f)){l2>ZEct^ zFt(u>$RF2UQy+?Y95KHzje#saEp2Uua&%4E>3b7a(o)W@_P#aU+EpM|YZ6`I^vbNM zv$0XsI)wi27uv7|26Aq=`H^m-G)1V5`Xc$9gsO9rlX9qkxtgw#QHAhbWiX}Nv<4(A zA+nr+u&^+YPz#w@F->=HcXDFEOITqm|J}vTu2{9x=Z+li9Wc%w-(^uV$#(AV@6!}b z4E=Y3Da8{K5fKp*0?Q|P55~-yk;9~4+beKoxj^{^P))UJATkyxm0bo#Mn=@4@I<>d zoa8ULvljr68Wa@d>-#d7%frCHU_oCwImDs$vp0fIq$$~3!5#=Q9yf<8Ej-2^DtMDY4@5PpYC0T_!6)3(mO-cIEq792afgk@~ z){TSSe;&+lc;eV`3!@1oG9d5WWIN z{&P58CYqVPe@dDa|Flq5Arx1+ewopf-R;B$w^;?pTs*Ig55)IQk#_#GD~Ie@iw)YS z`v~^8Un}swp1sX0Ro_1ID@|4x@;F~(^e@G8leKJyJL?eHhR{S{FDT6TIF5s(!x7$@ ztzH;$h@*{p)+U}%7eTxw8(n^ui+3%Pt)m7+Yo-=BR?XMx3@bjdqD5(2S zYi3r`iXnB|b;KV9DFY;-u@wfN$T?xZ*NxwA4Yo!TpY`QoV;Z z>+w$-o_O-8a1(j%6$15Lpn&}YkWR?PY1Pk3f?$5LEQr%!EXf6Njg~(UHTe_}jJjPG zV-yMe8i{DM25XFrk3=M(_jgfnYt1pSLX$OP2P^3%3AjdL2~5ht z)%vN$1*|ox?KDsB4~|9jh;f6Y4@;TF$aoclgV_m9K-vGA|Dp+#4WIo6nGvx4Dy$k1 z3IDjCJ?=;Uk$nuw3+5Ff)Y^~y4>L_5mV^d2xcQB13l2?`S=RwX0Q4G~*gpF^$v2&|Dg>^#{#5tpo73*lbXmFIjU z-GWWPZSR$|5fx<;9TO9>`hgSS6M|`039CCsaz%$b-#}V0RZiuerfa0*#S?bWhA*CV zAo;2G%o^I%g64?pAw(b99hx<+*%3p84g?!vJjmF>rY14A>&i|PCkR!+D;9$+bL^`> zCP)9GziUggGX#!-O;)dpaGir-Dl5|TY)J#h#;~<9po8Zde(Cmx_ggk1d|UFvL){X0 z4}*6>dKJkXuh$5&QjO?!K3+gasn5`?{WPB!&2gEy$;ylUN}0-)9i;yTwmY6{U%kg# z40X@=GxRQ;rpTs^yU4sFCZ%Kn8y(61}ps_!p`LnBngL<5T@Pm6>lVopLC?m0vY9x?mrwlJUu|!J)LY7|`GtklU&w=%L`Ge1 z5l0{ADvxIMTISz`{Qvv{Pz@j(3^Z9F_%6g5IV@mdajQ)QwiUJeGdCv_s_(u)oA2T6 zo+SltYv9QKq32Ic$2xzdE-zW%QT_R&J(~j5Bh$jb5y1h$ZSG|v|A6aWc5Y$dZb@x_6rrMA>pzWsX0wuzJ4`m zSf8R1#znM=W@chq+R!&NyngZnLMK2rKcGN&`keWwn<2s_#P%{vtJT{g?&F^l7j z^V9z0+X+futVq|Gx6Q9dqXE@H?VsAXd3YRYeHThQ{Yd>0FBc{Mn1OdRo`C1$kmTbK z$PNyFCll)1zE(Q}U<^*BLP1}*uU{4CUx5iVa6l#V^Yba_gXH;PI_Tf#{zo>~zaZVC zs~CgUBZ8Zt_=3n+nS|YomgBE{643uJymO!^yZJ>}TPv_6>xBEpQ%UDP5K=w{7rjwP z7=rAMy@x|TeqRN3a%%lJwTr#0)ATc8Mft*ey>dhIg$okZ8-uUe?B&r|0Qh7nF4jQj zwt<2J?MKHqksTh@UazYE8p(ZRoruyG2*(g=;N!tQ{Tfem>BQh(Tb}D1bS5!Yj^+ty zr^3O|ZEGoOKmhL1Mxr;L2zH4138ummQ`M>9hhm@|STqoy!3EO07S(bvS`;HXV)*{K zcYvgk$v1RPKS^@gxA9sq1ge?0SRe;gsLCi3HJ`3xIvZHlJ1rW>u@y*h)sUwuv_G+K z2*N)agXTd;-tOxpglagz1M7&z7I4(G=t!;Dg~VrV=!g|>kn#jaG2yQN(6s=CFS z?u>J$St?Bmy*Ge>Pq^MLg6(|37QN~z>dNE)Ge*c7;WJ2}aA75|_!ns$bvy6(a@yhs zKVptT^(C9{{1N2Q_AksGC5y2dvN+=Kc!cWXka-A<=z7M9dm3n>B503bbWGfcd%Bqt z8M15SV2tDFdqHSgW7oOqZY*OrCL~aCX9hHO&4dMO>Nov`u+wsluR~AP&_pI6ZyTCH zDiau!?5V%(zwv27_M$NLLQ#R^_%0w!5cC~X<%a_iZ{)MXZ6TgV2%AQ-oDRmncLj*^RX?i@j+z6p`kV3oVFKnn2yoWL$-gT=N#=P+SVhVFxXRseY!1 zL_BlH5xg%}!Ns+Uzc&?k@poCcg19W~MswOQ?OlYg$gJ*M6@sN|aX2&8JVzT5yBx+? zy86vkBeu-lrp(}1t!PEp80RJag-(dbuMlr5LYP^rI{wf)+ii?IAjlN8<& z0dY{uWYZXk7p9v~BeNLMcd7*8DYENv1qCT1SO}y{q{W5(&W+(*^5$9_{Y&UwcsP;)3H#tH$ioH&PcPH@O87~iF z&#DE}T~(c$2D=t@;PABpaSK)7Ajk?7&9YNfWL1Tns-V@DO(>u!c;}TT;7<%1g&^Kn zI7#uWjL|Y*)Xjy793*Un?7)#%?M<)2QCwrBcGBoT2G>~Z%_FDKsztV6Yl&7^xI;lY z4dHhQ)?%^wUSTo_=7J1b0ZV1bko?-^aEIQa29^-Qb%2`%VsN^V5j=Pe;*l+?_?ANE zN_6yjc$bLoYgXO!53)u0EN`;QZ}DVWQ-OefN3_;?1cU%d5hq%hrWsD=od_u(yj z>sKJPlbQvMYJ9J6Xo>>O1oc2`0XLo(!w6ryYCH0GRUG9Up%ydn5t8f(c zgd^V`n-?s`ew0g2MG1Q^#aB`N1v}&@5#zDYVJv;3v|%oH>Kcc&o3t1+BRU5cs)8Tk z%=OF#Nmbz}YBAaFFCDY?r%NVE#9FHwMw)XvmmeW0_d95s+7(W5G012Mp2pAEy3>uJ z*31~dmk*d4anJ&528hexVg%nYGsNPqkBuS}M6tqk&?tv;m8-RzF~lDOoD!n3zWbQmYa4+zaQY$2zRqltY?@qL--P z>D{%YG9xrIt>)KTWEoFfvWs1lH{db2ZYAzSOUJ09y#_K+ z_z4*Nv>S|)gS>$B0!J-i2MSz4e|z=;BOrh{dRz1}pKSD$&7n2o@)6L*MEbIdS1xCt z+Tg;#z=RE%2okd}GXnw0SaDW>IA*3ne>m;md3dxYW>hb-}Yb?n_1qc zP|A8AMdr}5`{oO@n;x=oESAZDhr2|Gn*y8C{o7>%TguecZdFd?NyYO{rZUIwm$>qzj7pd(&%3$B35sJ{u{$2QtB6c6h{#X zGV32|4L+aI`;him`&D#316A&z9RtQVbz^7Ku6c@{=I>rc2X2BBUswxg4KNB-9=RT1 zkc+!gQtTD6>zMI(xdvy|6$i%OB@^mzaCh0<93FfO0!$u5VlInyewyW{vgY#`FXVWn zaR!|~i5Rs@Cv<`rwUPMDt=HfG30_$|DaFjavNacaBJSf@{GqF0)IB!;8cFs+JwC_- zLT$+R>i^s5i;2q4&X1E4W>gtzlw2JF#nhoq6bYvq(r-U1;`&I6!-ySR3krtUC>$eS zT34FIXc`;CAP&GH$5{OtldgWHb<_Y}yRn0`5?;NBh*i&z=x^gx_S%5-hpa~{o@ln) zmt(aMpHQM4P)k2z#K4XezIV^(R*SHMRK*`z9U!YeR*ImT#*TaB9;EU23u8$=3TV37hQUKFQItZ~&}olb zTY@@pLNhT2#y|%&`BBWHi{=M+6D{s)MISqU1i0 zq-hkj&ID~Utm0o;TswoMCQBUaDtX0Pv8K(Wv4ySk!MQ?#NfttCQYsFqiXFq)W!C(` zH<-*~Zo2p(umoO%tQK3s1nRy!eVq^~tW$BWTw|XNb9JLLWjbWFBmOz^&0paw%Th;t zo{nOO=4d7cI{z5=-(FkmJ7F_GZALp1d<-}aKbDzSiFZ#50PZAUe>5}oc?8mZP;e6B zD)NY>OTmJvcoj(_myhKSMMBpsd;sV!`t2ct94N9>+gm835DCOCkay8>Fa~pMb#wHI zw^Zlg;cmpiJIh(%j1=KX%3Bb)kCi}i;kaMMT7gPHb<9sVc~2&@7SamgYTW|6Tr74K z|ARh?tqm1P)#?RaCl(SD9>>HSI5I>Cthp#Oi7Ey)3fqvw)+j~6+(x)@)bF5VaNH~` z=eSwQXd$T1d+-2{v6O9dcRh*W6}Za0MDrA5+;7IZY5jA49F$oI@tGfK{Gpfkx>R2!tr^oGf6m*PqXj1_3OjeD1y=CZDY{d2iOJFJ;+aXl%c_247awzRbQwik zhzf(4uj&#{!Q|u#xP3U5CU9AzK~{t{fmm5GkK`UCb{It{cfoPtwZasvP_fJjZN9>* zJc#f%brlIr+>rc>!#1{6<`)#28H|ytj?`yN6*hgyu&dY7_hc*4ZOGt+;>h*-DLvPA-INGelvg08RKz324 zkatkdb)6SqS*!Rekh8HPb7=ZcFS$m@SjCSGGUyEkPiH^`gZGGnKYFvKV?6!-()MJp zGi4NGZ#Xb%L>)pl=ZYCR(E!z+nMJR;%HHXOi=YpgswM4%-dRTkGZ$z1*{ei(r)XGk zWeSlMJu2oDI+&jAb_`n}uWIu${DOgcp*_KwMlTCEHJ$Q4J7U8BR~G(niZzQ>ccV## zYl`f9yzoUk`SR4%RFjMb!XRJ*Rv1Ua~g=ph}i&v*4rN2jr8=CL)W> zyrdrM*#|UcDZb7>B{6lOi(}nQJjASd1y3^>m6@A=zgMBXU~Y7SegJKr+yT zS!Vk(!Kb28F_+NW|Kme4+J0!cKstI-B1LMJP-PCuZti$6!vspvo8K*>E7#QXW=c+| zcH{(FtBDrEK}^zRLKN z3b%7|_WjTo__+#Fg;K3H<8pyxyF-=ogXhy38a1yttX<6g`^NMxQZotH47nM{(l z-t$<%RQ26hJ}s~bFhR_`Kj_4vz*J(TDcI)@a4Ymc#t72w68haiIQ&tXR{qx4Sl9rM#L7bED zVl0eRkqB|WWfnq{60?62h^r*Wo0wwfhipGmckSuNbYBiWy(q}&ft$$Y;+MTjikZE% zj;=jQ0vo7GoFMpvA_feMNcvRSo#_y`(xYsm++Ir##maXh(4<8-weRHpXFuM&P`S0q z&Z->{QZz8Y@zX|4qXN6X(8QER*f0wmKF_o$*2YgpDi9NTgu|uSZCO^UW0=E)k@ED} zlr`U|k_`ZDi=9|N!tI`0Q?>f5?3+?Zo}Qb$~`zgf6&xzP=WfGUf}yLX;^=v}t=6u$=~J9ZEk zTT@1m@3423!9S~2mHo<40z2bpdXG>@{QKRQdxT|)@geX7KfqT4W?j9my zmvh=QyA870g9rDFV?$tTHSuCtb#sal*^AqVs&I5{Dgx91j!3-pl30xft-U!Dx3Bx& zK9i}MJ^hT3fp1kOqbS)3xai#a@OuBS3lh~*tZO4FU?_JO9#MC0jMsSfP<60*K^;UhruYfVO@1vuF*4E99~$HRHzHAlC_g zwqtgEYIFCt@ew@AUGL8WPQ3Rq%Jv_g?NcHE-_Cam;>~i#zhQU)N`0&T!TnDDPHbd^ zMo!a56IRc9F##L!yNaWm^mKW{Ewdkf>562CihImUm=}i8?hV8b>ve2SbYye6fdBMJ zY~{t}=nV@Zh6xs|#RtqZ+1pZ#MK(k5o=z}|>{{ZC?OmtbGk}s;g%^VYc$4%j6IYkR zqTJfDMiI5GH09g7@GMCT6@II*X1RRFvnFZzm|sgYh-14lm3p7;LKJ5ZW7@vBMzcfR zpJoYW9U%s;FCvzJ!b{#sE;~{46)pki9elt-N4~1ouE0%;>qgNECQvCW4w~#?U-#KE z>R}bjMg|K_NlNRQmvm*Gnjp%`aml>mm4;fE)MML>_~NcOSgJQH`M$T|2f)w#UH5E_ znL?!=1NUM{PI=H5RA9YFMvi;$X&qO!$!&e( z;bQ0@JqqgV$<$|r&vBGd057T#i%7^^a?d)5kK69gB9AiL_H)QJISlrWDTZ3IzY24h z*?FsS>@Z6LT`xXF|-c7$c+SW{k&JDvd#Sp@-22F$tM+){Z4jj7Fh@v24(R|qBp(wlFfQoLH!v= zAr4bU^X{6HNVZ{1;bT|v$|hFGyFATRmmr2zJJo8$PiBxU#{M)umFipTT{- z+%ac(t7`WEB(Lz7cG(rH#gB3FRpN+<-?q!*QEi2z7N<2=IV#-oZ18#CVX+sJlz|}D zBgjr)ss->gIuptfnn2f4)8F(g0qxj8=iH&A0%jQ7(+TC_*CrP8OVPami24i14gk|Z z=(67_J~RD?l9IooK2hAHx%MHK#9E!XE|9_#_aG2rX7EMS8KdUV*S*h(Ibb3B>}>TD z#jBOtDBg_;5M@A#i>At>Zk>-9UwmW|7dKIL!>j28KNOFl%TIjPvm@M97QlkL&X~4I zfOGId++!*yU+RuIQXsWZUzomed!VV*=RtbF4)8fu7FUcBNu4IV9Tax_P!d}lFe=4) z!=~`JzTfFikFNjVlp(>5Ase<4__pxhoelQY>CNYyZ$Z4PHq~A-ZE#MbCJ|~S`Jsw2 zLAXf?A8rq-WA}yBz6t8oNuRsd4a85SL3+Q2Tdv`lT=q#8|l+zE@%!Rku|z1^1!Ukez2Nr5fxIhh$!S+rmCM zG%*y1MzTKi8=o;AHa`;N`iGUdmItLWnrHO~cb z@9o+bW>Tj9p^3Zemwh77ri2&a^1|2kt5&-2BpB+OF}iM~%|E@L%u6UM3?M&`?}K-< zW#*(WHS!FGgIU0aOZ_3Bk=bl}G*~4ODs)6()KKF7)5UE>i`#L}Qtv>}TwYdC;j_-= zv4GgetwPvM#?V*j@B53&hLG!n(djHMApQ6ZjQ=sFzka;7`P>hTIVuqYM0Mvg|Je3!M>L!#}dz zQWH+$W19lE_mXY==r{^U>$qet6{i74?p|}Yxr$QZ9$U&K{b(@wH7-;AK3iyfv`bRH zbx!aR3Ch$uT1{D6s8_gHVvkGul6hSo7381Prel#(LPQgM_V>~4I!cjC*6l2Lmk}Bb zvmk;F=1m|Qq&9wI2*Wce@=w#AJ#gM3g||+? zli&P$S&W(EH)Wy$du`DL&E!u##lk?8B4U=}H0g3N>t2IFUf4(NdYY0#IlwWXSlz@b z$xo>pS}fJOnF#S$63$$FpfTfzCZ{rx?W%wy44%? zs1;R!v#j37-RW=$o>*p=*Qrpr;t9vOp|b33)ByJ`oaLY=-X?c73?a_-kJNWU2w-dS z-x1)ffa?5So-wU5qX1TuMV1WoEo*74oG*a1Bzequv#$KQPtL_l*L1KnlW`MO3y^6Y z*FH}EK)yyoQ3n~{x$k1{Qg5Qhmtbnob9_r+`CIHp)@7>&UtxrPG%=OxYWhhBRxapc zU3po%4f>}rT6b9d@MbtG!7S}52pt)nboXJzsDwK_P*|5tYJZ+BYgNe9=vM6{LX(17 z?4X&_l#RjsmZja2y!1Wu^qp{v5Qtdrhl8|_yqpQm=RugC*~NTltHU@8(fzIq(YAnp z)f#@X&hG~|tcMMxfR56u%aJ?Av;*M&1M0d8N|1Gds_eEweUhiSAD&$%^c20RN_MqQ z#QHyr88?GxpRK+=hgD;6u?Lxj`U@%kiq*Pe>$f!GdUKvGD=nD!>J#1G6cSkYQabDh z9i|1Xme^RrsK8xuc*=_~WBVZ|heHS=Yu=t6Yx;dr(CSQR5Y-*06J*rpmwpKMkBIXP zO%Vr~23Osd{%P#dH3Xq|?~f3r0|q+T-;NU!vqJkBEoVE~ zCJS_x?ZPVCnG6$N`VBoFiw$8}7k_Jt?W3{>;7&y_%w*(#%mbML4sJ(5UCY@dU42&o z?xJdy1#J3a?Ne|qM}GIh#Bm8#I5w1dTHkY&y5%^E{uE4lOk2j8{Jc{9;Q|p@R46(_ zM_AoGEwB+y{xFWQN)ZUbCj;)>AMRFuz+jhxXiw|kXYmWYD=5I}pkCB9gbz@!MjeJQ z6@Z^yY~ORPh6WF-3%%}}jpyvr5;+lpCJ1Dg^O$CX(MnQ^P}>zh3?J5S1@VuEB^KO8 z%>6*!|GP>y)I~SkiW?27!aVq0!Y+ImCO)x#c=7Zwu-{7*H`;pbxnue-KLU{Kwxg1d zDyBd_<7nf#sIvYTBxCjC5B?`=zARP!)%t#WNV7`NoK|F=VPY6ADUr?;2T)&+@Fw4a z09P8mS;zEZB43it_X4Ev^s1pwfan9`49}th@+v&P{wk->E`n|0F(XZ2#D?)}`-tGc zB>ruEL=dkIgaD~k;M{yvh+q-;0$b<6yQ??|1I`0L85sK&iXoNEfl2*k+iR4)2?n%) zy!5DlKqu%}K_V5z6yL~zk6v3oB=)k*A7;0Xt(yZd5k)NCmXd%1x)75_(#XblUG3Fj#bt9 z9o2%YfZK?+ODV3Rz}#NJ9q8L#uD|@2Z?&W?_`C5yPjCBKCB}`&5s8u4w{W?en{FcQ zV20>CjEx8Px4b38d#3F#NT=?h>f)NC1Hoys3t)tY$rEz<-Pry&-eD|ZiX6F9>twZj z$@g|JGo6>St_@n};O#1!bZ=E-AJg}Iywu2(KM!x>ndV9_wtvkIf4`>%g^_|L`bUXN z#tzqUjr4qz{$zLNg0O3oDWt#M_s9?MTZ`i%?-0L^jl_nkMD_XonBP-OwW;(&7;;AS zf0{>06{Yd?OF0TSCAfI>#I;Zcm#h?DU#0j-E>>R~B`+#ev9dQX%{s9n>GxS4aAb+2 zNty10ex?k;qWmP(Az=LLH}V6*oFQM!got9ii{Lc#ldYoh+oLh{^5OBmMOqieTOzn0v{coll2bW~f^l`+9_XRUBXN!OpoJnfFIJ(FLZqk*>7x;v1gxSSUYV7_ybLdb^oo@jIFLz@=bM)55X2=jjo%*VTjss&B5ILzxw zz)a0?CBoNy3A=?EfbPW3b$t)9wQ|Bg<(rBfTp?yMMqvj%SI`iE7ja%}nj67qMrxdz@%f zsze-s13l@WNqr@Gqs#^sQe&n)+QCX;*6nbE4p!u5TOIjD!MImb)h|z;h^+Fr-zJU( zAXB&q$TB~5t=z#8 z;)w6Z(}doq*_EFhEyCe%>q4ReQV&ibK$}S>R^fa!ATYcWgAcQj`yw;RzL|n|RuKw$ z0wY7ahql<8vZTX-;`-NnJ)@Xl;IZfj`v)&Sq)k(sg=_vQznt3|b0S4TQE)U@8YTL( zpl$nc-(^W*)MI}SguD!c zx8;CG@K<=f_{w{+{VF)7{{mg`=uJMSO(a7D=w@6H^= zj7)Y)FMfMqOOS%o7&`bX9L-hqvPOMzEsx;8P)46dSy3|6K{<70D;kO0hDV6V^#FcH ze!^JbX&WhQtX!9ZcLt6u&W-UYI_w}Ynct-%+?KPT!-Lzk5A~f#PGO4^_cLOokeX)R z$#hxew7jauTK4!+u2iVg-IpZOrh|@O6qm@?U!y3;jNRavLa{($+I3_^ON{%|DLo=L zqQU=L?gHGhB8NQfza?PAZ29gb-cHutdrzGJigf&AnK@B4H}o91DmrZV5MgnNNImCl0x3y~s5@Dcx;r4s&#V zfAzRz`HOM&(R3i#yyKo_g_5|5(vQC2dOX z{1wF^(%9Yi)k`MO4crRaNO~TfsD%c%%>a1UaAM;83H8j1{j2WeIG8i zI)I+CtHv@B*aRb3yprp4Gp;WPL;=))wfRB8Yu|U^IX!Epb>03Fkm3(WJYG^ulTNb~ zOTIm}_>;%UX2rsN4x7(gqol{}LmlNkuK(-gO-F>+m~6J%Yua?0onIW$Ir5Z-2L8Za z$t=}i!f)j?bLUORM##2cFmt3;6rdL5`S;#6J%y3}ujjw)T7bwY{R_(p!v_wssOwwJR9= z*l>K+Q)MO~7Y?f~;Js-d{Ri9iE>dYqqwc#tx%;ok-VgV^Lr8-njuKK5-?OE*9e|IV zps8K}lI6p7M7)60H^J;BrnuK zVV575kj=3Tu5DOT?pEb93-DkXwPu&Jky+w6&Dd^>WXcervTve{cI1)wLkkuklKS0j zXXom)(-Q}}99e>}2)<*&Es-8fqbN|LpuEnQivaSH4t)9g5%B-9nnx+d_P0!rmuEcz z^0~yJxHSJK5HuRVHPXLOTS5Tx4wocECEfvj5&bs5(n2HL{0J9_iRqvcBg8s4FK`2# zd89PrZ%!$SRuW*sM~jmk_w5!TwX?q1f%!ZwYI{p!%22jQ&dP@t`iUPLeg?rY+@#W* zy(ynvlS@nrInP#S;a1prkWoNt;oOcS{gnW$>$t9(`jVE{88h{`#WHt~O_z*f6vd2< zW~g^82O03Jd1c{zUgP#>(u9kF1vpy@;9_Fh&P*GCU6P-Ze(pTZ>GA$HFZ#Bt&imtRfR zc;8ByS;7aerC=Gi8P(#&aR~>cGyxr%v4m6>03TCaEoHhFAzT$+1*2N1E%3FkSUHW1 z&~XBnlI$5mlf-ygCScnoq|GhO}x?QC_G=pWTldTK$Y4; z0A-wOGK*$RoiRI%d=WF{7K--)Rq+9faML`kKAz0D-ZP6}McE5V60e9$EwK zp}&#n^t4fp7^ErCFk}Y;8#M1(iU=hup}mbL&Q*Q60dU?1e4YLEiR69hlsv$0>&=<0IE)mz`_)P;c+j@_{TTH%B~Aw1DmoMbJ*WG1JxMFyzaq|h zRXYK@4_tDez_g$MIEb+vBfon;bTuJ+&n!gx{m_C*UI-usVeek8ZVi&zlrqtXs}v&% zxBt1ffsl=vnUav3iXHK7$O;|<;!D_q7?cwqMG*(6p6^M5+0*oE+0$)m8*^7{i|$!d zW)6@&ho)*qVeUA9D0Q3_=IkL*N}n-nW-i`2WyI8sn@Vu(ZJ*s;0p7)Xemrp$<){_G z#5}`m3Zh*v@0k%epll#q5JCCn8HG8F>R5K7fu7TUQayu{)4xYt(wrw!Tu2FKTv$V| z&}3o{phO)#`9WVLLIMlKU{|aToRfL(Fz^ahM+g-OpcSbA(aU{c)vgAH_jJ*V74CQz z1_324L}wjAxE~=5VpXM1yuoGMBYh_#M^ax3Iu3)4EBo1-p}-}Z>VA!om5^!QL#7G@ z&KC5#huL6a+4&ClJk z+A2AECp#A=yyAV%x83db&n&B!;a{TOt@qExW>>b6v~K)yy7ZZ!QZtj*Uc>)HC%-g_ zj7S$2{3t4xH*@~yG~r@3bCH81iIxrYv%gQn@&jnF23e}C!qFREazzL;Q_-)hnVL2kfxG@ek}9hdMBlvR zm0pY3xX&-aw-=##^cPBP^yB2-Tmmg=%$!G}JS5(RwZ)c!u30V<=8Ks1%jU?K3f1-Z z4o^2Htc;f{J#{?_c{bOs++EK6p#6mTh~vzk9P&>i)HH}@94k)J3EB3Kd(q2PfP*+G z#duzWe7ZQ9zvEt`+pYGs2Dao| zmAM&v8dkGlyJpGj3DFAmrgvQT-~F2d1dXXjd}F!Z1E+cMuio=nC!X;z@8oVceNZoj zi<%E%uSjC7R6~-P&{ED6e9i~S8q9VHyM)GI2PWXfc8azC zBfQ>h)%o?=WwSBHu-@i4`!DEBCuxuA#HkvphHol%%uG#X^px%$q%kG`VxpRdeGcaa zBNeny|K1wMI@w{Ed6&f<&QPv}suo9;a}0FnpUy@2h~nvZm`ZRg+#qY-;wUY4fS2Kl zVJh>NHf>zMjCCdK#92Yyo^KY+Pn4jDQZnakB#Y_Vt!a&XotQ9iSTnq|#gLhDq1abQ zcOBT!p0nuyHIGdBXcD{&xlA-|B_2M+Gmb%&s=mwt%O|2fwME!6b~$R%nX#bc<@Y9W zN87gM)Y36c_;6)b6|*lJV8rW`%^V4$zAhAr1EPi-epRZ=C^Xz-^@vbYR^3E5x#Mh; zm{?Zqux7qxUR}i3W+h^nxg(`FPD_^4@H(Rw22av`>Cb)e@45{tx@$UvSeLZF_Qh1h z!mb_=A0rGB#6e=q6g2%gif z#Dd_2ZSKV*S>hZ_L!B2yo_>laf!`-?C>&6MWG9jtes{fXa(DJ&QSd_e-wthg8PVEJ zn;gTdS|;t)Vm5;M2AfFwNa8BRHsa!~4&wesAvRO+KzxBkkxglN zDw_VqJ9e3SGVz9wPAK@k?aS~S$)v@92fMPHfi4ZdEiM7ZZDj|7yFd8|6_qta)N*H+ z(brGrfMU-JSMN+JB*H<~A(!a(DKF$UFrKsaTR2CHfmDkyU)$uVPKA_Ce(hz$B};kf z{iq;flnc3UW)ahsO8Qftc3KUQQa9RYC#E&yNKeZC%j`%ubjq+xEVOoWx)?Qx= z&lgQAD7!P}D0`ptHfBk9z%q^#H@eTL7x}6+Ue}|MQ)-e-K&fx2Ry?7Ij{2pG=@ zX^1#Hno&sUh}c;z(a*yNd5ph()SdFm?Bv|YjWHcSHw`=G<)79a{Ryih$s?v1QZ9vX zZQ8Grd*bhTBAD6fa_-e(#~s3ZKsqH zacnB>jMmKa4CuR@3#cB7w9S&IhC&_*o-SnmtpdU2U0!1N+p82S%57DczqvQBH(d^8n5=<<$IbFitfSp8ehQ9-KTjKCWY>^*Yj7H}OH(v|YCiA# z(!x`+V!!bmmtog7j*Nu>I!q9|hIKc#(K;6PLLalwa-z2b14H*E( zK*uKF=l7~ns-0ZdZ=Yc&6qDB`H$EpJPt%&rD7>juFy6o_<=c%&Su)@y5X3__?SFh; zfhw)9(8u#5um}-RNwi!uPhAgGW1D6ayj6BgA;I8JnZ8}{(f@$z5grL1;)bz_tu?dF)Rg6)prFFR8jje9Gxg=~vbQFKJgC`tp^$BE2;E)2B24)Nivf z>`#N@s2=0pb#EJs=kwcIef~qw=g`VF<$AIt1t63&QXnBBLVNOAmzAd>Iaf>ptG^0% zHOfFMc6c8^Q*L*pNNKY*+ZFoMgd0j_UkNd>J2DzEiG9`)VJ9{IPIReWJ$zB2$0Un@lkK`lEzzr&2h~K# zbe~5YQbv#a$HcM?%oH&9q7t0>$oJX5M>=J>=xHFJ^b<48?=qxc30-el#q_6&)dblK zeXqX;wx>7xarbs1m_l9LZ>n1z&e@l8`7MuvW*J}UYA zlt>qwOX?ZZ?{k1q^NAxSVx&hTCKkW5q~_Z%7lh0g$={j1@%e{;iJf-+Yd=t&vAkSY z|NTPq^;R`Hugxm%V4%|*);~^!WMcJcRK|k$sXQWR8N^&T{u;E6Z3ARx^DH=(M%DXA z?oxoWKxB}8!~~Ptj8oZ($gR_~3ApSf2>27(fVO#_?j~2V3_ibfE=(&ZVjwoRTc;+- zV|vYUaU% zX;hkxJ(bV}MCNgQ#j)qM+gIiJ6-2yTQy2I9sCe%N`y$CW>@oaAgrhDr0&Vxmq`Y94MmQi;u~b}=WSxJXZz(J_hx1Y5%JAG20eeUiXTfCH zfqN@rFHnBmgu|rt`ZSvzFsWl&C(=+}{~1jiBs%c7d2@m(+e)T(U_Z&$WmwuJ?Xqme z()ufrhDNwd9ZQj;ae^f5yh2GwvYk(4V~I|oVLIqJRKZr>S}r&MFYRYC(MVJ!<;y`LKX*y3zjj`9gc07DV3w(>E*|#caelS?K0!f;&6xX%0XS&(hq~zgMESTyMi0Uolzmbd2P!OF8t0i=76l#3isp5}K_0Xjn z6P4C9`RO*yl1O%BF^G?(lO<OUIVCBUvc{RXw0TD>Y^uJeX4Okjru! z`Oh&*jy3_-CTFEjc@RTRBU8k=o2sxtjT<(KJRZ)+#_p zNbLWx^aLQQEw4J)SIj4*oyK58sOg0kFu$v%fxT?8|H?){(Rg)S~!Av=Y}5kq8@H%&{7hn z?;^S^u2tiB37TkM8Q{;3@Ee^BQMaiY;6306j>&Hhpc_?$?e{kc2+e6Dj6{uHk4Oct zSRtqJ-x&q&bBJ?KVrMixAVoiRsyfXNN} z?(0tO^Uu%EK*J^gMu8WorsihKz3Kbw26XrkvHs^V3 z)=Ej)p%9#kfUN!MR}(HnR-=vU1)H8b@#%%lL*sW=l@3lq2YE7ZE3EdNobv>@=Zveg)FvPWnu zegsXO6p*8MYPt5moiA*~8vd-#F31H0JDd#dT&r zf`UNCN)qFz+{3%l1ZsK5la+@3-=Twh6hDy=)2{46LKdxJ4!4bH*MZ4j1|2Msh-to{ z@*LL?PP@pBG5^4xZvVP0FrW{p(W-O>p127VQt3s5!5}4pgFEYLDq>oD+d^6-f)9dc z5sFetL4DMsyf_?7Xbh}iB2=ITeP;BhsD+COhKL@Gl=@BQv~ep0RI71iZ5$(yCvoTK z5-jOGs};0vWW}Z6aPGLHmfgoWl@`kf z2?eNgx&;^5U-jJHdtxb}e0|SR_JW&T$mJ7Ijr`C?5O!dR;q)h|g~|1s6~Ue-KPwGv z&hT1&N+sh!bge2KJiJ)(u^-iGU{42XIPSLjZX(rj^3dfy9sBy&5TN)KcAeC}v?Ovg zWU#RW=j~OcxQt@riP?yc2oD&krBq1un*&Oq4R(H>gswXO(Jz|rER|gt^5O@Y8+;18 zoaHlzB21Fe{%Q%jsqn1L!*5^N0LKYthK85t5aYa!_k^Y>Wi*;BoGG=*fYF3oP76@6 zK}XV#IXAh*4G!2K|F-Gpt@-WMDI}2iW}q)lG&%1LRL@JEo8ZH^ui&$hoT`XswQ9pi z=Yn@pZa}PnF}Ix~iQahO0sVvyI8I@Rd#K-kFIGTr#SYzrUy?=;w$Uq$uM9fKEkNYh zLZT+BCvD#G0pk)OB|1qu6~+T|iIQb4k-t+P*R6x+npMy9kI7}r*ceCxDHst3i^9vO zWOhIPv7nfcS49~H*^YA)F2wfRypw7n5Dh+c3a42@D`)m=rRilZu_ z$_5`BzD$gIsT1R6VF|~+D1;L(q1oMdB@*7$B3zV;l01YPRekH?_!4dg_C>34n6OEh zZ#Zsgzv*51*SZ+$3ZfSw{5R-9fTz2L{fJ)NIeis`)f*Nt6-W3!>g>D4=>#NDVfVwH zF&hIV{8~w~s8rE&2wI;PPCrsVQrNjEJ#BLCpx`V&JSeiRo-*fC`v|N%h9k@u7{nFp zxu9T*&OJ|d7>HeIyOF+v=V}d?nuQ>ysBF;};aVtwc@$(??rO40Bp5CsZA#`Nee!}tTH_p*)wNx;45AS1~k~WT+x02F)x%K2gdz~n?kMT^o&CH#CGoy$a0yZ;|O*EcE zr*7yRUNqbWlJA5(1p@%89S1Kr4?A!mG?WhV5I_=_ToiBjLAc2adEcdV9vuzaZlmtnZhoQ z5eZI&@J3vEl8`@+%_4`&LdW~5sh3*X0VA*=TJUn2>S4UtAVOAMc2FF*xDng(mbW0+ zISq?-Y~N;d|A&!>UugZFlS}c17M#D%*dSyIZP~{v(+T>$`{~}^x#R_`3PMG}pXR^b zOt4PhbtDsB)W~Ie8>paGmG$8@=GJ(5NmRpS?y`gP?#T&^IhY(ce5l_Fn5b+%fzVz} z9Ky3^>K{tJ$fnybI>!kfC>FSkrWpyg)hH`fw6Jf)9j-5lr0wNJz15%eC8QmDG$!WR zbR&2V0-G^yEuGfK2!}ul|IOy1TR(f|#){NAKNVpH z~d4f{9!AssvKg2O(2 zSj5=IxOa>QKfv;u_EP<#;u`o;tWQaa8R{PVVTj5iua4?*_tCs9l5j58J>xVTIn`Z( z2AQ!uIH#Zh^UG!@%=UsUCK{IBpxCvfF2psbz(Ngy#8sqRnhTlkmzM^6+6@;fo;74V8O()k zm~q56p5A8UA)!kB#=c|x6;wa5hAQlEJ3Y!Z4Enc{1fiv7orpE;1(yjG>NmTQde8h& zBpR>BB;Ch{p}#z6itXEuOWf+)R_X;qD;7I2oFKU|e~ssipr(Bv-$nRsFmI}&pB0TO z_5BpW7WC(#s3pW>K%!<-Rd)WJ;E!>lTX!LWWqLDaIp)%Y9T#?4ij{>m!vZwn-pdJ29pwo2?n+-mm5C9 zdB4kJ<^dCIHhl#`V1}Ynx9;gKDbeI(#x#TKxBMf8B;tx~nfu8|U>3625$GMpc#EU# zuHeU%=Rs`GjcEQ8GQj#UL-UMVY(;C62=-P(e-Ek($5~og+UK8u6}v22@0-UNQ!<#^ zsf*e)+9<^z}B(X9XvEeMZ*%?<7+y7o= zA?7B-<@!4Wp;tR6I591&x!(<3LZH!QtIxTQV|M zi@E$D?aZB~KDdadNB0-XUCaYI*e>v~gWPwr>E@ibThXL~O9k&dXFng469T_h!)-?; z<=P5AQGca*HYOOn#CZBfuGQkd0tp90Q~xJ^KNc&MD@D0lSAP z^F*ofmHV{q{CPtr&_nD`*MNPRy^1q_T9!w*@szx3PxWQ)ALElu#l&#b10?lG0bxOw z`#a>87WkJ`Fa4Ln!}Y&Dw9Weyb1m(jDTir^I6N~(p_{S-p zObYGkE3G(do9msZp^?#jUNHjTT)R&z{`O17QPCZAot)qcP&6nB{6$zZ(wrN2*72yG zo7VORm_DtCuIGLS%`ipm%NAt8^P1bynB*(B;NGvinYd_igfa%WtkU-qir|9G+f}1S z=OQ?uGbU0@6FszjvEzM6c~KjG1D_roTvc$4ggZK{_H#5#vi`s%_gL8xpWCf-wBOJo zEGvDZHGrvbM;uG^=IM|+s2YV(SbT`1?ko=(j3&@?FYg7&(Ux3$L@t&QcbUrw${QAwNRa!BOZ+-8 zs_29aarmg$8IAy);jQ99w((I;G>(njrZ7hzeYyF!a5xA!O$|@~jr5LY& zMM8B=1yDP@Wj}t>MEC(~@ok&R_=kdq#HaLH;TW_DpOP2-;zkk`+u0pOp_qPGa3X_U z&JMEF%RW6vl*kj3`f%O)F)b2MM`!kU4Fo zpn%Uc9M-PPY|r%k|B97$uaoU~H+Zj~XBN#5(aR_Gf7dX2KLewlbW;FVFEAOTPcHD& zC)@h_s_<@UL%)|e-|3RYgvm>Cm5}1;b+!R>=pD}|f~JB#m*ZW2%0Q8!&U@x)B!rJyZsLxtKRQL)kAN_%(2`Z`LR*{;q2tU z?>WhDH7CR90R}!cQpEQ7PxYREwdR5bE^b_YGho&5Mo;QIx!=&-#d00kPk6OLJ+>o= z;-(!8c&uJR#pblyKKQAi{$b%ekuD7~Rw31}`_1FW*zKzpu87a_qM)Ea*gzrg;Q8wA z-&maAZW0^eb(2VT=~Q~_cfO<%wRp5R9aIX=vT@BWzqLmqpoTENmJs;c>H>-+^v z#CxwM-Q{exknSD*fHrWsisgT3r@L%jZ9W00_I8xgm$X7A$!QWchdRH>&}flYu8T31 zMKhNIW3sZgtg_p3nMPt^XXWX?mnufePf3*>tAkQ+>-zkZV=&8tfYtJVVXZ^0Uw;n_ zqhX-pJpyo6KH(oA(+azM(7Z(oI~_XRB77XYtKl9KiPlV>rPdYON(i~w0GUn3Se`xRv; z8Zt;}X9OVOcDZi^^(jqWIDiZ78{ti0t!gCl$&+@L0vB-*(VYvbA1wDC_8{h6%@FMf z)6O=V7L8FtG3Zd=>v&5(MAMRL9Uf%*kv4JBW_IdxvodQMCOKX z?ven?g#qfaRbHjPr|}oz&Va%G;{V_oPkO-ZOFVVV%|SN5h8DcLfFiTXdISEETk2c| zqhmqL8p{a8$b+rsL{~rHhr2uBIFSrad~kvm0MzD5^wI}D{<~n=1$6HT#stdEiM7bP zuA`-b27b1>vkI)>7^y@h16AWNE{D3jHqT;|ap(7j%q=#PV_VPUsb{m2Oo2G7a12Xr zJZ2pELYRI&t$A%xnDdQERlGu z0J!C%;j8Cd+K`3hy8{v?+NNGxtJH=JKUlHwH_60IMhmVRQ6PTuZxEl@Te75bE#4dA8?WW5S52Ii(#{)XpI@aG_0E)F6gk0yxUEWp^7DZGd1=>RM_ zM2(mS0vAlrW&JG#a3jO0wp*__I1S1Tom^GJDdbcg2#@R9&_X+;$uGFmD13NUR zFAz|?p=YGf1gL^qrF)WO5E=zp+vG^-@l#~H9});|kNCtXXD-t^Cc%vJNO(I;x6q2} zNxIk<{jI+%_a9c+%$y>jqzop9aLXuDfvaNQ1@c-rS&A2-FAS)$2(>~)-FDn2PMots zNMw*Vjw2aK^FGR~Xn^ObbD??YJsoe;CmP=oxjyq=?&s6wP{oE zbc;{=tByyrLUg^A=Cck+6p{M!k)=Y)spqgRl={uF@8Ieu33g`Fr|eP~FRe?wECYTN z_{=bXY~tQ?R(?zM|KaU&_db%ek1G|Z9|^}l4bnLYzI^8fX8?vBpeuE-EVfT#N^e3s zk;h+}8{zenXr2M{6n@HBY)OxS$4K?QvcyreWK?M8q9FPxSxIzRV)|M$^asE@ei62# z|JyHjQge$h8ZrThitE=wABDy{YFYZhz>SjUATMA(4sPxD=5pQk^EZiC58+fExA^HlHJ8VQ8!4FCTHUSu6FZ$flvBNnn zuaft&bPgBQehO*l{~z>Dz6*RPDl^1sv9Y&DOhR09`a#e~NwLWhtW@ei9@sbIwtscy z{%f$sq<(dA5r@S4l?z9TRqTFUb$EsA07;pGj*Q)VJz>)vM?p&WDj$Uf+c6ufEG58= z>qC}#*{zBP0X1XqWAfN41*T(dvACaj2PQU2*`0s>W^TrrgtDVTfQKzWVGu zw_7RZ1H*UvXB#tw^}{AOy)ao6EKSE-rVs0?eZ|`6m3dUwr$&XO~z!~HQDB5TN9_6Y+I9E zlWX$Cx%>CO>)!pMH({;4&TfC7=R<7KFv^<-v%MJbKe}yZ!@Sb4*AfhD&65J*@0jHguT~0 zLlsdSkJR}*_1)hQ;ItmXi=bJpR&(uhIqgQkCx&hl&UqW+jCb3c=HAhwzSUI62Z0dw z@AcM_q2MHA4{5&vi(KEVu!k%gz{Loel$|BeY3h5c)HLI)|T#Gxqm z5&rGzJE87F3jBzTEVvMw%aRw$GuSK&Ie#rmQo?`q3pg|4Wnf7rz3v;CcUz}cOyF*l z#ZlTYo9{Kbo<~gt5|(Dc(Mrs{Yc#^M!)V@=Q)d~dNLWgk7X+|2`7ZD^J*@X+46#`e zQNAl15PEE{pn4ORZw=uR~Imdk~L_}mO*>d1vKCUOQr)lOoD>X!lv89i2A zLl*|xr7ZP1@N0!AeeCAb0mI8dXea|ksdRZ4c))pvD?!An_6Gwxv0j@6b6&w@OmZ>5>wbs#>r>T!{jrV79DP>C_$ z#be0bo)FDL1UFXr59}8l*X@b)VelbV?7uQTPcF@)pWRz6=#io%wo?soPQj&7;^=uq zK7%{&>!{FP&siY;F;DUkNytAJU)m2P^=;kZ#=?Zjta*02;5sk*c{$Gyb894kJs0o> zWnP%288eMlC*tqJdrkg(MPiDo_^Li>qolQ8BHm#Dw4e~N@=Mndo+knmSpMyy$A#o2 z_MB%nm(qt^W6?mErUcw+d9DN_g#XH%F2=8zC9*-dmjoc6II}Jh0gu%>^0R-&9+op`Q*=9jNboRJ zT)5F2g%4Q$mDv0@PPiz@nT6e!t@arbPzr;EPCiNhvtRJ6YKsTZSAu9JAF5a~rQ&n-EDm@6*QsO$IO0ly+ zs)B$*SIn`tCdzrU-DBZ>Nw{$iO2V(9hhMV4jOXasyR=nXI^LE^_{11fKtG3 zX&QUHf>^B)Q{a6|UjCr-93MhXe(w?56I%E8oEyaDo@SNdq}UQq1xRL$S!fls0_{}A zx^~x$mNsICRO&_;iCsv3h-M6#b6|@&%gcGh8kPq`j>TdtIR2q|&!fTZ#!cCwUEnx+0l-Rt@%tEB zho^;=vxkC(i^kZtKng0A{-pbet)>zN_h116xDh?59 z&Sbqw`_m{m_$BSV6-$)`_2;C1Fv(hM&WD>Ew#=852ZZvK>57Vqz^X41XU}wevo$q6 zl)K$O?p5k@QfuE7-dAc0ifT{27JJJaj*X4|)#|O0I$9*x-o$B;PQDX(ba^zd9>)dMMcfa9_O@;1WqRI34^*sZ z-*-iREH5PuxDDYTo%PWu(^zgbNCxmp`4bIXx9miT9K7kC){q7U_<>>}rd!~?hm|o`k{cP*k?{nH8^DD7Wf@?Or1EY-3w+wohbYm^K%`Y+YvHj!| z3eXlDXXhiGWhv~`G+euzoIhCdAEUqvo^)3Btr$nz2#j3JW9YYYrZ`O&^M$g6bbd%b zNHds>DAwXrJ!_fSrofA1iI5f|b2=(w;`a&36geB?v7P=;a7ArOJ=%XMrP+G!Cr<`yTy!9Vk*E z+U20CStJKpn`T~h|MYkYm;6+-Jk}P|$?$=)JajwIoFVg~8y2E)mEf{vzd{O9gjS4JKMcnHE`gnLs5&E6qp1n4+ES1)Wpau*e zCH^bC)?Dox0-}h(QNYAIYac$IFvyot^?Q%4+qj53=RB9?TiViP5YOjp1sA#X@ zAbHAnMI%izhZs@ERzbJ$F!wUe^md&w7qef~iO$IKse_=kNLeC|Nd7EvIcfe)ZCukV z+FHyONLj3oi_T$G3E6D^Y$x;06OdQxiI#Yq`z4zhD~i1l!G_{ zrf#NlIy28Y@l|?^RKbash4l{ZIg=s!N6ss%-v_X;vO`jP%!clycguHpO1eD%v>&iX^f=}2Di3l&HjYQT@68nQd3{<~n0xfFZ+eFV34;oN-E=%m$2g?%*`TMuD;4uo%<8uqEPrG~`@%~0&nfdDGt%{I6f#u0p6 zSe}(_!u#nfvj0k{3>9dt>AA4*8_(5GV+NOTliFrw%5q*K5Ui|>g)pP&%D4=whM*6@ zd8{SGs>#?2BE)?s_o8C^@7kg{g&##`fOw6leA_dP%c`b#auL)av8cKKxgcC&h%lYV zF{T*#)(h~V$24=W^Q;jA!LfJ>#m%{GlC|ZX`W@;WOLL9-n8nxlJY@pYbQ~f4=BMH6 z@w&Ido_6e@#^L3p!bxDr&d%*epN!O@XsZ-@x8g zF}T#$fAa60;paM48E2Z_ufZsFy)3yCYw1KaPTAWTzahMl{1=mcE5A9$B^fgfaa^^L z9y3P#fn$sdqBvPqeNfwBuPpM!`yP^V`MZ`(x64!7zSv&PMRP`%C)O=7 zq#Nr-_!i915Pe1CIq<&&p63jIq~bJskECWadJhl7WVoeAss9*L zc^i5VDmmND=Y_!zmO81a!zbHl?bMop&ZwbdIA3{GD@8DTx`!+w!A+S5o0Cu+n+IO3 znvPHE2=1TSo=z|Ao)nfxoZgFB?@zm5mHx}ZD38~Ct4uv` zxlkk~y7>5gr3mKG=+S~5cE~Rum~%qTuailzwwBSScZSJliKS>s(|?{dY}+qwMBj#r zPjj%4kNL#j0r?GYGVa>)K&S|i1o!69%o1p0<8}KWZm=(hM{{fjM8%z4N?I4;=v-Y8+BFlS($UNPf z6vQt|003vV?;UnjLQ@*zCEg?5;9vcnPVI)}e9|XKE8wQAKnGEXwozV9<)mz#&~b&I zC$-tnpO2TNntyES`_d#_{En|o_KzVX&kdVdO|q4%Pi~Ii+@x&)(6!M&BOUkhay}^u z;R_H!?rT)YKaJvp%xEWbKR3AS08$h(^HKOF%%y1Vg~_syb%0?oJ3NPeB-=oNOxa@Wp_A8`n0G?;-uszhB*^ zpFlkCxdZSeDE62YWRqGs1hfE9-*u}ePf25H5E`fY3m_VVR)~W1IFZ~-VlKY^PaE-o z$EUM32aQ&^cMl`_7wz_W;g;gP`u}MGfLgQ9{-fSMqJWX4RV@i)#k&jwKF1Tko&Ae58}HpUL)Z$G@cd6KhDbfC4e zObAbICx+mOGS7HQ*8bfJz9H{30@B>Xxpf?m%EaT*d>svlw3>) zd)X@<5yOZ@Rpmp{Psv#Ip}Sm5{rhro;LBNswZCwwO@yy@~w^uZcB_c3nf>1u<>h9aXF8zxkbdr$A4 z=DTRWZr<^_HhtW_`~$rwBC+H06Q}n+Cz5%0E}V$J<(zaa@dGb=&EJw5U&CivRMT2u zZ_0+J)Mh6Y)p>7gdRvunCbgsSA4WKZIZw%+<&v1A6%i`;fZOR3FORej5A|gboC?uh zxvL0ZWD9WCqnUm!^2k<}#>ei>?yoodBXFfsljI;SM6-&5AL&QL*gz`M32PpyNPNxz z)JYQ3`j3&|xmKbdABYG7I6m)wy2Yur_|V_^Hvdk3HTM=9oKIc}v?atP1PrI;8PlQ; zap&9G_ED!@uD4gq?ar`Zoj#|e_fwZC^qw+jT=id|zBB><!6-#*c74BS5+*$Qfyx)1AnnS(S*QRdYvy{u~--%((X zc?BH0QAsW2ZRwt=2cWdN^m@!vGGAC)=qs?QpCWF4SA27x>{~FyBtWz9k|j_GBHw;J z^^=~_@x_KNM9C7gnisz|lWZaq+F2l2Mu7|}`Q6@l)X)WBLwpRtnb=I}9c@J@GshF> zJ;4^n|0TaQw;t#Dn`uaqeW)|x79thDazU9ji(VOXzH1ycc>+G4&j1N;MXnYvmcG1= zhiPi8Rj%oNmla?dy)cxVJu{gX>DKAk9g_GhI%UmTE;5>;>$9C7f->%gQA)j6WV038 zV{y1o>EN{AO$5o+F-bKJWyG=k6rbDn{2;#L6h(#AHLbeC1ptzbgF%Pdh&NwNp*(TD zZp~V=y_Q8Uzn}%!bW!a2+Bp+N<$$RN_?#J5?zTNCtr+`DY>HnJ3lH|qUq%eCXld`; znMOIi_MFm9;Bb)T_w7Y9mAFmg#QNhZ!qxPoRfE%v*<~hm&)+8RAH5n^4*?V&;jEW+ zf8Eckb+Gvt%Fp?39ZLbUbpRs~6+8e`Y4rftxK% zAHBjN7B0Q#uX65j{=A%Hy;)g zp?xIg0yY3n&Hl`QwqZXJpf+TxA^@<&mKqi$vwLA_ogfGdf=!n{iG^mNXzE&L8!!w2 z7sEVs-Ts##;q&1W;*><7RY#4*EjKj)8*)`t^lIPF17jA0)YH$U3}nOL8|>=Yl%v&Q z;y0Py`XDD@LXH8vXl+cOH?u))`vlN*=`rJnUrP zWuORIklpS(KY^8lOb%$86o3vAV9GZucOu~WazbiI-+T#2RA^gg$#vLOCXkTpIl&UW zHPf^Oqc_KcT(#jS&-39GSp5=x{7Vy@DeWXsJb1|P#LxZwt=O+8tr`0pq?Lw(wgN0` zRWSZXj7$i{w8JL>&zi+`(Qx;&v}Tkq;xt4|V}OdN!=QZ90-%!EvP-}6IXo~)aBw8X zTr?x@mypw%hzfppTLG=1ZF068g(@Tc{MeW56k{@=)=@8b4tnJjJcG|yKtQX)T+#?$6 zrQd|tFL|OvPvk2yqzy75@8|iZ7SsRd28lO<1*CEApHOLAhoZv5!4G(=|63j&X%^PW z7=rHUW<{;rHaIvqh+)KmaIyQ81Zi~&h`CW`-rTJJU3q!PW$K{8J!ek*=e{;A2}0>q z|6{bNCBY68OUn@jv!ZGR|37C0(fLLhg2Q}xD3N3?8;IwhL9H;N1XYmL^()fvGOrH5 zz?cy6_W0F5C>bM$(Cg_Ig?+2|H5cTjk;JBqxF68@PUD0{7GMRD(dh5|os1x+kdR&RvaQ<9;J@(jxH1=cg;g_|??Q|D0;#ExO!TCg7hi50D!Aj6MWbiR3rAH6*yT z7$j2t%@1QN^TR^B#LgtVB8?S$Olg*&A*wn{Y8eh8Mzv0<^S=bUXmb!B2(H`v*C0@@ zOo!UUL^T~XPVH-&ZfTpsk3wNq(7q5(0dLixp<2>^EcEVxD;f}gyUw7`=ZxiyOEcmy zCIq3dB7zR1+~vJs*GAzSD#<9?7{SSGmtA#r9;CDSHxUf19(_?lmwNGshKiHpsXUFq z5MOtbc#r9D=1k}>%>w!l=Sl=rdr8yV6;bN#Lm04rdAKjX36;Z!G<=<<2!N*avuC)< zT+(x#flk~G0_h!|Oz0aqS#+iCAv(3tkv`PtvVlQ2uzQ9=%I{&fI?t?i3u``YqOle) zucnC&Z7=KVrdhQ|D)Pb@Sce*azzlelvTRI%6vXChOzvBmK4sH?21Jpg#iyip*#U9f zt85aim)PGH3AJG3g6Lg;0rT_hfG2$)F3KB15Y)aUYP{J~xUA zg^hqrg%?iBML-DKf+xsA{9RqAzdM|y1vLC zWTCIMLX?vcyLlNp@D)@g#D9zwM&vdgdOn3|>~!CYN80Y~?(!fpQ-pC{0bRKRxy@i)8gAYZNAmXQE!Xz?wd2YsKJxi#KI!XB z_ZG?;7Mmkr4mi#oQmW_ixfJMCR}~@p*sm*k3Cr~o#J~>&L~#h)Drbkgbi0VwwfDxj zLPkM)eg*Cc*h~K_HQORITf9O*!pS5@lvl zJfLi>M4Xv_Kb7CS$?R@2eD$!{Ib-hLpen&&I&MgkfBvM8>U!V3-5m!Z`xE77C+CUg zvTFrk;q)(e$^l$b37H&I+s+Zz{*&Hw&tYAGV?gzwlj7LvS>IaHsnG=z6mr>Cf4P+d zFhd%4&JQgIMdN%`XY948M45lxN1!*2ef`;sF`B*ka%~Fy3GJ5NxI)*xk(pe-(ZYCp zn&R6}@S}jZ{VsikFA+hntima4TxwZ4V#&DY&>+e9Oia{>K}0(0>``flb3DhpDYqDc zehe@fsM-WC*(!>4?Q5RpGd362a5BB%K?bevuNg`5aNU~!L`TD)!U2(Xt46r=>_b-& zK?Mn$PZFsb>lUpygkD1y9^Qqczgr@PziK6QMf+{2b!Y+4J0~Bq(Tb;6BTpj>|AMgu zBUbdvc+ILxH9!w`#og5-4D`%*K+)3!qA#yNm9A}P_vANuviv^{8~^t>0vH+*Cx?2C zRCUGurbK;0B$!g$WQdJZ_lUtF?RYTIeCu;rzic}_HKnMel$_CQi#uw4_}yhu&@4l* zCR(NRpC4W8;%QRoM&xjKzAifFsfHf-`zm6Zk>&%*o?(YkPpz_V@VxbjQS=?E1E=d9 zT{v@Eb@zTW3`cxWz5&nGI)4;0k_=tiKf#7og*GD?WP#s8EBB|R9KONJ+C&2ZzAlex zyC++tMbQH8REtPrLE?_kwGK`rUKll7j$G}@CbNTN#i8hD)jfmXgH+xp8y^a7q3j^O zj=ueR1K-M!#EbC~O0et~pf{yjI#HA8e&-6$~# zf!y);#tTHsy480IQa?q7HNyfe1djiGJ4b%7;82T|Cx+nMIu3{#*54M=KJz%pUAhYg z6q>nI7XW9IkGy0?ozec#j=?!WH+xX|-fnmR=`CiS1<@q5idaJyC zREI-`X}5KVL9D~c@E&v85!IlYJI2$Y>Z6p5g?DsOU(MgJffqXOuP_|>wkVhK^XgK& z4Lzo}Eij<>?8ywR1P6Y``QX2OsqMU3u^#pdk!8ZHuJ(<=_a1ZwdZ5#D*W0-<5R71` z_Xr!bBIG|X=y2?e1%`4>5F+3l7ZId6)e)+$)Ocu+%OqVrt4uiqKH-ff;c|w%NvTmm zGETZT}oOM|F_z zEo2yV)tP6_Z@yxGEsrtkNr?f0d*`vdJ5Z1C-g1+$^rkM>>UfQufvB~^K{*V-byH-< zEKQeVOre#@mr_6QvrC;H!ucLrk^N@@HB!DSkVjB}0D_D{PQcF$HfXh`pfmHm0K_+V zQ(yp}rXBl|-xd9jcCA5<}04UYd?#m-X8Db;GNgeZ8?ieMr%k#pG`-?hvKyqg_opBB`quU)L|5ABI2oV z`BNIJ|HfM&6?x_19>WIGuK-d!%r?z#VU*N{ zZ_Ot)V5eOrE-T0WgE`J9Jnc$Rs}=*3CznPb=*p*|v>4-LRQk=-=gKQF^vY%K9TW8d zb+%pBCxbmj$!)?j3l@YBF6!2m&sY8rNF=Pd@bs5t|9Aa&!S1J~s{2faw2C`|B#A*f zv}W=}#a1fm3#unKyBGFsFdzR=R4+F_Cv&o%&8fFSTw>HGyo;!eO`0o-@#&fVDQJRw ziV_n1Gx@WdD_v2cOemYKjvvFuGw6S!F|JCREa=oEpHdZ2&uI9QZo&;3q4+yxz-$vU zp1$0s+!5kb#KU^&oaQNFT8e`0r%p3-;{Sn$N5hiFLe;8=_DK4jt+BxvL|K z$8W6qw39d(@D1KmsQjv4up~&VAw@#o*7unY{RuMILF4iPJaX+XQ^guQ!v6Ed1jpPG zIPn8RaM@rCqKHZ{5zg)d(XPGBAjQMft+WuR8?6X*^Q}kakSiC_EZi!)rOf$U5XmEU zeJ(O)))!DhRt!#;AO2h#^!prO@+6oLu*!r^A*C`R?EYkff*h~E_CwP3!C!(*R2MKg zxg>AiM|iUtlF;%V#&y{c23Wjl#CVTy<$gjBORonyI-pR2b>b=?fg5IhO|V`Y@C87Kt3A~I`J&kNvb!4=%gC&kc#m5Q z79D#F0olE9pOrE{=-W24I=7)v{gFB=0MqjD`P&Y`v9%bNHpOqXp8;P~BfO_Ot@>TP z(~8QcNG#Dy52@=(@ZY}`VW?gc+=QfJePa40@Tqc`pJ4JA1-S~F6W8<|2FQ2T{a0NL z^6p?dCtDc;=!K!=DSn&hBcyO-YAsvDgN@!ciBfjhZCe1v_ZbsRzjfEg&`AezTw;0! zx-S1IdCz@eZwa`{a4CbfkAsv|K;0#z+Y|gb;rxq3X;=yvE9o%%Ug~SDQj2${j}JMn z8jcf6?R0^)`{<+7$9Fg0oA%raKDq{2jlQ$6;$MKaqaf|(wfp^Z=@PLn4^Dh8{CMdS zaN)c)(Bt=MCTdl=LWAY?`?9U%?0fx>ewG`;#(DCF$H=|C!ktO-6}Sup8{F=bWxH;L zcENYBvJqFqe>t*8&F2Y4l7fiCAc1SO+Tp5%c%f=ng?kS+5V|whm6mB!9bXB$p zc1etu!rncnxyJHBGZkEh(SR+EqhV%CoPS!;3D;$07!NkRb!n`b-KgqOueuGnyK&Ah z;bWbWpvs_an>S_EeHO;3fpPn8TZ+`kO)zwdQP*%X2C~FgElE(| zXnoEU=Bb_-JA0X2!26jIe?8qv>*$}z7Pb0Do1<T51%KaAXHF_2}09X_$^62E>re~7g*_9x5k;}q-Zo8 z{Y{!0Oa_DHOni>U$z>ItuDszAMdk0?T(=AImW_J}YCu?sO6E&CxNiqE3l%Wh7TIUz6PQ9S;QRCr-Tp%#qKM&5h>Q59(ID+89F6XA3n-bZhk>Fz%Q z<%)Ox-d{0zL)OM9hl#T;G-z~PPI0b!tEvK=M#jSw%|oYIcuhc*{nwLv0~@O{x`rUh z&j1M|n#Unub9B@Jq|IJ*=m(nZZvpG`=0J{)^u4fVx{plwjHfh+)0ZGdn=qb`DkHdY z(p@GPs+#-s^Meotppu)o7n11StyQj(y(-&B*8XzXPPgLV%CfwJ8^e539~WS%8q7cL z;s6auk|D?6HRH4Rt@0kGx+AqkM@aYaDo)>KJWG%?(XK5gemnPGG&IH1P6hE5e=>QZ zjB45p_5$m6l8a*RxEu@Y9fcj5xSpmxWFD8ZAx2efA|{OsX1j+lH(OW}VzU(a;TNKq zu5rS_*G_Ky>U70$C+#59{{9hsN(6gI(4e^epcL?}h7s#zsi=C^Hxg`lk`Mh+z0v-S zFP-0_dp7vLq-w_YoD}BH=DcD3EPK5hqU(I9?t>s_#T6Kx;3uY=-_^9iaRRb7`4<&u z18N?l#@I7DqNTZ_a!qZyHxxZ?>Nggc2q07^%OPC@mFZwU-%+tAja_?n>^@BMvP*7W z30DCR*D(W=OZoQQu!f&6??(&8l-pxtQ<3gBfK)S^sx0uH40FfjhA4xphJ^0`r`Y@E zyJCD@rX7YqAZ}i3y75fEDANh5<92TsC8`wtH%4h((VZCl7q24W5gw)+5!J#jOyw*o zXKay+9zSgBKol7-Ag#iR7Ly47feDChB*CNm9$;=hsh$qK)>J()#+&7W_jibhh;|<{ilIaVgwFDzCP~$*sq(L+X5usY4SW2j2HL7Td z?|zI`&wE-(^!cl`^C>lFQU@>`nQx>BKvDn6Cmzq^+;-QqVNZ22_gNlcy!*oZf?FKo z&2XO2ui|i%avm9Rf6J+rDo|y=dUXtP8_TAGgq8ocC)kOT#Kd6KE|~``PN-7%Y-vh0 z)OEL$wGr(b5qG$BV)0qpDz7$jX}sC%!Im6z!@-(&YS`$))Vv!4@U+%4u=}+OO`8<7 zh+xzMPl8@6*2(F#>l|+;eSA5ruWBd#(INLgoS!(IRWuO2Sui2a1DyHE_>$Ln4B~aW zvfFiK5GgyE!-GE7=hATedz0!gWF5aB(DdyUFN2R98O}6 zUv3P4<`S}+gM4ZF(XFn_$MAS=+lkCkp%_Ubt+CN;mbYwlJkc-{KZNvq>3ELHH`8)% zWf)OTwQ82NYPg6KV}HgQxC`Yn9W$?%soMw=Q^@4rFIsbw7i%+T@bK_hHS6~7IC1Cv zAY#X&JL*{->WV7-OpkSoMTV+qkFVYBB_wtS&8H|cBPtYRglS*p^4UzkG@h8yFUFAh zZ}6OHn50djQS`;rPuels&d^lNSudiss5G~XpK&vecdX}vj_g={-@YB zvT|dfFt}v?&yI#{U;T-|53QQ#BO5&WqYxEDrqh2kj0*3vex=MM{?AmW65U3yqIUC7 zu_4Osny6i`pT_3@aKU2Dwzzy=7GQzPorE^C?k(NXOUCpgR;rns3My7ptRkK68M%W0 ztwoPjJorPGpC|@$c5&N|!b&a5{I83CZTq!soKHsk1aNUcAt20Nk;7kqq+s!>IG&8)(`TO|DL0pPFESLaKjGDB^q4dIi zzAEQY6w07E2T)V$Jv+{M;HTh@9W&btS!BdOsiMrSq1!e;eyxh_H5*Efml#pxJuMfg zw7T9~a4!vBz4a)wzSh??l;T$8R$pt_Qrq1YqVEG`lJO(6O+q{7C@i;cbB#+Qg!Jmu zfdpZ$Lekdf)o8a}`C4!LCfcdi9=@rA_w;;h#`h%(I?UrfBm}4ULu)yv#_(U|-SSGM zK<_}FK0{y?8-=1=j4Vj%NreWX)0Q5cOMHHRs~bdh5`1cJ^`#G@!)brAmSbkDQ-YPa zMf^VP{pkN`0p4)QC#l2(k)Q2ipZfkmgZQ0=(Z};NKUN_e<(sUGnjDr{z4{D7F|mWZ zCsG5dNeKK$8BbRwc4<(rGdxGeG(JTi3;Lv;iSU5_Ah_D+%^q~zp_B_s<>gI13n~Xe zcSMTa(_aw7ECGo@Zmco~y8Uvds z?96^`@;;ks13R@$R1pY9w#cCSZh2xEEV2Cw3CQJF3pHqIP=&PGmG~nbk9SJd-DuNP zAa9wMzoo)K!h|6e!rG6R5uxzlW)&w@7Z^CR+{Y(yPDAZ`%>KQKE%kB}g6bGWvV%?H znzav;Q>zNL5gNqXyTJ9**iUuO6R|m-`mTwLYZ+w}`BT!0LEkd6M*Lsj361nGMhnPT zqi}xCv$zLg==qu?1NnV@-LC?RMaf(_7iD3m-TH7Q?#o{|gXDfQ>ZfnI`U0|D8=89N z;|IxLAVbqFJ@wb{EseOI`FK2^!TM~v(qo1XI~xSGa+6Z0vZuza=t-?rcXLoHsnMN9 zWyF_vr1??Rcs%?BBw*NzPv+kVAY5WO$R$&sGaU{wf2Fb#W-$75!n*VXL`&RL z9ORZvh(cC|@LG0dosLR(?d?P3u(a2%A1dQpOs>6aGltrcUR(v(3OqRw;osc7)$xON zzXrsHSO7&@PJI1zH`z60i+0qG{4}VaO+sA0LIt3_q5rk$Sx4f9We$2mS*)Qy|4c71S)q)HwpB$jS2^-Ov53jdO;lYz!jC_v-&d7HEHCwrkOo5zY~Yc5KjUST32t zj-w!ed6RvB&d>SLk!)Y_QWq^8Hb2Vhi(?8Ex92p$EU4w`P*?DCH8H?^h(MV_UTIBz zK!uvsZRO%6Sob%_)b#!^c;zXsNwLcrbHPJ(kf8 zrXTXrSojP-8zhD1vyBv*Jv~xrl0P@Dp0ya;ag{SQ9 zo>AIeeuO7N2WADJw@p%=x z=17UDR4XhPda64ziqhNbsS!H2n*!M`fG%zi2<--YnFYX*jDvP-H7%JbDtnxU5NSpd zQ3ek^&pEuGQ$!{JQmfTb@?OSf7Iz+0!qP_aM zo{iV8tg7Ge(Ij_ARMlhsW~2_KuE@*8g1{9TT`4tE+_~D=RD7+Sz+WLBq5zqf!+_&P!>?77VJ@`;;u}l{dIGSTUU0E5Pol1f1BPSClgg)?#CuV9VxHK7l=_ouCf_(|yU~SVWECugAq-g1c!e zQ`DTHZ^%-~Qy)aIf?aP2SoR;|CCYh(-&Bz-F|{j9H0VoD?ji2f`?Y$sYOth^jQp+= zCkuFoA#XZPkLce0`Teht_Eoaf`;X1F#)!`5pNqe2yIz8#$5Ml%c}{ygf4!Zi=OfF? zN=b3sTXB_)I(A#d7=_Kt{q5wMCy;h}14m4PiWgOtbllNBds(aw9@g_=n@kQ`6n8j= z;TuSAmX^s;{X5$#5bi%Ic75~kWY=xJ5^9FIS;q?^r@81Z0R`FX-^2mKch|utYfxF9 zS5pSHmqx*%YM_}c{5h_pquu#er#8lQRmk!gou-134c(@LP533cb7ENAskty9KNIjt5l#uJywl3P;kG>^V$uqgnBj zu3IbP#6{Wghy+u$4uAjzFTnh;dO0zEvmr=9Od7xM#J@5^QHyCLYCCLbXgSja!DEJ1 zsw-a#wus+iA8Qnf_|bzU;I91J ztYjOMD7+lurv3HPG*6@7NS=|AA5Kl$ipH(WsSlLY8MWA4&s$*URremF(Il|o?v)7X z(Ld)N+WyMd2jM!MqK^`cW#uCJi+Sp7G$Kx83~Eq8p6;^9d$@$rpxlDuFs;UpE!-`k z4sbOC24=ogWQ9$UHHCR+F!8mx#6v}4$Q}H+L%j`~t{a$G+|{-Zc*#ZdQ2|ZNPe>6! zj`PS#0Mb%g@^9@tHg--`D@I=&^-bt9i*)U?cS>3K6jLZ9G@^);&`tY{7%6qGZ4S<= zg8Oy3B>s5Yy~p);!b)K`JVqSU-d)_Ex^Evt;KJXE-*ELr1!fsv=AwF!hLwVUWM#y$ zxA2=GfZBir>NnKCWJ^io=~9qqSc7g+WHK;tV}=`c&_B;NnNs8c;1sXyr6_qv?>-n$ zGImjf)GOpAIVYJyAKPK~xUe)$a-q`+l5oIk*FE$y$qdfp#}6@;M~!38g$7&+EOp%z zA&EpP1SBTOYjJ)f{F)C_1|BAh4!3yY2z!9tr`f3bn;1sadKR` z#4$B5%~vb0T_gXNCnYOlha$XbQ!C%YX#_!{aNa04 z5i*g?^APf~j!ae}k|Yvq4Vca`ZB6DpN>`;uV}wpt+baZ!QQEnymEMDLL@IaBxeQOE z4Sx9Uvk>x!a3Vl1Y^THA*I3AkR?ng+AqfKG^{%d?eI~C|h~q#1qN*1SbCiA7oX3f~ z>;0b?oyDq}FgPhY>Bv5|edYuZm!be6+OIsD{LpKv6F(Tl(doP%VpJzLMHREZS}}aG z1c29Z0;MT;0-zULlQ!kwzf-O$z1PYV5G{Ebq=m2KdsIngX{0A@mU^|`!^nkThSwJD zL({^00Ik(r%zBb-Z-m`Y)l&P=nxx zAtSaqx_bSJObJ>)d;L7Mj^%eMrV4Gx1Zj$whB2&P+e{|;`t&Ra+|y%3G5*joI@1F5 zX^7IOJ*b5=Ctb9>%BuNthr+{>vhU1rdthw?-Yyty(C3~szr?wot{+*gyZ*(|x1A_s zpT~DPb<_y16!^R}Zf@_?uTJ;;Qa_${{${_L-K2Qh`hZI2t$7KVv10>zuQQ62lqxi? zDJ8flyP4J^k`i(-pE$W=?iXc*Rlkfj3$oB&hR~l%^%F-M5yTLay#6ZbPHlP023B=>bVb5}a=GU9Rd5IkQ0TkRmu8#x{OY?e_iAbQvNdfNjMiEgojOluJgKP3X zGKX#@RIhZ;Hr{BJcIi%W8Q`-XH7sgjXJklF4QMXQ+;y1x4s(`tLJ+U)wm`=~^zr*! z@@ENZZN?s#C<77hpCGLwdc}bllYTuft`jau&`n|!ZWgHGs8dD^fa&8nKAWLy`41L{ zvaTtVconT%-N=`-N8tJ1ks6IRAPd6ESsc|-dD*u+JhY;T9N3OUt;SdpN(`N6;j=Ck zMkvc=Y|61g)Bjlr;3@H8`G#D>NKsUS^Iip3cvP=g@tb(SpwKqBs+#dEhna!~Z9|&t z_`u%~t*9tkF`ehZLhasT09Elf!3XGPX;Lyp61YrBbirX#SohQ_j^A;?$Ya&RsF*$r zpA@aQVz12$tBx4B+Z9V@$tED5jeYhf zwIb|Qj`RPTVSakh2}L+ZnJaFA}3&PCg$K zD?rIa!cg%PkZzCfUn&Y7yx3t7g&j61+B)`jnu~adR)k$07kZ)Z_MJXSO=Rc}yZ{(8 z)-E_rZ{5*d#ULr@Yie%2tn$b(hjNbV#`t2I8ky70VI*C$KbN`d|Nkrq$`Z!P3DuHBG5OM>0iHf)JPJIDcwCl9@zGb9ha8OMNkc;g(baI4jpdB z9Oqs*f^aU9xnkjqy^4CQSiui1+dPzg8Ryudn=?yECb<}cY$;o5eenUNtdaa?Y3D3! z3V9O4RQfYz)}%do(Z{(9+7NT+<-Gp=dDj|}PJ@)PRL!o#%mfYaT;|F@yMy>mT$e}m z@s$2$d`1NBa;*Hp2pPnmgXa-%ulGL38(Q*Ts{>rGItCxIJzkT|1BKOqC^mUrnp@8L zgXXW=zf&0LK*0?Ph&0?@x7%q5T){EPc5bDrl4-B!vttVVax5K0Q>JOD^-rTDpr6(x zXcM5TZ6i9IKwm&Ulhmo2!i|5S2q8p5={cSy7+9F_`#`e6k+R#Rl@csSJu~ehy0%>h za!gdIE+R5wb$Z>7s$x(6sBKMGq)~0`@Cv#3Aib#b$wl2r=~9CouDoT%QUhQ?N)R|m z>i}3yOKc}gTnHt~jjD~0)v|3W9`u_Kjb=Ztn%J3z`;2gff3ho3_wy#Y0G8gyfquDQ znE&HZxPsQ9x;c5g{LXp1mn@rh4@taQ^PX1mjz0+@K?Qk(` zrWSC`t5vSV+3Pha#kMth(`Z;J*8NV!JxR0Co5+(LYWBmtXHHi^9QUNp`sNU;AQ@To zv0e!A-h#$r$g2vl8q4ZS@_`OZcoKM9i+w^U-|p=DSbUmts^QP`U?d|?^>F-=1kSTU z^DUAln=2Y` zk^37**StdElfU;P@;!6NeT-Fha^AAi-PrZ){?r9ktFNf}I%J%5K+Qjqf@=qy}xJOSz zT4;q@Dq6Lto=j*AQLB`}B8MZjvYrW#H) za5)Iu7#%HpXBwmkroVC451F8Wjev+~?)T zq(AYVZqIsemx{LDc?DUX`_DDE1R59C259K`gQrD#Id`QH)hCdfISFqeK)Ij*r&d9s zGe(8tT3|ycP&}C31uXj+-Tv7YD^qZ)z#i{5K9M^_LACAOWhHEI+YE|S{)?$HPO!=@ zX~w%HNyF_;_*z8>=Mtz#cK(>r4>|Rq3+I2|UIV~a1TcYHE^LThh=eyN+T#Gu0>(4s zG%G@?IAIc8f5H~tz;+v<44RV3E@wr;0PuM@l2nzO`w!xQEVT6?jtr~QFsoZ61l3u& zS~TkEa&B}5D|d6n#KFK>ER;|z>3_QkdvSN7Vu6z&K z@4Ls8kRZqO(gU{)!-56-5cJSBsGU|Yb2mPd7f49SLyogOg_W(6nw{C0rU6u(d*QPj zh5*F(p&0OBx7)V|w~iUE%#}GdnyUFwbgw%*Tn?OhabEWRCweEz6$i!}{BTk^ms_m$o^v6}2c>p_syZ1L|R+YX5Qm%CzJnodil@#0Qvb;L9}9hAFFp{_j( z-hJ>4RziYct_k4-E;ns#5l}CR0ikH1jlXE&t87Ct8hCR;Az>;cdMBVl(ItfBV89qo z&4|Ht6(^Bi2F{s>0U?j#N&_6kXp)aX*2WY?DLm~#p7l%h9PLc6(rH&qEAKX6^pn;E z%n6r0$v#jIQMM%&Ia6yoaBFvJq12l05v+JZ(Mn~MlZmMvAJ^IBhD2`#zsAoYBi!P0 z%D-R6Bj_;ruQ?9!@O?yeDy=nu>g)CdJ`d%5wjhS90rYJ(LN7Q-54^{{vW+VXk`~gD z*~)bm zLvhZrDzlVUj+$t#9*x7^pmHQntWiy;bsIw&oir`SSdTsf;$Q5!N+^+L;1u>zLEu^S zl@^;Q6EvQ1$+oDh)>RCFo>XWkw6P9xP{45*5ab4en2u*?I=krUn1Vvow#Bqr=(p@5 z5AQ}$Q;c1za>AJP(#*?yG@IZ5?N%Gp-sFl@Nb)x6oCw!tZ!K9>cpF z3@m&s5I_UrtN^h{e2fWSX21k1Q%_Yt;IckO)OMe3vN)OlNhL@?6DAPC=B)SW_x*$| zmXp=3TC;xgLHd=h+;5j zC@eZiyd|Xvun~k zgntc|-TFn185o=0RBK><;Oh-W<hrc`}*T zooK0Q>$l!YRmY?=7+N+FKXdpS9)csh zay+FMjDa5AS((WTwdh>=LSe`V&%3*a$DpS7BZZO{IoC2y;@O4+lok}&Z^(vAe^-?K zLo`Rev~e|RB=DL`p~E{^TI~8<*G7~`N)vrUDgvUf75PKDthEen9#<-0h3-PMtEHOtiY^d-8@X2`K(NZd8mK(vsG@Jc!q&APxQ}HD9SdvJ# z90;)Kh|Tc*y6Q9oA!>UxN=#?)l=w+uD{`)m=F$#<^c)s2! znk(J#z>X27belgBEhEZAlBOH?!4krQRR%o6G*6pMKE^z9s3#2aFaeyX1UBM7)Zzfc#iLRD-c9C2RN;aC zU_xg$fQsRRfybCYcV5tj>oukyAxU`B;TUnJ)``?W;)zLUxV@uNzzKW_hibS0mnGr0 zAY^ay%(2II4l<2OXL|~mB6n`~gskA!1I_fD9CVEc$tIDNUY0LWIj){q|?t5YU>?7|W3d}+5 zlBZvlPlc7wb=niN5U%-mRVs9)DN9_b?hT?NImGRLzf~`xXg9dW{ZZvU0o0&)#ixi= z<)9-mjCcHqR)R>eDWMYPr~)UWkSfQ8ZKKq&bjAn&jYCGMn2UpG|1m^0`J<5woS6(O znZ)fPi;p>#ThSjBXAXguph9*uU09*h7wweGS;h6-%lyp*G}FQ=r#jT{ zRsjw&Tu6sx{HWB1!%H?903Xru*6KB-WujZnXVqjmSNN&rxJ1XP7Okc<-fGUCW1d6+^om`Vu|ow#XMi51TRIGj(Q@EAyr zQ^Yy}2_H>w)Ophhe-nP|Yf*4sDqpXLy3g?Hq*rNv{8P-Gknn+;^5da`D;SC505L}P zbZ{mVbJOTn&v$%w=_n2&Kobo25WId?60veA%m_Gx#yWP>!QI3Q6S=t;mgMSqaH}8J zVTTcwL|IFkjTSIz7w6#DI*6JGaxW()e=~a-*@HEi+_MHnve-vSwIj*Z5&{%iDXcMh zT z5?y=KGC@(iP(qVNl5Sw3nPG8s%I%h>lZS&3NI$Y$;3>x{TyFhRhR5{g2?}#{u!Mkj zUo=DTH4ys&YUHEMmOtUB<6SH){D58uZy-}JhveR0L$vaBX%V>0u#w6}O&~u{j1^?L zr@vFK-)q}_EKbJ3gsu@@t@mA@`lK{(6DTvOLxk|M-CjeM|Cb9e^*0mgjW_0VBJNhc zD;*?Duf_9TF$7~b+9SWNGP_lm&|iOm5sMYQ@}d()1Rcwsf>?tynEs|3|6bvG(Ni$d z6=X`#nnKW1m2RNla`0X^M7s4q=MUt0Sb>6AnQSn!B+OjES1e_-4K=-$KYG|~jm}_d zH(TP4loy!@yzB#6pfbr}mfL{BuXA$G-axvf%|ZaiSW7Wq)`|=UpkQ!T%QLZ1%I69_ zdHUdnV(a!qCC#R!?OR5i-1)<%DJ@dl=Y&g&`zUDQ?D?g-Jr(2lkzjxbgO;d+%WT|j zZt=ON%%E7$e~?)Gm}2gIO&X_`dNq7|H5ey>dj}i;T9bJ$ibhSfcy?XE)-m=z6kBtm zA~nL|gQHRJ88UQq^ZgpfWDqmAxK?K1|L-3mQsxal4-Gu(4(V~bax(mI9o>+0lT*J7 zl6#0VMMfor2cWJSN6|YnBK_QdygQT$$Z6`gmP%D5pjSAkNifg7Cj@a&1ErY3*c}xf z$6>p9k`*%~Z3x*5^7Mcdc>2C)!L5X67~Iq~9kkEOng_!wf-?=U=$LBtMUo6wO{XVR zUnKeF3J~En%8ZJg7?9IFi2R(4%460sq=cET-R>vhA|?F=4{c#USgm;u?`wBQ?Fm-k z97ET0cbHowQCwwR?dhM7vmS>CR~+${D>-q#L3&)bBzP^J$Y@!elczUl7|>qvd!n{= zuj52);#r zJzuv6_xjFtO2}brxxSB>E+YUOKHmg}T{E=oAKuoqPRfQSOAyx*p=*ABqZmzZ`4?r|wHh^pI)I-!;y?zHui0A{~aV^tm86!0QacA*(D@ zd6riFgymhE#j(NXKiAm6Er&ct5Ij2p3BLA?ftEJF)zLx_mJlpk_V!Y3Q!|Zh<{Ak>q)_rAEwiB2hKSJ1pyq*nu zsAxR8L0P4)!wgRUBsYZG6Q(+zjK!vQ9frT!+TtV#BBv^k!S3!q8)u2|o#{@&5?3}doCVy9kP?dUN8-T;xc)ME-&7qlWV7vXwB!D!&zF%=d=2ag`oE?k zK#b`{^2|a{DAH4$W1de}K{+YrDA)u?X7L%2-< zsRY@W+__1qn&CH9e-cFqs~TPy1D>AchG`K_4FjG$*svr@HQwb6_3*8REfeVp?6o^+3QlX+t`ED*}rzz36*NjYh#pq880l)-m#y zux+Om<$~(8ts7ZfB_=)B?hQE;AfxX`E+?z=Pb0qIGN*v*>HhadPe&u67k z#4%_K0ti#!Ta_}Micq+Mo8?CuE2QwiI`a;s=ol5&othPU;>*+hvpFODm!*TlwS|Sd z)j9m8lS-SE?kQ8Uj;C6-MsM6RpXiAD))fKZGM8JNQp2N@H9XVA*7a$+u%+H z-Qb_^G^O7kjGgvaJsD>_R|$+9BTtgid$bHTGDd^|yCc&7+nA~0$pIt}lZ7xS zM#MlpWe#HrXtPjpPx~i1+wPV9=@aikSWYu3cwB-e-K9Lxz@gh-F_g#QDZBXhKLeXy z7QmP{As|DMEQI->V;COQh$cH;%T=WtlPL*n74xb(BqH@IO-!G zl9a!^u=R~N)qm*eN3a?x5M3caFN4q}-3DoT8vT6?7m0g+DgQp?3gcvfQ=1r3mX*6K zr}%rQ(r&t#BwlJ1YRWtrv4*<6)?4nZ&Z=yic-JScDA2aMI|3Vj-l`GOO=Kt!-va&W~Zh}nAM>Je@F^;P%2p8J{EdyMH*{59kIiuJYkl|1nu12wj-%L91U9|#h( zX}|lHy?5q**2yY3X9N`tA%+Y6&IEaMp`G!qdJw!R#J ze>0~Y1dkQ$c&-ayNzRL`ZhLENj}{2C<09U>$g9Wz z?RZi){Skq5Sqlpc%LZhrzwit^s%jbX4)j0#_(FEqv*gLIh4z*fiYt#O$I_c~`j;_ z$L5qds(P%M0(@i1Ni@yLBIQL9_a9Uc%D~O9hO0PXJrV&}vv2a@qURN&n22yC{s(Ja z#zTG(v$3*ITv9E{s}0WphiRAbq2j224367>O>#WSk6g?pgplahP7oUPD|deWNtr0e z;MHByY$80Hfg(QB+|$yMQzW^IucRds?R~PfFpg^mr^VQ@^o}YF{q3&L!(w+bqd+7pU8n)u~wsD zT-`X|FpdYuEHa|i%WMTNMqPt!jb_#nr3i+Gm3ZJTwZauw1_T#aGpmH(Fs0aNzHj+e zQ=`7%EHa1^b720RAe1X)i+xjzSciiL7Fa_v-ZJ>A12UR^4VR`lZ3xj(gpknGl1tP5 z2a?rE(p$GQCZfWrk{yY8b;=`ONll;yGAEh-$bu#oaD)@%mOKCb$L}nOn?};7lkw$F zD)JCt2@|t7={)74f*K_N)?_`Rw5u_BZc-4gX^#DfHRqyaPFU(&(c8EZM+14j%ujRr zNVn`nfZw!-L>n~OtQRWQA^9|f4l4Y)wOD(ip*Eq#jazOx|+gR<~ju0{EQV0BR;%0{Py zlVpYg0YN5%2`^SF3OGyP7K~m^NK&HZ7JePnh2xjJ z=8_6P4}CEt>PRf>P!V&?3F1{+XmmBr9$;bBT5(gV@L!=c7=VhJA2D zGBq>NnxIYYzS^;c$Y2=S)#&4$YK2}e?RW-xBt6ZXWtvS<-l`rE>IzGOd*KaWRy40w zuGa7!gOjz}b_g}q>FuzI>DCx_C=tlU0}nRVu*56jb>uiXks>$3&D?7WqOJa6H=WZe zb4#6O-30CDCoR{Y2d||+bqN9kPlmFOIN^vac3!VV;?eV~~&$9A+@R6zFRM?Ft zLoyEG?7kK@z)|emdu$8HR&@O$#X%eQ(t@%3x6^frY;HomCe|2v(JazcDGXisb3IWt z$NQzb--VUC=Z78R9g|epAQ**A4XbJeIpNRG>WWGz+CM(Q@D%6EtFyKT)~5MeoMps3 z2*4br6mq=s20GANThY-3PKNc6$%1PvIOiZmD!TKU*2c64%mYE-qzGP&9{dkr zl3~4Q(-Xol`}jFG50cA*Az1t^ZEPp>6`ZWzs@6Cl@2te!C`dm?UN@!cNkI~}+lTmE zeYuKGhuuuvlizAYpNNX@*OSdGtqDb`1sL4>+Ie$gHM)>9{v!i;L}%OV3RY}r&i4P+9{$Hk9ZaENo;7wIQntg>YZAEei&E59y48M& z(WJvHoP!bS+|)nNM+Dg-i_5A94S=?i3~+WN$v;g!Jv*1I;xjT+e#pu;YwPJ{%Tg?_ z0f8<9e+WCtBr6}LCMG7jb_g!Kxw~Lmm#k3t@6&429HwOqB0sSScjp)^_Jb_KDZhW~ zN*Svu8wXm?`E++}Mkevs7Z1PpbUmg#im%tI(p0NYQqs_MxGZRk+vrUY5L$>U#6_~$ zqW={IpqMj8EFZT=I~LASVMOJ}-%k~greRZ2PsnK4_E?hX(_ZE?DOpw^L_=HoUdQZp z#`Zn&%~+ja-LNeu8n3xms~2j@P^ZqfuG?N;@Xa9hM}oWJdQO=&ZrZ&$1zE{&9za*u zhScWQhHq!Y>i_*upDEirZN}<2M-tw;B8NqOA1yIB6O?BpA$O(#R}mPi_AC`*&)G{& zl#=%woIO(T$-Az@UrAT+<;tijWw+uCn?E-(9eA;v04>T%N{#UJ7^i0$iI{}hgZvqcCqHi zg4-_L#%+32JK-^v2iD}T0U#H`W0{J|U}m30n?=;(n^FwL)d$T`#CE)a$0q)$bLlG?PDKb*E=rtBSWuT z2h@QL%+H_^eyhx7heFV2$v{f~uBMUwgjP?X_W^r3#vCKB^o_RT7b3Xjf*`&=bT+e5 z3J~CQ|HiZfVY0LbUNMkG^=Y5}I=1JQUcu7->+tUcC#D<-LH)vOL#%=TDJQC&_&FWd zjR`D-i$SCv$dyj0`v43GQ$rm;J{=zGbUJP|rKjzVr&beo^0{2HMR>{VgE7}!=;_bH zBoJUDQzj$9eV(wnSX%BJLbJ`aB3}T(#>B&|M2e;imRx+tYsN1dJUPoIIyEcbZD_y9lH2Z9A}yp#12#Km4B}EqE3%6{93msPty6Tj8Vk*Mu+T#IyUasjM4uqVv04D^Z5385PJAeI|1Us=3E?{;cs^Pzi;H)V%8B|ss zB=Ya|4g*CQx$eOph&KIOMBgGtko!2KRjI;o6mK!mSf*dqe_=Zn@QJf2)&M6A#)kEN z)L`mEb>*qaK}?8FN?IHvBd@W05udLm6}T~BmE*W?$9+LW`hOZjN0m=7nWZ-~ckzm+ zc8WDA;)J>kN$o=sQUSpJZQGnhlmwaa)cuPW8*aR+6B}-IZEd2aJ5ToG+lTm-Zd8Ek z!oCb?pox{N4)LL7;T&<~B@hUlvk+slGdB;N7f(=Q{)6J_%`h$>Ie)5LegIr+a_EIW zh}xnI(mfy~04ejwXq9f{NfJ)#c^&ENMrWJ6;t4##xGtxi&aA(6>E4t+f=nY&u0=(d zA+#eacIE25FF>OMb_HEG5%dSy?>O?nJ3 zk@sCsBuvyGX-T z1#QYn2J?DZB$*`Ht$zB)!=nV7PuCyO-@Xm*1Ns|z_V~Uj7!Wk#rcb$c@oMJ=GVkY@ zenr`?Gl5&r5q23{;)T1tqsJ@T;1iL5EPKp{-^C}-C2CEr#e~5nP7@L&A~3`#^YM!< zz{ojK*~?2BY#guvS$-adH!vM$i%1YC-Y|*kG?c-wC|WuWL>q4iU`Yv{f#+<*SI$@z@X-&TWn zi~s-D$ZK!2=UkCSJwNURLX`qS(G7-&D1X z<6I(K+^=s3V{|-- zwJ4Y1{LXJYh+q#P!uHsCJAP4oW{qCry%}N2UCFoN)IG?Iy?oj}jX#L-u9iI7P0vsK z_T3cjuVekFJxam+H}yYF8{&C5LsZI69W^6T`Lq-~&4o9nALz-D+IoI2QEQlAbHzF7 zbS0FPFCa6NS{m5$lOA;o=aqoiNqYilPxli1-v*;^SKO1CQbh@Ax$K3kRh9 zt3uAg0J?4X<~8%I`r4x$AfkaxBrTcBbN1+;!~|Z^DR|3sv3h0MM_ABJih@*i zX}!5ue%SM~8}Z|zGv<66#{`&U;+sY4xkQ8$xf!zpIi(I$C}Q@ zR2jMiQDjbP5wvJ$sq;h&ML{kDEG3lXz&k_Vey|fFY(V$SORLJUf80BlOZys!3U`x* za5ghhe=#A+pub7ZPt99@Ycrlm*{*%(%7`jYFRxH{W1=NwsJWX7Hp^*L8vPMHNGg@8CrPb zm2jQeq3MDJ{dWtRq{cm1+%Ie29FHPe0RzF(Jqb)smV^khTu$|%l z&5UE9o0p{S_M4AcN@GRCU18Ryo{H6)8K1GCnNWc?c)t|W_bMS`%p4faIz#_|(Q#(} z9{mA`yY)k5bHuJ}VVE#!ge9kza-4TNtP84Y8p*V@f*mZ`>GnMaPaB^5>vW$2u?k#! zTV9PlrEN2NG&O@pL_|cq1HH$-pRp+zd!;^~Lh+KvPfPC;ksckvZs#0ngS%y8%XW^3 zQxtHxx1|ERX4Z0B^oLgjKHrN<#htZ>j(hOo&#i(KAdGeGmIWjLHaStgo|+SI^ZuUp z^umovH%i0?8IM_fr$TR^8~DHmhuq0!hUGeiZ?*l)lI~G2-WWdUvXaH`|InnOhqvS# zn=`jHcK3C23^kyv63(Im@xP5@hB-sW_!Q{6G8r1>~bn875~_i zM|F9~=^SI4@AaG>d>?J^ zC2DmAJ4~_IIG5bVxGtXm%a|pdE>-3=I?ieiCy*)*&H@nFzcW`TsgT2m8X%D*+iNJ? zr>3^q?fKNaqE7~f4q@G5)UF#*r>$Dnt$%%X_S29PuzNA>pWN8Bqhm}m1suN)+TYbAJPsBXw8{anba5Z808kTer9Az-@;^p`x^`?N zoeg0=|NZ#E`Hd&CBdau=mI=|&Ed$20U2EM*YySIVT|IUCL+Q?RwrMDRhrOn;6Aqr9 zN@=}#XtAhG2vVW0nQ>qi$dk5ce37@2KWKnJWzL~>eU8wCCHJF5g${6RSqN}V{EXHSGz8Y@8E)-8pcQGC0|h4ohjBM{J5Ib z%*s<3gq!1$;7K#-uh`a@uNU9fY-@WCM$BFqftBwq4HUhF4bgZ87lOy{592`ikq7xz zE)rbPkw>0xmQ}BiU$B(*M`+2mo9?UlD@{7n`t)EXptzl8Wa4XDfI9|L6w4(#pkO81 z?Tq!W8(~UXc9N&Drljfb!f1)$I*m?~AoI)RqgV_8SBQmgm5q_h^9@&>JQ3F1&(JON z{flmIdh~IidF^TC#g}7Y@JKCy(de@UtJ>LX6uNwayCHV-d1&UEny+e3`LkpI^BK)# zbEJj0o2DRo1ZlOlZSKi=*`=_$MWf8kt%L~-LugLOeA}%snxdTo2m1FS9G{@d>PR%> z$GfVj4%QW+wLnz4!Soi*;1_UBo>*~=$Bu3O5y4tyaE&SHF)xJY783u4tih~Nj`hBE zD+xP%i@Knv#Rx7p7Z0q>A-z>=##xbqHWoU^c5}7PM(edGaZm9xS3aVwa`2v*pBiuj zF4%DtFW{h7Cb%tSZNG~v^Wm)dPs5<`y<_waD+gZ0b>ZDwuK24xNHd=0A|ctc5=X~( zz3{7KN_oYA1lQ72*_U>n5wq?{86WC0eE8`|e1KwQYM_zS=W3l>>9$$00a7&1)Vn7w zX0ohy|G1|}wY_V#io4y!=!GA$FT^;s%#MeqFefEaii19fqWyol05E=VT7cCF@YhXIhd;@6d|rC#Y;#WxlN!}qcw;e_+SJ^>~qk_C)yaWNRxGY24 zSX+595WQWlXEEO?{&3Fo9vH}oB^j&+@Y{B7GK`?T*V|ST(o<;DZ&0e501z9LRqZF} zM!u*u9<@(&Fj&(RsiE=;_<0o#hy%`J`gsvLm45sKD7XH5d#VbUdnoT*xkw5YayMZPwT6CCI zT$082j_pNu+8jQvt{jB1Gcz-}g1!u8N(W71KFW9U@6DF7U8^=Qh^u2U4tW$**Vs=c zs40&71$Y>eW)6BMn)1Xgslj>Xx2mf+c*gaT|8OJ?jjHCqoA(NkU~JIy(PvmsjM#EF zI>Se~v_&rt3yT+xa*)+T&Fbh@3@5IwK4JKq9?0b;W;1tT%CY5F_t|l8UMNdrGmR2Y z)d`Z8`uY9ipz*&giSreov3^31EnC05OHv!r)^7T1^Mek2Qbl1fvF31*4$jo-z1-AQ zw(i#|9wj9u>4a-lMmh_^k9dem!a@^V%|S&+087#8ON=QcJ*9kDUA12ebXr*>!6?b3 znV{3;(3LEV!^-4g!g*wEOr4o$S=EZQH1#-avhSa+zqh}GZq)mbf6kwzQePMxuLk4U zBe6{i61Kj=O5FWLBhXSw@DViIcU&&dl>t+f)>fF)vn+tVySiZ+>n(6ByXhu&iD}!xU?%bypUq^LSZ(;*VR!L*D(;W8 z7yI6%^Y0;D4d>i<3!0|rgVdv>F?I7FyUn5W)NNt4JY&T3P-;bv3G)vuKtna2!7Ec@ z%snGbXPcsc5@2A`@X<=Ea=*9YD7O0`obs7M9CfhN(CPa0b`q}deZ!&|VH#7B%U645 z!`?EbSU17Yy0hZD-?J7O*z|SzOY$i6spi`^s@;1-9=diD9vZNsebTctlf!X;&Q9KH zZyPS_PZVFLW;6K@OZu*c(=V@6a@tr%v%-YQVZ74dx&>)e;Dguh6cl;tiUb&e7(amk z{FyJ9?(#C&OE?@O_!SQyazTv%Ty3oYMJK(GB*7lNV+K-En%%dZ+sQ)BkjqR03!8J*I zE>te)=8R|M%KKK}bjCBkxFIvZT>xx8S4rBVL@VOm89@Hz>J6Jy3M~EiF)X53ZLhVJ zW_wWsG`JPs&C#T2{(zUQa1Re2n#7$lHU6udjDU3b!)~k?FvQKWl__-d5 zpf1vHka0~vNT_QnS)9@REY+qJ=SM2GQVRib4ueeRe^x5HlM!1|Si0`8gtRe?M`djg z&!HhE`PjUEs{+EXdYYntfUe|zdZafWNqgK;i!k@?rF?IA34il*ivH}>Sy{|`3jf_% zb3(56>amzo21YZuzQG8;`z0J4MgQAvy8)U>j(`(Cg@(RQMMH6B_2z0Gx?^?>Jix}w zr()n9&}XA5p+{iw>T=(av90BJslpa#`zLw+TGAtU9(MER0w>}`HoF*&;Y!0c8W+0#sae4n?FLW{y6O@E4^f^^NI%F z;hu7}JC|_aGul~n+066@7`>;SFPI^E<*gMHuewFO!Y$8F?%6>9WR z-(7iZuUt}}AvIvX-P?7{vE9S~#I1gNx?VTTeoJsHVQR2`yz%HhdWX1*fyD!y1GUY5 zNM+i-w9C~%iaL>r#6h0$#*h)`Bz_-S43;TFGlz$*Eym%4d{8Q{IJ>)37TZX`-%InS zmZKKUc=lw%9(xB|iT^dZpqpfr1l6sxlixT+-2)7Vqj_^;ZSP(;9z0ZqHJ_*^Yb`G0 zb9KdGl8DbNZAzmVHx@rXOyD_nI_83Ny7K`h*KMe0XOAjLbNtx?)MByfzL>ZM;53E^ zUT|3uNCmYPQU3O1gs+X9YOaTlxB`=c;Aw7MMf-=|$%3{=TB9|BdKYu#u$@d~qD9N6 zjR8N+`Nqde*p9I}T?{t7T{4H^4k#1Yw!PK4rniJnWj5UsS|TAB@7h;Q*u;4+Q|B z80m7C?rEg^p46!B(*}f4Fh6G%Lx1<nA$*9<_s=ex~;CKYgZh2f1#HK0~Plc zrl4F(^HOZzRSKz2&ds<=o3&l^KU|>}m&9b~(ycacj1?hQ-LQ4fhP$ zwPMPoL_rKvEx5n>h7FI61cl#eUDjoyb&a6G3QDfY#8tYp?vO^0398v(f*vPca*~rH zdjbqj4Pp>G+M_uox!0C60$LnlT*t@z= zX7IxjX@&()-)xjl3@z^2sU`RN6Cl0alx_AF%>W<5LW}tRTqi6D3f0S@2^0KQx1sFI zHgDrLaJQExq<4vTer=*1fzAA%63dx{m_$TPnjO-ksjl9kp!afzxJZ?)~YTGo$%;Rg5dXU76{c~?d5QVwWbwiVmqABfmp+x5J z#iIlFd2_LuHd%e%FRCDHL4LxrH_9Vp{cj2bT9%T6frgik*(Rttw^Hl(x^9D~F?PZ5 z;9^SFo|x<&q9yCKJCY3xq~!<--c|RrM%nM&-#`yCrP3-f~>VWs(>y|Za zYm%||BCWy3KuMg3gRjjH8j}vtBv;iv&vclpZDj}h0@BU zh%JI|*$=2tzd&*Vo4otsyI$O6R5O~97Ixf9TzfPT>95~g4Ss-lKR4Vj4ZDI}fr zS}SN)Tr7Vm<&(AGbp}@u{pr2k0=nW>0gpf7O zlAxKy7HfI|wG67u=_D#=d~-fRv}KKyXz5Xw;gp_Wqr;#^5zl&itzVgm|F~gKMTPIH z?XH0yk;4HmQJ@AhPaj0<#zT-%p+JFVXUmfQPYvY~Y7FOqeIU^EXNaiGbU;@NB^c8m zVm4iQxRnDnvPx-W_{O9B%P2WMXyhk5yefOS7fEUPSzJ(Yet7#BHg@pvfcs@B2XeM% zapobYW@jX-7u_9}5z|li1KXHpjGSQ?jZ<7>1mIUxg9S~#Zq8sRX&8()+Qnqn10%)W z91gQTMlsTIPk$G7W@PN8s~7_|AP6CZkdpg@A?W;|0daaAb21)lw2iTwZ4dXw;BmeA ziv7zRjukFF%B)Ez0Pi|iOfnq3NbYa?iCPMbldEbt0x$*56kRbX9#Kwby5K1j(vnmh1))7Y6_!n-FITv&ssc(D>PA>aJxjnXx}kJw@jBQ?(2OR3*00mQxd{7A;JnGanZNdFq$V{HhfUU zu4(NF*?Ndd?at0bm8(!J#e2hw#=9%YQ=)9#1ju%tG^KOdP@8H%gwi;RSmz&;k zeDnV*+rlx~NZD#P+mjf?X7naC+a(r>!Cug}q^$fWvghI%IPYg!n+2S_sjx&yO;ntG zUGNzvOV&y6EBDyz%@?N+W7N|ot86Fz z*$n%0(^7!22W?TEi8jvqUOTh*oc!7Ymgz%zFyYQuI=Gi;i0BzV7u3(yXf7bfM-svQ z7EbQ4@XD||Zz=6E)X9k$Dok-}0IiO#1a3|cS@cpCjftS@T?AC`qf>48A3>aeU4=LD zziKI+5sjQNuktspN}17`sW&cKH%%HhZtyd>eoY2L*1hS@>{JCYEi;A!O3g5vS;lXz zKO0Abk+D0O&NFN`y^sVgwxN*iCtYkZpq$>tbf)4dusRV7|A_K#$TmD4*!_)Z#_K~; zkc~Iu=p>9D$q@a{bWh8;>QVQeeGHEb%~`BH+WlbGMVV=06nQxx8ZC|rS*rj|?&Nv* zrg*dsAg0O%%2-;#*G~F@9yd(0DM?T#b@7ckw>?5*H}D)^+izYy!w1;7CJJah%W5ok zmj=Ge-Z~1rv+I;{=R&@S9io|XvJ+s=NwALhU*2pq+j-C90k5VZ#)noe+iyw-@5%y+ z;+ypNFh{Qjqc3~@&}O6myO`21$jeN^=iuZ-qWrcOdL;F~HB=>nu>Q!Zx!^?2+S|v6 zVW@Haa;x15x=+Wx+r`BNIA!m1e|823Akk=DFLqBK{ysB3EiW%mDB$&cGFPY|@Dg-l z+pe3Fm8Iy580bAr5x~$5lHKi5*X!4Yw~y{SL~befTb;+JP9C0~Qb(@zqnOm=pz0uC zpSIe>LDM#2NeE5pg>9+t(4Cf^Xxe_0uA$jks@ILOorEMgB3(`4&=_$mW+}e^cDH6j zAd%atNjKCZ`pzIlNgi)_t;bYp5o-C|*Erjp)gPR5O~;Dzi1#$M613RBeyXp@K)Zpy z)MiXb4{e8M+E)R)TJX-Km@L~eys(;^%={xCMF+slo0tw^7cKIOneE!OQiAo&HNr zC|(;@-u`+s`QKSg82wY<`PVboE?u9lx6OG$hyB%cM-0YP8UGdIZhD5ZUVIX%u$<|Y z8rS{KQNcU1bmL>4WPYdH1@z`o0-|eB>e1nQIaaju83y)J5wW-G5CKswS;ze9Ky>bl zI~3qW8%*j|e_nFmIqEf?Ll0xF_Vnhm!v{SKodbkvdadNz3AXAMr)XS9T=d}agATJ$ z$};5=!v7dOcKFE10AzX2>SInV&}K0#!_Dj60z zsJGW2>=k+iI-F zjcqozwXtnA*d*UR?>q0eb7%ICy*oR5=gzt3{B%g3898efy-Y8A4lo&Bsm4{cjlF+N zZ?LuBgvuVGVONGm=_q_~DR$<#FzW0W;JdkYJuMhO0Qe>1QClHso+CO-582D06V(hl z==b6uPp-cG{o#JV4?}hV{gf3qJ}-pS`C89g!Ep{}fO~&zFkcVyT7d~{`z)f#(cvPV zQ$+!Uz#61*AP`z775&`D=z)*5XMgY$$0YY|iC;HRSQ~&HwT`gtaff9&C+)r_raKgN zXexyy%C&I@g#It{jNVtbDZTeO_4Qu4V`y&Y$&IFVn`BC*J5P3DD>b$nLJ2 zRHcZC9el|%FsU-wEM%MsUzE-GxzA2)kB4pYCy`Lwf`5u$48k&u17GPe+}!x+X02?@ z9Y*!*O|yMNWbsye#BXVYW}h!;uCrwEgddFTrFj=0ntyCXclvj5rl_O|RY4GG`uC{1 zjKpy9Ns_ZGp1~qR0$x(b`RoNAhQ_=*7*Yy=*Ryhgz9o05d#}#y1#5ik?SsqiH+)$d zW_zC8841l*t!TAh6_JouAe5K_N9Pt4GcUUS6paOYy+Uh^(C5n{WvC8!GS#%}H*fx)=k18inQ^$C#0HZ&si4zK)-vk*-z@u+4e63;xo6ubVXLKBbzB)&YUU! zk-Z(>_fXbo?@Gtyrm?9tJ6Qz0PVlX#+v#V2E?4jMv6qi)x61oScHI@#Oh?eIcT7@` zE(1bmLVSylkeGph}MkmfGTG2%8C^N=gsR27j>7?SN-oD9^_w&48N_(!S(d_s-3Qg@s+m z=Yz2?^Q<2wy(4nW-47q&)ujdo$-zlbh$c1imm?Jw-vZ5SBG*SJ+)ICwD!3su8#}F5 zR1|kmB2WS;c8z+sN#mp_M!rU1bAiEdcbY0?yuur4#593(hOW;8G-F^bw+T->AfSf$LcWRG~9=%ldL*Rid!TIr)T z#!N&YUmDo#Nl^yURHMhTayk6XX&u%RargyMe0D@)t#$lC~a>1zH34c8qiC9D8W%a<@QTu}Ti~V#(Tj5OtWLXpbr|mGHe_IJ+;ua;3t| zvNz&}Ui7s%a+%MUS0vq!^&a#Vm#h&`7p?Z$9)6+WJ#6K!w3pF$wFbvRima^zA$`|liH(B54T&!)U z@S#|Jd(h1VtH-s~ugEWQ$9D?F)K2Sg>)0=`=k=5R3U*Ohbh1^rZd50v_fHa17?w{u z1rRk&c{-6=n^R`N>d^sqe=6C*k?Dh5wK)rimTpnr!ef!o@R@f3)7NIUmnWo6#j;+V zuiIX8gbwrwi(6{oCUV>n1D@@x>X8Da9^4+S=+3HbOKpEM=hLg?;#|MTfII} zwX#i1BJqoG86Y%(D6w`IY7*8A(!u|Vm3GwTp2Y@+EF_y}tBMXnf_hc&V&{k!w)r{?YKdx73W-9kP4hUf9IALq9B6IuD; z(z{rAP;BP%OPuCMlf@Cv#lo;g&zWSf84I8Z)^3fyA$NkBC@5LT3byO8701mrPC~(k z@X9ugsQTd>N+J(KopvpdF+(iF9bBQ1SN1OJqGy1$cfMOS9rSx1|qDRv5Nyp}4VJrU8!RYB}lu7%0d)PsXB; z*>Rk&&O7fuYw+!MP@wE#87h&VrH&1o-Xf2$pC{VjT(KP|A6DA%Csv=~SPy}`EYk+v8C-{(X*Ff8dQfHQP8Ha2F&;(1=(3jX-v zv@9Q-gl936_xJf2@sED(3YbW*_w$q-vT`wS=Exuj+<@uEfL34d&M5w|5gi3-XKJP! z&Hzg*?ZsgT-|8lhFX%*lgxG=v?eW(6?5aYGJU2v3#k<@}Ea7O|XLWc=Dy33MiXTR+vH&ts{1GUtzNn-DJn8CGkfVlU#Y8u>*m_@ zXy7kaTB(B;dhTPQQ2-7%VdtUAjfsVxCqkrufB?yQnZeVygATX7i@%gKS)Esp-VDKX z*$wAaKaiMn8`+nHB<+>TY^VLv_X!MkF0{^;JvwtQ!gk)IJ7C@^q{5|wl6g_`3$bBQ z!UBeG+547X2oV822)-!5{;4guqPWto^y0u~qIyZ!!lIz*Cf$|oPKIwHMN))*gMLM2 zAAEp5i0L4oK5FwAOh7KH|3PW^CICP}62R@JAz{N9zk2DhBB^$YWB3ON!mk{FjswB) zO`dz{p*T|G@m`(FH4F)=Z(ID?JCNov;H49>Hwx4~9)1O?ha>A)d~w0{=k3E`(L~^1 zZjsH@Po2{l0n1Ay%t8cJlLmv=Ftr0_rnP3>{R;w1y|pI9ynCK3P2-}HIP%E+%S6$p zzUYK`%|MA1aCrYVb6i|fE%K{Gk*#qu>Mi*G!}RML5j32_-#_nOv%$(RgR{dDmSK#Y zHR*U{l31x323Z3|COQTzm?L0w9KH^RN7vx3L>`brk1W|e5x@`|gZKgV$T{_LjcU%WAO3;o2i%j-=Mc|qDSEn`KjQ3 zXuSN^<9V!tAWMk+;f+&ivShf@SBo9tB!j2sY<#XAt zD;x<|aa9g1`)x#*xLVRCjx9+^a3-)XeDJzzQmh@K^m+jo8bFIgSl2GO)$;*GVR*Ub zEG%Y_tMV$to8^E33(vt_(75}^crs~Dd6AU3RT=s~eWvO(tXbO{KQYx#qXF&xBr1@D z0mXlD&Z<|WjQ2)R%OQS~$=>#O@?snNR(3sr3ntu`>;(_|-DmlI4t>ZH-kOL*K)s zr|2U2Cr;N}T#|%n!e}yZ&b~L%`H2NHSljEi%qZd|jLZ{m#P8_DQ`;}Q>DN1y3U=Vd zj<%m?6#mwe=1Z$SjK3&Ma@|c-`P;J>={D&KQ7T^CdUyiO?GnWiGC~c@5Pui}HPJE1 z`rZ20>sZka7ndvi?!M+$Fg-?YIJG$PfbCZfG+`el_BUpM_jEFo5pOC_5-iVtB^4dE!;8FD1tu9;yl3YmHRjm}v#iX)SSHiw zEe1dUl*tIrPv6=6Z4)=>B^Otoq1z(BtjlY9v}M(T@VCM+)NOdc4xtE)fb`k+-7LR`qV`<6_a47UC*ny;K4~iORLXO@_*V_;ZEU zi!?_*tbZiDI&43r{hcz`7pv%~Z$&oWt2Ea<>Yic~>#e)hEjF}!JIb>5h6OpdIsLxD zK^m=X(tn~e1^X7G#*90^G5UPLll8eI2%vB4`CmyT{%`^W+W+*6TpyoU!nnptKEpRq~%9{j;N(zc4q))G=2E43ZCKAS$& zXC^>s?PYEZs6Mz+GZtgj<#ROuPu21KdWXLqMOWucyJcv1btOVcCq?jd_@(sw&6_#% z9{HOh06YWT$B$Hr)7#pj6v-z9oE-NgPh0&v7(d+jJl$mTIuk{N`c5tch4DN{$nUR% z4d}OL*-Rxnxd7mZO*KQJcZmAe@UUfSCpDzKxWEKHGF~1=Oxe_WX-nwpqpe9|B!FhH zzH;X_CRCTB!v$_`&Cn-lau1WOdxzmHTeWmKkh5*W4aTKU2+`V4q7b38e#vjHfhTZm z{mmZex$2&eJ31s}rL|=l@T?D2WtNAy0AS=5P+qZ5r3&inM7D=?fHi{x^Dql)=^38x zI_5Uq{%6OAKY;Vt&2H|8Y_eZIWB~w&)@~)P z!MrigC^ubjS|;Lx0xj;4vBesASxv?FeB7s2rT44RbX|znfx%d+roDLPs~2Sa7w%BI zN|f~lU-hq0XaLDW?Umf>35~n4c;6DE8lX4RsNz^N@cZ*nDzhzXc>dnn*bh7YN3*|w z+1GoA4&_qa;`F3P4JzQ6sWNkIr(YB^?}Dg|TqLeD!; z0Pq>4eh(N^vTeAx_&e@x(#s>J%4l*Zw2uYZQ^RihNqhazWHCOlaUqAbzIq&WEbe0_ z&=5s_=7cAD5ON>LMVcjaX^`qkmdY(^lWHq==8Y)m62j3q`xnM_f<%tljf zi&dPNMbvx!Gp`rO(#Vo-ekZEUpTZ2Te-4IE;R;Kw|6r91b+ z+NeV2THh&QYyJYX&HGB=S7$`2zhkx*#8Xo@W7o`C#uGUajhr`*SKA0QNqL{Zs)iey zK{iHbZn&Efv3sWwbuxK2NbD^o>+7$kcEdcKkZf_hM0f^fGXZ=Nqnja$JrI)!N(>na ztHWXSig6{I7CcMb<)@jkP^HFW-p=|Xy`N0xHKGh~rH{=Pu2?>1`y%-zU6qO=UZf42 z?ely|mP$~It}O+ix8Mv$7?>Lk-4R(N3HH2)UR2KPn&{ReN@^05`^_+WeimQk2B${#;e+pQl#(3+32sb3uxb zvb89P;vU!Np%e&HG}FUEU9bqFVX#$vX*i87!ZIaPRZicYAfIBqwzC=K>{)u%?t8d( zQ^}6jt$){B@8TT!CFmi*QkriH2B$p;+8VDIV*mP@;oL%7lsnyVWvjcEkpZH1vF1nR#7%#xy&5WJhb zSOxM5#*=_)J|_3L0HmZ5-{Yxp>Y6G>)I@>D!la|bY+(l`EkJcU4B)P};3!~Q&OgAA z#{YMVz2sd>flNS2e0sHyKUXa8zG>a!y*V@~|Trl)58BTHM8e67dBVuVVM zg^kM>mO>*|ny5~wH>r z6FWSlHSNYh@8zX^yg-Z_T~O#crwd&N3Q9ySka=~jhgaUCMDSw3V3y)d;OE=2PHj6% z>3MR$-IMIHo8%2sy6k4e@|5xq<|lvcMXGJuQhyseA*?`g_sQ&4jLr)ETzpK^hwh@f zpVxDW>tmR#R!O2h;-Tt(V}q&8OHp%T!~DI?&^TWb()c180&3T!QOs3~u^iR6OB%;> zc}sGYZK0o6v`k6E?LcCueEjSogbweodCD-W`C5tU%_r+u_flLvo9Ab?r)vw>d(F(- zLUmWe%^qE5o@{R8nX1b)b9c5$CUc&~x_SR6@Eem-rK_u`h(j=-Z~;gIlUGFRVkw{KE!;Qba7UQ>)xqX(;`5ViZ2Kzi57^8F#A7$PJ!| zTe^+VX^#5iA;W@~Neu==Qk!w^c^ZceCbfve^J~o3Vc|8M{v4sJ(b68G3Nv-*%bl~N z`j~FuB%fncLc=q}9no^Q|0%os-Kto`U}V*60!X8JBzs(6_r<8LEk}V>24g*KysZ%F z&ip4RBl9XU6RfXSJ4S0mhW!70*{X#J0Spb)uAb50l&fWX*f~;lG$=niKw&W9$b{z z^wD&1*B2qG;IEWa10Lxhetr(dDftSOEDkwxQFqj7lZe-iCg3pI`ZX>+8cRUsZZYqT z_*bKIu=3MGO!g>GllrK=9LDzx?uduh!kreGd=PG3*hhIJ`D;n&n3`}s6B1DFu$CrF z08`jN)&R2i-=k7j7qa;JR<4OC8_z-cLX3sYrC5RiRSkKB`7f?eaEXr_&x-=2I;9kk zHut{`THRHreGC?BE!^+x6Lrk#4lgSVPya-A@O8mki>8r7o)(7l-=Wi&k^<*p(0jMj zN}xvlI0G)s(xu2=N+HpEh!=ye;3PQ~0rLxDgULUz*#&9$kc2(318sM|6Z0;&n_RMG z6NHv=E{?X+UBEUP$lf++RTZxXKRv{qelK&cw9NN#K8rF8sUtsnlcEp{zQ7gx2e{Ee zm)s@S+I?MJ(U_1X2sSr>Um+{SI+~vsn&=%A>F0p4UeN;n?vSeYQT{T&{LU%0lr5%K z_=G6-=cT62x2g0gg&zw1gD!d)EK;))OB|D_(U20@s=wGNNpjrckm%5B&N_5W#J(p) z-lPD;+eq{Ol}v6@k*D}uP#_JfLb^RX~!k!%`w zDR&>Y;PF?wVr8OZj+Mz-dNk2*eQz2bKnU%v#}Uh;j`A zS`0KqQ2Ci8fOZX+^FOj^mzmJc zhKCM;X?1*`T2o402ZK=7|H^JSMrYLhYx)-g6E)}StGhJ)*74r}dr>nWZ9i9CzfDbY zTK5k<+4m^#msM}Z#nl5kBVHJY-;jJc(5HoUc6`tp$)YqN!(a5$CN<2OmTp(msZ3HP z@m@Hz`PQ7ZqENIb|EBrVz`4~WROIPyamE5Wz=fRTg|pg#<6ZV2RnRjRZJPONlt>Ht z1+~K$C{z= zPQAPRM$)?%?fzta$IdTrPS zF#-M0VlKm@s6EWEfsIJWYijyneepw^DWXh+#YrB6#tsDyE~Dc_OSaE1k`&m;j8?Xq zZ3=3fNrgd%qm_Aq({KLKrrADJI3BTo!M$mf==kjbI}=rUW!#8qhuC^Vtlzb>?pKG2 zZeWlzZ)9IPwQcL;et+;KMUL}xgEW2|sH#}$g2Y`vz4J>Aqn#1CG)BU}w*@a}pqz6J z!aGp%LLQYcJNX{xwrC^NU!};bz$P1Q^jyW@9 z1pCAC)Ac%v{=ALT^^FC~ayQLUu zByrn9N^Zb%WJ+Tt0wYc8r^NP_MIU>g!12Bki#UD{NuZK8l<;;1NI#6E(7_6DU(fBM zWA3qea!$}217fC=45j~PG4%vJ4_L@#qLD4M)g7Oh& zj6SWUYF~`Tii#3ldw!S0&yt;<*5q7%52}bV%ZmNd81{W16BwmCBQDJ9*QuVlznt29 zk)}%pFJe%hcHp~AkEY)UaU(I9N*ecoW!5x1r%2;hn`^=fyWJqMimx45EmYZQR;QU1 zD?>rD=uTga{#!XA4)J91PRT%M!OjayFa~Mdjf<>#DKK+0{~uPMRByKbO$p}-5J&F5CogK(`6!`suA8TKd5$HO)=MCj+Oe||=E{Odz-3vaZ-zYy6F=bF-<1oEwBA9_;}dAUOAFBIIq zrps1z_tka@DT9vpmX&3d$pkKMrBu?nZZ^vszP)Xif@^kdye}ANAXojH?KlZa@y-RlKA+Aj$@E`A4+^S6b$d6@)tJc*Os zX}7})X4m>I*>T+dsAe(E=cV(UL*=cGo8;TWb{qd4N?d$u+ygv{k(U7EW1VcvQ-iUh zsL#>5!E__G%!fC><<3U+?)6KJhdOoj+}vE*T)qojWGdow_s*E1y|c55^~;VL`U|Bt zM!;^Jp1r0JRy5-$X2qIbG8~g~1}x=Zk*fsx`9T_gE-DHsSjh)|tpaXu(FLYv?%JU3 z5j&_)j=2uCMyH0Hg7pWt_D4!+5SlwTnJ!gFNhL#>=#hlON*cd9R>@m^H}P}Uh2^&K zKn3V3qZKvcn6aX1D;l0-xyo}2yGJtG;?mKboz`G;5w)tK@>iZwD#bkzej-LwUmZX3 z_M2tzInJNDX27)j{9}4cDU%B1pLw=#1&8!+5cBJOg+`}v;e7e^kPr(8WZ*aEA#(PZ zH{Iy}$%YZtjU{s+6+S>-h6N7Y$4{Y1N*gGv$bzGn&nF~Bh6U@ur%Y{LFbvAT4;3F= zH(||va{hSsO!;E*$hUUYQ)s;3pK|!8>KOUYcY3ce=t)H|s- z!wdUv=ZA1u7D4)ZZY+)+vd8Gt?qoWhRVhTnA1~>PwyMJkpywn~G?3R!cEH>~l$Y8E zLFvB<;3iwZpKl@2;ocqJghv+k<3xo=1`bcXSas9(#9!MBA2+bO3y%Gm3EP3Af!X6q z!fdb0%rLvSP#~npp3(vC;1hZR?1rf9xXl|SC|}&U>+_TE(uUkOhf`!9dj^$-VeuM# zpX{l#-X0e%9;EI_ZMf7B5~D0Cqa2V>X4C&od4BUKGujQ{SZO}M!-QW?OG`} zoU=x;1xz4FULk^7=C=j_T?i?;1lRE8HuW)st~rk=(zZefhFJIlT6SdL1x((#=E(Dr z5Kj&mTvl{>Fo!XnDhgGqGl#>p1)jcxV7 zeF`2Jw{nNi+rdZfJs}07z#hl6`boK0o z7O_Pk16>AYfdd9!X#s-)12Z3aNMs+`{vd8Yz^);?$vpGLT>b&+<#D3FYDqv3An_9> zX1C|Z%~#-$f2v6+WFG2#On}MVu$aJ+&Q@SgmizaofcbkCu{FlKnhI5gR2w9~;e|`s zhRS0fp(W}jo_}Ouc~W=x#jn^DS4~GerOM<=$<%ndsceLmUCCdrS-~a7!lRlM?r>MH zcJ19n{go(oH+o|x$O zVKflE+&1W^un|~1hIH$Ll!oQN7A)Ib`)F5HM_$c|^zRS*)#wqoz6JB@b97fat-Dk* zum(H`Y$FP_@zmW?A5(0;QEBWSbHDx2Cx1e6u@S+x;DGx_XyAO{fT122LyxiHgTL&G zWM#~q+){&R=T-G`yu|F(@BNgjF(w7rEfOVCZuR*6f`G-4o@SfEUBW_RV9IYC^c?6p z#p~vc3vQxia|KW~Q?%ELO;oK7m7P!?Q*;OQGHg-q(KWZupY?nc8c~6p>=zOBx2{1! z!`ZIta$&U*QYkenpA#v5{d9{HZ|8sTK7ZZJ_z$00_bhCd4YtBpu}1m|xAFSO}T@7k-ULhrl75we0e|CB|WJC&b^zC&tON zHmxzsYfpE2D#eWIv*E|z8YQj7n+4deC%N<%A7A)pCuvi5-%u6>zK9yA*>xxDDi*C#0DP;0$-Qhv-Xo+2maFiZdJnMA$;UQy|-&3k> z01KWY9aI#{`tUwBxd4C87}Xeb-Iogt>R*}SPR%;GIXSD+BZ5B!?MUOll^#Y)Fe=tf zhXV^g>|5m)yw(xJzXt#YfqRl4ayTZpw5qOXOUuG<=<4vqcsgs7@C4YH$FDQGNdk{r zQVHSY0CUoGPlOXlQVN6D(}u(~zc`$uw^2SOY}wO>Kh6G1e-$7`Yc>w*aZ@|ypmU8{ zXf1Gs@jd-=%T0XG%8v6@yiYo0di5m4;}Cb(ML#;kNS(Hos%VNpV1tw|V}_6o$x2a} zqVTtyN|CT(Sn+<4|A0~ zKzhosf~G);Sx!+U-yn5PYF(mpi&+kfDaP}JG!0ZiD4+(Mj$85H($qd2CL|^N>1fkj zo5VsBPqQ^R_0&lK0PEXs0?N0uY|unNEh@);b3?5VWPZ(&UkR2)Fz*dn5yrTf%o-Pr ztr}(01Q639Y?{N)1N#))bgO%+M8rIJYzW_GhU>oatGXkyovR-3OA>4e0JDm-SD7Z9 zUsjGbo7!b^Ar&vhrlqy592W!{A=48nEmFa@bji8VsY%hX+XiX{C$UC7kW{;bfEL2h zPkvu=ccM6B*K>?btZU3U*Gf&^aB*oQ&yZPPq&X(bk4P=1sIgqyzgB+aS2Oh=EfTN(P@e##9Lkd~ZZ$ONY+*Z%}GfUfC2y2ZyE99KX)O1I~)31$s`W=h}K}YjCwOMUf5x` zOuAYDm8O)e-|vj^SI@t99no`Md&{mAy<&@~S?y+1*>Ktw7rT}eHpjp9u>74YFPUwL zP48i4)WrWG?39|ssr%!7=6r$r1IK6fQ ziD9P{m1hD-+R;5utsb=SP8xNX4c~VN;1`mnle!h|-~~ud4y1 zRSY8AWgaVvjI6BCVM+)6CJMvjOjL`W3pJfAB9;r?Vtsrd8qsD-X9VbLlaDaT8S!eu zJ00t<}2Q#(8YMcUXtJt$?vj6;8?X$k=LPZA5uC8OKd0< z)Du<3(vxrQVVY9royCYcczZfX??(nXl(YsJ%s}r z#B1{QeTd(w>^<Qo`C|q7^(xy>_KSnpluBx4R|>&lnmIo{ppM$xVZa?C&7IF zKqv|F@qhSk>X*m332xy7&cIa!aPPvb?Nz6TWj?@mW?hwZx$*OS$R=Qo5n>RmFvI`b z9H%#hR8U{tuN{{gS-+D=y-4|GHB52VcDGMFkh}{`B$}dfLwwT%Y)+{l4-aPGtQlvhma>zr;2nUu!@yQ_utqE>9U~ z_~0Ia>eB^ojjTQggb~0JYgb3}fE76O4-4}bQV76{8^|!5{aJVTWdGWGZ2NJ(SLdJj zgYp-Hh=3JekdMqJq{v6bI7z#TW&~fKs>JNB8B1#y+^nrcw!|NOQbi%a!- zRFh%%tr;3dz~-GCbu*3jM{Mt%pp?tWHcmvFwUC2<>Mia=W|5Df#;oTz**+FTBF?}K z3rjXsBQ9`~(J;Xy2-#EiaPBT+dhrfBKep?%Fo$s*9CR4O?s+GTh|~KOQQ)l0R+Wn| z8bf!Yw_3(~3uB2c2LB1_ZTl6ALA^)qK99!Wsj2A*i5AMH$eI>ex3iF0jmuK64n``a z4l3i)8tF(p!1v`T-E@pQ`e#nXan*jI_0v!t66SLL+P|<-@0uMq=i$=8g4-DMc>;9; z{>c`f)my$n1OTe-cW|?*+F^(Mj$4Jwi270ehf!G`j^yPR26K#MhgI=&eNzS-iro`` z9kA$>y7LfnPv?o)86s6-2@PHsK*IWOn={joRb&hc~sx8Rgg~gQAdR?9S zUNRRVnQ;})-h(I5Rey(oRr=if*9-L&=7_`ONL5|$^8Z1sWyFHP>}M{xF+a_PRjI87iwkRZ((my<>oIxD znnWS!caB62EuHzP2!@bL_Qc^2R8g6eX*@fZ+*}0RamK=PfoHU-{23nR$Dw_(U zwdPj|N%0`eGvmH!g>54lMH$?eAp-m%7GD|-qU;793$HCfumsIV1N&(DyEYIlGTf4& zRQHHu2YQeVXA5lN#y{&{pX!pL-vS>(D8Qz`RfQ|hG2#PZWk4ZPj7Ak<bj9q&@lqKSJb&{L@SyoiRuYjH7PcW19@edB|OfLQE_(gvRw^0;`mVHKlo&7)SfI;SI6R|dbefftHA_a7ayTHE}oN@A|5w(2>ru&&CZ&Qh1V_`RN0 ztGKr2$`gK8mvKj2c;9^9!z$f1iU!a1G|dryLuYbd(IDT3CqVHg#n!8e=CQtdr<(2y zCS9bY^2Xk2+<|-5kqz_NSx4W#3EF1?qv`Z8=I;76g^L08~{2RZ4`+EV#iRjIqJ4HXD zzmsACw>`AexB`ARG!qK{Yp;FSq&RC1GF@XXtXACNj3BEcG18PEjw7a!o*0c_y$^B{ zkEYYtB;aVK=k;{{W`K*qK{S{;6_Nojj7o&zW%~lU)!?N6g=&hZMEn>@1AX zMX4FBHSQh)2DLX&WS6qw=btS#-B88be7m?@t+XVFi49=D8a}QXBbzPk0gsS}W|P;t zpO<>;O2Y4t6dzxN{YoN-`FuNTHt_s^>b!A`ZmR)Pv;CTA_M3IH^DC>)hrbBpdyS1w zdA* zA}WD*6Jls5OcJl3nOE<&*|K<)kGND=jumqQ~*K+_>JAQAz=&z z&xx&u6;H4ymkTqz;-ZLeM&Qg>8f4p5ww1rNJ1ovew3Q!rz(an;67m(|Lo8cAL;rVP zuS2JdzrCp0zwLTpQTf44Rp%KS#>X$P!n%rP{p??@j6O zCjScg@Q(bEdhgOvd7xl@{(M>Lpyl+cdEBAjdhWhiv#!*EBB@%pX)l`w6G2Q&{JzKh zu~+-~S_}33yq^G5ovgLl;fB=LXfYEXAOAHaN``I}5n-ozlFZQ4$q6E5Al zu{-7s_X8+UgV@|V`B$ii$A+Kvq~N0)t8aLGo!|ED{)x7G z79N=j6B`C)2aLieG`XICep@BzU|TA)26nT(6mNH56fR1chwY`SKe&GjU#_9scS+`X zN{>6aM5hU)_M9@HGc98prt=n_j4<%+99EKMoY{D+YxD<&M-Y0OQEYoYLys-I`%Zz$ zq8B@1|JLDS6&5d;Ary?V-GPvOzv-$fVo0|9XqgsXF zT;y!zAMywP9RN#-KO=7gKH36NeE@+y>pHi|!zbcOZo`OmOMSwF->)i!XS&0q-+ zfO_-~v|4_gngHwm^7n%N5M(O+KBy$j`uyA2eeY;q%o&~Br+6}%OT3e zFsA!&*zOMvO=feKfRsM6dJ_tMPnu;lhds0NW!LR|bv{W|5J``+aPMO>_*w7+P*}FS zWD7y&g;NJBaz_P-(S3^l_zQva@-6UX9lP7&B&ysodvo~{gX$OpFx+>^!c(<)<60-} zR^$f%8;>@xxzBGagn|G))45xBu5&FF-f5{DKIa}}XMOc2(T%~&X3#$FDf$ih3HC3- zVAzyd!N$@f3AO2HQ*+mwCl>i;!z^Z}TX+NgjU`tG3SFjTj+*ZqO(hvW(_dj?eh2p= zI>klbb5(I@5t0)qKNZPsgtGj~JzdVggCZmEPRPXC?gJ+g46g^8BjK;V@&1&n4xRJa zH~Ud^@2Z;SDha#^e^pUu`I#%ow69NUFaXMznWg1eXwj8v!sF$N z)^NH|we|UgT=O2%H=5hG4~ zt(9MQlQb+?At@+unJIhxy1r7weYIijGb=;vXsa|&?XDiWAUgnRT+}PmLn!Q}; zJEq2!XxGX77>*hR4a8 zUmWg*^*3E0>DH4$q=mHyYh|>V+KOI$gdJ16Wygr{U*k!kL^iebBqP{MO;E8cD!?h>2-Pm?xyRq$L zV%uuixUrMQwvEPWY`Z}-vGdJ)&N|=xoFB7h?=}0L`?)BwjVrqIl@+c|xPm8m$#&R= zerm;XAP2K}WNMgagn4Kogj&Ihmamd(E^^LejrOF^097~d7k-!oEj7XOKXB;VMq+Lo z=gPd#NR?DRM?FKMYa8Y&UYC;7o~n`$&8H0H)9<2%<&g?$g?V^8z_ZT-EnPfWr& zNp~qrTEeaIVj_jFz|>Xh>Zhkw8{;kSu-YC{|05t+hf=uq2+4UL=F8=~$JdQ+a!aGF z-ms_UnO@bAjm{^Pz1Jusq$X|oxs~X{us}4xEvHD&Whf3(TQJlc%XQkevA@AV8=&Cn zJ7n+{T+;eIeqfri$MCB#M&XW$wNnUr}K;MSVs?HmOO@!j9g>l%Qo7| zOM4iMsnS$5QwU~Pvvc?T_8$L1Fzz~m*> z_F+=i&_5ufleujO+a!nV=v+O$lq*GhL_qbSu z%yKb_X;mby?*%^CE}xO`=l<6HD}e}4qm$DXc(J^C4`K&ET5p+pTYKcCjIR-q$kw9s zD+X>Mviu=)lgmSD!}F&P&d@z8M(`cIWTI9y`Gkk#ER*vJ+!>ZF-UdJc9q}Ma38~g# zI5hzCBl#UT!TaBi;%KuKGqJfd?K*7v9>zF^@m7PkKcJf1XVYM#We_vQL)^?Z#JlK-7>uAU<+K=coq+wgEN#q>75 z<+jqVbZ6krZ^zu$;823f=KEJ$;>=YFJXejw2pH^tB#A2AZ6aS2|MW||@^O*X&qwt< zJ3qx|^8~KHaB6>2E3^(QE>-8OWObqm5t6=~NpKc@+(bht@7yjt-of6D?BZt{C+Tj) zNu*z~Hr^Vgd7EzAk%E5)lcu1CiB^m5ij%TH;fEwyww`Ku==^kxyeo#dZ0%@1vw^z7 zikKQq5Ko9@q_ARt@;$!W=s{@hr?!o>ds_urqzs$3{o>|*k&BLfief*3oFZ(9;=EL6 z-1};U#v=B=*03TM6SzR5^B)-}5`DDDe6dbLh0g|P8E9{7wG>~jTx=Va{EkHPcFsro zq1ZMqGKhDIt3#P8tZ*c>(+AT?D$ zia#(gFo37W`nuM73C0{oiCagIx;HMt89`&+v;Yb|wLWl=1|g55ciyNs2fOvcR|Ox= zD>-v;tYn@7jk_~aETwyLb?v2eBGHw%U}=qbI|F+|R0bbE^iNNaG^`ESY)QOeI~dhw zhp5+?mZ_&Cwu!A#4Jhz0VxKWX2p)14b&-rxFJx!1B2OZMR+Hbma4j*YG9rB?+eamT zWkbU6rl1&bR%qI5G2k!?kUn@Wj!mrw!b8voI4T}Vhm3W5aszM(5&S4ToiaLO<{?b$ z27mGinLKgHq)vS4DkL)>BofuHBVUqSo0*-pu}KefB?N2|b}`&j`TQDp^IGGt25uQ>9=Vw5=^$qs(E<_HI&&FWc2$HlpOj1-8Hh9Jv=7zF*p2t{{zxF+L{R0Slc=Tp%87TXAws|4Joy2Htyst zOpn!6tcjl8S1jf*Rwukq<1GulZlg6^u|CBdKfP`MM7+`%Z?j z!X0Q0Q(xl5%ggXIeg7(-BgQE?oQt*h~i zmpigX`DV!Hw)MUrELK>Se_Ok=Rm9pa=p;ifSJY=Nyu^R}z|)p>i$S{gkphb^5f3jN zlofp<|LH5EO{zqu6U0ZDrbo`6zvDZ6Ya?as+oU}M7yy+rc>-E^EXdAgXcJ3tz(pFW z`lmz0^!sP4HJ9Ph-S>aQ8Q9fCi3}swR5Pog8p5Zfaf02?@n~&(LFR2&iW&B5H0cnU znBx>tksimXjiMB-=oI$P4d){x@-w0Pd5~;<*H*NecVttJsnuk9-Nl7)%YU}mdwOb) z(*ry2e4xbYaCmS4Mxb)k81>YDg3Sf@;_1*tT1}>@jsXGu8;-J~ER0jt8J(KzPkMj% zwOsUR6-{Uo@UztrIJ+{$c6^*>kt6RgkRQgF93g|WeWqCqSJ znlM(IM>?^msy$A1qpOR))dq)`d**;yQ9mJT1Vn5WUcLcf7t)u)BZ=$ zc0`hiMXhc*X~W9%Gan9V*On5;SnWB7v*8MtjjQ3xRPA7~@Oa~oA2LN4HDqC4f;qwF z`bm@5XD7ms9ZgM5!)B&sW~OHKp#vs@Bm(j3D_lr?;5@f7o2*DQQjRdju5fw`dXx0P zKT!B(|EC22>V#}Ad$+*^%l*;e<*JU3Z)MF;WTPM`zt9Daehp&-Fsf?(nhguSD9g}~ z>i9vtCiGn!KPWtLf7x45GLYgOc#}(S1M%3+FU}cG22~F#$z{PKhb4sUA?Fn0Ta(D3sc+@V@h)6kg0 z2VziEpj+>cZ&9 zg(u9m)T@x>0h?dXZ|LW~2LQG}_WNCv;6VkUvl&h&0v zpwSOv6|(2=9*s&~c%J*&&08m3GozDP*Iz_I0n}~f;Q6X7XU`Tioj}?h^=pcSp$2N3 zqND5614N0_<2#&g^*%)bK+j)Z%eJ^t3dU#*GNAdC55}Eyid>l0=9NnN7v%Ht4iJ4I z7I}|HBQv%+{3`OeU?t3y917H^V7{`jxhz%hNvjKW)}k%e+Z8<(TX9=|5i+PMp-?)( zreVtN!1<#1=u5B4jRMqh}HHJO|KI%g%o+nuU zJ9@CW@nObwmTR13$=|qZi!Aw4rNao zEntO#L=V7RubXHy>bx`kO~yn5Z^tnt7c;xkiyK6mE+{r=H&M{Z$puwam%`+cf%Gfg ziV22$#kHLYL%;*|GIH&lk8_wpl&6Zxl~Am$BF0ADCNuW*V>*mg&tkEaeA_|!ODs^CVR z)vNo-5{2w}$mFF2QS{AK(VMsjt5FFGZ?&=R^xc^omoc?#o4hc~P@{h3fe5H9|B<2O zuM-4js!e_fly)&V{sm&Q=@1iV);Fc@FUHzel`2Yk6UT}FMY5kTu-9m1-m~qHBP0pRrPeFKcv`)Fu zT~F;!fTIAml?Z$Zi@yrp=_Be zUzaZ0E!r5i)7EZCA91pB~VfUmWg^k)cFc-lUk==Vnu|$UHj&UUH*Po|mVm=fCY9{WizkygVfuto@myB1(4NWLnH6Ln9-# zt0__hMD427_FrpD<3MraRuw6+hVKtw)P)ktSOrsj)IJy?fO}0za=7=ntaF2Tri5M*`yRb>j-mO-y>ZuJ^G}K=63l{8p=My$L>ygYOIaxr?KS=I8m`_76KX{~e zxSoSAs4LckhlfYCd+}!3^s6~{Bm=y&gZpn|U`TIU4xhT=zTe953Xpakx5DCobEwh- zTFM!!>mDY`!|vYQX;f;-A!vDKVR?z_Zc zN&XAFr41CUXb|nazsR;aDEeX!h@$!BPfOoh;2dJFP9r0BB*EXG__+j*%xGyC4v~cp!L;a*|3y5b`wN-$gD(Qv zi)V&EI?xFm&%Oc)7#|h83*;5KjcI#4FpN;QdYs(f>M_RoN7tiI)@8iTMF@dCtKo`! z=;VDiQdZpcq=WMx8^OSW-KS%jAphTa(pBJ_BitP0*4N{@3wY1AlStdnasbdFv&G^r zE-~}`$<5=f~dSOWkXv#zp)})Fh_mon=ylx|KjbjT_j!fM{ zA&d15-{)9My)4?Z^Lrss14$dFHrmsamC+D6<&eIS@q9;@T zCY-9zm8D5cN(l0CQ>s!Xnl3Z`Vv2bf0!1_yk*%KB({4QW7MmAxSjFbCxkbU%o1$^Z z(U0?Zcy7CSYVY2b`!BOh*6ch5W*67O?>C2L#7rlPU*h!Ra3W{#zIS9Sb8jr5VY-hQuIFr@v zE`AaWCtq-pqLp^?v37BVofWQ@nAm2fHcm6+ystD0gib1bQg zdEQAawd5_B3HK#X63Or>PdG}+R9ADS3@0tIwQff0N=m>S=P|k{l8g&OH@O7g7FeKPKKU;bE14=$b~MZs$ZU3;ydp3deIGI+bIhfKh{{VaED>k(jjzlqkoT zKgUMuu(T>{qu1##n%y}%1-RZ_6MVPt&CmVmW0mMuuXp!V5fHO11Tb#0KG~{qstc1x#0T}E?)BbE{J%6a@gV~55N7~PQ0r5+IjgrH#~=yq-vt> z6wxj_qnMG^rj#)|>4pwi7qe7FlfPJRabFT7R$Bo_rn|Zh3OnaR$3WV`P{iEUX?Na?c5L@fIaY8dR6*~eaDb

o(NYzk(tkI^u}!C%<`4} zRT^@VxkQ7k1Q*-1tyG*wU@Cn~Nl#rf>Et{^k}rP`GT8h~j7Z*cunIx_LA}!b%Cid$ zv;2u>38hTdGMl`pH{jJ;Z>|s`9fR$bRuDyt915WiY2Ua6(}W7eOSaSq7C*g`18%7= zG#9>twHRRG9C+I2h;YbZ{)Ma8s{!ASqoa~)#3-0ymz*VAu1tkh2cL!UW;`dZgKf`6 zy%Y|%7y^!WVBjFr-?5TCL5#KcvUjMvg-xosn{Je7HyEkoP(9Y$9o z#JUCAkEtraVS*5Hmwz;i7B?)@oMi7^(yLfRl1nNigQIPC%oOt;*_X)Qq%WwOw|Lay zLCp^p^UL!|iYorb5E(n5WZ6HdI&Yi`GMeDHbu=h{RFhy3rAg?1$OJe+fw4Y@QI2`y z?114zzop;KX3-R?z)*664fo$A4jsP2)i}a}x<2GAMdqe6LRo zw8J1OP`!2&f@i$AssZMmNz#QFqptpz!n#9uJ@rl`bRU)!lxqYYPSXbZ?jMlJ5WPRb z;=V0>ke%dvkCQ?JZs16Q55WXo3{LRjEDC(rbyQ!;^h#jo0|b!GxMs_jzx z;H|e$wK9|@yme$w$Q{Ui4yH#m@2IA_IY^ez<`ZN*Jd38hwl9k1@B)3$)YY*P{$5lA zXTJR2Z=3W#Vt31Ry8DPpU-aKALlW8XJ{wfVJ9hA^QpkfnQ~OubWFyiCik+{SZOTSv z%sbml>zRlf{x(;98yY-cCco7vs z-q6Bapf(=OQP|HMt_F{=L^~<*hKk|@&tEKY-n*pzfcBq{`FJ^`Mv@VkP4W%fQs_M~Fj0*4lFdF#J5{LN~?kOHWmH zDp!*e z6e|IAvyJ?3{g=(7qHG37yO5hL-s;rFzzd7E66-@WYZ~tv)!Z)OFL(CqF8Z?%(+BIp zf`2)ldJG;&YJ|tmBS|Gi-=*-@vF*oj_Vo*7h71u+0kGkR8 z+GoLmaFLByr{F^?GvKa|gH$q^uV=|ef9qXRERYp8r6s~@VMbehX|%?v@@R?<>{64~ z*I0Rh>Ztw@78nB35pOuH9+^DKroV5h zVJmM-AW*|4r*4f_^|v!UIkSlA@oI-vM0IJjh_Q_~ZT?wxEa~x&YajM+*93X#cRN~^ z^3A$LlxCmKaeey7xQ|0H!OPwvzj>I87AJpALVt5y5g%hrF}l;b9=h zFXk+r)|T#VaDv;os*1nSw93)Wx!flF z@Kurk>Dj-WHwwHSVqB*RYa$L|UH`&s?!she{_6Q(wKx%m+LqUFt!Ea)*)5;Z;5Gdw zWc0@F<)$b64a%vtdS8tAQyhit#W4!L=@mzKxo#qj`U;XK1g`%JNGeXB-z~TM3(!lR ziOu*$kAy?aMSE|N{}d0$b8P2!|8de=7b@ysHae&wJ)!3=O}OP*QKaXns0IK;oAA~w zk_x<#a>`JBK|0*HvI{zl95xSE-$gCdzub=A6y;|NG0_dcTg;cP&j9}e|sC7 zOz62#MIh@iA5f>P!U=VLAhfsvYq&_$K!hH5B4KMmYBZnfiSIHNZ*E*41p*69EC&J} zFT{OM%&8)vBoQQNeHqg1f46p6x7ZHhb2N97ZF49xHZ8vrb5# z0EK<SgQ2K0Y}kNN2HX9NbvyN6yL=9&rdIQ4SZB0s zyeKA-vFMa)L~zK@)wEH88QdZJ>|pKQxbVfp<)MiDC0o0yLAn36?h4MEhGI_5u*$s| zI4q+_Z6y24>{m$h%-pl&=n>n%_I$@G|D%B<*!7mOi~g98tgovl$1;FB=I3FdlFJ6x zaDaE&1KOJ9B;v@|mjegz*2fA1cyN5JLC=lM)VFj>0ToAxyJPG_KM|GEE?pE4LII*y zJV0rKU#!`>)c2Sr9isjfIO7;W2JbtBvqBLb&I)!XcbF?;BAIH(Ck*hM?&>R58tZW3g7cxs~)yX1dfrk`K2-3_t~Wmpg6umSg6VP?%1r+ndH>Q301cqX3fPQ-g_!T|}v#^?-w_PWE!8C4L_qIB& zwl-XE++z_X%rXBQXbu$Snf2V#fESp{$32O0lRyIOJV^K4p;L-jnS1-f!dquggX#FH zQ(gRozh^EuXy^N-m_R{d?Iu|qA=H=+MA185;8Pa3KF>vY&OwnRYl~%=B1sV86jL@2 z8l;+=oBBMGovSrBYKphu7@{SRp3I*(n6PG(X#kxw|2$$&V&FBd<_h(V1qxJhdb^d7 ziPRU*O)g`k-N^O!B4?r~peVw+lkse+yL(^kiZcZ~PQmIGl!CD)aTu~&6YaBjsLCs? z3H;T(S~I8PG}Y<`49#>jFF!#+Uv=UL9?oVk_I+N??$MCiL5?w21r&-PHMLC~UXmeA ztX5H4^b9C6k3OY#J}Kj9FBWzew9WT3P6A(RFOH89OI!Gli&%*Q(s$K^$Fvq*Q97>BGThWv()#8xGRa_{;_2{zE>3)PCQ{&74HPo3OmuY0z@rn*~3HP2&W8?i-v z1i28h|CGP`-xnethCV-DeSP(6i{K%mPNAfV^RiJ`cKvJZ!ezgP^OnY+?i`5lU0oQQ zhFO^Dc8}y-*}3<}NdUL~ zxz*LToE{Gt@(WgBVx!)nbNJJ&a&6QVu%_&Pgc7suC=k5y2R|fsT!gzc6FS>htv_rPr1ae?;HU~drcJ1(A+{q#pDW28 ze`$ZbR{4<8@Kn}_aQE=Cp|B_^r)mE-;@xlvkm3Sc1LI0mnFL{@4w;EH2L@H@7r`7R z{M83!aZQZMF)4dRMfs7yj-VCZmJWU0d27XSF&$ofY5#$N=B6I;Yo6>lfQ3%1{>{Iu zz%B7Ls8PwANkJqdMf_zniE#^W3#!Xk057TcOCi5aRs=1JTlSo}k$~TLjXcqaE^^ZVj?{QBZMoif@xC~#p=&Ho)V#yE8eRc(ZTA)2M$QZ`qfGFxjdk?Y(y%F^w7J%5iM6*BD`4x@PKSB(+!1e3e-2=Ew0%QVfghjK3kN=-O_a5ERd@{)j{BdO}Xr(k7*Wq9#~2k->DQGu10x<^P(4@V68 zsi0S`F9p&cop7R&KBSbSe&aGBs0Kk0QUw6X9mKK(Mu0cgD!>>HYF*GV@S=gu{6DqC z3@yo@%(_dpI8X4V`m|F8>VxQueu@DLNnny~Nuv!QO@^GI?Ru zm(3ok6&)v|q5RuRa~zABXCJHfDio|jfVm*A>*0SvXb{CaOKX}KrhNrRaWVt!3LjZy z%C-oIez_=>t2MeCi4@_EtP$U3!>~%N$w5TtW8>Vh@>WXYVHJP2o9{hbIs%@h%aBP@ z>c5YZk*>XL<8Z|Ev)S8@zaNQ`2HSjG{`Fu-L%AKq*G}-Mp|Y&eoA%yT3m$>G$4X z2UwrIErg#dWe$@`;9kG{V^Mh7YQGy`_Ur+@d>BogVd!<@X^1jLm%QJGOIC=};x2d$bG7Lj^=s1Lg@O*^0ODlnW@ zup1$XUN1YGo9G5zc)7dC91*hm;2z4eRzLzkvM6MAabMq>XSNxVImRF#5)9=ZEkM*np9?v9+msyto7Er7*8t3*t{)q z++e2qup+ZcDqUu526P9OU55K@baD`};Fcm52haVdiwZFOwU-J!hHF2XS=exB(ko|D&nWh7tpeg%n zMgE@_fa`SLfq~{JLnCXzcF;foIq-g$G@R)&s!Ec&<9uyk?~sm8E4mV^3%^MCMQlJK z!}@!!TpB})@3$4|A8fH{zhQgTerY@e9jUrM*1CF~y67{g*NNz57%I

m3V=}XlA_7IQ&`*yek?j>aD4C!aYwlVDt;&l0I}1my z!k}fk=qCiH4eYdF`nR{Yx3EASV5s+y6+I^XDSXjJIvaF{X&Fv14m zTg|N#IVUIQxDN;$owHvv=_;09_FMCUjk#cx$iTpWd8^d-FHk5pjNy!zV{Q6>CF&L4 zd1~NAF{ro*&srze7^*N@D4F3H&qZ_-DR92Y)12gGnlkEMB7a+Y>L35MyX9HiuhxJg zQ^cDwRqWr6AmN%H#bL$Cowg8-w=V~FJ%wi`;>vS%D^vJRyIG6fp1;@?81V{70G^q& z{^-xmF~riwCnsT1^XLvQ#F3win3Qc=FrV+m8cQD(DE+|g$MZU+I5zOaB<90y^ER>{#{%k#q}sU$F)V|QWJ-9_G4LdZu8-pPC=18luK(1imSi$D%)%lkZ0a54 zfv_D%fx=PW;X9gFfn`qW06$F1l=st%-Os2^vK(wY3$GgcT;6Xq9ebxrX}`A`Q(gBm zP`q+2P(=kjcwqEd*l*w@&xmw%>?nW*dn)-7@ zyOAZvpA9H{dNs?+=q`&XXV|?}uG=@O^zoUa37}Q8NwPg=P-YltFcj(L6NG!q)l_0(L zc9ZL$)~C4tHO5_dYwu7Bn1LIw8kqF*uP%JnMzpw?gE%%ddvr0xGG`Z7Q-y$ee6L<5 zG&wR~%*I)~IjjZyY=o;CjoJ_EqZhIq_T|}af`IMe<<3{Lv*ByLU5Ku=|#K^xkPlwH1EsEqZ}^C z-&yh!1=ouIJ{%0k%t0A@9@!Uwo6i93&B+VVwTYer+U}E~hRT)O%&JSlRn3*(F%IVs z677eh0-~|-eU&_ZL~lzv%?{!KQb+YZ0R+{U-fX87kWU1ae){{yP{;RSzvQPxpM%LR z*1RZzFlYH8kEeVh^`qAr{_=fzBj*oF47+Q!2|SK}?G}EMWV~2G@fN9Keq=H6C z*_(LM14EVU!w>5YwYruJD~3Y^dO^FEEcjdbxv5TOQzy}62gyR8xlkngXkr=A<^$x< zoQQt|CLbAY_n<8i)E{}e(3V9ir`H&YTf|AGCQ}4&Tozmdaz=IuQ?LcpdAh=brj=d# z&=NCZ_Yj(P(R{^cqYaJ~q=vsMEAOmc9L7OOwR7)O@I=TOhUG7_jy2yG2>V_)0Fp%( z%f%>ArpE{=Iw+DXtXl20$>8-?UQYejt-O9lhq9651&Ia<)g@)FyXL*qXKbG%x7_BFt4R8|B4Y$47(}LL{5l%xxwc%^EeyYtxzT2rJjB?GjK?TqJMX z&$q`KkKfl$>dAcwQjA@1f>&oaT?Jhmo=_s~_+1WW&Vs@cm!8?$@34-LJpX5u{p$TF z#jhrFtgfW2b~_tY^+YX|KD<3XlM*`~_fq4L^fTm4XTWN9a%>Ql^)>v`DyBJY z1KXFVbCfz}=jLdqZJdAqR~V?-m+=*O0EA5oO$Zz3w_w&Dc!0fXvCd@0d=1tw&4xLL zi%@s4v7IsSC0}2?%_Jz`i|!K~^&AKTFM-R_#>U3V>brpjDBN=t%oUFfO#ZM2{OHO_ zUs5!!7AMCJZHc>Xl0!IDz30r2OtAgll9(Oe2W8$5;`muxSX^%O#g?~r2&hG^e(`uLHn2D2 z*phzVhqf;YeK5d;KclInO@!YjJ<}09yw_eTev6Pt9w++>_WPg5?1~}005%S&8i#!= zF7r|Bdw#bniy*mFp2Ls9(Ogw{G8|xdqb+uu^_Kwt2p~zA(Z~7E#u^e@%CS`cAqCD5wrEx&;a9{MGc;$V_)rSQg$oi zZ9d@NT9^B(!(&<-rcd{^rTUN2JTHS)OH5HLa{`e$s>D5ZHD6j&IdZ$>XjTk6*#l95 zs@>j+aj+5a+V_|;8#L{B=ibT11fEdW<%e6Ty*ax@8is=)Oh32Zg-6kR4getwkJPX{ z-%lM8$7TA9*goxLhDn)D=Y@k02eZDr>xk|gK|ued;IPtxceR>kAQY7YFt*0G*oF-Y zq<^`OXdHQOf?~2@y{u2v)Hw+1K_pp$;oBuQ@EKn1pYjXj;R00)3&<~-{rUN>91?61 zeQ0VKI49xPihpaHC1rL>G|ZOwr_9v0qn%G|cU}b!Ialv_yN~MZIWhK;Cq)!#xNMkX zjig>({16T;v}#~MKXf#^ZR0DS`H@5ztWR~Q&}Ow8ievyRgap*{;0>U-BlUi;3kKIr zPCIGWt%F{eD`nj#YRLI04BZ%k0(>GQfkcm=z)o}kH(;U! zGOlLOGN<=b42DpYaU>Okm(ape?R~CBKQeJu=gITd&uR!d*1{OsF7H_Pf8SRe8^+3q zVX&J!cb3HV0+WF^N$@YZbGRw^wd{9GszsWx-`8Qe{gFo*pM?))L}Qb_9AK#FN6MX1 zaREF5%^Z`_8ms$K?v0IXrs*NIWKJ)rzbDwP#F*A#y@kH?)K0-x(j%irJv3bT=Q=I~ z4S7k4u~55F#0i)|x#0?H=zu^2hGYRAPD3_kreWcol!H?>@=x^>(uO>?0ultIfPAIC(oFt z@il}FPLWj&^wtI=r@#E*nZ2G)jv08fN0uSrvx1_EFV9hF4M>Iw31k^mn0)L$LCfCw zwt8#GV5|mus=TeV7m{caaTpT8-5cwOI(~-Ard3=Z**{h^>f>A0F##XK2BFEx?m%fC zXp{nWSb_8lYa~_Y4c_};oW-pCE;!Z|$F;BRXW&ggOwxzd}(9x{3ab# zv*MM>;wC&~QW3oLrBL}MgGgY}WZ3lnt43Z31&%?W`qI1YfJA`3jAZHR;eJfh29K-_ zd!uzDV=GW$ePhG_U6G$@Rt+}j1x8CZ3rH>PN#0oCkmrk-p`P`Po4MDBX+~e1X>O}$ z&?FKhs)VeR$@9r;Rb0`U5@aD8U@iz{y9Z{VCXFyU4%{1jIC?ugoa@JKgqH3<7vir~ zMAf>8+?L^SDN(KfcTl+e2HAWzVg;5Hq5EjOItw>XGtZ0qWRK4~2vNssK1;nlanCF` zFds!ePQld|Og>9!nJTU2SJSZ+&o9G$$isDcO~y3amgYGk*~tIyI~Or=XC9`ZY5Pm8Kk`75)ncd;55KhVB_~h`xIU#}JsXQ9N0~)D04Ovq}Ip z7w0A#JynbW$A1=R)Cfi)kO_4+($U#*YX%);8`IqG06if%b-1%Ay(9bkZe`zi41W=$cm_dfK~d44Rr!VtTbQcmwpMfEKoUFT8eiE z2L3Cv-j7=IN=T^azTdTbSA}n;WSNkVFvhy&o5@b6+@5H{8K~HQ-m{lq`mK@uy;<&T z)|tjPL)y9T+1I5uv++!9J$1_0<=gq-N196Go7+s0i$-yhCt~CK$frA>e+rBt#$*Ts z&4j?S#c;b%@m#n5`VQTj8$)8C8%{;ru!0yehdHBw73q$2EOSDsoi_F$qIkhY^pLG@ z{F6*}&9MU{D`67X&z09(AFJND`)=1y9TojpIzAj~cDT(rn&(*#Lk06Mbl+6znv+y} zii*#O3u#h{W(ZMRzP*9}!7xevwBjLHCc65%BdwAh$Ky|M#8dlOWG9P5NN*_7}+S>s@nda`sNWnby zRGS@Czmt4B;5Mplz-&PQ26Kps+j-fAXx72r0Rnxb6~2AdFRt?i?0YdX2+RxXvs`S0 zM8rxLUt<$Fau!FN;@LRIy^X!hO~|GkmVMF@n+4AD9m(cf$S`>G+2d%ZHT_PwXnZsPb^CPH^y25QJe8Ip7! z>ZgjF3o`&<(M6ElP{DASHYEZ^@;TUAssE*zzkv2}&L^9x9=zn)sKZBL`%8}T4U)%1 z>#w`Z)u+|q`-)j6@$NGBm3Ln6Fur*|M6m2awaRFNlRxGQbXZy(req>*!(HviVKG&c z82gqWfNu>;qNxV^CqxFN+}8xv@#P6u&h1~<-aNx3p6KV8v7XeW(|d~Hh!f2hT*_vOXZii1wa{xIKf;ota1sZtb^ z9^pfp)4W~pNo(_laKBISfbcI+$er?4QGz^Fzntlpj2c3(wMECOWmOXjioE*X0F*8} zdteT^y^t3+9)ow55#hszdFlRreqTOQN!=A2q1fm}MeYT!DpEIXW(@BVNA~=zJ@Vty!rk}yi!ZFDO=25p!#xL07x^5 z%sZqt&c!B)Fn}1!;yxt^GB5Y;N2Tn;LB#>9biZID(%UYwf+hhscuy zW$yaln2FXdQoraG-l_7{+&;0t>O2V}4IWfBrhM;dP%d%qln*A6@3Sy)o&`1kaCk9# z^0}oDs`^n0b1%~fjy)*oDcTZ38sYDZ3u9?5ntshrHc0&*nofjzBeWbosKk%XDI{y3 zy1aS*x_wuCTY_Ga5Aek5+@E@J|6)Ukci-!)y-kYIMD6W)jqwX-?~OlowV6cdJi&r@ z|0s*glbc%00`Gn^H{ULJ5z74cZ=STTDT~0y-z;O9koL(@2-@lwp`!aiivDZ57BeS-U~NT zmrwmocadGULKZpBH`2t6e7BqOL1Uf`rQel^$Nz=gxsq92bgd8qQ$j`f3v%!KT**Rn zOJ&O;5f;=@%%bC?SAW8>fU3eKlz9A7cL%=WHiI|CLuy~PLDgltAk&p8bMH%rUIW2T zM2BSZK3|NBN=V`r;J+w4dCr=A?QkrTx3UZcP%)q>RW2Q!lesc>ZmwED2G%28khuT6 zX8ohFy?um+{btM5xnF~-voKa!!l|unGd|AVuC%kgE->E5f$xo%>-JaAj95LA0w4a= zu~Ki65`kFZ9mY6%|5y?{Zlh-PNEN0rP$t~S`_bO6CBewCk;8ZU|5X|kjR6H4 z6)v)o=w2%w<+n)wYT$Iv(MkbYF73rS{5#r z5haTI1^2b|XTc|5NkTYTC0=?YbCZ846;+Q1JHv&d)RH%aXd9x>9rFm<9|>@C1{S4~ zeXG?kw_|<$sDd%RbbJn+o{8mwi(@%fIV&-I&xueRStS>^U!^yiwMv*rMkDr=2lgYH zpI32#;0cR(<$EysWZTepVgh4u1o4s%`)Oe=+V9OopBQ1WyTv~Ae>1PMr8m}pfKQN% zW1jQNxZ{g*eZe!%X^mQ*7U|aqTGu>p&ya#TZEsTsi0y@>SCU070VO-PhGV8^(E)gH$s=NfLDWdefi%RB!UEWj3YMzdDGJuqqpg^rYoX! zwYba(zrZA{M`JYe7#ytr7>c8F}FG>56Ugdg0wHM*+y2ro>mgvF0D%BcMTi4cf3ZeI4ytpXtNlA z`do|MRw4HDTKgjeR-W{b0v%;=&i-@@Rg5(GA^CA5V5jnjq^Yp8)tG+3!2Y`pxc$}p z2{YtO7y}{~dbxOCdLg0%T$il|JVTiwe_O4(yRo}Rp7q$#>=svkYtFHZJXu=8V#%zv z)nsEXTlyX&UOWq%A7G{~NhET5G`R^@nDw;3)J;l>Z$<7LkR0e^)!cVV6KGWuWPk!q zT|`+MXYarcC$qL(%WcF#`ED6|zmu^kXb}IX6f#;tOA=^Y$<65QfrGyKZZC;^0H9g- zoocnbA_C-$fr8iR$lCsirD#&}In5mxKj_+WBdfip{S5Jkub4tfHfo1N=N6qWWpwyQJef1#PDVF@6&H6(@I9)JxIXK>~F1E z_+;FMx0NUR2_%Q&qo8Lh3C%;U4RVJvqDmUD=_V%?i+L-%Uv|ntjJUNr|ocpMBR>~xR=BXaO>C|Eb*n& zHXqrpugIkwQkR|fh<+R_;*a5!fP&#;pC)v95<$n;y&?Yf`p?<)ENUqkwI#fJx`0&QnkN3psyWz&+(rs#0 zu?PQ>&>|n5cUQ%MT+i)2L84%DvRfY$?2$V&_0|Fa$kAU>?;;5hkq@(hyO(1o?+^2( zUM+~K$)(OK-gy|e|NM?I_9+k(pxY*sbt~Ks0*)!QgKM!^9<=*HPY;BKuJg4o?eJkj zhOGp#>;X#&=}&<_3gqonQx5QV!{{W-I8&M74~k5^p|6iWd)%d!Ug?ESR6hPx`1q6D z@XOov7>569%*!CmKTh{k^P;5>MJC6usdrrJ7OltmE<(OvSx?Oba(XcGKMLtQs+G9K zR#*=tZ?`R!JGy$XJC1P#JyI`eyP0d({4fC9?A~(o^;+ZGl%xl2^s!4%wtTx*YyaMF z`Lk=vXuuJRI)NnQ;`C1N$f45I_A#cghv&b8@vE_KRYd(O@h2)d;^Sw2u>pe;(y^5a zX)IT5ky1}A0spWrtKC4X>OB(`mNO~f4HCH24%H6j4Gz939uS&=TeG8>0`P)OGak9i zQDT`SLoVs8?s-n~f$Lp9dP4EE?sBA9MswF8R`)C?$TVB? zjBGHNcKDr2MmjrK^5xLEPMBX`e}KNzL9rc?mFaK>3V1Kpml&v~hHRV|>0T=$OPX@Y zwv=cX^sajY31>O2mItQRnO6O}Embqv5P)EbIU9xa55F&;)z56%&w*D>GWy#3*40y| zIeq8J6K+U%<@?47?4IKyiOLd^w1~B8^_k7Iif1JeWnK$#SMl=#F^-#OG{8F@Cm^Pb z!9!-aif7#Ms4x(^G-hVAXn9zWZT!U3d@dyQ*tYLsm*z)yb>yhGJrS& z;wf=b+ce4#%?s1n7BQP6D;X6a&1ssO+=(k{SHhaf4Vc*U<;vrgta6QJdPJT%B{eXq85J{|0*_`>S z<}_nStJ=Y+)pwp{9`R&JI;8ESG*e)R4{qmcE4)Q6!u<;4Dm*>7Yi$zn7*dxa3xvj? zP$sXkpa^Q<|OQ+V6{WEB_)x5w@ed0qiB;~Z7AJ7H}SUpIs8;C$1_4n8;@iY zKpS6lu+n=gSjh+oW7!i+ z%6X5M=4E{=NyI`LqRts}O_c$!k}88Ai#7Q=japlz$_%+W@g4we`ENMXx2xh?Dyg zkql$_UEMSdtG&U47jJwk8^Vt?eqZ$08y^?i4E!zh1wpC{1=H2S@&vhdw5pRQySeI=!T{jdEWh`coZ@V)3mx?BxXc168

SbKj0g0$}(z zhey~^=U&&_rC{@`JfR-=ae?+;F`BsMSiS33`yy<~2UqSa%~ARmy!hH)K+=%oaE4tn z1BWobVF3O4s?6&56J;9M(e62KEI3qVxup&Zc;PTz;(gz1lHo`v5S3!R_1Xe)ua7ifBnNnWPC+D^Cg+OwO-zt+78d&WZs2Lg_kmJR ztnkEbvi?+N9D`0?vxH8Eir{`x2?Ym#vB1Xb{a9*K;nJ;<_)$nXyyDLS>SwJ9j|&^^ z$H$}OMOBkkyeCjrP9ZlRqJbvUs#m6yr%5OEv|WjsY)a^4rOjLfXd?5;Ob0NcTWc*;0yaZB=$^*Wp!lpAz%VNte`B zC%k9|hJQT!ygEXf`Oc@s?6;PPv!uyaV?Qt%ojMmijZW<2e5P;bPxjrgb@Rubq4vd- z1MgJX|5eHBXA#2q)drk`-@Z*1o^eNjYhyO9-rjI5D`#gg+$nX?PD*-mauR$uLHGik zetmfMllC__qVjFg>^qqEO|Hq-h{#dNiI|?3-4Z#Nvv6j(8+*bqtSDq26bTp8eep0s zEoTX=dW6^PMlj<6U$MnLu0AC6Dn`9|9zXY|?q_P7t*kJtBdzQ&yOW-}`RyBG`G1_% zYn(fzjQ6_*AyQ8K94r^(hvA08DYf_e!Y;thi8TL46L$kvXE{|_G99p47qlDP>mMH5 z)hwI8XZNPn_HpeA+RY`JEZsFQz->zscr~QAdjaM-!$HmGjTP{9;DJQu9e!Y!z`jqrcK3UU0X7Z59$+G`P9s9l#Htaw;BT2|xx%tRo) zW9}R_e0KCsul`f^Jjk~YY|Nda$uenqDG-E4*U8(}6n*?oF*teJC~#Cb3IJOIk)*as zLG(N(Be3L6@{rSSo8oc-10LvyUojjcPaH0l+uU)9rvnZwoSN(_Ao?9JE#C zU1Kwqok{c7B(Yze=JvfT49=;Oyy?bH-6yU3)2}Ytgl-)r%T`oXeU=lvY?%sQ{}Iom zuC05$-$HlvE<=9-^OsT%&NGg)cvA6nqL<~g)$_-H1c5<5r3%CL^cz{LSJI6$q4$Sb6fJ}ZrBy$2hlgGS1l<9SmeJS zh=eM3W`>Lf3W!@upYWa8zRqYGD8NIdjgYC`}H!YPRHkN;!-*L`>M2#zA;QImop{-$;?ID^x6>O9X&ev%XXiO(z-=^>q(=FAn8X% zJs~5*l#i{@;UO6=;s^nil<=S6d;lyDi7rt8=*I=%cwLl%$fX{H$4tQOo~$gk!ekJc z{y5TO(%;tyveBN8ZDU`u&(6+*c^9BTHE7`tQec^xV6q;|`%HB`H7O~SPW|9VWdT<6 zCdrg0Q>tBNEPtb!%)7mJoQi30T53IEZ>>AdFetq>{>k4};bZSH5>c?|;TX(4(K-!i z12<_a^>6O(PfzRW)6&R4cC-5XX=rMK;k0_@FQha_#y@;@^cC}pyv-u6Ta2@H?@<01 zc06PkYh6QW-`{_BApdc6JYo0zb`7La3z{%~SASbVCIzi?H_>eEPv|I!PaK}yssbV&cpJmF` z63Qm-9e2`x{#?RIm_9O|tHAa<|LT;PfvH*O(el6Li_lDQhTb)jQjNNI7yf0k={@Cs z%wgvYascqHq+1`5m-z}=)Rxvec10Y0M0Thz6UX))$b)03*(aO0&2A-}f#?)C{ENznRGi^`VfZvQD`8lcEXTYk>N_FUF_+DYsgL|=uL|b-b z-cvc2A#Txxnw4*-S+=ub#do6!i}F*YNfY!DP~aGi_<56ZfL?-1g)KPMZ%359kxu)a zV7s23!i25QdE6cyFFC!>n_yX<3L85KC^bwHOtEg(}|g%A}S_ z&=cc|BKMg;{)Bh&d$rW3?~zx3{MmiBQ9OqZEjiT!dlOS9K3d4GA0Hu%L2d-!J89wU zE?3G(+x-awqZpzg(Y6rz(a#)31;qy%k2$5{;`#Qcj@Q+Q!;DyvuO{>YQjpa+mK+3) z!yh0pv*H^~k4`sAl}1b*v_7KD;wpT-KMg=E2l}~~8-Jnn2$gSNf06E@PBV{@cFp|U z0!hi}ewuCC0(Vzu6sMdq3yw4;mJpv=YQ?YpW9YlrD2DGWM)?aiR`Sn!Ul*%8EzErQ zv8W}{MuzC|j%(ZmlQ@FsW3~@@%#!*0_uW>#Xc8s-Uz=s(Uo4heyb?N1%1_*MTgL0+ zc4RktPXd+l%b!e|l5Bl6s9irUuIFV3os>WN7swJJh{ky0yV+4k6cM_xf6%@5c^zD0P z{UsZT;5ezqpWHh43TWI;WwO4GJ_>3G7vhb3e#N1#b|}$iwKq=IRWhOHuBwCzqT%OR zg2%p^ZaK64kpzAcHE{#^`gD&h3cun`{)%02vii0-15jcC?V1_ni}#aIpdfD==;B7V zy{&;1ZCp#Nn#htzFl$Gi(!=Nh-TcIs&#woH&I)HmO$50b0XKFSK>-F*46X>{sfjfV`BbE5k8qiCL!}KRe{IN`g#hDxbo!^p1e30q|WR!{D+vJyZQ|l6l;Az% zr071_X?!lFo3)o6`wksw^E#&b@#Qq2&k)rx!A-Q3QseT>Lr9iwsHHKk{b~L#f^$r5IvKxORvQ>^Okp%~cAa9OKj|_wj4(r|y?;@GUPq3XVe2R|uO%zI33< z^QSL0EwR1AAyKgwa;dh(lsjLDRtSKoC+IB3!Trl|(x0k-U!E|Zn(O8V?zFAk#*1x% zHA4H1XgE>bGY_^Y zbmUgtHjZD)BNo75i@Qqwa&YUlH7~Gjd4B<+`b-PYz0a_8(h0F3D8r(fn){5FmfBJz zp=#P0Y;saA;|tCq#SQDfiO|^K4ni%QG48c$N9a&Lp8@$N**v39Vx`6QT06=BfoHZZ z(yrAxgPXjmcyUi(hDg<(3hhrj*Z)mnEhMj=cE;|k8q7oyrC_#SO!YF8a5=;cm{k+6 z-c+zHk2_1Qn4;ILXEOTEmhu1bTURY-nNP0kdk(vtD$^?*|GPDu4caH@mLQ5&P+=JN}zMvjglS4hd5R?Ybtx4JklhU!TWl6AS=6J@xslQ-H~;`$vy# z9CQcg!|Sz98j-b$-Qr-()wla<-0W2wzFLBg z%3i;GaFuz47WqS5_h&u+1=RzB_iiE6VJWU;cJuu59ud2coC<@-ZTRk)QQ5y=utNfm zyKZb{tl}^_hf5+~QSJYk%#`D93f8YNaxXpn$M%oA+fpH8cy1xKjhLq`=U4t+09vQj zZe*&GGZbxg)8~c&Au2D8-iT|G4+fwAg6s#*i$@*c=1TXJ#X^d*!WJUgzRhMLWUNlMoNzL?^1M9>vYust#`sawRpvOB5iv$ypM^LuqEvDl0m9Hy8FujL(b6yDOojx`xIkk+%|Ex*njQtTk2eI zN+)fsj%p_M18Ro%IS``BNwfZ#EI%6f=83~Ki~C__?uZXpbV#n0ndD8~v5u6t3DGh$ zDkEqq`aZffoCT#~It=3oNE|<3D?qn< z)I={h7-+nSylq}k!CI^tz?OG*sWgZF`NVAYRaNODlY)xq#%TsrTAoOfn*&&(jkWF0 z+!-5o%hq^1;W7F#j5L}wn%N)tW%WIKnf$LEX-x+=;eDg+dUE}{-7$spULu4aE%6w__265rB-3bkYk6Wle&LIBPBHSgzIa&YTEYf)3k4W=X!2$3KS zTbrbMQh?J+4R~z}->PneQrxx(z_tzp7}C1E>>*KuAGM8@t9C{G4)x&}50q{1sEd!pz!EIDCtY=@mh|(R71>ZOW;GRklD|qaWHZikSO}5uN zkyqnY@v`ZfDZ(yIi&ZMrD)ru(dh}-tlzBjtfyWF7dwUvMTFGWg)w9`odCN;nZuQ1s zO)%t7?#0IKTRH;c)Q5+MQ7ETKM_l}5Xd27<))v>ArJpZD=3DN;vsu;?^o+UO7Y5NL zT8~+<`+_%yB4pnT2)+09A-R(OAm;YB{AHH)IBVc6Y2;MW+DMiCcDxr$4M)}pBh0r& zhJomRy?0PKf?%k5pL!NODCu>tC3;aByMU{n;(f*@ys3^-OHJO9!ZW*P;QlNEfw;K~ zsW;}t6|FP`Ur%Nx?VmGsb@h7VxDzq7xy8i_{qiZllg)wcf1r#7zDn>7F?^Vr(FcPa zUh#s=cipp28n8dByM8u#c)q^?e3iKh3IVr@w&*jzx_Wqwj*M`rihvYcjF=cM2wm6D zC|r<^90agXsz56>XV7Nknw436DpWig^xeR% zdk`MzGnOez3U9RhTj~Cu(%1U`vj8CzGyd;K!xGvn4qDeq&HnB7lL?ExTvq;+w_D9I zfF2wngt-F|kiPKk!79jWy}7RlFjXH+%&Yku*JhSn-G6w?(XO0j5p!GSb1KNYl(ffz z0P>JyUoLop3sG_2gN?6I=ZCKX6l+Fb+?SVqsKWOeeJU^{aa05q1<^=fH@U}wHAznw zPV?eq0FS<91mB(UWT3$L)(6_{bBHDP=4}2A8-Bv zdDK--UprnrS>#AW9=FR-=EslpVe}UHD*{n|%Z9v)UUNyfC`sp}numJBPdDuvhgy3U zTJBGxoqSf%T)Gz*azzg>;vy|ON z#}8ofFgMt%{4xF2?wKvuIiS(E?8|QCU54qOeLS3b^hPb<-P{w5P8T%;4tDy3Jm|k9 z?eM3oX<1X$B@|b$kvOyol4RM|B6wc1!hhn3Km)*{!TnvZ6|?!FZ1$K`U{ME=P^ujI zoQ5o!opW~TzNoz+{QV$x`qXSXl=21jV%U2q4UXuabIf9Vp38Ag2O*u$b%`731*gt3 znF(!IbLu;Tsy6dYPSyBubSWNyB}x41i>qX^FjCN~B|B>nt`GJNqr;XstEM!LX92h$ zwAjm3B#3+(D^<=_HZ1g-2L*s~u?bwA6xXNc*Na-cH0A=#mBDo-1&D7z}i<5Qt#2>l~tOJjXyx2mPvVR@CjiCNhmP4NqOuj6#4FbG=z7|SY>47#+VdV>Ki-CQv| zmA1!q0U5}&P4-G)2%D7_r#s<*=1o_^OkBp8vjom80G)3LqMt)bMZ6m}F<%s6Q>L0w zc zy=?5;s(2)Z!A0Q)+L0s4L@4$W3&X)M^4*hK4<_KHJ)m$Y1+aUiZD*RICyJ3o_<2Xr zBq5&m+frxPB#W2`UX4G~Wkz#o-J$_U*-29uSZ-1Tv4)5pUikV8_)>%%`IV%|#hhen zyUHvh;^xE$9q9Y99(kx1@i_n)L048bazDOclJ@LLZ*e)n^x-z0dp=}$HQ{&nk@0O~bcp?f0`vRUzAvG> z<<%=Kr_+JrKohcS1-}RWadc06_88LVVRXDrXpWKpeXaK5-k+ozY$8jUrfP;aBx1~^ z$^Ms$`VWkPo)l$pjf(;A!!eRn4K+6h8ey{1XI1D{peX?8dh?C#Rx`*GTtqR z)o35xV9*SLr>uiA8i*7th12l-7y(gR5ZUETRe^(iFqmQY{GP^EMMOekYwT)cV*~6L zs%IDG=TR3omHIB=EQ96oTR6p{mZDP*OQn@ll*lyfs;0{c& zN7-?%mV<*ssUbhvJ5FA_f@x1PUK$fjq=@1ry#;;X+!4`Ly1C`$<#j(+4kyFD z`h$L{SZPvP^_3MBV4(q3ybmUoRJapmkRI>IZY$6gFBm08dd>ZHY4;2(T%luSWpUBx z*$rq#@Z*Otoko@oXzT!`8H0^w{^!PE61#x#@Njoe#tL&CPB1EwC=z^&z_Pek`;$W%yHvdlic3g`n}jJXoe6FkR{06 zeEru#`KzjwW_qe<=%^IhIBLK+Yiv^+(^0w9b5v?Ur;+bM#rtkV>Fax)wmV6U!z2SJ zTs)c}3v!EY6>{|)tMi=pE4H{)r{>cO|8sh|*2uWU$#nhCq6WUX!>JdFp>T34qCXb(^{}{sD4`w$_JHgNfur ztw;NEgyGKYtOki4UwtUw3HHN(YT==;28xb!2xd6Zjlt0U`4 zbW3ZYm`ZKi-`>wqv zqMzF4p&6Rn-~r;udM71V8I@!U#wrtsCqzP=suCQ`XD_><8JLfc3{tUdTkXI0y*F8u$AnxN&d-=?YB*^F^V< z-CxCO|L|{WbetzWfVoz#e8y&=+?Nbj;dw1N5Bg)0V2M8wo0LFE-M+YVl{|@Y^%FET zrB{=1Ew3$aBAJ_)m^}0^A(lO~mJBMUfdKRgQv~;WPmEZY*`Rt_dMph)IWe^{WtgfQ zop!kZw$OkZ z_#lx9`q(#&&IBc+<3Nd9$AOKg2~p!^ackrWBcN)7krI|e>IRqx$(tlzuxpoR8!!1} zCtsg9t7Xpa;sWesKtkyj)9JK}T1S;nqzQXfK+`vuuC`vB$zs} z0IEPcWZEtgKlAFmc|uSUH4o(($fOP<`d%RhM9l5SanMGed%=Zbranc zVq&RU^_lDmCJa__@ZUE>fMB}0idu6=2UEoXNXt4O-DWGqt&iHaOrQv+T|2Fup{ znQH5h`M(~m@SXCPzbe9?bpcS3BjIS;v{y*|cgjLd1oUv?k|T@-bOp)Bz(@rS&b|c9Kbs?*leM31KNsw*Cs(bS2TKfuS(6 z6#*fkgt)ku77Yyz07(!-@qKSfH#FT|6O5bV@ZntZ2g^)Yv2|UssUW-?9ck(3=NBD9 z=2?^zv2hE)#9DpKaiR>$UwffrkL~-aT4;E}bslBD8k=Vzz_LA7F!TirkV4sd%0N=0 z7{D6}uAP8FT$Tl$_OD9=!StA3w&MU@K62%e?SE4Q#&ZQ&V<})x6Ih8r>l?A6!tt*Q z`^~8zL6e55jBBtF0}Xmqix%AxkB|@ysun1axWU z)!S1SBR_1RG>O0Rus#Ku{VfOMFv_RFyF29|`93oy~;8_x`U{G_$^Y(VX#HV+yx?&Q}jRih z|Ja56sM`+ip~A%wvGe;RsJ3TdE1r4nJB*j(*f9LBp$23RCe^a}V(#3J6+B**uCzaA zwI_f%-VJ`!YcTQ&uEzRR!_%kXW9NY{)RC(4G^Vn9n@HC1Qw)~;B{4c6ci+<?a6q=Nqj*CnOER*1ui`R-Z(*r;vd3O}Njc5}8YKm_TgDDw7irvI+F?tEwx zm9)OLeG_M149!Zx>3Znm`ssXtNWF!R#EOdZqB&CRFa>I}m`7r-S(7`rtBPfLmiQ{? z&!$GU>Nj6;kX0ow>2!OYA=+8)v>EYTlg3mx;F$>9Yjh+HqAsT$oy0DW(q7;MwSb2J z`MPE`5sdHojLg=;N!sRkj7X}cTugWIwp=9<%pv?*2;k^#lDenG{z!}rc+y#{@pN9r zeB`uhOa-rV=+5vXH0n0yMl|&*a!&Add$CwC1w9@*(zmf#a(DJaX7sI@6=1qeB~NSk zr`tww)Qa6`+n4J^;BZk_NT9#~C!Fp4;FkJuQX(?L1l+GVk4Mt!EK%BrFSOc<`Ig5O zb??(ESJlq5hsmxo*v#kYos0OdGZ6*U=Od%LEeOL{b>Obq3%Pf@V(hCCHk(~f`)?F3 z6Pa^8F>_vCN?Rv4{Yl0g5cNUHdtWA#qmJ@}P4QxXV^X}JdC2@CuMKLDG07ATGaM$n!Kz_1Z zDa0g0T8)_)T}0-wCBC^XoxB`@eF~FG1LKugP)pa|ixBa)FREhKpKOJcWMLlq0cJHT zDSPt+54Byu<#XhHw8{&kB4j?9QvI5KWe&^XweU z{OKJ^Un!g}g{8Xs%Qa(lPM1v2(j6ymRzn6mA61TEt-TdG0LH$d5y1PZ1Xky$mKX8pyUd12@%8ZOmKHpBs%BD^EN(V-~{|9>guMb00Cx840rH$JdB8Z23md`#`T4|JX5+iEMD4c{nuoXq=+15{X`}EB`60A;Y zqW$}3+Xst1*1n-O!8!!du^!hoD)3>1RL<>^UE&rW+hc1j6yXtb84ym@V}r$c@&yfc zGzkIDLMoT5U&0nGlTNPuV>%$1jIxXo9SmQU#hh^-cu3L-^S=X^MU=#ue>a2ooetg= zq~7-m?Ox3NM-%_g%|w~BED}cEOa>{68=3S^X(k}AV|&2k?WWoFZF!-Nd>T>1PIk*n zffrxH=!syd*-M!%)Yy4~os~;56;`|E`FCnXWmqX^HAS{Dj>DPBUW8ogdaHu$YeLWZ z*WsQ+<4P)<*k2@#L%$yZ1-{A0Z_20H_Odx}pG1HP8Qe7evFy0Hlpt+1i6y7JhMkJO z27g8~Xzex-@V;68mxb={2_X4J*7wJx6K7{{e-*0GBe$)@=#upCIKM2;%@sID`;pUf zKWheEcO)bvWM#Gb=r}mIyUC?2Qf9z0)OaVEHB+(d5*!YHh5mUbq(gfko55bGkhJNO zUOH~eB-Gv26)ZNSI3SmYaZr}vqYDm_qRw?|RjKx0?B;4kQW*mzI3RTZ!fY60PLS>= z$XC3npwYti+_G~$7dJPU>kcHttE;LeF2`;#UM#B@PyGH(mpec1*h6DtW|o_o31(w} z6d#x$Rmb$-N{tI;9Zr~78N0xhPsWgyXOAs$KQY?*s5Efv?%LcAg3L?7vdHnA2Gc*UrqD#hz3x z=wjX=eB@9ozpPPxDOcW@|b4|WF8&eREZvOsT~7RRr`Tsx(QA`0Q#HpqpV)$^}1+RuD&)i zT{NaPRJmN?G`6_@(P$_pbJ+b=;E!kIS0UFtH#+Q@Soe0u6{(LN;<|vpUV+a=0Ajpa zfqCmafxhK%wGIQPZ9_)9LbiwEfd{Q(548p&S3tWI&;66CJL=&~^lU?e{pt=1^5L>d z&kTx_khYJLT|X@_zoP4`P85QmaKk>^Dzdz4W}oLk#DD;5Fx@2sVtp|lUEICep*c}6 zVCs}4(5@3{Ei_Huk#y@z^Yn|4dQExK3K~~f??ArJwOLmy-BkiOuxgwTicp}Q)5^4w zJm-zGRTTm5=63s;U?K>NYJ;X>WB(kzW#UJCPtSRx z=V=fT{l@ad?;eA=n35Dxzv_Ez4F{9BgP9bjg#b6)kW z$e(Ym2A=%(+FgBXpk-)fxZy{KG;~HjGtevDQV)m%)ycTj7^`E}7yBRMcHF1(o&&atbG%d+f1zxPd`x;3p<#r5Z zzcXO7;rPW3m=FzuI^R(*@wT6W!~MbV2D*PZA>z?#PS-!x zC1cr>!e~C{6+xG-%OsB;^SmLn3g#=N3Y&+^oF^C#+XsR^sr(&DQ~%8OjF#1Q)XiHx z$@yEd0$7)FC%Sdxd+drWbg$QZu7?jhDt`Sih?fDtuU*N+U~=xz2E26z#}qHzq^tF_ zk75lxDdAL3|779E;Vm4R^i2mpX-CFP!#$@|WK_P$ zZPLyCRFcs0jf})GLgTbH5Swhp<;%k?wKmPK{;$iGyQT2U66FR~uUyD#KYuVzs1(V= z&m%qk>9_w%BFhs83FJ@JnmZpNFKBl9t}r4)G#US|M!jrZfBE899!?nPSFdwY70t*b zHXGjOjftKdnH~U3>@JBLSXF$o2RZ%>hCJ?EWhnIyB_s7l)9zodA#?3tV$d06!l5831X9R3tM?HT+R%>#S>H4V(aN~FdhBT<^Y9@Q1)Q;$)tg;S;(|^|{nw@}_H9x%G ze>)Xu@&#)|QYkj);@~&;XarGYcSwialP9VfUZ8pw5)$I#62l{qnvq{F*6Qf>u2R0^;~bC#F-cC zBDen)ZGnD40NAmB?yTqM5^)5CZ<|c*W5K=-uHFaIAOfEfM{+;bEx9Lv44z*_{VQ0| zQ}F7FdRy4@k4$y#@5PX|viYTO#ivWci+h1s>+9>F#5(ng%!T{|7>Ci*?;V-r_Wj{Q z_+DDY?Gx$A#P;}ALB4OlNZk;^_|+&3JI!u0VL#l)wt?IJtKZuqv?7eXCGjmL5Jt|x zVuHz@RG+k3M!8SbFQU}3Xo)uwdfnQzz_|9!pBx1uj>IeJu3OuUay=|}l>)@l+xkX19AVmq^Y*t9gdT0d-EagB zE|owVy0+R5tH8pLj1O{cN%`l|a9dirXmb;)*91F~Euh<=EHCSOz3cwIpdj7iyu&Ek z>J6yCjNc{9a|Ng5qUH1)NOr9z1)Ny#K{BX5E}wQJ>6YTUZ#T6u22QF8IS`TIJ=Y$w z;2!#9YfAyO&>oxfP?K-e%b-JKgIh_3b%fG4y}w5l?{8AH&OJ^Wb4l%!7s^4!a5q!= zxHQ!rJv);qPd7lAKnvd+-gyxMTqxm5n?H?UvTfel zd2zQUYTRd=qBO&bfwCNF3lJs!3?^s=H#ex@wLI8;c!8?1txZ~S;rO7Wiy2@Atdef` z5bk+OKN^BPJnXgkdvYR!SFVDIB@+QULb2v+*^&~6l2QjQxW+PjlCiGHa~IXqo!@gf z%wCP>GLhYUk&+bUcgkrJb!%_u$_*brAC;@PsVv9UbB=#X-84gfDJoD&VpH6L)&>St zk>l=3jqUqmxJY2T@8o7Yw(I!8yd=|FC%qZXXt)g{Dd#H(lDxL@UDFbVD>gyakDXs#(v0&+F$-CT$6|K zD(qp$bK=@lgOr<6qvonb<^gsnpJ^)WvDjuuCg~mpjV&xu!Nd6nUn+n?cQdTo^(p3a6HF~mX}4I99n0V=nO2TJXai5 zZ~yJ92lZR)gN4pu!GQ5Jl?&=K0U_q1c@Aoyaokd>$qMUXk?({#wf3+Y^a(oMm-H$p z@l#2r1je<7Q`fNKFZWR~qNW-Y^L8`2 zg|nMcmzk9P(`439#>WNb9R6OH0SA>iv!-1&G85_t)Mp3jeA~Yl3F+>Zl!m2y zK@p`JT)Mlv7m#M98w8OB7Le|I_nG&7e!rc2=lXAF?%A2^ob#!Z!PJ4TWs{%uo`~AO zIM>KicVhs>aakim6~d``J-NPA{ z*E~H;KODG-c5S&cVJc^si?lSRRJqdt=jv4wE*y0>*<}uHvT3CHn-;@ z^;$#HT!|#aWLDP7(;O0tlRs!Y+}z?%wbWEqF&hpL2pc0WGIDZyOS3W^|A2rI_VCL8 zfR`;rU=+SKLc++lkD|2L>xG4cPkUHCfRBPE*^_ckkB^V{_BfE;GGVG( zd?=67?Z=>?AWzTa+fWK+YQlM-)Md7AHr2L4agODcz=b$mouZ@m3uGFX6<3e!WU?`x zVn`gy@^Sainuo;|E>J5pK_A>dHOP2 zKE2QK-14{!J;gjYdQz;Lfz=?M180$QHMOK;aguBjkYyeEh^|{X)|{(b$I60cPTujo zxcY-Q?Ir|Z9dv~5q8E`x6&P|Vf#p=CCMFPyw(W-_-8l*u#gR7o6JY81!abp)fx9C$ zaTYo)-mGl)v3{r^lI55)tRTtoDZZ`%cJ%C#9f7a-ZyD%wEvztRwi7*>V4%8e2T;scF-?i>_HfL+d&%<_)ByF*J**E^8o>6-g((jhQqW?qsx| zrAkvu3M?NRi7L?63~L4t_wFWs=+GFmNFB6iG9In6X5SlNn~YYYnL6-HO?-9fUqv=f zPG5^?0G^8&_h_0iCKymcR9jDZSk^U;THb^^%aBRAVOfY4h zve<|how>c(#Gg0C*x%r$y48__79xlD0%G{N`6hC=ciWpUjphcw+bmJcq%>rGuK(zy z+klDuKruqSkpO;QsE9UUHFZ;Q3#pj^_a1Qw7cTXRlS?~lHfSS6uVV1T_h|sDi5HUE zMkk57IK7DCI*HMLvf=7B$l5xyTQTNmTboO*<@|#*(aSk`a$SbAcWsLp7Vs#Q0JM3twT$uHrn#}QkgS1 z{tU@CkxU9aLz1j~U8j*My|_aY%lZ&(XPE>KW{u67x5eCV+=M-E?{?E!26{FzY8Av zFMw`nFTRrxp1sFG&o)!lhVA6;&asyoE|9V7KS-LqlGv^MNOd$(3KU2;&0bF=pLxjg z#}~d+?(faL4mRM#-&RayRqX6$dk6!ckzImg?)U9IbaN7)99_1pF;njL3+XAJiqdkrb?FFvVm)DAZu(! zd%6bgB!?x0<>BF~`JhE?mPgF5H)=v6!9QcY<(6vWhbt2|d`<^q&-%qPX({J=p}yQ>N9vw9>m<%c}ecX1Q^&Xywbm(cz|I zrTLJ8ukz;Wr>*;!X(auQT7_TVT4jEq)f_S1ebWftd%0C~Zl9+3pJN)UFWqPNP`)(T zkvmH>T4hJ{6N2CDdE24B3}N3*lf}EO+@x9dBm@Lz*VlVmTgf`V-`(C0rw0TDNnEoh z*$I#QC<{OaGK^WH|Htxc?kz1{Q5mjRLFIRA1wsyfadDN{#VV}@br=3T^nMH7QQZhK z+6a1lrWV2~w=bq>0zdwye678dR+VX_m}=U4+0H!wI-+A}8mUy)5jRFKp(9?_S5p`C zf$fb6nVv=;J|Igcw)!m?-+S@g6XRahQSJQoq-dVUrx)RUcXxO8pfX1r=JAl^7mj-d zN<-}#=0{&I?&|CWXjlSX{8$$pPTA~uexecs;a0=H$TDqi zB81C~{HY^izbH7|=E=FR?v44*X&Xk*vj%%jkP&a~Vi@XX-mF9OTSSkCUquL_`>tRNtBEajd|=M`QU#hVjye`n_&xvngmd#>mzhb85TO}Qb_Fp%qQn&)^Y|kI zU+F0a^Qo$f?V}rJo_dXEw#WD)9(=q0+zVdamErr(KQ(xHaSTSlCj3T%_&R8?8%zAP z2}M9n!hQD!@Qb6xw7%ACV+^{ss(bydPL_1DF)5;`XH9{GQK;^95X$KKJoOF|46n9B z)`GjH)yePBjurUPPCR0^EV@L@l~!C3&mmL(buXM0ddR($bLxTyxp96ou7MD#g*ia8 zKn2>vbd5uE6?vQKgdLI(@wKq0fE&D?aX*9Axi zY^6C2Xm!z9#ZZp=8L~SNB;CFN^g~q}G1CDBB~e#yyaK=Os?p3daJt<{t09W#r(ep|4!mX;(G!k-7K1|z&H20)8i))X;CS3>Vi$`&BLAF_ zGFByL*6-8-E;2C_26|xLM1>+EV_N@W*Ye@9);7q$yi{s)Q$R!Rhtt0@uCDUck51xy zo`#^w(dm}C3jr~YfklrS>qIHrZ)$7w?GjN5e+}C|9yFixbY)y81O{ZaFX(mb055AV zz*W-rZ}B%OHWTDGb=T5p)fELkG>NXh|I47OF~^hu9A_+ASNOq1E;cFavVVqh+taKM!AU zmjjv02ZiAtYIwX|d#I2S?I8PRVo48&*)g+{TS%6GBNoyJN?mI^J_a%(0`DcH8Jkd{ zOajH)9?9!GaDTv{0XZvEJQQ_{|K1N!6P!6Xd8ZF`M#qMv3dTYH!Yb1!?VB}UR4Xb= zI>)F}bircN{;K`sl`x$}PHb>Ou+2~fiEAdv-Wy0)p&0u{<2`CVdXBHl#k(((2|WWR zMVGKwvZo(jfoIAX;LGU$5ZiKRx5}G=f&XMvx!FiFJ>LB%YK^4tjc}C9Igb(roD|fB zR%ZOb4K6syuJhiXIc1kyfd)MDg#?`PC1bQM6ag=T$s`&XQeGVDMA(miv;DIoI8u_J z-jZ+Ar#wjG!W40~1+CNFa7#s71nCup9F*2Cq~iO7OF$*n#vVv}iB%#S>wl3ar`PAz zJV~l>f1j+UAk+|Zg5AN@wk~*%I1(yrx{1(Rw^|C}qOAYCe1fJst4{2nV3Vc=>@l+v z_?{>u@cEM~jvRS;4BZoUe29Q0$G89)li*di6U5O-ar?t!-2Z*nrYPxN8{(ntJ+H)Y z?gf73k{whT7fA>p09?8_ofQx}A(**{RjE?GF^Xx$^c{S021w`=_#_8lFW=Pu`%LC@~G;B<7Z?@Qce;*?mg`D*fzbns44*rUbE^p`utXsW3L+!_h_LOKwEg z(KRu7-lWm^IfDaVvvGqcU0&y?Tg6PDQUX6RE32yb28UZex4(lNq<_U8r*N4P^xpkh zc@m!YweFKdcJkaWmCxrMog6Qfa?$KD`bABP!r$X|MNXr$&X(^l8(dRiy-skDd=zZ7 zX_0K7W=|;o{Va<_+Pg@g9G|&S3F*0-16QMrrxU`KK9d@UN&o0~BJiS%r{-gV^PKvvTeAjat&-9w{PNyme7+m`zCFmPId zgLn-U-?~BcO~EKN=A+7STFO4Q=S^{t+3f;);5v@6cIOfju3DGQN^iWD?H(^aRv0q4 zcn5P}B(EY}pd5)2|Dod|smwXe^NGauSx*YO-39!&yz0m7zKtmP&jON!5M*S!s<8_D@E_$BNkV%x{-z!{fU zLPb}xp^O=!L6}dD5MrQaMq&@4=z#3W53CqDRm2ge)*21p#p!vLRT0pRTytoOWBNVQc(E)==uzpW(aGvTq9es@qZ{QTqmV#gp25fu#G>I22| zu_OU8BDIFWxA5CS^T7=vf9XYh#)`p9Sr_q+Du9hUD75X6Q`7OSMXdSvh^TqaA4>{=G_C69l|?pg zO_Dgv-=Rm-RVO&CBg7 zzR!6AIs>D#XPoLBXFCrt)3s;J-g0vr@^9Io{_Difp)yIHiuuexoBn=aG}u_tbXhQ; zedFjmE|BtkrJ+ZLeX79MvA-X(ppCYWr~n{y4`CVi^s~#!tJl#{d`2Sq(-idcmZDaw zUvudjjZ=A`_mkL2fZmoDU6n=KTs8f(T;mx6Le&pqrfOQn>rQy;_&j#XR^Gf4y9lA$ zAGX>soj?lG2p;GiDSRO9r?Q;0Bo`XIS@labs6clW^VkyUvNbLjH_Ce9W_}}!F_gLx zZ3B~S+(W0+IMs10sYb8eCWLG>hbSF0BUl*H3I)W-xurO+mtEH5xbQd?8KKm_h&*j` z|M3LHmj;qW8M$vi=QObQE-sZIV{iFGNgFBL2tqE(z`s{n~>&nZeaAbl^##sK~wT--GF}E4Fof{<%jr& z`)lB*>to6ty6gV~d>)~4JW5`?qvK9nZ>PBU$rIOPqwzm?VV!VITTGwO_2Mg}MMJDM zNwn7tb}3*!(Gz_)d0(W#e+k1dJv7R(y4-l5!4aJO*-T}{LdN`Zu7&*Gi7FdoffNN+Ws(F0fX8{4ma7js9&D$;sgWdl7}sPj*lh=F|C7N z74^j(*F;1|ghV6acJfx1tXHor1HbEw0=6nqJ+b0)na6H~Ly4=(BHqi1Br?B8y;gYX*1XB~QB#J)X%|9)py_6brY|4K`puGWn2Nnrl;BPQKRSdnHWsi6w zloqQo|A%0BQhII|ArAPpKhUsE_yVG++kNDYMm6`vD)u8wJx}4bTt)AAtQ>(rxADbf zc3yFoncY$D_u!qEuChnIoVe27RaP3~{{!2YjV7oWcm1m0JQ4lbF;KDEX>svlth&e= zwDjmpasBLZ#C1gs`VhhOplAgOG&_#tyka>H$m+aE1~W=GnH`i(1sk;yC_f3p zrj^i@z{<4F3`o#Pptdl|Zm6ZAwQ@^9>gtt@5u*GEf-~5AE6~9w5+{jgd`|Ywc$LqB z=NG-ezcI;pF}MKjQC(DmZMg8>K{lmLjDmDQ+>q6fswflE&dH7YQ|5~4)TYTpMQpC zjcRe!R(f~5m5m?TeN{m`OqA^R+kd6|PqJLCX?E)yC zR0wb!1i94>V@iZO2kht1TfqTRO4tj$NWp$ZtBTSqzOKIrGSUW5Nzym~_zjhGB%3+2 z7Xn~q-vx|oi^*%fo^gARvQVj<`jwE)tjKkdl5L}@z42{Jv5m{hnsNGFrs#-bW3Cc$ zWw2(PBt`=A-v+cFCJNjpb@trHZ2kEc1OSPFXb`~`kehqH$=lCqkGfU?5NE3T?caZQ z6of;)c#P-IzuX$nSW?*Q)orUy<2}3s$J))NYf^1l7@tKwbsG#)wM} zecMQeFF*iH)V;a1s#2kuYb-^wR~rUZjxuzJk=cqP*w85Gf-}V4jV7peYA_RuUg^I5WKYB`K-Nmk@GhUoH0$nc~yQ6ki-;aVh}`2aEU-YBXCKY?b*W` zal4+mWro_^cw1X9`*fSuxD)RN ztnNu1eO@4B#)(ZMO zZd3kjTAqIuTaNY6MhY&}x;BqKucoh;EJR<7I*D^C|G!oyfgibcCjT*OT@210hBcT* z;qgu5g=*ci`|Qj-eRjac ze$19syroWqAv{~l<+TAQ_TThxG?Bce2UFbrzk{(#Pf%OCLh~tH*n6au-1iG5h8yic zwCku-iKmH%^DB%eLo1NUuj!gYG`n@eK$SL8Na?xqXi)vn;*k8Mw6Pgmfjdhb+B_=A zgy;Odv0=LgS~#jw&?A6VlKb|JVXbHQ8!oBU_LuD&U#jAgnVlT5Hs18Ezi`mDx^o!7 zv|B^LeG`Fe*iu#Xe#)c?)>0BBwWYae6tiTs*&hR^R|65o|?xZ>bj zD78hNFNBg?1r+uaEq&c++!f~b1)@-y^m(@H7$iP1I@)dkCya0styz$ggbJ2f=Smq6 z!BIy3aX-e$ePD5A6qG(ZZQok~)fKb~Bd}qI$o1;id*aZgAib>Y_AuQy4G};kWrs5t zL%@=LOqQT`GnEoYAeZv@>s29ddC}sCg)MQ2W^aU825(joYpJk+SXR-zN%Qtw()&P0 zc89p(Vs9#uVsaZFl?H7SasAmy{g^J+2M&M83(^nYbK5>?e5Dw1%Pw3ZuTLmq89$_G za);j*m_Iir6+A+)Ks>@&!)nlcQaG71{i7o@+d&(?jP$g|fPE^~a<|@pMT{^$I7@@) zTV+iil(I;Nk$m1sq2VLE)%RVk9Pr*&GNFjbP>F`xthv+a4V#aMdbPZ&2mvk!Dz?OE z&gqR-9$M{oq@cbFWx&d!WG;aS{q^@>OM;e8=2f|f(Bh4LL!*>n(+0fWBlOSHHOawr zL5A(z*Y7mg_a|MQYQR^8H53844X)3PY0HQUvifcao^wH@!_>Uv5&1ssYZ|=X|3S@b zi`a8dZsQrLD`}G?bixc@L=b7?T8sByjQ$U%V{w*)9QF=~w`+7DRS>%~&_Y#{;Kp3>y0xN0_ zX56>w-5=q`S^q3y(l5WGI{SB!e0kDrFbB;!qs>$NKdIkBm(EH~-<-cz35cobUB8|Q zi$m$Y6(tE1rAeBGXjZqf*Q>wR`J|w`)tDKadEZZYSuN0VmaVL#GY-a1>eLWdoz9RW zumtxPDvey?0JkZV_D|dd)<{(=T3L?(24(Hs54ZI2zTy`E5iAv~ADtBkIi+h3m+y;{OLZ`@<_qs`!+1WNk=%<|Bnjz%R^rdQpnSOT3KH= zkGc0o-ziT;E~Ao8hK(?oLvUd(c6O}tjl1U~cn*iL{>j5N#ERdI6Y`r0zc+o(70ZlM zqjv_<>O#FpAyKLX1a2mg03z;(ALh*HK&$9$QenrGjhPn%XrN=Q49gn}}b`LN{RHJ!<_tG=4 z>1gEn(^a*lP>|LX)w9fZxm&)>s4&Y!U4`_U6tHNX@+S4l&=8ZvxcYz7^nC|-iT{qT z1sHn+7Q}Ixx*Y!-d`=^Sca@oRH$}XOAA;R`5fF{a>lcTvTcy)B@B$il8lk5#W;ADe zJzx%Z@OS~H=++!xgc@ti6=Cm^;d#sY$8(Y~eWI@ZTDxDZSByWMv*Cd|5ZsjoLa4`yp0+NO4MU(+Ld%-eeG4(!Ct)3HGrMQrcSoGq|gnXf-ul#8Ef zkAi%EEo!U7S^>$APB_;nPS?dL2ZdDLSf)zuB{xWD+k$1je+_{xqECm&xAjlw2$R6{ zF<9e}t|`uTsyggVn z7ww{}l2`6%$ve#UeZ#paM&{NMb*=JDLUw)xF_HMYfBj!AK<}?<+XBiL<2J~zwyM2~ zLJAznV5G3)00a!oN1ML&HueY3pm+{g8>w|I-p&^5Q%-tUu2-v6VpXTubQh} zXQMvD-otHUy3E27vrJ>DdZ|8YG#o#4(?3*#e-?~v7VMYj3t7Pty;^h19Y}0}j9=3N zVtj-#7mQY2;4j))?Kl>E9g-#68g{&=wwN8G;C>G(f8z;bp(!bO{S>! zbRo;A*|xWglIc(8a8iMx(JYP8-@bBKBDiIL0HK9RUfJ&I=uHXmrm(U$oExN8E2*a$ zcubX55I78gSEQd2#9+q1aDk)33j5@aQqO%*J!a6%VsYKC#T95(S}+%I+u*5mEE6WB zQ=KdB>i-Ry2ZC!vp2T^nWjiBPxohf>8a7kM6~HKZ2pdZ%4~M!G%b#AQAJ?AO(sprUxwEY}N`gw>?Qx^`z9c zQeD8nW2Ow-%;nw1B(&;R06n}o{g6PE7gemLp-CsACOXrVn>IWeF%u~K-(RyPS+LU? zPWj0=i>r9)#SBg(jdUHpfmNK1eLJZY^#~C#KW@xFF@Whv66N3O{R|*wC$*nj?0vg# zuNB-oy_Y6f!=1kqz0s1=L8#iM4-pnX*MKKwpU#J$JHn>8sHdIK=_2A^Kvf9P3}BN% zZAAL6hQ~I&akfa!-h~x0R*k7j9_0vujOcE^*xlaeaJHwaII2HB4ww+i(JCb=&g(!_ zA_74!v&4y~(Zv4Pbf}N@WXt7k&ecwLkdtbH6e zs2X>w4-YD=zkdHe65!!FTMm(wb8p?ySW=prO~yp)B0qBYE%}uOGo9l)K|3kv}&Q*?Nt^>1kZulc3(5->bphNxlH2w0cdPigaoZ1-z zAnKU3Yn3x$Mr9FO_)X2_>unuT#mTZU35cK5GbpV@3N-Ky;7f})mzT==@4h{w=gh!S-?A%fqs8-|$ zo4m)U)ND7SJAI6mF#hy)=z+*%#X#+MbUl~1U}yc9?pGJ3?4uJ3l>=+kripglYQz_6 z0{0|jaie*j;~GQeB*(zf$stB^dPh%BNI-y?ueA?~erDG)&f2E`!wt7Rb2NWwSd%$+ z9vCuzd_1cE(v$iz7KP^>-my6GO&9^2@FC23mZ-q)JJmAp#!_0&pTeTRS-tbB(y8%x z|KB631VGYDbDk^#Nv8|Kej%o_Yb?+35h5C6nCULZ*lo{M_S(AUPelq)I%!qwPq?2l zKK)+fm`mYyEiu96q2F02ag94rXZ%bdEJ#B4X_z`-H{^Q#tmh*aM2ac277TEwULSl& zrc8N!cigo5aCt<2M>$oK!|$!uP-D#wnP9)_FnqBQR>ui7otU;7Uj#^$8aXdaV&Hi^e@56A{w0dvp9WH?~_%l zX8?RMoQ;GHyJ%C^s&;VvBT$Rx1bT?E&NYk2IZg#LPNOfPeoWDdRIK3x+AbI`*xISa zmKa$ADYm7w!4pnK0phYFWHF{ZN#xuiVqYw07F8{1M3}FGtad_Q!DE5XhW-nSAd3$7 zbKeIVfB^S}THrk<0L$M{GgWSAFtsuAK$1cGW2~(gyss%ovwlrS3|>0S&m$eZG12Y4 zEe97R;Urre5N2H3h#bQE`Z`jKp6b;fTv^&K(hXCrPIWD|sZlcXTpoPO7gL#FZA1U5 zMVegFbhf!k;c;eQ#eY$G9XoT*iA{M&;SmMS=%uVA1nV4&4gNx>uiET4a<8o%l(PbL zGPP=t+0O?#mK+Kp4m6NicoxNaDmx>BRvEB(+oAgNH&&qYUF2fMT>>}`@*bWj-d4UE zdCnS&9wsGlnY%H+Sm<6{x-M(&IjMs`ZH^9wCEH>*oHy68zGLlIwK8OU{_-EUt{Fez z(P8`8Z&b(qFy*6C|LzkP#H%+Vx(bamtcHX1_4!bA5D^_`y2s!z`%7LUR^xdmja%ig zr*bfD{G*kPE(#wszxUp*6_moNEp!(h;W0WhEbdCvRtaH*A0`w+qgK>(J28$0NcBf6 zSnNA?TyCA8#`p8XCjfcs0Xl>MdcvlkDNJH0I3x z&U63h>6MLz;W#=*?`6$W0?$*ckYyZTKqwh^?!S^XKQct64>koxK(F^be zsq0gMZl08-xQA;;Dq)vZk)Yf2r}d_5&et`8h`4gNtp{phJt`nYARA*UtP5cH{0&xu zcF8aso;ZXVrefs8QALP3B5GAlI$MJ=S~n&q%$EC^M(CNG)$=_UC56eDUE|~ZXX!lB z{TeOD9{i`@N@X7x_(t%;U$RBN@-B6b&mDva(hXdDo04L+uSHh=$C1D$R_ZUKx~t$e zgwL=v+0}c&+#HWj{4DEb3#X?D!<#_Pw-(6FBY_Z(tRD{$d>hY-*Y1p#tDw8D98LL7 zk>~c6sxI<_g6<Qf70tK8cMTM{Sj~NKb`iT9;r$^feclx zZ~6=fL1IEI?(sj@+6aiOg4;W)`9ztm2MoWWRnebCHj^@ym#UHi z8li0#1L!Vl%gesT#@5*_C{5?+PXmxr%RZz^Gt`;}av%AD=&4j&&rkXm)vz~;`|8|k zT3}pT_-%E9d!}w8l^1V+7=bp@&vUf#VK%)rcI=Q7`T9&&Aoa{zrXea!Y7yt{qg*Nt z5SyYjzV0{F@`*agU$3qIB47V@NukOf(|mC(juJM<)n#BN$?)LI?krZc>WBC>AB9~+ zb@Zi9)dEOQ3U=aYG9pT!8%IAwbj7j>8#Es#Y{X&ERuJRF6gt->7EM+bEv0TuI`ONc zsUD7LnOiyn`%qLQd?6J?wryrG(VIZJK@ZrStJH6J)w_VPK0Gamu!S=_Rv%RFpemTW z!$7|g$fB&_O+kQQmAM;>Z;dTr1jPf{)qBeD1L#oQP}{DovDo4*#a^p1eIETxhrgYo zh{Mz*yMosW@4Wh<3w<{g)9Y+mGDgrQfeM8qM7efL31-glG&3&OM@ZCbm_rqv=H-jf zY%XS}2aPt=Dhpodgq*XD&rGG?C%8;98PwkU{qY|{V|0->W~=jmRrqtS{CZuLLyD3u zdK?Za2J!8X=o{7GegF3Gy0O7TOaCgf)qjD|$~rSMOgGiGsBQR$8tMwicNEh3b-6!S zElW5ih|Gcp$R7(v``=7LqqatBt4(swIj2c4`Y19Ko?g32y8+mkJg6=(KN!V0EatR8 zi*$Rnds`sr)50kkTyMq}QjGb$XBTmR3Q|fNMBMXWmE$%pQ!GFyx{7U~l6Wg-l2f9J zn@a!C#BZb&jIFGX4XDDQP>=yppxp7)Gh_5`Iq*5u;VXB{iE06kC<9ddZ!>)77e9=8 zeROmTo-K!v#3PM|!vIvSq^zOAj?EyqDU}8i(vs-|-kA?w2k3#QI11ZvalcVLo?J0# zx3;?qUug-pmsky*#MB=~?$jSNiVfQK&F}#|DE0Ox(+s1Tq$@mEu*Uf8_6?%B=;#)F z*5M5{IMYkhRHV}F<@vZeR&;Fv%~EXOH|d0(#|wJDRYz;aIN@Mia@+FJ54?7)kw`1WqH$L|D@5~+*J?6_A;_3vY%K(}umZ2{H z-XH4Aw*e|9?n_-T$+d%w%w)EkBB5+VzF~ zER;f}^P*A(+4%U%1lirqH`+j-v_y5d>W+T@HftCE7SjJCv?#H~RiWsc7QgcCVR{Mn zw!&O75t=<7H^bbtYrE0A`>%cI$O_r=V}o95=%id}*`H9-h-T~?4!bJ8Vo&%5G8UUO%gLUcTi!C)l~VxDZs9xmlbIC-byfAXJDhml^02FNuwb`Sg-~^0{tA zQI>E0z*(dN@hM+3ir%z%xI5|k=A&yo#uwM-S^^_9Ubv<0@!j%J3@ZOCAuHnY%g}4p z#z$*<8yGfQiIP2POrqMBOT1zQG%$fVe5RCPrHHPk6$-{N7J2NbyQPL18lT!sJQ`Ubp(_n{o-viey3Q+j`Mm$~xI3(picit8rhru_Rk-T^ zh1fgUQPCVuG_R=QT}X?TPD3%Q7EPu+oQknfVc4F#+HkSS#>@ENZD;IXM62r}svJkr zk+(#RM3KeKZyqQBx>Coqy@9XiGl-gnXzFhe9tclf8ZzPa#wI3^J+3~gP7dwQ;$|Cb z>RX6n4Aa&cBDb=OW)3=y-;fzR92SIZ)%}Z(mG%C$1-Q}g@tt;vq!-Qk*O_v1FOVY3 znM#ts#_3K(xZ?nB@xjclCY#zVG1QYz=%18wtUF6<#B?}k3~Vlzn_U7-C3VpFoBt&;ST}4${>vD zW=kg`gSV*%vq>l;S79k})$Q-vZNFaQru;~q!yAUVsL1pMV5nlxJfau`6 zJP|i;&q>dK$mP6z$*ir0tV_~~w_WkJH2|Oo$rk7^*DD}h#47%g{oKx@4lB1b#%N~3 zlOMhu^wB(qm(9xNob- zvBhUlYJBisYnqHnr|LYzJQdp>%4-HdkOcnrmG)OX+7%{LhwU}m4`zBl%<{-vE6#+o zjE+y=Pp2!LvI8)}+85Er4Ooz<=9V+$L8)L3sh68O4MclP<%;Fz<)oU(k}eo3fjPC-YKBOb`>LCq^+nS+%Bau-i692YJ7oxZx?^FZB(Mz*9_SW^& zpRDJ8^fiwR3`)J~x$8Klr)&IqAe6_?=W3gIZ z-a-~hLak&EM|xY*N5RPXQt^ts$hxF;z*N3Eg6zM!01y&CQmE?xixVUR)2cj!hY7dJL+b zO*8iIr1xMCoJC|(dOw8=1U>_3@VHRd$+a2X-ff1-d*0r@>%ol<$BzX#`w`1R8LAA! zf69F~!~g8p^LN)ODEqdqd(A;CtBj z8t*E9sN4}BefQ|7BvO~bSrFk;RFX|WY+g^h?p`X%T4CmNZ_|mM?m+@+?c0CAoX_JN z7q_E~`hJNz>d@Vp%Llpnf}G1sX*q_OjIzAJKa=d`pLxOlaJvx{FTIyXAvWDt{Ki&k zC+FFD@>vIGN28++lyTZz-Vbyx?m&}_oMgsNyJo4NCQ~r>*yDo6Q`g-Ttvfaq(Y>NI&BMbWngPZy zr4S;>Ijz8DyDiEF8V@d*uCbR_gFnFZvO7_VbHp$5j&ehg4#X}7^Vl|XVs!C^TdP^; z@8@Wnt0}aa)ywvEZ*@6~_Xdh>fkDWHQ5}tD9KBT>x@+1Ft%eJZ!32>xPjhIf|NBpN z1$v%!akf>T=A+DdheB-`KV~u6d}zz&GSzU=zQqpH9?=DwEL+V01HyY$3Xl_9i}iym$*<(J1P33Oqr%QtfQ*dNWR_$ojT@@ zD#EXVlvr2-D;VB;G?1zZ4?fZCA|RIY!}SPsA#pH|DMzh=-SLnPe7`u8>n(dsjPNe> zDL)2hMa=+-;=SC^W|hx0U!%_4jhMVbWO`NG=1u(rZ*2W zs?+7U6-0NFJN_`3co=}?Yjhkjs8*0AMu&UIQCmuWvsY=0Oa(I$RLh(H&e3x*x^;CJ zENlsTdY_86yYl5$n42hbb)@DGy1MXTm#OR9wH$#*-Vx!-8}i(Nfv5f1k}mOqfgV(1 z?4iM#Pbejje%P>0B%OqmbByKdO0e}%3@#{@V9B1>keV<)dkt_`v)ni(qFnBqdaDU$ zlD{T@*oJG**vpsRvbn8}DYn}i9x#!fDN61kteoHjMQ;CTRxqLTYfuUBp0riABGHo82V-%mk|6XX=fWAnNP+g7*2bk#o(w_AxgHbt~WA z-fFza`CR)>dX9TT_dC}s%Q7dfZ}Q16c_#lDxEaM{zB5WVl8whI&^g7LHH)bf{ZCoO zzDny2%^vy7k8~+j!#K>pzAntYlPzYOQ>#ca08xKqO6V22VPXKN)nYSf7i~BR{q;w` zbqL2#!e~2S{;LLWnVu(MBuKuK>`{LD9lmDONd2|AK24#GxUA&wjp6s7Q+a5hJMWWC zvcH3KIKpye{w#%*EFOVi$bfsq&;HlJc>Mg8#v1XWUR-c|9q79+;>G>D5u)TR3^eE0 z3$^h?6~EB6W79DHi&T@vq5N0|;ZW>)mA&N9_MKkik@pN`E>Br}%=C14ep|-x#Ixm!^A3UXXlgwa+LD|Wd}^#*UCzIIwujrY5!azt;ijn`a0gEQf*K`kC87QI3vk1Zc zDpDM%#I6&{w2CqnX#A8cj>hCAZE^&sC3U8te9p=!D3B)9dHPagqWUA2Zh z-i54x!%<2ds!=Va={YB+Dsg(9F0564@4_!CeBosZ>uBC6-*Fdew!#u%T#r^BES4tP zopO@C%|)8=tTep|a-%@TTpvAyL4;#adPg_lZ1nxDoQ{u%A|^peH`6src){kw#x%k- zhHnMBK9wg(Mwu?RKwZ{ckeRS`jcW5-mRcju`MrTc6lG_e^vE=sOw%4?eYZSk3uJC-=Q7X)iyvD3T_2ss&uQ6OxF!4+E_X(3yHGElXNIyB^{Y~ZSl)8N zINW3#0;J>4tzea4ekk6jd96d~)IqKqDRt;{%cIogZ*lp0rk}8{8a~n5IO8jF^f?t_C?Tbl|lx@BFVAMW! z$`R4})q~=)R<+f^Cq{H$7L+?s)j}gl^N)nv%%Y~MnnF9?!EB^$7ug6uP%x_cjQ02Q zR>qy@J!}7~1wdvXyk7s_b4%1hJZ9IahlaomWo&MwMgginPBNm;?p^zyyrR*~Irctu z`bx#7jn)iI7(Q~NAhOp$N{=&K9aLZ#Oq)J_x&aBxm)su^Ng;^G_$v$;oDu%@iCT8j z%)uk4KzBJTRprAd-tIuJz*6ZtXuU>jjBnUtL_&XunqZZO!tg zcmSFH@F>RU5YmaL`1-eHOs2EXd)d4(l+XjH$ni}e3LG<{`Q(_#De zZ*+Gf-6bI1DBThwA)V6QF+c>QQzT^|-3W*b7)Ymtbi+V;bPDgD_y0V{aev#6eb|R9 z&g%?Xqj4J2d5gn998FCB!>{_y-<4wa#@2s{VYNZp1;tVi3e#d z4u?`^Q-&?ik2QW=8xhJFKbw=ynn4xla=OH4e(EN)tjUraB0wU!AB_NUjIi|RHCAOK zgYK@iqwMT6PbCe_KwyWGcNOK)|F0G^1@ucRaKn(P@40 zeE1>Tu`RkLZx}(bTsI1JW(u)bNmX$Z3bx@D!#~mjWP2qQFkiV#eZy8Ldz(SWXsIqr zXuTY(KJ7QH&iqxARJ)&$xR05bx2$q^{@V<0ds=Kos=$S+`>!9&!#d5dJz}+(tSfHr z&n!5}Lez73dY?1N1j~ju=he}!_i|pkK)mJmmX9wn37z>u^=W7m2WoSS{5}w#{)zY@ zBSRFrv&S`^! z%i%QJJ6q*qPmXH>tWdGaw{Z_&HE+(9;`O4cS3Ndk=aOTy5%$ZXsvp(9Hr3tfYhC}k zgo@TJBCVQen!8`sz7|=5gT4OU9?iz!b|})2t_*ag*y-l`pRuDevPl(9kxNVf4}Q18_dmTz3&pdl1e=G9l=YnfFJVHO5upBHQBDkjypK@(Rk=j ziK$;FoOt>{S?wy;Vkd+wM1?DsNdyQIuusxn)X}t844J7#86)(5v+#%^q}!vyrw@9y zKDeXg=AeBk(h=z9LP{a941}?}R7*2W(H3E7^*swIUVup&O15StehYbg|8ozFujvke zWX}oL+eucFkOa;-;xJUIO*|OA1HhhP%6~u&%1X@NNbqVg;3)v=)M$(zoNDGN!d@cp z!355YcnO(F6oLg@l(7>$fh{G=Sq(OJ5!DSuYJ%!kUN`TKDii9MJyEcUQ=A`mZDi2b zu>^|MVDiO*6nHvG*j-qM?;AO!Gbu$AR}7yUISF*2Z!opXP&?Jz1h)3541=gJxe-8~ zN%5KL>nvrNqx*hsM=x0kO@jh_1}X=jy6x3PfF`xWn92cFX!UX%&}HCE7)5!Tt1VM> z#tEKY>5%2L8#LYM^tRA*b`uOdF7PUYFU0Ib`A+VCAy{WqlY8N(f8zjoQ8kp!ejZ5C z_!7f8iMOzm<=qY2Pslrs^xG(QjJzU$-|Ysk$s73hlIx5E)u3nM1j}L+aBM^3Fr~Iq z#K>?WuEif))hU4?g|rrRo9m>8H&oy zigGTZD(4+`6UQDMd=&&huOuuKh}SPal;F8?z8kP101%rZkf)U4Dxmt77NC0CE!yM_ z7vo75-&*r?sx9XuyX2L31rpZkci<4wT=)b^_H!qPPj|-sT?Ey}`gRY-x^i0I%g&S~ z(~Ubf`d)K2WBmT3PALLRE7oDS9L-Q6$f!`(`!HTN*vFpM?tY|UY*jZ zNq}VtK9zqZiVyOSCo%3cJ2v8SLO_mYw24H@Hf96_wBXqyOmh2}id}m%6q%t1)%10{VR)DO(}LCS^z}00 z{j{Sqa#z&CY!B%@Dxq2{0)C~bV_D|6Xu-w;QY1CIJqMiuENu+hy9-H(12*b#UL+qH zt~_~~qe$O@kLUPe5gmR-=E2+chnE%?4E#|RO>sbuLR?&6J~fBL8mjxCcj|{4;#P+# z?0fP2zXE56n+)61h_*NOK6M*!6y^@xSPDOyWj$#>nJIPb^=9m@J%W6(gVDg?w;Xv? z=ReizJHrEL{e=Yg;BRo`JN9qHz66b62RsNP_!%jrP2|aSbAS)=E^;MY970i!_YcwI z$i4o*bzg4uuT#~Moq@X5+4%T4GS^6I$TNl{La7)GYxei^L)zk%m`$RKdrZviGNt^T zk%E{=+QpdZd8au#zUKNTY0Z&}fDevI#SM#(jZ-$fmrp0|VJ1dLCfl0oT{=2RrdE31 zL&3Ud)3V23B((;tRaslDUcVP(wn@zVuECS34Z%sK)A-g|;UWGYmUWU5cRxj~5fLnz z;+N(nM4yTkZF3OH1CrS_T##X9zMc;{bda76ZK5=-xH2hz_F<;tSgJsDk4C;(SXoZ| zO5As&EA_stEEGJRX{%e3^TV}dSH4}iD9M|=3ZIw`LilPwVBb)kr+|}5M<@HjJ3CK& zY44!~lTF(tFLB;c{!c?l)t^su@AuKk*qP`XFD%jD(O=F@bd5dhFEq~n>=IhJp7d?r zBq6MkE@qWgrf0wY`SK(ko}f#wg{Iwc9-Er zbx{Gi5vC*z<3^-3NBettwk*^Bx8&)vxfmQFd-yO%4VsI9=XlJAPeAXFx4X}P^DJ~C zPQTW+a{?wFmfy|EP+Rmkx}YYq>g?C!efEj0}Mz=Kz0D8I%XfrGD2 zxS9m;IYWvcifNyLYAKP6Q5qx_sFQy3;aNgXNLL7+tj!_vURRDxV!Iys*6pbSvOx-o z>!>u+EB`~iwvk)MgPnL%$daX@+`J8?CkXUQZ<1e?+s1=o!~26*G_+}hORmRGebvf@ zza00??gmxdC6$m4Yf-nC4HdBKhzIv9pxfxM_C@;02>BTW0J%9XPA@K?64WTq0bI5n zT8c1}8z#m8t5#P0`Jdn3{h4R7d7EMS;)=`x)QKEMr~5I||Gpf@U_Hus*2^Qt_`vvj z5)GE!VAD@PEyel3309Vi!|H9)=jmx~<$D-E{}Do?wNc1L`QsK^@E$ z7BzV;?ogbzDsW|mSo>`|Igexkk@=E|dIMLjNo=y%0@$^m26O<{}vrt;C0Z+kYagH^se=T`yX7ODd(AD8ewKI@~|-Q&C36R zQ#`-6)I*eikLopfSV7Y#gkn0iT2&4Z8~1Fff0bOee1rjXEh53Z*Pz_;*&#Twnwd-Z zW#9ppE_vAeysKKA*L44@^zg;O)jw#k%o5b6&m}L>hChTKc|X2Q|MJAZ`X7z*zZ2^4 z-Svq2opWUMH+BvaT?pujPvx~h`&e`9(ss(%Uq^X4S9AMnJ`L_a{N7@Sh7KS$HTCYa z?FQESB+AT>$ChKO4?<6|^J&KU;(!J+X4!<`^g+8=c_il%&}@gZ18Dr!Wx?Vg&qG@ z-lC-VTZ3^RS3BAO#lvYSN2}}^&@YwX4@K?`zjEx#vY-LkA}x1%uSsN{)%&vV8IOOu z(_4qOW-jqgxN`3{_P^_$)n2iGkRVy87R-g;*RszF=Pz1@a9SRC9Q6iRx|9x;7kp>0 zR?rL-3?G>{g$L@9hlxuZK+AhwvH)(F4-3-IXcmfTS(++CiuHxVfsIcfWNCh>|3z5B z@Ry~bHh+aSo3w(>!|nL@b^Q7&&$H-^QZASsh)wILk+;-YRH|uK_8U4~x6%2RS}hS; zjFtxy8?EWGXjPvt7t7S8sr2gm!?o2Vzr3^Sf-K+a{OlMIkF5a>5;}U^{>2rt8=JvB z$?}RH<{Nf@ahq~RtGQYnl#aC-7Z0vqv7s1;D0E+^MMyxf z@R&UZH2I^lU zJV+`^*#Rb3XL1$Y`-qE&kjW6k!d(~rJ@TL!nw}s{rys;n|JPGT0X`|!I3>4yHm(gt ze%41M9MT2_wWnwU$v*Egy(-x8_{Idj)N)>o9U%}N0j|siUPT^0z1r}3rlozRwnt)> zBUR7Wk^kbH4%`}~zRBO%Ed}JjCmI*uG4*!@wcR7R#4dt`O-9kT5crxcFsfr*&DI`1 zv`IZm$(O}=qIaI9MC&xM;VqAQM?<`PpcN?R6+3orEo`-p-cQG&RgT z4ZEr~P%#hI{t4uWt)t_yj$j-qY-q)^Yp8;+rggpMK7`kJ{}BdMIspIZgBTDw#uPX7bBjWCLza9$A=LdRfm2 z$P`w}zSZ;eq2VM$i$4QSnDZL-2Hhq+UI>swl2i|J^3ca=@7wcaGK8Z?_<6)omPdpD z%FJ9ca|WuF7O&tQ%%#Nkv`)w~;Wi8xRY^M+)0=>aj&5r3T%tx+pF~Cv;`{7 z(w`N}^(EI5QVxf;>_>l{kzY}tnn>@LUFW5sQa9&gKvh1&yWEua5Zd#rGQ@*ZrwYq2 zbg#aw@oI5!Q3}|O<+bUZUs0w2993?D`ys+jvdCX3h9A@Re?;|&XgUNd^m){?i1~@$ z?iV3gV2TUgW%NM}hokr4X&^ANz3WmgLcaW;0C5!VJ@e`KiHv zqu5+XG{pQy2@clfSLSp8n6-KKP6`<`vn(0hAVVZk?J4B`-ur8{(E1*5Z@&BTQz!qKnW3A}4M>ZMaDS54 z+(q-?RBOXxcNFPrM}`qfJp_njTvjJbf zy)(U8&+^U^0@{b*5^v}S)_WUsUpINfShN5r!6Axivvs}sA$-BS07OL^Hac&$UeVy) z-TAfJ$us~(6QB(g;wUFGRq~Q~kVi;H?;V(Hqdw$S#JQpOYXrPj^+h~UwfIJOW2y(YJ zLP;6LJy3zkWGGer4(B8v_uI+lEP7w3-|;wGe1Nu=&?=o`mb?9JsYsMkO*)*s%rJst zQpVZafS&89L?@b0ySd}9fUG>+#u+1G04BZFeZ9p6<~Ed$8bFb*l|vE8bx`00Pad}> z-W~3)F-RWC`INKz3Ng`lJ{)W-+&Yh+6IZ5eO{O@8MWPF(5$1i9sNqmITseSu<`avZRo!we zqC5MMLG7+JU3MutEauCXCZsnVhWu(VXN_~@A`RG_#cIsFsMNQ7)p@p{ofeatlnHz`H*G$2z4j=- zO$*{rN=}AH&FisLVm14W8HcQq2RBS)N#usXD<4=&@y=7c&au>rO$AA8(#gglbCN7m z^FEG$MWT|Lm8@KXQuIF1i5Zek9~sFK2zhP)b)Foswb9Y@^}zY6Uzv+CD;~pDr?Vo& z{DhB?)OYJ%XUY__wXqjRA+%-#9UDkUI{e-06LYcAr>{>R1VYaNIq9TLKHGjiiHLO0!iHhy4 z>ht{{!JjT|iZ@V_VKTxiE}}?x3y7^E-uqU3tU^SCWX5BmTjfA<&`jY)t z5h?!oZCWC0F++(H7Hvg!`Q?>6k!Nr2Ti&jIfloor0IX|hbix?8doiid3$?!`w>NK{ zM|%Q);Wrumm0;YV)SE;(bABS&yJ=k}RP%TU)t}IiEM%_zvvPxh3?H`nuRg~w{_p%NH z2Yr8(4Y!e#d@{}&MgdBE;-O~&(kM*@lg2Eh;N|W?zni0%iXKq-_E;)S7Oh`cg5%+h zmbF`5jGAjV`%Q+|HJdBWQ~eBMAz9d)bPE9rSl4ef7-pVbb0jV8=Pqq-F~g}pnr*M9 zB;W<=LD5a`;U7PQ?=lhyh<2W?8a$8e`=%^v&fg<*m(~E(0#O}x14!Nmw!_hslC9AX z`x^NI^tRKF?20$Szc$=D0D&0|u|=303+_e8y8N{tEwV163ngx)^~`fwj?J^=CDJU- zZX0{N*};QFudbZXNAl*lr()Ve8#kqZjg z)sF5Jd1{TT)3{G2vT5OR}4wK(jfUs^nJTrD?zk?Q4EPL%IP|}*ec81+t_gp~?(JN=sm=2*L!3qB1oRYp|Mq_6b z0C!nl4)?w*KSoD@>IGwF(K!pq_482zs9n3cyqZJ?-Y2+jb^B%@CnlkglZT<$YowyP zb2~;cxx{V8pe3IfX0OYDDrqi#X`Ot^qDacGP0`H0MY;JRP6Uk#CF$cg2Ir4)Zu)H+ zaNA9R24c!VD3#AA;2KJWhC#)^amQRwV|u+wEI@xImSt)Js}(u1PdtBFZAMUrML9!m zGaw?t!gbVm!qG4q!XouIq6s&_`4zlgB=lOtpuv6HXeR4l1hfLVAz0TK4K`f{HT)h# z*^%YpI=emSHy68l=3zpb@nT=X5^vCU$Ka)%;Y`-2pmMI?SG3(}wDP!r9V5-#0|C?F z#EyC0Ah8KQZ$Nz9SVaPhL3_<%LwRP99vJB_xS9ES>%+1{@~Ha4T~TlC-v3sq=GZDaC!o6Gme(F* zz}N4f)SqRA4^KxeVT09#|1JJ1)KP`+w*T7;9^d^k-~(2V1GU$$gC8rz;#TiKjc~L( z-hLTLd0J(oT4SWkH7>ml7?cf)Z|X=IK}Yr-w0eBs{yhrpWZ^sixSM2YlN5%@^)o#A zu9v;#?$TpDYt&{(C#IngqF;}s_%gDxuL_13I7bWqkTX}U_`&ID#&kvxD1fffSCz`& zi5o>ey5HX4le(>b4~iNzoq5;z5K5s;C*Z&3i2*#Z$m=4VwJmz$NQ$&G86E{4fN>sw z^R`?haIsr>{Qfo@kt}kHs@7%A3l2APE37653bJe^SW7;s2C1YoPXNp7hZqRGnjfaJ zF3G5JHitOCdaxQp*yOy(x|!wtynW-p`2N-DZMF@$x@FXLrv=5JoRDrKU~RMdx9zK& z`?SaJ4XqKJNgYdrI2(1SP#+fb*V_w7mrXqyTe*}Bn)Z=}A6`sm+w};Lc^#|E<_~0G z`Wl|hcC{UE0^Ozy0Tl{HCN24@vmW{}Fb(_24){&eB!ptPT-wEvg&E!0OK426cGw>p zy|OP}@EP>@ftR;YT{H9*F_|4~(gqZt0Mm(wVIA2-oqA!xcYP`klJ?4DiRjf6tV4Jz zLFox}sTW%7o=7>cF3(P|^ZnrbOt#;&5y~iVFw{>`kB?TDi3LZUBM{|kf}@P{*-Uu0 zusoPRo}&@H)JutT!)Czp)eX*r4**1Jb<|S$z>l(bm>f%gbz+dP1?Q=$hwoP}*%H4z zXIqtGnV^D|a(>s!;BG1_Dk%nPsmh_(C^PC||DFTGYc2MkzvkBioX47h_SO%rJJ|IK z7gU-2sK`~DygUO<0*^bzjeC#W25IOb_56XwW-dZds~-dy+XVdxb9j4LZP{BP#gx7q z>%|ehHr#}(_OZ1Tk+0`UxB0$?s+v;3?^9FCs5gVTGl|P^hnHaDuKZBWZX$X;8HIuP z(uUNAB*)}h^u=DGg`@5EnV^=S;CeV^vAxBv}?t%El97-wp%QhAG9^{JGm#nR9nZiSF>Wxjr z<3;K~z1!Fu$nN;?G|&je{mqf!D%xmR0QzB2fQUd(#tm=rFNv}P%?97&(2bwn^2X>B zMnym=X^G9M%z6!Ov#K3M-`-up`49brcOvV;|6d$1!I;Y0<5t7W| zH|}^PfG4{ev|wgRpzry;_9>*$KuDC zQrYz@tK3$Fxj{!~j`K^h)JJEbW}dh?t{}U!)5>K1MKxYe$g$LekYnrC%2&NM9R{BN zaRDkm%<=X>`_u`9gdZga7|+TW%BBO|5YBkupMTMyl1DzdSU3G%S^N(6i~DxWa*!Qz zXY+;!|LnUFg1HE~_0U+*1P2w^q=_iFAUq%Ry3qU1RMAKJBNKhFw0vkCkt_dVLGrO& z&d1)kki8hj`Hi`!?ab{=J@4;oXJdHamvJi^azwtf(GJqyt7p0Qu6y_-v3_@J2&V8n z5K(WulzCnH34GyNo&C~v9C-NNz@)I%8*!b#X5glN<32zZGMtDLE)`hWngeB*2CuJB zfBz#ULQVYm!U1?LJF&Lqb#g9LMOkegk|_kNeZCMH4wd6VWHl`1Jg_@hi2A*q+DPlv zLM69+lTNO+Dus{_Tb<|AqGwyunfp}Kd$46FaYe4B{J{d<59}XwP;s&23&oN)aFf3o zQ~vnkcDuTPPivM9-XEk@s}b~00^rCDW_!nmoMyB zlUlR85X91SY5lHkI*nfJ3d_SZUELZgV9yKQFt6Gq%0+sUOtE?tXO$=nA7w}p;99_| zYnC|$(j7*63O`?<+N^E!idQ9Nv8{EBr)N;n=EYOXHPt@*O{dXrSdBxtVG5fLI#qw6 z#H7EV+~J7B(D)7g;-RzcC(>v}$4(Ysgr`O>K5<5Uw|9#SD_|=8Kg9=;l(eKvE>K9r(0g;UIg*f;#a_`1QF6A8# zyx>-GRF9GQ#GtqL&)!uk#7lwolhhYA#pkHih#k#jkpi!_%|1U5=tAm6si*Uf=$3;i z@PPrXR3gd?>v0_bJ6tmRV8A5CtBn`BMJvLE0ZqWwve@vD{W>N>x@X|IBz_f^6}nx? zgA<4GTk*tFD?brqX159{z(M|MPPd0nXjMwbsW z@!FwT!*T?sc{vE{l+!o;CuGf!&}eO9ehQHLm;*IoyFqo^;LRIn3P2zXU;LPiZBa@@ z#Ybplt|AXBsDr=5A%vr3y7;U@B+C5o z$q~CkHhz(4ow^RNgu)Fz)x3l&o`6kY6dp6UWFoeKtzdmu%U?M%{SH8YpwpNTBsZa~ zO153zBYgEa$8G_oDa;tzP1&mdeZ__QBVl+n89|V6gc(1E1_#mpj26E#nC$oU<&C4p zp>Y$zasqTdehhL|QZDy=AAPGXCb5jId8bnUdMCpBxBLXU6a-swLZ=haGN3CH{LP%Y zX30})Q;FsnTk(XS8@e2PYwC>;Orm-U^3GEn(FC`kEh{D$POaP~y9B+Q@_qCAiz}6e zxJH9-fR5c`pV+5QCE+D*1IzVHO# z`p~PI(J{ZoNO^H=$xU*F<02W7nd4#*G**Gi7+=rp!}S~S7ee$eUiTGZJ?a^E+&pF6 zH!qGMOsZ~4b#+rdA!^8I8>O0^)DZJL7ay4APa-{g!;|NL>X)r@mZBunSBeuUsuDKE zTyk3P?VB%>kDKiNvhIvmFsSZ>iMjDqSdTMvq)YId)0e?qdMbOL=&hXB-lur|nKxV( zOgoqlD*2f?m4S-=gwH6Fw(L~b=O^s0CeyqXaeT1qJ@NQgY-LxHq)gC&B*OQn``V_8 z3nzil73&OmH8ZWVs1K+3n;LZZRf#-Q&jeD2!L`?rw5x#ZV|_hv>bZzbuUAIMsa=-c zq9&_zsUldd>|G0Xa9?Fleo+q9GDAP1%-zf^rb51Ncj_%^u^*(okn@NA1CEfp5nhBT z`+5U`;PE9!H?Z$cdFf6mj!kU7S%(Iv=#4z-G+P0Mq3`^Rjv2?=v3hQrfa1NbFbcK9 z=jHyL6B|Yg07Sp!Mhy}RWeo-eX-g<`-TTzWw!3Ye0zYX$-dZ0>!Se5y|q^% zfYSiZ%a9vh_o>?aK}BBV*vB^^i`Rm-5tg`oLlx)xAObeaFwm zS5ul2fZY2-1}_ZD#*n^3dJ^=x?2Tw-B=2A7@^KT}niPE_hBDs7k5zdc z-%6a~k*02;0Ma)Y`>EM$?LUS*?%o*d0X0T$wj*pJ z_Y@9g&V749r!jULYdR*<%nt+tMMF6yKxv}c1|E!d*wyisbF{|aC3_F#9zt6$0v?fP zj7w&fsaVcN0MD_*zqwSQe>IdQsQJoaVf|;`*HUHzxRGu*YMGxYK{-^Fv^@OTke=s? z473OiQ+*fFw_b{GmrC)3XLvV&i>xo*TSZb3SGZ)mR*W%?Ev zuRb;eYfcSduI6-ozTv{8MDOP(YvwQx`(9o{cKHUfWbOi#iAGygl223J)OXT56r5^Y zXDpHE6i0p6Zw1L$GkU&M+mf`$R^}wiSiEk(J^gD2fBoWs3BH(NFHKqCT`im&j#Y<=iHPeA22Q@!A%_;Fvgaq zkRXi|K{csiq$-yr%p{%8MkQ#Vxqm^(1~b!?vQwWQ(DW3wb}>z7vox7>ll-A2YpnN!R842V*-Yk^W;GxejO6Ge%D$Yo7mOwf=*W zR$Jx*qIRK*aK!|kX1!BN+nE7 z?Qmz7ea>{o>4F(U0cu2QAe!aSJmNW4=5F54t-kZ*eErslm1@DyrFnGIy%n_dnPQWn zK9bxIEr{a4+13jsyPX-=De(vs!GgSV%m&|jA<570UWd-#6*REqK=BE+xWCo;3p8W? zHmo%A z2P@1*tv7!}t{S0faY>X&Uimr?9yoBQQjG%{iT-B;i>52}&o0gf+F7nxrn=Ax{7SzT zEdF_s)seI7pZU8_h!{p$@q}Oh_ii!-slHgk26X$ra7XLfJ8I@f7Ndz|Vic1h?O7-| z{kR8};x?>He*n-(8+Y44V#ojJxJD@_&C5CLerKw)8IsU`vUrnj3!c0Z%Sa{?_1ex3 zd6C4tIr!SUFh^=svzj}Ia{xvBYt*qfTGD07-GS`vm!5-+xUxRUI6v7JW2zrmJ{(;H ziIwG7vwz`UiresQ7qhX=+nBGCl?nJT*dV97OPlQesmVrx*r`k;#%6N2w!mxE;N}?z zhu$7mVdS82{<2>k^Gqef&q|5WRPS;CygYo=D8rDoYhqzHF*K%0EF&0AGb=w_p^a-pZu@XIF`xV~nH3#jn#V`AG{cJX z${~}MLN=va1o*b-qm_=?jZP(Qb11S-_It{fZDJfLEly(Ryl?6?{?;46vSocpBrv|9 zuNHMQMDOs@m`1q9G>()H%wU`l(Ny3JNZpf`_N2`jb8j3uW>cveFqG ziwiLB(b-@|KsvG3vk|#Hgdo(!QCtgT7{EhwG{fF(APKO=4>B?&fcJQb^+%1`V<*5tQL1cjE?%n(|8yqd&Th1sB0EcUHK*t5rn%>|>x)2${ngV%2!^St zk_%P&>jA*Vv8P_LXgYckxaNdP%ETUPp6s!*K?tUhKqMm@Ih%*D$uY1dG1H>|G%14j z?)S=@GLGRRtmHG3T!UI}~bg zLOi=t*yP?9m-Lw&NB+AE##jG1>Uw$qZ@)B6LkopV8-v;b@JmFU&@bLfA{FRuWS_!^ zw`2Pb@prk=Vd~rd<+sj;a!hASWZ>Hg-lwwgh_G?G{}O4!VY-3$N3E#<-0?M$KG{`; z`jXmse{7l5H%CbkVR;Dpv8bW-?;jdy0}ZH0=B=L$`171PrhTHhTn|}4?R}TyBEn;{ zdAk3>P2%ezc_oi6rH0X`{+^s9&|j*7=jG6i-b9SwCO>g-8jkN)2u5R|hphhBcUsR_ z7vtV4e`reeE$vW`{<(J*K+{W|w57F6q_)@}B~`ks_u#;x`zFRMhAq*_nkr4(w`}eo zOJxzL)gY7F5L3jei#LL#^!hz5ugJT8qsBq#+8+`RzSsR6`G3|L-s zQ10O7#5TVEd75jr{p~*CVGhZ=E)W`}ssU5%oK9?r>YoE`^Dry-s0QEAqS)v2`;nx* z&N{u-UANvhI*(-qyFbM;q?jK{*-x@`M#?gCL96K(-@UF`|0Q?{^#p5m^6Y)}noPaj zO>{-kiSU=W$A<5Gc&gczp$%{AHL}>ngYnbQCjBC1JnYOkyp*t^jG#ka;5;|#Jg?B< zfHa13bofc1yCefrA}mhuj%VcIM*}U}YN$ned=Ki4tV4L;yhG0NpKV?2B!>if-}6cA!D%P~mWK`zbXo=KIO};0t>U?c&*!c9 zIWaBK%W=9cBZ-x~64$X#8w$4k6Y*PjGJ6YrM~ncQJQ>~N3TtTezsgk&YvFV)4SqbwgEclx5-;(z@`RK~ z6K2q2n)EPixlGPSuY+}wl9S|&B?{Sh?PbFq^s1-Pf?s#6m;_>^}aL^-F z+cIqZQayi5P&C_T5nd;5W;LMZNRyreRE6qY>b`KR{;xw>h&M7@eLJ2q7X~*eM@I!- zQsPHS?UBxO22|lAIhoahKMkK8HPg$O=Xs%bkx>hz-E?py(r09&OTPwb$$_sN*U&B@ zbp|c$xjm@AC^h_}rTX1~t(_X@novuV-tlp#US+hT^FUQ!(nlO% zH$Ovx-NeN~#2hdYc~4Cbe_kFM=3P=wCOrQW@@k$dHZWJ{J!7Ui|f`mJ5LQ} zy&h$P7X(+~@hD^Zb-lU}&veL2kijv~lY8#{#3sFP@Mz!NcUJYr<^)8V69PRK0n@=> z8UE>FlLkNC>hA_iQ|;q(Bn3R?Q_d2tQpI;NOmMySe3}3I^XuLOlNI*Hg%u-O&iyjn z(O0x6fWmKAz3^ff>R*b~DuW}5)47M2UNvF;Lv?gNqaU7l9ucN%H~O<43(#{Li<<=o zbq6F1<`Fe%snxwuCirTioiaRPGkEQ8rQ3jeN!C&`^;HAocg;5qnRxI8LK+4P>Nz-I@ zgH|`8?_{-=DoxOdGJ5iRo0yLjzRggo-1=pV^`l^3ZdLUDNH$dYO-+dkd?3JF%zZUa zCf>hc5Ikm7+0oL+MRQD=SvJ7z$8T4+2irS7H2CyZpy8F zl3T9L1y4%6B3{+z(n~t00Nf50p6Lb+G8-ldQ9D$m1#IEoU+wYnap|WM*_zOw&mwI-H-GQm@xRJ` zTeHe~_Pi#M{PHwX&W@`EgV8>O(%b?C$l&@h8t!KGbzFS%j7sJG4IZ#rg87xf?~mpV zdAtg2H|5EMk}n#Wwm~2wXL0ODE{+a_B!ZBs$#mrOFdHpNJN4G@4=zZ*K+1L)M*aAL0c0lZ zEh!L@qeUJ3CLLc5bO_9ee5s*Sm6n(6sRNFroj=nOB5R(j)}6qzkeWlL!WXa`^bi)D z^DOfs!)xhpZ8n;Vj6P2+B01u{7RAVyK;+RCX%n*JGCMy2Qye8{=OPGr_aXZQ1&rIl z8;0hfRKwVV$~cUVLpW~IY&|kxoac)AYZz2c(~fI!R$Un<;)cXR9U=%LF#DC^CHi8E z@`?hp?_}cXAOm6_*3frE0!xt;F@>Db3_Ft^IaG@MKJx+@UAMAP4=Q#(Dh9NhcD4s@ zj2tS7to3n~p29J!vF2()f9M7F-gv!NQ`)%m3sxjA9g9d%Kfa0Da%6r;&shhKUiJ)J z)sIq+a{WiWPMS_f$w6hMkU}S=X+1TxHuW|r)sw<}Dcs&rH*NEl5j0y;P6@NswcrTK z{>!4%Cz?(M*7pZoaJyn6$R|Hl)7tef6!%GKtCiWaB0KpNu(lA}?9(`D^q^d2iCTz`tOxOT_5-&muqwBZ*#O@Ums z$rIx~(#(b@2Tzrz?lTg``!Qf#KPzFvQ_D)Z-a1TZku)oLFFVKQOi}%EhDC^;w7Z83 z13Y}QTeQ{pLqtyLf;*ET!)_H8QO{m-(~bqpSxex+o?J4JZQPlOkjaXdY(HMXFN?mTUMXmDs4boSQ4bn;- z?lMNJbksn(#00nb8>b&-fPs3aE`6ij9iMLe2mo6u$l{I(t03m~FJJbnj6U{yUOI`) z_4?FcfXr-8`QX8*k%T*`5-Ehe6+CMI74N=5b#8&qW5~l_XAv6fH?XVLU?Nqw8K*PD zocZS?0980$Hcyi^lIiX%zz~`+_vM-2{`hm{$i1=j<6sG^e>*flzXfQ$?>WG_Eji+F zhbP~Ed2w;xJJ@S9u@FE2%pF`gp0pav(qV{0)HH6^35D_;eg)c(!Lh%aKhHl&FF4*1C>WhaG5OVAxp7lRhsZxD< zjiA}aRfXQx-RI#CLyA)6HO_V9mvcCe2NPUR%b$-%p-Nv=6#dGn8;zo<8xrlaO8v;l z>pteW=mM8>xGt!j2gNlL>369pRctNC;=m35heFK<3qfGtTRZGCz4gKWaGKOU%i$9M z58pT3-j}4xBEwR+IlDZAV30UU`5|94#cM+~Kq?MbaRzdAL`!6@DLALL4O4ZINf9Sd zA$LM^s>l%;Yo_|s+0ch2Qx(^x!l03ef{>+PsM0cP(%1N;N@%n3o#UvNQtHwn_D!@6 z*{z5=ghmOjy8S)au6B^DsGq6VhDD(MfWmj?B0Xvm1^DT$KAGUTex$uXB}A&)AMkLsHvXr7D}BI^5T z#FXxvZ0QB8o;_QWgmWfPKa@)4_bw#zemKVpL)ir13G=V>V@?wmHJ)v6c_z@yZjcbr zPJ43&?I;@3o6(#~dZd)A4J|UiBmNS`FhcyC>|Jr%?NG(|-esvXJIB6u`paMg$PhihrV|QYLafFjX}Fwi8c5 zA3zy$ATePQ?ic9{6q>v8N#3XH=kiCco8IgC++nfnF+*X495c& zNdu!$%JX@9yDlEO4%QBw;ZYYF&6{ooGGk4;8&Q$RStVr|?fiQs2zQ=qsvExbortov zHWOk}+R|*x&e?O#&{D(Yp{8Wvw$=N;^t?r8A?T**v}q{fhCE1;&sso(yi1GW=xn@} z7JWaNk=mG4TBq${i&rw686S^vIk`@R0}{YkJ6U?+Fc3_q4dfArDYs>-c{LhV?=G-y z%w@Je=So0#5JE~tDUjD-wsCEqR*nZrk46`_cQ-39))q<{HbU>Eaz=5w@C_1=9H&w* zFzRct!NhRDAdPag5DD3E3RoVR=P|=SMq7aTkstJf`7BGnx5~1IfDWlm(J?eiXnCO= z5d!2aJ)|-WB*!(7GdzWX-+8#$91_m66w|nwr}2C?QayyI(|LSzNFhH~>l|YLPHjBt zW9Ox|&7i6w2q}U-+u)s$R-Mhhw5Egk+6)LUpo>Oh3VfV3+A|=+x6192(|3DyljTLe zK`3dXDcU$B-L!)WC??-+<2{?+o(a=#kurBF#rXX>H3$8FT!5IOc_Q@ow+av8haJHQtV5x@*ERbpmn=Wa z7=&a5PZk!I7runrtG?8mIV~6RX<>WS82Wwve#_;TK*sO~Ptk8a=0U<8t zJeY^P-?(1KVZ#IBQ|gnZIYPpgBRs^&@}qtE%Sv2em-Wx!JL-Rx`?Y5by3}-UWU5x8 z6yq>2PLh><4ef1v`Gu;uROb zB^uEyn{J6uoT;JYjC3)EyK&3j54l|J*5~*D7wz>CRYRt2x?<01%hvBocf->CAy?*s ze+I+xs~sx2WsVZl8iKT95PZwRx+F;LACqDGo?+276#KY5#J$$Svb^&|^q1}bN7PpU zMb(G>o~0WJ=}=M{MClX+mPJ62mhNtrW>Hdlfdy#=q`P~iLqepx5$SHY`+oPkb7#)% z>};Gl8|OU#=lK z>x~e-IpD<@yxVw>PlXT0)o%3?0=nZd<#oGUt|CWzn*M0IWrKi}AV5U6;H>nmymZJK zqq(Boz1HwUUWK#+$1uCYT?Lgu>+YAd^9`{>eTUDJnv;`wG@d5pg`Wc|rek3s-x`RW z@;cK7Bk7b<+pFMvqvG})P@!Q=5V6}=3uEc6={{Gw|F&cFxK&_J0@J>ZD2Nr~3Dz^L z*ecjGR|+~b3Ub|pm}MC6k?}!xqTN^PE$3L<9f$qB#EPt|l|7+uIm3#kl`)`FEpuyE z=>9359Ha!ynid4p=bDw~=H`Brx1fp&q93Q~+RVLil2696Pk^-<_|ReJyL*#htNULNT?N1!!U6|aT7?zEyFVy!*%La+JS>A3m)(66USdFQ!^gYYpSLpDYxrTyp1QEB)?>D!HEROt-I^g`HML#$kF+%+j-aH`7tW1wrL0)3tiNy%7?Q}5 zB2Z13Sy2$-ic#XyB}4Z;zZi)XW$Ma-PtSvgCs!ai6@2h%j<8rgo4Lzku8F59^V%n%u)`|75Lexf{M zSU*Ap?zuW1NuUqT_%%I?X)J^XLXewUaJE9yANwxhPt>oV^ICNZ>;waFVm&doU**EB zhz;8NjPGnJ!Vn-tb~1ShZt()*#3h+NAK9r2A*CyXCL1MfkU|{+I81yx4_lVSNcYjt zOc8Fq@ET?cRxo4Z`sM4*1BPd!kMQ8Te?BA?brssxQ&G>~X3vpWAlZD=)9)A8&#=K#`o~Fg}3#3JfLK{ih9{vwv;y{VVX1`GCfivT;wusI!<) zdndrTZjPCXvE*MrA<~`^JaMYu{-#9A-V7nRE@*M_bqW{XL2ujBcsiIg(WwC3fOuVGDDcd%YUBImaZ$1lBb}ytFvT}8*y4zlXk|%is?c;gY`g}AB6I^>t*@Mv*XZIFezF_gM5`Ra=a@eY57Pe zGx*RSF`c+a0V^h0mt4ux&Sr8G9B}%MRtiLvqF45OT2BOf2}>E(w(eh*lIZvgD3}n> zO#d?*Wcbi`NjsV5SD#u;F`~tnMSZLs)YMa;zmHbNLW>#yvICrsaMb6ueVt$t&Lu9T zn7*&ew}(m~>!TG~F4)W>@dHm4x;-FxXwWyr1{nGtX{zEaq5zHhvPoZfW@S&THgTKW zjrys6iwMSW#W|gAGcs5k^{4r2q2nNh7ERieVgXswNkgQgYR~SK_TZ9>f5+fHKTxKz z^2q9@QerTv<#p9Hz9saLnL}KYXQ{FWi^p2qO9ab7Md9KMLlU56j%qhBlpiGYeo8LB-5##?>3Syx!b5$BDYR=y! zmjW^@J%kH9FWk*L|FY(r4j*Z+z+}Hg_OpxGK<4+o8ma|}=tO(}L|oM^bLMR5O2+i} zGhwxVOMpdwE`qL1fQ+Eho!5D^k+JB13B>V+eHUi!>OOJx!-f=P@< z-C<>c#^}WxR9e`bQGt65<4=j8(IV(|hYBQeM>B#fQZa9a7L~rmJq(1U9(i$^lRY+T zm&8Oz6KrrsWST#f;5_ytu;_|@+g7X*ffsxGA>?1?syq$VTYps|@1BsLuDniQ=mMLI z8@ETg>zD?4Y)ZPhvXZmtBuo>--$F+IXEmZbr%4;!+LecP6X~_LM{@WoOXW-cCOR>1 zNL3$In>KZ;M+rD8n39qNS+0`1)PArpdC(DPa^iX{h$j zF(O;k!lGSSjo0xy6Hhb%52&UE2ToF)A_ADTDs1ThnG4nLKkCGCEi;c4RX<(P$O3^b zcDvG$en(Pi&mmeOzoVJv28)@Zoj{Ep z@pm`m-t5hXuetAW^Oq^M{Pf(S@=;>bES^0(Of)GTl_+tgwX*!6kEs>b1D5$v)+)W1 z1N1OH&inl0P{;yEo%=qC-+f_`w`g0NvD$-mEsU5ISN(Q~`z`AfgVJwm)83|2jp}qg zw|A+6$_*?{$jroUivcxG!wNeNN%J+;;QmKb;b23A5yh4f0%)Agvu8ye zPy=i;KI7kjtFy%ZW*TKNRN90C_ItqzFdEql(OY*?Of@{{T;D9|tZnkcwRv5XZHG@W zGxRhj({a2BexR`O0L$lXpoHL=)(1NwUL}>gUzU!I2IGPwSYCrwIqxOG&jvnN&cP_D zMpq+X2M4h?h1TWtGb zNg@@T3Lwq-XDpBs4S%3gU6g+8WX#Bf+>hrK8!Komp*!fhE=uazBveI_`Qhd9uz@kUx zeG{CoZQFOLbeg}CdoKgu?^IP@Q`^xpZGEefJLmPBW+F}cXX8A&Rn3OHlXbC_N>c6c zV#YY?4^)`@&~N5=4In7g8FR)(c0!gi^pW` z6Q+ah^WwVKm^rIgt=ikRr%->)H)SFT>Bz;THtX(uyHm^@qF?N@m%%7}*mCKmC;d#p z@Xu>!=4P-qx{=VD3cSs}J9?cNX^RAfbJ=?)3uPDVHIXYtv*lJE61LDiIg+4}dn}cUpw7Q!Z5mjFv#eex8xO%dC?zRQhaU(fVIz-e zn<>&eAKU%U(3CRU5(_)NZN40M*x-M=R(u@VI5|Hjjs1h7)*(TvVV75aaYeG9ca@z! zY!%2qbWmIPl!C^I=>+Qpg)zO9jTJqS{a{~3>qFB$ zJ^>qlqhpR@wdbA(y07Z9q7y4MFCDJaZS*cGn;ITM6^LrZ72r*O5`PjUw1$ITQWU+GjU{T7lBYgvv zgjK#Nw3-+jAV@g!yzObAI4J&J0Zqnm(k5<#SM&xlYaT6}v>kA#mp#vX#L`s0%} zb)pAZ5VPtH&CZEn`~{G%{dgS;C(h2FP7dUoyCa8YQ*Oo8Y|QJSnTR!rBjr#I=&j@S z@I6;ytY~yW<%+7a*ZF;1#LKs=i$n0BcRSLh`m~rtEZ`)pO6GxKZqeK`9B5j83iIqD z*aTAqyOg7CWSr+v!SHXR%YrPpCG`HumH(lsJCM3@VDSz6gnwkw!AS>llg96Oumww3 zBzKJIjIHu0-NW7OJh}gO?tpOEynwZMCI5PVz~+7%(IN!R`e@96j8NpJ~dskKI$H?#WPvW;R}3-L&{wazt;mJ(j+b73!?3g-OPQ^hz$2u%-RUL)0`*BrwE!V6&Q;+ zF0yNvq9Xtny3%^5jye}u5rKtg^wA)$f=WyixzvCI{oyF15^*@IqiJ;G`hSaPjH9e^ zW+YW5z66C;c#EfLeN*nHEl{Jk_I64R4&>;eA-~I72%GHI^QY8opv)(#F_3hXg=cBw zHAphBSCe04{=71JDxi)#04jaa#`H_{z)RUzbw?76Kvf|`>4)&%+oO*ZKQO%^u_`+S z@H;nPO?es9s^m}CF?yMm<`2*lAK?M1v!OP!2yIPd99j?tGD4V68gxYfDRX<+L-h8dVN$n_*1>fdFpvI?m8JsX$;Y&>b6 z!300CeeHx^xMU+9KRejN!m?#stu z{qo;#EH0)&FYPc*!uwZQ(%tUjKhX#f?cKI(32b`{5A@cGRZL1H?1JmjVW`;4aPpbY zo_)(gYcM6nAu->J+3=}Jg{v%RG!@kUg{5jqAJTkVGh27J5&@>uITLfW%$VV{SGF=cjbWd#T|FUDBf+SZL!nY z>cWV57%xQSdap09=1t5R=xY6#q#Z6`e>3 zkbdvDPyGteW1lViSJjG+ZftOi)m^xn$(el#!#0(|-;0wTm)iWlr37_5$`$rmu%aM5 z3+xjFgKel!-t5ZPQ~h-5!p}z^z-#2ksxu7&&G<~w$=KyMN0ds4B~!{1B%mutfsbJ? z#F2HdZLC5r&dk?0i?n8_bnG#8l>b^L85)RSW-+l3BsEi(!SqQRnv-YB-9re}&R3uj z8NRX9B_YT(e~j_&56q;h50mY=cqVln*#2BqNqyam89heVhHhOa8)@Q0Crrv1rEl3r zkF@dEz?@nr`|v1WLij>7e$&_D@snL_-n_8`|Hi(Jrs?5dK3VFdk*co>{W8L7%{Z)L zT|Q5Rmtr=Sj(te8pPG`pjz7VzHJ?s!dZkB-7ucI4+Rm^p8Me+q(07l!KDs@_$$lpK zu_?GIJd*K4Ae-y@gFk-PrLCwC!L<%k_uH;abFQKrOrGo~3m8JMcZH(E2L=C%DWvVI z`PhMpphC$k?H~v$IF#qT@r2us`dn_H#*h{~Kp6C_L8;0{G$Tc)gsj;o90B!fRv3+# zJu;r#CuHj^hIR~qWH-VRcr9=#5 zE?YokOE#y&9;+ntFB~Z3H+*NoDTzE8-yLXoL<;^DJ<#UlZqY`?SuMdgR1sH^x$;y1 z8zhj~E)idFXi?|paKC}oRtZjiAqh4j>3zNP(G(gixst~JXW{-i1oV*{Yr$tUln2b# zbQ<@;uTcasKNQ-gGcNttxs_yfZxpbH706WJo`$pptS~_i-|k9}z&9eUJqc6!_Vf;Z zG|tCcB(>}!PnG9du~n))1m_NQ!N#jrn((sXL@74N+*Ua86Ygqqq)M$t3%CK|tG~1T zdx?)@zt1JB1$@vNe+O%Mn!nw7y2X7y*JZEFC%oh4pjPUEKa*r34|g>&(La>$@wmI( ztYpdJ;Nx6GScJDEF4Q&IYjG`9kV;Jy;9$UpCRN*>R#UPsky+t;)AK8jzAh5Jq}t8q z`>jld`dH$cbuI!B2Amq6Ulh=W&>gehW9?6Gfsp(qvZ+5`wenkl0msiR+j`Zp&zTRn zbI?~j5YZG~LJ)^`jCP`D1H9f7L?&vf;Z$z^yOI1xqf{I7;&=S_g#IX%3B9yq_dbi? z*M0@K;n=@0ZAKusz>i`wW^j@Y7-7(NkVcEQIMtWLtn8t8Y1a2%Iws-t|4g zqF8#b7FKyB2BFo894e8lDhmjqsZ6&T2;+C(q~qBx9nXdTvK;t58tR(EHPFP}lzSG+ z?W4PMz=-1L(2kc$drw-*g%K-HLL@I2jzgRQ^%jY4&9k)RM7nZs&8e2OiwbGF@PTQ zvoTG&lTd`=*JVUP+ON4g8Xo6fqG^Q;cDI%r=jG$$qz*tOgmTO}mtcsxJ7*+I8$&e*k&xYJBp0i(RvR zA;?75LVVzkK#_+upaQ_w&s5PnbU+DfuL#S44D5_`IRyzw^`Afwu-A*RDLWD>P&Cg7 zI(^Q8h|Oswo*CS6{*Ii7qtd)v#8-;~6(H_KY;%7i=%e7JO2)Bad;YPiY2H<(H6(_+j@Fa%2iB9r(W!)LiT&h#T z;@KCznKgXG{eIkaaJRABT|VVgzUyI1hr)*}EaZc1@k6~+U=(8c-+7Fh2yq2y1t^qj zEB=jU6|7Y_M57igxqXw){ z4Bg@6mEc&dcFAPXos2rDjw%~-)vnB~aF zLVg?^KE>(iDS1M*bEeZta3+|6_55jYd9U)mZ`;8;2fO>u)7(ArCwKgy6+sGa?X}qF z8ces*^pd=$IOvrk58^IYX8lW%#nD8iQ$-8rVp zO`;+^(YtWR51krljkgNpq1*_@zg`kwS07`_{9@O`Ia5X56kVxZka%g!-~4CK`$tRS z@i89hfGa)JbVTNr^O=?t!3@pPZWHFj^Ch7@gCenS*R5QKZ}zB{Jl#Sp|%IH_?c8A2l4S0T7&lVO3;n1H8pzb77^T|F`Z&d7V!(O26g_D zcne@nGSQ-cmnb>o zFp0>AC^xvzb8rI{FBUX?Ss-iY*1C2{42pd(_J9A%>_4TE;UbSlpDIbT{s?b^OTAb+ z#+l)p7$g-{W_b=LaBtxK70l9(iZ9RJ>ukeNv5XvYq@9oL0^zRgBugjEp&UO~M$+T_ zejlH5j*`KKQyi*PX3sB^jQV+2012JLcP7%ND4=50DpH#!nHC+!b3oyazh~!J03ukQ z1<|Psn+-!gM$)mnnKgO4=}q%$_QIn-zS;?{E|E%nmgH}w9**eD_D^= zAiD({$>(yp3&4`j7pxrG<%YD%!st6NJYYoswO9dVMrHbGm{K{L!<_rsY;Md0PQF`F zZf{G3VXP*^u=RDJ?5IJZPyLFqd{@)p3-uCVAa8H?FR{VZa9{M52RvXXy_xEF&M*)X?x#QxVJCSoBmk|CvkdRPgLK^Vg2Nvuou+HnJsT9DW4I zEp|s&IATcXaQx(mT^;#T{@~W`3t;2^dZ0e~uY8FoXXrt0F}t6B9V|ham+?FPf~S9a zzp23lOn;E5Q%pg^)gNVj;JsQ;q8a>}wra~eTxi=y)cEId7ysJxO2Uky(+V|oo$A`h z#n;Z!=H1@#eJWR4m)h3v_*B6_#VEt`dP*+HSpb1nHg?;QrtCS+^i5hx>>-+gW4}sfu9J#>z@~TOhNw+e=s>g@X*f64 zu>4|xuD=sA9#{7}P2d+_XzLu;LZB%nhmD)^tFg{<>}g4dat~Cp#D(tIw&kw%X8v8% z=i1|iVozd=6mNf*0{e5yE8ReK zaWwL$+~jNztgRmT9nOPIQoh_sTa>(;;OAUA8UwcB-XZ)YfcS&8w)KwFOlg0>;V;zT zJ-vw&Y-qKDJ?xu^5qAwC^BehE^xFgNxl@@yIp)m%m^o-yoS1qK=p$`95w@Yb%JcQi zUip@JV=lfC-NJK9((%Yv`8UMk2}8>4FaP3D)4B-74cEna6&Z-q^eNWUg0tRhotz>5 zJRdNH9q&?6_mwAdtB%=?LUCvn!j?L0rs4U)_Nethh zVhop4uTX}2-M*eSGGwqKdK1Ho+SA=-R5D*45Bh?dvjA@2w4 z+Lz<3=WC@L!bY{7K8cdbooSm)=QB4h^N0D@q6Q09d-FSAe-K(?bs$)?DSK=3vbAZD zht;*uRn{aOgX;#z*4>pWASX_UyV`M{6=L0+$Ft9i_DyYi8o;4%gdUHv{dfvf;u^_H zF+Zc#fU%~pe(JL1oA5^g2#DZsCZF47kd|1T$bt1h9M}E2G9PG^#m57~PQ_KR@zn3* z6Dt7-aA#Wk=W$g0!wW)_mkqi1mlxUE&G;U$LvIuI$Q0EeX$T;(b9iU0H3zQlq=(%m z3r3Gor*C#G4M--*2!O^j9= z*KTIRO|a;we6dqq0U%fbRlpHE6)b5Q)`U+q0_dZT3sPv9gu=_!wR-2*oC-fl#XS7< zefNF)rGjlmEn(cepQ$tU%u}l`E#g4J#wK?Y7pgaE z%s>QPTTO>COel&OXORd+@k0X_@}TI8h(O_ z;L~^dmy@z3jUVU_<~togKfQitW0izT4v%X)>EP3VC_|Wc41y+99|sw2b4YwP!INF}i<>-?6-_Mkn@)nL#(fM?)SLC=gtaCn+*pQr6jll=O!ERz3{*>EsW$ z#8#k@Aq%w+e{Z4jP#Vo7t#>J?u+Fl=EN}Bj z>|+}=FFtauT|GfTOWRjlVf-AB+UAKVZIt0t?w?wrlEo+q{QnV}ZMRU?F&;e!|$gu)pP1nnzik_w7~ElKIXX zg!gH7Fu|*83%)e*){g-q*uD3($i=wIxggU*uX&%@K@r{&foY}5O z^>XxGMTy22xAY?cY_y5^06r3Sg4;wRol`x7U%Fo6n9r;T6n;`@nnvg4J)__;A^wZ@ zy09K0x1sA2@IQ1XSGphpfxR{os~KOqSkKEPF|CrNuQj-%RG*xgk1 z6#S$YONuJ5F)OF1*=pGY*j()YiG-F;+F=@R$;5nS#bi3$(uu7yarix7v@!p)WDXKw z?nMV>!$Hc~uR0gFRYlNCpvfvo`_UsygM+b_Xq-d8z{8#Ts?TO}a>-_mPv(!GafUn^Ub)7@F*u7vNDsgWogwPLK7ro-igp88*B>ld zpB8EB+%L+>7|qW|x;u=XEB%*`h+6Gy$S)KqJ-=T+?keoG(6vsKV zfVw$ZTMX;$xoF_Yvn;wdZ%@0bh(x3JojSQ=JG>-v7}brS#(8DsZ)r}~uS{cCt`Y>J z(2vl=voV1M060ITIsEolUuu;fU21(sN7Hrb2)9ql|M)%<+NVH?>Ij6%&h>bVgl8`k zPlU9xC%q{hxbI&y#Q(Z~t7}rz#|X97l501a^(*o<+%70JW*VW9dN3O%XM}=`ZeL`- zKZdU+620!{`MxyXh!u^t+|3n=qCn6=gSyAFHN@h>tdX`k&wo9Ec5ELy8|P_eVP>@z z5>Mm#@w{XZ&7Rk3GFUlyG%2E#_3MM3Dl-Or{K`p))Sfqb`orCVp7F58LpBv(S-MpF z;YM-ci!s@j6=Go!&Zy=4MLcf6#;Hsv4DU2VT;17}xumD0SACSCd)4;3$OKn?)r>{E$PoraN-}J~xDfHulgD3lI5W z=~;MgKQFB-F-%8*eYWRsS&hOT%dAMHZPaj*Va>Ifw{X}BSg2$Y8#<9FmZKG=lxCr6 zbnp9IJb#jzsR3u1E_nk~F^X=`w8*)$WQ| zK(-162;f2GkV8gWqvP-Ltyx7gS-G0%Irp%jqfMX3jn?eC_tD!$pAVo0Orns37yF?l z>&j4;V={cBPre#(UMOuR#%fTEI1r`xGIO58wEgFJw$4p8e@7xK@G!)7uVVVBrZQ{B zWf@TW%JT3-cpO%?7qbf1j~R5d=W#&V$`5(>y$wu+{ORbmSBA&TJ-qIdtIl~ z_xkk!Rh7)fH<(UIL$K=L5@vk$a><1_Hd50T;AnZzb9wRil;akOa&f4^inl;bde9l> zTb-i5B{|NR^+yb|q*q@@^wnu;Y6@k0`QxVk9!yt^`{A&lV?)4nz>+Rt_QI=CwL0G> ziO`_7P9LLQ(~J6^r2I9rSh5e)c#O0*qw1Q5|6f%d2~Xd)hR}~mf`nV}R`F6fTIDrA z&+Xl;h8GEpgx`#HV5^wHXw0sS+4xu~Q>XwDC4N|>xOxpsYAQzez^3BkfF&8ue$X$u z3{J})k+uBvNCR=^T>N=tzZdgYg!j)0OJz87odM{HD3-|w(!NEG_9nIgkD9~ua@P&< z&0zke5Z|iegw*PW5|wgNAF(1fw7zPKA?YZj1|Y61O>Py{V$Y4aVvn9-#sRbRq?J(z z$DOA?j_g8BliL6PqF4v1h!+ema0Bck<=4O zP1hCAmfqZ z4-fk+FW&@pwtpg2YV8}-lHX{Us$eC)W>g(J@y za_WCL6LQU#~0lrwA z)#VwkcW%k>xZ%7aed|o>+GFwfiloErD2}+{=KDDP%5?7SYA)X24*0wfU$*;O0QsrlIV7A6|(k*~$ z%ZYi52xe}3RBC9-0prLwKr%qWL%(i1k$cbOVJ~>%6M|LIxb#k1^F|?fCJL$V4=D7+ zeoMEwkl29Df}JTSLIcwC4Vp5!cf1j()o}MBC)7qmtuQ6TR!Ku~+XvH3!A)F$h6f>~ zMT3lHi4|vRtDk5E>7-!L0TP*CEsC^-ZBAKu)G~+R1)bg-0l0;b>cshDxN7ADbAILm zs(^e=XIIX)b-|>cCVZU zc~MNWO>WmaWJG3?p#e$nR#d%i-sUImh6p<70`r6^lOo(f%(7x>r|8>uD~bDL>2i;D zr$*Tn>?zRxYdT=^=hN|a5exu^V>aj4KMQ@em;Y=bPzdb%PE|h!rNt~_dWu^B@ zN~>Yr*p`zbe3fDI(ytW{xrs>fAPNxZ(Qtk%pfi5nDRwXi&xqgnF)j#z=HL!)*fLxJ z6jbX@YN=r?etK@teo66b3sifesI`P#lH3ECSDn~*$ybYP_fE+n&dFy6toL!r4?I2! zCG>N2KQ?i&KL6g*1QgW!`cMh<08h4vszj^8=yTtRtzx0aA$CB+YcxU! z*3w?avTNJm_}j%_WT2j&(f!VUhT2iTPqB>>dqt!E$0V*Xv1*Cq3JPbu9@7y~d8vk& zuGI$=f<0F%e=q|2UJf8;I}U@%FI2xV?PU5Qyx=ha|60;|Op+r25t0TEeIC@wqZG={ z-Nb`|vj2+EW#64cEdhP4)|FK$}He{(@1v#l3=d$OCiFHvEzjJhkF6C{*k*@n zGmLn#{K~bsEOYf2fp~4}9&$)z(tG2BHHwfok zM~>>a+mv&71mF)v@5dDZuvrO}_lt>*vZQfWg8Ans&)1}d;gmm@Sxr?fabeem^vher z|BfTR{w*_Uc7yD=nvPsHpd_Pl2bjn&Sw(cCVR@D7sayI-vvS_~-uv5wKxhFQXTg9VK7BTwC3O;VQIMkHuhi z1UF#8wMy)OUJd(>nwjxt?OAP%Ph0Ozj+T#piCGQH;?abBFYLE!7#|30$9xUtW+Qar z0sg9PDhCJtb}i!+rcCwgC+5_rF<;2p-&eR`3vR|*pmQIf;_EeH4HoIkl()bjNu2%M zA4*5k7}xM-1AG6c(@H8RfXOX|NHkKC39Gwv72`|K;;K?8R4%Ahv`(7!6J6tf_+w2iC=#erYXR`%zwmRw4#IG zyCD0;sDwe}C~W;$?@OR?YOuwPJxkX2hyqsi;U6JBKeS6WA+Ejd=+AXl6VS3l__fGB zetwf;mz)xySn&Q5 z!vZhgu5FG!y|8~LcBCRTP{y@`nm4mSg5KCVi-?jIwf$%^NU_Kgk5id~;H~iFXTRQo z8hdQF!dVlQN710c1*`%3<3WZy7*|;=03yw!C=cjuqTN3D!r!$p{NmnpV)f8!V6s1H z-KsX_cpV5VZ&EtG-SS$uSL zN14^oe)d}Er^aymjL^gC$34Lcxg-8$%#<}27_f0bJ86m7`vbg3`F%^#*=OZ3VOI9L z&que)hki7agpO+PV{VX4_qyppJZtt-EA|!~jA73dL;)Z{Zk63~$R)`!Ky8wOqD6^^ z5}H^RR5~80S`An^f%Z1MvRmG%(3)BSE>L~Apk8&khau_XehYlw)uc7AeCGA{WQ$zD zD+%jJSGDfS>Z8(dZuTXfco=RUF&C?wX+9N*1G| zPz}=2b3o+4!AVmA)VNUJn5$Pk$uAtvILKH2N!pdyUy&$xOq>cZ`OJ!{IJZfZBl;-wjTbdViuyt}+&wcTWHA&`H zg8`c-%Iveym@AULa2S1AIoj(!wH$wqHb1UfT$oUwqia?_R066xi_YvzF|P2@-CxXd z8O=ogd`!kY1+fc67y1oX^C-|WDpxOEX?OwLcAhk;I2&S?ado~~)jmuu@@PPUQZ>z3 z^>rnW?~xcnb^g0Oifqz&%$u;T;6Hfms#ab{b8`FA?B_9-qg37`8Eq^vdQDgyP~h;; zeT>eeC{d5Ka`j_9y?zE;X2SqL@$u^VEc+UQxnk8oIh$7SvRVI6h^|`y#R$KpaeA0` zxL^RsJjjHZAk(5mzl=sC{RZKP+736+6?6a1c z#mNDq7%6ZdKzcbr@gRD3lQGF_U$+knk;ktQY_oc0+HE6}mXX?Vs`5X;=pziz^;0{v z%McgEd4ciOI$cRru$Tob!EAwiad<5eer@@|8aK>Zc^XCnHdAwCW(b?UOlC;j@IW|h zO+CHPI_Pa`3E1Fda2^j2WrfGb9hGI7?c5}2-~kV-9no4!4{r_pe^&=Rt_!c~7(NKr z-|b6{FyNPiA|9tKf*OSF&MkSCS!b8uO^n($$yZls&!#E_P7OMCD$+^2D8U3a4(C73 zWL1iFWATHUM@KBdbNu#J~dK7XjVsy7eQt)r!u^5)x-(P_~d=+>qG7n=G zLNHpws$1aq=>ZeSzfXm~_KBc}{Kxq?Cg2R#i9Ub6$A>j0^)z^csIte2Rfjl>Gtdb1 zo&)mX*=wvZ^zlRf4Jx^Csqi}w&gE!*%UzN&7jG`QYSj*0aA`p7H#=BX739TOQ^sCZh;aexY6qY7=qC@9~2gRJ?ALseZmsL6;UpEd65m_Vq zH7Mh}mq!mIo0J?kUtaE`b&QS&DW)zLJN0+? zD3gt_7`)Fi=7&)f*@?WkP9zuA#-9^Xs8Pwzeocp0tss2Q0vCphDjxF~^)(hMwsB>& zp@!x=A$-lc<0J<{EU3u}V&c}jR?k<#)@3?A55fAnVgwV2-u4Pqsf=fR((AhYPEet;<(Y6@b5sNo?J*8){Zz=AQJ*VG zhE;c}SdIl=itW?T)WRMeuAS_6g5PL>9OEM>lLD+-Yxom#<%Mi!HAQowuLRf?Ti*ri zv}gZ<$1LzZC5x3S@sp1gZAUlxkElpuz30v2wg@RY zoEjSZ#RY3Ove!G;H5q6$PnBRrq7)Sz9L1t>F$=v!bAs?v%BccZd|j=y>WPMqg0rk~ zLc~;()bBi$X1D4rWc;*q55xumnPntHbZ~^^*to}NdTU7sW8apb+K!CvhjEHj(*u5&KOM5r# zjE2KXm$>&sJA3?}!(bLh6oLMMttUw2?S|E$Q>d4Nk$Wq`qAluEe*y4Gx`Tukh=#3i z!}k(~`y_Uz{&6SxEq&&nWIJcH;-G01q^tLdR4?)I$!tLB(fSvoXUJf{QSQ0vU0y*yH-p|ugl%1>;PS9 zmKF7}v`~8re%Ci0Lv{RCxrAkcz5|brWww=M6g31oxHJp>rU$Qn4=g>EFL`Rx8G#M7 z2CEH*p`N3(Dxf>0s!F#oC)2|1PBJu($r}1vs9Jo!@FSYWw6^)(1_Y_AyUhtH!4HlKCby}xaBKSL`JGNTg^US#R8l0ZebU9}9%JGyYUoX2S%>e$Z|)pk z1c1&>RM#S_P!8k3GXN|v`=RPQY20Mz12`M7E_uJ8L4)LKe`#lG4TI>pwVd!@vmDPZ z1lCt}+@Y*VuUQ8xg1&!=t-4jjIcMcrW}XdN++_&*({tqetlP3{No}&=RkqjcFvilU z<8qaAfmyLw>}W9AlT$XoEFfN-#V;wM83dCwIXRLQi&fK)IQjpCRMM{CY=%(HpN`MC z>7JMnO(gAJ%qwDm9DYTi^lwjsy_oAfqwV9~G<$b^OEhAn!O?H4?qZ;)KW8bY#dSbW zAsA~iX!3({L6h{geE38-uOfKJu_}M4bpo&C^IR3=d*#ZpN}sMx3sAicK~YGE>t11t zm~+1%vRg}?>HW6_`z`n8O#}L;XwQZ7{yxzWYgp%T>zii<$Nb{=M&rjEuU4?gwhQJD zkxNB(Sl^d(*$%APPk3-|>2qqO{Jw411*Y%$cKCUh`p1d7iTKI=>nx&WEV`PD{PWaU z-Lyoz0>wI=47Pu>{n~O^xcRjV`}HeW*`!Y zW!!o~NpSml>0Y5ebpyZNKMu`?=+B8E-m{kM2uPbj%AP3`FBM?cf0Rc1Y#Qip9|$8u zO^}MFnP9gZM|$jRM9!9*{HydSF>JsF&b6)s&jrDuh|t3}^Xy0@&kt_Dn}o8eLmknk z#g;!q^}c+qqV2To^Ba9+X>i>slo-KsZHH+6R{IZ1*;aa1 z&Qjm})Yxvk>L=ppjn%%nF{zGY3p=A@*c^{H1)p1ZPh z?&#L-C%$TI39cR76@4f1g?FyP&r!l^APXhwXM>P5{WxQ4c;T@AXnnY7#sWDxZRe}0 zK6rl#$!=f%ZtYu6FN>K1?@v)Sp?1t$8QOqFI6)dExodg{kLz0NdZ5f>J)bKd|4rw)(G&+#=Y4{;@|$_9SLVuBKu{C zIP(Hd<>=SP(eb}=5i~)R*oWVmsEhW6Lgvv`fy~kwlJWt)9K|l5lc|KSG)gR@m-OQS3PHY@;^<%aAB12`^Hk~uqd)LnLuoA;dg@ATaIMb> zzxS5F$ejKUO<&m-RpWhqhM|=1W)zSSkdkhc1}TwF=`N8TLb|1-J4L!Bhc2lBiJ?mg z>F#HK&-K4Qz+7`)oU``cYp=bQR{V96H@ms#*)kgw1jnOsp-MHJ`t;D-{{BM-vvYsl zq-feWNzzP>5$BE8{3;DHn(eiQYre*$eD(*i!9>3M=J?hPI(iM`)Vh8oJ^= z9#lFnbi>L<_cABz_t?48prua0Guzyssumx=w| z&sb$wOz!rtlPVP?NbN+r*;#8D8lyYL1odZ&F>_K*roTE59!nzW){HjF3GP+?4!LF9 z+noYE;K*O!c5op!JQ%pQ+<(21iMq#u>s;rrkeSc`K;eKb~=I@b$Nj zgGlG`HwunFQ&oZZ09gqO-{-;y%A3XsDXGUWK(@#F?FSrd5pMX^|K0<(-P`CmlFx*s z2b?tZPo0qwt*~1GUI!X6HS=VqLx2wGF|`o;;Xd5XRv_`rHnjM`ZWW~78v$FzV|z1o z;K_Ww=8qp87c%P+e5wSU;kzBL66nntP86?-`}%?yE>5@*TE8o!-~9CAKyeT9PADD$ zMZE5e((u>WZ%UR`_W%+yrO#J@qsn@yxAr;AK?NX~*0COqU^KppGsY{Hn6O+O?6R=o z#KwA*j^=NjBxUXg8~YQvX5D{Kf86=<`0MY7!ADk+oAk%0;Afm}5F!nI z>31SYHbuWN1GSm#(EyKks#M&YX9^_z4^#XYxe&_V&;5Mlwb%zbsp4kn{_nE7b4UHO zZAimJb<~t0)X0c-MCm?C{O^iMXTabs!?TKKw6ZMSc*`9R<AKm+&&H>BqU+T*_T&AN&?Ch>-h^vn=< z2kw_e&(aN&9xg3LoEKoPS3Xu+zH|>pNZ;DCPJN;Ji*M-jfY=6h@M2e?CFlpN!(7t z7ybA_D#$GK0HTJCgFA5C9%jVn`=E5Q!`YuHY6t#&K1UsZl8=7b(c*ulBlTieu_Z=jT&Ash^sFu6$w!K>;Z*J1d4t6!tnfGeW418|(; zpifDgD*l|XImM#3IV*A0eL24>saNjcs3_=Y1G#9!bU1?p&>KBAqx>8|S9oI`iHN2` zyyVA5kI&ofUX?ae=#fbesr+`4+ezZ1B$cB{&I0+Zmz`yJ0md8AigqI#e~XsLDxbdk zmVV6B{RZVq>iqB)ftE^s5J##@?x=-Cr4lN7oSIkvn~m`PC?sVgdS6)&DLgCZ2YvaU zH>?vMaSC*hn|a?|F)VK4h%hchD$V@ghjz*e3dqa1?_223VThnvaaF{!gq$KK_xDla zqxz&S)VEO)d>OJZ5Qs&kvGr4`+e=M*C~@H&4QZfZzW4j(=FfVvwQvUBA|FX*q>aOj zVC(l$bT#nux#_Y|Uwd51xm86^w3p#&%&2z_bTQOf)8qru7f`y4odj3>J6wMZn;s5pcBOvSa+HW50 z$mRh|oDs5ov#*pmu;$6f-oFX$+&bS`&V_HIQNAd{EcbD;`yZGrt|3Af^LKu}umQQM z(h!{Xlj;s8%ALza=QN%uB&a^mu^q1Ltdon3u3Hd)VkOkp6SHXv!a?TMfQu@|j3J-njx{`sZ2oPq$P}?Zi9NR(J)%fYn@kq+iNQ+}WG7^3q zBM1;O$u1U%_G=%!$O4oPsqYiD#6NW(y0rlZppv$XusDW{=eCK(P0=0ey=bc#=Rw(t z`BB}sVN1g}Dxy%^(QU}{GUch2CfBiukNuD-x2f$XQ16!&lVos2z1bP2I#_(`neu`x zCtBje&sd#5_FGix;^?c781O5-pTya^^S_O6<5Yd0rxUZ8h3c@?x+iG2v+!?h$lfwK z05Xjl(;iaH2nIW{^KaVR;Adq6+`jB=^fPRXkrQrhgN=#4ul$+@-6?Y#YGtOf7--Pd z%rg|k<2R*bV4Z_{9U~UTV=0_QNu!mZYSigTa=YGzyPrC*htNYfoghYRjR-r_cIZ|P-23jL1k7Y@bLPXhLkZd}Cv@r&PPo(vd) zLVj#rCO?+t?bzh(OhaG{`<2drNA|}lkkP!vkC1_4ev(YXh%&M9c{~T!Em^}nJYZ!y zk;Op?$7EhYkBDz|55e568JB7dyBzE=+U&ep@~hnJObBl>LTkRBy&ZVd>6G+*XC?ne z0Pk^R$>Xyv;5@|3)AfD$(OV%!(IZ}{;37gEwVC6vJMD~W3%f(_6~oH4qj&v3{n5a2 zk@ReO&ju9IlRPiUedkP($#93`Zz^et z((`lUL?!3R{cZ)-U<@y^WRVy>J(;lkzD7eLHRqm|%X!5ZrZliEME~Zo@>1xS4}Ezb zuhr~^YSj{A2xEcA;9%K8CcOT=qQ!Q_C1I1p%>w)FgUdgvmwQ z{h1y1&Opamf=G`n-w+o5VHKja=)-lB&4nch=)|@M^y8nogFlmAo1VxlzD2AZ(kzV? zN8Y#{BaDJqA+`3$UkS=85Z$+RQnREIZu7qJRm?}PUm(ahiabi&%?R^OE=@7j ztrX{mA)Nme|aA$wn46QVmhaTzx00-eR$BJOc)MH=3eE;+AS|ry|f7+UW8<#kYg3G}id zO>MKL9t@8V1vyK2Ps5}#Kr-RfI9!)+6(y!26K8j@do*}DKc9@e;y^&r>yPOaJl?Iu zoTc_j`LOkPIXv)e>7U0dg+lnHvC zlF>#UrzcOB*nv4jh+HSc06mNIXSVR|Mz0R9>a4xThjDn@tG0Et0issEWxh>#_C6Z%uX#4b zl?A$YRDMw|{eB}d31Z!D`4SBZiuM`Uf09rC;<}K;EN~Kf9nfSf;Ee%nM9GTeR|2^^ zCvMq`KdNr=qVqfM%RB1lQgsJO3Iqc9ClpT9(+>do6WAt~cS9)w=u@;$6*1HG^A^4v z5Z4pj*W#92r6k~J5mZp=Zf|ySt4e)Be{;?&whUf6%R64cWZB2arzw*uN8u!Gyq>Bb zP_Nti=Y~qN8$3I-uERjQ-Je*-BI{2}rh&b`>`KC-08Ij`~uw~|6P0FIKg#`+&fAoXyl_sV?{^HFodI8Fh_M5IXW z_e_D8t9FLRO@hz2nmKv;S=8$#HdGSo{iw05$`a7Uc>BFG9Z{vUH@oG*T@V-a_-f<< zsdT||%Wz-iL(TcvK{iYKsP`yP@>)90&vERd=!TwBm$lr#Q*dC_i5XPr6t4h)^?)? zl533te(EV z=vb(RsgUzv6P5SuK>5Zf;2#-w^^gQlx$lycx%ITRS0)kpitbI{$c?h=t9E~~R3+W= zFO@W`&Xk!3^QR#)?nA8goEf)kj=0#XyylVp!F5L2A=vLwyYu?9VU0j=(Dcl-ls8# zEWCU`vxRG=PeGA8c4NGw+D{u$cqECLiZRz5nDrszZ%XjM%(AvLOcB^tpPEzMmC#*f z*{wjkwZ1b+_`#u$XvH*J`rvI`JM_6DJ3M|o9%H8oFTnT38-@JyR#~IkQc1#+Y{>G% zZ;GeDwJouAL#ng*3r66+a&2~A(_xIoM?vszU@#@&QIZCDOsf0Fur_&Qmho#u{(5prlgVz` zw}3p`DSxcx?;N5ED0AL}gRBGsuMwuEe5zV;f_is;iV^%32zhGwd&QDk)AmEx>yI#CQ zp4W=7%b+#-Ws{BX_3g;IK3n|m`o-5(0!3D6MPD2UizZ$CA{rz9Cn);9Gko-A2qTcm zW_KY3m6#DIi*I(9j6Y5irki1mv@Z$)p#tInE^;M&4et`@V`@q~KWO62H(m^byxjNg z6p5^V_Z5wm#*HNM4PPVsBFx4kgoah18qIi-Ox0<-#E8>o%S^-AGPA<6kI}{>xFC~k zK9NbH>*{&D+d4oA;z#9L_K2UG#_#toWAoCn)s9u`_&tXU^4*XW{0;cnUlP5HMx6gt z_2|%6N{HtM1vfpB_D?T)*|KM%LS$?8IG0zWk7q&uB5yS!JvY8AAdF`JP+NI4eE%kf zoVF}Y+JuBUHx(J$Gm&_mwAo#_a@zdz2u96Hnq#tL^E+7<{hVORQ(D@&C$gP>&4L-f z|H$mb__%oat+rGV+p?EL#+zfAoLRabUzwHqDqhW&`GhG<(epL^;=%UrW4`~2$iy#>R-<% zlH=tAzP^-XB}>b)-=5Wu|4O9;(IueLkGJi^?F8|Ig&cO8## zkH>?0C6-#LyrU8Or*8l3P?iAgS((`xuKI#X=BXnz&*<>2)YMw7M=~+Gs^Bp^f*q=- z@=H(mNk6qw`u^`3*;!y++P;BXvt#jl{!eyVS1xgzt@f|g(_zU30b>1O6=y4&U>TUe zklFmXE}KV|H4QBNSWc!93ztX}L~bn%z=xNZszSTtWygom05hd{0WtG ztW?epO@ZK1h5&E-T$XmtXAR@d;VLhCI>F|+5f)gbGKS8~AM?$;LlU7%3mJVu2HJ@i zv*K2g|JL`-LhCGSK=q_)M_Muu-@|Li`b6gmRTF%7zw_hBxzB3VnQAuwkc-VBK7a49DYAr}RB;J^=bq<~@ zfCD&r9ybUVBrzz_AEPY_WICoYmdr!Y;3U?mvVV`*b?eHMW2uM#Lx3dfR=Depg=t6`WY zW4v04RddbDX4O+4XJ^8{pK*VCUu~-!8jA!aw8VYz4yM+d)1I3p&mrTOj!1aG_(IF0 zwQ{dW^+t8S&Xl2cEIhE4lh&;@8PT|4JUMQIn{_`C(s4Wcko#CiClux;oYmegW*o#x z63U$vcS+w(d2o1mYblVSyi(=4xNa2o<^rRe>n0u6@X_a)blb-O#(IHgvlGXwTf`)r z)%{3|gkM~7dFDDi4=o)y9a+bUewvIT@m+4lHPzA^eL;iYgz1O4cJlDnrUI==N~yOp z?PX$@e^R;og>tH3f1kgQpVgT(PSGc(X9s?`A~KLiV-Z$ zkRwB_$F8>zt>lt3tZEq0XwKKGYJI0N`W^b)pHHv1jEHX9t_@r(8s#T+qgjXywscfh_%^E&XiZj zQJu-#=4;esu}|et9PA_3UCz^O$U1bQ|Dx|9r5$@!Cc6zV0v00g-YEL_K$C|PlV#CN zp0fd&qmhuAKVB^4jNKvoqp4btx(*NJ2asKLlQ)8ZcEe8;$8>I_a;dHeS{zR#hy`Y> z;JMC9EK6FO9~nU?zM@~3N0kFeDa5E&;~Z0JMaqxiTsjsSWRS+Pyw-WTmF~4J7cd*e zY(*!7wBYCk%di&Vbq71si;OCWyfR>C1MFS+(-DSiTBP$1OaMOVyc1JKCK*yR#ht+V ziS|gMjDyOz_EMJj8s@BQvcWX(%?s=obPfsW3f*$*lu$#?R|fHdRT77b;h#qF7d&f# z!K|gsGCiSVV|?_Vp)~o{%kTUIg>;(c{Ho-Fr_P%l{Hld`;h&T<6virD++*sL9op)8 zJDm3r?!i9g5bxm&1m$}iZXGI#*BS~PgID@MDD{wzVptK~Z%a+291>{mO-uF&$jh}7 z9Z4ImtIy?mWN_{!>&;iLHm#zjmQjH$=!y1L|O@ZF{*v&-d+f zM25S&HRo@$e+dw?9n!!^;LQx|xKyx(;eiwl?|ipNrxYKsRE&9pktm{ncmeR0s|4$J zD{l@#k-z>7?IbbB?4;}9&7SKM5%_#gCn&@?`hcusfyMCr7%f;vOCkGd;Qoka1tpt5 z4r0tq`7D9jwniM0eoYgK%UYg`g_HsrYxZ`19?8sDI`{$&6YT zzBPnoM`ybE#Ql65)POQhI(hqx6?EBv;^ZhG+L3B0e@6|G%DUU5rDZL=uU?A^JEyE7 zKDQLiD#ik=k+^f|$1u)jOW)Mvj|B?xczJv69Zv#^Gon?&e9(&k%jkd+VJmB4@IUZg z^oqru+A9O|AT4~bRM2jPN%uytmil4Ph}Hc?g!V@;mUzrZr!=De0ntW|T^}v2gf`T1 zgug)2nabjWPyaApL5`3*Dn3`~CrFfJ%=%NS0XuKjc{crX%M&J>cj#T86QE=!N`g?W z0Dg9{%P`X8vQ5>R20nH7O2Z? z|G-`IjciZO_Zz>^!sf3C2WaE%vTz#WyDTw3YORGq=nrt3l1P%xi7`}VS5R0TomjKg zo`xjyp5&O`m57&cJyJ*2eDb&*Pnm*kHJf}j|6h*Odym2 zNX8=;vBunV>4tDhmz(tOIWN!3Clh5m9nKbHRcRFPZ;c?rv_|SK`QG+4|8Y$IEyqva zEd8favZM9g^wF@L{fh(a6r_yQPlfSj>@9~CUY52^v`Y}7;I94Ghhy?R#3uDL(1m?P zhY3Kyl9wIZ{z0Wez_sLiCo^RWrZv_tn)(joB-U+nDXLue0eZ{{sl1{-*^%Q7VAn2O4Qz$ZWuV_{aO``pzW8&|Jud{4YDO8y?R9aHtPUsZ&C@7cOD7 z9eA=7;UIxIafZEz)Vf3@?$f49d6ShWq;K({o+4I@A`D0+K43?6_it?e;N-F{M#;n-P-=S z#<#!RgA z5*$vel@~rPyRDRcP#i7_f?Flk74-xpv+)}8dS@N8uq^=A!XM92DG_Knt798x7xDbb zh$!yESCWOIU$hF@l=s}~Q_C$B zaK&~?t<9Rb&^cBOgKYnlI)=SGOTL;G=wcy*NVo1!UJj#QtS6GV|AsA~!qRw?Zhmsj zx5y8HC5TwGAUJ7t@n}7TmX8{TgQlQUw|FL^SX)0uO5llGp#$4%HBL-2uXt$d*7_pr z$UE#yy@=%pESst)mn(o>B}|B<|x6>mecC~021!oGVl77dud;#oGgFyuXCsufV!=6N=L*nJszc-j>3O0IEYoG=N~{1Haq~-Y z7ai2`yJ32Nx4AWUYCBPSU#JE`%!HP^^VtMjhwr95ISTG7WIUR`tf?^Nwz91Y6>o6; zT0EulPR}d(*s-KdpH~?|y@X113z#H{_UP1zuzhh&5A-j{j_Y_yY8=A-&;llDRL%yA zK$K!n14=ca?g8Jg*r8=Aw17fY=S9f!ly(Gl;m(I^E4gvK# zuQ7UgAO0Imvo^Nx7c^!iLaiS-+VoM|pJ0ay_L?EVQ&yX#d6x+4OB%~1ezw{dnJYjI zLQCm%?*aOJ*re^Y7cPf<#hcJqJ7=H$&r+t&=xQ3HATkr5U{rpA2p^6;;XU7UHaGGR zb!XhcRfnJFKUzwlaO2U@G_W&`C1>!4;gs;e?`XbId+B#cbPBjHmX0fNj|wZTlo5)*{DXG9+&ljbSULA z_p@*BG5>BWI@yX>)m@Z)U?n?LUrip76BA%9DsY6>lDyfmnB@4>@tI*Z)`Xnsmbmwz zCHZv*0|U;VTttO*V_z2HEqYPAEYwxPx z=e8>Pm3Vh2))AAJ|3=x`-Y+~-;f8N)sO;PUT8E@<;+qzrS8yDL2>DkrhZcp^LH0yjD+A@oSDoJ`% zvxJM3X1tKKA>j~z%P7U%rfb?bgJ?kY0O<3;O#G7+LK#guj5F)wzS z!P(jH^{>Om20ECKL`AeFf8#?8_H4U=Qc7uu?V0A3hc~~m3CXTQ0*CrftMi4>6%+BW zIAH}+`FlHz2Yg^#tS5|8co4tkWf*kjR9Qv%VE__#c;LJ*WmIdrcubH+=`nA*<{;JE ze0qfJu|8y_O+ja%IAkRL*Of8X8M*h(m)eE<@Znfr&e7UGjYs+yazNTG?2bznRU76E zXjDnt82J-t3Q6JGsO~3>1;d$Bm18=p%J$Sx_iqbBHcWLk%A~6LsXfaH3F09t39Wf( z-gx5A7yiy3s(`v~)T(v`&}t*%uU_`?7uRN}9>`QSmnpJ8dSOElERr|))XJ*1yXlU_ ziU)~{{rA}ApVj_HH|P6G6ah&)>Tq=n$~Bi!j}6tX*HoPL469Q&QA6G*8BO)GxQY}N zz%jA;-;VnNXMYfNo@&XjulNq?HDI*pF|#p8S(_qR`~8p z*X=sgfeIur;a3^UD#+o_&}`Onjnv*m4?c z;x`i)y4e->*z=-pus29#|MzPaASLz{4@96L&55b&y@?Vs<7SxylgfW;Sd&fLMwq}v zC%!L~NY^JTM!l-c*)g@WoA{s+}ppA$4>{w13 zDTWRIr2pprp_%gKeo6`r>6pw4Jr438TP^rQ$Svd8nBA#^Ob6zj1OWCUy&9jUk%4VL z_I5|wPrAXkn?PKC1+@EB!DW=%K!9q@!^ix#$U6q*M@~SC16_m&!VAL`<+&LMtgKEi zrArroebdgMuXu6`P(H>^Qk1_F#e?p8B`h!~MS3?8vz6S+jznZ#C9Y}qh_f(k5CFYi zca(83nVJ8AG;e@l4--%@PSl_@mHa?-=)UQkDz?#hQcqG4y}*F;{wA9=B>E6IVv&vO zC07qpDMuScjA6lrfoGx&&fyiP2SxE9lY?vb){G*u{-#^0Bq;!)=CR&MKt+YYLf6i$ zlFOOHJy6v2gu$NxkeN|9c?z%zT=dcbRj+g9(%2A+Sd&w_PCF0MdYvPmH8Qwm8f(`T z+C4AH8kSOKtWshK^sc#lk0PkC%4A@CU-#k~Ku6?O>^4~MpPCTs{4S<@zSD7Ztaag&e?BbokXaE2Om?ki`H3%=&R^_i|rg_rD{p0gpJx*Zq<) zlTmU~KUXmV5tY>Nhlh^wVVxa54g4f__j<`EB(P$+IQ*cgdevW)fTOhnWK#zHidDV1 zRdNWdANSqblW3z;t7`UB&b4gx378!Bj32(@>?rs`_AhtV;YN3OTipE)=ouzDZJhp( zcZrm^l4_P{xUe^y>%?&j>aXc<_E@Z5oY+4hnVn7TAPxU`$7XTROWD`|Pox;--=+M* zUM1Kr1cUs_>7T?w&tF{JeH%G(t~FQK!t*R^|NJRCZ~Ech47R|v3--Ed4C2b|AHsry zN3xr1XKKG5^?&>}y`e3B_VvE2t7`&7!tJB)df(v!;RUpN`s&5(Ky!~tf2&%uqJ@(a zr<;)P2Yq$%@reMglaA0Uoag1i6F9UV_Xduk(TALGy{S`EnC&#=>p87%;WPRerlNIN+^Y|% zvC9iu^|U!xBoW@5`DBdvId3(Gl%^!Szken)0Iv!thJD>@pZ2TSW}})VeEhCT*|6NM z?W>=WESvAmJ+C|lv_bcq@;4|NevVKD97;D`8c$)u1%??f$%I}y9hQWcpkZ#^@ijor!JX7A>Ae#~AAC@B7S`YeWfK>54Z7chL#r^!KOyj+G#Q}I`x+H> z+@VELh|0nUOzkHawNRhSvra%^Fi@{|7{g$ zFpC4oOs^^-mRZKnW#^)hf-?NU`V*E-@A1pDmgz|{q#}RGjhJX7pRayU6r0!k=C0j5B)iT=rH&4_R`e*8QD~Q#4s~%? z$^fr@dAIz?ucv*AvlLhXq)O8ST>dsBA4fZ*8zLEZq~}YhX>08>Kf^jM4|x~2d_T{| z4=Wz{bcg&|YMxUk7hl12ZA#4NL%R6LMVes_b zK8eFO^F$Y0-r^*W>z91fEErrG;+{wEXu`apDCx%u-Waf$c=1*-W|`L;-2QRPmP~(P zy>B6ts(tuMG~inHHH5wTI4L{XU1JpO= zOhOxuQAYRg{3jUIWy(tBJY(6mbD zS5(494WJg^ND_1XMr-;69c4RRET6jdVhp%5L)lNw{P}^>DvH#&%Dt1kYV#HNACsXp zMNodnS}i$cjA?Q<4w&4f0Kh5ly%+$GoisMPqfx=t|GC=Bmv7WusXtO8+u3y`0HRa| z#Z^>+M)Sq>r>&?i7bq_QN*Ixjiz%rW&rlRo4wv_|HF{SoLB4yYHP}ZBUqt;pfO3xO zCg8Yto0+TM6DMGD0ic9LjnREFCH7pyn2bKu5!&i~w()~rUtb6lm#f2O3-gFJwZS!~ zR54)|pu8ug#OkLyB>ZhLzf8LrHVKB~Pn^uqZprwF3IKwW&ut;8m@UTGIo4pcd`y5; zx3$!RGUw^ei-IzwO0?d*6e7x=VJL{-_g93?su0(qfO>Q`qb)?x;8fOMep+zC9ln)B z4Wj_m*|imuL8RxgBy{OoSX3NBPX%{AT5U@Oc;kMBrJdTFof*JaC!K$iLJZ7?-f_ES zU4qnciN0d-CFRya4_}9PmT0GeX^nM5lw&QFRfT|N*&OJtPNd7Ar|sGMZ!~zFKQpjl zdO+^>{hPw1Bi$+ASm44ITZHz+3&I?@`h_sNd>ZQCH3BSwBnSn>X8B{=?! zsJAdX5tDj*$Wk6o8ScF5n58}V8RY3kKRx9#BIV%1(A8{QbJarpq<%vph=Gsm4Q>2a zEbr0xOad zHU*a;3>=FQ=(F58`y)m30}ditDs}VGVIu;9MwHw^_@%<0!dUF5>c>7sNz0cN_05OJ z#qw>hdgk((`jX}2AcgZE4f|3>UI|I8ew=q>So0SouA-Heor8t1%uZ1C-3V*!jntk1*%O|FomA<7xo=CJ$n3cA$F*dT*= z@l;Z)VqoUz?LRA7yo9sF10q;I?TtO|o5$3(74w@%t}9h|Sn4u&>G_=g9vL{-&gZ@a z;yq=84^THSL41d@3R9E@j3B_7NdKk$V}SaeG~uj{$}TigvQ!G>HIHJ+wOu=8&|U7p z#Vg!CQ0E;hTEu~-7V0Y}kVnbS1%z(X`Bzr$`Ps;WeHhuqhe&`!g1i;RY8V@dh>IKGD(uFr`1~D zcF&Bg^)kfZiQZKh{1$-%4fF5K368{R#5E1siYi3sha;0~Oa2C?^KT#yKz7}HK6{tM zoogvJP7oY{go51_)+HX%R~J@v*j6-#NRemzr%B##Tz@1H6R@1L8AZQ*odKn zwm3ETb4XD}gu~iw+YRp1~#5?0#+x4K}p510T^5&`Y za7mI|{*&q9PnR(r<5xm)6|)WV0Dqu>5RK~hm1wiOX+sBhjOVt*>av2sasbAX>E8-p zlU>y|{o}Vk;s0Ngp%(cbbhhRDW9x})CQBXR^6VdT#z1F>HOtz340~tH)$jGnYhwUP z=5fUXzb7^l(D43BR^gpu;PavVg~LCmhtD?tCbKhX7Hx!~K zoL~~GXmOIwWjLssycNYOeI?KnimpU@FAx6(!dq5*izk))FC)r?xlPY>`yrI=$-FoF zuK|D{5Ny&P0RniJIBK7>h1np<)I=sR%LZX1Sb<`kQ5?G&(&tWr0Ki(LPhMV*rkxpJ z94UKi82EI<2()ydsY${n5aZW%75#YPoKLsfFo_SSrvx}a(`5-jWc?YkIhcfle9Ge~ zQY|~^(SG=%#XH|ckkK#Sw(3i(X3b$d5UaPspQvd(j2|n1Os>9t$HV0gV)h~d-)LVN55peMM7x-VGLpD0MXH4A!;>HQlC;Gjk+rUmfo@BBl;3WdHF(d=i;2N^> zRxyW`yDrvDJHF$Q^JaQR{GbzQu~+o`F_3IloHOI>Hq`(8)L*d3ziC0Vs_~ouLh+;6 z`JA3c0YA2X?-^B)%OH-{K8gA#N?CrRaP=_$vy4#xUxfGMlUzU>QdsKwf)<=lZ^%Wf z|3B`lI3+8a>W^9~-aF-!647BKxxkH|#{Bp&9*N4ioV20(fl|+BMxs zgwTNL)k|l&l-T>@=YEYEn*|DHFNbnoc+Qk8?}gGfHpjSStcSPVRO2<-xaaRNAS%3S zjvk+`qr05AUdjrzOSM~tBN^7eGd||)KgfCo-Df2kMT2lR(1I>y>FjXPM@>g4dlR^V)^5R-^jezEAMI+#u~x&eP`j#oZSrIbLaH^?*@Q z-*U2hS=-;smK~E(7X_4#CVxf+$HS;uKR`k}Z#0;n)bl-c0N|NZSEmbFRd7Qs^~;>e zOj7DX%IB&mW&<0N#%$}V2C3E>$#fNWoLnxvwIrK0WegNm<@G_#ffx>L58hamB#xk~ z`gq{T{l(wHEK*0McoDDWXEUhrfH3ARm>=L5x@`*4w_#dlUX{$yG!ZSDLjD8m!;Q3X zx1KPRtX7WOD1zR#GwiQbGn}%(a`6ImOsRG8&{^7pG-NorMw_X1%4Z07x9)w)GTnHC(xK32(HG6 z{{95oI0pWdIhy>Uov|@4xx6$_-j$rzC&xS_dhk|`uVdju>RpEy zmq>|G2(?z?fvgor*aM|DQV5r&U&M~r&-Z7ND5rB=w13vl*pWpLIjRbls0i2W!6*UW z4=W%{N-NHQA#ZM`eIs7dr6GhRA@+csSFI6eCjY0c5A@iVq5OdO+P^(SHu-^7-FnXE z6CiyIz$PCDeEDSnt!xj|S2mt_=bXA;zaxeid`2Q<3RX~RnI>NaD06w+F1m|p__0%g zNOlh8JqOS)@$$6<^(R?l&;j{5cYd}H*bd5^NojHSJsCYdjT=oVGoBzf_P+_Y{6Y7~UzcvN#p99Q z;}=*PJu;0rxS>OQ-t+qH5WIeU87<|LE>}rbNuEXy&_xWUx)1LQxJE&%#y<#7?oM!W z1`v7UtNw^Sm%BsePpuAC$#gLdJ|<&x0$1HW{-X3ZKMPFG@WZ@aFI}YBN+gGKs4D}! z`;LNQ2`K#))8SCg&{bJ7qk_1@J)_7DS^y1lF?n-+P30FR&|gIfYnD@((vS^nm)H5Z z)4SNn&-WP=AYh-j^RM7FJG<$1diJR!~;Q({g>`9mJqnQ z5-*^PfllTkBm->O;8iNG)ciGg6>G1LU?$4{EM%#2>Tx~pS|jYS;X!Gz)25GXz`xSR zz~J*qmA=dJ@#D8OCUjbQ5HJ&n-&?xph{)lJVffyum5V3lFbz_m`(1*o2WK~doU|#Y zd@mK^-lSd_n7jGEqu!3`?UTiT${VI{U5aQ$0=$Z>6q|@HNDp{sm4DR^hxkL%)hkQ? zz!*$H%DQgJneHvM{GnVQJbNTXRGxduEbjA4uEEb{vAQhn5kV%4KeTSkd2U#DlKd9m zTvGE4T$uo09>&#Fo2}LKZ~d-+U}-HxwAJ0(Vh3#)jsyv}e(J4mje9l_&NK5m>{C!| zb5)~`0-cZZtx>N@yVE#OMB(0`hqnM^F>Xtco{~_HlQQrmHk+r?J$9cScn+ggo+thu zSTy5+@VH4Nf4p~7l%h07)a|I4n;Ejh>P6%-6lg+Jy5nq(JMJC*%wv-qp%eQSSnmL{C?%1Bi?Ce%?!d7{Xjw-B#z-WY zU|YcmdE}kVPU_vH(!uxXrYFT9Ne2?ZwWm07iH4Q?&)plqb8>WZ!+6`OIQGkU&6$5u zi%m7qCfTST4uaxmQa{Vz7nQ?&c9BVav%Dz}Y<{~p!mHYA#Q^*#ACQ<8rNYbRHi-<> zK_ZN{c#N5Zy143fbV;pNrvtn$ZXhh-9Df*wIFhKrp)5ZIeP{xG;grih|I%fyNq5xQkJ)}~+(iXf*Aaom9 zUqd$_T+K`yKT~v8<*8}eekFrqt2p*komJxXS?G3u7sI|HIt%eeBk|TkLzHUQ&D&p| z1S^Q(oz2MtWG0}Og13f}@~yaSYUa8`sx7KE8zG;9P)qBGu1mk^fe`QG`gqZp(w2dl zhw}(;7qly}HOzV{kb6N#oL$}f*Sd#POMm|1Ijq*4kMK@ch}t9z`qa^mE1SGf4XrcH zH3E*DFD2u@F%)!bj)XRdm93T+3`#44caFxRZ!dDu7qe4w+1?X5a**eK>mV0s0ELQ8 zmC5UqR8nm{2+y~&iV9!$nj7f>1oc!}Ou64&K4T{&^uJBuT&AE|s8Ma4@evUT-Nt8JQJ1NtCjrpIin^6 zhlGp7J`)fUKAEX0h+W-;{I|Wn2wB&BMVam=|7iheu?q0ij@Rv=2JvJH*>L?daE9TV z8=NG>`K(|aQgZdXU$nf#eFVP(W7<&S-)_|6HiAKaA<_M1(OJoo@QAf2@k9`NPMvJ&;-=#N@k}Vc(YnQSi!A+yu0}n#?+T|N4A8mmjbK)H zLK9KR1VSTjR3P=Ay9?&9RHCV25yv6`<)LjURTZ_E%rr>3HF78456zmV1I3M^I52U5 zGnQjl870)TCz~h95uD!sa*VK(Z?qOx6O$J*%{ z7F$eDE1^u?keWB;M(T+vT6fY&5_=3@1p+1sBB7q(-n$3X!uRVdS&bz&=7f}AgM zzbT@Puqv@E@!;D}oh?936H1k!30`ibQ>L3l!rB7!%YsB-V!)w%ABO_hm(stks_X}< zcOVUz+yf|ckVInEfLt zEMNZdNlWEu1LNbk@S12__WD1UGhiT+e{T-Kl^7mn{{h2fSvUXaBx(a88WFAyR=V zo83f-i#mLZEDdwq_A=-#C|(#}$yIiS}wooKI&V zL>5w_yXvc$N*$$`ds4q*KG3_hK6u)16A}19iN~-y7FiRG`WNfQwTj-S!-Jo0w4+O_ z&9N<-l^s;YCX}FZD&yWyplLG@#3)w5=aBaX9jo4X%O5T!F!O5o~qsg<iDiTG^YseBhK&`ETk}t}r=SYejVbz>akYIZHglYKORD&^Z|~ohk|T$k z9};F|{zPiPQIy=vGQV@N{jdB!nfG7oPrFCa9#eUMm1x_mSm*tOy>@2y05&+811+i? zl)&wfqSj2u1^+t7r~>?rX#j~_WilP@O)W+LcNuaI+=nkO0>66`eQg<-XzeD0pO(&7 z*=Yc?O2YZ?y@l8sPnl9h%F*cUedpxIWG_zv4h0d8#jxdGfU=C@>T%9zic%r{uI=#q z?m?M&zRykO*v~58m9)#)IlO}eB}AcT`0Jmq6%s>VZ38b~W??8n?B}@5=U=ny6XSkC zNAG#fO4j&Nrx-gh_jw{O%lq}845M59j=etPzi2+48%&Cc!DKzOwIN#s>Qr>Urw-{i zPpWku33v>3)BYb#XBiMxxPARIjI?yO(kb07FqE{kba!_R1|%b|6 z1q9j}8%j=Mtb6;NF()O%N7(Z-{ZC9U)`553C zHhq6ufZm||v#mit@M_d?Y`pro>yExEvm26+cmsHQE;!7x7Z%qNx6cOZI{+Gt%>)_K>+W?`BgfTmM6ZW`#N#I(lKRdd|$P($M!sR5f>pFQ+C*v9|7&SBH?F zOrA_5$(1BWd&dSDG>6otObF3sX3sw-<7}9HIl`AA#=AwCj0&f9=jcs?KlB>mcw6D3 zh6{g3Pe{u3n3*y;l5q}^rx@q(*0fLqwX}dGYKEEX>}Etrj+QhgFUE7_nx002xvlT9 zp_Z!(PM-Ga2l*Ku(1rva6!G<9)u1Xy!tNfbp|N_DfSXKVGM$6*2S(0@W4&} zygWjYd+cJhb834UQwq40?%Tm*e^^p^a)N}t&FEa9*;(*VfiOsA+L|E~L1#erf{Jte z*3Il0M8y zE?)#%ltaSRtEhP`q5WKak#XeewR%dI2Cwf+RqkRopaC zRcF|qaYx2Gn0`4JS+kN$F64C_U5FUp!?lrwNv<=DOS=4Bqx(cK02^~7Z*59Bt};* z^zvM}ETntbQIx(ti6r=t8yPrA+LX>4xRjgIHWEzsn5Gja`IQ+A&+N0M%BS1fkGx>r{EY_PcwF5Z%gbFsXS z(p~uZ!gn@5kYK~8@S|$g9rBP0d0%R&E(MZ6X6J-Bk+o2%SUsxW8Bzi)9Yx)7L;_0| z+d#T_5DZ;tx%;P~4}z~zAuDqLzOp#N{- zsGOtJ)~V=_OtSW4(`*9QJ9Dh9xgj<*sdZ%#u1PSpmasX6A2O1b#Wx28!ULH=@)-ex=x&Js<@}B&N zKw6b&E$R?eA8?FOBbv`v#jpFEQzIumjooH_lYk6j+pJc()n-PnL)@5W@YL-DQ}i4p z02#{**`LyS`BlSRyK&QO8#PjKf0D)dZ}14klnePars4|qu_mj70Eon~dOiP$^>?Mq za7R~k%4rn2~j+ML6d?3apm%v{*ojOzYDE8DO7zTPzBqRhL2 ztsJw3*OXGgO(Fft{;a^Itl(`H%eW6AXG4fchl7`~dX#r}5X8wRuit{3A;j1LNcAc8 zR$YSZeoeHUFp`WmQQXQNaP5||pOp+?KS$pGjtGgO2LD;368>`8-I6Z={T$1zuy&my zAdU^+a%$ieh1UChxm>OcBfafr;aS zhxZD!=F~Ok)d;7(En2j;zSrdz=uJ*Hlku@=p#kiwIfx?^vZhkjC6K16n|N$!Ct|4U z-Z#w^><3jGe0*X16zckv-D`#_GgoPUfmtpkJC{zKcX}+ww#*+)NM3Wp;#{a&F>ye! zT6_6$IUXgD$I=rs(w9>3UDxsKqR2pajhKhnlTh1tqBRP5QKM!}CGt#&CZUg1zM^Oj zA1LpQmQbp7!7H2?R;9m;%MkUAN)QMtm@*(&OYj>KdEW-B?1!#{K{a5dT3Lob=Q6fz z-h#VqX||~K9D#lNi)TMjzCScDVwT>vUAUD6i3;W$5mp^ zjFyBgds@phr^g2gME@acl@Gnvv`g2Cn2k?)M4i#Id5DDPJ!jIfDn+cwUfoa5DV4}u zhkA@R_!MJ{KGOK4sTHbxc`yf|yGf1SHvC`vavaj)h76t`Yp8_GRQRyq;^R~v=s)tk z7p3Ty=Ic38c{txhj-{fl0jng_b`%$E@6Bu`D-$vD^14;P_6k>@pVke~Ch<*IBw^tN+!EzgGB61lXbVzf5nA8Mn>wYU6Lr zpDoAq3!>Nz{=@*}Ew?$A>f_Uw@3UW}SIubP1Y2e|hOCh?X_G|HM^;qoqG{OEb5z{{LVj5=hn_=t^wZdw8O%Kb=$$_RTwEDWW4_oyv~Hm>x)M%G1;J_vYHUS%QJ%Cf;;|Jk);MJI-4TzRh5st z7vZm`huIBH=|{$oVt;C0*EnYCoM^F+=6&^u3Q_8TYJCv%#U)@s8w&>sT%}m@{~`vg z*Byja$376tm^KE_fZ*FLZwyVQuc?oR;9<{0cNWzaq3bIfRiIQ;I?Hm7wa0aw%esZx zHmjQgIeBo~uA(oCuA4(yZm>Uw#}svn?HMn+%sYO4*R@OOp58FT2k6SiVGfyhpo~uA*;2=H)iUj1(n4 zgK2(qC&0n?u>k>?+D(382vv8$JEX%}zs`-E;qMrZ$Z=*yR)lBdT*)jd=(V_gjliNl zCENxw_VuHJSl8Q{N&YqTy=ivHck2b619o?2RXW!8p{3xow9`En{vPAU$r;tSOPW}% z)qr)S+13r4^*9@3!oecQX$4U!c69g?;o_|Las^Fp6QPit|Gm@V{Sz7dxh5Y0;)jSL{cn{N)V?+P-g;MruGF%J=B| z{*!^CYoESiEobe9{HauzHvt#b1l{p?K;D}yyr}1%2fFzj&u1K)IZqqb-S7XLbPJTS zj4Tx$ug;$JF#$rz$Zjwvif%scixDHpWIg3KXY?jW5%@3=ndF_d9+cXHK?QdLqV9hL z8=he~F$htwT&gn&(bdGgTxGNIDCoz97Kt9leH&u?DwY%pIS|7g6q0P1E>W0s-zDeY z+!f-n{{2(H7~PyIRG^P-fm8fUG)c}u$l@%`tzPd4CDP$i?+5fhOe8I#!Y>+XqS>~Q zo3kc|E>?}WK%34W{_^q`t`fDGkmXQ{-e6SY=?hPhkqQT!I0I#V#-83*6@A{&D5}(d z6i6nka;>}abE@jXFNLx8^}urq54sG$`~0sQS=>}Uw9upF7RKxs=v`k&w59jA{zczM zPLV*4O8p|-G2mGIQQa2GQPdhS4tWn#Lb=G-i3_L*;+Pt$ZPQWMMiC1QJz;<;nqGI6 ze=%maIOJCi>Gsg}k1!=bTl~j?V}4xZHXEWWm8?^7BH?@@HPd;li)147XfVZfT6YfP z?vd38M_PyNa}e)j)+Zc;E~MHw{2Z#4ABvJs)xMlHj_kOd?`(%c&;MH+9$)a1?^pmiQ3lq~nJ@j?g*sR%AJ~O3 zMBAr)SP+e9PiCpF&{=7o<15F?y{w)TxMu$?Qc0MZ_PebWQTn*Nuz>A@eITNDacc#B zfwl??jODz#x{}O)K6Qzc(4Gxmx(qy9z4_daC1HLJe+5p7i?(|M`w&4!aFXDMt9u&u zyPZrk==e8=GjH13ZNVD#hiX!h28-A#N| zhO({`fXxpxUe77gEs_4x&o>r^VRk_shnhB0*gk&S(~E2w~}&@)H*a4=+1 zr;?9oeeptoWf=#lJCG@dNWA>JBDobGa zV^I%p?PvTOhanB|MTx-aQ@U|x3hN8bR`a(9@i%EbXN4OvJ?;qmh2WXB?EHM2 zZ0I%WZGYJ8ntsb>EvW)d$vfRFwNM&Pf~k_U4~$e#lrewQT(f^-}@ukcg9scAsvDN%D0kM*H2j4DHNZ9ebB#&$PPpAx1?Df4T`?hD#6Hn#*` zC-ZaY6_TM$MuB>qqq5?{e1&Yoi&K{qH*C{TuF)(25oI8_6~X%VXh_9P^^}!d3gZmR z51>`?9By^wY&2Fltt4-MG3*0tKbU8Ey%=-wX_w=yFJ1Xw{7RC#k4+sSJ@e?%onk4|31a0&;31 zs8kY^JzJEFnsZi17ySJ365|mxFpk*yMWaL8a9-HLh;^lsDQ<2T@7mbE5c9~^D(FM} z)g;>Ym<{~n7Mncp6S<2+0QWmna|Z0H@YAtz*RwCxdUS-Mfn4P8Rrz{M+B5wF_*ATR zW@!TzGRSJ1aq{eIi(_{}0X@GR4ml=UH(MJ_#1KCH- zvS9noaU}PQQsYzd2VgiX;+) ztF_Pq5kgY2o3rsjk(>MShp@Tt1PsWE;sm^`v7rLDe|lrTIaqrDs*2+q zE5~@0ZrI0@0N=9*-Xz7cnxMwI$GhqHwx@cAJ&VO*Gx;8FLLWLn zo~-8<;@cclcHYc~xA$4HZB3Xj3sC0uI#{ZtHNLy%d%sV_aEH$Qqw4AXz@vhn)#F2& zncrLj446!C01i3}*0>nB21s>0rt?u7WO~Yy#6OOS;vbW+Xr!Q34qjE5$#b-68@i7G@cL|ytEz#@4e=BU!Ha9O3^%G`-|xYwV{40 zztr_%2pYTo4YPlN!*M}jfAkiSY5;v-!F6LKL@Qnem-9V5XSLugW~4p>tv!(04F&#Sy(KKMWBUA$LvVaqQTZ!?aM7DV~J-71U$&_0m&sYHVoy z+tz>oD3(^y*XW+HggGN4{W$vpN3+^tvg1*ta2vlz8zp~M;}}>&c(lLi@B5MKBr3l_ zLs)1hBs)bEr`u0?^4fXwMd)vL5yO`hsy$6wM3lhvFT5P+&AQ4~N?eg;ak0~2;c&)x>Rf)+XRVy?mk&Es21ltb4U6*3YU80jDw z{*a6YMyd9{2HhyL?8&l+mr#p*9h7}V1;R4Vyz9jeUC(x}D3F-qAX3SKF-)E9LxMtX zHpypSQKEQ0EUI1VZ6zZ(;5vuBsZuNhB7WiTQaDX?TGC)H7HjW5zi|L!#8l(G$MT!I4p5oJ0B+3!Z#^&d+i2B$--V42?cMh{3W(8M=BCafH z|GJhkuGS{MZNfI&GflYH%%Flt;LJuX1U& zgdJFVLwp;WjPbWT1C%%#@0b*D=4gtcAr`@ToCBG4BB-mGJYI&5zme+80^xV|XpJY4 z92oC+BQiAj7tVH;=g>5SuCgP`OY&@PmYxGrGc@-~i6uFUSJn$2l&CC5owS$$WcA z(k}0gX7+oHO+Or{p6ZDb=vt|rD#ATgy3#|K24c8NVnN!(kX+PG)0(v~6+r{Or1TvY z*9jtWH&@y%K|qpe4o%}-&%!x#^eI(X#(Rt5daix<0?OSeKRmDGlYNi2yVvOh-Z84{ z)=|F6a!UQRbq9Z8BOCoZ+YFOfWTfMnOzBzt42awVER(hLEYY?T1P8lzs&@;G5;P~- z3cE$r(Jk*l=koDLqpC2ml+qdNFKh4GWTD!(&M;ljRcFWgPJovL8m{ z0$z7$D4$BzvkRV9#ETyr*!Ef~i=Zig*Plb)b?2Q918wlNq#(!wnSOrX;$PZBGfmTC)fHWH_rWB2Qh+g(0^M%)!uQz=FR!DqI zFLjm1#(1BW``4@Byc%Wi%_&)n_PuM|q~9kr<;#T!K7+KNZK&7seG4;-(9IwJ-83Ra z?O|qxtMxU$LZKCbHpIGUWq))#icIcM9mGiZi06~Nx8RO<6~%{OD9xI z>8I+A;cc5d*n*{VcW>JZdThF{sBz&PN@oNMz{Tp5&+|=j*hNDag#=y6 zREf0P&RG-DYgI6-Vzl1FBx+#&P1LZir4S{#>+{VJ2U$kiD}z~4k>1~KG}+`oeNx6dcU zA~S9MpYU+aNDsVPjFVKE9oQd-zkC&M<7IPm1)u#rURqkRN)h(B)aqPXnK?O7kbc~V zZ27h+G(f7IdQABX&3cq{jBpp@DHc0xZA%H^F0_;RJLa!TWFz!5oK@tjC1ojG0|a!S zo841C3h!uyqHjnI2WTKC%pV?;I?qo3RsGYZtjx`MQ^` zI6~0<$BG@T&zUSR{9?xSDKEb)h8i&D;cpT9p~GLvG^u(z4He%m#4@j8%(;;v@t86h zs7N~EWZ^T{JkX;}642Dg3Kb4sZZmbiKf(mBHrCV)E(O5o6g0LH3On;`cHadcaFmUp zLkJF)zBytyjM^gyltRE&(QWF}Pfv6R%NMjNH1Cf;K{`zJWt+axRszWS{!b=l@shog zMm2M9Dt}^^l~>7>eolsgS`I)(CLprmnxqAABoSaiZD62bJ~8^|P}D<6$m1&*O99jN zI-J?h<&a(GQ>$YpQ%(7~fcuJ_1vq)@_bUiUf^_R$+WcZ~?r3XsIoW_DtdeK1Nwszo z1AFx+57%J@PoVKGfpS}wQE5=hsXaa1qtUpFpW%5Gc5KDB7|sxqs+$_FnW`htt2g9* zr4R|xZe+}SYXxN}`cZ%hSL?i;l@plA@K!#sbK{3d$Hw)K5#dVfT{#Qd zG-bpqp>5@)x2d!-0(U}YZ(?q$T2}hFU>~R|^wTQLgB3V)|N0hIiy43S&Q4`m2u`7W z`N#!~c~Yr(-5dVwl6qYbT4G+IwAEs}M!FMddPmb1OAOU>3(HS~Vgt#Rq^MAAI`$A1 zU*u%4@2}59iRP+-93t+tuih>_k$pOG;NmzP7L!gMltQ6pd-#5JmB=`NK!qtb%VmD% z8>uMA=KlhtIn<*}Q#zI3t&MfXtL&j6Y&x^Y4SsPd2grBm zUk0SZC_Sc6Ugpcqp#TdR9>D?*^F;U^pbDoU)XN8W0odGtgGI9Ndqb#RbNlGy!*>qa#0>;ljtow6B z{Tzyuvq6n$Gpk*fGeVZq;Cc}LZrJ7XUgZ3zTdo&N{ycbY#m{RKogj(G$Oq8W8&`>( z!_IDWu}Y}nEpHgACuOBkXC6ZH#k-f;)eoArXY+>7zU8lvTL4&F&Ch77g_3F=g#Pp0 zuu3`tZH3;bUw8waN8O2te9}GEO?BX@_)?GB5F{EJrG^wDm+pdoyZPI@{w8W$O$g&` z%T9dyaq{VUVdEBiHc)LBc^_rE3P?`a?%BRRD`C9gL`@X1+xoom6EXHFa{wWbjq?4T zQE%+!&Q_=3+9OBszhlOCrcTU#+B%`kjh$YITr=JxsqoysZ;xank6R~bgXofq)pSRP zFFIycC9CK-(xXUV?`}zTk#%7&0zx9;F(SU?aA(QF=1T|!!$FDYicEHR+FHWFa0@al zu?_iM}=JVIa`rbQ*^xP@e2I)0o#VJ@Op@EK{%w@Tl|MvVo( zk}{`j>RQ@eY+$6=FCQR2{*>a_kqskK(ZD=oY#TB`wO1{u@z%_EpwC=&VCC3q>Q;_m35^`bAUO2ePR+IUR!Z*XyeJzQJ9wK~fiZz5 z29IK_boay8b<^6VF=uLQurT@gmFB3zpp!o$ym6>nz4jR#*KfJRM?M*Q+?}y!vViBY zC}=S*En?mY37@>WY3RlOcNkD)Au+}ZMeJX30>y_Yih7t*Osk(Wj#)hQ;2@r1aZtCh>?b#tDzj_F8HW2VEJL8_DZUl%Y`%&?quBe}x%I z0z63DOLYVDp~xX?(9q|_4_JI`y~vS&WQjwu7qw76zG$v&B(MHPg@k7HJ;4>?U=SS% zkN=|O=DapUvHNeTNYrfGwWN;`)JjhAnnp%D_CUZj+%KeV;-F^5LOFxULZ#BZY}@y$ z2u8@_FA1cMlfZ-vnqiWMzQ|QW#q=AaMbIpvZ71ikR8{#oM{GPObUl&LN}=ZEu<1`O zRCfb)l3~@g=7kDm(|u3em8Tnsb1ex8Qz0B&5-vGJ?+?p_{pFh)e7f6?dZ%2w0$$|? z4TkEK9-;gh>BZK(L`5zHJ=$>V zFi7hth^ueYC?!)Hlh ze}@W^8ck0lmO&SJQ!9#>KlHkVnOs?`Hcpa(Ib3e_C&2>zhg;|*7fJbaeV29R2QPQj zOvh32jyH2YPY9t)XDbZybF{;Fr2OS<PwC{VeN7QYM@D$ApE)DY#lP zsn~*0;rWc+3VeU6%$U~)tt{^2LNqcs48_bCqx60NRX1LJeszJDY!XuT%ydErL$Ra2 z#XE=M9rb>Q#$luntf_V3ZrYBLR0cZpCPVoUnc?K|+L``tyfVPV=yD8kKhbb~e`2P0 z9}CWZM8|6MJllU2xs*&rQlz;~Lu#ja zGY4nVAM$cv6hqNRtUG>dU9YY$1jj zD}xAqhAq@p<4>9EhfkKo@O>3GWlwHZv-lrZnTt}~T(zJw#YuDaMux?9&S4QhGwbs# z9$j;z-6U;|cDw_ibAUC_ME~lpoyPWOVQl+NeOn=@m27#R~U;oqKz*#+m zx~VH9%PP+^8Pc8_xdBi=#PO`9YKG4$ap89Avg_>ji1pX;G@cJKk_F2zr?Us-ll)(< zy^L2ZpVWUPFb$oLK`@ML=oNlmX7~I)7{p2ZJ!{}?QrY%2gHqm$@%?zomo#q7Q8hO= z`7rgHYQzPr>IN7V$z*tee(N3fBha&a$^}{1t#V88q7P1M%wM-h-!iWh9(>7JTy{M0 zpMNulibU(#|4wt88A-7<9JSj$TO1`mQ}#&36*S-XkLzSHO!c`Kau9MjOA|)KF>L8A z-(=P7JNW*J!ddcH-_WCyOKqoQ%#+QbJe_GTKX}6*J<^(jAWOt8K%C*{n5H7e3d`dhHOdB_` zxC~eC9)+~JuuFp5o&^J(Y#}Yd`)q!9%{fDeZLP*eXbGL5avNh4`+#Oz;E!OIMlcTc zY9T$S3VeU30=|a5GLb}w_LBgq4;@rZv8*o&XFF%^FGNZhz%Jy8ZI`w<&yJ@Dd6#uPie) zxSF=2leZo^`NWgCaUD*u;2`8EPbHHz@{!}X_uFmE3H=b43pEsV` zvAG7Xqv(#xBX0M~DtcA~@9Qh8Ud27Am4v?TYbFg5ka7W0f0#K4D+Yci$V(H3V*4*Y z)K7~z!5HGaT5fz1&#wj9hjhX&`HTsKT-6fCNI4?E8)szv0V8PZz~s;zfE2LZ4FV-rR=iMiI5Rw`s7jfOQ+_$6~fI|9&_vNuF^Ep7)+=>^hDMe_e zLkagh+xazRwQm)o9tGXfYFns*@;CB+C{yn&8s zuX}{ipFHd>qjaiqcr)r`$fu}tGI-fYC3+q@gDEQR#6bv<8uD}TIwyWCo#qia1%3zsm{E z_Huy&c~mK>OylJ$vy`ceBRLnE_YY$%UzP5e7|4{|9ju;+P!lzbPjJwHc^RAx$ce1> z3#~8+II&Z;O#@@$+Zq%2h_Bw`^=V|AWkAnGrqBPMIXUB>4*p|4Moysj;?xJEHjVML zLP#Jqe7SJ0T_7mY68jz=O#*(At+t6Fi#q3x^`aD3qY`r>Kdl6xUh+p*%f8RHIn7S4 zGAmj+aq(yV75d3mSZACsZq(!3p+1G>%#R$}%rDe0=4NMJPFPuW#Tce6seSM^dbckY zeq2k(5n?I)vv2z4b%u_cecm@M-hZmsIi2~{pVxd*R=3F?nolt=b#U&$UBESrvwdLa zb()m%l^|V9cfkMJWq}PVDaHU)TpdWT$x0e}X3mG-u$2xnK7%Sx#sylc) z!nu@gUE_RRoGO)QjXfJLb0b!0sw;W(ej2#}pKAe|^Q!*Z0Yk`Y&t3nMwx-0F49l}S z$ClCERZqhOF*Y81bI0gf0I|GcUtv@#ZkS&1r3M~gx@n>NWY%r=;fH0dVc@Gh_tNuT z>~$goV?|y;7ay&ZA{IT33?Z=PO6MuKd{y86&v{VR)!q7N<~X_Pq%eI z4I-fiX17KwQ_e>q!YF^s* z`;SR<(|_n>dVM)4rvIh+*w)x!dLPlI)}<}tt48f-vTU!^_7ki^Fm$_3<5K|pn=Dw- z+dvfLO<*n!k`&8eTGgP%dR`1_<`GQ5Aq{C27JddFioHGX_4^X4?fR?=QN=N?E06|5 zx5*uLEe4G-I`9XoB~zGpTDT#7HqS+Rn@SChj&jZ&J!a6@7uD<>)ROg*4${T%HC@A+ zEQ;qu=_Bg`6-)gP&Y~k}YU}QrmG7e?A{bgh*#ed+RfSM{K>B9FLl&CIpUnWQ3&qZz_X`X7Zr}xZSE6PU z*RZ^rtL~RZ0p{&xQ)s}T5zMmXwc!{krNRw;As^4&!^!h{13yXE ze3l#PelMCtWdm*;wcXW)u(cjkdNHuWtNQkBMDLzOxUcxgZANb)ocTsZwSBqR)ISN7 zq_!WhG}ak063WxMH4qrf_=ug73a?c^Jp)ICr`MI-+EBRhicO8^2e9={%ce%JG~#@Q@{dIo_qL_Lcq*SZe1 zOjX;4Sfhex*cfv=Fap#k|nwoH-`{rN-Mzm2sC?ZuZg?%?rb)p#?`oRP;C(iJ;^ zm;*DZ`S7>0xL!6az^@Ne-~|Jr+umXG(zHZFtn#8Aq~w!K@|m;Y1Bqz89W z_W#fKbUi_`N5aJt^_4}IBm3x_?-xN8(x+2=Q-PYO2CLRk(o+Rl^RodyCZ+q70Bv~O zM6ch1esj1n}Ix2z+72mMk9Iz|>4jf`k{NXT&vpCEJ>* zJr6;W!QZ*oBH;upZ|7O87Lzx;yG=>AYE{DYb`$NZUk#hPYI**QVFZs`1thlN+U>Fy z0=Z-Zu{?Hd%{=aUgaCg#`AHihJyojPBu*SC_FO=tC5zUW7V6(IR-uE)o0nLOVSrbu zQai?t->PP~K;`4&sxLASwKglRf<$Ip5!xe7q*UF zovEI4#`v$~kjkygT!h9aL!#cT&)9qaH2X_<5W)Tym=7^`mCPw5-(Gw_JYe$|z*U{mO zHtBxIsN7p0h?$+h$X2wo_;OErd}C}?>*;IvpF);nCk_Ay&i=`{kb00V@}7vB#J`g? zy@c2u!eiVhjpBfaasJo}i-M87a=}9s9u@Rqm)|Bxt5O|SU3l%%xBx^#og!qmN~ke( z`tLU$4xq`HE5U{L_G@da3ZAF1@!;#cZC{cpm9yti0*Ku&pCe5)xpSEU`&(rUH44@oY@`p)pGU?hJit%_{$KiH zBWbKb81OAq(uaX2);_cPI5h@HYzF6pTpIP!O(KIQy1}14_!ih`%H8uh;mtGuEL*&U zcG)?#L07_EB9`fJ$4Va`-BJYxJ&;Jp_I0RXHEtsLNeqD^@zj=2-WbJhVs9SXEp+2r5r{PiHg3OaK*Z~ZJ222X+0@NXJ5s@hSE6Xj1Em63snE9S zD2rq9=cWfy{*+Ycw$~kq99{1UP!*KPWeQqm_P=yH2f>BX+6!@^0;9#rkB@s30 z69=ycN0SaY*V!2MjA-oZap6=WR9aJe{m(jMx!~XDPPY35s2Dt*>n-w9=|jx zRnM1R|98!xp)Zif)Z?km>1P&$(|u*ao4irmz-xDcY7VT`BsD4(x_k~qf#Qi(yYOHG zZELfns4tcU44wfO50o|zVM$uNmOQJ+-Pdf8&WBnw8Qw$zBT`fzwB}PmjHF3qPZpWl zW12JNnQlF%1MK18$hZ=zQwL?&tQ77|7?~greqk2tRXWOh`gn|3`yn8f#o@!q(8m{m zvb^kDQID@8PlN#N-`+-%`_b|6{bUKw~gRZtt2!3*>3v#wZA^woA#>?9A1h^C-o&JEYJ)5Q)m#+fe_ zD0U#c?UKc*Ch<*ua*lRvXFe>Xd}nA5%!bHXOAeUyXG5C6n%k}ra+FxltES-LLqK)8 zo}vkF(o+@a+iBv#ZbwDyOycIb)pTHeFoE+N3l$1Cf!(Q&%l0!7UIcmu;LEH5)~b{R zz3zBoOsGvhk@Oxm|G<*OE{Y=7Gve1)`zCl9OCELCxt!z_wbgYbdWk@>|Xq!R|; zPmcT=sh*?RF#=_q$Xs-dgiPQi#X7Dg7uAm`6M97*(#b_*$f8Fux5H?>Fs;e6-kNjm z$*JXdp%Lx!T&-!r56h^_mXqu>Wi6m#5=^K#?e~5*U_xPLlfi+u*=R-gXvzaAzW~Ww zHX1eR7G!WMi&2|hQa`Rkbu#7teB^O~p563(Ife5}zj7b4uc$OXIpd{7m2i_ZCT#|-N-GkwwQr`XXQEVN}yRgKeyrvtFWnMU2f&|P4taz%}f<7 z(QQ!@7pxoO6^A6lz)wySt}##L6`2g-B*J~VhRut}{j&BRfd&t_ZdT#`fe^x5`9?dN*s5y3nD zSNy-CKF6CO7Z#mG3BfFD`OY{7;QXnm^$EBd1KLEa{RIy6rKj|WP+SHWLLElp@Ax}E z?_+*hq(`x#VkvGCg9Fk5>6Puq(({90LI&ptxE3kfsgY|5qc}9ETBAePB^`H)W_^O; zQ7!8~=vxt%rWf#u_i4HG0gM)VQR^IM^#1BJ$~GtUOS%jac2*I@Q7RPSThq{sSeUWN@l zgdMayWxN}ZW%93K-%m2s()d~OTKkJi0*B$AZz+R2`TT0bf~ytP0+0DLd3N|5MN`TE zPb;`pylR-|&Z;v9iM2B24<6olcyD5Ez++woqPll(rE73l_#1Ek(^$K)peR{|X(_O? zfYwkqvss$nZMs~$e#v%mHbO%B{EKUE9F_1P1HbxL5yiLb1=|$ug7-KDV&UZxhUn`b zWaf6%jpo%aTZld?#<|w=WjEFMv)`LH;&5z#ot<|&_gKVSA;)^l0t=CCt@{~*k7)Xn zNpN9?H%821SoYki)DwR~jX{NBPrN~Hc)0)K8xKa;t?s^BJ5T$U%ciib@ef!JIqsV!j9oGvesWq2tZ_doxGIqnX~K*qM5V&Mf**I4^M?# zanuCHf3Fa{^S=mLIbaqzsV5jgVitZ!G=c#Ojgae?EnkgTN^+tE$<&{nmMM_AQyinw z+`!NJe-!Oyq1bAcjIUK2cy)&*Jk->&d|dxZ63X!iQ-w$vm@O0E&P&2Xzw$+RI;8&vFiZ5R& zdLut3wSx8AcF6|agB=pE8ec8)9eX+`i^S9jiS8q|sH=MC zis}>rK$WS5cpS`>MK%8xAk+eyqijEAr}^qMd3SD$d=OHNdGY+V9#qwD2sh-~T^`w> zo{)_q`70Ja#q)!SzUc^fq_kH}?WrgB*Wmr^wxb^oiipbC{9a0j~ol+`N(j6i_bmt)5C7_ZL(%s!5Jv2i%(%tdSbIyA{ z&BvK*&%V~a|Lb0R{pMJ^>txFCOEIw|$WE`$sv^dd)R#RSzA$98kW@C}ak+l~JynY5xlK?lks}HHN?@Qb9jrYcZP~ zJgj?~Ao+`LMtGusw6X%S-ma;9Z+FZ^DFpOGTWHD>trd$ejFTMDm4Uk4MVwMp=Qo}1 zMw@B86+-MK_=h~^r8rfgI)eYYgRgk{vwjgqv}?Wc$?L?|&}jKMInerDQj%=F&nzb` zu2wz{-`HLr;j#*tZDJn9E#jk&p}vfp5%3Rwj=p{#&$st2)#{TaTC(Z}xw%2^;Tg#T zokYBz0-#y_m*ric6b}HCbKM_6s(Ig5 znhSy%f`*g<2hry^5_zu1&6qGaATgPQ9}?BNOy)3V@rF4YS*ni;f4&Q|iH@ghQ=w5GE%?yULQck4)Ug(rNwuk)=)(*rM`%xW}#AjLkQ@ZY!$WzcY zI{#oJ6u50}=9d&#`8mnH7+I$C^U6O2ATafH4D|DD&=--fp4DaB?ZvJXi(Ti!xRBHZHoK#r}U)yVjLZby}3hSKv9h z!lgYz4_RANE}s72&VBrm+&AbqMNjF&ph}lF04w8Iw7$Oz&f#k&*%1t=`@L$+W@w%a z0vZR6z<#?=zGbU^-QH>~*J7GOWWYV0A+%kU+Mz;t%WaM&`AKy@OrE8wnz>C)T=_TN zULgqY=1?<8#JDR=0%u#H6tsifO1Jf&2cXWlIYpJ`G9kZa(aCx_4D z9uSspQbu2ocC9q?X@0)*tZ?mO^%BAeR&~DFUCN%kaj-lBlfIi%$aMIziKidU1S__0 z@G`+j)2s@XY^#pAvcGj|7aEIa$^;dMbO^+ED-gw_S_q44=1 z_@ttk1BhyEbyG%++FU69$V8~`iI+yb)kk_vnEf=zdTC0C#hH!_sZXUrWD~8YR7xw} zK}RN^RUvg}{WjlVsZFxh;O7%(i&W(>aTH zhiK*o%_5A*FdYu>#>P?+f_sK?KFB?f1lipc!L3;AVKqwwSy8{AS|7)fbN+*aEyIJR z)ED$`Zf((JHA$KZ=nc4e=gpL*S@V;nThg6C!0J3O1ND>}Us8aScndW4nK&vq37r$h zbz7q6l*P@imPTTqH9VlJSj>Ohz`7tbR@gX^_OJUFJSks~l1wU`921<~$9S>XH9L@d z=s)*v|G-wWrxBh^;s;2y&&Bhl1PPS&H`A{qK1 z|IxX$-rUycBN@;qu*VADUy88`s;9#c$~lN)irDRU*_k3u2lcPt@IXv(8TRfozMuWNb!&s>fKQM?l98w z_*!hm#f0xCB=z8P04f{9;Y;>jm(6RiP#-~xY=>8@_C%0M;21nNat>yCwi@m?Ub63+ zB^LO>X7#Ka`#x5V4;NbLlU=&3k6Dv*j;m=MUtzut3 z+#-XDpEQ97)7*Z4vl#hrnN&VvF^@24J~5SlJtqfxvAx)u6D#oNzIYLD3ar9ju3-Gv zQHkyrUZr`4kB{gcALsZn_NPqx&VY8eHmhHmL~rsBi$^wPD3KBO1%>(fBg&oDHJsze z_vtcsCOLwhYvWA4&^p?u!aB@9U;rO)blIeV-M0xsC`9<>39 zTAfk7vl#9)UV3Ht0S|_u3GG?D12u9y`yV~SluKx^{cm!+zC(MY1;ak+f1_9`#I$aw3yX{Z`kGhdD)PWs%6WQ z>O0-`(#F1c=iL)OvM*7aQ>NCtj^464IG*IS~%tstG0cIlAz9fvH(^mT(t)XucaZr<_m0g{7f*u}HX{xGp|nWof+uGPwilU$XYAt? z0_>I(x%~wkv#h-UiJ!}EOKcsIEgEGB zlMTTWa-0fNAo4#k05nR4Kt{E{@6#rN^J##uQ*AU!G^t4F>2&e#MF|%IMGL1Ch5Wfi zSa%PvP8NU7KQ&X0dUhGE_D1`@kIs_C!WFJaV9*F)O875w=LD@3r;P9m9^Cqo;S*x6 z;C&gbZqE-CUZWSYc%`~=XW^4DG0WsmnB&$@>nA&)*owQL|1Sri%+d=SqG_^qi*`;O zxkB&BhZMPZ$8|!BI%`nWp`OU}NS-vA0Y+QzT=qB?+7%yEOrR0Fh!+lUQSxJlVN>k^IHnq%Xr+mg@U=;_8*Zc#jW2K41#V zUZJqaUQK)sl4SwbOdxFP07)8sAyHuZTgp@430Z9X8kxype0^EN~FqLfG zSB78-`G$G{g1}MTIdf-zq{f-Sz55m5QcHw;uRrzEWQUMY#Xxi&Diqi7dH;2xBJ>)m2}IjtBU*MCi&HF3k(Up7*a*jr%>AiQg0gSETLApXQl36mE*n`MxaqHI#FxH zxw3e8@jE(zs^y$ZNXkCWBMG3M*oBuff+@*FA7ncbnww=^%d>`EcJBubO>R`ApwP`S z)YYerr|C8`;5b9xx3*;weRspFn8f8?^A+IHAMVU_jTX z_a*Gdy(CMtAP`hlA+XmOg9@BuzXISPmbe!Ygoobp#TnNBNu9;o(aT>$F8_^l@fJ`? zIqMR7r{laS(t*TJo4{{%{N>%T?MNNQ)sps!=^!Zwo{ZR@fOg&$;Y{P}uMA4M4sg&) z8b1|?=NQ~ij?(2?9FRCkPa`MK1? zj%5^&mTmh9HRpq9yzCS;)6~}GR-+4?u0aCe85sEhn_R#Q$KzQo?~_t37fgGc(EFGHmY$UrM+;_hN!X zi2YX?z=q-L>3C^KhXkj=``5l6(9?F$PB$+N7j*>1YO}Yk6fRJLs0LdDfqVF+S?>d= z#KE7KD;X9(i~#i}3k7J*y_iDV@qECW9bhGm>E7zlcLd-ONLJmYf0bYJj+}VAG9Qy+ zss6p7jSbP-NGM7u+YEl(uXpZcJ(S>7#bTl?&8tDvyNPtM+ zxcpSc)zk1|H2${-MCBS>N-)m&|w}&DbP_{KR zFz}h?Fk*)n>KGmw=np3j+jY!}$iJi}2XKg!;?4S`YlP!K65o&V*9XT@y2CJ8j(Ctv z&6vDpg;vJC&ET_I0B$c+yu{X<_TP^w=3^vlh(=(1x4=oaG98A3D){EZBZK{C0y0+j zYpd!0vQHqs2a#=I{AHID93)taw7+?`kgiwx#WLVIRKq`QgU;@^Vqi9|KHD!B%c@S^ zd|vUn^^$jvxcXpQd6qyh2lWEYs;^FpaQM9kiAe3yL5>dTA&#WL`d<^Ex|)a>TUT&b zI{k!rylHIQTW|l%LT^xd{p?=gnc{F{pN6ZJAX?ss5Rn6Cj1=p*4utapk>-HAI8HV;Zq4Fxno+aa zrtD`AB7t7_7cgoOn@w_i0cO7M_p6%c*F?xp1T;hBMW0?@Ys4>6RC_h5t?ioiF`F;@ zVHc}xMa*br3v*y%Lg!9m@=>BEhu$~1y{?(A;J_oR5qWZ5_SH{Oy=oq{oDAD>FHGmw zFmN)#tdCV2M}?gnG>zlcXVZY~RmcG1cm%2MEx3oIQ(r0%pX~8r`uOiFIn5aRM~~&1 z;5X60@ymQk6Rqkb&qWWV152pIWChSzJL5^&?u59`>?!0^&Y{ORv~c24r$()dH_~bfLt?BvR&g%5Ylni8vOZB z`H=GWs8PQCB9@}f)oXWJo^UZF?n__5gn6rL!+*j!k6-fB${f)F?hC;34zFyeP52M0X~7BK>Ue5>M{T=Qy{lBkQ+ZQ;e8^?|Pymq=0I( zUL{2uLlC$ZM3pGPQ!{=t7;_{SK@VTvoKqEd%dh+-B;VT@^lld$h8^ysUH!IDVPNioPL zL-j%IGp#|TNbGT6w39_nJ5khFs&sQpcvzD4QuhT#&;eTNrkFdR=6E69tSOWIp2?!r z&D^M^-|cVChD_}{R*aZJ zA$70WRP-%Fmg~#kWs8-aED&c{Y;wVPkuHWWU{b?6Q`EUBFmFC+bPmlD`ZhT%!lK8| z1u=0VIS!opY9~+>TE}q2sscETyS}MpUyya=SNzaKqh~+ntk_j!rjg*yec0dI-?Gt9;mZUwfyLfd7rtl5AZpR{B_YQScm*wNFF`(IClDA1 z(6G@5xMv=x(XZ8z6d<{+sn)NMmh?0)iL|^`r{_D&T>HHIM$8u z%4)CY+ttAF%cNfs7U`c@A9QEf!>R2mQ#Fr!pB*$oq#5_57S zjZORZbRnB1R(y$|nr6PV7z{b06<3gaLaiiMY7ARKZfP2Ak+Vu=KPvQO%^U?>g6&F^ zzrsgXc}~>TC!_xw`8-BqKVi4w9jCgSUZp%xAuJwK^d4W3Jr0U)Q~KIJxmAeSN%$*f zKEHqY=Sesl98f2v5O>@qX-rLI=g^a`wcxt?0xSYVf|R6M{}#T*fv=gi5gtSDD-&C@&oK1C{{ zR!-3d>^vu>m`wLN`RFulnP2k&k_IMsMGK^@nI$JKGC2tD#LvN~Fvn*A|Am>gnHUA? z)0Q6};}cE#$4i}0@NYg|EX3oUXR%IRFK!H92Am-xKX`FtFm$d+pZ@c(EDP-T6xNEP zl5_v(4svo9o^#<6T%{Ux?L6?>jTwV7(Y2n$5Y<-pyqFJYPPj0URwCGwI)se(cHZQ! zzf!N0<}_~4X;DJhuIj*u{j-CvwKyNS%=ziiS8$HapyS_862{FycJIfvBe^An$LJP@ zIe@VN?HU{<#_n#jFk1${tDF690&lL3%<4^!og~+c!AsB6W&gnRv-FoGVTs4J)g=ZQ z>EtG&7?}#mZ!xN+37Glu02Y|JDrq!Tx|NL*X_9)5X54Bhibe7?Au&tO?8Nlo-yR*7 zUfoX204mwM7+H3u%- zUg?GcGNK3HlK6=Tu60DxsIVxSMvdUAV|G?1iYiufieb0!R7sbB>r#RBD7S4Kj>YnP zhC&Do-{5Y6G>}Es9ENB;;?6ciu5xsv4pBrCT)Iah}|7QB|tE<++m?;U9l6_!RBFEb`f zBu!hcaM`9To@E;z$8g7o;7UNuAqdl4(Z(x>ez|j5hh&yzBHJ^1auEdjiR(wg*4+31 z+8xVYcL$V88tgqSX5w3=2Ex;^kod%EA)9O-Nzk#lvFFr^SSWFtn0dV!5FXQQ(gzAn z&+|1f#1J$vt6aCfZsz?T`w-sE67mo+VpW4^ySX~8U~D~Czw|hdTE3ANzr!yxEoxP- z5G@iviDP76a!@xNZ9OtyZg_z2be-L2+;5}=UtO(_r26j4e?1*@i`m2~E(l|2y-+FH zKR>@%9@L((stJD9ROgqeQLqAwQ^Q{#XCjZ5X%z$TJ@Q6hRnz`bpeMTIw0YO{T~TEy z@A6!z&?R36?`ytZl~`^bk4!c*se%e{tG<;$4WK8w>&5Xu5r?o!PkF>B3!2J=tS2m+ z4o6dRTO}OpUh!lT-s4$^_K_j1fOwraH;Wf-0~;S$8ufUjE}mzT<1S*sFp8<8$r!+p z6;0pH%LQpq{Ri#>$&0+tbQ`Kc^@aj%xw-;?9BecfJ%i9zS%(l6-xyfYqPZN{B&PLL zL=+Xo3$Ai?E-ne*AF}p3d5xY{a0swML+pWpaOYgvb^O1r#9b@js=1Ai{afySak#%H z0}NL%+S6Jh>g`y@Tik3iO1;CXC@trM7X{EpXf*zNeG)iLK<}u#r6^HDyx4~y(d;Tm=1!j z-8oTrukL8g6A%E20y@w2#|)b3f?)>p^o!PP(<4+ zIJDk$5B9hxdk~By%&3mnqDU9Bzn{n2N1G|=7i4t}_J>CRYn|cvEE*$sIg+DMScI1X zRk|L+XmYW$iCWNNayOHx6G&_G(YBL|TXe(kwF6%n2Kd*_gF~SgK8OJaV37G?g>y=f zZsFC4MowCSt9*TSs*5|JpW~nG0?0NS?-m~3^4Vl-lX4`8^}R3-s)3|P_WR9rmP7nm zqG}LFySDOZeTuUQ_yg&-{sSwl3#op30la77iY#9yMXiLtm3t}btdzq?ai?6U6PG1S zjJ_$Mpw0qq7HC8BjABtH1L4DyoCg{DX5 z!;_-<<{m)1 zLr|FDHoKM&#k3x)zM3h1D$5)uJS2W7utXF;QTnr z6=e&~ge%yAE3vDcLu8Q=w@$PDDS?4c=PidSzs z^&xHNwbf!+qo4~;Er~*8>0n^M7^u9G4sFoEUm(toBp9dWu=_RJ*Kv%u>r>S(7*R~L zBrRTEcRdW+1OX-exdH3}lpAdPvr zH!HO}5^UdEek7YA_$m;paX3D$`27`fmR4g$Q}I#c@t%YihT_k!dnTQ9I1lG_tpxM& zSI^azXUpN*Ems#R6w&H-Ua&Yah)m`~nJ$FB-Zv-mgNg~h04-i^VOzU)CH~sy~GQpP>q*#MLs^^o&Yj+=bCw;-VsNi1VrFPVy+%+;ik40HHhmOSKG%M87I}>r!4u zCHvpW+fMvgbwmJooL(GJ;|~>R%P^f;ww|O_iI7gUm%)|eFSw_P_`>vnPH3L$-oN^W zRv{uIDy~4DsB;w6adE8$&&#-m&Zag2G;ono~`4n7gx5@YDVW`I$@MTM!pp;n$AJG76;yLO3U z#}lQ|`1UvX3F$76be>dJ2E^{!Y0d?G*Iv^X%TeUI5y%|c{ADd7X)@`f03E0DrAc5}Xqv91KVEGO${N1j zeUF3H8zlIed>By1w|(iO>;t6EmLr)+>M(Lm$g^3wFW0K+AIFD^XVE%UcC6nE?7Xym zu&|KCh&^V~tePdNwmRan3hStMt{)M#=UQ@uM5nIR_~$duIN%LgtX+YbJ@jPcjqDu6RZ zNX)MZInl5h=(Z>$Y>^`Pof}tQ|M&Xk(INCaiJ#8w{u_KIvUO{ii9~!VN%>55+*3nn zv8d!P_Fg^CC>=K`@*PqkT2g7}dGV^hY%@RY$K1}V!L8NIDi6 zn5ofb?MBwtl}SH*M&1qDnQx#9_0!cU$|RqxCOEG9rK=TE9M|G}gfVc7g)ZW1qGMr(G;?wImx=A91qnb%D1zw2gtq!$wyx0lEz|px@0*nkJgv~_O6*OjFLwYy9GeSDtXAt3*Akq*rouqd#ubw7x2 zy=fN<^D$1B4GFc9OWP9%waZ!Scod!NXgBu_8_AwWtCt zNRmw&heBEGo~{1Hq|TUqaC=ipvyf9ArQB^rQ%e80aWNJ2ex3@{AL0)`6AS0F>?Mic zhFb)f+71z}k&cz3L1LD_UxxE-Kb%tzNLgLID1ukL`cAb$r-6iM`dZjMlau;|33Pg# zdOk}*E)utA-{^VKEFlI{{En?73Lfi^C?sF|` zB5}=sH;n&)485>R+0-9vWG>roG!@tHB1^C{^FI9(Bo$Ta@}{P$@a$hnSdow1{&~ow zb<>+}_`f=<;EhS1*)URThU(cQYjJb8{2tX4^>O!XrtR7$nXwGCuU6=WUAS{3W@S6h zZmQIBvW^VqHAqdGq+jbBFnW(r-oNX?bqu=TWIR9t-tfl^*obygAMSDc-_ zzVR1-dnC;oI;>HcxV14{M{%wVhPCxKSMaudrkdJ0lP$rIbFxYcH792We3T7euYq0w zDea{86#0^AbhJktFI*x+*+T{a>Jb5(Z-%CoU8gRWO^ADqu-4TV3qEaVYI~{f0%yZY z7w|j`7?0CI0wGA+Veu@7LysS9`CWzWbu;DlYgr(x@81hdzofsa7i_B+$ed6~DJWn2 zbV9^kS_g<(=8pEssO}58yF#w26@Fy%TUX_Ww&oq@33#cch#9eGNz&BfiZUQK9l!et z#`>N1aBT_dJLk&z?#6-nz<2O_sX;IYBwg`2@@5%y_+(3KUPiBa z1x2XxF+)2qJ_wh+52!75L^WbAI6f9VzonOX)9JyUEfW{ce}xu60UdvKiU2@EkLZsTWwL?;eEx0#suz>b>K5ZGav3MR~WLPrvHouU~ zGUknAf04;UU*|y~mA@GD7Dhj^Rb#1Ysw<#mKqe|2$PCCOEO3OVytPRg|05L_{Nc*1 zGSWu}5gdCH%(tY``7uHo_fvM4MyUX~c{63s<~aob392Wv&ge<6vsV|q#79+g?s0-=X&DPgQ*Y$NfJq%IoMpmLsnqSt3B(f+L3mcP>MWqAL zeCXF=6_vK8sq%;6UyP5xrE}ck0licJN0|Zx=lkEd7sd{A8##bY@{VhK_K)W}fx59t zCohPq=a{-1LjU;mhIAPTH3+dt2$$0w)Y?bYHwOnqJy*2nV}oLkJ^ysz^Q~Du`l;zp zKOP5wW_cHM=a%~Li%&ikWCVlP`S-zQz`~LO*h9J=y`)PXoo(8Zjl^=XWa3iT=a9ve&Gmu6(m61=b-NSOO|;G}-WXdJ7j^e{e0- zsw(%{@+{RNB3Ldg`p|&2cYK1~kHTX++(0O)n@RfszGS{@5nByBA5&%B)k@05fQlHg zW+J?9UHv^GLRc2x2n1v;h=t!vy#BU#ONZJHiAAQdBklkk^<0(bF3du(JbcDw_ZgYwTwrjUk$$fvU|Hp zjpj$$&IT32+l%Kxe-a=nXwpwz@Y*)~R;;Dsbg%kJ%mn_z6xUZ^OiH#U?wHPhiO=!x z+LN@qz?gpr`6OxwdDb>F&|uZo2fhi#Oh#!jb0=QsR_OS@F?C*mI;$}^H@B&1z2+)e ziNfP`f~8lNwML&E6l!DkX6g;>KAw4wzhnstXoI*&?4T()1)H9!0&wMwRAFaMEdXi)9mz6RmQ`{c6yrD0*a2K z&-wYD@9~`>_Za#_amkgD4i0%%#_mq^KSKn3Y&VZ5EuIi~9@6A%iZN&`MJ{)GN zkTU9h>NL8fhmh4hD&W80@iOF}ZLG4tIf)T}9J&Z9`IMgiR4TW8+nA8^ynSS7g6a|C zV(n^~jbeH#wQX?abL4KplPp(EPhP&hz(c>Uwsk30$=x+Jw5L4J^1eUucIeqo--eOsbr?q^BN61I|wi3tbUL#wWHV(|Q&V%1^a+A|2)%jHEcff0ucL)%bahxFgB$qhLAv-m=s;li4=E}T z^HZ;)|DBESQQX0xSB%ZIX{Ss-7K@JFs+PBUTpsOhhA($7%?kT@;p!rWLEZi@qm5*$2$YQZyDvnU(Q5o7^j1ml-^|dL zg6w9w6m6Mt)=LjdFFc3y07N91KSAlq3!1KyqgkIPfCO}>zNpQiz!^af@fdvQC-0=? zK7amdI7(JChe|q#=o4&OdGJQM!|oXkeU-ETd+x9EO{5V_1C6jJOTDlHx693lcFo1| zed&yPbL#$iDI&S$&`Tl(DkF;#pN9>%e^%{XtP~SUWxty8DfV}XV-!W2L!N5 z*EFrMJ*~G}v}TmY~_9k}^jA zjcVGyu9f|zQ|Xe}oW15ZB4`0Gp};4L^_V^Mif!++UF9`lWhaxg{Po$rMhKwwym77b zv!32SxZu%=0>R79Tbs^WS{z%wlvG+dHws6$&7YDaS{~W(pNxVL5P4n)NIr2Z%RwB6 zMc1ts3H8@q6eF;YgdrAwt7!`DL8r&SQr{S_j%D?8`_IO@0)CJvhpnD1ZiI8!Zu%&mb38gbqUVJofFys+-VBh@d6zWXi&YswHU>`}tMe5gn;};z)-xc< zCciVh&mBq-vE*Lq~+&E_qq9ez zG=MQCD&m$er`n{$^i6kpc9j)6T}379ow9m*&m`p8crK=SJrnYisBIXn+_)-!*SeZy zjJOj!(2x;VrL)vIE{1*7BY)B8uP~}dCWxS<8Rmc6nxNe#|wFhn#=RBX?p=to; z8vzPn5`HMde5%8MrE@nLje%GJC7MX^4MRj5Y}Vn_m`v<(c!vD{Cr+#|bLGwRL_)pR1I% zr;C;!ZRZ6_zH3T%F~mzesl)$0W^Ub!I#-)r-}2U9VKpZQL! znqyt^mN%XcQ9WH6E>e09r}$m(|K8vFc%!UjJ*@u_vHUou-nn$zWk)vKa5iKvc6ayW zvQG6hsT*CBy~|M6H*datNk@!TV>@ijsKQx>SHeIButLVr@Ah08~gDX%*OV!p*z`D$S<~nG`8TkPQ%QP>M%PO z9vg`)LDFH#W%EhWmv*QI-X(mYI*cmmyLT9EL+6bhgs_efpk=nkCX`%&JK3=ZHQ4$07?oVac_xt$W^68vMf?gVYbMe!wT*oUrMMv%OQCyPV|5KSwl_dft~Lj47v(_Z zH`*yHXqPO7T4s>GxdNj3L&~UQEe?DFVG0W#If$&5767cnMN)(gk*M|51U?1bqREO@ z-IT8~Nw8G=q$;X0Gu&gx?qNJOx$~bn8%ea&A=cVgCWXyu*Cs8HD1k)U3nv>t@lGw;wCmd+Y6dI3}pIuhFtna+C4m*AjrL(#O_TcmhaI&w+QC82^`|NHA9=O zP}#;mzlahd%^I|{3?rp3ObZ?wbZH?5!Rk2_vW=ApF&8Gzfaw~`AJwIhWYz8gVFPo_ z@0QMJ%udHm|7F(WxwA3Xi&f)VLvK$R<#QAS4F9S_n_C4kaM;=7RKON}h$O9)*pzg( zJ++)gFDbe6chVq|2a^XgWuJBpoN3rEbFUT*5j43!5u5<23h4#tN5b>~J!9>B#V)fB zmDsTY^PGMnd>>23leFQ_xJKX^3kDF0;*?tRW-a5Fi_BKU$d)G# z9QardGWn`fImJxQG1wG@;c*x^Nafn4coT|1>uh?d0%2K3!$36_g-v?}XbHZXe6y}u zywBGtK1}T8&Vbk!Wf1no17fSVj+_Y6EMg!x^|LbBE`TEWF^D+T0jt$i8li~d2~bo z=9bXcw;O}b?n-#1n<7pW#Cd62XO=~><|0rEVk^md&m#{`-{&quloHcBKav#3ExsxrH=u1Ps%%8^YatQ@>-}69#)U z0q-&N_()n`UmNC=bQERz#34ZZ%>k7!U8>YK`=No9uGQHVD#9gVIjY%~U#CzF+kZvi7TwEf;BTE~QB4#6=tRX`;oFRc z%NIMMzPFQMuBiejUjJf}6**jOGoR=E8%f-L98xS5d>>KVaphBl=X=4FLk}owp z?)m*GD--Q+jA^;Zcqpnnv~Is#%*#l%5Pe#r^11uzouyPdlD zdpo>A>Hg%kP6hZ=d7(sH5s`XsJd@ zit8_HfITM;mxa~x4E_@(x;6>B$hBzn#o?H3GRPw^c!6t{{OrbT$B+FSB!Yj-_-0GmwADH9Lto0bA@UtUKNq{d9pTyz zEf2yMEflsWy6wy>L4_}jBx4y9tOELrx$eAA9R$zo>X*V>yy|_KtNz)++t(Y1iU(u$ zLO=0W?MXz;p_H?QDxgylZ^-VvMVbE$5td%bPJK{G{C4t%#*d6x6Q zqXj;NoxNiYg7TH)+`cYo>vj=6S3TR)<;j1JDU_`Cuz(Vti|JAK7;Y8sNx^`$geEO~Y6kR`!=JwLW z>i5Wz&e^a6Rhnbzolyr&qlh^{Gm1L%dRP9r=LG;c-ZNMM>ko^Q93~PCeq7i$;uxW* z+6)}gm#X{ZE+t`RE$*j{YA!~Y?gHl&@K4f^50^$QCbrV3?eC|^{$hx`PkjK2^k#li z6noxnf<7ylAp}UgQif1=6szZf+Mg~Xj3CTUJp!#wKBBLO>zJ-r!*Vf}zmIDrLGj@w zH&M7YQ$Jj)YZCm$Q|GGVHT^$JgnZZ24QKz=KN+9e+jWp#QGm}6(1w0ZVbD2U!^LOQ zsx_X24u?_Q=2>LkB(l|V(cTVJ)b)q+XCF9+JRFyAagVI@Fqa+W`o|6Y%>sLh!^l2M z7SjEFqp-p^(^Wvzq=sY<|HjTF{7FNK!9DNDC-8X@b^4tjhf}OvP9qw|1i-obInjcH z^7g&Jo~)yXIoxaIFUJOItV!7j>yHCPWasv8@$_Ri>F=z2wfmv*EufZ6LAteh;8X5= zr3?KL=1#=N$H@4*Y|;eoDQoQ|=>(7uv!LGD$0S(ZgFOm>tE-rtmRjjG9-l<$A52w> zqU;zSN(zG+s5;We`5%pNov*3WFJtxRq?6+UOaB(?5)`hO1rOD?DF%x-e57rzS9yV7 z{0a8&wNSvPBWk-!OcJqF$c5Lg9l&W}&r0WeQOZp2as9+&9i8I^5Bwj-| z*HMsYu?Nk?p*>?q<*)b%iR7I_N5sEpK*yLTDM(#7Cd9BUH4%SNzFVmyU zVq&idm3f*C?Sk89AAIgpc$7~CX>ae3>vh*;_mj8?DVy%>4vYHc-)uqSZp?X(xvMWY z3u>SJg!lmPJB4#!DZfjsJ~vKeZweCBN9z^kChu!T zF~jjF1zEfJCgdx9U!$nl<#f63@Zmw9h zPRU!5i#*ZIQaVN|_b6T3t`?4>6or|+*AM#jU+YpNY##Z z`1ZGj9RQ3n2FZ&7C(n#|Yw zI}G=d6k>beScT`XEknW}3jXH$6Q4a+nJxxWzVo$og(|T@rQPHBBc7Rmj(y5aWef4g zSx2nWi030O{vSvl1eESh2_*z+>F(}^L6i`syFo&_y9VhLL5A*> zp<`&c^S^i9`7-luX1#0He$M%wefBdSVtC_LB{lANL2$zLnDbb(phNLh9Dr4>NDUk01v^02$lTWaAW{h>7YUi2&k0|sHM@L&TE*%IZk(r2iv`$%2 zgnz?@B>O&r4%D9GgV=RDljj2JwXQ&F1K0TVF;8eUbDkJn`*_yN zzRn@ff2I-jH9AYm7C3=4HI@rQJ>n;Vw<9e83ym2xP#jU;pJ_B1sG}^kg_(QKm7UhN0iW)UNdW5R%HRUz-x8owLe32+1x(P_ zA|kjvoLW}QNu_Z z0SFDn#k(1>idzuhMF6WcA0no(*{`k~od5K`^wDPRyW!LH-~!pspLQn_7+Dw$Z+;PwBomyvePkKDM8%%ELS zeLQZ)g(77XXo-^^e+x;iSB0fW0Jy9oN^;qe2F6PzTbSJNeq}`o%3$C3!;+?Af_X&Feq>ampyhEXzE_DI{<(uE<$36&AKpo@W1!?Lf>@Fn#$z~xCRiE7w8A=2 zx3X!L2;L?wp-$CCIGau$hVPtD$V!#&YDlYX04fcNay)ik_UuPT)5?HG+me}LSpgl9 zwhIG-+1$2kKYW9?*(oQ|UG$9zqqcHf=_H0LA8)m(;_Md~JNNubsGDhErMY<05+Nh_{ zA%a&t%5xz#n4wbP$N;x@+RYulqhPvrVn9Ej^F17?@c+rYZmd`bF8}`J_>7T^91cgr zq+=rxc*jOt?czdXxUHT4VeH5DKFIyXoTid=QeWcfG&acYaVz%e;!Z8bd!{P*hCu3g zg~wo=IgX1e>koE={$A_T?&?#_@N$uUoh|b`LSIC>gKrag1DU z&hU=59y}(g81{o?^P2!E1WyL=#NquXJpT3HZ%>`8_}SDqA$8^eae8I@zb7C2f9*wW z97D{LwCPCorT+(4bzL5>C=ZH+Kd+BzZet#LRv%H=CJzR#+?RhJjN=Y^RBKUwGVGpS z+NCLNf_%}kWF7L}BLn)3ETsSb zK%xm)qs~XENa4}VeAYVG=KB6=sVa@$niiEEk1knr5$`QJl(dHWc3Go!TaEA89}iaE zm`{dS4>VN)Z)l~B%M1q;I;aA+=M1*m&U>@Srle3; zTwr_>X=Of5%oon^t|5!$-#9+wU-FuD&IdT)gBySlu$ z3B_Au@3bj3S1{i-ThSpVrS4%J(qYD$KJ$;E-<1nn{e zC7{o?8pn*0*2|k_>gA$mn1GOz@aR7|=fd&@*MS~%vG!zma|x@6F5w_ zvb3bHdN00}viqLSp_L{DdYc$h5{3ouRU?-Utp@$vn#p|F{LZriIb(0<3qx^8_(%hK zR+QlsvjRM*Ha_Fd&)oW=?`&GoU4<_KP+xPy167?}54UEbhx3N8DAI6W3&#KL7!!cd zm$<5RIaw;;Cuym^jG6ODe5o|-JDi|3+p=Qntr;g?U+VEr@&@b*H(m5-~aXB zcU;K(t2o7uR_dzhwPU8ID{U1M%bf-5p11tD7*t~7c!pQKyVH%4EzYbGP+V@+K4xGP zTS*n|f*D{6GG)y(x!jN+kG)>U1C#_&^ifS&EkHpdS}|#uN;#;{CY3=!isum=25&Zm z3brUwZX2vNGp<@G?zyWirwObZ*a<$!wUYzu{B`h=B7b;9;5Zoan z{+sZB{&3KI8{JeCWwo1xO8Da+dXgco?XBCd@}2iq^90{_aH3vg+`Dp@+Ta0%L=e6N zW8JBu_o{6@gnI5^Xn5)LQ;r@r?2(NMFbQJl~kraWX4lHOkKoMhff8O66 zf;r+J** z_b(&(AA8ttzaJ#x1EvCO`DH;gZS+DUhgjEb)_BSUXut-JG4YH0UCg_{$JgT-g3L6M z)+b$pY|mn@19c)oj&%LsqlTgXT9oA4|2bIGfhQFB=RUu)+iOw=gWB^%h}6flN_Y0) z>EVxBW9t%W#(44aT!Z&{{%hd+z(y*%YCX)MQ-?pLdi?MrH)xR22A?F9rxvpPDkd8NGC5SDOVK#Ljf}dV#w6o?XZQZl8@9JjJseHT2H0J< z@3*uo#Nw}0a+S1S8U3f!w744MjUoGg)jHrt1d=Dviwk}TLC5jK_v`@!8o$CB$0q&C zn4Q~dh7I}H%Ox+G@*kCK59nTz@Xzn{ff>?8pXW&8- zWwz5#<{9ArUb}m<2+?Nt=p`aG5?;_hJ4cCYgK*LR_2%ZSB3rvdYV5 zE+&aZuJFgzcxy{a_+dH2ZFAP zXq4fSkbo9rB1^rvD)6?8mH%=y^i5q9?+0r{5w3P8`7KN9kp&{qIyoCmsEw1JofTKc zJVX&^(If-@RiXJpv^UP&@@x#2aK=FaywVz*06kn2R=MykqAG+sLBDqrU}<>RJLFAx zCC*cshBCNnvkD!zDTKKze9GQ-ym!S;V=X>b{O7FIsdLbZ(`rywOm{hXY~wwSHMWc_ zZq0OtJq9OHxZi|jYJm2@q-lp>Z0Nr+b$6;$J`I6C@8zm#RmI@37W`?%$bfMq#lgcx zCXt!!{5*1%=wk=CXlfndEqfje7jG<|1)y@8*S_ahnaoRtzcC2!z)VtjP6P-M8V|$e zJnz=~m`VZhcVK|)-3;5ij44Eg*5E=h6We>i5aEk<*LvMJc%YTX@udg9N7d}2%5Btcu!>QucJ){^&vb zS17)UtbpA?<~cxaDv?S;#*r^Su?yd@ml0-C!KjO&nA%M=~YY%2O?dcW>FU8 z<;K(XFdA6=qK{F;N2^5M!0I@eFd*jkrTJSg2)(2XYb!=i7XS#69J{X@K4ho--(P&D zb7&0NZ1PfFg_+*_;XvukjNONt^oC{-w9dG?ZM{EJ3D&WnM%J9nEav+o0dp^g6624d zNbdK(eNpO6a>W?e`RLK&I_LS6o#D;jz5!)iWSSU2b3?ljVu+gHLkBn zpE{cVIYo?@r6_0y`E;H?8Th9}hF})0lpPN++@=_-k{i&wF|b(zbs&*vfSs!^*J38` z5n19}lN3+Ml$($+crSliYT1{tdQ%^_T)OdN>utA4^kQ>s#&d4GD%T*HvZy|~pPjk^ zlzRNEJI`~rOS}_$4DJ8^8L#`(gZt(G z5fjnt(2a?|F16+DGry3OA;_lWk1dJvc0}<)Jpv!k%z871ty7Q~y+pxdHz#OgaXMCo zAc?}G9Lr-V=t5o4eSKIh(0q?&H8AV%SUneed))E;+QYH%9a+eA-yn^P1S0%jzJ`U9 zS<&$rrP}2#T&NowVv^wVw2!gEpU~yuMePSSAjo~%pndAGd4&DAib>6cmyeg$Uv;c! zUj@N8b8mWo3(|=3O{MwW{_YMAxE?5C3Vs{J1v7zjZ>*p|K7M+U+SC>xzem($qW(d2xXYfp+%Ztryaf1;Ivpn<=8-W zaATmez5C%`*nJCr^);~f#T)N5gN)?87Vm{MK$mmAVLZf#-6;(kVw61YKaaCX7B83k zUK7lQ@~fERAsdiB=M!#3ZkFf=J<HmRprT(?uY<~hO(`X7I(*(+2i+a}p)^V{v+u78bGVXJwb*h%k8<{uV=huXi9p1+q9ItmjUkUw3ZS;@+_N01tC%f5No@SUBmuNkfoOzrkR8HF!QUzf@FI%Op&ykZS#YlUKZzVC zg=@)EG$4WRB}z^IL6Bl74}{wQ+$I|$TZUd=UqDN4=BP80>QS(OT5d=H7O}oVwaecc zQ(=(}5j^ea$`ZLuO+<()dF7iAyy?WoEecWrm=x#&~9O$AXmXw;j#HR}?eD#LmKuq+ZXnj!aTeoZd6@cMS=U$xn3O#}rpL{Bd4^FSqPG($K+%$X-4B?@hJr(=2b+0%lFt zef16f=m@CuAfi4)Z9~qmY}&ww-{jCtVPI8fNG9n{ou?W=JuNZ32LgL}Y0-zNrLDcXd9kbPF}x$n8xbgivf`V9hm5?5~r%_6LLWc2XU_F5hstZ|El%L zo>l3k^w!|r9|YrRK`x;s(@)kpBC*GmXJG_SOTW1SZrYg zJELHBz;XPPJe3==PHFOZJ?*tMvf1-{HQ>1P4%t#cnc3;!xR{gNKUm0Av(vH^fIFyx>6NCIl9|p zb>%O*x8_A}lEx>bFvv`8mMv5MkUIK% zxh8QgWL+V$Y4e|2{(T7*GA1+!ghrv$%U!2i-H5w=yQu*m`u`+9Bxcq=?41p?H zL#A~mlgA_!I!+>>PFdhB52iT%yL&XQvP?wvc=wl~M7beM9pCRa^3{5-ozYg(pts&+ zCy5kzrZ1j<&B0kv{~m=GAzlnbzJI>rh)hyb_a==Q^?zS$$- zX=fkeL-O8n4bV@lv%^m6H3Fr}c$J8Iw^YA0`VdX0M#8Ogs7yFq;lLf0L>FjQ3{U==ROlvRd(aB<*bnP6xhsUq~ViB0tF*xoV^|{j;cp@8L z^#B~h*)$22uz*7S(Te1=g)8Mo&LP#Q8L3}hBUhdt**1t5_3~@mmS*|p6rU`MR`m)| zoulB+P&AGm*(W-Z=9lkQLDbFDnqmqine%V@TP*4{c{r@siDARu%X>mA|L+BG!JIOM zVKE2T)$}yd<|vi(YBWA~*^98N`E~h8%Yt9pynWq%w62zoWHYc_%`&6O^#hb99nU(p zv2~UV@+PWj6_zEs*hxPIbbi7G0pYSCs%2eeKDfoNhD7{=aMKEUzE>c!^nftrrqZ8# z1;$Q`(5N}(l6zYGhv&1GeH93b*`YmJE@gqFG1j@~eJJII)qL=2XgaUjSJ*RT&V1n( zj@*TFJrkh1dKke1Ycbwv!x01U|Cq9^?-{8WO4IVHrvQ z9qi>H)IZ*uyTriJCwti;Q7_9H`W@rZ|0S%GJDbsZ84pg-8r=eQTHf%HZ zqBWqU=%!?Ea%t(s(~!)37uG{RMJ67QX$;)SI@X%T?JdE53aDk^vi6%tJmpk-|0P9z zxyE-Cp*R*>l)dMLxSl*>%tPFWmy!0t<8^opw-2t^0M>(Em9k+q?;=~|k4hm{YerrR z{-4^Nx1lDe01mV_zk17w;cM_5f%LG0oM$d^rH&t>3;5H5ho1axA*|F%0XTfLq z7!hiAFpJU^iST6S-md|f?8UN7|>|h}D}IpNF-pn(qrUY7g*`kn{Mx?!d)4Biu?cB!xd_YZ8R% zkXh4M$EwnZCj8#z3wt91j9Ysg!QNjUvS19Bv;{0yFAzxhKEapv3|0{_vwE@^)u2HA zdYj5uaWz8!va+;+KJ{OPBrXi=C4s_k4}QG7=c5Ir3N&XB&JrbF*X|m!#%AEEMKEMm zz(LP36u-lH>c&fYMaz>FfJ#tjNZhSDpP_@GDeTM;URMxcE3rmIAua5aH(b&%>gd@u zH=+KrW6#5+o{>~GFW0g8ibDfr3tA17pB*JY0u@Fdu5;V|Kt{yGyBSn{D2EI)T6*MI zBEK(qws$Nz9-T;IhBwsl&h;JZK_ke`w?r!!{nqvbqUE9OB8dQ0T#FBmN|_sVOA|?jRQd=b>|NiPvzUck&Pxtcc>;4?Zp7^alB5ba@P*x(Rn1`VH3PV&9WUG$r7uFODzB~Hx`)(oWVaGX6qzoK`O?iGE|JN7#mt3kGs_VXX5O|clTGk}+l4ignS!oBzOOB+>55zt zJQ+A%7ryBSdew@~k0N@Ib_!WhN~s1g_wo|>EW;wRXi53I4QjQ?kwgZUhut$7k!uhDGV6&B8Xe7tm zZu>6Nd2i{Gqq=@U54<(jSud5sPo7L%elzQiFMe1+K^-r(n}rPr38gAt&m(qp&O}n} ze{RV$_}`zLP|Xqr&{n?Ys@UR_yYR~2-mxrHV7T+wzRj*5TuV9$o-SKoZIGB}bsR5>xai8jo|4!RmsjM=IPIN)!cpuJvJKO1?9 z-kv@7c)%(!*N`<-(mseA>k?6O3pv8TA*8@$<3x>6eELxFP4&V)tp!f2!AYma)8C{WkZ0f6}o1`T~a%{6jX#NUU7wZ)(mw zRmj0g`!=^XQbSi=k^=5{{P(ha_hVWsS`DlIF7t7FzbdK}yI%iPZLibpd69hkF3>0% zCF&<3<;#x!^UaJ)y<0;%7*;^N74MH}J3#uH++?Mi$_WopHdQ8t1j@C_q1@EG0T-m! z5GqU2a+_~kV5QE}?3_b~Cu| zw5EcBt~`JBw^#i9#nrWU0lWfB zLkhX*08wmY9%9N%zClQq3ZjbO5kn*?fIZT!{GmV|1WNuU3>Httq6!f`82K2iPh6UOL?OH|sTO0O)lY=}Y`T2*$@2s(3e$M)x3&3t5ayjwWJB8Qt>) z-P;i+7^d@(QYxN5HC8Y4LW;L!rT;|lzPFl_>y`c<=~Uf@N#};<=8N?a4PT_4fGPGl zkAt3M9?~-b>I6CM64|df>8(UlW)OVTK@k)^IbT?%)H$RG|zgULDC%dAGeKFmFO(`R!U?xTNTbFo|~ zQb&FNl#ItR#BbJHNntIF4)k>1b;#XjQQb>XXlXz-`gsf&$5StjL z4J+JuY1h^Pkoc4&ckX@R#MBfo4%jJjf4W{bV_MwgjEWoI>b3W40t(NxjV$B$Zh;1-&N!EPuSNi*|WeXg~LefbL zeP2ikvX>^})w<^1O9X|KTgNtqtlrp-bLxXM=$RSNBSNo0(b68NP3Y3+pp3XMY&_FL zXw!dHB$7g}VT4JHUG{yx`u(&m6_o5ilP-z?&*kDG?R8v1cbU2=O&QYhzK>!ncZn|4 z$IoVwlgHFZ_f_dum+tGIVYKf*gC$KKIQ66}%s^VZ5~)3}V2fi~9c#6cnFB0mSGHp% zu+*R8<{K{lzzNL<8UV@&KvF}4BT1eIFYdZb0Y7oC4H`9fBaTmR!bz8321g8LW_&kT zAZbuMJm73RfYVpYhX$%OG!hwt^K=oK_rDT+VHSNOSWNb)c$S;5G*9d}1S99@j$RDZ z(>&Kaka+qjouhU2sCG>o8dN-mVdntIj&&&`b=H~Nf$yP*k;H@X-_P#1tN<6zS>ORZ zI;0Wlfl4ZSFWp|3HLQt{pR0 zK__?ta_nExIe71ZB(mqKvkG8<7VY+mLN6(edfVUV8Q`?AK!3r~%E^Z;>?BP&>iH}* zKxtt6G3&(VgRI4=^VYu#NS{-5s<8s)+Ab`-ss;sMGUGA8=tt3VufkMKs_sa)yM;{G-9w=)vHkGelJ`Q{&_KqSHy{OFr|h*1gr3Rd zq|Ac3ZCjf~=ZAp-=XXtHqg_LkPFgQu9bjg2qa@^-fv%LpM`BSRl9w529KBKdRqyLJ zwJmcC25M`i zPq^WaBxLd*FFWSMkTkVaUl^Azk4PHt75ar|4!mT06hQG8Wf|gqHfaIyn;e+Ux{S=1 z_Eq+i3*=EprDM2*B;bFORFB2qgBiX;H%N4HQAi6%v?a(STcM6s=FH~RuZB3Pn$x_* z^$GCecxc@v*ZfKW{?Kv_YPF-DuE}aQBXAo;kpf6le&HviYbyGB9&c%AFlE0Ay)(_gn&#-^P?Im84zjZi(?6cdFQ@^4PU`c#pr0CD2J>Wtky}YOj8`J`U!` zHu3Oe`F)A_O)is6rO1fKacA&ufCI&USk7-$e_~_4&Uu{WeiH2mGE+GEU!<#ggi90q z_Y^tlT$Hu`JEsZ`gUd2*by|Svd#0^;-tYEmexG}b-tq}yEJ4D>;E&Vd+uqSi40!^Y zuZyr9qzna;X}DHU^KRTm&nAjfBRPPSWPV!Ltwu2p0AjUEjz`SDO1;YSC&OwH+F~Ul zbfa?qrQ(5~(8#$T^5$F|lGKFgjV~l20|C0=417##-8$S?4E_%%X;uO+yL*`RdDSg) zAN9|vNA=~lIAoFfLalp-9e1`#EG;VJ98p>bA|O&f-`Lio&N}!=c#`C~f51!VFvOjw zR0SBxU7&C$r$jxQe6K0eKvmgAHxq=U`J;8#8rKw)cw3#mvsV4;ohg-IzforpSV@v> z5@Uz07_u{Ox%E0)zyB}e^jolI`sK#3r>A|ye7T_u_hO9Ux8*-+SG}j5gEnTXwmkw> zsdN6wR*81`g@$_EMyQ#Q(4|?YIVr;?iWc?j>Mck6qU=qIu_nYL1o5uXk45n^L(53} zcz7=0Otp$pZ)o)cu=nI`GcI%amCU5o1Mkcj4bpXOgt}~Azx=UQ_1Ef^m3FNKsZeML z=1nyAEF@L>=_PXb=d=qSd>CO==ur6;0v|O)0|c~`m{}K=I4yde36XH7|6f8-jq#sLjTPxqyPe9(Q7G&7&Y7K&gj~>p`g^@x(r$l0U!pp?3AF*K>Ol4JL}MoZOn&pz9gL-Xl?I3aX#+Gs=Ki zSBa4WKJDXomKwE97FANof%k66dNLjTZIL~uJ6mr!?KTDUa+1ZcJ7V5!?MVryL@j@m zj17(Ef90NS(S-2=wF!+Jt**}>=`O>#U9ljke-;1~vlWw*1EhQCO=TNJKAmN4=>QM~JqmcSO|vaC72V&+%_#P=8aQ_D-H3XE*O7o1DXk?ZLC z@s}DeQp-4p+^0xclSwS`U-7g{he=jNk5#pt88W_ZI%>kqs`7X6S-5d3ZL@Q2H&0>o z_=JA`U%e!6y_|#y+ZOOSLWS|dg_HcMs3lU!w!AG>|3LlhXRl&xTKukJ`V`5Gcl~oo z9AUp0aF}xO_QI4&_!8{;%e0oYf1l?3R+?dX7c+15?b#oR5$ELc6$);`0OVdyFtW|= zEywpg1)lFLs0XnimorGD#GP4@-X-rSdoU7U@Zw#7ebaJ8k*i>gQpxkZFgv%}YNwAp zU?>5BLsy1BA&^#{7Bx40Uq_qsE*5~u3j#>do9IG(pF^pU1@9Jb7*=9UG7f3&iG`d{ zR?tlHrM4Q|AY>>2Uxl&=5&>VIDBJ7xDk*mu*#`8q+5qNmya@3B)@vf3G-GN8-!7LFu_^+ne_3zb zrPWqD=cpF`gEyg(3AFetRw4GmEo{@l>Se|^<5vvGQ<-%q=|kTC%F)5kO38KkSPHk~8pf2zW02vS%ZFz;F9UyJe4uA;x+BP- z(y*n!do$N#;^MjV23Zqw{U<^}Enx=l{+nINV1yX;cx3cU>8vefX%5}}?MkRUDJX5) zPoafX3>Ki(D$e~Rfqyn$SyWauul7`#=$pZj| z!Ua@{+AHR&w`mW7`%P2%q306H4w=_<@?W$ki!*eq1U3VJVt zVy*f0RkP6JA2T^tK-s4tOgWvD#QYd_mP;hcxp?e-9@{+s`YoyH8(QevN>lYaZQ??L zfVDr+cVC9KLfh!T>CB$f0MzwBq_(m?VJ}*Jr;Tn#6mO@{-7Rz!`pmWEy;#%y?#$PD zYeBD{t}0eAu0`P>9z5nb-i_MFJ(#~|IoE4f?jA?pi{!wYkIW5|ZW5aXS+La={#iUz zI)w4ivx?Ww!v?*zx+!I7h3cPGFGaXWAek>v!qIDSp;|i}i-2i?)98Xo24|}q1A;2F zJ*=a2Y&pgnXaP?>1E*ACVBrL!>{8&WsvS;CD>rHl8#Gz7Ug~&KOXu&8%Ud%b*bQ{g zL_XcVD+t2>>B341p``)WB#JZv_ee{7BK*?}tusFx)*x9)f;G7vU?n+{4Z;C%3HF878$A@8qt!8q6_91qHg-Bi_;!hVG0iO<;I-2qFCWFhbJj z+qB+|;eC~+X&FFb5l)$bHz9@ljSQPR7-LG?h4p?i-dQ_ZW&b*NM+su>g2zRwfIaL7 z&b1mXzI0yBA`gQ&4r}Ts(IC^^`i4eI5<2st=sOOFoArzxS!iUG0<}jrYaqDo=T?ms zr_5=F!Oxo-t3>HuEp&DVqAp|c&AwJSM*|oRw9c6coY&!^mPF+f{$iL}2lPq=1rk}D zuqo%Lr=ybYz#y0)Tbt!r?#z0!;e~Wv;k`9xYu(n4X7-Pa^cp2i@bbBL9n~@|h={D2 zNLVa)PPZM<8t80E&zhIiBtP5O21nopf1K*bxtW_$#H^6hNIQKwc*9+dtUInUI0fk;|uq z*`-2MDZ~FN=vD`+&rO5~CjcZ-_>$gykYL%>VE=}5+`81M6AuXFH(4rag54Kb!5M8)ob2!Xd8dDw zG4htj+r8wIKMEJOzZ>hLu5xus4~j$gshI-DwOn*i41I_)czHkFo>HO~oJvM{LqPl> z6fmMi!*lSiz4oj*sYUhI)7m+Kt@l!$&)nYb_ZF481~drGP+5UG-Rh5z6JOyk?=5H{ z;#Ga5Aa7)YN5}&daE39V#FtWfvpn+Ctdo?hK!cZ% zj~f~-P25bA&vos?fT#q&ke~%3cf|pBB{MLCk1p89PeJ5| zE3jU)Od93&3!NR_TnmCXRt%n1uls~7htzA8f2zQAm%N}&u&*<>wm2SaG(zupDXWa@8Da6XQ^EQpp>0(uNVtcVLHFm<2bk;ZP2SSC8s{JA2juJ(~1>-)9? z`$qr$z^EtOY4~xl=IJA9T^_y1fi|D7cFcLeCT;XJ09NiX1T~omb;au%=toT(_d1xi#cwS+1bS(gr- zOl1ZHEfc(c(h|N)C_u3Bs=_jHgg`H*Fg(FV;T8I+h`Ris=s~KAa*Ddo_DOi0&c%4y zoqW#WSok2S5#JA{VUL8C=l?g}n4}ah@I_P}!5*`aK!!7ii#ovB6#G=jJK5JpW zwg!bNDg`_EOJHc#aXY5>H#9bII(^X@K5P0gZCk7^S_zbRsr5Wp|>(18$c6r4FwB!dtu zI{Tdl2uN`azm_fQPl)e`dLOGtC$cO@;!gCl@FN_v2_$?+`a#hmx#KRbQZ&G3Dh^Bz zI`{z(bkkF%?43{T`F}6K6vw9NqSX@rFBq=fkgy#lWVC3EUGoS1qObL`UJp?yDwL^5 zs=>J%8kYA?L8yZAb>4Xzo?upLl~W1J1)gqug5Csx@VBIaK3toCktL-vl*9_K?5k_uq z*Z~_Po2m}bSjsFNCM{wqssstQgFL}WY2%5j(fr5xegr_Z5b$ieBk7F}RwF0BA9J~M z>}=?3in^Jp(6I!fi*G3e!73976j~I@O4j12PLK8raytpW(|oVH9TSTU5vA(@K>aAf zu|!y!rmpp2;hYC>|MF2cC)*2lilB{mG9A0fGg3eD?Hv01PlLAVi(?hT?A`XgtXQlD z-dy2V`en4MVK_^GyBE-&it6J{z?61ixZl5Wq^%)hEve6a)I`u0xE4nE!PIZdXRM4+Bt=DccwX$o^d<{+_zAg(` z<}b(HD#A5XTh#_6$w7v7M;Zat9eO>w9!g68Hr?Qo&eRY!yQfm~8#>pjW%xZ0yvhJ$ z?ZaK7+9nY>7x|RakT$$ZA7gD3W;EM1+qR-5|6yR(61B!+*$9xYMxd?|1qzki9ny@z zqQst(I9C%+?P?DrzIHNRzg{Dr)OM82`Jx-jdXlkLjn&2A%RBGWc#INGB5OA}qJvx( z>bWDKd>;7jM7?LU2&WvT9cpPnV4ypW0`WT}z$GUM6#5c_mis(VsrGe0Itl!@T`c`M ztnyoec~$mjplOMM>i+EZ-YQ`KB#9pgKldnBZ)+0BtZ23(wMY zY*=BB6E=OP7Ox=1#R$p#v`V}*-~2BARUb!l5Lx?rVk)lpl>{i^_ zCLiY`tIlHCm)-CKy=IfF9tra1x=E{dE@o;^f|E)DPj?GXwv~s|%g|)>s)oml43SZg zoSswqEWb(qrBz1t{P9(J}NRwL&ukk6aZO-;h4M#Q0UW7Mu-tvSq;EJd*^=?L{$3bZ&+EHIhs_FGn0otaF@$K2m z-U#)12&YaaY88)woJw-3Yz8fgnBfJVz(oJ|aH<%0oN@$9g`>Clchjb_AyH?>tXE+={IX#M%!J1c3~-60Y80*;}=b z=bc}_V?D|Zh`|W?CM{HpY$!N4sI%f`N3j+YJY{O>O{wN2c}R#I%%((j0$)CX51)>r z)J}P@#%El(AA~v{ijM1w{VvYtFD#Ifb30n}WPqK!`k2s*vi~GNBGudf+f@ZR_FM%d z{owEym4U18z*`uWq(?X07~>;(o)OSqxNa;t5U>YCVo;Ho5(E6=k8dLxqU;_?K?^AM z{==h{k;f5EK^p$cStLqb@x=o+PO9?{j)e6FC$R?2dJ_^TKo_GhWV)#R)CGIRX1O-d zP4v5NC_UBkwi?ML3B5)48o{69-h$p^QVBgUGjSLK@Fg{bo4NJ_9oKt57Yf$M8diC? zJ`6mHRuWSlp%{fm^@CMs1Cu=wu$#XO*-EnF_Z_oia0{36yY5LmTf-bHf zC$jWXISKO~8|tDL6OovdydjImEb$Qi@nF@T;}BB3hrFQ#%H}1SG#!Vgf$QS0^k4)> z$J1-BBKXMDYiJbE?J8REjUI=;Fh2O0}!|R=TR~T zv&lH!1%i6Df$4>AMvF#2g{G_^3~1%89IK{Zo2uIG-}$$F7leE*AZ{z^50 zKraF=&5&NoM#kgG`F`F@E)Jr#P5X_%`_Y2HzNioHt*4%+C3xQ~6jRym&>q^VoOJZ2 zZst0_>qWvRxHD(#xI!;XKkE(vs*^u0v)682((B*|zNNVbS{Gk_aY511{N0T4GFWXw zF9xI&ZNeokVd%^c_xbpHC+4HNn%hfr1c0nf(Eb*;H{&=G(N@toCep?YSR2(9``4*5 z#$gqZO^Lc$#S{f_T&)}JgLD@1*3cRoK9uGJZ}tb3y};img4otUh+^loljGDNE)9z z&Tl=F#DQxNQ#FSKW{K0)hg}TgG?8>-*R0(W^h5x8mnOUrDIKoqL-Y3K$|&j)Q5{w0 zyuBGVlM4iCuhwk&yYl`vh#DvzS-GM}MOs+HNMaTR3xrQ*vPM6}TFK z@owk3KM@1A3Td9((ghEB0xu=F?t|>#y$1K{Yuy4(p)5n3+Us%tXqOwj_ayrFD)^zv z`{1Wy2u|ekC4I+@x|f)MXCRixwN+9 z|I#|k^w!Baq6~F3pq^)WrN+?bG__?RA1+hR)6Xr!^TLeU?e($J+UZ^Dpi2y9%dZ3d zocRPpw#D#ANM6mywcTAF1+HG{tSuS+MSIe%8w{7>Hu)iCQ6x3j}({RlrtIPn@+1_D_nv2S9lZp(TGxu;e0KCs zv%kXnA|4G3@$!ctkI$nO`0KBhq8Brdi z=Zk3Uabv=R zz97d~`rJZp+p<6wcecb>n%#x-pSz9!(ueyg*=ntAUMjL7tvbQ?fLIN<1}Cy#hXq2V zfQbUXD@nkvaw4P0`AzwFB>b-uqsrDLCt%;Lrp8{=xN9S*v=jsfSI__xdU@5vh>kH* zqZOMd{0WGbQ>jj@0OPVSiGDzRfU5 z#Qd9ru|YxZ29$AfrAbd0cNjW$ZLK4y2LpSh35_AkOZ5jEtlX^Gl)GDc;S&<~VQz2c z0`2of12>kGcBkd|{_Mc{YmeafZid$xK0pmd2;xyi7NZffwDX!)8hgX%I{hD6QK05l zVO$r-pmzFozE?b4;{FBsx02iCm%hz)UJyYxZ;ewvi)Y(i#*w=?A2N-ddh?f;$=Nr_ zGM?Rf&y8*#m81M#ePdmH-DJ<{l^d48KgheY>$ne)?Ufn%2R4&OO>AIY!f4}3Y2qnb zV}!kX9JE;IbypVbEASVgS8pkWRusA|qZ{J{M;seeo5HkU&rjqR2x62cRKRUnKVd7z6ULKsdAP~CTSG10=I}sXub#E<9`Hy57Q=QGV z$&lqkG{vAXk#VS0w7sM@8nxvbAmHd>ntt5 z%2A>f5c1v~(62T|JVVKG_vamPiFTG8WxdOgmW@WpzPD7Fj-mhOnI-Z3aSnjzrkZP2 z6_upP?H2P|bM-WIshvfRk(Y711w|9(h`%Gkpv7&d)CvdeNVjb4&v2s-10=Qv2_ETY2N%!@=f}tJ!!lQpNa5t$>iRNEXSYbO*ECny0 zQ2j;-PwsvV)_DglDkjiuH9yQ~jJ0ie7uW$kpW zBt3mY3q-`?Na=~w44bOrFPc&;G_viPqzCp<^9$i_R`~S#ET^2A!Z5cumOc~6rkuU+ zf74903(`>+mk&68B7mZvR0Owb^~Q1YHI zeS_*%My(*8Bhpn^8+%JzYsL-vK_^icwnZbtTvaWM_X?MpdxCrT{&aw}uvKNCHYQB zqJ2^H_O@adwzV~)mZP;*0JXK@$p|r(2NdiDYaa(nDUP8F7P8N)Mcr^!Cr@|Yj&EKf@uqLx#sajCP$g(n8@cLtT&p25 zik2$av%sI}iDP_$egz(YyOqb_8IZ0${zA0ki>O?w9bmDko0psh=GcD^*RjwGge+uJ z)_kyJD?4b}%<#dH`_K~|kifJIdCaa{dR_<3jcmY0_V*=Wn0NX6^;sr z{OyNoH+7aFJG)Xt$k&{ z?@W!9voNXq;bR=d%=$K9v6Him{mn)&|5c09PJ82qz)lNh#J8pnUAU{>sSB*V@#MX; z+&u=pEzp7hCmWig7~NC0`AZ7^imZm~DD~$QhEYT1Ki9e&&gky}6BEUX?xogEdp6Z{ zANuX$U>F}7$VA9SzK(#Nf^*!O&xW~7qDjFjDx=Qt=#xXep0Se!KGcd-qs5$rC|qW$ zpdvPHb9weHV3OzdN^O1}$4AVD2UzV}Q4*r6la6{}l2HHWa+`Roo6!y=ITgQaCe`R# zr7`Fkpi!3+i9?}DRsU+c(JHygE>3D8q=Xdm;uzkm(oAj3GgWTk#l50AvF%7Yzw-~2 zV$a6=4X5pAewic#>)YoUJ@fRO*V`@DgliLaQg!qK+j;c0#jjq= z&D$WzP2+~1v*JBkEt6m2a-hj-PF;<8;E%<)1STKMBI8q37%SMtLSL9e;ZbZ&wLv}{ zuaR<+0~~zRLDE5glW}#=zs_%?H88IalG{eU2<+S-MMA!f2dW?u6-Sd-g=> zrFKrH*X}llfhnm@G)MHY^SAIpH`4bwqdu&v!KD)ufL)vDZDn0H=7(;zU|Mmq0emkTV`Nb@5)icC$F5~WwYgzR|Lz^*htr()+PS_y8Fb;; z1G_^mjhHOV+COk^vNRy|GB3&Yh5Ho+-yC~O>;b2rwb{K3g*oySX3O%@zP854uFsu5 zK=9tGr;C%;y(@*E=Q7HTL5u#wVLp5eS?)=puJgJh5@LR62Wj z0bVNR>6$ro=Od-F1=Y@QrSRks!GHf6=A}gX*sm0hWIhZT4d2oX|N019ujM9?tZ{s9 z_t}QFTfIJ&A?)1M=@~j$Im$S5fw>x^TTuFI%hcN&8|gXEq~sg%`s8e_o7dN1`K#77 z{t40m<;{hZEsm;aoB+lOPuI|tm+o`z>it(ZOPL-LSU_`irGei-JIhaW*u~6z{+#qr z&2^$69Q!4-V15lmRd=X8r05GvXwBkxpR`B}Q4_4#%r1waQigc8y0ZS$X4)+?G(x7L zO49a5bc8>wSNBI&qr+x(Hbm?6^-oZz7X0%jQ3+qw&?1v{iH3faF^9UaGiG9yPLzN(mqspuZpJCyAP6`(70rX`=#X4yL&sW>ysyg0( ztRI1ur16zjMH*>T`9H9v>uX*X0tP61ww+pKCZ}^;lFcId%%T)h@*sI+xlpd-M3`;$8p&$IhkE- zgd`YiE7HnqLT)7-_LRc%QjlZNJS!*BGi$yh%LonH@0Zm+*-uD@-d}zd z7%Y#uw^a#%kJ*h=Qar%vl+Nyaz!=fF-bcY0L$*E9FX8ipI!QMrah?tAitSXp%?-9A z!Yq5lyalU=>>b%g=(z7n27hb##Vnl#l+}U<<&H`ljLlAf7l!6rD$&k^OE`9Tc~bnS zU9>1aWQiKL;HeFXTbChNGKkxt5(;jJW{~jq9b76X-rT_aJCB3=PI@eL4 z{oWq(Cv1dR;7=zpo;)KQcF47IV|-6UK&P$#{4NS#bOkdL0Kp5>cX&jYr3hEk{YoR9 zj=w2wj}UP8ST`heB;nrkx12(@_z_>hos%pzw;n2A{l<=H{d-~jH@=OE$fK=z#$X@7 ze%7I9vrjknAh~{UiEOYy3k22W(fQVQkwNBpMo9+gVie^=2pjw0R%c_G2G@6WpT*Y% zm`Tm|Ox&&7N6ARW(Ob!#*qhDnxSlazZV1|#DcY^n{Qe%#{}dE&c4?>BF9RzLS^K{% zfXY9$bh~c0^%uYy%;X_}1M{&`61Ap>{)P+%9aYitDJBaQN%p~RRg%%OouUb1d)P34mS|c%&CGj;j~6-o2<^d$A>^ z8JYvK3V7@CYO?{q!Q|TimNAExk&~bhmAV!$i1u=$Ob7)K1s||Fo(>(%RMLXQFZGEQ zhczODE?G)%-!2g>U{ZhilDYuEb0_4BX=|Oucf54X&r{_E-puMJ3%5D1WiY(1<8hE- z*%ko-0^!LYEUQR;aXuC=Y9id*h2;}Zwx&X!rEmI8q2=UYr{#^5vk37=`ZB<5`YFPf z?9%55)LCt?9JstzCwKGR2k3rp6e5NtAlCI=3T)UvP|s_Ig{NXmtB>_>SmDT+Ic*a0 ztCg>m{YV2m1B9_AJuwl+%t`aL%Sby}c+0zD;I3)o9X#O*c()v&8wha5xfqEc!7&R8 zX3?g;L`E6`yxcdbS9V}m3aa7$hMG!^4o{VO_aCHy^YZ%UY0RnX=eS1{K&qi(x3k&K|2+NUroGfGYe1 zIotQJA;L81{N2&g#N{cwTnQ|C5xCl}rsda#69@G^uqYE<=K=9X9d*5?jW2wUc)>=e zzXnf`PaT}yNS&H%N-p+wU_b&nf7N1~k5m+XKQ4lMf6vhYBIbn<5|4ER$KmdZI6l^4 zCgfddbs&}js1)X{Gtdy%&*eSZ%Cl|%W9G$$-B+c7^2M+#)3{d-JxolmmTy~q*yHNW z8gQY=Kl8irI)5pk$_@<_Q(GJw^4&mKXENq9?WOUch9EVhV3UW!esTS8)LUCeDL69^ zt!?njTV4KX7=e|qL$_hb!qTY8SR+px1~~p2@L$6NSGkxdUb=N*{+5@BlmX7%}?N*zd~1!Q$`iM3VYT@}*Gjz=%B>S#qU};FR}o zT+-$Pi&yP_Ov29C3qhtPjURuSxv}sR#FJhI(zcHD2RK9`bEAR$gQ2?m4l5VTig-FC zc7EX3MP<9V5`mD&rn7do5p}DVP}lVPK5E6b!G7%;F%Fv*K}~pkw~d{b2MOB_oEt2^ zC_B@vm_B|cR*^D39n{_xsRX5Wr?~OW?%IZX6|wafcKOu#!=XzUR=z~35;n$OP1m^E z>J5HoGJy_RcNJF^?_BTBgYR#sNu{_wr;*Z1ia+PR;?f+#9sMFO-RD)P)KOrV**$4Y zH=Id(sk#fN;a&$$lYFG0<3#2Kg}F>u*>A@SejlLhTK! zjappUjc1&*mbS+@WWDt>hd#EW-`3~1DCz)spUIX#sFuo;r^SF0Fhf))M6p!230g{&H?|x)5 z=O~X1I|0MBu9gtv=F9gmv@pH5y)s&G)#bvBI?OSE^W%(1FUF*}gIV3A!F8(!-Ts9- zY+WTJ?Mi-N<7Ks`jpPTj7OiDBBXkQAiwc#m2`3~}NqLKF5=~&EED~y{4-8o4IkN3d z+0lEB@d*SPL%%PU`%pp6IMSEXW(4N*QB%FTShrDO1)%$IJVW$NpUvx)>yDB|>!W?! z2Lb>Z=A#;gJuGUm##)Pp4Foq$>0`md{T61moRQV@L|R+-;2n0bZ7O~}lE9Yc zAuL8E&G=apMj*)Ew1=VV1M{reRM5*3tFoP6Q6|P}f_8GkHhJZRI89_Gous>p_1>VM z|JFWBIM9n2Z^EybP=kbj=I=XM$|;tTyE81^sTvw&e5U;UMWb#NHAT@{Vc-?TB>Mod zy4b~xSUzV?J6CJNQ+Kc*zQn$&7nM_gdFr0f%;+qOfnSl7%_;}?cTznGg_CO=6CPp7 zF(jMS&mQIjVZYg~xvn@%9(GXl$22I#ri48a*+M>x>;)p^5@N9c(=OEmczqU@sDM-#955El=Z&KG zM=5M@MYNeY&XRjMPP7poUxb>JixBOuEI;HM9Cg!C0?GlHd@s&HpD^3m(yox${g<#- zt%$IZ%TMxW(YXsm192Bo15}N1K&R~>a29fDa~SLCpp(4Vjx!z^Pqu5>CE7UW1TFBr zzpv=lGCe}umGvaIg2fI`2S*OF|7}&{fx7fgvr!+_%-{6w3IE)Qv%s=Rb2Ui*Ft8|yLKBTnyjW78wtqwBqE?Wh%@NJd3G_#_vcrqC1JVuor z^Uetrt;n!5^=3liIr|9`rHZNG7YcU%2-=95pfz5f5oc0!x0A!mSZ@N|)FC8s(Z^?# z>dxy|c60^ai<3?FJu3!5FVbCLZ?-46z4-PnEz^s{-qFlD^aJv32bXEDon40gn{EX2 zgO}WD8vJ4?#D%;3)XXMd@Ps_gijW_aeCz?)QArFTCZB`Z<}0JQ zJY@QMxSSs~KS~?`F}KYjKcdH-eVpD(O$8-=5G+T>1_walWcg2>`sTL!^;3A*NFq(4 zkk*JUJ7q2S`=iJ!y*l)g+TL_)8Y9(rN1AH!dFHkD^}sPgYE4^pBLIeNgMHy*v%(Oigr9kNCFDL&6oYh`c> z4&cYNgvxFCGwe+J_s-!Ha2 zwOhPONSkd;(mjS!EGhi7FqYzXILa=G{wyyA0$J^(^=&ED(aYk9AyE|e{mcj%I`{H1 zvsw@Ax>>(jY3QFGrEt1K5p2I!nxIdj+M(>dc2rfyQ&x=vk6xY$df7H-(s`#F$ZDqQ z)|JLe8|Nkdxkj#k%F4NL%3lM7U2?oTK9|u%r&9(0oj>7#6lyN;Jubbo&UzYn@ z94c(DvC#EsEoFMETqK_J9FgI(z$ohPAVTowmKWY2JJit0_T0Glo;lLYW%ac${cDo| zo$#^;7Zva^NGfuvtLCvFfp@3a3bx!5)N=MtY9P4Cybk#Y&z8DoX5C2kzVRmy=98B~ z1RhF{?b<8YF^06`swtJ92UQj-H^0!yC6(IRYa%%i#N76* zBy1qsmC(lZ59S^@HwhvF$ml*fll|SbnucL;&*vSnln#&6v&t`h(vt{`k4Kanoh~!x zql=lLa@^9Qz8c1RJbWvC&Mo!pW^}|Ra5=!lxy9}M+d?vc?RHj>?u~$8*YEDR*Ku<# z^4J<9OIV0jP?N^c5m>~hB93Y=(pDu{u%L`*dt15qJ^RSOu<*B4P)jIRC)2u*o~SNznBa9hmla+nDl0WO5_p z`6othS~V81dau=wM8bTE22+N))aHM6gd>ZxSdVr}zuHc=r^8&yvEK;y2^nrDk*l)m zfU-{UepebOi@PK(eQ#J@dj+-%US``l4*uEE046-%?zXb4cb{qBkCJ=`Cpj8j!Tn-n zMnDZszv3Z|U`Qr0o+)tLV6vvzk+PrxqZqVKtAsDS;jah;(^62)`+!V2wiauC_(a(2 z6;rj~%1(9vFeuza#>jISvi#%Fd}u#Dbi)+&z&*u(|E|i1#z1H%ogp|5)cOu?E8g~} zuX(*qkgHpBmIY8Fx1kTMlC@5icg5zag@PWquHnJI~8CdI#TUwAvZv_>^8b+H&mLS z*=U}EF+E!7uu*K;>9Ur>5Xg@^)XI*hlikM|7wODB5`#qMzR?bnL&Fh!pF^CjE^Ak` zks>XZ;rOSK0T_t$I7T`)UV!3*&+^0r3*%vUait%sJ7%$SWs>S&k5#a@w6+G(Z`WK6 zcNQQ5zrsBBGG7;kr|=}}x%2V%w5vV6(lVG@*<{^M(XHzwD^X9Z< zOJ#-cI~|yTq)30@W08auy2V;ILv9@CW;gY#FQk>3JCjs=pIxNSmNc?Q){Om;ilic#tZYy zmqJH$cJy~Jk1*Ile&6xeQaB=;a7hG`pi=e0X0)#ad~~%0N8})QU>YmdZwSMjHM`6V z!YhPHZzH9RE59TM(@cGDN`1-M=ge9g+h7gFBCfEp+mERzm2X&(Lo6mVg-r4a#cor+ zSaQhWK{{+sT}r`5jt6$?$h zO1Y0mou-;*I*y%;vW|}Zd|J@dFVe5W+v|uv4%WB;YH$N?*4`F2IFd_Hg)SSRPTDR% zoCO;v45+13W!9}kB&N`OT7F4J1~MTGV!~>ezeLix{Pt03lNa@m>NmfRzmxoY3nR$) z?;@QUW=UIHZ$DI+97!R9t!=tNNyk88!?6=vcVUkb&3RRtQL|5~^!D625eqes7~km1 zdN9ouoy3_)>thG*`=P?Pt)9)LedGcF=muihL%!Ha16nZb9>WXENaWhS0}w=5;tToz zQo2g*|4-?3yOoc8*pAP2bG27@n+{mxj5HKim54qBj~=L+Nhf=97E^h$<-GhXF&?Pg z@OtN6`U>C4H}-;dJqzE7Ke$?`PbfEPDHVFdv@lr&at^{%fZ9 zhH5;s=sa!jRh41$Fv%$!1GbW#rpK1mjR(VL8FpbK%q!O0RH+M%{L+^(iAJq2R{3^3 zI4H$lZmZ;*)kKn5NSEn5{z;n;Ry~De9Df>xrf52aYAQOKD(`XNgL9YtMqBYN=6+H0 zRy`&qa6DsK7~GptY`mhhTn_9Xaey5odX^$}`Vlazugdz%^5BvJ<{MTP<@^HI0@`j? zgx6a1Sd;+x+6H0gRkxTTqw{d)T;?!wP(s76 zDr&4NS8|(bIk!PSv|XDm>T~(IKQOe-)d**9G5~Ly32Z69O64S%u)&N69>aaQqTD|R z{6-_afwup9&R+qvxg7Bn_(_W^S&Rax zH!4AbU(bdbGP7p%pR&t6lx4GhGv4s8V;PGHC$5+AKp(ax0xQ3k|Ju*qTo*SOMA7W_ z@*`FB#6)zqjn1=p1qoqAHv!<6q>URH9!di{dNX;9WmL;<_A=iM3a#|R%wV`pngZ0r z>bax2U55fT`U9pEBK3RGt~vv-qhuaz&UwK(!rYF%0Gzj+*G?O+mH!M8 zdS1*tBw9qaLcc0-A?4YG4_FqT>txN;V&rw_LmmT8?@ZE70sE&rJfS>O1*hj)Bm;0FSN=4dJYOwf>c zc0yYb1bddnDjZkvd!25EzR8t$#I~oKem>lZ+eB-$!CcBVO9|LZ?_A2JuR+azZa;Ak zumDyQpO&Xv0*9L4xa4B_2TL!_12G3lp3|^Pt8hDTyn2zytm{-z^Q>+ThA7I*iQ`N} zzZ=ol;h8L-=FeRIK%XRD69WYO8=M=rArn#9i|SfO9>_A{QM4umFKny5YNGVH;^Pa3 zmazZ1G)bT14~W={9%{*d+(hmeN7el42&i2~JBRHNO-z93qdY)%g%bC9@d75godq8p zllGz=N|P%XAeqKfBoJi2$3|(z^MC8CF>Sf?Z<~b>@s)wIDYuzz^SmJH|{F>DBIqyC5%jM4T>Q(-_5X%^HZ)F z-!a}~Rg@xyXJy{J4i^gPfuq;3T=sPD&|%-R*y+X8vpxJ>skziOc_&P2B(j_I+df)+6; zQX`fM7&p3u87Uk9{oZ(!A{#4{PEYVo6es-?Nv1eQu-2kn$Lb%rdxnI7u!~;sthb-x zTBhxXT^E9EitNu{@vyEh%B$9$6c-uT)|I}LMR&9zK1z!X`zP6jO*a@>=5;p^usI6* zthv`e&!HYg(9kYp@Y!HzCwY6|E%fi^o8#iza5iOCA<5`A6=r+h?29Y??}^oyN(_LgK?I zmR<<%zD-AT*%Q;;JVD83d&fdBnk-+YDC^r6=#FbLXN(E<=UI*8x~%c?8gVho5r4(= zg6hDWd>HP(TgX7Y6 zn3&mZXK<3^`dyS_KRF6CuP*nq;w%a@47-=#JB}v#OXV=Htuu0rVs9^hLRkn;nXL=D zR{-}p4n+aUkyy&D^`^log>|wZMH&cdrePe}ivhL|4QjeM$9B)V&0zh8L8X7(Ru{8u zx2p$6rT`M0e#J#C>(`iC-o_RLeP1oYj*z8V8C`(Hv&(rp$z7^I~TT*<-7F|E(6wy zA7VY-K*;}gf3PZK?5U-o&j-D^uyLOJOXXg*+KioIsXv*Xoye0efyjSvUMJ=QtcTvp zXl1knQUpY-AT2?WbO|(4!YhL|Rg6FjcssTiFiw`z%Ry!n^Lvz|s)~cmT0mc*C+8#U z&DT1F#AxVFz#T13(|u z?=U0sw>@4+0|iXWxZp-ToAJv3tV6 zmudgL8j2ZY)TY>zbr(9-6~R9B?;t2;`!h7LjPPhHKL-^*9|95;BH6*`J(_)G!8?@Q z8Wpczh+9;YRV{`#&?b6%P&=vEY7d+qP!x`Pc`W20@W;0;>+*oK7RLlxuhri8Tzb0W zbpcyIJWESNUdxAwzuVy{YkO8$U`Tj~Kok2gZq3a--H8m%$%K;g=nlU=Mn{+}bBBDbqQIi!VKoJFKpKlc|6QBwgj_%%<>a#`- zuqAhUqYrbpCYi>0fjcU%1`iKjY@jdpyQsREIP<-dPSt*smG0qJq_>o))#D zHE4TWQ-u5bXA7O-W#wtsQVQ9ARUa1=CyY|HQWq#L4-E03tBv-B&OC3m7TP~STF1Yk z7^9~`v@BbLn4C?2MLe^rUBCPE%fONgJUT*y9M6wU%uQEHZYncpgPZ~pxbQcQ3ge-N zBnyiD-gzc?XhCgJ(8favrN1e|xYx7&89ewNGFc!EfR2%?@n}ymrLUYDolwo8pJvH?31omNEXo*#lUL7@ zu)Uyo9M@h0NUip8?<%k-;=*b!zNp2f#tQjv!bQpt$L!|3soT_6Yhk!Csxtd&f^0w_ z`9fMJZwMeHu=>9&K;7naS3r*j6^1cc5QJET4C`Es20}^4=B$-=iTQas65Ec*_w8w5 zxQu3&4qk^{dTkDCNnSRKehxoMQT5wf#)p!cNq7kboYqzoBx+sA(NeKWFg4Gt5_>{< zuPX)!_$>e3i}*<)0U7?zs>x}3T;jTL(Qk_a5T=MkbDyoiZ!05a$hm9vazHf?LTzlqGt1Ws&!EC0Y44@^yFaEtG zEqGPn`MNoH8OgmeD{N7}M%(>*6vK%Pj;M*)wmLaGr`&AGsMh#f(^0_^P^VPL3G!ah z+VobSdt3)oSXCo>5!BstbW&^Sb6*Qn4Ga`$qPh)DrCJJHs#E0EX;(OnGnMH9wVynG z#?n%zOyb%Ys4bSWQjL86MHeKS22zhgfhctNQm}^UO?NS6pgAaUxy`Zodtq3%M8=fOJy*a;6 zWs449J##1%{U)k8Rr_JE!owmVo~e-5c;>?}GfDrS?&bcYIL2v!@`f4~rJ{E)*U zXChc!@j}&1ewh-OE<`^7`baH?2>~NI%VGbN6>~vm>XT)~7Q^3$ zdH-bN|Goye3_;!Vfyccjd1KJ&JL~|HgLYe*Bex4xHP`Enqv&ij0*boU7j!R@{6?O}e zuUVT51!Z`T8y6T41^tw0V8Fi%qBpT+wO3|qKT`X?Y&y-)ur18&{vZc?d*tYg_*rM= zcQfIu7caz6-9cdNqFDQX@+(31a#ad!O z8g04490gY>c1&r9eb5S;k8M04{u5*(;H#NNhJjpLYLaI}{wk5_AFYPvo3vny)kSOd zB->Ur?{up4KRN&~y#rm$O7}1JAf+a$GgCU2w@%SaKy|m5MkLs((Fc-1`sVwg%UZ6w zQ9~_>PM%*6-@mggsczGpB7bvF^AnU;F_R@rZX;UATUdj>M4h|>L*%$#5>;$UuK}mo zbwoMx5}AL~j2WZambmsBOpQ2Ob&HiERweXx;n6T}&N93&P9yF*?tru@o+ppWFQ&7; z{tiG948v&Hvn~wVGxhr%`w3*POJ4lW zU%W6WimXkc2D~C1E>>(=%>CTIy=1GvsoH6SDU5olT6&GQm$eN-T;RU}c16hj1G-+mT~-u*jZw=Ijahz?EVb3*jqA#;OH57H+~!FXY$)4kJ`IeP*cw3!97f^JGb zg%AxXW?Me_gn|WB`!u@63SK$H~Yh{ z=ytq{Cy|S8Em8&*`mY?iPi93`xrxUYk??n3PSv5wC!>l%`x!KT=HO0`%AXJ`D7?M& zS2~vDy>iSvTmwng(z&e^KmP3hs!3%wG4{vMtpY~UkR%0YNX7ebqRz5&t+ll}j?)9& zNua(q%rY~SHgm_i>W^wL0l`9#!`2{|Nd1KB4Gy+|#5F+j1 zzOQK7Z*pf%iDkOiHY_t(~9>9Wx_ErO;^uA6Aj@16LmgNpUtqBPl(HpVwclnl!aW zJs@Ms2Brq3m28{gqQ<5OW*Y^LuYUX=Z5;ey_;u3c`aj(8f&Pui+kaW0a)=hO8O3|% z1%g}>m29{H6{+_@LGl&D~HuxrW=NZ`bXM%lA)R~50RyHSfwR~o|} zBou?;+WZQiB{-DwyOOlTKPz~kL$f`%ahGN)3F+L-?aMI<(>t}GKG1i&V8yQ1@i`&3 zx9k|pwJ2xqB|d(v;b(Vw>k`}Nyb%-_4di%Lc{M^@Y+Q_0@5 zNf`+)9c~ae9g+l(i?97~ub7kC4;=ky+-6CE22T7vQ9Noy2o$oy6&3F8YCHw_;r9HT zy~Y)xs!`?(C{T0+K34J0zv!+WmQydSCju?t>~=HU#CUG|w6piljT!x9v-u17#S=WG z*1b}S zpd1;qtcA*)k3iGjpZD(6KVbbaBFF$jV z!Il=h7I}YT>09yxpsAIE18>qaZL_9qRFR;1SN=fO!gr1c%}15J4WiW?CHdq;D?iOB z5mfY?`5@skCv^%^A+Z#YC{hxzDuNK_|BtA*j%qq!`-i_{lyr!IG}7Ij0s>N!(%m32 zN_uqX$k7ebAuSH+20==?OX(KN?73D_FH)4`azxuGWLsI@k${hK3$+%n}}?8>mS-iGdGAA&3(>JTKS4N z_jP(%*}Zpi^ZW{f->cz#Md{kpyPD@u$P>#3Fb;6*L_{lnd%?uOKVYf`7^|k`h(RCpDVb%>@ zF79CmCr1P!=|mQiDrBzg$pMQ95-_wMxSg9ex=;c#P#B9s@iUbyLFOp)ky7p3Q0E5g zNw|f1QXEV(N3c)c3_Y=C34YV+hW5taDA1(qen?VVdT(-;L0Jl3y zeYTB?b10kCZI-CjUZ@<0h>@Q_f zxv%bbx;pc%TQT2#OgNZPGNKv7FJNiPZ7{KNg7;VRnf%&;Q|h`Tr-Xyt9GSDOMa~CP z#}wjfbH%QVJ1D<$f6|Uo|K%Cz-!Bd%hS2u$TkQ*ED`jbeeH=(XS_DQT`-Rff?eLq*)GH;P486NQLo0(g1^Dml88Ec;O-ZQ;# zOtTB!?q$x#2J`uEta?e28m{gI3C2F$UFy*W42d5Mj!e?T0esgggLOAe z=KI>xj9@5#l{Czk`R?<00dMQ_%Yr>m&B$6)lAmE~ki>NH)FQA%K%T@sey{xDaqYDTWr|l?|vUU2M z*$WB3bl{`T4#B*D1L!!LMwCvBLY6vj_Se8xf>&|Z4YriY`4SfCDIPcsE|BIlCUd1$ zjNt^w^HK;!MG%MqE=&tsi9YcPnfIMNf!{)?-+V&@8gLL5Mk;U|Cg;~3>mE0u#lo4Nh`uil4w5 zTc=uDC;ljv`69f_xVzEfgbC4=(N&GO^4Mhpn2_ndf$35dL+7e_lY5?ni{u*$N7XLf zIRLBtfze>%k3$}wl4nrX-U4!e)Rr`H?z_fDFkcM{!?iXteCB&eIH(;>fT*>2MRt#S z*HhRc3c2V3=320Ux6Rzl&Wnrw0|hCq=scKzDjS2rccf^+KNo+9t)kM(O(W9@YDB!8 z)uQ6wJM+DOMj8Lf(3T!ctv77OgfepbwH*>w0s0ri6>*wXCTJ5r_B~-P4_mp~T|YEx zePMA^AxwbN8ir8EM*zCVxzn(hbs%>InIG8fWHT&iwU_!f5UK4U;Cgoj-77I3*A*_m zcX41mou%r=lV8y1JJgY=`T(foDwyWP5pG0imy{i1Kxva=>f9U2e6_eHn@YFm4rO}F zMn?wq70{vBdvj1hux66+p%Ae=KETZOu~@wEr96I9X^UHj%9WS-kR3*&drcLHwv*6$ zq$0`SGV~yCSP$&>iQGCTt_t)8X9?NSp~<|Cf*ulB@Egt7dIE1cn!Glp+jbS>b*@C= zqr$(oJv6o^cPF8C5n?%%wG*sPab%42mwWd14?XK9g2%tQPYU zJvt1|BAR$qEb_EC|kL^mAw5)|h zMIU-_GSQM^hIrZU>e+{^KXQ8H13DP#k_P5jh5B?6A%Fc_U#*-=Cv zbMn{cbJCCt+6}rZAVoM-0MwW4PxrQVg1A~yx#_B6?jitx#K~g-g#f?nRZC^V8wG!t zwMKWF)}2cd$M#x(EJU~6zz5See75@%=*ji(F7wf#vIjCd@(9~>I3f%yWp0=i>b`r! z#x70tC!?_~UK07TJli$?R!9E$;>~i4Q@jY{B@A+Okfjckvm*CcU5qt z_-NLFPb6e}(#TXBJ|Hnjx1j{{-JOqnKvjEd@v)Nffx1D{ncwMTHgwKq$5TIYY*g~C z{)n0M)Zt~WI%``B4|iW_itbq#Tc2ss zu#|(`F5o=oX6jaqq%1JdJUW@~^pA%4zW%@kdn%Fn4R|Icn4qrBl`>3}XhJ+kD@Uf$ z=i`1IvJQ4L_PHFz;P?*`t)_E{c}W+(7}+||qwI)xP|ILv?B{728IG|-28c|=z_@|w zKhBlY!9e&=FZbwpX{i(Y@O@adQ4`Lz$dRY4$Q$)!}o({!6 z*apd-$;E%o<5=fC26Fu}1pRNtY zUoe2ry=l%Qv3eiB%8GgZk+q(Y!_PZu;m~os>mdmE=9EWq6U3A*Pb<&UZ=CfJ*5+c+iyaNW?~;;xijCu%>+ zQY()BsESjVv;Z%Dw&i*$3;Xl;cto1&*ga z%Se-2u9n5~;B}b@(T>vH&Kv%oVW)VNso(TcqqpLNd4pr|L~5d7MfUG6v{PVw(4A-U z9`mQO)Yeue0?EL;f2>X_pMuhZao^9|H(HNqDE3w$DHK zV1-W7w{=K4&g0->*$UW;!#kOCU!v8`MdHy(d4Atzf7$NJ%;aq=x874;bbyfYS<;#= zq81$4Hx6y$wJfB0X}N~6M}Jv(l0I6V2s9)TZWsqJ>G}sORVJv1BPe%V>PvT!+28sEq>HaHj1bX!7>VtIi>U4a(Ypr}i_tZtQ$=<3@=Un|#_{)%VPb{x=0glQh$2v5d?Qi%NW z1CTLGt~ z3Vr~gnEnbrUB`djqao}d>TINX z!f2K(JaMsplb|K)sbi)fMLqWClkql%XA z&`ct9^UszZyeYGNbp|(?z)Aqs)Bqc=;x7=$Tqf3IQ7(B4qym9aNJYY2YQyk+j)5QkV4IzTd7t+Gs#<1P+ zRprHXz26H*&k=p$oCD0zjRD@@h8_tAuL}3l%wyb-^paJiz9?KKA(>jL9iEwesNhBx z<0B#{*(yabac@ptZMvJm`!-an_(QVH>Z;bZ_;8^8w&wkOnHuPev3CvAzHMjG}sG~r==t7aNtJP9w#6mjRoOR67fno zNGIbUuTlk!TWUaVI&cU12J4}U?cIX;kHw1mkn*P9EWxgMXYiO*USg_80k3)3-p>Kk zTOilF45KyVv;Dbd_?xvd3CQRFqMo_+Mp=-#rp$YtD*8#RL* zoqbl$GVa!Wx0VSA*fiKOOj7D!(#^nj!y*`~>zBS74Nu^AnR!T#e-@;feIT0X(w-n* zq!ICbKp9Zs{DEQk>YB=&6gGcnfAxIi>dxU$>>r^7= zIaLOk&Ut)94(|LP)Fxsjx$uybo3mGrbr>~NWM?n9`L62sAcUuqFe=cTMg*Gs>>-(9 zox}K+W+v^<`P2WRYFFn^5epc~|3%o4>?=*GV$E~C_nEJDtdogBNEq$CDnAc^L+d-d z)xh@GiQ4c_Q0AE~zA+>*2EQYp_N9D4#C99hRd&_mfprFq3U%x}O>IS|#r(H6Js&0+ zdVCRZod0IoFrfd{2PzF7_lW63Aq)bChE?o;1uS$D!PIfBkwH)a`=0 zY3tS0?b3``j;7x(8thK8?Ry*%dCxB93{s=?9qE$32kelD9H`y)q>`!Y%e6&Sa7n`z zGHMwK)SoyuVN)V$ioWuVN720RrB}7~_7G_cq%>r1r(;9&An>b5-Vpr6sVRTfggmlD z$M|etrf)H_v2QftCAK*M8R{gql>G_bGzuPS0iQRrfLVL6RRF}3Iy(@`M>hNi3PFN; z)+da;d5v}U$#AC6md%pAx7H$c#`UcbB;n2?Z0G!ZmWmYv0Z;ON$F4lcNNIL*-G;_P z+vmJHWjDx$)x#nJl_ht1j`78mrsAFwYJ~)X@R3&&UugURZ^iF{W+pfw*9F<2>aAyv zw{J?DZRo3Ed2 zzWXT*y!hUO|Pm^|c2IT>DB&Ho`&@s93!r>{<9M&}2Y2_(1CoNg@H-?hHC-jkF{qETReH}mu^+m~!>KfI1?z zQG~)mP25(ZCsf2?Kke%WDfIvRpz4|zxf)UI3RGzKn#O-qHxNUbUh2noA!GRL8Wa_J zxnhkit%J2Ck6UAX0*+!nMd7q100E-d#O#^S<6LV840?RTK zWr;t#T_+xe@O8QmC?fw?XYv%$^M6|y=19qJ0tFMuE=2y&?I|{Yd8J`jaaC{}Yv`O? zmYz(%28E`t+X=KW1Va3wGBQIp6PWhUoH@y0WJNe*{O}y1{`cgQkGaxbt|11aMB6l%238^nU!%gzustO4#~NQ0*+( zqH1CBp`Pqf3&u(wG`YA=6i}v4WBnI&);F+t=Yu^8c@tS6a8r=x$~#n44>3c}h<_So zRXgTaV~Q=hC}I-k`^l_{nzIJp;QrpCBtWHo${}4;mFg%oP|Bm@g4e#b-0&dAcr)7W?sm zbVzNOB7&M{**`k#9clAvPqeA46N-6T<)&<2E5wiPI)`r#OZkKr8a{#2w^S{)z5R?r zpcVF@9{#-~cA87s~ zU_9*#obCy*_y8@|S))~g+|j1C_uUhwT9QnPYgAN`9vQ} zed512ui}*Sh7fJ3i%*G-EXJ?)K)_h2_-9kL?kIPW@K+VyVG@R%rii5W3S+rQvN3ep z;c`KrYLw`5oPwABa%UMh6r&3JFpY$~>C%W0TDj_WLj9(bIT-s0A5_f>B%#e^Yba#> zv2rCnJONuO`$3l6ltuW{NOriwxud64$nVsgALza=CpvlRy8?cxs!YxU0V3dWhWN@M zc@4^a?4cQ{E-AT7a-i-kvM0a6e>7pYg>7Ft2gwc7{=8Xgooekkc=KfjsS^PYzK&GC ziswQhdG!X(Rq@TVJ}{LozMjW<05=f7X6cbQuiN0>@>KfvCL}D?Q|~wC$2w(gbRcgF zOa0dSliDtNh)pj(R+1Nxys6Yt6kephV12Os4b#-GuzrkyDpC3#{r=dX4J0m^FQk?s z5wn`ZxLWgutLOKeC?K0ix^Uj-5;jK~Dna`I-HXyJGL|i=f$X>$5RKj`!d){VR$NRq zpqVh));uvwbd*)`Ocx@}vpHK?k;C|;_;hlYMi02Kt*N#DfwKsTW%wclgI z8M$i>AV(4^`Llnf?by|E)8~n89HgjF?2}>h(70>Mbqgm<9u#MJ);d9u{fdy!HaoVu zS14tfs6O9`P8uW_9Ra5+7UysPXU0%B>@kvJ+dSop5$|AyaBy56F*~p21#SI z5qwc=0FDfG24AY(xU-*5=f2W$G zF#YF5ajDs`Oa*mGyYDhRsm>|XbdVf@+ajILU(FuEO$cE$hva|bMQu{KW z5Y7I6XHg2(hE8QSoDLeC8nP{*9|Kud@xN?<_W!W~!9wQL2Ef(@GI8J?ZUr}trT%wD zz%0tN8a=bzdkqt^NC5FJ$#t-LG4d~%p0EK$Qn>+7BCMMP^6vf@v_SrXnx8XHGkWH< zLUx7*fru@0N%ss(!&_Jt3;~p=c@<3N&;61LU;i%Iil)-E6*@9W)lB+__pk4(;?Y;a zs{$Y8Nj>(o0~NJFn~%jKc?WIDvqecKp!YZt;?RxA{NYjFhZ0wiCLH^d@OU3k5n=R-;rC1BZxOr8#{v6) zsSskm05%b5n}F}j4oI(4)u}vRXM=cFhJ`>gX^35DTRc^Ci&q{B+1n?S22zp%L@K0& zPl7Oj6wGZ6+iiC~;W{fc$B9A;Sa1ZirDxa;|M1;}JYB~UdLODnlJ8rQ3`4vF(JwQz zawLF-+qq%3X!z;ujA^`UobYN&R^iNs3<$8sHJU5n z-L5X32|@@o)URL{()HC6i!a0Si4%&Lp?Z5MvvrT&oqN0zB`f;hCW{2K&5#&gR7;Sz z>~H!45P`J_woD`(;)?RYyzu+7`YL{t`?FvCTN6lyjZV~iq8C+{W1(^|Npkdb3RZQu ziN#7k2_u~*^p+4^-*(5Iz5$~$IrZd;uE96LzXHjHw9R0fN|99NhHd~A62T*qcxY@P z_BQLV*`0jOC>)!fxgAj|9f z>YwplI{u0D_#uWU+BDw{o(sV8OQfbl^(rV?TK!5TBOrm1J2!Q}p%?Ds5Xd;(L0b`$ ziO8SWYyXIYu)CDX+1~;+;2~aOdTtG!)=m|j}C-nk6o3_GA;uYx> zAmW7vxS>))-0`7;u$e}996r0rBLP&qL^gkWiw?+W$rH1i_~^OL)ahB8ZLX}09fTOb zz1nEE-jB#FWP4uEhQ+ZQxw`YBK(R%1Uv(a}@Ndt8;WTNTCv4Hwv@d0; z?*&i|u$v~(=sIj@c|?MRJa0xiD(ZhO7X#~FB@ z*RCO-K5;uO2YHJvQrXP?!j@YbIZ=ldlXQLTMq~`ywKbxH#E0=_@Bx9?Tx1U9TtMfh z4*ReN6dAnt^Snf4)oWQkCoWR(m|xOq4f(n=$+U|U#jF#O28@o9s*IACM5Pc+GpJA7tH`0muLa{(@&oYhn~eYtnliMG4Kt znMt_&spCu67Q5V^QpBjH9Ogoi2U{tU zXMJ&D&#D5dp?E|-7hCqIMZOn^3?^Li3`l3uN;DHOU%V4Uqa!Q16)BnafVUt$6M@Am zm^={#TI;DGL?nchTuHse_75gfIQDoV3PqC?LhYve=ou-Q+yx8@RypE?IX|=$gXWT zCAkV(LHf@RD797~@Izc|#pRgwq+Kg+3{{k`)xaX2P_OtW@8bOZSNsS*F^iVl$ZL-5Zh zUXmGnk)K+-DUXqH)xEwkr_r!;ESrz~Up_^l6`Kw~yN}ggFy#&8>K)(#oF>8BhzQ!D zkh*<22Y;#$VxhTbhY}MD+b^AhPykXh3YeS^ z!GZc>nm|LjoF{|nm|z!zgA|#9h{9dlfd-9B0_pSXr!GiQog2jM72XqGP*r%>h|+h) ze8d03@*!$oF;EC|?ro9q%mnRE0h*@rXR6>|l{R}@!*HLx2g%~7uu=rdgs|jjeE)AW zdNFk}4q&7BnPlD_)tK1oJ5QW;6JAcI^7h5uE!+yG03n^_ zH1IKU#90*7Jv!&b37fG_R58o`CgJ))YP(~nM$W{3>zZ6kYxJe72Hlruej=l$amSMp zzqRq5n(pU4JfJw!Y-!R?18M_5-FzPKGSs=Yyoau@l`@)ot87eqCJg3>F5~NolwyW! z;~PMBJstLAjqb#eY*0nXsgO!%|6T1`eNJ$#65pc6;_+8p?5yBb6oP-3KG(-e&K|&F z(*{vB%Vg}eYl zH$vaA(G-Aoz2Zv^-i0n3b64(+L!&pOAp5p9pJC6eas5FUy4GDqP9DU{H-jMAowp%V z4rH(J86$L6m!3Mejd1OJb*J(2F%cpTFZ^bpvb$$}_p7o!ZPQ`g7ZyT(jQUT{7%A`7 z!|~8|(T`MtN?#9NAurpcw5UMgFW ze8{MAgwXa4VAW2i(ZNOPM**ub(x0!I1s8uxH4hdqnk#m!XKoIK&bUw1v0IMv4?GHYPb!r1m`kqH5wOgLl6EPcu_rD3g0e$@8~H%>&q@ z&V@Ta*jijsXBdv)G~`BOhu(V@C*-}{C=^K3N5%uwJ2vL`31|%rcUtN>$Z!lFLVcFW zV~bv@`hhp2&*VO}`chi(ni{_zHllzNW zbPWon=P2oW{?Zq`iD&Y!qM35Y74)?{Y1$a_5@VG!inJS4cOqiF>j?jxAc-o5Xy3>g zGzFt08)>aiM3CQ}BGi?PLU8T_`8+fdXI}t$&HDBZ5qW1l@JEPr)>49zqw_gTYzoyC z#A)SJMUz$pdobLS9+!Y}J2hoAI3dB+f(CfwPz3QL|1S01VP7uRE^@v7^LR{<9T6>>ad#_wf)4VgQ&z`Y@u`&0V)(#5FSn+WjfvXrx>}|<@ zzH~b$L<%=px*g3YC|dqvLIuO)Hh90KPQ@ma1P?E;Q|(Eq+yHl;4U6R#xOAP46is>@ zR}u;KfjqW!M3V1Db316~J!5yZ+yXJ3LE1n~%yvn=xL|*(GMAzHFYru)9fmy^Hn3Tq zxBQF`erX&{@6PomSFH5Da>`GBNuYqEM;*`p>41b8_Wt>b6h#1IVl<-~FkeGp;^8R9 zcL)TCoiuMA%vw%JxuN11@V_@K1R9w5nvD?XGp{(ZPet|ocAAA|JY?6r9XW<^iqJXak2)q=*y6<=5!8Xa5N&dY(OOVA|4M(59#c~aH2zVi5_S)nmGqBiZm_b5fP z->s1^QPFj*voIg%^5uH|QKe>SyID@YZ3qpW%?{xAOF!0i**ovp^Nw$|y8HP4RS)Mk zzumuTTEK@P1J1;c-jfe3y@F83-p`@~D3$U*UudH&hlKI$|I}ao-lr_I!;4ADRexw* zBIR^VhK>$B1ZX3})|7d0@A+ene74*+U`M0J|EXF_6#EnMLAGDE_H0@#M3LEo6OHIT%L%~0M2*`jkA_EPcZaH7-VVf4VOYPpVY zEg8(Ryw>;Rd(b4n zq4OINZc00leKUu@r>vDGO)r+OSj>NOkp+>2x3DfSyq31Z;Fo6jh6B(;oA-gfGHau~ zSML|H9(W0hKiop%1rBGca&gJUjo;Fn^hjUJ(T78{ulfTq4FlqcJ)QGjs~7E&_&;^-lHkAg?`bHX5aGjUbxN@rGjaeO+Iwdz)$69V1F9Tbk3s;Im>v*7dr zu|b;a!%f;P?-21CUju?mD4)l#*(&9pwvBpHBVv*v?b__o_RqG;0`7I+FlR{cw=T1v)UF`|`&$P?L>)#V3V|fI9$W>sAvu zK)f_;M{R%;9!gfx)C=#E7v@)wtb_X2HDeX+;ITl~=Y)b;kG(}G2!IW8`LZU<1`S#>Y zs6FS&EvRtWH1}Z8G0v^xMoW|gn6Uyv5lH`+OsX(g=_06NxhnV996>tsK+v<|n9&f1 z0-}Bfr#IxTi40zJ^}iF1gLRjR?Z(zeX~Wx;O*;tO{RkE(^V zlH5ko2&0*r6Q`UMYZj~n&*NRCgO=EMG7W-ec~i4JIDo&+R{QUskfzm+>bn)3E6~^1 z-sMBU-P8Cu_g@hM^edD+7B%&YzYM?50$%XPL|_1`o;bn3{%3R@-TjLb^Dy~Og8X>} z@Oc50tQ|b0!}buOGi1JVOa}EV&&;WWZ^~iSa5$cg&#NEFOGUvfdsRfr zu3u-|hA9qJn_-iM1*rii8J<0mI0bz(HsP9W=RMSG&&qrOK5w z>o}xeG4K!4$oGtHsEvI`Hp4(zq!qXSf{UIL-r|U2{s}W>Jj;p$%9%SMA)joBKNOM3pW(%kiG_IyUrqm1?IjATw(~i!v*Z5EtWHqq?Z_OcM&pObYv%g_QG(=? zuor}W3?Ebjt@egu(`;f5M5B2OU||FI-h{xBgxI? zi7=odIFw8JXItMlOleuwG%kjFi*#Ysgm}O#R5=%y4a3}U)0nq_AAn*1@bJiwkL58D zRa!1wsVtp9wu;7df2g(R-6I%Tw^3NtKxeCdPBj?X%w+|-au+fR{{>uFJ0?~Q-cX1S zFIiZPtq5%nm@jsQ1NIxnbr7jWXWMv4MhDKcgygbOi}CKk2njy1m)JggIkM1jg7-MCllmA#mi7& zrn)jGOp|h6}^fQEaNFh0G`L;#j9YVDs$rc zEpjyXabOB{7f9VTPn8!Yk~}y1g$Rj7Yt;^uO)FbcPe9fDn}S)~`w~cyZ_^YtpO7ui zp|_*zH-64b5oak3)`mVQJ8+B)0s6#0KM*Xw=UF{FlqwKJsg3t}w`BPIV}YRBKo7Qn z<@Iaj5TU{e_y-x{?dDua3t44KH=gApTupwe?t?E-*yQlJ5n#s~0*U+xN{bQNPS--K zFs!N}WK#6c*v%DHV8i2=JwY`L5fzcjbp+H)AOQ)DeOb@dq(8l6)0*-J@kp)1LB$kd zi##;1U7w zW7k=y#TYW&MI4|rLP=3A zOo5#THvog5-???hiX1qwuw*g{O14=mLE9_bRW|Yd?^x3uqQO2I_xevo#!vxD|5@Xb z(V8~@ZRMh|yv|LwEx#nNq%wh%GkHcdN7-6Fa6!lvi83ED#a?;zL9dN)h7>qMt2v35 z#6Bv7X=r;i-jagj5R=&3hJB?2pBDS@?sHde85nx=eDc7CX>|%RtorO zedU&ZeW*t?P6|SpvE7;|SJzgz&F%dWv%&`(K@W(V-i5pD{%sagv+kVY@fJS|*!`V( z<-BVfO<;HF?}+`PMDX{lwcp;DJE3;4)?ORf=fx7<-bn0t-(nQ=_)qrVi$)B2)hnsv zQX@;Y%3sY-{0OCTwo!J0mENVt_%C%w$5Dc!_`tNy$ybk?H@karXU{e)cUv7VWJs*Y z(t|2WgADdu_fG-`|F)+6X=V9|Hi+T|S52I#G_JrT`QD-UoqCsc1+K%*PS6!M!>9dq8nWL^tYw-q2qBMGAe4ri6Q5FB~|7ij2 zxfp@9q7^Fm2^ZGaoaO~~ANFa(x62pS<&aL_>@qKWHXP}MSZ~ka%aWap8&%f0H^*Q zgLxCewWO)YQ1qgC3MtWU%7Y3pw<8EA{FEzfsIv>|lyfj~M+KvKj5>a$4yL@LrWl<- zi^hy>7P1-=5LF46+VztM&M@tM(Q~|W(dI>8c3jnDD*O8`A6PVsZ`*f*D1}!5Kp@;X zt>x#Uixs}xO?>HW!Y@4+{cv8jmx2z2Aejox%e1&UB!I7q!W4H#VCSK|&WQq59{nu; zOmup1sj?J1p_VC-ncP3R*}$EXK_eQIYE&?WpktfRyn7yIM>Ngx&1KHqEwn;S@aBDo zEjO}Nx`w}18%C}`In&0{W&opL6fA?6l@wTUv8^yb`DWoje}xIcD*iNfzc%}grz=6A zkQ4e#GH&g`c%ur#FcD-6r&wr~@ks0_mHNaD@_HR;2oirMbZ*a0bcOU5gpI;K84x>+ zB6GF$oS67~(4m5y^1>+o#T(0Z+lZjS?aRi9gF&{wWA{Rm=yP?75UvVj-PVPD;|IES z^kjmBPi4ukcy&sam#ao}sO5V%4Z+2VuaLRTquvF2Qf)dme2x<$ZXyo_0H$U8sKGvq zD#(z%#Y>lo{}Vo}d&tfoI^!tqRM3i2t9jksc#^J}fbKL8^r?TqEtY1@%i1vkq7xHY ztkiMQ8uJh8SbFLZ@B|qY93YCkzyNdPR&&W}LJF`E6(#7OqkUQ3bMTIYKjUCk7Dv)n zh)6B^ckFGgIb!jR+9&Y1mgsLCFqBuIA1L~aOB9UDB>EZKX499V0qHLposVJ)yjrJb zR_c^aXgVJFGI&$=!Nix3_BBI2tXq7fD{mPUQAMRQS;vNhw(%*$WE*9F79Ov0Hz2JL zzEJwte`wj*>-o;=&|fE6DZ{LeXUu*m{|+0U*<1=y{HnXl%*uK`jS-j}eFN2HZeotb;?SHisZvSl#LN0&O|Nj~YUDu}a z(3!i76}F5Q#snym1$}3Tul(pE!L~G;HBQsv-*@^s8i6|)4nT&}cqi0Aw5J*emXW^r zuqz{D`&EIx0ng^riLz|=0bGP9%KP#nQJSG9Ig5JSd901Ed29F&f8MVdyps?|H^?8d z*t2W))E4V+x`0Vo)sN|C$+tC~6y z2=Qi8%JPJXaBI_1Z7J2KVg+J%YWb|o!y&F z2&|lLeTsveW?rSu6`-#e3fBLvguGXA6zTf0xIpUjr?c@Z$QxWgx5En{CI;6u-&zWr z5)RD4IbLj@iay3S5^Sy_a0kWIGGc*^Ux=?SjfyC3X`*~6(gd)S7LfLcyyES-;A9E46`Tj&?RmU!b+OUNIs#`T@-_L?xs;WGdFpEAcC_1@50;z855f^hxwu z!M1x9V4ZNzT+m&3qlOb-ZRKONyb@m*I18Mcb#LZz^J4c!>{+jUFr}#dhH%8&r(Xzk zBsR8lHNHN)^fO_#4tbJSzeV;q#6p97+;1GMe4M^By-vcMRruHgF@-Jax$?e1gu&%+ z$PvnDeMUvK9gQ=uc2kz=e5CDgWOV%iY$9GPiEedMmY)7 zRd8w6!Z*jZTUmUuJFg;!Sc<6n`Y!w{GNNRNNWqltTV{w4*`w&B&|9nx8QmsAH9V!| z@)b0AH`itTE>48zc+9ARRklwo0V%k3Z)9FVwy4!b2M>XaKGFLDwc_=#;@13as#FB#F!AXe}7YDGCY-W2{71r^qLU4WkhGd77{MUBk@OCzjqWM@!}=}=r5#>EZH zbd1~bpkkejQHu(;$T|EuQzS57VKPIFDnrm*BkO6Ms7V}V-&D?-Ix`feou_j{ENM!a zh{ij4NBGw#l*5l=+E$Hunqp*yw%njO@gQ+nN$dxiJa~Ke7A6=b6aD7>y!`PI+)+$W z)KKHjbJ|WW-iM#Mwk|5h<$$;vq&j2$;f4Ap4nlnwT|p#<-)SC9`@rF}Otubc0dV7K zPzX#;YsqV{-rtEp8Il-RNc)wv;AuNUm~A3Ofm-O9?!ID_6xfJk5X->;gG6H|J`arjx zdPMb^dE&8l?e$LZ+#A%C7r^`A=(B9;@wwN?IjL8CWuA)9;F!IgLnd*tc$$t$xi3>! z9xDQ5q2S0Bypea>_~O<3-z`y*Dprne+$BT0 zx~f=5+*+FZgNcKo%bh4eSygmVuRTm;dtUJ-C>rTYV84};wSd&xFY$@5XIsC2^h`Nj ziO^7b;M(o~!>3!S#q8l{^P^waWOE1C^8pkf|6Q2f2l-3L&-4QdHgRP9V*XLu9XZ~b z0MPr8AJx&ODow(EfB9^KZ0-wqu~enw@j0+5dGHONSVSc+hXYLCeyt& zU^9FfT@2QAc`l+GZgjchZS~&i!a_L{Ieh!j(r>E9UtKy0W}~Zu)mcUAz2E`T8a=u9 z_WOYm5Md?12*_KpfRwC#8Rgq{rUG`R%OlqnpSL5S70LhTd1;#OKzC8u9fMmg#u!-| z%ilGK8)*R^L`~pbW9boqE5pgO`RC~Wj4QEB6H>h@!g zB0F%VvZM@d-z%fu_XYl-WIUx$t!>Pp{N*c`+U<7;@hI=v=|9{ofYU)|Lmm^pRC$I! znzDYQz_L20A;aF#MZ%MuhgC=)zX5%JYwSO6Vi4k&C}8~Vs(z9fkmia$tq|-`{(kkk zAXpmIph65#2zIn7xs{Z&az8rqNXHJxDJ1=9q&|Bb&Qz$!*(+pMWYG}7|fh-d`|mafomydMx<(>0Qe;7 zCKEUuNceI81ttn!ma73k7WG#u1={iBVuAniL$&l)|2Tr%-1R99d{%y(C&GD_*+65q zb)8E4P>4ZC-3lQ6#GZuI-^1h1UQY%&)cmj}2MA3^$)T?0f79tDG<7c`=p{_vsz2Yf zNi|J=z?Q!gS2nXaF}m1k9skymc6Hdd3}l)V6-au zzSBWpGh+?t(|@zc1uYhi{b&Ah3G$iN;6%XaUE|scXlD+y!0M=B<*$Gr$vzrJqr*nq z*385+sh3^LerG(06et_klDFE%pN9eYdWmn3=KKaVE?C*#jLdry1!j%HG3Z#mP{KDY<)hiz$Fxd9w!9REW6BF+u)kX|#iop;99C&O-~^=d@CF%n zc@`HWq&8n8y`y-n#sq*;Ok_@yz%DqctrNKYuPciD&|{(*vJ@!p@A)96(&e*w9#J+} zWN?yH>(H>GisqA*Oh^A<2`Hae5U3&?@px%79w$0>)%6nX(jzRVJZ?_bY&%jp89_Mm zGWNLO6cO|%cp0Bcj|bcx=4!YIdS|z+SVc@(Ky*sOQo2@WQQ(`6aVHejFpBgTNiK(% zCO(EG`hN5Lw&cb=x#&8X^Qf}nkz^sQupZ$cU)Tx3pXwVqKk^bPV|4bH(1CAx>g^H2 zA|-{aV&M=0z#*C1!s)(jj&+lV(-xab&0USok4_X3lpUF%DtL^ghVZ|(ZfYa1BJ&yl z%eRPqNq^Di!z@ zjj|Te>0pZc z)dgFfOFibQ&^(-ff6Vu1wXx!b8Yy>8bY*ZsktVQj1mU-15;IPnI-?&N_p>up41ndh zo|okP#0&>kAkcxzc&FI%pitX|>e`x#0MYTQ&lhZZq?el+cek#Dy?eS9F#|wsKFk5Y z<}P9vt6#+-W%}AvZ1{JUOwKaI;?G_alH`p>e@)3rCd~2PWC$p7xdHaX)NdJ4#Jigg ze*Qga8dKVm*W59tAqJ(nBa7#38#89KufnNPcnEbX0XIR>hMufECUqPfLFkBaE`$_>qN#@=rj8Ir$9opS@RN zK)NKe=pvv=VET_w?2^j6IvN-}uY?HibZkVH+%@PYq-d;%PIO?O`K{ zh&FGTy2SvhM|`D~NTtM2?&1BT7mpacTv)1E*Gw2}W;%6##94PB2yVfoQ!Vfm_#Hiw z-$taAI+s6uBf%l(^V-MJPx|YqlYHUK+uV^X1+y(-HY-KOvd~}Gy$Y0rqba7#;}Hy} zYZb)_SS1}y=gA^60li;Eu>Y+*_i)82@Sro?i zU)6HheVLHa0r+$ip598|kBmwR*T+(PPiJXTDkzCjg3IMG^xMB!f-*JMKuCXRW}Faq zP@g7!RC?TCWq*E4M--Aw?w@Yg7Sa+-75>(Gc(g#Y2L zPs(Mp^1v3HG(}6^A)G_L6Yfv{#ici@@E9p;qJ;_=|rwI}i0H zV1?de^k!+io@&Fx>Ue=aBRU=&_4hLt$3W&BI)QiF{h0-cDRArm8^0fOG69>9T~`H@^-rW0K>zf>wf z-U0+B*jG5u^=SZ6&UYE^u}w*<6FA}45X;Mwds3l!%pf{uMsJH;)ZaihWxtMFBSKa0 zVTzDZ7_6!(8FuJ;7hlKl?69l9T$q{7*6%LhKe#NzZAXLxszc7E{JMRnX2A!4AjS$h zx5yvZp0+s9(SD7J)Chh2fy*+Omf1E^KscR4$ZvCiLI8O6uRAqS?#!z`S|=KvJRqHA zA4_aW&n`WsWN~)l9(Yyg;MNJRC(<9@Ay%RQ{{*d_n}9(xL%(Qggc}knF^QUg=qBxS zW5%bqB>f~G*zU}Iu_xer!ZKX+DpA@8)_SZSPIbNNmK;WX#MtEeOS@eZ@)YNJl(R{0 z?5VU7yS_!Hg!FvP@P~1$AFVIyific2tz@^h8+z`Z@h6{0Q@ax)=RO&7aELLndx)Sa z5{I-cU8ixl=do_YN8Cz3z!fpXI?9#RHB0!I#e!lR0~tvD!aKEm4DZH!cdqXqZ)EXEylF4MvvgB89U7*Pppt-dBJnm6OfZ6+t{ z@H2fuvJu>e>(p;EA`&V>OOZ@yJ{W(|#P|jVen_<-a=Lx5YtgEU(1ajtH;@75>pi&g za*6bSGGpQ`_<&MPPHdxm11O-xqKRo96-vpXJ!Wg*g;Z7QA%Xtjr;u_QFM6QhfM$qE z@Oj?@Dd;0VHte*+nWj(GJ^+i$QBl4Ti27hLc#wZDoAj&F+0djLs?I+JNM= z4YJuL!w!XnX61X|>Ws{DDVbjVD`#s{cN%_t;(&!stFkF&NU%0>Leq@K{Yrv2o%vpm za9fo9DQb6$*=d48u@Ma9P`MPUeCQ&F3%P1)*X)1d(n!^LC9`MDu?~Z}PsH`Cq?kj; ze^02h_sELDq?J8~XCmW9?8j*_f$B-8v|TgHLJDI!zHUi%X<93U>vm^MO0B4`CF?@8 zUDGh4g^|_;JnIjh7V4Aymm)<9FCI9nrOYB{3yddjv;GOy) z|FDvon`pxFZ7}T!JsAOemrA=sStougO|vsgW8Y2Ag@d3MKU*3r0-vfgqXCPtMKMf4 z;3>CG#kO8O44=x7_P97hOe+l8G#s^N=ZxHf*=$LfT{cQqH=64!KXq9mt_`ARD6TLN zfBEy|@#7H7mdacY6U{(HWM>pOP6*H3%-6Fn>`D-MyIIJwSc!?ATA4SMLW9p+1Sx(? z>%FmziPPCac-s|oiX^^o3=_QI&K5(vv=3#ibW#RYcIG4fwG;!2IE;)gK|N%+=aQRN zehI+oraXqKzvlV6CAhUHkg&t~gt~3TH|{RLiS>3+^&kX?4;d? zU{n61=r}_^u_g1Cnzxc!aOH0Fttc{4XESa$REL%!^{UwTCJZ+|B*(;l8N7X@ID>%>AiC>KC~p>m}7x@ za#@vL+J)ibjrX8yxPaf=v7V$zD~TY-ex{{Ud%p~met?1hK`pa;^RR{Pp-Od$-xptr z{q}(m_f`%?T+A!%aJ(mX@Y*K$9PVgDE=VD93m%w=S-8gruI1l|8(mU4m9dV!c1`}t zG|>gF-+-N68B+Tu3FBC_3YPn>iVMux)vMLQnECzl+)lwnEqVKBpg<~NCPvVk*C)UR z5G6de+sDMqgIlLNhDP_9%8&I=8pshA{evlDkPaBVP1?8^6qOQCuO4CZgH(dlwer22ixFQo1T0I?}; z#@4aBB5&i5zm(n4-r-pA*{xwHy>!kh&@cMMl*g!hNE5+(z zl@wnM3t88{pV5jwa-DqpC=rkOpl*;zUH*KKKEkRWFS-jQel-%3Zg|pT_`3UP%A-JJ z@R%6n7C#&cgsjUhj43O=IYO{5Of30&bY%1bCvInx_(U__sMN#SM6>g@FWcs!lo&*c zu1=><%&$c7-BpEiBuMKdZC=?SZ+;KLl;TiS#T;Qnn6yXu<*udtRX;a?RRzG_FCk)% zu6SMjK1L<1`u-X{R&!6?V#%R^Hix;t3mUh6uQUw*m&B$vh8rdKENaD?s-peVb89l=^rI_SDuQ3Rr^;Zl>_hv4|)| zW25BXd9Z07>2$BUhJMDy_Fv(Af^kj9avi@iL;M+F0ncLQqe&#_6#&IeBZ5dFSX?a+ zH93Tsw)LOdi0WLs>q0XFtjTj7&O)={(i8lsKBb|mDB8xuX14UuaSIv}>P++8(W|YX zG!ih{e7}<44`N^hxhH2a_VWpJtS^&guG1c8X=S)SD=|JOX)UR+A`klxJJ0V)$iYn# znsuWBxp@x_AMr@&y#7xMAcoA}bYAnu*uNXqrZlJy^^z%aR4Frm+?|?=glYsSl+fXw zQoD(kK_6De0tL>%rL+(N`5dBn@gJ4BA{73@WJP!gOl2t+@F@)US_*~~UE@ks<51s` zL+?%f35s(qXQnH49KmFN`d`)SjB(h&xi}0+<^&LGx6x)bZl!&ZkW`fn5Xwrb3hiJ7 zlT%XT#IiSB>zjL%W5Qfq-bm2eJ8*UqUayV`{?+g6SC~n7Z;R{F1blZ)ak)w611^l} zC&eM?6n0G14En*weWwplAOO~9mLF_qu@v9^HiJO8z203x3m#4QaTplffNLhd61Oa= zUOrr3+MLq$TdK<4Gb#&qFnII{mqos-Gm%Z5&9~cFllsg8j4|s%=~vCM%S1+YwGD(b7mYIsUzmfi14Z{`*Z8bcwDRXIl zdGr88!fzBx*499br0_UI zN>LA6hysh$TksgEiNq^2+QL&*ENr6a7HPKEMMV)mHVoxe5!DPU--F6=ug{pAJ={+2 zBY!dVXV1G#Czbocn>H6gQ%(^V;n~$MJbPR04W1M&u_ncPlbOk3v6rNXmxT1#6bUY7) zzVDIWD4*3*Z~Z6X;5E|_di&w&VVFFH{!( zkE>|xYsLRZWlhxLtyoUynd1w7Vs$N`j)Y(jEgiHq!+0@I|Ayu3+o8^43gB;LVJThI;W|tOSt$6CeRFcR3&%Xej@}5wUn)-85yXscKR8XQ zI+O+WrR;6=NoA^b@D%B;SB$9+G80`=6ly=RpM26 zywuXznXzeFMTB7yaIxc5B*|LVASfdgFt}ybQD>h0LhLn4>{e)-hOx<|zHYj0)9^|#%bbf2DvY9kQ`zV0 z&Z=Q?GMl)|Nxqi3uE?f?y1?6B6aj~icjI8eW>R$1crGBpb{QVv*J^Xd37XK`8wC`# zsaCyP5mBBElT!6#ccWo01HBts`wyRI99#yA zj$E)OALEXXHFIsJR-+q53Qv+R+G|{eOi<>0X zQ%an2B$gMI(`S`i>9Z7IIt6=uy68;;rGj@oDoMOJxidv_VWJS205rVeGfWWAKdEQK z+Ot?X_F0aQ1RWHqN?Eh(V>%2UIW7;JURxUFcJi{V+14wDSq*O*DOfzHe`JMEDr4lBd?Mddod>$`Ge)b^aX*3gmekffjjUi-Ri{TMiya1H7`Tq--Q zR4~DXu^9X36z)3|E!u3V{+0159JpRo;fVk|JQbV}<|VqX9A58z!nlAOs!1JZ7{^LL z><{>GvmHjda@$#9*x=&-7&3N-E+s&R1G$bPNt@k zs=Es9W#@tWWyJ!QoAgi`f~z6M&>v41ac!xvko1um8b`Q7VoGMi&V3g?{O?->`ZXT2T_g6g0lmUF05|&5hkn@^ z6R5fv=`w17Caxv9?{$39TymC`<1?*aN%NahVp8sv4~(D)euS$Ww1A6{{v3qfSoL~p z6#&Dwo=>HOv?Hq_W%x6D3JN{;Nc0b~UzQO?3LjsS>0sJi$nzc8pwZqf5!E5&i6#&> z_l2UX_Z`jwvA>EVCk}Z{d;7y*>kn(u3c)4oHBr--e0L^M?^1tEf#pg0l#M*IF{bEQ zL4_ESu?c6V1fb4X_+FLR?EkEwY!YE$<7)*W0oi-P!dElVsWUJyWCdsB*{51}R94 ztBd#i+E)i&{E{;L&7AEYn!jhCz@2mE^f&V6tE_jROH<&=h~c6ZOBa=Adk^!C_zz?w z{MO_9`!+}?%GKFkli)Tmdhy!NGBMfYS7s`xy*z3Nm7A<=Wa4j2uyz;0lnhO7CVyI7 zK_dr90C85g1r}aDMOM*|oVl!@*nxb7u*>Ac&E1I_D!~*|cvlt@!FFG-FN>veGOTlT zs%>mI+W1_1grptK$&OV@yWANp@F03R#jF+tA!+egS*kpw=SVJ~aG2M&-Z+T>2f(n| z)WmnBziKT4?npZ*_))o;`IzirOM5iQHj8s$*&ynsQ0p6z5O_L@3&6x{75VQ-q|?=< z|B{DO;$Sim-g~pd1C`b7?YnxOt`YpvS-+M@JIHlej;rVMfalBxvhgWoD#AOBe1vp# z{{2Y0!i+8CGlX_-0oz5rMy_r=kV>9Fw$m$?X>1YDoXImM1^jY2`?eD+h9U?O5D(AW zusn;&yovr*D2H`r1<77j0#(qGs#Qy?1CV7*rCgkZRi^uGQJA>g)p{yPiRft7vT`!8 zuY5zCFr|TByG?G@)H=M?AIucwIV*C5Dv@zH2Dv>fGEK3WvnBaMnIOXa) z%7+5^G=&%)+!$1lW1J2#!V!5y=OaR1d}om{VA1o1?R@@w5HHRn53z=G2CC72o4f)1 zlUKG~w(SVYQ8uP52ZxcC82V*OTpe)#xCVpDgBC6PVMU)SEZdL9^A0AtXA?=~U()yG zgvA)_6i#r;H>vg;!Gs3@$I^0@mVioBXTXUK3}E0*!|MurS5FdU1;uWmAtr!iubEN_ zZ0H@k&BnM^(%%%Te$M@i)W*5x@mU?DsqvThM81nlt43NnU34AX$BKc$=T}ckTA8>h zr+Ad2@TW9JuvpjWTU{G)Lx6R>n+<2H7)Xu1F!ID>NANS-X`!QCB1|n`2@!Bl7Bcj- z;~PI0R%j!@VbVVn7{;`#?6{SOVoG*Nx86uvwhEbu(2j%N4HhT8 zz9UE%dwlh`Xw98K)6)0fAM_DorRiY`cmlGO?ukRLI*y~HIGTkQ#E6jdGSq7Neq9Ih zh66PJd0)tK!`vb;DEk+ovN{g0rUqOVqIt919yeNQC+c_B0UaR@&XyiaTo>O(X<8nN z|6xV-*2EYQC-dInqpqR-@3RQ;8aJTC zmABY_SX5PO%7)*+q;-B$?-`}nReOr>9ItS(5`m*P1HlU)PZHfGLSBx`M%gJ4F{i6n z^@|;$z8C(dg$1gBw~^1sxQYK#xqvOHLY_DTANi!GC{lr@iW;KIt_%~{{9QPlyAty9 z8s4?HRAD>DMwuRV{eNd+WZ%^a*HiRC6hta!Bq4dkV? z%A+@`Hx$PcSz@~mYwPogpmV38ZBO~L()+O>4Pm+P@J6$Y&4VR5d3;69RcYU&V4|8v zss)gArzy_<{aSl}@H>^pGw1&B!eHINUu$vEXdy+b%UgzfMz&!L%)uat@d0x5!4@LG zv{r`UToZ*^5DERtkWGUpAz?)-{vOfJ7Uc-JJv8wk(QkXB5}`ZX_RZmp9h4$6X^%CmXID zq2lvheHgwi$fyTVWzrlXo3~EWvl@@mn?}Dk@Ikd5g%_g34G>o&4pJR9=T!2>r42~M z*A+M^ksTwy>U>()X>2?Cm9xTp*QOKHxxd2# z@m_UaNOX8JuCA{GSNdFWer{9bXd@Kl9nmGEF<%1iuxfi>XHC1+Tu_$x*Ixwxw#eHC zbiXXJ83W(3vy%2J#LH_KfzsPxp?4vpE^cNOcXV=_NEsrA^%q z{k0nq2c0W6id(@7J2CoWM@FA>f8nY|;bQmOk^`kZL$7GABf{E#XxX0Pq~@q~D{R13 zW#ZqbkxwHXp27#uwhQ0tu7?+K$XM4)sReVtqA@FLTOsGL`|iEyt(NZc9*%&$CjxSX zvx{k+Hcp=dIUI&)DmYyFE1{uus^42LCuaT4#==ppI^oKnN!=;+F zfe+1SV_Zgm-P=Xzjkb!=Dx4I+bZ3gm#!I?^mQvs@L(ja^wAu7`dyj0 z&p&C9AedK8K4wKGlf5+rvG5 zm`D8iyUk#5p*%$U(8y6Bpfe%c_{GY*4Vu=09*lOTbFHi8C_mO`pHVc3CDa2q4zHls z-rBxP54D_q!$kXZbYgZkTelTvN1N4n3xZxY?OcNAro_#Vu6StkSZ1iMd=$b4FPpgY zyW2V0b*|0(ntTt7H(v8FPUx+6yU<#yX{v$rYR4tG+L3S(wrl!#UcIUImw0}{?GwWB zEAyMoitpChrbWuE#*pW$n3Wc&>zZFav8VB_+7`y}uKpE^Y(8j*-LT#DN3UA7?=>X9 zQEk-tge48~1Zc4)h8JW~o0nL}A^6aElvdzQ=+kB78U3jeT)SC@EP^O_k_zHGCS9!+_!U_4Y^HmJ4T%bQ( zSw}I!j4`u3e#sN(v_YB19)*E`*XBd6wIB=buR6lVZ44#$H{a}s#2LL1wkx6H6&hC! z+mX=HlmOkapZ0zfw|I@KiBMYF4z|qaya{!%+>;fZ@XW_xatE4FU-%+Hw!Vy$!bB_Q zclz`V-09e--IJ|N8gizKVG$mLtah!#N<@q)qjYDJ>ZUztNrIdCG*_l}6Q)DSu{w-s z!rQ_(HTFzh(&w6qE`rwmjj^XtspUQ^5kZuWiiY)ZK{J1iBfg&)l$Sw?*k>`m^?w2m z>R6?nSjN~9s%yZjbMMW_?o;}0+^cyibU9F3GgR)m$=208l3vFuP)Ha*$i6T z{?=U=cwmQ+rm%SKBvi?X;!O(2TZ=>}9a%C=H4`+A&E1ZGVq(ZjZ+1G-+yzrrOfzrs zn*Nm8R5W<9*YKuZU0`_lw4kD*U$w%%f^lh)w-Kn;rXZL7L<3a2p*D@6?u7JJPqu+E z-!Whe6 zR3}K~i*h^&y_g@;_43QAetqlrDqT_Kpb?PHfgzqyksltaH7dixqBw_$_$)u+tvuB{ zO`g)V-sLw?+0)mRbnDU(?r6C)3S!9w z*%$;Wc6FNxdF`C{Br55*xQIc`~%*d!6h>F=CGJ1K`Z#3ssP$=fDH69_?wdmJPt@aG+ zi%KsRkBH4_GG|m7KWD?0*YiG}q}D%eG?yLmXcCdVFJ{|{jMd4wa!tK!3}~NzU}XLp zE90>~BO9y3qr#gwW}iP?-`JU7j1p}`M(QD`5RP`l?;P$LG#ORR!ur;x+O7MTlxxmy zcJM)f8Dh;?Tcyn%z8u6u77#hUfZ9ACh3i|tCtN!m^_>NY+=V#8myF(FNHsUxGblfS zyK0~YjIXm4Ju?0F-6YhDHI9>2zz!96Qo4E5mk&0}U+kYOf;iSLyI zJ6onN*@B6}y_?EcUu#uwS!iW`X+ay^Q9|nuO9QzOZB*BQ{&9=JpmiGp-sf>Y6+EC%Dmv4-q`3f*^@h8KUFN*UPUBvmCsFb zso&q$EmJ1EExr((*1Ni*0z6%4m)jUWMjNrqS0HqWt-_h{eyerTfm{$5w)Ft*7C0Jb3&f%HSTwVE003MCNbQ{ zlCs=CMLGJASxj6%&rW2z`Ivo3#C-UEM-`Et$i@o_v$ZFST!{elfr5pVC#`D;X5IXF zl~s7-r?H?zoBW1wY9ej7z6YekQZo*f&JLO7-wwA@I#s%cQ>#ASHMNohEcZvtj}pg1 z7!H~K>>J%WRt1%%H{1DWAWa<+v;JfKI!+ZYM&ijnnk_`f zigt=yj+?Y^r^O}>nroOs!L!+G*~PsF3yNLdPsQzUR}ggOSr#PaEDqRtPa7&gcq{xv zzNvzn zpR*GOW&O8HWBPEY9T-I``nibsP8*Ka-kC8zd~8}`*tfQ71_%bTl}jBm@~isbb1lBZ z-(51o+^(w{p}3k#SdL=DNLPo%vVY;{lxzv=tq*jyx5a()oRcVz5rfQB1Dr?nJI*}e86Ftk!%CnrFHQM z)VZq`+V4epd#iqa@2mz+Fh!noWJ=F16DlOH#56(a-InM`w{F;s>EG8WccWK77g61S z-V61N;`4!VOchf7_=4A2Wf#sjB5UK|%M&*@=qab}xNEw-apIYrR^0If!_HM2ZZ}1! z&P+4U-&_AP^LG74yI!b%j(z}pU{zzo4)?a(ln#dLWicrS9BbRghc0EtA2&Dn98t!v zZH|>4d%W+_gc?UM*%*$EY}5^u>pfOQ6creb{Aia3&~Tf%Rra27wUd$630r?DW{Rh> z3BY|Wji z8wktz{Be%v2#zex4W!5HbrcC5N$HGlMy|gRJ#q^o&d9oVC()YY)cAm(I*b)<9s z5f}M%=-6H*shRCcv9|y*asEVzN~W?WSDNUMbNTDb>Vq=#V?EyAZYIg=3}LwTs%5>^ zbl}Q$A;E30w2~oZwRlX++jEwV5avv5oouV0>azGnp{dJggr2%)0qaE}=sA4}agF*W zW+tdhzVC5~(bSma2EAYtx8d_do8U}Vp?|Rrv1bQ2AIdjViW7>WV>HJIob+B{k)w-I zUAs36pZ`O{&!n$WzpSg*{zFOFsFdnEke@94g}w`Y_(h!G2Wyq0CZ%xlC~MwjfuH^b z8R&X0U_xqBe?%>F$qnL$pLnYG3cbIHjTlu6zOa;wsasN)XJGj;)<;*;dnRp4PrtL@ z3m!wgHVJL3-orBDY1fE2wk;$ za@%T$D3!9FXYN7GjsLiRV~U{4HoevL3Ob@<>ljQ-427*4{>_hnV1eIeX7;mitDvb5Se$UrLN88<)RT+tFy;?xaJxv>hh}O1)`f zF1{QtrOqr0h-aR|N3CWQ1eMUF6^g!fm^jD1g^gm^!+1FgpCY`S>6ojs^usOnL~O2V zwFeNU;tFyR!pLN=Z>2@vba?dD6_4sK!<@hV8x>yr%MkAo*p{%l2@kJ4T$zFXhesC1BdaQN9a(k!#upV$afA(hyVg zOtkc>qPbnQIJC7FkWg)Tf+Hl!;x_zCAk#@HT(Q*~L+Uff%$z^Y`pe48{~=Xr=NhXc z@j>_d+W?N;U!;?UnJGoSItrwiGF{}dB&5-gAWfU3P85cdtO9cR21&KN`+VlxQCj+3 zZUVC|@3jybikNl^1{wa7K2tW821&x0JMYdloXHYyA^h7YXP&7GENkz1N%f7(jV4g7 zyPX#SgrEsgmL#I^BK9$$Q8rUVf4&*MKbH34Hx2AfR36)5UKD+maESpWWmw4WPMIR{ z+_7{IYU0b^x&0BZoN0)1ta+y{ZZ8Ci0YmUe)ati_Zo2d;J1^Ls5YumSl@FCk+$Bi? zB$0j}(u=QmK5x7&S_$A7*!RNiXVdoH#k=t(EN)k&7qT2mCx2sIo;-lAFpt+H`r#zQ zy6#$;LB|6q5A(+I_cqpHbIhxKkz>>9-uwt?meIe=Z#h%|abrph-H$4;xTf#=jZoX$7b4%)^6F~{I__+$Q1Isw zZJ5#KcR$YZ-T2rp?aFEO?Xp<@9+j~IZN!$=hOcn$}A``|K`776z;Gz1<_i&{{xYln~avEuV#6(s9pa-suy`ElI^Xk-}=Lb z{N|dx_X(;8lW%^p_pX+Dh&4KWRiw7Z3BQYUMC=B~TzzG$<&ZjhpI^c1R#8=ll5V|u zxg7Vv4}1kdHX#-2vyEYw*RfJopl=SJyt)SR9kP(<#W*dlW*&$NHxQg7fgzU@;~i^GasQ7p@zjS6E

#52KS^KtVmo&O`58pi`T>f=&gqj!+k|To^afTi4lW_q&MP? z7AgtnZU3doFi`v__BpG~`G2zK%}=|UiFw8uqg7>KcJvio#`ru~qYhf2D>lfO0ZO3k z<5ynAcwI*$lu?i4?mLQE{NKJ+=%ezw?i6X9+f+t%?*Dx*32%xf{`N%y^%Vc`lnwB_ zEq3_pZ0FGHbPp0_3MsjjVP!m#GaHdkimRrT4s__lYkDgkL^mTjbB4LHo2DIWLs@+6 z+V$fp^Ke7gI|$k5*FzBVqo?C=oJu;3F|lijbugeAko2XxVLCk)Wo|c^_k|sY`kV$z zKNRQ$?Huh&=1F1I2c4qkDTXt93nqmpCbzca#1x4m1-j&at4R=z;Wi!fVbXlAHTO<8 z_6%?GBem;DsAO#t{xC8B{QV3VtESy7k@EHL*@(SiFtxf7kFjS_3XLCu3_(@;&&F@@An#J!hZ&9eIB^@s z%IbBoW+Zo}lUW>d>G}7QGdO|v4va=9+CL za15T`7aVNr`;lTzrj!hS4t7-}=~5d}*Sy$}DEIQ^L++L32vw`W)=*0;&1JSfgavmG z>YGNhi=f&-yJoaph7r2-bn6kY1oOkA`=%3o;;`*}X@T)K<8t1{W+m`#HhoRaH>+}a z_qgK%(O>FkKNkzbjIyk8rJV%FP{t`$u6<1?66}M=ia!a!&lRt>_xo^!_U9@z{4rhp zyurMXU~SX2MtKJJVT%0T*gycMsJH+WpFWV$4G~oSx12}y_Sv|^JRg6I5^idR<;Sv%hwwb zyZJ0A!ka$)T&}^hFFWys>GICMrRPR5?$I`LLzgEY#@nV?pJLK>-hID7jRSX?)lL*6 zy9$3!kZq3f>_a@S-{DR9S02?ff!7cBXlpAs(u{?YokF;`e{q=ECU7&@$vo;fDBF_X z-(D{wewR<>+lnE?cX%vTJRu5UIsbMcd>rad2OQcDtqQ|AJKm^KAkjGtJxlx9n5vD$ zGP$2=rrz;zjp%b0?^6Bf)jOQ9CAz$5%d|3`j4FBkmvn1|7MsCQW})$RTi4;O1j=*mcLJDMhlHaKbX~3Bg&aOg6sM zoXgQ9YC6T!R!WuBhQ`t%J*#f*x#Z3#`ZHp_m{zPW$@t^WmkM z+p4drxST1cLWh2(qhGd3vpJlrg7^4s;lM?V(1WB63%U~@`0%Wh5=iYieTQe6CqGs3^|8pK=0<#g z&Tm@&t*Nv_{{O|iru-?x7FcZP6yWkx&VUbQ@2C0h>}-2H&st{` zvqahFt`F}PQn0C``fEA+sPCv<_;45UMMfmQS;vcb?i0Io7oN^&7jzLlP5fLj!Nn(0 zDso8<>XV;zc3s*$=G>qCcI7b`+$qT9Fu?r7X6})i{T-`$(pUC-?$^@U^noa5**jex zRsYcIcO3rk3T6I9E2JK*snLkiP6af{-dcBs4cf{5b>a3wLRit-op_&>7>Y;inw`qD zF$99u2&48xI7MII%aRd;TR1xVa^*L4@Jc!7r9%Db5<|I}%9L|z>hGj6HM3l&j z__S?>JupcuQf=4}F{16T3iPU`!skE`6y(Xhy18e%e~dMF;l}R`6rbMPR_QLyUVrzS z(PMwCJo=T8ntqXC@2Ft0C7KGVFz|U}_M}5#!xa5ndvYP_!4C(Av=Z>E_=0LJd=j3x zpKQ-s+hZ=6*vU8M&up>A3Z+Z7k!#rVh?%t&nqvEjsB-P8mDK*<D21yR~Ia2 zDh*1TMzjk@l!r?p-je;8G!Lt$2gM{e7eqJC5Zp_MY!l^4hN<#rBd`NjatVANMxWt) zj`|cqlU=zooLmswQOcZe3k!?d7J@7c>{IRgJ0#2qncFi=ODMzP_(>-_YssX$xZ8}? zBtLH$&6h+!Dkfr~3SoPy*coZeKSuePBu;A&`Gu|k?rPp?c&xAs9MoDCym0C{@4R@Y zlzm$|@IImoW$od1cmEW$%<+bSREM7A>GEeIHsy5;Zg%f^tH+UW`{nQLEqFiBJBV%x zE+4~;V)bSB3pep5-3u?!KesHNZHVT3>?k*INjp_nQclJC+`qf52D!ZHh__DCda$93 z8ITKV-EY7DY?R!F6t((!nL!I$-bHot^P@Ys7OKXsb@97s1;FrGGMFcrb>vS+GwT4E z3Kr0frDdg(s!b!iGfidc|64q0SQXAe$=RBh1ukPHwvZf%zV7yssiZh!l5kY*HpVJo zu*{%L9{XrVmkG&dr6pFy`W0lreQDEXS&CMsRk+WM$O&G4Fe9pz=g!%m<_}Ic(u`Y< zhbGA@FGh{|)!7dHhf(>5zi+z)KC{nQ5bUJt9%dy`#378G&3aRA?qE@yUeAq1;`c){@)K~?m@UGNRFwdqP&$#;#}<=JxTU*P84nLmbAy8bx6 zBBn#lEHQK#x@zAxlAruN4a@KyJP?Pgj=;vwR_H2Os%|@01rtc=&NN(f*}wjbN0&{{ zK@en);#F63#7tlY$KA!doQGM@|LAa)t?VKadt<@GGC5lqA{=|q!iob!*_XDtl{JLD z?{5yr1P?DGjG1|>FU|t0(#r`g4B?}-#-`}9ooTvm3)UV`QVb24Ax+sAG%VV_A0{eH zFwg9m+v^)0UyH#gM-})Rg2>Fj>U??PgtlN~vQElAjgi6fXP;);YTJs~7f-P_YgOqc zMmAi32D0&~>1rS8GCuxPoHhuGP~IP#*QlGVYP|JkZADh@|8gBi_aLK_!{8tMrgh1; zi+0hO;o9FoG$%}Xvf}F|@e~xE?3dij)0_6~(eaj4|6G(wC5gc8V0Tl)|4oOTp4kij zKk(~2hkD6d%CJpor%+71ZNLLPdnD#58>ZPj2%k@Q*&Cp9y?3O% zG1ZhQ&Vt_je9Sd}vqui?P2yYgH9c@5Q z(1=<2aO}N@;1Q3Cr{H-3(&vV16iFv;+aGQu zkN>HC-tsm`ux1_}hY`0I&y}&I%z@tCRm;_Tl~4u2)OGiA;_O;;y^+Kdg$5A^myW}A zXz@cveBX4|6|)%I!+c2ikd+JVHt3Ham}FeOln+!OtET))h{(j>Oho9Wz2j?I^hn_NTu;tnY2` z2QW{?5;UEwVU?~7^!-0XeRWV<(f0KX?$A=8K!LWnyL*As;8wIq(c%<}2M8^c;>F$F z9f}60!QI`hxD(*Zd-J{d&1CLh$(=iyd-mCTt##J2Lsd9GFu6*X^p=qJrBRy{Xy4Ef zUtjvkM~NE1K5o}i=vq5EEs)s8XYjL;PZW#pcF#s>I&Y2%ZI(#MF_}Gg?vJ~R#wAA0 zD}D`EKx4?Gp{g(v%#UZ$-Q~<5z0~pQ+TnfilAJxtZyR~fy&R+O{&j9G7un216N+`0 z(!>H=@O-hxJ}Ltv^7tql$TYfpVKKze)t{REtxcy7Ih7iG==u+-Bi-jfT;E_PuTSvfF@jL ziF)7KYC_odMugXoSY2kzzsZ6#3;6m*G_()CtLkzaJ~YAu+7y|;546QDq_Nw^qi%H~ zS+B;a74!ub);Kw;pyGg5MG-eW?wk!T;$fqHJg;2sSJPFTibbEKhYe*fsYkyywna~P z6krF{Tr{yPtRfy>?cRw86eQ_7dHa{|i?RxCwVPwg&v+nDi8ph0|e8#VvA-$C!j!d~7 zkvir{V6&-Ai~3X8ZcUhXL^{~db2 zY#2ZLKjK8++Lop3H*WnoJh!bCn9Ql3)|(8C+q0NXYO-xf!tFXKu|oC?a_P$%qcsL%v)hA8J^k)WiavVtAWyBVx<` z!dskBkzqYYV*&wiNJWF_1ReOx-#UmFjeed`VY> z{o(gPdP7cky&#X{d83hNDMC#p>9Ar@8fWpG|sjk(i# zh;U8yU(sLP`1Uky_&Br1KqVgFicZGiQm&eF>}(6- zOE{VywXJ!~-g5eCFCuaV?sdg_@kT!fR<6$yl2O?`jXgC!HN3}&?){*i0T~%Q9dWY@ z_IZfo9m6=@j*k?ZtwUXHtf9_`j4D}C5rl)Q?BtX>oPB8GNM{buGJ9dG)UhuoL$ zZc~geP+tD&cxnk8TfNUlB8*=@-+%U=qyo3;>RWws%z)xoPB$BB_!P8sFWWEYQ)g_-_mTGl~n$RUWy!_>b_RFiiIb3RdH`r^oIl7c^SzP8nvg_4bcPIN?jDYUwyUVJRq|eG9zfYeiei2^PNx| ztC9^j7m~_Y7EWPFjn>lo1CQG0Se$y?CY^ML-_63!P59r4mYIQ#P<0ZWGNdSTu2a5(OqkTo4eI9m^!4vNW20WGH2}C2$i5237ogH3+ej>b{j@_=D>4HDf_35N^%Rwf1K_i>BJ8luLER1oBn)aZF_Yv6N`tuW|c*;y-h-mAV91dFpidRl;N z1j)R-wMITo;awXnQ@@ydN}D#)2DW=T(uvBxA1u-!YWM6_`gTyNU$vph`aDP zDDG#QFz%l}kG!o?TQHhzAln}n@LT#XebWoWsZBcg@6>+GURqedNjR4^X?Os-go?qw zrWK&NX0XNZHKmAaas?6_Eio$A3yQ`jvwoMLo~lJ#w5|~7*GO3mz-_CN`1~@cfU*@a z`F7V2#Z3yBn=Z)Ay?n<8Kk!pYE5VaN6!#|hjCHZvyNwGfbp4jIdl6gy8Zf`tED)ob z^_G3#)CqMrSz+=Z-ag9=T2DQ1RXB2N3bowp?`{s!g~ltyAjOHXXe zZ?FD*h!dzVEn2c80 zL%6!v;RXJ_=}=`6U#I8yzh}=wOzom!@bTct`<0}PEF%fpo6^gNrXe&NWhO1AZ#*ZxQ6c=>z z)zRs(SpO>}1gE^=oiXvsIqK=ck5{eHn59yEj(E@rdimzQkOjfs>!g#<9}d6$-JCc+ z8R32t`1$43Y1hOcA+T5%sMgAb6+o z_HIm%e9t9AIG0J($CtJ%W}v96=uoY`7E#v2^1|aF5>=O?BT$GwGs%k9zgPYrIhOy! zkk?e!fPF>ak>2h}m7&nejmo!0Dm8K8+0!4lUD=}eEMr>uvX0o7bfQ}Z8yY`N#>cdv z5>2C8*VkE(Xv8t@H;yw?GTBUMq+xvD1J~5GTj(MEt+*1$_zV&(4L~pbqb%t^o^^eb zDHDpRz|7Tep7VUA0WV2?VlnW`eDwH_NC*693Fmw{^P^pz@mJ%^=}@x$8%I)MjH82P zUqf?8g^J2YYlhUxQ~FTETQRO6l-0Uv7#S2*r>`N&WQ~=$Qm|T(K|Aq@wCx6Q!_E4* z-&E*uevGv~Gwig45%2o#X}E;u_jcOaIpwV_*D+QS3Du=3d3=qQ-@w9l;l9W7#WEvi zJ)D61)TdRpmBaM`zvLE-Hm;GN$LRu5(2-cr$k4g+sGuxiN*bnue17jyA#BwTjl<;; zn_f_~V*7S{g8qco{SMO$OQCI3wUc-xto?_A@47oGjB>dt*of+B{{=bVA~MX%oC=dv zTshm%#v^FFBJeu~sI>VWL&%%A4O(%}#nAMtAixe*)NvIu4xJfG$*nX9o9up}&Y8A@c zME1qpSxV|ypZ+5_vY_Z1Fu@>A&1f)f>51C-9%FQb2qR%cDgiWo?i|xFC2E>Z*ir?u z_}&PA`sjh&o+xD}w7v85Yz?ObO?b^V(XD8TNm@&0!b0`cCqqxYs#M{fXi7}zXS5%W z0v_}f>WIemV0^HaRm2zanu+hcQ-8$}o8=73v&Rs!J)(o~?}Uc6?yO$!n_Zhvw4jUl zzqj4Qz|l^tILjobVtWh6u3=Pgf7d_K-K=FzCsw=esn%9aa~f6aTkOgIQSp6ax07=J zU#s~;wi?D$1yDKgHgzr++oR+;m-y&)6)!P_OjC+ICc+61kcRArpCew`2W= zplOXf=1-(&J0ij4QSk!3;yveWbWrwd)8&^o4KH*cu@P+iPj4nObP#6ge`f9lABu&}eLF;P!7@LCU>W)LaG#uuc z|4rdB?|lE>;t{^NF%rA)`TQnSFu$Pm#x34g8s4Q4u@mf@#YO=?7E@f#+cZ@0MbLt; zt}Y5}dRi5H->Mo-e`qs?U+Ue(WA>mTEtPEOFw1lk@-pg88={-z4g-f2kk1q`u`Z)` zC!ss6v5HUlOAEQH*iB>$98hS~CyJ3Edf8 zthPPPDkF}PLn~j;(hPT?#wpNCz|l`%Y~lmO%5!)2a|aV*&b#=V>l!xIG)QQ4!%*7o z2DtAMrrWN|T-c!1kQ@ zNWgv@yYJS#XL;TA@?TW>)vHaZei;lvW#amEL-Hnh+DGc z#nD#Vr_*nBhTH6HEe2$RmF}I*_FxIBLH%O^)Q(lE(I;`CvhQ zEKs!kLE?W}0MCY;+Yj$swI;WJB%L_a7LL5A+cO!iV?eZ|HkLK<@6iXPWw^Hu+>!)y z+ZB>fa;&c|{`2h*vA0nK8=%5?dZyWimQ#J}6P^HA{a@qZQ<-4{&c_4Vbyp`>GEO^g z^P3AcQCG{0&Y zL~c1u@7?tCLcXLD9&gTk)&;MkivtZ8XOu3fTF%6X(sO95Dq>69*E>}NQFZR3jaU|j z5{f*9d*%VNE>_oR1_kmQ?yT)l;*q(K6zB zZm^ak54zgll~`M1Z1MCSo$3Aj=Xp~*!qO?@#9Mhbdn29Mh_KmY1@B1n(PbExW3g7r zs%VU6E4_P@yzpS$Zd-b@cm1;@ZAG8cch}9)m$xN53PP~h_rTe~*@0iTEdJtx%vDh1zAc7Bx{tcC>f zDP1+-4E9S)JYF%L&e_aW?!FzjbgH@0sM-LoNc_7;Jz|x~(5@2LuYz;B&hfl9uxRP7 zwsSTMYzA!$K|q!9q~%7hyjvi5?yrdZj}zN_Bd{yaW?TZ|TX0usr#ymHC>eDZIMzBc zW2Ck#9z~E?sF6kuh2p>SF`BpT;F?=v?Xx8GBZL3{edNo=)5lu=ng2??R%D!XyhQ1% zyNZw^uexwKUlH!+AJifHzI)}TZtu*4wDVb;LTVV?;k_>l>btw!}>nZSsTRknmJcqbFua)*yi9aKK8-EnR@crCl zO;nn&B&%)ehqIWHKYP8wbdu`-iayC6YHi_bu;0&r?EqgKeZlxa9YJq}|0kuztNxqL z{e16RM}^)}p@r1!9c<5cB+W?P-%NoZ5%@M4vL(j+&seZwFvIcNV{klR|2h$g?Y1NZ zf?h(2+5a8eGRIGb<{B-|R9j8oQty7Zrk5{C%NzBs!ET4MrP(k`qDShhv(zF>elBYN znK7K$q*(itLys3RfyJIWy|HcQgGk$f!ylgFjQF1>zJHp!BRjMgM?9o5LNor543A-* zSWFh=ddJPkLS>x3AI22jKdUf$?a05@TlVbla9h=7a@lpZh*!9tf z721$^GGu!rO#c*ge*IC$t%ihNuzTUQ`dsQUX>&#y>tx(d2jP>B?Ckw3(umrPg`R$s z91o657JrE_=3jF!q1@)LTX#G&&mpNOL4L?aKAs_CZ;{uMVVD&BIyv(j;#};u$m@+O zL@{1KFgBuHSwuk4H(wiJon9I=GZT{XtpzNe{ZS4+e|i#p;b|JdrD*byC^xpf(A7vay;I7Vb~Jf>{z9c`hx)t=W{m*c>Oayl^?$}3Hneg+BJgHVQ7>@(K3CtQ z=h_SupN0FOCSrRQCq>o=+rUMt7zAx$Obm`o&AydVPq8E2ZTbazWlbmUS#9^O)S;Ny z(>b4?Bt2TnWtYHwZ(IK>kLpE+=e3p5LoMWZV}@P%&41|`AoR^B=o z>7fjY+DP>F4632-O>;wm>xgy?B`D6$vbqHI=EnX=jZ=%|)T*+RX0KS$KJ25gzlF>$%e^g>bw@cn_ zg*452g9`Tfg0wNE-%LoxVYp!DgZG~@$zqz{N9T_m9$OPz&8dE;SB0^g$38hqp);7H z=O0gHz*>@QLkpc|PTsUdu$D^qU<5Jvp{}RGm(H_iYfOTn$tdpe%nyHmMzh_gd*S$( zL0iN!C8e?A#ndwoHbrBXASBXx)_7W1S(bTvy4mMfKMQ%a>ND}`Ci<^QXNarFx{dx8~V6uqmKZm+S!BgrQmd^w*%Qolh}N7&$9LIr`zyMl}vULhRE~*+1lM=`HDvL zl)6GY1r^zv8~s$wpSDk7FqykW8g0=dD5>k)1}9I=povQe7b|oiSsh`$FD|u^Oa9i%-6373o9DZWd3*P z>!*Orf6=1T*3i5BcZ7!T2JFi9lDD_A~A}lm=_#{wW#VuflT7EWvV1G>0N6<7Z~oqg#KtMVd=!WB`83j6y#OyB#h zm3kLj!=O^F7kX69m)|-$1M71{1<%f*3?Jkbz0N&6v~NV3vWCUJ62%)rR3^ooJyo7eoR&IJyoLC!mJ@t<~_R^HK zW&B;4&~%P4xw(2&?LC4gA?VSa8lA}$iyd5m&ArJ*2hhnxq9?Ko#pHIanxKifDEj-! z?skifs}kXqAD&hYX4|U*W0-tDi3u>KwYfF%%2gZYP+C)hl zFW8YGHo3VlZa14Z(PV1C4ms|s$ncR`1n!g8vNj=ww@AA%rTO72vmT|w@Kmull*)Xv zjgpp|`63Y$qK)$(oB|t)rA1aPa}2cpq_zMXM!QE1Kkbh^_Az^{a$r>pKTff;G5dwU zo+JLRqdhrfa-^*`k#ZrPi|s?2O}=v@S)F=Tnt~Aj-%yNf$?NQ-(>K8PRb;Xs76d?w z>M93{8jUVYA-YlZ7^Sz-yVM`DAQANj_ABT!q%0c2=OM#PsZx=LT$HRw7eGPzkp2+7ryG z1S`dcH{~w$x7tu|9`S&c48y`#K%4O?Tfx6hH}wcbFYgbM0iX{VY^3)%RtrqmWM;xv zz_``%)wU6XZh;J<-}qyr zaI;gSm_H5D2)fqAkZAzOCvbE-^$8^0yp)NiE?azVlFgtDp4PlMru&y7>dW@AT<_+m zSf&O1BgFF;CAn3{qG?=JYk$+%6A6liG`d&q3d#Z~ciS`*&ht%}Rzv;#`RW?@+H>ikQqVJcCsZ2g?{PronuL$CqBoGP+`kBE&5>DiPs`tRK?; zatN=K+;j{Df_n=>hsH@!p`Gpts!<9_i}__F1(ObBO43#{vj61%gte4nLZ{$QE?QJJ zq=XBNEcu|dA~Lpl%Y-3S=A1ocMs%|e$>d)o)t2202^mWxx5H)4`L;D5UB5#3K&4LW zT-;hFHN2WH+er#WSSNra!>T`e{8<5ba z$d)Bf@urHuzb*kk*NU>4o+|eTJpp4frz z*%vfDxCxxwFLr2{pdK0+QvdcxakvMANY^5H&TVm_#vSz-KLPaB0|kf9MRS@*ZX?XQ zLjnY~){Xdv9p>5s^!hwCsAtZy6P3s=+%ip?`O_Kd6b)Gm@uj36mY#yd08GHy59}WX%TEJUd6)#J%s7%y{q3Ku+SzU+I4W z5NJAxudOKLIBh(}zBdb4;U4bAA~b0bT40A8F{k_#rh@~ejEI{SO=0Du*ca_P$*F1P z&Def!dbFu5dsO}5WRFT)4$O)$l3DUX@&=CHtd`5*@|@}heth7iqf;?CF!m4l<$$7J z^vP7Yae)``7^7W*YVsQ?z4k(nbNPuBb=inVe!CK}A z!DE$_u6VLy&KJ0iZm0ri;;m*&&;FfeF{EJmB{?T-7ToJaE5GnH)vHI{u={?J^)v~} zuy(G=tpMK%n(?mkY)z9qYATmklsa*)5^OEc(5Y0zQ_-U&p18e-W*hjJ#luo?30K!% zkg+rro$MXI1!cfg&bA|5Ns+LDT9!yF2d19`Kg17F*{=`FBd3( zr>2!HDo4l9{_CShuk_*r7Rz3(1cCl+_3UQxq5PIepE&5#61zXkM-Y2{k$Ce>J>6OD zv1bnU=M94waQ7qPIty9E6qx{Y_v?z?W?|+E$=7QXqEf#lUgQzVZR3~VgP?A9cLW^* z)WAx5(s#o){xma2i1lHSkMa<8=ZL z;kq@Hq$Tcd(DGC@k`ar0t>#V5dZYTymyq&fxih9m=iRcJ#xdZY|11OPH$mL@q1t8# zLO)KFqsz58AWZj^3tGRvkICnp{Ka4Lrohb%uF31225N*3QVbv$6%d?wq^%poTD^uL z+UexbyfC_1ZZ)bSWuc@^; z-)bb}+1Xz5yp=5W3f5BpZ#g`ciEAwXZ;4cu=HVmuX+cz*wPf`QjrCzZ&MQ>{H;ioL z=_HnNdz~N3j)7gvx2u=ykko1Y?er)EvjY;@;jGV>wO6vWo)Qs76js{$K%tyY#(_$z zEA*AZkeESw_Co*9-4Zb4yolDZabDSNDn}eVZo?*kxJ%5&q*uT6@X@KJ5xw1tOS)xl z@QhF|h)EQyA%XZ-*ay>1fz0%aNAx9e8$Vg-C59J;K?NA;8`GG2`NH>?^GY1m%kD2S z!l+!cvyM<|Db3W&(pNzQhi6y?IJ=fWwOi=~j`w7xqn9$SewUZX*}h;{FmU!ZV39^na>Uy$HrVm4T0 zQckIn)F=UWXAlgbp6}*XIN;bv(!<;K=@$y_l@Zyy&)uenVpRCZ@Dg5O)RTgKJk{JW zVrw+$6O)yn%7CD=MB#}->@p>2HGvn{(|mR{1WeY;ENyJQ@Je&u0egiz1026Eqj5H#u@f4U;MJRvt6oS z;yfWH1DLLvCWbL^Y3xivUSSLx_4hzvm8UFi7q zam%o(TMyF^f$u47rBmNa?0Ki>>GgVU{Z!GVw{ z9jyJe0J4e#ue#>e`s-eL!x&Oji<71+zwcgl8HAmFRFTuNRJp_msi!o$K$|bbn-IS= zx~O4L6YYWu%W@VtH)=?&K!^jg^_zm*?97SL=ryTlGY~l*2$`k+$E5Zn}|cb6}9QC(`WB zgN{KI*ry;PeN|YJ+VTsdwMHx>`I>FzJ4mgesgqd!PAb>I86t?W+AXvpN@{zbLil&q z{-G>&2?tok7UdZBO?e+l*=#>YlEivAgPX^Z{Ju2xm9fK9@`=85e zA(HtKE?+=x(!$nl*Cn@ttr*)>p(42kcSLC(*rNlpA5-yvUy${-Y5sb5Y#5u-sy$xs zWJ`yx7IH8u6O+{`=(<31F|9*Zfm??f5Ow5$dnWLGwZKJe)@Or}* z{Mjz;3%HM5y9 zkRU2q^Krfj*(@SEMnB2oL8NQCmU@pL&W&Vqn3Q(xX=k`F{?hws{OWI?>0p`L@}#a( zRNd8|-rc*#UW}Xwk7Dk9XF{LUWwcVS@t2c4Ay*pCwUn_Hs7=J?`*D2$(Wq+={+J%Q z_aV}trj}zSC)~6+gZMI?(-as*nHoX2N%UKynrlTEQ%m=t)|jj1i$|@f0hZZv${eK( zOs54+QGXBbadvnUvq&4!D5b{GDSzc0wbE?00kY@Jq_v8k+v6$)e-LoXggHbP}sJKXH8Q20b zexkVqDA*Cr+Go-mE4BJN=he-YeVyiL5gwS%EO@!qw-~8$(K%EgHF)lUeP@f3$wjNM za{SV{fJW9v2bmM4Fr}I*G96r%Zrl%uO{bw80Z9LP-E8cYA=GyKo{NGobSEw=RmywW zETrLlne>x(n8Ad|c&(N3FSRE# z+j5r}uUfpF?LjI z^0<=5F;?`gle5-=g%u|USbm&Vnqg^1zlP&4bb5{8b8q^~7{#D6;f96a5(ZKFIZEqq zD$6B(xRPeBl7P`9P?^uqGU+ikkX$93(A+(vui59p3$WC%QDaTYTjyw&r0$dDP8(gY zM9oNrlC@U1Hu=E)q^`qD#z6yFMp7ww_FzL{`zi;Kmr zetQ;#-`9Hi=y2jTLN245fEvx%oX(8$Mf0`$o!BFpUX)#INGX_b%`YwEfo-c(9f;6z zc&Ii6A-yGW{v_5&8D!)y{);|(X4L^b#&y#Rq4QpJA@tpR8w&gPW;CgIT#<8_?buN!z z$;jwtLbOqWm5|-OtW}9`hkbqLY)T4O^EJ{voeM{)cnP zKvQ@0yGcp-G;jTd-Y0uIfGc$vOVNDdhSZiYQmuVh}|VG#jA!{EB%a7Tsc7=o~cy2Gxdq_9_is34oIN(l7&vO zVgqyUl{syb*(jSA^a!X(|`=8$a!Jn>pp%Upu_IvrKGZ(NRef zxs>Nap0~4gjH3g(SS!e_B+#(8*0mpm<$a$!1{E?$exK)fmEY_8LP;*{fj}2+Qj2Y8P$wK+NVlr3#X3Ii;sNbbrpx(cRVeRr0 zmkJI4RdZ|Q!g5b4zx^EeyajDjk#G5};!5b?*Z8OSB(u`TpFL)_X_$VB?{wJk4_s{7Xkw7|x}!Ig{0^BNH%j-~>i9o&kF~QHffI z>W~zLcg3}Ke$L!JoWnrux9Pla%5z*88yOj5STHs@!C6hB8eJTe8x_>JtkZ+6mHXudPWBgJo@RroX; z0Vuz>P#qHsjWWe_AuD7hKUM06CHPwHNXd*6itL)(6sfdbOHVqi`_j+_U$i)81@Exv<}a{H@O$`<_!m4l`QJ6 z=>URGZdFwY3Hw9s=KAgF5HE&-0KJU# z_MzzX7{P(o-t@nEubRG5fNt_~0k)IGT+E)i3F~jp>5b-}A$7=5>^&zoVa5?PYi{*3 zcI@xAvEc2Appc4g6Hl7-(VSS;%gYiv@j|zQq-(jm& z?gq8`KaUfWYV=xzO`EH`<2mLp7FQ>{-<#ll>n9w05|@iiP{CJ4{}_SgD17kDs;(3H zx5Xn4D*3|W-NvLf*HXfU+O9jSx9pgKO!rjwV~(BicU7A+!l8`UAw9ZL3uqfj9M9(+~8Kc@!;SVDa~eqM?mqv zw3qV_Fe962VpPZ!;(sk9N|DEuM2P# zbG}&zNC24vP6%2I=(WjTd)iGMt+E}Z)-9yOD|-p^Og|#?Z_)u&#pvx8&;D_O)>BC; zKfpVm&G-#fnp$>HiG}ix09trTKj+%hC{Zkw;6T@b{|cH4o)RJxSbwJ1^g6^HzM0dL zd~AQ{p4_4-KyjS&iExd~SwOb&S+4+S<;yq&M0FS#M6T_`{u)9h9-w64*Zgs;0XwAP zUG1kEFB51k>w2l<7Sd6=@rZV>r5`1Mc?MRhK!aSme@=M$_sr~^p6nEO0Qxg8=t%_# z31obs0DaLa|9In@ddXMMIEq$_^W^fIcgGT+{AWv8RnH(^1^x~l)cL${1-pDnF~ z>I2gOx|bo$z}0P{6;_giyf=% zKig-2>dZr{7!DVx#INtGqq}mxy38%>CD&s4g*dw_c<~{z+>b~89J!k)$^hEL(S7q_ z>z~7xh8^!8t9RGdTE*>2x8-U5XObz${MIk9CF@F0&V=az!Vg}h&KcH7=!>HB!6zGh zA=Cd25CnU<4a0);GM3x*`j=8OIJkP!45R(WIwkGxXt|_sN>~=wJk4}~8YnVrS}I1s zgm;Y)N!@+yw`V{+ri$AiN~cnhS_RS1Nn33meXrRlJwrLxpM|ofE&cx)6ew29{r1MXe zQOpSal2#+A6V@}Q-HVcF^y`jJuk~brMKL9J@!nIR*_r4uh9h#s+$_QNOmEA7Tew7$ zjy~bME=Y+PaJ8x0fEQ`~L)NDk8J&}EDs6J0LfkY+aB*3x&@!qTqwocYvnBXmH z=>A@J1NA`ERVYzu)xqcY1`q;6Rdf5VT$*^}vzRxvx}`QQa$A=TDy3Htx(%}={jEWq zfqNc+n@4@a!aIpcwAzb5D)fsOmm-EG#7$0oN{W#}%=ku9>!B2$$L;a6(3SPQ4|0S~ zB6E`x;Z*o(5hAizNU`%>^%uqQrqv6nAx16({YMVe(cpRxd8GbdpRXvPmcD?(+Xf|5 zPNTq5W7WVc$XOt$#<~2Kc6dMB5PuM7lc)0UEU8HyGMM)pv5D^+mhkp_W*tt%+u?2U zg$kle)f~$;MfCEDMay>LcCKNYSla=;IFMoQ0;S9JVh>Mqa1Cc1CH}>R64knZa&_FZ z3!U65DI?_^9T0c_z)lFi>PqOOuZo`{uuCu7ri8kZb>((OZ=+J}CDHK(Yyas@$mS*g z?MIrzPb_~Ks0yZ81xeZM4{65J z41NcH0Nd&6%X1cTM$Ig(w{k!x?vur$-$!n4{slK;ORd(?3{PAijz@Q_-}Z_<%yUqJ z$aEgrJVAtT&3A`=&!arD5>gM1rD8eQVd!Bnyw{;A{&$)6ZpD~!4_J2%`Z=}i3X&tZduct&>hrN#q(EE=NQfW$1sGsa70k2~UEHc? zqE}(ZB#rCjMPVA71`3ge?gpu4`1avE24Vbb@3zX1&Yp|v39~?U;eM>xFc2W^)soG& zrD1jewGA&rAKp4t+w$dPhLT%fu&zx%d#vj3Z=Ewkf7NNI1MUa-dTi{o1IFT+DCs>g4S z@rClMYc=o{_YceZmy`Ty{IV3yjQaH8h+JZc(M=g;YQ>yOm!}x3X|))}vzNv6b}R^% z)#K#DSn~wRg*_i5w`e92PG4>5?B*ub~;c+lkI?w1uiQ5WG@(3d+^ z&vnDu+q!~jq(0fpA7Dv^GAJYI`1dhQ{19#{TOKx8yTDol@~Bw#$Nsu+a9C)SCjYJe zO+MX%5NzLT3s53zTi6Z_GsG&bz=lTlkE7b-uhN2NkPyPts-4-E7hMvjNYrZ1hF!b< zpwqX!GSDs|*z<7c7!&rRsD|}XJ<2^+`Bs(Pp#(Jz!tm60NPydpm^?dAYDrF(XD3A& z@MkdLzu_bYYRb@mhmCX-ajxV8liDhHSBOX|aYpi#V1Eg=`VGgAaWhEp5J|8gMAapaze$lhyU<~c;m0PiQX6bthj&c z-m!l(Hg&6q=o=+ny=A3}{EK$_<@?L6jVrda>#p3$m#aTyKAc)fR`fPsxj;p;63Buw z4XqD)#kOpRdzl)DzVO%6Sf#Ku$lmz3KOas_-jfqP|3SK@)2nx!YC?gB$0loUyP6Vj zdlq=o+LS1JJ(=rA0h(2aNs1#`&?N?3Zws5H8wHg0$9MaBeQ^di4l`2A91n3!K2v~p z4Fx0|U--sX$^1Y)jCpCp#&OnQi2mwuQ}aa~SAi~oP_b00mUf{ERSLTRx<#n`E+Nl_ z99)y{O9>r{OVFZSfV!7Tq_~FR& zF6p-SYaGQ%Oz4ylbH#|CaU$bSjr%wez@JPr4D_=?G66BW?f3BJu`azjG+C_3o!j+`@+&*o$nFb}Ez( z`vFm{H8^*YiBZ^)=%!^)ID3F3_b>+T3b>T&RgO>oX1u*2cip z6ylFoo0JoQ$MlGV)FG~Ew%)uSZWf~|__@y5uUh~v)RzZ68Z45vmYRSOpB^tp;+7mf z(RU_}T1y!~eQkpc+ij{cpWr20tq6Z_Xd6(Sn?NQGwdAxRH?~kl!=q~&3zpOJ0;a=E zA?akOcH^O^oc7f(z5uH|g6#^um_VIg%Xl(Iwryc)-L_2jy%%@-t{aO%buJ^2$*rhO z)CvM@wdDhwn5b5@exD)98UX4Go<`&I;iUHobcPwBD(Y5eg1E9od5$>1*Mp9yO3Ftp ztULJ}78r`xh8t{5Q3L->NfU;;W4Tmgdi!IIJl)yXzJVPz2^wwHJRgJT9vZ7?n@Zd$ zouJMm3i>=FX0c2sv>i${`+f7#SFJPkGfcIsXC1 zl$Nm6q?mX3HSLhd3XyB{b_Qo9(WSdH90|R5Q&BsTRPs)wFv{4$vAGE5fwPZxDuhQv zS0x_{cJ1y55Hqf zz%~N~fmLfzCWno@%%cU_C8h>b+DysX+Ma?wIEHxQroAaTW`dB}!!-B!zFqEcO=@$Z z{aXtvwEYcbW`3qLF#eJiwO4%F+qIT$iE7QTUrcLS=_%Ls)2%Tg=owy5G5l{_(>#4f z`9GES?7u5Y@i8tmlB?5DpvAB>?WacyxiLsQ6TkB$L7!7WuUZd>R9bxt>$F?C{)iN0y_n zkx##QipCZBm!;Jm<<%XDivclHt{2z_3})UCuMUhhj3BCt|Wq3lmkAvUQxa6?e2QT8Qd>sNIguLa@!uWH88 zDxP;%^Z9+Nud-xOD;-8Nqt5y%1QeHepq#v&gkadQ8KBV2m$JJkz4NE}do_22A;{no zAJrtKvfg2PG)6Py186r|{!T6s_xFL#5RU1dCBs;(=)n5tT~+GMm^Op((g%IzP3 zLj82%?ZHvP|l>-bD3>|;o#bgC}NWY_29PO__4rt2E9@zmb_Ua6RHFE{CJw#aJ}Ta#1?%%T`9WL^J>>DP^`tWB9#6f{Ce zoOS{$+R4Hfe7)>bo0v*^&}2i@nLoU`tV~e#i{eY@ZAuC1Q>Shy=dauW z9TP*d_CdRvABeG_ErJ0hQG-43KFy0VTneyz5=2J~wbc}<-i3f0U5lRmk* z8wbDME+%lhN8`tdWDXCrXpK>y+1nb`!*N&8KHliRm{5s3kQ$}`gxateR9zq8rxK?@ zm+oM%7xMcpDbSJZHD;?c{w?c33x$E+2QaOQE-)8Lj|bfdSkcuVMFzEtH;VVB_b-U_ z`s;0n*PU!J>7!Hqx_dkN^SzIc;KF+F?DCMtE{5TOT^RrV1~TH?EBj8AqcAVj0ae^B zl@~Mg=ujGS<9mtjOX%r`S=N{2YGmj~(&8fHi$!!sJhCX}17F1b;-e(P76u~|;!gz& z_F4-cB^od3An|S?l_M#v`rl7nm2CHwIWt zSl86u=eGJ!Hw<4TzbXYeqGT)*3iXk;x9EUAJd%&;iJ@Y{R_8uDRO=v%q=r0E9*R>S z$~_1Utc{{)(Ng6}gk~@(t0;+LOI7_vy=2Mph-1l9ny`0EKqPnI44PquIzGA>iFJv6 zBCema9Pm_sSg7hQdV55pP-u+$uWp8%*Xv++rF zf{|JU6K8`dC7eX!#-rX0y2o$zyBB=rWxE&Two-WCbmD|oA5RvtKq9HuOTagHVrdN2 zjc>tF;w=BYZn-f`L(4B$E_7qKz+OugX%ZXM2*w<8C~_x>bxs225f_!3Au5|vU|XgG z90i77YH`q=eXsS7`(LO~t>>BK|MP^=En8+HrTk|sew|`Z2E|gh8H5{>yv|-K&ncsI zq5bkP(pl#v4>gwF#XFi+HSkO>3GzG2v;pa9*1F<_fi<2Fu_lx56b0kFcCQIg%=TYd zjXeJia(?oJ^m(S6@cq}wa?S+QhQ?880G6(p;uq(;Up-Y5*^fSk5EDuL>m2Mhl8)=c zZF|>{OQMtAT1L0U#Ri&YSb)9N?_6LMx%i{p}8 zTV|Y56BbY`AWr4)PGy!|Es54V(n2r>u3rhcAAcSKCS~;dU_c>_SBx<;!;4db9Uqlb zp#3VHnS9Mqi4tKbD1l=|UxUQ`pHAKvlBWp=BjJjjewP0_KYjjP=xzQsT{!izUkB2- zBR*HhIc;*|jIHb@#q^TJr4@1)HQ)Kajo7ATjHBC^(tQw!91V9HFD4f6N@xOO`)2>g zk9*Xq$j9?h(PPR<7w%>tgTf``wdnN-3>^;h0SkKt*Lx{*qk6$yvD*O2C=lcvE zX0>5G;@X)H3ly7Wz>PU7b!&l+$v|Fn+_@vdioP)TClhb4FEKc9TXaj5fDhcNw4s4v zU;ey*Xya+(K!Ls$Gk8w!X9=fg18zop9x#(O93NG=y?6kRH&xwW>L$need$bA$``{p z&cvYiGp8z5#4Li1*T|f0<3)cBr@$dcpTJcH(-xHm=jpo%8zr0%QV9{Bt3(a zY(npsAo1-iPTpd$hyBT!M{$(1H(v*Ce?gJJGLl@~0PuFvlKXhDmrdLysud!f%pmOW z2H;yEuT2AmTn`?RMy3z7bkdlmLW9Ib5c?oqQB4F8yFUL8MuN2D1PvN9I+IkkW|1I+ zyu>*vRrl&Sr65lwqP&U1ywuP#)HO7hD-E;uPe*L>#HB$(zQ25oWE=l>#tHv+a9pkC zK^lK$B{H~&X|D2rEWnEe0fwWwSKE}BP?g)ZXQ#FmJpIEhsp*NlhYSPEfJA&(k$|7c z|ZF<|wa+B!9`1FKsLih`p}qRG$Is3&v3Qg(}L{s-)nCVWPnepo3J z|F0*c9WBy-0mtgj$iBWy`B~Ohy(a}1XJGQUi8LX3tmH_kJA)E<{#E3jzI%Ae#1rOB z{3#Xxq^0iTYmp9AlzLm&EZpwklOK%I)&^0XU(~8NS&}r%>85`u+pmI7#JF5zW>#=- zQF((ARW5|DNSRDW%U$-&uvtrLb?HKbXt}W@|C5Aw>nt1JV~Wz-VDe|uSu=mTXQhIm>dj$>_y(mI z>x%^U2V2YA`h`^jsM~mp(-TKq+>df5@^9dJH!x4sGA(7Mz3>V04_^#k(YIS1_yrXb zzGols?_SU}10D1%P(>j8w{to+rl=90x)>R285fD(dJb1SugSe=xzNU!!n`Zd?xtn8 z{vQoDH$T;M?c8B8I3Df_oSr7H8f9qBt{i!sz5TD#PhsffneH`-)mRD2ntG?e;4-z% zz!INHn9DWtJ<65?ORnCN$pLN9?gUShLSy*b#~>HLpZ4Dy=PPqE!>s?p*|z=jdmna$ zhiiGD5oBF>LXI9lX{8Ylc8bn>gSz~ucXWJ{ReofM2jAzTmXx)?i!qsjY~6o+ z|K{W;d>=ULH*WpSMynb~L??>$m=~KMbavicZG$N@QghRvNAD0DyeX`(Eh4Y-T_QV! z8J#jog~a3VI@0=dfImoJYgU)<>GWIP2y(ftl2#x!*C6)<|NZ^weE#lY0p~k~`?5zr zWL3)M%K&KBit&_@`&Te^`9H>$B`eSgJ_+EOu{Fn48;!s3>CeGkIdhHya7~`agE(dN zo`imTxSIy@g@m#rC3En0`yrp7ObW*DBJ?F>gCZy&L z7*C#sl%9!~@^D&}(${oI#(k zk%(&i1byQhY6hGI#9!Dp7)g+^je2Uu^aZif-9ak~BcPqWHP9Fhz?~k6c0pYYdGEs- z3H%abgZ@W8dn1ceY+h);eUz2OJg_`qNh|6~_f0Dn(?6wG{XP;9MjC*+2OG1j{ZD0O z%mq}q?AxCCC)F?bngt_uLG#ltqpOWNIpX8V!hLxs&COQWxUv2r|6USbLjY3WD}kq8 zT`B~C zIW_$oTm=bC+)-+U)gOVc6eO?%l_l^K?FEVII`|UF9rWrikDi{!ldD}l=Hi!pR#xu+ zrtL&O4qNk(Me=Z4UG7etKR!1TJrl1TYG;<(l-U(#{~&w1mUM(DDCXG9PyeVZs~CIV zz}%Mbi+G<63o5Q3jNRI?Yl&}dy*#jL)=!wo?|l(el_z04Bp3Fh$9AMM+>K{(A zY(EPL%84k{BW`BVdMc~`HC}L5YO3?1Myk@+gfL&&ZX%qOOQAzonU6fk})~IR6$pAUYo2 z-UlEd9IiHXH)A5uuX1!3u_bf-ad6I_!XRHs<5qfWr*Pb&{7SZ+_8=6kyr;%DuDDbJf+|Jd9DdksFa##dF@6?Wy ztF0*X_1?)?#n#o4=~WT9LMZq1%T+vS8RutAnE=*9t)=6%21E7hG1e63!}mwgrfxjf zEAj@~CgBFn-no2M+;>qlU+exR`Vd4>W;CH;DtSBY)vZ5~;XOAJh{Q|x$H-xt@LU7z zc00vOGB`$>c$NXI+;hOZvgY4Oc!GT7U2xpThLe>~p`TdbNevB{Dx-&*zEjkB$FMqRH^dL2sZ! z2j<@fD3tOULX{NNxUcPAU8^;5vW8`Q{cwkC5}EswCi*ROtZqJS;i_~GAfU0W{^#a_2O6CLOV4t_>?2sMg1ZM(=1UNt^D~Z#`ESZn^cw%^c8a(Wg^fV4K zX-?2L!Mgt1B5DA~TQct3t%TbHQL~oWGy&yLF;8--Y+o0`mYCMLYm>|S-{DpD|FgUJi^pECBI8@Rk&n{YdA>vblfQRio-Kn*y}8 zx<+C2;O`o9Ozus0Z9m?@(^4HuhjS80aU-N&%#%PUPWUQ5q-vj=YIDPDPqv9{_MPFZ z?9z%2<-X`YAiJ{N;mid18x|{#zn;7hH&Mj;9(yHp^*FgHq;=tvdBv%R6wYD zWB4DA;hm)RZ6gTAzkee#qoLHZLFXeZ!9AHyVJVSm4(!HZH>VHAu@z8ee#N=YPs(wN zt2?ezC5L>fZK-{X!(&gqA6Z(o{V%lH7OvUl^cu{mN@DXq90%(uRnZyq<*5FVk0BWf z(kkb*e`~>QGcnVIw6G9{z4aN3YKM!W1YZeNK%_q~li*Sm<42Znt87PC(`#og9DAbo z`%vlt_HX}?8XufSQQLIVOQ({S#*;o=Rkr-G3O@_;>TJGuD`9G6)Nh#3vc)fmZB>fv zU`NiG#>b`ypuc~RGS^qM)LTt4LP65S?BM|GNX`@DIaKZrUo^C^puAu@X!4D}muOyd zFt$kw^=xHVY+m6opZ^5^y3`({uRUiog~fwpcrI*|svO3{SQY4#6M1aS+Nu|uFMxsw zYpi%K!vwb!mozFY{01w7Iax2q-j0}baQh7 zjm;=o0k-oATXzvVqJcO2ND=*uZ+(~sjl!bhJ><0`$hW?fjE}?(k(aj^ml<(36iPX! zCTibb-}*gj!K*c+}F!TTMV*z#GnK3fn^bkzb#}ZK1-#5NFRvLx= zqkswGwIkl2>Qp{MW6UFWV8Wsg^4I`Uz0=U-T2)qY0qBo+1+L>r(qVonBq~c4?PODo8lT6Cmw5IVP_1h)Pw;yIC$WO z_hTNG8HeaHAOog#T70zCZsEu5hl`Khg;(+bC*2C<9~dZjXfUw%Fy`?>m>gFHjGnSf zZy^;VMiZp`az0TZT?RpNX~Q`OV!4p>#g%cKev|{?BAot4TNv>m6xDo*r@3(VQ;^Ip zvEyX_U4j8kSZ314yr^_Z-gzuJAPt`Z81?NeFvm%)NsRr7k+G#N(NU-T6!e3-*)Y9k z!%4h9WR-r0H`Vhg$A0$WerZ7f>-YV_N&2dQ{9$Y}li9JE zVhHaHrb9BQ#g}NMF;>zKAe^s+h`l^`%k0R^|Grs}q35?W@NJY#yvjl}{RHiWxUlwR zU^uahPYl|5(siuw#x=ohx5_?YbbmBug5zt=Pb{ZYrz-c0vemm2d-tX9O@tZOyYf*u zTM3lLa&rGH3apBeK3Zgm8pj4pKX5w9U#4ymkp7qz_mv+0^mhFT3*ul&0AquvjqdUl zk!z;kYQu-sH?KNb0wQW?8^zjG^Qo+>D49)15xVM4p|{ZzZ7iJ7@&V`+T+jXvu?PXaKq2fPNI?lW_r z@xxO#xbTB{yvPLn-~%N6VE3kfmV9o9)D1+nb_%e!yqirT1vnuR(<^OoK!<3SJ?}`rNI$z@h~}>We1Yb_elIEVtk+uE(KSHISEU9t z&gcoX$x*yYjP@Th6ivRg!Yxl^3Ad+aM|91c^7c6wCizfQk zg@MH=Tn$~Gg8JhV`yBEd@AUr!DV6_UxVkA3Zi?xGOl+q3i4T2vxsRK}TYMV$<*cb4 zg!_$u?+6vpR~)k47X(9j6Wpil0hAcFu*nQ%cY4I6k1Hk==$oxS{W3%P!h&DjbLNqO zO(LR3E;sT(iw&1A;mWJuh3_@I@&$m}7)=sffzdOiw&d-Ukvu^@mtTbE8+qC+J+z{s zmvyM*F>Dc=BtxM%An>B<%+{U~=ODglKNv>lwEn#hT_|%fQ|D#0c+igbi7Y9F!Rr!B zJSbg0y10qTQ&zu1R_s0K7T4Q?C{h6%%079u`D7-edlF$u&`4wtzBX(`8&8-ZY&x)l zqYg3WT1yi#PquTO&_^Ks0$(srA6DUsC+!^QZnI)^5a}OMlo1+i@GXBy?dLpq1 zhyXNOiWf!+fFnlYPtGZSb5q2N-a8);GD4eOs{UC>v*U6>7pu_)q=S43pH*In+-?G+{bPPAKs{msI4fvsq)idN+>Uc^Qp{^g|8bip7N`3x7(dl$bA2G_r&@_;@GFUFmI$U>;kpdIpA$BjtzKKK-%VDg&|~@e8k6hF&f?>V#^xQLr zFOCGe?4AAbnI^6fRLel>;{3;<{N)Bc`qgEerF=jk>1M%gbA{o0-PV&bo*1JkFx7RD zP1Cj5dVr>I|C=T{lti2k*x0)5{W>X1zi!1RI&fhk8~knlsz*YB98LzKlEPYTK72pY zr#OL+Lh~eum&pKO%vRc*j3yxM^K+)ZE||PR;@fy)v^mD-f{rw_tEL8pEwPybD%RCl zzffNnL^4Td>nbPlZ9iqS#OT-RVnm?+)yNCFm;K826^EcvI~9jO_l2-?lP)*$zbAIi zxjQke=CDCYR-i_Fi3)5or{>i_h_fxWB&!eD@_A{H164_cUJ+8jP(%6HcOFgTxuF+0 zP7E@!8V{`vIGemsnXEHf5`WTEXhOa<;yM3WM|=(3*-RDon;r$*PGSD)VT2xAgIA9u zt|lzM(-?JkH6^kL0Ry&^ z6VP8Fb!Q5)H_|jD7VO~Y;BO`;I&NHkkg>@r=Q@yJc8IuC!AgPhZYAJCVE6Ygys*WO z9f1ml!oOpM`BE)-`%I{SPg$?=|46{;6R~e(u7(IPIDO)X{I{$AP5IP^PwzzjPUUJR zSHDyp`Gl0FuDGuwXdbuBdc67ht6+$7Wf^x084s8Wybok)Qk`1jP}_Lu`UT>mbIDFf zRHjumZ-M>(eHS)baji@B^OjaanhAoqrX4c*8Y_Cpw+PQUdxf|6Cv=ZSiQlzFuNcR=5<{Q{Fielr_$Knt3krw*P8M|J&mVaq4$zRrMtSyHoIs*-_tzB zy;(hG?k*-URRiJ-o%jeJSV~fem0Nxpk(if0{OA$!m-+DR(HD~oI!FYK2$XuHO$qT4 z6-zgo>-N|yBs{U)5jSbRElSw;eCv--z=Lk;H9@0hcV9u23svA=CeyphI}8kky&>t> zZ}ZI>R|Lm6c^wnYUR|3ry;!%?cnmojWrUiY2fNy47ces)n1gKPqV{oy9>z(7-{0(J4IrQO1=rhhOE>ZLw#9??d#u3M zf%dBXGP>UrmUBz+05x&|xx+mkdt~Tn4({gSz$zo9TfQnIQUPPrTfhyUW$wwL0y3fI zcrKR~SS3mZ*Q~b1N3mQqPf~Cq6Gl!k6?--F?;-a{LwSb@#*81)d0jBG0{$X(5a#LX z0j*HAmGQpDS7dHxq|AsxJ_n;N?`2P$-!CkJaLaoKW?uq6td6&Re~j}D)YBtIHZIuT z0P~sWjhQ`CEmh94-)CJX1^genXUCS@6oS{Ah z@d1`#ZM$=OraPYu(Rd$#*tYrwpc;|#Ucgzh@i~+)QXJDsB)5aS$+6a||G360hd@br z*&;%;sDA*?s=YZzQ#RiRMz6UnuW1aK7^+E5$rMezS7?6@oj8`icM@v#^(=6(n`@k_ zQ*5jj_Q2IMLE!7z!V z{k+nRHeLAYO=UP=W_NhOBk%Ya`fQ>%dodAY)KGE*x-sD5!->PL@%^@dKhiD-Il z1!z!07;=T8(9O#luiP1R^#xU9T)>tTZ|X_$Ibr5MT{x}Um6S!4U5Q9(ZyY7rBsQL> z7<=DNZ(sqJq-(CiQ0fwPs=d#e+<5zEX^SK?;x{zq!WfRZ$H27709*j6J zXr53ub`1{v(q?QIbvD$P%jp-y8#-PLXTKU-`c|(Zdpzd6`J_o{-(#$oD)LdHU&P)C zE5=8U=R3~DJWv}LqHXH;6$JB_1R-M}=K0wtHLZMF*+zl8p?Lq%a^BLNM8!Tsne;&E zb$OzfI~f>tuDI;IxDC74uLU_V=N2dk{kZ2>oZwqBW*+=@qyz#ufF#Xd zT9D304r?>S5iA1rBk|Kp{TJ5qr~kBQ5uv^ihudR4`c8&Y4&;~J=x*sGYFq7F2w6_0 zyiajRw2DCmPoolCL(o*vKfdAlAjI)5s3z%2MJChk`=6TRd^sOxHsmZJQFlPux8}=w#z0QiZ?V7$V}x?cS<3$mAjba5WKPmIxCfhf&nXDS-XC*%|E}Q=y%Ed9 zE<@+Hc72%(P)==&%LFh(s1NjLA#IR(^WqggVBQ?ALJo)+hf=Q8Mpboav0t~~&3`Mz zt~}8yyYy8A;{7b$P8zACr@eC$n`>T@sAx*ETC&A>yg3F#3%!BLT`LO>R%XiuN*!fQ zeiQt$)USl`(m;d*lK6C*PK5Kot0Z>1VntRNT4E*r+n}9&rtn012eqcW@I9*Vvz!E7 zxSO_lVaSdx_ct|`(w#PrarxLanwNBeC&gOq|3bGU7v1~bz=iMf2lpMx$TW>UOS(z< zRjYA_ddHpM842U=PerDvbmvwI4~GSt0s{{0K1>Q%F1``O`R^BoEXHJjpCSfV5})s! zsFEH_-L(@-yPMa2__IkFh8`8h+KoAw?WOj`PfkDd~1>G&)L08 zdp=n0Zp&Y5!!Fj^a4KYCzeu%&))+Pz4_XI609J?@+S}6O-BXehrG=J4L&bNH78-8p zrT7NRqh`%aO8d`cH}u(LY9?jTa!X)i+ow3+#oB^WmVbBNVDS+e;VWA{5bWNw1Q``- zD7A$cVzXqXyD;=ew7`OhFqP88|-RDq)Q%g_dSRT*3snfN9A&(h?-Vve3S&rDxv=RY{!T z1W#0dyiV&(h)-%$@r&yML#!yGp!7w7ZuE%#zO4w>|8{V65QHq;6xzC5lORF5+GdS1~@iJ8v z=VFz=Q-GIpIhxl5^L?+m6>eYBhcO(F+Uj-w?vcdhRdL8cRpDbOVW{&@ZZg8;la(_q zY^LUqSMA4zrf+^MUWM+*37Su|P0B2-^jLHD`YCrOjKUS+R<5tGVWIF{^}Om`YMW=~ zbecJg~wsx0vc5^{!~-BG-~woODvi%~|=*HJQYR43717J23UOXuOBq z`fS}$3ooKfp7A@xp*{*EUXhS_8uX_N7ZG>Nwp_+Qu)*34{`vux={p@(v{eD<51nD8 zip2ZT-3ddyvAIC|jCz6ryPPJx88(7N)C_)|TY1)A&$iz4EkH|dvEOfuHB4HJr5&h9 zxtDR%?^|3k&euW)8jR!k&rpxZ8_`y8?*wng@*$E&9RCV=!&WyQdIQsdi#XIE&b+f1 zLw(wp98_!H5z|*K5V?+fQ!^OW=PBAd)P2S!$~pIs((7(J!|>yj-)pK3F2Fa)vD z0qyKAZyF@0fo38kqp^1LmP0vmWp*1Pt&Df74-b@dw5g`ZovKmuy7Pz-%^UFv`#6F? zhP!t`q2U_!poZiLaeb9o56WfGX*b9>IST)7H&Y3+f5(ZWz!?wxS%_N$t#3*Y!wqqZ{t?ktXX5I&Ho zxm!++UxP6l1pk`WMc$p?W*?I(P6m&k&cWa4T+l}U?CM{FbnCle$cm1*+0#S0hB+@M z<2785Xy`;H%Nw8u<9BqB@!K;D4=sH??si?~jM$bAr= z7VKDD_Y#*saZHc~Vo`Q^E<;K)`iGhGBB~8us4Hdeoa$zQLAB*|06Jk40a(AMDBj4G z2bhgxv4UkJjUDFcAdUj8Va(rf&U|B%n)O6s)v}1x5in8l=T>j~&p<%92yLRa!|wm1 z!P+_IgDIkUnAh!qc>=&K{WDu>vIP}OVxLR=R;#e;RlkggDo$%8C@T@~0@wz%LMK+q z1znV1AFyn?qq$p~A--kNelP&sahdd|R3FoTl-5`vM(UF?#Q;E@V?h6%f}22Kg{^PC z;!RluBFA<3+%v4B!o%1UQX{GJYbo`9E9?LR;eGx#?B31s^(hSz8?8sP0cQn><~VS? zxR*#B8B(m#pFq*kNS_>jd{F0!@d4cP3;%N(_N=W9)%0=ZCru?G!=O zu^w30O`AYP#9myar(ohr?fSpssRcjHBg+Y-Qw7#9mFrZ_PO{j)virxRv9fTk`<=e= zec?(G!Oy>MSmC@Ip4x^F9U3c44Cw|+%!{iT<{Q^F7x}?s@d~z?>b0znkPrH-Eh-V3 zM7|qgQSp_G8^3tXa>#fDHgx|{^L4LPA~oEV_nOs&=ma;nPhKeOzFuMCsYobYZ8L2G zC4w@gskAY(Qv`a=PA`dG70BP$U(Bdu1Ms|{FfA1WOW0mJB67#9g(%}oMC zW&qI2NWS)pDwG5|p$Jl)efER&atR`F-r=)|Mfa%Yk~8J9>tba|BQj41qUo6TfR+bp zU6}^e6&fS?3(eQcdZ&8XVR}c*&k^U$lilCw0c5cpb z=imz43qvyRQGaboU)s00W^Ia}Ke|>Z#RvFeIpGWw&Im zQ7T##bbo~Mlay{yPV#ZSFrk99scx2b9y+oe2GgL9$F#o#P=8z2(VU;#vmhP`N*%+7 zZs>HWmboqyoCmT$TieRVLTJM%Y`E+~`MPmiu;FlJF1GH@7jZD&V_VFD%-r_*7SB@? zs5Mv|LN9qyl~k)k8U#?Y#<+b0wK;G_2XciffcgF}IS{7U%?vA4lOY)$KW}9~%Ad_oVWGW1CVXA%F2)&Ot)MH1Et(dLh zHu_82Z@Mk*7m@HI&hkETp?w(*mGPnx4fS%&e95bWc14*$%Xa*)nojNAe17Z@QDX3; zi`%}qVTR+W#6qY3Z5_Cgy5WckqHWR`(i+ldeNL8(pNH+x(^Z>{mPL?FL8VrpRImh? zx6&BiCf%Nupo)U)*z*pG`@?Jn&GKtf5!YWA6>ull{r(`|#`Q7PJ&cv$RQ;&gda9oh z>J1@6dh0A2PHzo1LCs|_*i8K@6kXusj>y!vXG;h1ZVfTTsm!J&zFD4pXyc((=xbi} zD#c;{QYeZD@N)=3@AT|yL#6fhq{6)s_h-5asDwPi{rl+|-Gp(iK*+?3t*h23y1{QH zs?`#t54h8V#0t%X*T>+wcivGo`c70No3!}|`@j)_mQ<%W$lv|PdY4gy6W$Q87bU+;Me^9j7fwiujKDsb9-niF zh?#;ij+3acxP0sO>GWhY|JTEhL`%Uoq5HL!VI}K-na(0Y+7lWKHR?&PQ=J0{bAxTF zbz+mGeS`S`BQ0}+>voe16?jXzT#~|h-RcYo2DE=Gziwe75|OA<6e1M4FqoV>w~#3Z znpCx}IIey1$9!ZKY{&Q;@)*OfGLpt3r2|-!v6Ty? zLxuNfZzfF=yYoL9Km?zk8gYEZ)y3W$>27*0P z){~>^&o68^jzZ27>vcp2s?!;P$B@s#>cAa)mvYt}Js6rUU(2&c`%Nvx;|xu?tXLeK zdLgYjxuD&7A&-%yrKLEefmKvq4@h+ulZ|aYd+|D^p|5&Z!loRL3#uXI>$G0CE;_=U zN0SKm&6D%AP{+&s+0gak+9=!2vDhJIN3f|6^IVz`GM?co{1G0Eu&4qM7Ieu7*QBU% zn346h8a4~+wtHT{O2mEQRgr+`;8rW)K}v&TfyMUSYBxn%lMw)=C4J20J7!VGU?sI2 z^4RpZJ5uRq8EeGh((5{65Lhe;3Yh9f~0O@?Zg16|V7vSkEI>c%?Kh-Ly;*dtx zk`DX*qCBEKbitdm1Dp6Wr5G<)r#FAhwwj)*gPksHzaM%@c{jXE{%syVJW+&%!Rfk>G(+C@>jWP=RW>+c9k=^z>FBZSN zkNk@LQ#eNXHE>gB)U`^H_0pDi?F6{^{6j=)ivUwxn3!QWKkjw&_q{l5z(Yuhp~3B& zM)+XeE08T79!IZBbg?tueILITn_s9tIv@c5aS}mCjAE)c9Pu4WhJxo^$7yR(p8^v1 zeFc_#>Ex?8RyJby2}ijlqO{^Pq#Kgh6o9zW32XbN7S>vtZVIT9CCa+{l*8d=BC%$sO2FPlf>qqsvzriEtDP` z5cvyjM>X>V8qsiIxL@{Zk*za*49q~9sJ3j53%ZO!(-G~?#RH~&bBKQ0%e*a^KWIf4 zztR5?v;jDI8XZKiA~{*L{o&vPv}_D&PG@&tq%lB3Z0hva!=4DAS)~C7+*5x60r&Qh z=wYue6+#4g8f#pqfAG9v`)c!))mu0mSc=omt*Uum7q(J$)mR0aFdT{5%Nj+mKNU|0 zDk6iA{74?tYXD_@L|;h;?fPocqg~dkNj6;da{&0l*<`%xODdwB>J=6UjnwA46R`<) ze!f=c;d95~7G!dcQ~x5Ai-xGAIm>X&Zcq7|0}`L!vSrZ^aJ410Z9O^tH*+%E zx1|UMjZ#Yql}&4t4lkfxyeEUc6wI9)G~_tv`K_V zm8!zlk|JG>aHgrWT-z8v$?@BO5W!3O3l*qgnl<2e*h+Q@*MmDo=sO%}l`fD|!U5#Y z={B+xEi>+8)&PotYF$wRTP6C+w=J1y0J`*tn&?q1cJ^E*i8Zte6dwtgSZsL8fJh+L zYaha-`E!Xi_;7cP3nxifl5`pat3UuFIVNoP8g)}edF3IB(GIznM{bcNd{+CqlY2$V zHl037iik^s~OXpa$?4Cwni%L5Zb#WlaDR2K8ens6Hn$cv0{^$XH02+HI@0+ z_tTF>TRYD$pYeL1LNPUDW#z-Mf*FoFIh5z0^npO|5rtE|$H4ZV(u5tC##M!9#IXA?UscZuiOZ-MkM3R$wd7>X z=3FT3`?EUybm@3tSF%G+FSc6yUeb~0xJ~(o!7j+2F>z8ASC^kA{a`Zvbra2UPmoGe z8>~!kv(MwpeD}hnh7V|BdPn2j za}ycBQnM*2t+gG+0$Q21Y^33qdSJ>;b>orN#6ZIHm?MB!uw47)8D`6chwRjg;TMAM zT>L#v9JXlev9qWA6(Hsk(5j0Q>n}5gUsx@px}Xi+Kkr*Q z{BOLPK1nE)wl4V(vRzaSAHR8K|M|5{LWcoNas1Cq1xLJ;#?%N)+|hDckA|oRaI*&r zEjxX@u3n;K^^pSyhA+hDNSzoJJp-cgRL5{9@`azUhHIa)L9iz|(A!~)rrci=_=bEU zNVw?xt4@Z~216K$j(ZC%E5F*0a9wH$tM$+ZJl zcvVnYLp?|&1zfz%)ruAO`hSRe>!>K(H)`}58bn&UrKG!Klol9D>5}diqz47*4rvgO z?nY`vx{+?A8>E}_yua@|=lnCnV%D0qm|@-bzV_bN-fnA3&vMmZ>0l@!r6~ex^W~Ym zm4hHE8uGC=AGw${p}8l`)~>$dLb}iUK0%FnRoO-3`HMxNS2cPdAIa>fySMjZSIe*a z!ylv+t~J;n!S^(_Fatm0@2m9l(&>)DYO$sHha791Vf$SVdiX+b7l!nU(@M3F8t&45z;O@c7z1sSL#85(14y>gS;*Le%YthO}A0izSn*J5H zWUB+rcD2wr|3&0$NYzS5-GQjcyv3Er$t0>IEQ6Z4u<4)y!>hGxrVdg?2%0vC5xVsL zu=H1vTA^FLNc-RWJ{@)RvcQ${sd^t~FVrSNg$4YT(>;mE1|CAf4H(zNKrw(mZ~JWv z;}x5$YpcfUKIpWF8z-s1@%x{3_F0}o%6=n}mj>w19lH4YXXL&4)g+`TeEg75DB~_f zwzagbGL#gN-=)GP9^R{PSJ_0mn|KUk z62A-$Z`)Hse;)0qmrqo2zI{>ZimQ$3NoXC*2I9_wiQA+;Uke(dL~W#lf(PP*2Yw@) zh}oIeFSKT|iNVW6e&wg>wHUo#gHKhvM{N1*xN6fQChbA80m6hd_gsD~GV^ zaEHCk*N&e4!2ONUxxirn_rFU7OYUNHD5_=cU>i|UpsmnioDkr^4qJ#Cm?&@h;b7eN zh2!Vvn3KTfWO+UC=HwfDPWPE-@B0>>UJ?y?SJ~2jZ*WaK^|>WrL?l0oFBEH@&d^;fJB8&fcmH!Km;u_C#*E zbbkQec$!uhhIhgRT``+PmoaD__XZ8DE7N%-v;FV28|7cbY7)15NFFIfQ$`LxE7(4p6L>=9|RsZ2455xcc(s=VyX#f9n*4?zc*T zE-UiBSN49nA3T#^g8N=l{ML@!bN7`?*U4zWUDKCeDOq@3TIK&pC+KjXw3&f55Ct`J zD=2rfqwLE+oSf46qXIzJ1rPig&B=^mu(CY5O|48^fL2UMi_41fyh^iiULO)ZE|<;= zC!`!I5XL^2Ypn3#e^ltwe{a|OS=pyJ)Q7~i0yM)S_K^(BDvMXgd%dv{T)%p%@?OXO{A z4z+KYRjDg(bbV7;sDi9bk|F}9sPz8%wHtNaF&~Asda|M|ifvJ} z@P&&nzr>NjT;)gUXff7NN8KSKj#rodF;`S!=ekLas^1p8@A#KusI_5(}m zDbpi9sjmUbg#Yp@@v+Z{ZB)S$+ojiGV!|Jpd2WjYL%6Y^Hg5W_esV;dKPx!D3w7GR zkr}^V0*XT z?R!_~^=Q07q4+(h)Kw_~UFZ#^lxBF=Fg>6-PZmFKJj*W5@X0Ff^^dSt&%sskxA+PoNR(C#Ni=<-9JdV0%HwjliagF~mU{?0Tv zuBVCo0qY&(l5F~yWO=E#iw%oX#R_Lkk1{sRSEud~KUUMdKIP#5XnZNz_3a%4HT#UQ z-&LZ zOK9`4%_Hj4)wwCY0sZP_UFzUY&SdaPr6g#jZFJ$8;kNN{e$sul2hM`HMis-<2rI;& zHx|harL)YD{_#z@4>KJ-x+^(R?-|&4KJ@1uN%!|7m;0;EiV6xoGJ3q+7}r`{7%@D2hYVlR8^Z(lNAYODjm2Y| zsy3Wo$^YA50!{uM_ySu$|KrI1u3*@zu+3=c5m`jg1E#Pk?mSj;Ge#G6cKLZ{g%|-~ zjI1OuRJWSiiB;C(0)OR?+gdfXE&ks-Z)N0UXtwR-wv2@GwOS=Ek2O+DCezSAI%@dh z%qgAZggV|b>x`bFhjH&q37+-z=TV{?WrHD>YJh9RbR6{rKiNU2oLzge7EW8yxaF~$ zNZ(!<8duJw1QM;;pempji|z4D^rxxwls#;*h8>B!k~@tmr>`W#d;gUKDRW5FHzM6Z za92~whQy`gbzIEpKQAr^fS-F_%%x3p22&@CkW7MbhVP^77I}EtMtj_yKrr-urgRc0 zmJ~1TcvI!=W3{vePKB3&|7&?a9wP6EWjpsCIsdea^cpV^rrmu3Bqz`GbBLjVq0Cr@ z(|@KJ^6URq76uzMX{KL+OUj4&ZEdEcHI=%)1=+$w?~}{W=gFbFTws z)-$?Ix4CvAsD~3nWi2qv>2(X+jG}Ey)+JiRX3bx&c!8zd1^8zawnT(}VnyTLD0a1o zr!uTcQ}J+}vx|F7RnI1Hf1PTMJDoc!xBD2K34`n`sO(m%dxvV$5V)w6ISBxXjJ|B6 zu1>a>_kNvKQ>y7v&{$TwdFsDHxi}lNPNS)E;Av04(`mDmGaq-JYoey1;Dpv0EGdcOpE&&>A zN7t-jN5*H^SDSHsV9+9zEPjc~0)8KbiU%gN9KRnu@-4uC-^uuv3my~Wyl=4jZ_~}L zWd9!eYH!dlnHi?dupF9z2`40MTgB5XJLAlR$vUqh@-KueZ%{*I~lX zGqN_7bdv|)FM?51J+B)d&_Cv4=I-v47e4XqeLhzW?wK_C=INgO7 zSS{*W`c{a-bL|Ae#BHkTjBf39DXjAI2l0nxjq_f1B+w2?5_YZq2MME20IL?`>Raw* z?m=G3%EQT91G>Wo0A5(Xdq-r+ewpXLRmfJeLa=hq^od|aS6DXNauO+CCF0sS`)KD6 z71ht=0ErunQF(9oo)-~txr}?y#Yd_tzuj2hl8?oqLgNLeztK&q>Xx3h%`yJxG>Tp6 zOrFO^27HSY_^vn*P>1COVX;NoF1NEo5w8Z&{N?lL*2?3)CCRWe+^@Nvx&{yt+IkutNt-zm*DNuNQ7A}?eTuszbqR8+`C0Ppzm1kom} zuNR=2jLr7^;G*aclD+6Kv0Q*fBH*LcBK;b@O@RU!tg(jCRW}Ms{5Twb*eg;$%b2MR3W;EAI86JD1=$d(GO}@#$I#qk-MwRguZ=3|XOHn3Rqj zzC0-Xj7n(H_e&WMA@eI54x2R~#etoqmOS9zl&JIKigBmYq(1y9%hXc+Z}iAJ5H)wxk0GebwMh(t8+ zpW#adXrbgRL~UTpLEiOsp@TGageUE24d6e!gdDp)`>=ux-^g)&i6UeqGBr?440SaZ zd06~T4Zr``?8ZiMdyIyt*7tg-f#5w3=$HHd2F9GyWQ2iJ!DqAyf(e%!U2WgNQ@S4W z7qA&6D6-7)ZX+~x=X+ng=b5~=18vDG;xA!)U^2enpEMPP_8%LR9+!{-l-s6iDq?6`dAxkCh%#wjbNnuGd}%MYHedyWiiU9 zNLiZPlFti0rYIKrUhOyt0RM_pHmef1MdHO=xH@1cYw)B(`O(w#JevJ2%<-;lV8Pyc z0qZeMmPE-1+KxtlJQrMU2IE!4(2b=G zE{75%6Q$L$I|M%4L_)PF2u8z7eAMIQ;840rl*m7)>e8cSR6`1^(#-jQi6^4*MggJz z*-Wg#zPDw>f8=giil6T|qZ{_dC!kR%`|4)hm){#~o3<45KHs@{B(|a%+|BOWsNURi znhI~zW-_+)6$+aF*7PT#CW}0=HX{G7fb>k0Jg#UB;J7${p}71jq5*A z%+{Cum6`|b29z{|7bAZG%LX?BhPr8Y-^_Q;1_*s|tg?r9k6kZY1gP&@5S;jqlU=RD zM?b&%My(e*;f$`@r!%2bKa1l9_TJ+_Z&7e_y!euYn1GFMg#ORhXR5Y_6FXx5UGd%A z$Q;w(XC5f8E`JO5lzLGq9@P6V>3>){J2=OcMuf0Vh@SR#%2qxqy?A;Dv$B1V(klp& zNtraK+IvwxCDWlJo*4F-= zBSFyW%*GA?`xZhJ^q&%{JM{Hk8CK#>zHtLIT8=ml<&Pt&0k!uR%Kp}W({5Jyuz^7n z$q!T6$tph(raNMx?Mbu%GLU2BQ4>tQhg$1jPSGylsp0?Nl*@LU8^QT=CpRJ?ueAAS zO)8?Xb(6!%Yf%5usqw#8KH;TIfW;Qai?4%4r^33sQ_6K;=3KDET`}&}r4igzm>NsK zHY&xWUsemho0oTMK!qCv+sONHpYIa*hwwW(Ck3Fdk^xY*t&I>LO}&+1?#M`CD_@rG z+5_MLpHsi-11i#dTW(5_9Y1gdaeF_P=jri8PTo|wNOSRi2lS2QziE%Lr10HD?{qq( z3|`U7pGt+rB)oMiA8|IN%^}f2yAWrtR2|Y9bh1dI^1z0A)_Ej82J6I=sT2szF%c%3 zZP{i}5-MrprUKWDc(PW~Jz3AOk)?_&b(1mSW<5wc1G)-+ed3$;;%A_T3~QC$tT!-D zkB|6OBT7?aua15%0X zkSbo;s%?vS$>*jZ(>j=D*`!BrMVBy(-mG_tFCeW7abFOj18sPA$Q{wegBdx2PtW-N zAXzWJ<@@V3GI=ak&2xgweJ1)0x}w@ufLIwGGS+KL*fC`Aso8!)0OqQfKv!~((bfht z!5OUdn2|I{0V&{l#IrwBb_U9!wc&TnJ`E%>Sfubz?yFp;YvUG=&&1*PKQ$^nU#lIv z-g?kepT!3GcvJMhP|@U)0r1KVHBt?P^qpu&}m_f$2Vn^jNMDe;<)?>nhGra*|ybVTWDehw1s$s|+fu&}BR%Hcdl)uaHBaadx`n;O2h$s*-r~;K#s;Jpb-3+K!HnEYVfUZ@MUhy! zkG!$R1kyV4*UI2F)~a2o-4y=6M7s)dj8<8XNzS}WJ@IdvWh55D-qVRKWV6JYkr=v< z%aR!0_w4Y_7~Wfr|0r+SS$o19+Ah1{5*67c=OPXn5R}Q(8k;i}-oZygWY}F`grRn= z#a3LXTNx&?b7KRoF~#c4$>`$9-a)IDp+aBJdnH@?kXN-ydR2l+D3E~14`_(iG820? zYVJSNz((WXSBc^N097Er@bSLvG&#RD;*e>f?OMp%yNRv z!hX@hW@B}q-~PJHF(VJmtc(MElgHrNXPO=5f}I9*2_MY#5t@NMgF|nvr&kZ$&5lv^ zz_Jf{@$_{;}r_6YLtf|DFB>7CZ9rO9}<>AAGEZTRWh z*1|wm^JM=q;~qgFr;E1~Bq!@&12jqVi>nfPG_bIsAXV5wbzr&mE z$cOGL#F-y?82JT*LNdzVhP6`vdvpV6OqOET?M26k4poxuk z43u2#LO0z9Q$1PqNL;RH6qP#`o0JG?$oL^`!DnFnEWj3mVcJuSpF=|nyI`pCR{lF# zLu(mUV6#jkQ+oeV^_(>s);}HWq14QZP?i58oLb@jCg_3Di^?Uq8gTUG z{#>~?C3-!Ldg<*`ei|W+tmZO(U!%KeY?$2o>2lndE#cb_>K{>JZ)vj18JVs5dD4KU z_X$#QiWa}YtO?xh^WX5FJ&;vZi}91fH~HnIDi_mh+797j9j9ea>yrWOg~~x!uV#>) z@xd-{Tvn2{gS=Q>zgbNDYpvwB*@nArvcnw2Ku2imQx#Ch_&Ma0e%i6V1EwAx`$-}1 z8CVq}m5^FF|H&tvYtCB7+_CC@4x7c=_(H4jnD*x5xeZ096$E(FYY%yJV84U*)u;RS_rr?5H!TM{8{9QY8yRK`@Q&)0wN9k{lY z{radR`BFS}oLBW${Xc7)4Kt64%hW#oRZkCR`}yEWx#s<4e!$4(?O02g!e{UA2^pzE z`gQO^Z(n>;M0%6}0I!~F9B@p{5D-IvZQ4P#>YG_k>~IMHPBYTdFT~c!=kFjuHf}C@ zCY=EhPSyk#;EX*z);%FxB3d!zKEK|qOc(3*_vxy>n&Bb@aGe`GjO<9dUKDrG`zQ=u zlv-vddM6NWqf9P4eeCN{8M-?R>$5wfj(E*4C3lw20vA^8Us0Phd+ahrOZhrWdaVz; z{JDCZ^&lCbD)QG`8VM@#@GI(~1%!qmK3w~oJ80nf--#xE`n?Dl&#MhW8=)Q*{OHoBP!=!$~q&EW*hwE~diD z!y|Ihoi?s7`ptoR=IE7rB7c$I=INKo`?$?)%UckUGO)htaq1{tM8l_dYwMhSkND2C zgsBV^X5`mAvPNVLD_0Q8k$zk%4T3R+Ba%XJ>@wQ)e5GX)p;m^zPtFH-@lJd zdGKxaVQcNVZypok>F@E8V~<&Bik!HC(_Y3OcX{!Rw{QAi`Eo&GSLD`DF)G4+T>|(31H zN<>8j^iL9#Ft-hvv3ErMplH=0*r+5p(XkbsA0`Q_(Uf?CXp#t5 zv!Bp#pAnVD;CcC&X4&3&rV_x)Fzy$I#E18O%g`|DuH6Ww-cXg|68MFhTX{bU6lAS- zl^~qVw|FBuWX@o=StcuIKHQa^KPo%%;s4e+qhFI}&eL@9S9KOX?}_;)Rqk98*Ox57 z24UbOfBL**W)X=%Mrh=Qgk|O5z*S@Zw3-ogUXyZfO+s>okcBIKg9t@P^Tb32h@}&G zCHE~5*QT@(XNHSGx4p>)IyU%qL;%m3oEI3*>B$E%u2Tc>B*!H5>Z` zz&+Wf-=h#F{2Y5UTg=B}Z>l>w4icc@MaP+`^7Npq8_>2!tgD=1g96Eum=gA%E#ZvC3nybea z*B)~zgNE25YK$dD-P?g_OHVpnz+g|E~=8RlZ<%RrW%0vib z(_;>p)fdTkbGgA}CY7^jXIm~{Tt7TIcCUv8@3{PRKBDx&bx^ZsWpKz?|7?c%xe1Ce zPGle$foLUm1}2bp`2Q`LWXlxhI1%DG!vR0Gk0K9G1n5xzJ-X(c|A9sK@$TPmzBM2H zZ|>g6)A&C9>-Yd$iB;mGj0KuTQdr$bS&!Z!magawr}k_t0#?b!qU~F7FU@K;!q%&} zc_8=sQ&EKtGmpxDN$O>>gsxQ*f_M?e2Rswuwn9Pb}A~rji61Lf{ zn&-;>(l83!F-erg#&KG+Q*EBXuXqA;=3#;afX%}8b5?RXhwD~}h*zHL~wDVtdYQYVKy7P_K+!|P2|nFLuO!OS>{3* zNb*zh7~0MOPSII_#5jrW$F=_VUtll>OP6ujIK?Lu%i^eV-of%LCSC^1D2M1V`|6l- zUOVtSXBkfZ)ZSPCSpgG24VAHj-J3~%)4A?|oJSPw2)4$rI;9Q%e1Ri@_d8IGiTL9( z^T*@6ru#Pz9v4VF9rTruP{!|)>hE6Da4hPrwZ8k|>$EJtPMIXB3@AwK3x>LW0)|^` z{Dn~QtmHR_H|wv7Ta-mu?}=3kWSXwC`>$xINKJol%#R8BR=8$~Lq+|l2PefuJH0)UqxZ|{yrVB00ZO}&iazmv&t zE{-*iSuvUhriR7c(T{J8P3Cls%CJtiy6zhsL|L`at9khwCxk=d7>&xXPm^UNro)l~ z1HQa}6sbn@iwzYB49H5|)(7t0hVI*^&_i2a@r+jAD`CUEKPLz=o9h1!w&1J=KJ}QU z1!Vty3DCORBwz3pJ;++S`*#vg zt@r%w+K$kmlx9t)-o$iXj~7;9v4fHj-WBFInUqgW)qv6C$r4O*IbU01Bt2$sz_28@oGm4w4!EYUipVn_9nvq? zAwI9P946eq3)P_`gRT@(;oqa@Y)M5F|fT4YgFY{gwDQAsn z>r=WoQGSG7U{N<26Y!b$)&nS+mq7(fsgut$M z_VJG`)MR5JPxdsjg$xO(gmLo+d=I-Cc_xV-B+{{bx=z5k?!2mkZ)QIVwW?98-)4Y{ z;IDO39wjmP8(da&+WD`X8jgAi{TVRU8R8GIe1O@&aA;MvVu;KMFNFJpy;A~bzi)mo z`6k_wkcVOd=kV@_O(t2LUNZR0VyUznG85T^ioV_2#5?b~$iPWl%STzRA2)|YQ1AB9 z09c*_>O7tuQo*kd9cwclOkfz9e__vTafGDsF@~3B=}lJUA`?EPGqM#xo#35(vyCL( zxSFahc@X#HTa=t2feEkMJfkkr!vVfF&y`zmd84gdtl2J>v5&$3VsBGh8pIYds zE^kOtV>wT6tV7}yN$z}ukkr^R#S@Euz^IibdC{TNhYV{*Q|;BNoSH{_ z&h*;svj702QrghS9+?!FeE;|*>$AWWpMSWfX4rvF@U=V5@XV5lwA5nd26JF&L&-a_aDQc~FL-Nc3)uD2xkJ3@$u zF0N8dVeGiKwD^N>+?a<2eIBLJ5aM%4VwXEF9-FenaZF`mNi`5^oy$x?0%NF+^QGk?k zaHi?b;Oic^M^!4nNkg}>sK-bD^RYnx9A%tvau>#qV~s2i&l~%0F!69S(i9O8Tf8j- ztWBC!)ZE)z8W~n?+^3mZRL|m#X~)id{;FW)x#&X@qPsPZ3%S8~f$Zj4d`BfDF?=;% zcbJ|7Y>WhlMx+*gP?;!vM2yHm>fMc#VYxO#3gsbG%Usy3O7F zkQ(_)h@n$0b#5Ww<-^AgriuDEkNk4xBz<*iQ+jYL`Pr(qWei_(swPDbV7}W8?e&58 zURSGn19L63(_eS24229T>Z+`=Y`IzoLfLyICF`n_=D*|aX0UMxU>t0&7FpY%t71~IuKu+Q`7A3T_1kyl$ zU*lQ?3piD{*^e{T!gSH%fu5rP!dN2XbnT@0i|n<-F08j-cAnj1@F{@^$~te% zo2wQ`Bjl$z{qI-cJk`p=Bu`k|w?_t^ORB5usQ59Gq05LEzWTnfc0>$MZReg167(G1 zKQuLo80r>j8R07_H^s|*D=qmpFHBPP|MLPweR4~*jPR3uGxe4k?TzR`-g_mBSq;V- zS!!s*Y(!uVv*J*PM$pWousFb#g>8oe0WL*8vd0zb@u9La{!Hq_w37=vg1|6M+cXBnz@$Sa-NFFSNO4#SQn4h)s$&6$ET5C=O) ziZ^$G?j|2$fj_3Nr%t5dn(1FsP%e>8?va3nS~ByiUbcbjRLQ07T0ewnE;>Q;n*S!4 zvVnKSAP#YsiNtSfVpR3qgL1c!ah1trnH?af-8)l%C#Fh;@w%iqoSNDcWvqyaC2Jjo zx}^duBcfp($;T$P^@LvnS4M}>z*5~;zRR)!MF;NK_1^KJ-w{{b^_^jXh^wh-l(I(e z_%0#Am4#w%7y{tlX9w92XB3eft>(4hRy!@bZiOPFN&L75v>Yc86JHH7Zx(2vKm0fy zZ;6BSHGcalzQRQ#A=c8FX%R?6ggWWf{Ve+_<-6nV86g_&ipo@;r62yEs2?kR|8%)1 zlZ5N&6x8&?O$a_p-;=(X%dog$!T$mQIzoO7`ZX+`Q4QIHS>>>TX;B{1Yfei+eNc9M z%%4cL%MgzRiU_vA{w}K`75o>4zHYfq$j*nF)x@u9==WhGxNuuP`_DUv6|LTm)igb;Hqbo>cSxU;fUNM~Zd5%=p-x#Q{25 z9R2iJcCKDzAr}{f4wYW|Y2V1tUXe@=?^CIhv&#Q8zQPc*HW7?3)qCghXe}YD#gIKS;VuO9ik++; zW0?r)-@UEaIt-q_ttk`+?&k^j_i2u~pZle3T#dc0ymA0Lp}z0|^cN%+kJ%zE13JKS z6-ipcGx3Ni1p46H0z>l*i-6n$%C~#EmrORLt6x8HA;&ggG0A?BDgGF&;4Hr$jrE=^ z+SO3XdN~@60Gb(}mFgGG$Jny;)t(u6_q#hNaMMJ0(CUP8=zQKXV#|SCqAAZu(JkCk zA`5IyDCj+%HmGiJOemWIxZpTqHnH&rN82A`BaL!R$%~r|sdUh^$02QTdyua;`?d-3|>k zQa<|#d?r=gAlp>e68&h6hl2Q|i_HvOT(auknziSR*y(1T^OS_a^z+OaNcuWTw=C3e zx!#9$_W0$R9UHAQdS%EddCSOOODpC#u!&v6&P-D#F5EhZOleatl8-H>EaOPo38i1F zGZP0lsWJUr>}w0tJML10=AEewY299b6GKDTR|9DwHsGOhm!h}XWwHuNJ$4riaq11{*quzua^b^e{zBn4M4iNVVIxT z?#P|ufIwH;oQLP*L_trdKZ_#Q84L1F$>7h8|G_j_lBbLRw9x+sz8GH_vse)k^|lv6 zd5`4q`896Tb7^**i@)jTieOKey0*UdbTZK83}R%AK(J4wVX9>y+XIrfdTa$;Pcg2j zGghQJto=hOy&`l;MW*dYDq3+Fzt%C_>zc=F6P}cXm0>emRdmO5hqOxK=L#BJG6X;C z!c@a;pIMYYdmsXYu;FvIkkxVSZGAt!I8Ww1W#&gxZC`9{md5XbP^w{Z_)lDfi^}EJ z`R+hD;a{-~$c`}jHy!ob)s&%Ea4^z|5`Bvc>fc)3%MZ@fg%mAVO~HHs|Jfj)6wacy z>s)Cf1ycc_t2Urv9AtW4oPg2;BXAHsuqhLv{UJxeSYk8NKT^*46k`iZ7tD*;zeUL%fN_FI5gN)v`bTi4|d5^QZtlQ_w%)RfN6n4ZOE3y z2; z*;o_Xo_fnF(3k-WPunLy{HGhE;Z}lYN7AC2NOW)ApQfUb*y%7C*?OanMoYsb%1Yc9 z=#D^+eaToTZYa4bQJZe$J>K7+fBOu2AtI8Q;!n~4mdDW5N}W#t2tUgCoj(`vm9Lu>3SjKJU9ca?j%8M*td)eO=)$1soL-F!}46HB) znPU`_VaZ$)=2L#VuVIc5Ts%L2dSti^r<*N(+!uta$!BYzYKs$qJxAq{J-4P8f?%xW zXs$zz>4lJ-_eh;-g&l^bO6vE2>JYetFl0bXK$nOWy%006XfSP@9RR|+e;fb~2SXE@v+MjVLy@ly zw`x@k?^|2{jBp-wC=Kh8ZCkp`$_)$|hmqxQ^$b5P27tP8MJ34nQ_<&{Oj7Yp;_JP7 zHH{2EPRTSropg1I=e+tD(WRiHJs7`rprgAlGfyrc`$QS~n3K$oXiQ7eQcbemLD#AG zF;L7Y3?s$xm5SKMybd(|^?IXySVNzE?iJPL^Xe4H{O0-4vTiQ{I#M=k_RdQpftNX~ zzdSu)RePgrg-aI4OU7EfZ&cMCb%I7avmX4q{PEa2joXk_zYL2IBLCg*@rItFz`Yu$ zuJCR~F}-s*Jx%>qX+E6xG+)im4RGj^9HBQDVo!PKgsrS#i!&7&F*l$9=z~5NRiJ=e z+W#wFMUs;c_+5-%H9H%3y6@(6$j2{ytSPMiI6rMJf-q6_~1hEMFaVr zoeIvNdBNqrrI}Bl0HQh`B_@7P_^D2@*^rkk0HZ)+)DMGcrc(2W9lu7e-}BWK32(ns z{@i}6$+MN@8_!+eUmvMV4G~5rlw1A8>v)AB1KGo^E2lHOH-V`0l^R0XY^q!rH;pX7 z<21Td=Kt((oIkIJ$1E!TCwEfc;6-#&o_gcNl`|{)=M+>e*C5mkZq0F44BxfWnGl82 zcT0x8r*rLC5Z0c|IE zS-wjlbZuY3Xk|3v&g!@+jStud4{vQIpaB#;Jk4GCFW4d->I6=^r=N`$S+HTGM*mDBUjO-Y}Q?w{wey4Afsu5GtueGoRoRUyW;!UQE zC*Li^1=_;KbrhL9x`Cpv5%Q5BLo6W;y!$#|vLajQHI5+?dvWWVR?sH7f99LJm1lTs zA+ObFcBQVgL-v`P$dOKoU20^qim;6?JD-O)-!ZOeQY$~!KB7H`Sfmc`$KuC@qb>g7 z!eZ;7Ix9!1($^$|5zDccGiwsb1Ww}=lWOuWsN-<1>0`Id36hp_ne+YHP4~9@hF&&E zklz{r3LCa|H~@y}eA-Kd40~+fL`mmsW#l&4b4FK6C?1DhG!lo2w^6tJmy{Agg68hD z77#MRS2Y9Dl>N&ohkbknk>NYPZiY*%6cSw21blRbzw|L8JMO|N z9me7b@Q3}K@^2ktCqd~7Mm+@s28>ZXqi*nrG1FAl1jO&y7WEfBT}lev+R*IluaTj3 zlk%l0RAtND1s~EK((3&V_N)_$v=fL(iVVwMhfRFC8f0*|A-PoR3Tu^djA&c*IWW$DE3-!-30<==?Co}hs zsb&0`c?Q-8E-DS%zzK^Pgc9O=lN!2G@UjO-U{?+w5T{KTOuGAt0Th6Rn>4_x>E>hJ zeZ_;%ri2F5p5R=%h7>j>Xcc9wKUU`&)6Xm4pUq#S$8R8QF%x8KQwPc5BT2}6zj{~g zO!%&UrLvLsopXm$^RtqW+X_O~yq80uckZ!cz~_L8J|HnAMz4P8UjVyPWCVvtZgb|A z)Q>GiH*JxjK;f4;_g0v2?;1ioB;nKJ7sn`P+gis=r)U3{$b51C?F=QU?%^~wI!D>snmA65wKH9c9-A=-TLb*2#_^ee-n`Ukr&%`ahk zhv#tP;Yl~qJl;b^e~MwJeVs&LmBzxx*hTH84Fyi_8b{-$qsB&QDaMYB7lXNbC}~Cw zb(0zv{NyKvFa4eKS9-^}4~~ozLgRj9YIZQfbXPR{IPdgmgMG6JV`iA55@(9^$H#%^ zVa^f%ja88KWYC_{iD#8iuf8A2lvn@HVWTMkVy|pvn5dv1!{+%6>b~uZ8-^!QU*5d! z9?7}6eHB(UGHayrRko?ne!~>sTXr_v3n;4hWjXVsM@dyi#`|s@BwI`~{0fd~Vp0B~ z(I4p^xy%b>!;SRX4SMlpr|mxLP+V`P{G1KjguuO$QFCzds(DYGc-(%VBBX`@-`}&U zLc4`-KaGM0lk^!n*F>J03?lDW-ljFZ(>V)_r=n(O3}U>aoZD;tHo`%s^5*Sd=h|;Q zyfuwwwcp+cKsKJI2?5YL>1F8rrPmiEZimtZ1}Eq*MR$YOxh(pPVbIkb8ShB!OnYXu z2F$dJPe5yT4Rs9hsbCZ*JrW(Sr^{>T{K>d1Lt4lNAC;rwc@QaE{fNURpF2*}pnM9s zo{0zR=_(ICvefh$o7>^rG{bXW9pMfQUm>>aqgQCOdOmsX|FZH>MwQT-)^Dkn+Ik0n zCt>|#A(b!Q%{nG9s=Q@%VCo7j_Yk=AUBWi!WDqtQ@sDPE^{ZNVG=Ch2|Bcm z02vzC23ny95X^Xj>HJL?U*$AAy(noa32#-gt2aQHa9zcm8S4iemRO9f)9+7i~#p}P$#UuCKnDRp*C0jJ)4f1vk*FyqRfGrYWYYojc`kc^BocCS6E+ z;tD#S^IpTS%qh+f1-}%BRjKL!QN5W(t>^;fwWuQJ{QTW8D?ms!u;QOF8$un&yd*Zp z3y5?GwZDIL&LQ7wHR0BC=oSG#&pvGUdB)VV5%4`@J?FbPC5C*M&Krr;X{*e;_!D{OK#(jGfsog+|X8OrxRANW<&hX;f7BSli~)~RVw94Yt-0) zeq`bBLkKS8t=;auoTJ1VBR1fqdbY~(5aFGbK|YS|`Sx?hiKS`m^ix+x_@+trm&>5; zMMa^$FfNdN?!VX*!5pEvYYYze&V(u<)4B&DJYMJ5J!Pwu#{XIopuSbi*3ti`wUaS8 z{|J1TOKT}wlxM}o6DhP8TpA?HeSoDku;zcGt>G=6&ca902`S&KAvB}Xs3E8!gZh}d z7#j+6l!0OqH)qd;FSl0;VczMmx#R9v8FH09AP8$5EzJBC98I3YD1A3R|Sknxl2hWJPmd);haRHU~* z(K1T{Z3dk5;WQ?Nmn9o~Ln~>%Yp_dkl!iWpV|PmhkB|s#!%{6!w4ww2F6UN@ z4*mM%fEUt8GtFL#BaLJQy{rJUQLV^5bAS0WlR3w4B~(7CF%s&|Bi%rS$R24YQ6nT} z#D;kXnX|%~%28YwfV1S0fLxOk}RjEu= zIsP3f<5-HY48W{Fh8@4QFPY5JjC^N0G~SUExvwdkCXc5VKD947=7YGCkW#JKL=0!$ zAdHRjv;#zDk40;_BxGTa3P*^dH6qn?IWrIX({_wV)f7-h;>R_PxoHV;f2gT$z!1gU zRz5w(@d1q<6uq0AxEBM&PC)(a%f~AvLSm784Ie|}j&iJvp#3nHiwr;{f<0wRCkY^B zFPf0Vfn>&kyJmV4OJnp7P>w>FH1oyUqX<;4lOCc%sN zkt(}$R7)W9BQ-pLz}S3D2w3~M4G43^m~pb!Enz=IVb>}waBhLoGtAEEm*khq1CGw&r~^L zYd=Zaz{_b_qd$@ZkiZP?@YKX3kh{ZZn?3D3-a*b8|bV3LdS^wNyi z;r%9=urfJT+g3|AtZdF^-H0GeEv+{(2vCIH@)!YqWPXel`g2^BFagd5b(HluR0@xw zRicb#6!UUAbmravmQj!1Rr@@qJF+01!0m!;5{5{`K@_%^RVSiiO(+0=vgg2OokI9T z4L~?H%C0-j8gY9)os?4&6E8z)FgHaFb(p&g5P3_~+e$?%(;;Yo;!9iq$bAt2y1XG+jr~&Xa8?nO#}WA*6+^`nh8C zIcZiP>{*eLJ4n{Z8qd3iBD4?$*1?@=K}R4D-t&$bw_fpw)tD;|UgDMC_aRtPEoz|? z3m@dZcZiC?rKJ7A?>ffy4)II{W(OR2GQ>#SrYxsba;nwHzIE5n;cHQZpqp}QB!fS0dOp<1beA%omz z9QXnir(n4mo78C-69t$Onhm_W7wB`f6HL<-@!Q~mum1rqD@k56ha8%G%18_0;OG+^ zQ&m2C?Di#?jd>2>@PQP(rn2)7?~2Sbz6{1mD-^!On3>?MqGUb&p#kETzLEwDsf&WU zcyDr#Yv50feVY55m@w#2W*3cliQ==B>!|2ns?30BG&@$|T+#;r*=(FcO8T*le^mU3 zG8?F0W>Wcq0GS-Q<~WWtLR~r}Mq<_4eBr8wlGI!njnm|T3O4rk$v6Jn%6oX`ysmF5 zp=ZRvy{9Qgp1zd7B?XC`sqpY9B@|E=a}gl0$HnST;`|3v#&o;~(AiC(p28beWIV5y zE9Q>87j)1ZggKw)U&7zcTJRGkwPsYTpyFDN&^|(Z$v0k$Q~KZ$fUllSCV@x?|GRA>Gs-xk z%%v7d42?<>;nkeM2EdnJ?ph9r#CULv+`|Jd4)2G3i;a4cZFr35PG)$4ep}tQsjE=y zf!-<{dRGSOTSCBku(wD!ym`bgB}Iu4BznUJ_H#!G^DfFtY=p-&C(15>5W7_>+na9x zpxcn5s$Hf);F{Lr2|ZET(!eByvxX9p24Zhjxu0-9>~PeR+Q%qQ%ZRAf?y{Z&YIZ*| zkz6fS?}w!6nwx7(40HElqVy7gG~yI?B|m%R4@lN$#U;q0ChFCrDK{p_mJD>Yhm-_I zJRHC+^<6Jh1X%OO1Y|lMDRLx#NW+HY7+>&>WH?m^3L<&F{eQ?6VLotkV@QK>lwRa}X$g?8wlXx9GP zbWX7xEuX?>j;_Dkm6JMPrXFf6dOCuu4Du6&H8YQm?>L`eCS-G}W_SH;vfxdAXh8>cRVKFm2+8JR$B4^9p{h7+(RCzXpieI5PT$i!pxT)5!1>5@VdLmB+E8S8Ms9)<(zSNd^82G`m&fDKRIFK}>~Kd4SY z2<(tQ{}hTY>F}tM?eRZbHbX%Tx3uH`>Pa%ZqgrJ#32?-j6Ai#UYbriU&^I14n5%JY z4!p4!S8CbkeQJH{G+k3Hat|u2AULob1jZO)4FEhD{{r5B*7eWw>^?q|)w$)zm|~zc z0L`o|dkwhE2hQ(tvP##(vQ-b|$Uf61ey;|455Bru6l7UBm>v)comXjlF#KnVmz+SYp9eSNe^xJxphKZqVn zT;}wtQvWQH^zf3&mxfyCPj@ZDoAIgfag9eZ6meC^#$#RS%WbK$UcYEde2sU`%-zQNBltF5ZUeVE=5}%+_kVU4z)QE6!I<_qB zB+q#x*}LDWX)-e2j8jGr?#=wDv3;|v`B z@5C{q<2fC=a4wO%jNvWuoo3&ZcLl!t1F_g)dRuIhHA-~dKy(r}&F;hRpTar0NymuZ z5eb?R2Esv5ETOw)9e>VNiJOkuK_>9zpJE|(Z1u-A%V zD1}ysai+62?xC9?LYh2bMAP5K)-nck<7aO3)|Z+N&PtEYj!rs!_^rqeMkz3N4Ka6+ zB10*)@1)>SIsf=njkxaSxdeGgNvTy~s1VkM8c6DDXmFEYN@9klg{EbjHXcB02lC2F z%Szkw? zNY&>_LrHo7n&&z8cetWXd4HQYXxcl1$9v;1iU^qwQnwh2u3ORF*meAoMZ=e&iq-}L zTHmB_mL7f*{ta{GQf-6)jGXEjA|0PbJvYMgBtc$)+_0&(&8CsI>bUh#z8gNLn47@i z5K0!WfkbTs zBuHRbsA`HT{vo+0PhScWR{f4*!Md3jP!~WMm9LFbuUB-xO2Aik`f}skHU*r?nE_8p z*|1tvmuVDT`iHEJ^%QayBl$jQ$Cc0CB|-1Hj8bJ7gYfjF=BUM3&nceA#=2hf*myYq zJyOA65EOz|;(8yf^G=k@gbNeM7VaZ==(}4jqX zQ{P5WvC0r#XAjkS=(L}fkiv*U;Cd6NAx=f|h@QWC7HBVYccdJqjM#=?PG!yQ$IEx( z^j!O$=K>cb8~;=UdG6_UQ1~fWVZRJ-u4Bpv) ziBBI%86K+c-Mns&>xpTFu~VAI0nC}N5<=ISnXCRi@P=1kcYR|%p;UqfIRgU{OY_qm zowHTT7U`O>^rV+eciJfxF{)JwE=g6ke#*0=)NSxB_W!yvDt!7Ll6p)(&{4zI!+i5k zYES$c@4C3HP<)opEzjUJnJO#u4w>_#+#s;nV~bHOaY(TNlB?thq53ADKn4FdM@C2< z0U;hC(Mq(*V`U9yMfKafYm^5q0y!(DKOW8m`!iXw=eM6%D59sHiDWV45wm!jONX?6 zBKr7Fs{$aw;X{({_R|5ICHw1L$_xVITszef&F++9ZC!5_q!#&mm|Lq4zS*S|hWgR9 zr1~?&e_f(-VU1!k?-t4jyoETxzSL$}$~X9Kb72+yaz_*P6%@ErlCitgYB8_c3@v_53-y&^uT5 zbjl^|f`Fls$Um-hmC&DGs$iF6b6NwHNLXQ(1ub_k&tZ@Ty9S@Ve4ZN5%sAVCPO|Di zRIO7VHa4QSD%>&nw%LL~D_^e?(<{jWmOG85F@7Wv>Z3PPNPBdW>}iX*X|~|MD|;~8 zN!sv@_8#+`a{|raB1bjON5ZP=H#}os`OuDt5WvM!Z>?j`)OkF2&2}Um*f< zLPqV178tucAhs=bzCeyccWN;>ut7rq$b3h(p z*ww0D!=C56IK${!ZKsNrw>I7ma#WpTX(6RcWXcd?eY7&A`de%9T-FY-%;05jE3ET9} z7mLvG4|__JO|gvN+49?5KMW?!Q=FQva`$qzD;y^uDA7<*vl<6%$p>T;Ql4WQDrV?7 z<<2}1;$#J3H?dwqw;i4GaEiCP8|(14MYpdMVr3h--7lo~nZU7(KN+}*m85F5`r#kCqTq?DyE3t7=%=WKQP@bx;V^k@ZAS95$ zY&_@Rs$6?e3(Zw4l9=|IyguwbmvR8zDtUNXyPy`CBh3Nq6{{2%btPOylNxDVk zreTv$zX?mzkdZqSN$~8jZw=Yp5)m3pUZvrSUKM)p7aRXg6~B^U2aM~YxR-45qqtwW zCao%$|8vUTvC-7W+r{Cr=H8h>;cCZhBU%7!mq?6rVY)s`TJDuZOd*ZnX1?2uE}ggY z1rC17yT=cB!q0FL!t34I_5t7>d!l2%dnTo-rXW%*%=wHlxb z9Uz_AJkGW?W!NaMcs-!k&J@j)>;|v~7wskZD8${L>KReA^kuF2w-Tq2Vp_$vw1GS1 z+Q(PI*@U9<7rk;*rg3UOtmjl|DFsCw#yU@dP9^S^o4BTxU(*ru1HaRz^TDwp-N

(0(C z4!yXD*dQEK>_;f-!rjkyPX!nIrS72+5xih}{{cq;?bwwUr9p;v-yE>3QXcQ?6yzf+ zTh(L1_K(BeU4}j#dT1VJI-hkZA@@zV)H$65KAUwk`S5EnRU6StM;TC>y7#vvxe(I38I8UNC4!twhp zhc?!lNy+aVCm2=Q4l;hew3`94c9Dg!pk^I>R3u<`FhaK)Z>Vh5EmUC9u~Qeu^qu%@la z(DiMwK}0cc$cN>|1v{T5!ona~)li?MR=qkls}fIYFDKlt^pD<$83td4J|FA-D7Qn{ zAjpCDf6qh0B^dT*Z$($T2Y7l$*TwVMX$h>2Q^j!tZo86y zp3Zu76o8g#NIgFrWn6g5rk+ChltH5afUEwLN<|XYWrhvZ(-vZ3wojT{2 z`FJs9k0syQv_3?Q25o(W7k7V(&nlC^g^nw1ydZq+v)J{$yb(FjzCj4~E=f)Zd^7h; zE%g^QC%K|D{m9bxhbDk1;`sR6)Ek-FX<%uMyZ^6;#6GeAuqKnm@qFmNr&GDvsjmNe z=}xxywP4fhcdE{OafzJG8!($uz+Bs;&75^8;noL8E}IX~y|Nnb=Ik9dy_}eBD~B(| zfdbi83ze(7A&al1GJ@0kZfW{#u(vrgzJ~>tlLKx*9}X~SVwbSx zVez5Y?yzYV&cgT8@j6F9p7-H?NIljfCo^qK{9tqom4>0W$l0<_bKo+}iBAq83c@%M z=fxgz&b zFPwiUE4=oh!=P4r!oUd+9!qpsg{HUP5dx_t4#GM$rK>g)6H4>!8dPF9ahu8EtNr@S zWk31(NJ7dh93n>W!10fG0%$n}w<9$&Bh>M%f3RNwohpTX^P1I-?R(^pb}473_rKms z*Z%#Vm@<$z7_s(q(oqtIrsi@Z-kNB?asaWgbpi`4VC{G=;dv|k?|9-58X3h9-bY|L zm8kfWEqjAP+9~WDW2prY!rAst5!x!AkQ@!IgytJREST7e)myxeBT?F7?iOt1ixC_@ zjAdILy=_?V64JH>a^L~t4_2WqPSlr;97=syrqSBMB`SD(8JRE(f7f=L)ppARbW`TD?8||CQ=j>9 zcGPGw^%ke}b~Z|H9Qzf2m)1s16TuTn-_|3;mlt<}^La$$gsqw6p2?FIXM%^xWhlg~ zD|VfzWZvGy{Fle+W~ifwOZY`qvcx5Ac_YixS8vyERw@1Xe?e}PlhllaP=_3dVdk59 z5!}BdGe$IE%X>Q`<*f0+bJE;Nbx8|<2fdIiVW%38SAoNj;D<7u&^uJ>OQXURsmsG1S(d&NQ@y-U`eew^IbK(;mB< z^?J%g*y;D8Ps`K!RMZy*!#bmaRn)qWzR?LacgYdB z?g{mpiHkZ7l1U(byCzSM1(Q#uR*gvOfv?r}0V|6*W>Hjb)369MV?}AarJaB+B{z|M0(s#fI zdV&z@mchM-R#xR~yXi$bvb){o_5mR_meDVrPzSE5>Yh)%txBSk%IBx(F@jcmT3cU( zVs_>f6kR`AirjuTM;0@oN>w4Bn(JBdjq|ici@Y=0ZOh45U4?!|Y?Ql$9be1tKSpRk zR;)sxiYjmfRvzy)8~sp*&|pBd_Ni~3^K}nN<@OySG!KGVI8anG7i3qI@x@^Nn6T@Y~fKu1*0x#1feJgj(i+gxVtAn;)m{z=F}hm#>SiOyG52me)hnq4Aas^lkI1{)@6P zrXsxfd-2_`FJ3cUYAcpv@o;jnhKy*UU2KM7Hpc&!h>Z6LY~{-A>54l49EP06b*tu(j^qV`i?K^ z-DcTF0(fOtuZ|o42A>?_ijr6Tceq-z*w^}M>tFK9o;JLKK>hs5)-)d0{fxLwkw?`VyHgSu$ak|8i zP+fF{Eg_(DWhi9prg-dp)dZX$;dCD>K)E{5bznD;cVfjz zi@1DR9etvu-zGBrrP?LDItv|0{?%!mk3CdmCK3z3QFr85V8KE|^*~u9lLTKK(h}tK zE8v4ePJ(ur0evKg>ZCG!4|0n*^b?vBg3ncq9F=j?M{R$yXq}s#$;mdJ{dcJ9!%m6; zMYb>__aO^akJv-1W0S)m&dN%OjwC$TfNHT?Nx2W0abMzW$(Fg(s4^fgU#F(shCEyK zB;N{rLE%8BD_L8`DfNi?!w(aNN={O<7&>OnkavEi9nh@0^-ni3XE||t)H=^$21Ztq z_(&THM9#&!h80Qh9}Yv|Vu@Lga~v!#m>rj5Fa*4QyvONZXZ0LN`f7O8{^q%zL=ppf zrvH@l%T*rM^8*Qlcq3`#+Eb9X(V;id91pbMz~^AeiEsl0w_Y(z37Dvrsc)7vq`8l( zDU-Ajq8>!0x;camX1lyakfgR~NBM}DRD1&ShV7@JaL;jPxI4sMA&Rmww?N>Z)O~0& zP9bJCj)_iP5~-`Bel&GJ-WWaSrFb1dP{*&O*4JanpfYA5BRf|$VZ2>YQ#ein9>*

ofH%@*^6$Mo>$~0yAMLad6sqn1QV8)oT;MHL_+q5F#TsLp8KDP|j<2Fgq@d1w8xD=HsnO?5EXV@5&t4NR zoqZASn6-2{Oyxb&1bLJreD#V?7T!@mfaFTfPY8&sxYK%~17fH6kFq>n?Rrk$5SNZ0 zXh_eGl6LP|2K#QW$g>Ty?B}oxVk%up4iQFz$p42%eV^o+O_AVJ`N3g1gU(@HEQ-B1 zCjjYr%e4*uX1S-5tJ?5i%K_6Gx%ODwXebtf^h6PBf^u=C!zbZ!A4&<#0Pp3|@ zf~0SIl(BG?>Wk3t{`?>$wC92j;b-39Waa4d%0ZJn5mV@eIHt)=?=SauF4*&k?K&o4 z##k_!Cve>`b71u1YM~w3TMx*Cy{V?t{I;s(4jg1$F=d@je9sL?P|EO4nxSnCO)(TI z{@n34C^!!Y6?^&`@a0Yf44)~NJfCc8Sgn*Drkp+ldu~gC=+#w=(#d)QlK`{+{I*|3lu}aBC!->{uPqk2 zWqUrh?UwuNe(}q(v3`BV9(<-|eC}qOnHgZl)tyAvu_Ts}3n=x^;1tgY*{DpRelB^K zC9FG%FJJ@vwfYD}&W0SHa>{e#73=RQ$`?N&K(rs0wOf-!k;ixY3V6`kE(mRJRdsBv9qgzM?(p~Ddsu9fl%3?8^m&Mkdzfr6_HBhPbu*6ZJ`Wr^cN%P?psLop z9}K{~mpl?qW_{i#&i{4$;FaB8_ zN%Ig9__1w!8CDIa%ka?HqWqZCf&bJzTO2FmB5|Dq6Yh zfcU#&UsC!$6sAq$>x&vaUnnm5|Fgozsu`H*qk8G9ZP}$~^R}%^7VL1H2(Nv8P9?sG z@4#%^Ug&~6hWoFrf3|>q!^W=U7;3IHT=hZB9*S|g|Iv50v()ttQw;W}PT0y-av!5g zxZ}RmqeXkl`)Pm?sjAkvbFKW4Eh2PMMDjq$`}Ma-`n44m=q@^1bIZf3Nu#*(eA)&* zFK1@C>cHhKb1X9y}dG%o2^)#{<=R@V^s9|={_MELv)p5zPCiJ+sbs6gl zf!#%P8}8r5HRX5TCpQ>wH3-k|wd11a=hVEK>~*ZlLOyRj4LLatTsevIw>zEPL@q!) zz08_kr_r%n2vtGdrVDnpi{YYKt4RHRJAb1#tA#ndM=n)ktfB3`FW&l+(#g$Gv z@V#IxMxCu~KM%DbpwdbvkDHTBa+fhk%M;}kGh*9^_KvfN%c^bS@V=o7;n`^ zzzMU^e|yvFQZ|}|65Iv8BFLo$SO@U;C3tnzCpYyZM{Dr&;tplz6h2J}d;dMSCc4QD z)x61zYwV?Y=fu5@x8s09+GC=vqBg5pG|cI!H0YK%m(n`oS)6$LX-$g%LnIr&OW8$> zr*-4hW#`QBAzI7U`M>&R1sP?8-`XS;cVTg<-IQKOc9pAsXHoE0@4EAk>CmF}Az1rHOVmC;`58 z=1MY}mD~#@V13c8U`!`Ym_)2jp^I<4kddp1=aMO=0NyJIBQrFr{V3Wd*h)8QU< zh`;qQ8OwWQe@=W^C3WkSxxOp)mAXG)X~Jsk&MWwMA1QoA>zpJ#`_5RSHN>UX5u|{p zqWq-YdB;d`s&HVNiFfdRrh-d(bDJOPs$d+CbSg6pWWnOv*fbAuz7JwL0rtvA@=pZu zfPE$IA(z8YrgUcKs7SMM36i5gvY&#W3LYLSd_syJa=OvP$KOktA?4LzLsY`@!(nMQx~_}j7oUIW{AP?%TevsaJurK ztzCyv^$4rc^4UKbvx79Gxly&EVetI zRuKgG!@N{I2AQ)t2l`Ws$h()Z5Il-&f=-Z&;3?jq8pm;-+@@;w50ee{76HOMEdc5S zHmZt|qRDU)IY7kCmrwddxYZsb)|+;SkyNI8>yB#b7G9}b0^SflhtCP?g5-Js==;J+ zob&GOggY$$$SM3Qpk*R==G^;3snRf_^*u#Zu2%SgOz1<@vd47`u&i2`Hl0zUaDJgG ztkock+eC-jK=Cv4w?^iAw^Am}p9-2s@x~rs!LEQ~eV+^9YBe+vRsgqC*S1=t`^QYtCMB zyL&BBx*l=ZX2z->W@|BucJ6()W|hYznQ+zp#hF`&QzQHR41NQu1_Bi74;nIBaZO)9 zqE~`K+{fbZ`RH4(2kd0sbAJB~7tn!?mL6A-@pvl@C4`ZOt+};7#N>2X-&E)U%))Lv z?lw2>lydUAfj=;9^@o({yF5Mh5At%ID23e2K>GPRWPJH&f^PQ>*l}Rg&z7DO8&k#| zUP}$r{=57h8myl!PlgALUnV;8eL4P^O(l}VtsC3pQHFTS6!X;9S5VaV=AY% z9(q*y^6mWp)l%kh6rho87`XvonOEJ7TRn_i4`T;b_eWW|v0P=b$#i0SB>nTFi`4x| z7Zw(f38Dua37nrFu8)q6j`_d{))h{l2MIbl5+ymb*EPR_U!@cbEVKd?o7%=hS;4=? znRA~x?`C7eR|y2sh8iR;d1UVXLR0W_U3Lkiw?H#r7$|E7Si`)fWOJYxZ~tav23#FO zW1crXLz*`Z1hYIl2NDGAY36ey43#%3j0ja1;8wp&$f#>nf7=F8$?SJ^327neOZs5P zVdTmm(~)rkyhcCKUr^XZSr`XU9RC5bn}$)}ldZOj_)Vv>G0t>CXnsyoDvC;4eynFq zjW0K#LQU9G=EB4UJbcKjx(5W?N|6GBlpR6#cv#BAtJ0a_H=bkF$ABPVMq>Z-vpR+R*B7J>TUXRirEvhrAYbcvUQDu8-LfXn25G}%?dpj?`GXMukC zIB8XYJU7G)Ph%zYiB32{jqUs^;Gz%Tr20(h*F_TX3lX}zE{}pigRZ7a9okL%)^3Qs z#|x!udlXk68HOX0#p!$h4peH&;`{GAPM2?61HGpOtXHvHC;Fv{uvB)t(9&tnHABs? z61n?RQ`kAMbhcO3?*# ztix&Z)dtt;q*{R_=bjR)m3)V9*Yqg2I@h#~=DWH-fPM%_VbyEfDBNXh8{H5hH zsxE$3c?yuB{j`@<#`foMI%G((k$=isZ&wm60Nzw&7ow*cvFCrg0;(^cNv-DolP8>7 z*bYKY4ECLl#VIFoc}L~=3;9AbQ*bC&sD2b%(c9 zEcUm2(9KBuWmUe0-jUL@ZGd(DsmZ_0QuKFzI8${k=Q7tJFYW+dav^^oEl9NNWZ?+a%$?idcGe=}Hx&Ej`qMjQ z52d9U2ifSpv^M27k!QGWYT8Sh{eSfh2hQ}%la8$^j_3U+EWNcgcPb(sbiD4aFdJ`k68{ul=I3-h zp7R|(FmCE`*HeleloneFINL02KAl%7uvbBT)R0+>y2Zt2Pw5-q|8sh^gzyDV<%o25 zISsfzpO>_^w?_?_)^$AQdTbgtSWYb1X_GzNjP3n6yeQr5gk@JAt)1vLM7LE&xjdJv z_t5ZBmeKy++#4AgeeI=x^8wQp>Gxx%3oMI|gww@R=#6)5P63p!MATBf^|_F!AfXH7 zp&fhb8P__iJ*!>PKY-8UR8Otv9BM&%baD+Nn9x^zBQwfB>MNGHk@da>;f--?zZV@J zzWmgix06o_SH5RXSKB_^x(30gjzY@Gx|{<0QbReOMUxR9UWnrPk&5O-&Mm;|>P3pc zF$efjkzW7E#szrMQ-$Be)Y=#>hE;v)2&Lc3kjgO&DM-bxypSEeh`JG+d6`FwQ_rA7 zevV{TdKgV7daFY83j@04bj5j){+gLiWkQJ7rbBomC?%4Jo(fFi9|`JWYpY3QBZ_0N z`QQlZvWSP`A*u00Q#v>=X_KH4__@H|t;HRxIJs%$c^Uy^6CL1aAv0Pm zz`mXe0B^u&i~vvZolglN81vmX_6BsPw@k%VExW~3g>PZxxk0VH-u&rfpc@Ze8fx+s zz+0?V7>N(%yAkDW5rBUc!@2gdu?ydrmjYcHW-LkwKE6gd*5;6gkZdtJu0ou)9@KA% zOHpUxqUjZ;GeH*HI{L|YERN)`N5Uw1^ie$@i^-!$_SdV);?>d~N?AB!tmche1F~q5b!aX8 zgZmwW+F2InMGNHdt={J+sP{ew^SxK!+eX$~``*Lg*s1ea>vQqtTL@ce2?O&@fdV}ZA_>ta|)q9NYJs|O(Wx^>F#ssIfL{NQ^YtfZ1x~qBSWeD>17n%XZKaY z_Zi#IF|Tn92UWc^40&Y(97OgWJ8gfA;ikhfziGXv)%TonC?>TiBaLuw!3UzRoU7jd zA5m`^6;~5&?KUpKU4y#?cXx*X!6iV@;O+z`xVyWPpuyeU-QC@x?|#o2-?={+gI^6@ z-Fwwqb3U`G=p8#7%&+V#J`Do(JzDB0PgV56;K0j==N&}ZJlw&29na#I^3|N?3%8dO zn_-9O>;I1P)BgCcDEi*_$yNkA)`vjD#t+hhg{iGuwFG;eoz63K5{j8vWuulp?sV61%pnU_M#peE*ZI*BCzAPkaJ4E7E z!*LNBW~wZP`$jPgQI++`d1F}0B z%1&IX5UK*wtLrpA?Lf9-qKa+qdT@(k2iR15D+C(^WZL9QNRyI$-A?T@Jnmzin9!{?{5BS};i62aPsh3)y8Y60cf^9$JW^2_1?oQNa-7Q3_`9i#|zsPT2qmuyYc%#(&{U6vSqH(OglJ)-N>)l?`e z9rKPWl6CRb{(;F2@cw{{TFyuJE@r0=1Pe}tr-1r?U%m4=;NG=cdeZ| z`X4QuheIRLl$uFUzui0x5BphA^`)?FiI#kyPL8hM9YMcKPu%wad9ifdKtp45Enz&% z8n5nb5**QFep(!r(~j=P=e&(-(6)ITd|5r0W9s7Ok{5PyVe2-Qip}s%T~mX_@Pi2? z41S)p+i3H+9T>m3xF|0-4#v5mQE%(sgQE_Dj#I-b7aidop1QVRs;=9LB}82W1r$_w za^IUotL+dlpz0UiGY=*H%a^v$F{_sL7B;2g=2o2AJI*za4m~{%Ysm?6eBcftv z#faV)paMpV6w9aYC!_@=Z0~c1$HP?gUbU27j6!fT`!hGJ8cXL>bqpW^yswt?;5Nz^ zc|)=!P7}jjYBt}9%$mxlAs5m$U^DoUG6)jK*WMxDjT*oxbxZDAqx^ReTGTauZy>NN zMma)qe@l#jz`Y$Np=Z2v+%T#VZ zSwvG_Xj=}Gue4u_d#vaYr6G!!0DjJbzXR@b^3PSyg9vqBQ!y07!pXgMQ>>esr0OQA z1UHPifJg4qz&7P@_Q)5s!cp^IjziGP{BoHlJ4BzPX|5UNp<+r-49ukXQ)2|XS|kwE zL>7fxDr4|?`!G55)&2FSM3@jyzK7{XqJG&Pf))WHY%!%6#QEmv%Ur@j+f~#qn*r>Y zG4pNnLmuV0iH&Y=E4_SAb5uhi8f3WEduVO5YBF+Bq0i{D1Lt&bv=qUIxrEcWN<4Jk z#FW}#4HjSZ0+t;(PP!!ZY1>fljGyCP)Vi-EUiBithdk9OVMWHw`Wz;P{y`r@bj`8q ziu7o?=bzsYoln?Juj#A&gM!XYB^i}8yINL_ftF_Fbgw;VZ1)BRyV7-kcLXfWl3f%h zUb_;7d%UH_on6EJTZVLfY0*2Ej7pV~@hb`+`nhvurPRPl%+I#(-@N_9&5y?X75+AO z%jH=Jhj78pvZje;@fJLbU`{S_OIu z-oc^>=gKbg$byK?!Xi(&LZ=3RHu(myH83&A4i~XwwCx_0&`f`0_-npW5$nCp2Xs20`#?=biigb(|zWRcz>}Ku;VLC3N7D#$TbWX_fL4iGNpF>^O1K z#Ef516Ty$4K|&)UOBvV>F2I`WY!4QV&&*>Bm-q69^Gxj)D7F!Rx=%28X)=?RP7mpV zS06r8P5gbEqg>erg}L(LKf;RCZWKj%D~69o#(cRBBxvf+hy;IP@fCprq%DcnT9(!> zV6y$Io&qbIeESh%Ps_Sk`nQkFFBo^TqUx<>K0E6yWHv&;c7KtNFvAknyIo%8{>gV- z7r7Di;|LJTi=$s1LFoSOzog`_hBJ4s-;1~c_pjDOGfTFA9Gx3wFp#L1!a8z6awn`5 z%uU+j`mIeTPsAuy%BOo;f_@~-2$=FYZr5TGJH!@$%P*H`B$Mt0S0DOqX_Koh6Vkoi zo-zn?<@p&;Q$~D>1fm+p8`G*Zy2t;?WdDsDb0j4f`Fe&O#=Z|Xmuyvyt*xtit+r$L zmf{dw?~j|(=l;TLAU>AQyzBEkE+1#%f!6-3O>lEN0w8tH`iA+PQ6CyR1)}v?HN9EC zK9Ms%kK%Ih-a-vKlbX-HtIF!ibb!libm}sbA}=WG@ILNT!-nEz@$UG-q8}Fy)!>9c zpq4=7abNre5_ZDkI8X?RPv<&#!|&r4Szw3RK+sCZC?*g*NxS%i#+W z9;eALt=)^c@cU}a!lf?Hcd1*=q5buPsSEZazsp=c=WHHtSeuB$TL&hMF2z}`Kn76x z(iR!=(tZDSMFRE4F)jEvy#asTWZtx0)##77N09$2&0^>C@IJyOQk!_E=f2xz6lzY| z+!9A+m8Xg0&bQq=G8e%{eUWKOY~+`&D<8zm@MYOR#lmT_3o^Ci_%4@8;11bW?@ULT1ZOXg-JyGITe^ z7;DlocBwIv+E@ha25gXDs5Gl5eiDx>r}==UL8D^4iWfvp;JfXHEbT_@+Eg>bsI=1U zJKOP>rAxEbNmQk53bu@8gBn9OpH4thRS-Y{AoY ztW1wmFQp0xr$$W~X$4*y2lc;E__w!$60c_rXR#YTbXbI$w|k?&X}CbMcxdY@0|{#C z${5R%FW(Ow0c<2`>bB)6X82?#64mc7k%*+bTq-Mh>vVt0ThHrtg&eg9|A`D-=|tJ0 z9nF5^;iPFtVr@hk^yn%$W9=Y*a&2~u!@$*cMoQCMjP}SLIl`&O;uGe&Ui7$DAU?O3 zQNm8qT8abq1EDd~$=e;a-S;TH+&)>HGp9K54LWq4p{~zo_Pbv7dbvl|^1ued7NNwm zeMHH(9lNcg_q|loc@3e2IvKrf2-XaCRnOsBx2t8em^rWA)Cx_KV-h3c>%U7ss;X zH#pivZCWLX_!mBuW=EjlT}qnh*`I!z27dKx@x19x_a<%2%Cu-~-fo;`u3z`$u>2D(W|uy-`(v=$4iPqS!B$Vt2s zrPkWjS@)=B{%-ox4XZP;7~~zEQiy2~_4Hk_WMks63Cor=yTqe)I3GMTX|S{%|EIgegZ2^tLDf3Q8BX+M%B0aS<)ml|2kV{j$Rm0m}ak1q$Su5A+gG>ZCzv zmmq4geRTg7O){n3`OBX$_+06Tx)e%CnkC2$SjTe*wvJfI1oN~YC`CXGK6e|z6)~Nu z^Zq(agWUiZFfK^DA((uBr=VRpnFVg4>C6MfwHuH9&J$JCNa`;Jz@3Zjy6TitP|I z^P^@;fZ#}q*8glE|8W7*rL7S)oDDAh*nI(ievpUr%dSi>w}|NSV`{{3MIG2 zMs2ectc5GVbi#U#Ce)BWVBf1KHb>Y9E(% zh8kR4h0CMOlG~AG`FH9Gyjd-m*C)7ZVVTCg$qvCfs#oq_OvuT z860Uc@I9PalU0Hm+h%Z0^Sx~Gv3O4(*OW#+b9(MFC%L#JXbD0s7yakB?r~DLS=GvR zk-?($)1)Bh>aqRpVnmQ4JDbPzGs)GhVom3Y`Lu$Yk^bZS?P0~hl`K?w#R=i5g9A7k zYW5`txZHY=j;lFJW0TMA=}d91u4PkGs%Eb9oF1pO%3YsP=w_&wHec%u_KQzTjPt&z zrlzKwo8-R_%!;GR-q*CPTEbR>T8}``8*v$ugx~qpQ4mqdn@@JN(IeOz~EL2Gt2%z*W?dUM;xEl`A~GNo1=2@L(W)IDDCn1WsU1lYR&fq+uNWS>0qwAH`5!OYVua5ud z&+PlCLI|EJ1jPnPLq%Hle4|LFx(96qG$ZOFQQ42g>c>Sy zrlnompo-ueNa+O!Fyrg6@28`(HQNBUQ?)96C%y?SCnff@GxJMkDMuRo?pLP;5!T_n zGfeQ_1xE2%Cpf_db*~f6f7h4<5}OA5 zkZ2{^cfpuK1v@b5Va(SU#<2UZug{cw&z> zl>&=jcyW#*zHiEFZ+nz4J#-{rpW)ekYMuQoIQt|TBja2HbtFW9*L{&Kc89eF);(T% zSxRQWi3XEn-L((jOm@nqsQ1qAcv=o7p67kBy)8vzM3nQbsm=Wl^G~;YVwC5CXA6oB z(`~_U8LfX~S;WC_)sSbDrq~lQPb!#|_Nq~1UIxCf$9ksh6iTcSS;r@2aG1YCW4-`B zhcq6E=@CVOev5kWdNdGB1S~^~&)RkL!ej_Elx@pbzo^c9VQr)TJ#60J>|&}MTI$8~ zHdmSInZ*^S&dTuLI0O^DHMPG5NeC6G1lwE1Kkrz6bCAAv#S|{}s1sGBqg((-;j+x! z{j2SK&Z5cD(AFu7T4tOr*oAp`d$C(J;PJsuj#zOu8$miws}NKx@}eDuLS`-Qa~OcT zn~pQdnv3y1@|xtVd~#nW-ok(|R+l4mP1{#^ru58##x# zV+|p<>$N8)*WHA=E&eM9(P`qv z$^o;U2 zn$V-=Wb$u>uPHUJ-HFd!hI5#^*znVrKJBnk5V-;-mZ-O@*w+xYP8)k1$7;x}nn&8* zxJuU#K9*6PHf!zMxjIDH51NI~^4ShxOl9V8c^Lr6lbPmTe^52Bc@~$!zbaNcUsSYw zlYyu&!U=gC-@s&0`L6Lf&!yi32Spii@Z8w^Ie>gWpefxw8-_aeNxo4cF^+0PlU7

yj^j5-OGXRav~+i`9h2Rjb#sk1A2 z*>~7R;kmk%xU=)ww=?`lx1HpozX9Hdw_g8ak?qJcfyh-EgERxE6oTZZOf%LYz8&|6 zT#Oc4`_!02AWCDi|6yLQRD!{YVU8u z=1I*%D(03$-4AzGHNlgW4%fJa~44-^X)g&@sl zL*~gYusjZF9(T_OUuDXJl+3L;A5lq98)6k2ni4FjT^8jIP-I3Y?0Lm>i0?;rBjfBS6U6TI)E!#TI_p;0>|je{#EC23^!_l_M_ zmK`Z-aZfvl?(TQ~(2dk9JdzoWNPO@49=e0M|Cl7BRofFqGTrTE%fq`J2#k6=0^&`Q zabZqKiva63UI+eVUiSo2CyS@6elNWrjZi~EMl;vGYLu5+uaq{ntJ5SiRHuc^f=3g< zU;2M6z##PwQbNp%I`_=hjc>e7@;6mz-8BroR}?twkP2p&4YQx+G$0XQ-Eg(YO%CUC zn4IPtOO2&{P;Nr7)m1kvF4+X&U}3rP0NYYVBobEEU-#<9lm%@Z@1325nU1}Pk^It8 zq}m;I)c%EN@8FC_43Kv%847|Ods-uHj%u(z3W?cK&!<5uTJp@yTpaJ9Yr}_~qVyQf z4|xLt>Dj?TX~u1h*0wJZ2;&EE8V~7tOS1f_>I4V9NToJTpN`HPpz7PsP-iq72_0g8 zd|Xe-_mm~CDwU8@`rSqUZEw2_xOjetNYo++Uan0g!3tHxR~mRH)lz&u5*^9P3>-^R z0p~9O2N2#N(xze#bsBsJf#!WOAn$BRCrfWIT9U{!8qiSP|5DQR7|*3RUhcuCb^4XV z*!Sm3Ql8yLIY#G{Sm|PG;cfiGI>SA>yjpVZAJ@T6${?uUN|hN_w#;d{KsCx*`|KBX_z1GN{uBC{ovjh z+!FAjc^@WtHs*X1ikivCVP>ZFXGM$08Wc;U7YJm3dUg4+$`Z}Jde@o$v5PAx?5kR{ z_=w+f#{xdp=enC;70vmjmfXR!&*0i|_3ZHJ(lt^es^HMq>29s{y{yejTHq$f?@ea; zDunTA0^GdCV3>W%{g8JV>2q|EL9i$M00sWj`tf5$d^6ki(JkrRbEyY62Y-Gwdi~4( zt8liM@c7dPn6Ka`C1&<}&TL(;)cE^B%mvRv`2Yec*rKNw^AFnal364)Zti?`^}(0n`Vabl)W4 zhf8t0MKw1n_7s9MM430T_X+h3y+OAZrUqNUjX@H0oBI!l+J2v0k1cQR{W=EDP`imG}V#uG_ zaa85K|2PyfI74^Gzxg7nqs+p+pxA$@8>v}8z9R2f0^Kz0V%zE-98KG>5r;j-QAG1M zz;T|a>rtgSlbJ%;_@`xlSAX#aRYl&0Wyd~B-5z${8vB&q7vbrg$5w6U}8EX zuRl);3e9OTSokH7q?zi6@<%*!|EaN&--2Oq53gff+KQ)`0b8T?Nf$FVP;c?|*-%f^ zPAN|zJ7mV~DrcH>x5WG5^Fov8ES7j1NcOpw{K+!&&fSg{1@hTr^>{zs0A|77Of1zX zu9i_BI1)jaCtQh-CmyAvzweXF<^J>WPKbN;fQtk_@rKq*>;S5Dyqu-RFCY1|034P% zK-qESWnE00Z{g4nw1G7ekXGyYJZyR$nBGK~p8^W=P!9hMiJhai!?BATqRzCjnTtL2 zHbkrH`8L`1HbhC31n^^o^_oVW$_XsAb5QeJQ6b(nfNvW)12{v#6hPp?f-p$4!|`d5 z9<+S~El50j{S`U!=Ct%!EL0>DzvWXBXet^)W$6IqFIqbgg?nmIVlw-t#HN!e>J#9e z_d_w3MJO}DG!er}U#qMhvG9la72NmKarv`=w@)ynD<`Hz@$T8lo9d-fJe=2t_eW?T ziB=*=&nYlQ3}IgxUW&wP=259QS^JGauxHS0!jZok^HskSXZ1rP*X}p%r<4EQr(6gl zk)nQY%zq$!&cAQhz?R^pl4&G?n^)0Jv`wz`*QnuLZ?C$mogP4eZP|Ds0z}Oml1r9R+g*L+lSbK>YSj`UxBQ$DgQgFx5Jx`%KAaL zq1n-dDR>+Wiv2FKLDl(7cpR(_?dccfJ-iY-&X;Qwc`WE&;O*u z(dabWS`q5?vEsbNTfwL8-E%eI+Ayj2NqR{M(9$-w=eaqIx3+AIclDjLo&M?Nv~(y| z1)dUge7!84>s%hun%N=$1V{D3h3cPKG=*&FKAnc~EANp|jikPFe$phonXXGQ^FNSfbT1cKMdw!_cG8;_nh`a6vpQy*YzJ znznZz9fZwY=PYv=YDwqEN6@8vYh%fS?D8+Wpmr` zUg*OW&4|Zum6&OC!bFLo%QMcr1PNKXPFf0?nck{q<6o$*frI)W9uz)u@*ktJzpr-K z?xW0TD(ZFqu?$H`=YRFi0YsWVHJ{*!{>p{3;Msk-rX7F9_bb6Ab_2*8=D+dCRh4Y_ zWCo?G5nB`~7!`%EHA&>DRT&|(5JtIAHz72sFaFb8Wxghlgym)^0v+0o{kK?%;-riVN>!|-1}9yNH2 zl~e`+{VV2&XU&^sP7@yReWB^oHq+?TY#(EdVoQhnZg9?$^R2Mw>X#I=D(y$i*f6P>hmX z!A+knZH_+4eZvX?8evohhivWBN2lZG_Aby637tbc%w_Yn2^D9fGuPyo4O^K@AYwr2 z4g%68Oj1I5AX7@XR_pZb91od(HPH545Pt}Fn!#|wGXj^avQR$aYgR4Yb`Ahh@}c6l|j z=Sor{>z=9*?{35?z-w*uzSsBDr<(Dd39Bo%C(%!X?$HxlWUf`p%crtK)Jy8M{o}32KKEQI!97Yegib6A zK)0Iw_^nfF4yCv2AH+POCC^IbQ^&#MR zADG=4tmyp1MX(eiV+&Q)&Ljn$(lZfCnrX6dhrALBJ_r4++~8P;7pWagO27sItbi~* zg0!|Ki+_&;4bejH&R)&EvEis>x&54|Ff<_Or3M6n~{j3U3_a zH4KA#G1avVO?iaEJM4F~xnv_{vhbA>o6_D2gW|EpxzP``Ylo4AT=w0tw;jAJH$h=T z+u#Bq&D2dsw)3sFW8J0@s{vH;FqXv&E6ZPVkL!$za= zmN7FnXcuEmsehRrjoM0=~oTL-&7A=ni1O86Sc9#|1xeGfrp`>6PwMLYv3 zS3qF3hl)M?x2UP}5CZ;?`kD>dIGo4?^oA<%ocr5+Dff$d(Zv}vss5jAk^~93Oo3x8 z?PB~m0}I(#GX`$7v@B*Xhk#&{geReKI6Sa^jh-v|q1LbzUmYAHr`q^U0_M#9Q6J3Z zKah+^TLPDg=c}$k$mGHOfZ>l>f?Hei4pV2nw$AP!(AIih4%u*atk+0U^6s``^96u%dj7T=r5CcZ_Nz}0&HQgY;T!<_Dje|_;0O2zoSVOyld&a zFRoN!bHtc6cSt{RwK!CuY&h(eG`!_O`p-8?Zg*bvf2x0z|FJ#F;sM$-q+f$}wETI% zIuM%bUOZqlbXm~@r{ui0T`fgO+lKBE#>M}Jze-&H?yr zrW-|W)#&Ky&vp7AkBx!}S>{Vao4b0_!ol&H6I(bX_$0QTk``Z+9924t`Yg@ZWsYA< zS63Xp7daT5{9#zp&(o2tp}9SQ|BBx|m?VLqMe6#KtS?GQ>Rw-fvP=118uZcXA1WbpZE z#;LQ*1Bsa>MbvT_m(DO;DW2A%4y~RG#WYaAXW6zbd(RZA;*R@`7U&^@o3g(|Ml)kh z)oHhn%IF}|8r^31`3)B&Dz(TTmQZgO7J8#x_SKn63Vv)3Y8w0>snh03yO=<&kj?S^ zrgK5XQ!|R)?%8nSwW%&kc)I+g`zKHr={4v;J%z^B_^?53UC(*4une(I*uRJT=K$W$ z+o^W*oH(m#pab|<_umocson`dE%L`A+PUOb-EahFp`G&y?CK$C5V0iLK;`iZ#D(Y9 zRm*`eI0xGTCXQ}GE$8*4JLrZ2V~(813}D%UN2$u~yN1t7>%U~~$+I~G))zuZO{n_6 zf1`|Rx1ZV$RHz}M^s7rDNdz1)fA@d`#bW!OxJUXq9c2y@Bbis)Gnb)Ad>PFNP0&ps z#zZ7I7#AQWd%nwZF+rn6`-w%ZE@>n|6v@cD^;@86S4&PIV zEyWOSe7~Y7&7@H*{LdZ{f1*ETBaHaiczCf1IaSC$+q)nQ?WaC<;EcFEI365#$zP(P*YLrH@G#v;~RWcKD5x496!2B!* zKOGPsX3pUpBBx=x_>ugNRPa3xqUq0Ed%Q3~#w-*EA>Ibqjr=#Sh}{0RpZHjaoPfUz zDusQy%k|cRbipU&Gbrw-!};mFJIFy|tg8nt&cY%zw*@=0N)I$ozNaI?YR$-C8o;7- zApYrat1nwWFM84}O+01v{q&msKhpg^`i)^997O|`!{*}uZoQIRA^JUo0&0IS`)#uP zDh;X&-09V*I*ReE@@Y-%t(mwH2tPdP$Jfc5KZO4FjUjqc=?%sITD{w!9>WfL>%8B~ zDeL)0lNmQ8g5Jy5N_;I##{uRxcncelT-B#=YT_AvGTH_AMWk3=;N{uGe<87PpO6?K z+h_Ha!FA=mhKy1Qa{^$OuSewCbGtMy*)(nQKp@u?s!5IyO-ZR|I2@c#lcR1?%j$o# zI^wrHsw~@6hL9Jk0`+W;gEhgg;2P~2tW0i`gzdUKwKZm@B>bPH*qdCd6u~jhyIv}5 z&Z3W@t$tuqUOSnWjF(=;pYh>L!`}nWN|`RD)8&-6rZj8Gs_zGMo)3m>aHDydoVC7+ zTU|*~D$>fG6E#Di`i*)hc8YfKrP?mE$W^$PX0g*l`i=MKmiS_$lYb-$w<96od;6#sM)4K@ zmffk7Iph}(LQ!^S$v5u5w_|e)4fWM=x<&Ggx)+d{N(jio8Mc7(>x!x*r88@ne^XGs zIzjc6$vRJ6Z(adD2yc){yhTm|iH1&>{Lg*&zp!ZD+xeN>Ula;9Y-KkpKwF4!ECOP2 z(7+i00YJfO8;+F{5p${ul?8p2d8$EDFo*pzxf1II)`i+UA^TznF)#l=h_9cLG5-syr(a_;F*L`4FJmp zdU@_P_sr-C-XK~!J%^q@2s4ay4v_$Ap7z)q4%h-8H3FVBf@4yBkEcdi5quI}L_#wv zVcOoE)Ologn6E4akuQSEYS8#Ekmq5zR%~2mLUQD)PZa_Valt^s!is!?bpol|;JvBc zq6Slm_TTY)j^{N-MbDKP#ieH2fT$$WFAFz5|7AWvW03;BGCdl(IMcwfq1k=294%cL ziit`T!&ZHo2>ckax#IYSKHaYb%hi1z13(OD$U+p#pAkE%N#{5G@Zbkx40C)f&F!4h zU)`45azAr=Ap@o6n+q{9Vae%WTEScL*Fac-nm95B{DQF7GAyGB) z#}VD?7oIJD^+m-klSm#*Rz~kqbaU;uFe#>;A_Cs0&N~Yq5U<(MX_tOnn$Wo$48E|4CpMqPp;?Jbku&f6*6qS=rW|q#+c(4l& z-ysO*vIT^wn`KdfIdK$z;WNz@^p@kHZ9#_M%2v~dFrZJt{H3*9Cl{p~HU(!k(T>Jf z#%U0mVf_j}n6E-8)HgmY_qg;OoCBP!GgHt!>qFAO6@)Q0V^ySs0Z$8|gQh{=PmTl+ zErwx?9`U2gtkyv_xM`P{{ZOGV+{rG}%h>oLjmPOS?a$zDQ|89Nu21*bD>+35CmH51 ztpp9-MjV_tMzNEH_p8Z~a@*9f*ZpXk>P;|Q@SNvnQ~BS&C+D6w&*1EguUUkwi)wBG zE5mzo8SiZKi}*fSsu_?3V%2}F{D(QYIyup2eaQ5RnzsyW%%5$-^)QbnU-+Oz+J{Dz zGtN@V1Qv}M!)VDhSIQ0e&Qog#aKMmqPnENF5;@Y!PJ?Q#+8-k1%5^6i#VqVrG!&Z- zhmr>Ec((t}I}m&Bp^rN+*u!pfp41`U|ID0NM|oOm>5heA7nfSk?y1*2G|-&K4s-=~&PW6cK5R(bA!^w>eHe@-8dMPUZ#<(<7v40>QE4kWfs@+E@8& z=2m$L53=g(V&u+}a97aB?2w|@N?O@9B=xKU;M4*t7PW9YY_P0=e49zXHvJd9~Lwteqp$sz!y z$==I`z?1EukwDBYn=su|Qh&S0cO=FT3g|n1N=y|_8p5=~Igev*6|UL zGU=Mf6jJJrn%I1Zkz-b;p^KdxTjBN!sV8IBL)QeXZ5o%?xX$N1JIj6S zq?RoST^S)3`xk3^+|#2nuf%{vJa7u=O!f&e+DDFlQ0wNv{_T71HN5hM6j69Qu?caQ zI!r&yR-a_eJ)G}tb5tPOK?us~j2~JilapuuvmC-Bs?dxm?41*Son08^7|n3V7YV~fPA*~jCE}lw!oBIoh^^c_%EA*-Xf6x)a?Q+H zh`QmAJzg%_v(d`bgF3^a!j^9t9v*F@pJnc;LWJ}bZt);PVuh2@WJDDn@uE&FX$Nab z^11D!5I!>2Q%}|;K2efEuJp~@>-eSTFNg%LUVmX3TzV@4`3{pP?hSuy@BM=K%=_YN+dXq?d3C=H3x9%OwZ;y!1A%ti zPGDr*GWdGb*0oB_k6}xzs8s#OIAjoIX!d7;wz5Qr5E(dkrKgXhW|AHBx3$OO)CJZg z*Wfis59043RIVh-(bet94G*^kFSN*@BkS-XeO#JNf(E=e3$>@WKhHjVq4+4J73wHB zb||50W!y0dOPUWP;ih3%r$_Z7Q1DPojeYy8o~QiV*8vKd{6LV(gqv}?W~+8X_$(f* zvX6~=%+E9{Ok6d=V;-_!w{NgP>mKo%>9ehUj4^)e1ibk-p$TT90ca49l%(rcSU?D$ zW=|Y7`$Dpzns3~^Qw||Ia(akF;qDNL73T{cQXy&Ixli~3#24CpqK-5rs^^qL99ZV)?hNK@QoKrSN6%mBMJJ z&-|$qH87Rz92WWf>;JI;lO0*fJsL4iGwHHs;~fcR8gk-HlMPvL&3Zp>`7s)j!jBCU zZmm9z+R5xuadnbGkh0V+bL+xhaciBap}%K0qU6r#jS+=xCZ%Yx&YBQObf#cdrta5u zDj!3Rb!5fURyxgkBx(}!g8r=-KkYy~h$`G?={PMeat*idA6E;kOZpIr_-f|Ya5)B# z`(~Z=IAf*Y>NI5Ry9Kew`|!6l-$J9(7&lUtVS4JH(Ikk3l1(sGs>$BzC)fOZSzgjCFk8+YfU=sc z-+vwb5h>$|RCB{ae$Rh-~`i(Deb^%ao#hRcE5!Ke``uu^!!EPWg32z;v>9k9 z2`3P*+W|7ymFV@@OC8ybv#t!j*aL-9=&0wdFT=v~mS;_&8;9pNNM z@YDJV$h9X_O2We=N_&V5np%;f9)Bycw_n($kiR(8E*@t1A!n7jvj4UpvsK=w&sdK= zaiOlyyfh2&Xdf|kD|}(6ew8h+VRbC(7gEvWp<8@$1jOA-nS84$<{8#oFN}E0AzV5s zkMf9_TOO9f)}3Zh7FwP6pTTXFEx{veB!3Gn!tP`ZC?t|Ry{&Rw506Srwf5BG z`3Y)l_D)W^1AZi9JgBVTVW~>f>C^cPg|UYl=ZLachM$ML2F#AnBpB@jw1!TlgCYv| zsc7EIo>9ZLiub`TSgW$%?qF?-6!h#Fl&|rE1g4F#Mocn~?u~zIwx*_@(TQM-aP)`% z$q%ZIh!m)@MbY|se1F39t-WW|Bw#4|C4^MDKH&ANkwb)c!}K5G)sMMc(7UC0Y>?TJ z>ldA-qu4H+mgyhooLLToc)S6yl{Or8jR9lrYNU<=wZNYe?lQey*x47=9xZAnTWe& zlwH)iBgfD@h}P$vvzZm9ovpCY!m$){BFn6)`&Yf9im_9WY@_AF+eYK#dwHiVU(D54 z9-z*pbqEZG_x`u+3<^Xib(cjz7ea&?>J_gjD`pdIodgrRnK%@|2x^GJrfG5f6M?~= zf1{)x%8DjX`p1d^^IfQuEY7;}=$_Kggce#X`4jO28CW|XTmTXKzFF3>F!em%k(6&% ziK#4ZU>X=H1Pi(`Tx5SIhJ&g4VZidO!6;;FEmK(~GV8K_K!KbcYx?-Br5PI%z9AZ-A5BQ2g2`E>Le<$?j}| zwT3y@(QZ(*h);xd2EIO==E-^g`>QbG7+J`my4JX*WSUwgI`#ZE1H-3%xFc(%0SAsC zU9J*MS5cpWUGPLH3=e~_X%*-pD|FXS7CL=gl1~5U_m|o7u|m)t9kov0bbM-ft{gTi z{IB6xItE~0Fd1C?GQ$j@OPzmj=ypX zMSMsd5yOL<+OtgcvR04gj<%GA3k#u0GsD7m0@!? zA`Qy5XVLJ*PmFEIWg|nAc$le+6BrRjrPz#P^q4gG%)yQ^~f^&P?}JIUTgLSi5JN`zgM9;YHc=1Xd^>QZbu7U%mOYFdg!qNvc$r zczRe>na+n1c}&~k%g8AGb2+7^jDc`6T7Cq?e6Q*6hB$WES@5TlfIBAfXT?d zFjyv1p1W|wZ2YnKqTZT%^yrutmCYsxW;o;}cs>EDn@j$t`6lu==Z1u17i!nmCN~~; z42VcEb4->L9*^w)*VsethP0$lnJXi5@u`+ugCf}`{pvALz-GHIkRqHt6!^1)jO>$N zL!9(_N#-_4y~e3UCp-(I(W_jeRZBdiY>}zw^F|uv6fVKd|3}ta2F2AyO{0TDa0w9H zf&_ObxNAc23^2F{4Gb>9U4py21^2)NcbDKUA;>`Rd!F~Z?{|OPUsO#|H8uO3-Md$J zueFs6Z^mYlkus1~8q^hNBnliJXXVdKF5t=D@;|8C|8Tv|lkE!@3vkIN^aYRIz$6rK z`X(5`9B#{#9|_W~4Q9P!G5^Tr4l*ZWQr^W@ss+xhZaQ;v&trBvpkR}&F%R(u(`WuL zX`2fjn~~69OMnE@Zz~WnmuE`ln$E3a5z>}Go04GP3P{@+OYR{xm_^CpO-acF?abE0 zt9ca!NewkB+xLXCJ_mBKz|Y$*{vx+OGEh$07s-*T-;}a+j!D_L>a{nVr*P?0Vhf^rwv_+) zCXxx?oF!xIwQa!BNz4lIuG6*T0cvo(9THxI_UEQ=pW^;r3Z=d@e-qWSE6l2(7(G`V zYK(5zD7Zpo`Vq7Vu4#aj=&ru8DZdvfZ06?f-;tz;MIK2!I4hIs-vn#d{BU@s>}Pj% zS3lIn!P!ikgr~WxAAIifF%}5#5!X6m#=j3ja@0pO5dCe|$|b)8!NwV3F@06mLP%i1M^O zq6w93zof4ps*?P~NI!nrV6+UW3E!cRm+BgyLhAbEmU9r~4JR&y8~9YAU;XY*MO7Ac zFPbNhVG`F7WuuMFOxxm3m#_2oY9I`Ic#LJ}Zo#X061EkU!Cg^N0G@)OzUE)f=DQf6 zS*U+yGGz;L_b)Jy75w!-_|s{5_MHDz)A2tgwMP3K`1||Z!$vg|?8SA{t{D^N@J>ht zlW6H`v4SNo;MYb%(%HW7;0#fI#E249gzJj6X2ci;hW*4nBe>3km`CnXq>6!n#VoC|JqbCDCzDdxtA^j{s4~40nha()Uz8O?;#vQhNaKOw zwkp4%onDbi>2ex0x|(aoOQtD@%l+EYUA>ziF62HRbd{=4HomcaG$Z|=Z!|M{(uNAF zFRREl=k1I*1+RG`r<0-#pD#o|fcDr*C(+UIeM|6@x+G>z(01{4&dl~ybsctyZc{U5 z&n)LvI-%uM^Vt2b10_uGmgD}DVrH#)=5sML_V0OuBQ#?pSg6nfo}|vhMC-dsQ5)7FZkz^{>82T3&Wp0W z$k1`t-Q9;=2QjKPpj~3A1ex4)Y5PwPT~(8r+;ug%42t6*PKR6>CYdN_AMU-;IRkE& zJMdQ=u&%?D2u;8`t=YS%83Uek04 z7k{IObhcCI)!Ok{x~C@K+0mW6*c@TN>%-tcH9)lf*dsc5aqI=2;0Mi}sH(!}8Pz#{ zPIdhClf1^m%^0eqlpcR(9BXg2rcK3`X%Bmy?OP^ru}!Kg-d|~D%m0EDKzuAOb!G`E z&=pNHp(3323PfTi7U~nnK^dOCD~ynsEOUr?oo%T|zL`{utN&%I)7~m&-(vd`-bbJ= zT`C5PESKY5?tA)>C$yDyO?}jkoAYjrYQUW4q*75M$xghfBUuw5|;Ur9bvRGG;)We zRNotso>NnGipB!^pv&^W_b|bQp=#{7txlj{tVqe8gAzF*!8|xn1^T+6`-Z=F0KfZ+ z0XHw&31tE8rf{ZHZ&y*LM&QyVp+7AACkLo0W!ie`y7MfH0-g=>T(9CMd`Ukiy2*M{@3gI&zJZ)H?Bd8(fWzdU)#^v{Ene||wp zA~NLe$NbZ$$>t0RE!}!sD`;_H@iK?SLunt9G+?`6&%u*@-~~qh4Tj#MQpcID$k-BRsh;3wuovnhwt8CT{+iW7a)}?Lz|U$1hBBVfYe_!lQaZz z9T~SHpLE9lo)yW`S%(p}k3fhT{MF0-rHvitJajnRgaVdW=rpkJhVRU_evxabsHsVw zB9Jv7bm(`6XblEJ#DF?qCp2Ebxl3#HCo9H7ut=%fQd!R72;t`gB`}AxLz2Yj2tMkc zx$K`ZYQjyu;Zl;X5vE@H@A8=x&65!;S2}htvTIT}qaM~_>IW)usRK!1eM=Z`yct>NxEEZO& zo0hhJfqywj;2TM6C4$g&bk?R`;J9@9_`BR_Me0aM=7WvAk6diPpcHh=Ez49(|=@@`75 z*VR$kR-SMyrmydcyDZ)-!&gxMlHnJRPi*8KHif#-XHr&v!)^PS*!&6DBsd537$D!6 zBT}G@q-owq0FHk{RsWSu6O%Fw4J5c4Cx2Pj*1byT09laqz**v~{@E)w#1FF~oEOIy zU!P=X)qR6sO#;T)eD7xYkj2(Hv?EN~?JwkPrwiL73!obEfSN z!=vKs;hj!RztM~67ylKC!Ku+wAb2Y8@v$O~JLn-`4~0vFfe#U{QCxz;G8HLL7Y!I2 z@rrH!fZR(NF9RW*rCX8Wmz1$NKvEdJqfyW=`h4NVXimU2B|sHB@xq0n*c zA?vm|#9rp1S@wuVTQq<*!4Wy*oVn3)Wa3L#Jfs<)mc3$A6+}+u+J+MTQp!3Qn2HQ0 zH&USHgRPu1jy|EH1xT6S79lvfG{{A_JvbOp?TobHpvC{D6570EP|44O`RKBJ8KA{z ze^g*5ZoOn?f{Kq5do{pluJ2HH0t5r8Oz`F_jZ|-JF)P8FKh_cfNY*8dFLTR4p^3eM znSkVz6stJ}v(+dF^F8XPRJlZdoF$1Z=6{Oh))Y-Uyt1{5p%(6swCP?tA25mw%Ud@^ zFqt`a8S*#A{L(a53a;fWASc(TSs4MUK;P`XK$BhMpW{hCBBRbN?6aw#L`|Z`l4e6%fUUpf&S4W!jOivlL zH@DSg9HWj#`-Nl{&{ub08&HlA>RiUhsbR}D?-KL+W2cd+GmTIyf(aL?i_KKSc`>A7 zvOD#7rp$q@N4QTS+(zO-{oQ1JLe~@po7Q<7nkIpBcS#1`b1^hBNrNIOznMEb6Oi$Y zws%nkdfpB@sQ{Er2cIsrFzrA#H;w`r(_X+7pKJrw&KQ)dt^4EhHGDIPm5oty?8X7t z1*;uP@azJ9v4HO6`}weJs5|$V^9{%occdPjNvlK8J5V@leA+ryY>=Rrj4;rdS;Lw1 z^`ZC=V5nTbp52}SIX&L0%e(rWau%l3t$D@=t-p)2uZz}A#_24?C%KXNd&8xvZoagq z9vC#qwB{K5L`j`Wom-78~BsM-e8|FM|2JFc_Ie{LQ1QH*_ z{I@!AhE$Sfa4*e1bPd5dgvkJE*t}rOy|hTt`fRI5Jno-!Sergk*x9u&B^M?Be$8Mz2rWOd-#rsB)2#7d@5;E(tmc%5ME{wMQi=QG+6z|9Y6w1qXr^a zx`kF!6hyfPqa=*Qsc)D(Ok4IIzJM+7tCEgcqYtnCg7`a;vei1phF?d0Zd=+?0|D!1 zW^Up6LIb?md`MoFc!j{GvlWeUwv|l!jsXgzdys!635EcuJ0KQ^5r3c;9STh~H71NI z)e!U~xtnz_>^IWYkJZBK0-u@ZbHC&*aDLqh2o8|SW0L(^z$m7fgsg@IU~8cr;eD8@ ziKqPD+vJ(Q|Zp%gYo66P&x{Q5X)0G{_tS*wRHp>s0M%;kMaN9P_E^ zUjkJny{Z6UlUfp4gz)X65L4W#Nh!0&ecfYA{hjr_oRvfrC>AF#d4Ol58yhhYbwuTz zk13;U+%}cM)ZV-PBo|5S-IaDQu+>-128ija`?pN@%7q?0&S`_pd1z?_3??5=Agu+@ zRS|6H(q>6_KgKAg%;gB!P|&1utYFarU8pt&lLn+ zzeR02>q;l}1z$rc%0B-7j<&^L*1{XKAEiTrlD+1MZX1AqY=B*d-|2}5>)0@(lkIVu zvy$x6>E}~#DOeOFyFS#&yQOQNMt~3o4@|k*`#DLsB?y6 zr1rho@!Nh6V@1*$&Nodl5%hp6hn`JT)pwx(BU!U4#*{fcW%+&aC8QE;;V={o4TI?( zr<6n>ha;yo>5N?;-`!hq#{9Vb_3E}|qXcw_JbhpS$=HVw)uu5gL&EC{oGz%wfn&BH1Y=vN_SKRH-P@~)4~s(Cv|JSIu=$3A;WR{|E)M+ zCtm?-N(D)qSOB~1s#jC?=(m1*O-SOR)tk$X;kSJ^m6KfCT(ug4*^5E;YMoAG z>&@k2fKrU2lM9)nV#K)xH5h*Mg^pu*(O~1P^UJH(EoYa5O#!JBU>L=a#L}lCGtPTp zZ7m=uS45_zp`=p08RqYT>a#2xH;SM!38eyq(jwBQzKksmVzc`_cCG1mp&@(&$6m2I zn<>xH2mn**QHFnGybRCGw?m)EiO@Xo7sN6}WhukTrIcKGq#K z95fFfrXruZ6DJA#_lO$-3^dx@WVDTItu#GQ$ge1rjrzus2);rK(&*%tFkU=_fQGOQ zD0s1Gq5#!tch4Ee?D%gl90PRshSl=n)W0N8{UwtCP)C{iw%hDs{)e2tHMcvYtcz06WD3pc%y_xBLP ztj%hpkfF|c=#R;x>`GxUpRfr2CJLHKKj&zAadE5_Rn9>}?&Zqg(SD!b#sKb4Y^aeX z%)Hiv8%yf?9+Ja)&>@6zlr>X@N!~s-wTwU8xiY*GgNW~qIP=Z!4A|V$-&j77e9aSD zKq(s?t;*&JJJeglojwOF0+%+JbspL=<@fjThm&s*Pl0MQgZ2Xh^!K3WMo8hK&5o0Q)z22_wKoxzef??66W%(>)V_a$%r) zVQZI1yH)okfw;8w7#~NnrtyyR_`y6gbd7Lq^z3yw$g?~sQn?-tF!*vD-utz$<{V0g zXlp#V2jfc42E^ja!2NE#q8)DX19J`-d$YalG`dZOj;V-_gY%ksxQ7+^JUS?8b&}KE zCG1;4c!_+#ZJgVYfNfR#tU1|oflyCiOE*W(_F{u52{wcK^Dg__RZBXV z%I^2kT;?)?F3BalUqU^`8S&tA)l+8tuOAt@CZf zAEq?<)o13Hhz}^r-*a}&nV>U#8dQsqRP%RYTk3J5`hI;^az!_&S0=7H_SdCzoLXaq z-bi>_4EZ`FP=xP7sgQ{()*;&4x1rM`e@GE$0Zx~0? zxs#Qo?bwD&ueVgcfyt_+1b~MK&01cb@_Yeb;C~?P=VGJWIQLhm-WlA{gUpst?%zo+ z*-v6=u~MoLylfz^n(=d`0a*!a5_E?YQ z-{lg*OBag192#FpL-ysns7}{I95pl3yXh2>mNjNwY5=<-TJGQzM=Mh#2M|<9Bvf;# zB|lIITz@;+Xv<39QG9qiA4TJUFUdjy!a^*x9lu7$<&&merXsgQyuF05THc=;+QfGa z8F+R}+0URgI2E}x!MumM69gs}a6ytJC51x2q$#!QZ^i!EAGj*!=v1Ny6Z&V3nkJo&~aoX1s4(Ae?nAyL2yfs}Y+x#qE3*4QQkuNi@{)k#H* z&kHj1o9pK#On|NjAzU8}hQQovYXy%{81KpII>=1sXAv+c&Hu~-R%tegaA-gQJDJm1GC%6r|)d-*g(Tl@QQ85Mxy3TVcOO(LiKyI@Hs3H zmJp~x1*xCw*3Ah>oB0_MP@XssB0^Al*F!}LYPk~3rMUxa1DYCN!T2_4LXYK$e#osp z^(qWGsa%WE$KIp_aj2Pndp1=rRHN5m8Q7Y=mnWM%@+)vHTsI+=ZkzfPhuR~6&}8!} z!CuW@3KyO01Bb^Rq*MTnIjnocP2lp>s$6VT0QnJW`HphJ8xXLL;`S(VjtA^>U*6$2 z_B&KxF>|K2p03*TLg#|)f5eaO30N=uz@RJ0vg3Y*yhgL2aPtJnC}q`b4}N4)Z}vW< z`qHPQ>Vwh(ZjR+T3haM_w=@k&+e+sbO2*$Fuk^>Z%Nr23E00|`SpVaaeUOOOtO3f6 zFL;r6>OiVTK?Ws)b;Gp4Z+r^M5P;9~!^n=lv=|y4HGnkapENXT|9pZxpb+WwhD;b| zudPOG(ZWCb_yq#UycAooE%4aY-n-PNMIy-?!CW8XL|uIY9-wOGoqrkMM4d{l6&i^w zlvn@xe=JwPb2$9}Jcl22AL)o~Bzc6V*N`OfyV`#;G9ff*zy$*uAan8$zL6L||3EU!|E^!k>UN(EjZ->PlofN# za8#0bYBvl~ss?KJr>%T#_Sg@m+1tHkf?d>zty{cT+pE{ffpGi%V?_YwDhOW7}17Wo(eh+JMvU`!hm3LHwJ$ z9BocPsF(Fy9Zp`CJcTgtxsFQUHbb+~kGA;^K*j6pp+e@>RG({5Q+NL%>4|Zi8s|PQ zZ6C?r)Km{NRjD>7#4KHn&-mSdUlVh1P?#HLhB$zX>ta3ew@*=Y5hYgkx3e*a+r4t| zQ(y-BWaC{|#PeiR%@coNGZ*&+2_~hlCrX*P`+*Qj-;;{LnCqT2Q|z@TTK1x6TQ5*| zJ$4uA9fr?h=Ut)J=4@SJ8FF}JGqt51aZ{zM!ka>)LjbQqnx!8AIPI{ z;P0b$MrMSB1z0`U!E#TZgDw4$>unXgqD}TIkS*`5zhkoHHYq1=J)~r^d)YS4Gd5M_ zbGJkSiT?CC((hJ3Yak5tm+gfM1+Qwh(qT>mW{)d51{k$bP-ijQ#Gaj~_h1I0#1+L8 z8L7Q0maBVL)CZ})I@3Yhpct{iiZixmwt*f{uc!G7QQcyi_LbK!Q{+%O`yih+LJ-Y^ zGg<0#D0pvoNSwWqFtx>}Fnu0HNXgzEL=a$yO@hu!nEc4HxKyQF z?gR=j0fSBIse{lS)hW0^d_(!D3BH2G9USafNQb20HyrzXQGa0NHAcrE^B3J$G!LfA zjc@}YMY(pwnxBq-nYv-hXZgnuGYuFL$n!k^~O z6`U*U|JP(~ho6`H-!itGBq9gqtbPr3(fLX5UFSt}-ubgq7m&0LF|k>UY^@}*MhWeH zD2~!mCQQ{c8*BLv3=nNtI)_Wta`N?oI?{*7P}w9Mrb>XTxU#w?041q0JxaKH1?xvy zD>5tIM{ygy>mNqq9J0(4p2s#sA0hbV$A?Qvr(36(d%--{9T3z*K`5duX zx~7hn=`Uh%S1;HNyh9T@JYAz|ua8CarZaNsW0=5h4cdJ;m!@|kCg5WLCkI-Q4 z2+McD2Fz>MA*9kC#_v)?*0&y0WT`B)f)y00nbf!dm;XYCL3|hYtxGw!hpq@oQ&}Kx zpbRLWYIZ)#sH^{)U%qRi4tLpU2I6PpGx$-5&13E#5Yy$JKfryvXH?3`wajjl-gY`z zZsf3Mo4Jv5$cp_7&7ZqO%Ghi!Q}sWm-15EBo(p*pe4_Cz#}V|8i;qR&6AB30@BcmO zbGk4V-Gixt_~0H7tL0t8BrwIr*d7!v({%_R;hjFHwDNp52|`2Q^PKW16scDzT>4!T zU)Pcl1g?_PgFxc@Ngm7uHP z3Ksxat4qSDqtfby9q8I1IH%5WZg~jq&zJq+6<#MAFtOSxHuk#lvsW@wfNsEwsj{Dv zNWtT?NrIz?kTc~dj24`0@dacX5U~uVINI4GEPab3uT=3QyE(O~ekMj#VohF4t9}Fe z3*th6an~4~&N(tNdNxJv;l9RD-XvtM5p%;0kU~$5KNy5C@3$Qb zQ(-N72X@7hM(n^@Q5t)LcH>qnSkpByO@;;=388uUgjT9jif02n*BhEfxF*o zLuK@B$(8vT-uW$P&hq<4hOBa2_e>c==RoQ5XUql+-L>y4QNQ zg`sHq+awDXDB31|z?^WwnD<^N_%{eo7snd+YLyTeJJ^fX^zGZjSSq%`SGjC*gRGC< z%XNo6HdIM8g9f%D36<>22dw>>g{_SLPGDHZ`OD%adRQjr)LS`ML-+YTW zm&e7fdC9^^Vbp?6{%m_nQ z#t%^|IeAF2P;b6aTYvg7cEU;epCsOOcx!rQ6-x3XQ5ke4l4Rp&SO83wrCXdJb0GPR zu&e*QYGjWj8k!zq*3~(-%@y9(eI*npl`O^BJ+vJxa@&xiXPC2zh;HHkm;U5E?;T}C z_X2Xhe?Aa@ttUa?r(u2U+6Z&y^GoA3c=?turDK?pkFJK>C>F8!V+=LGO8_-yC1 zvAq6wf7WS#D^R>Wwq)1O%X7v{130|W;Q9qS-?5AS7AvXNTn}OCyqp9Gc`swgSU*{a(cKpRQ|_z|`+%epOYB$BWe33%KRsvt zF?PvI((toYWWHqMS?AEGj1h{u-8*E$p>FcEs;%p44aIQ`oGJ3)af(739Qbsi61Cz- zl^m<94nPBlVtjCXM+_BaS^7Nh%H}ULU5R}cg(P3N(UQH-&^*FR{uO*+s!m2IMP5-V zT%ED|l@Z2*V}^jpX>Uaul(vh4g1i1fUJYr<9kVH0fO<&`0$ieA+A6;G0J%DD`@yLY4>eX)ebEy|qek_9t2f3F5FE=eQN zA+b)E6%Iuj=jUMb>{>8+H5Y~TAcf$zL;}_nA5_vKnH3AotL5?}Ps2Qwze&<|un7`@ z7l#_nt9>|efD0Kr&Z#q&ct7bUJqgX*sS!mF@KFPgVrvRf(?Vk`-xjt~3X z1q(M$_GLv8Zn~BB7yoytWW@TtmB*cw{Ese?2|8$J$}5D>JCM=5j-C1s-1rR~6^I(c z2{1zsk8+xsJ6AozWPw zbu$E2L)))Ouq4zY4sG1b+ZICq{%S8s)d#dAHT3qe?%ax7z=j5dO+fzQe1nB3Gi3fw z*RU!08@$w+M&XNM>FF(upwy$zw84EeP@T>mE~IF_Xe_wAQ7R$`(9>XcWHp8))mvmV zk~PA}S4F|Mpu(W^7HFcbMrfJ@4Gqoiya1Vd*rz92ho+1_?~}oK&0LUwn(hKF+_QuH zSYF*Ro`oKUbFY_$$?c?@Z8>=It1Vrn!P6& z!YSq3rDaI^bSY_^3TY=<`)K%q^p`hbdzI!#wQGOw<&C2I7cNl6`!C$9W)zpyzCj!B z8A>Lu9WL6T(I+qF1Nc;g@h>z9x-B?YY)t!}+&$gETo43v|79`{5n)2j-;)Ssx)Ooe z0B6+t9#QD?f5GlawCaBi+~2nE{P_@;sRRYy6Lo=&t?Q`oLW_h(QW`(c{RWw6Bb|+_ z6{Mmh+H;S7G897LwTvsew-4Uh3cF+@Cq*eD)cQUxwdJ2_>7SQ&K9`9Fl1D;A0{zM# zGlGi&Uf(4frX&ZDfS^}0sQEz}d>U2`r22w3IZB{yV~MOuKjfOS6CxFGXGr5t|0EZE zY6?!sp!kd4G*sMUJ$I9_EHYil6i^2w)Hae2?@%S-M)5qNoEMuhD3^n_S975u+I6<{ zljkbeR#?AiJH+2Ag908GiU6^?FbgW`7OPu(dHe|{U~LVWpP*pi9L{OkYAZTPt#+Lt ze|>j)U^Asw@&HL-jdPQIg|pN4O>2M{#JzGd8r1o1rTkTa+2q%yD3_d3zm#JY#Cq9O zd9bxy4*;l~C_QZ}V~U!sFQrao*JZ|q#rT8_4L zf*#dM>{=I~BbVd^Z6lHE&?ghY!r_t|9-#gPTO4A{2AC@Yxjy=!Esh7BcbrX-#MDwj z#jil@3sHkn;seI~O`gN>tUa=8D&`vc0~a36YiM?#URlc<)XeW+3KWwpn#5M}(bABc zf+H^6S05xmfwZh?x*dAXRjhHY%WCCm$5CcR;bNa10O}VDB$Op&{k-#t<8g|6<{l}_ z+?flw@%A&x=xy1n#O7bCP~b>g(UXiJ;b9`O(fRz$2cpk`IX+E&cmv!L6l~L^K$d@A zC+|WuxNg)p?5&?-2Ii+Rd}&PyDs&8Ir9Hx#;K0PepL=W zyGPhk1N|dQWGvnM)@z`O6({xA5H1y@yu#MQ+oHBG=1!e&>H32Hz}eN#m$G%aR_Dg> z%gcb^L~M+_N?0q}KYb{wD(%lavHU@7Ga`)#yR4+gzXQOp!P`4MMJsF((+3ao9q538PL8?c-@5hpvB=qit;&wxeuw=&wNA0-I4Bt zu#e^0-%n2b3R0{-rm4q%--Z@&!+3#o$qI6u9_#~?r8oB=iB#2 z%OVaO&;qO1kp^EfC)D_?}sGl*@%Qlh~N)$V+b!oFbx9AsMBZ z0*`d~3N#lC849h9&|p}Z#vBM6PB!}THUUT@p6|&KTgT7dLkq#CK@T20wwWE`Y=aG- zlY(swUYtsX)E}Xrp{c^)I3=w-p3yQ_w!L3g&0wK_Dof z^iJuR*DIvb3ZbE+L_Non03KW13DyEsC@e3OuqPg?LJO0hiXPzf+E1%hz%-@FdD-Z6pm@H0y0vs8M(a z{{i}o4kyW;^b1kb(*A4(FIDT3!5K%XRdy3}RIitLZEjR6NC2M%qh^KbCqci5liKxb z)Q7;Q@CNt6OXVv_J$-7uks~?Hut*`U;4UM+W}meqN#D)T+CEv`~&E#h#?&$;?xwZ zVXtO&)%Xphndt_4&G73(N7~A8!2k__ao^9Y4(300rs>vxSWDfMAYu{)(Qei(j=m;7 z2V7K7{uC=Aul!HmX`A5a+akjVrS7zyFL+#JOPD@WA9F|rGs}bXiboDH=4Y?YsB}+R_e1;L5Hp+uXQE5& zh%CreW@7WZkd{CtJWL;JxKLTb(CR01oEfnug`$;kV^H+&kBXM?sXHk z2IHc8yTE3t(gvY%xm>3#ETEb)vOqxp6E*jrYs)h2@2II#35(!hYgP+MJCUh45S-m+ z&_!2(>bK2B2vdCofzA;NHO)B`wZo+Rf9HXjnAKh8%{rl3Cw9>*V-87OUEQsyKQ?~MT9S(AjZiaUxyjbNSQIKc`hG zBa!T7+=mYx_$dH>BxL^2cl#%sLJIPWCenXR7mf$F(u( zlP=@KYBI6FB{_gBBdlytLxaDqmWERElrh%(#ra6_!`lAc5+Su@O)1~7CZ&d&ny<_; z9dJ$9MB;E~FA#vnMrge6`?ntNq4By1Wr;65(=YSp{@I9AFC7R0w+TgeK$$e;AowY$@81x}!46OXV0&CPm=+f~hSIJrXvO z0KXkC!-kNPSm<8#7i|x{%|;hY)i`T+U<(X3y}%#&_@5kc1al)Exx=Bx=5=nF6}qU` zsh&!3{r=ilP17Mkn7jX=g{dDTPbIzN}Hgh0Q?YPlz87K!kZqwt&!L2UB5!*GTr`969%9UR{gI&2!J3E4faYz(d_Ci zEKzl2fkS1uND~Ip^VIs$=e~V?Q}EL;6S{3D!WpV44-GF45NZ<>yH51b$vOHfas4{< zx~dFafx-EvQQLoAbBw59P2W2VzK1H)6hYpb57Nv!oI?Wu@(`GooG1rME=^yGjajh` zYai67G%47qOeOV-6pg!V5a`Yq%`8eCWjG=Ehrx&xiiqJ`5E4`ITAU zu5JRf7S*u9pEKgh4x}NjE4K0)s@h*9#7lPlsBM|~5 zydI74zcq_#j}fxQ<`PuGiX_QoCbnpWZNIsVRBMHswZ4*LUrTaPb6+?&6&meoX8x&1 zGvSYK`ICDn)>j#0WNZQ2L;{X5@j=ZFIQ$c%p0Tc86Ch6}V{TIVpz}{DzAM-u`8jRy z4RHJ;kq+%Q`&92W%AXrpzPAD$t}$EmyI&cK+-ER%@6-&DhTI;t1BjA}m~n3QxN&4O zYk9ot4_<#Q{ogDA%r9KOTS(Zv$<%F}2TF2ROX!u4O@!W1{!D|S`3Bexy1oU0rwTTD z!Y4&EZFupiA+oY$;HH?p76zAMhuT-@e|Avha_oX|wd0&^tHa+9db&|jxMttM}BvVaB*7BeL z8X}DJC@wQ8>5`}Ci^@MuH|p1&x9hGOmAR{v)a}dqcISVkYjdYukwyc|A4+&{_JLSa_w-XOD2b4-+B6 z>^D{4d6OWzaoyJ9sYJOKhq%sOZ~-xMb~`f{^Rme=Q*x~a8vLbtU1bi1vjnjsOGkq5 zT!uuZ`{poLxh#ZvOkVFY=4WZ8B-G$mf$n8uF_*{Ndn)c$W*Jl z9AaL;-?@ni)V$yG{&yKMK;#_AyMJh`7U|1=kLVlkv>)XR7NgL07)>QK2u%)_@x7aO z;v$RHBK&+~%%b*sfCTdUuw{Quf%vhTqkF;E%*nLAT0z&SZ0L{Lc=|$?4J=OhUOE;B zt{fmTmOt_^iy*t+55V^(&gm{Z3&X?B{qCRfG5a8Vo*yh5%5 znMl~dMWfpZVKPRJYg-{6yR`_+M|H2VldV85M$8^j^6dJ%dr?X^U!pDKCJU$y{8b{~ z4P<5IuTD3UExc7a@Yb!luxCp+Q-YIIR2D>os)yJ7$RiI!i% zuq(s@w{+R*qiaS=F4lgM&SOYwV96RL8+Mj9O5MpupQLqsiI4 z)1waDJVBDlyKg-WOh&!gab@|X$cl|b>$tmbZl~T1HO;c-Fjh=L*O(X(Okocl!xP102`NE zFtWz*r}Y~fKVbh9gFiwc`J0i+amO|>sUL~m{s(j560XZEP0g;Yt`*J?k-F3AA8^|b z-5F`WtJj1MQB-5m@6@TDOnESI?;>da?CqmhGK!E9kSt#KNT(Q4p$m(dFi%liin7*h zK?RZurBCXMvh@2X0@7ltJs3JT=cCev*S8%u&+%?uT{~gQKXMdD(v|weD{i&cQpttK z|0Pwbx7j=)7Ro447KQNOz27lk+RMFcFzyZGqH7PUURDwoWwBzSK^%?;en7|L-( z`lSvtOc|#5F#@?C)B-ROf(cFoXrL=={VNRFN&N@ZIYjh!d*1RTCDDO$c`c=d&T;>4 zVV%MeMrnkDZ5~!WDZB1`z1hwxa&s>kuqI}r1baNgy{^O>{7Q<7c!F>uWi&ocQgy>d z*F4#9_@}Ic&Hl;VhcMf6I_8oyf&!m8JrmPd>#|0)PQ26Cc~z=X!gm|2VWu zf@Vg&TSau2O8>_vx}5dVeZ|Vux(wtX9Kq!*TSNbdI(K2ZJo4S2!6O?u&dcH~W%4f8 zQ`B6-jPV^SCG8v86_X-AMGC2RnULCPYPR<&qMj2F3J!RMdCb2S?_&Y0>|#F!tmy_K z-o`5fGO8lYV|)VPKh&wDa$lhc2HG7+tM$&5d_VTW^g+IRJ*OG(V!foj_TuY zbr=y?^JCpXV|O||V-4OP-4pwN^?J__cVaN_npI99WMM#qZQzE6$M9 z%zKm&%ms`0KiF|JZGWgycR6NA{T+{J{lt=xiNdB(U&@&aq_ovRUzvtjf0qB*w{7_7 z-R?n1Q?6lNgx3f@JAqUV@EMAB-gz3UhEKS6DK2oZ8_mS_XC|>rg#7b54^H=AQ7F+Q zY1k+^{t~v=iy9w{NcHDp2>g*o9IBa`?<2v2aOG9$i-J}-oH$YX$oL7EWpwA*y)=IN zH+!-LWH8CFtaeuFCLmbwlQqI_M^KN zYYfT$k<<;>sTlKG=C@6T)T`uNsX)x*$n!ne5~kaBmor~mzi>{Nj+!TZ(DTdIto_mV zgU`gl!^34D!^R}ZgV)oDLE8U;(X#2D46=jv|FD%z4nL*fS;IBlp(`ug*!7j^{6v#q zn1#PmO0=J*@1Px{evm}v1&*WuZ}kNYDLOFfWNexG1AO_ot)=N)*KUJ&KEUIGMZ^5K zU9&!^c7=XRr5Wz8Ju#FM>u5ZTOVIM;Ap4}OsWl<9u}T=YQDG=;=#SF)frEow6YeMk zm8L_KUtx8jF#`BXkx!yR0FF@Y>|00e^(u#Zd)~;}-n86f>)0R7n=547FYmCJiY$n2 z?o~0wt^?z#&l(gyxF*9!6fLHmxUc2zTt1vGPDG@-CZWGS!>z(~Z|(Qy9u2MdlQ^?+ z7?m}6`tFSgvc!Uk9`!%(kk5IXk)M6DBjVgeIX_6T&tFk0%|&u;cwD#{ z?gml+!Jg^HV;cFpf|Tv4z4U`?T1qft00hnW^sF8SkEZ3-wx|*1@lXZ5HEO^@l+xWI za-2@>&*%XPeAiS`y*qE_*H<-M_xwA1NuhSGg374FH?e7=qKMSBWLJ&&)pJgf@H zZ0Cm|Vn2gW(eLRy#6LZV3X2`S1x~}|kLAm&84<+6fq{5E+jpMSt_>;(mw#HmfTm)^ zE?~r992`9~7sV-mEA8Im4fEyPkMJY(;o+7Wm^E&m&s&yX-c2pDDtb4H%2CAo%$SmE zBlGLAMwVyvO}(m3Q1Iymp`eRvB=CK&l88I*E^8y67dM8a9ey3t%-j zJ#1%D!9l}o8*;CGAr;xEe~!mUplz_aZ{5H`shQ!iY;3dyCFuGa1^Ix67l(NIT$v80 zWZUmzJV94w)x|`a;9<7!GB`2z5Rt->^n^kJY`cw{Ip*q!J-im@rrJWVa+_Z#5s~3P z2qvfF_TDT;@#fCSr8C<1u3&}excm)saSA?3PDrtOK}0(86LIA&y4yv%?KBCLJ4r@H zK%Bj3a3*}VIKByJ1X7YDG4NN4{M?l@dMJsnShUpEg>a`X&duYt7VB}i8rZDY(#2DB z!22re7uG*9)K~bmvh`7mS7{U^;WR}!u6$NBeq#uDETZz7oClyed>kYiLELJEBnUOG zG-<>QCQ)BsYyy21kZA2HU+#;nY-<~;Fv|uH?WRp-q!1BywIGfB?Ru{=lB2K zk6>QsoIPu=bzSdkZ-e)qt%b$&t(!J$%S%$z!UHrxIo-QC9lrP&Y0=ywa(50|bGe3j z-jT@Dv?ZxuE;cPiR|>IWNX;!MLxdw-Y}ymE&`SD;ul){7YUkWUbS@MwtDTrlo)7EW z68|uPf<)d8<~?sqw2dHA|*9Tb^Ftss=c3 zI;A`C7uNPv5jp0t$AJ7UHaNg9>mQ4ihj>=0vE>mR8@HU&Y~WZ7&)`qiIs@95KI~Ix zPM$4PMaRboI*Q?RdW!l&tSX%}vZ_1Ip{MG20$7Zz$W$%X#-~$(zBK)C9>SB8L|GW# zu6pY2OYFQ+s9_Asz0;qOgFziMelG&~uP41nL9+IM>M0B%PnOIq@5owWQ6M}ifB50~ zHVeYu^`f!rv&xk*se8|I-kh*XB%$%U^8kUSQ*Mcw3Lg^O*8My3p|`~g3(eI#x#wDZ zeTJ1dDNWMFgI#R#7?KkG`LcwBNs%tD-+vH-+6tm+T5J^fJ|j=5ks~{zhIU0jXP{)t%$w0D_NG{QDq~(&XraAMH15lw6IZ-snOA?xX|p4(XATaZaWbPE<~E#kKm>)G;S34mwt9;Z&yZ3hDtjD68R)i9fiWT3*T(Wq;v zwoN0C$BqqgA^BH{-Vpwhe<@^cvxXHygbU(iM#vH3LA=?+5xTEo4^c!*bk?Wuq&j1- zo1TF;OtIqR<@Y|bczyP)EIjkEsMLVkP{@Dpj7OI zR_%gdlyqicrTI^YPYWI8a3m!L%2x9^Xu%fDhZZ%`C?e_FxVl)Ob3I?IG>0+uzyo96 zjTPBiL_@$Bp}{Sj;~z+;I}e6JIJj^yk7N#xY)E?^XXOnub{@DalI{tiKdtK_!r)w=hD@Lp8t9`4G68b#sG^p?F-PEyqAIMfUdU0U%u4k zbe#uJLHcrI?+mH7Fc*C#;tR199fwLt1)Py8uwG_Rge%m&4(V=qWuvpdhJn5sHYJA- zpR;X>-<+fu`3seOK-&~=izEJM;ze-6#ePzV`?|4~D2Vjio4=-@C2rWntk~v1<|agm z5H}a#L!J6v)T1RO*LwjvZPq%!(n%XWP8$&V6L+5>uH&>8Q`-UU5FQ`7^brjL0!Wx*-f>ps#dB?P-spHrl$rPm+pjvs>K2 z@Cwml1dCR>qul4TA+8y$@@uK%g9{t2n*mx(wK&O?j6x^c)U)>x!e*#;>1vn9i}DWo zjx$eA`MM6*jwH0`lk4WhUk3q3xYruCqxEicD0z^~{Zm@vaH3Z@FC2t`JTq(Tr^Itc zY3d&Dmms&t2I270jud&UiGd({lZx9cI?5j24;n;;$xz>${On)umY!X0D` zVk0R}nt&EkY-WHzf7Z`^qncTxG*k?D^IH1X+MXDHOVd+i(uKW-^=26n&Bml&=S zSsf)y51wq=#8+`viN0y2IkJB&qu~L}kaWpIHLKQ84`PFp88VeC1vyp&h#fmFE|}3q zt7z+iiC@w|40seXZ=u(!25q_rOveOULY&o`*nbc{7VI!_Mb5_?C4C|7?v<@kdkA&d zqia3eVk6bXNWWI_a>06FyFb$a`{hf-y-)dt2k4>c__ce;*Y8h&a}CakTQ0GI_7g0Y zhYu;oihp~J+mxE9!lz{9#yRGqft0O|lcJmon0fvBNjlY*RkVvGc76L)|5yM6^u3HU z`O+RXS39%twuu{k>`1U<_fU{_{}|h+Ozj&nutbCf)ICx-)$o`*N9*_Jv*YhPpYMYH zmCLMX$5!~9m1OAv@S=TH6!w0pSU%jK#MqOg->%P`GUREot1NLG(X1EOb%zPt86Kov zVjJYTU3=;~tznQe`}6;_W;|Q0%mVVPd$=7DK#4jgfQJ{tdVvXLw8|)w?&IPTf8a}!h=nPIaTOV~Gk(-lk~G$> z-rz&_1lx^F)S}UldH{6Ee6~nH0SfLHgfN6Ze%+anRKqeoSG--jfBZ(n3x4Jiz!%=< zNl*OdS~AUnk~7#Pf))-&qPR<$=|JTlhFw%fjwN5hA)=|0=^57C`ikYy8{d}?xf8W7 zjmO?WeV%*$UQqJIGh^8yx<}zt23;DNPL-!-8*8zg2dNPS1Sy}F-MSgqT)X|%5=I~{ zQqn>~6< zSWdR^S=U@`(6|p{B&rU*IQza|?(h z;FRhDM72~qyKu>zVRTzseh#-Gbr-Sp)~+CIB}nMoqI!KR$?H=(=3Vxn_c_7^xUOyJ zwJeMPF)9V~APAu&UnqkJ6jlh9_r4|b=v>h-&gOQO^Ey!P5h7@#J3 zM;OMD?JEm9?25vhc~o^L^Pg-+6mgeSv#=MYjEr)Yo{V>v zMHyAs9+|ky_gqpCR6Wm|7zFs7&|J$} zOf0V8wAa`@gGThY9~r2oP#Dlc#=HIz7fP8Dc60VA>qk(B^UHi$iEgBbrpuG*r zMknsChk|*VbrWJ=1-4ycjkT1jCwhZGxgfD$4cR(MFS)|O%e#tSCY!djD^{)Moy*|g zGw`{LT#IWr8zN2FgXpfvoQrBeph0StXWy!e&&-B?l56J)gECnJM|ZY=5u&^Wf6 z-DWYjrLR;4nBpvGKelXPbqC>AE`P8-9&gu&!u*+ zhk1)?&m(IiZK6XFx@gv;!)J06t!P(wOm$B>Zgch6?ab71F_}SVd||`{rj1#&>g@A_ zG@ED53789fU>?Rd1~)F2)YEG`?aa=S@zbRiV!wo>^9jA7g+ZH=TTrXoYgNL$^Y@sH z3`ZQJOD+Nrj6bSJ;pLpnI+mxtR;H~fZo7mMd|4$oa6eUa?6lw6wjnCM8kPKO1Qzl_ zM^?0oEj5jm1_EX3N;9VwIGjSFd5iZeh5j!4^r_MIpmrwQ?aKid-UIDjmYmm(#B8?)ORm1KCOJhpfLCR}R# z)M$h{7N6EVUA??{_@|YppW875p-!b-2TS3o8#FoyIbKu0AMQxaX#fAb8SMYHe$UIR zeX-)wU&OJR-Zr)7W~$8Wzr~1PFZU~w1u^1cd-O>#24pTg97;_%`KoL(`c!j3wF3Oi zZSG$9mBs8gZ1+~c8v0{+5k9Tn;LFe4qIR&i5tp}W>8Y#_d$i>g{U>-3nP821-87$Z zz7n|z7yC|9t#ELJek%TonM$Ek5YaY5tq*LZ_N50blDUX+`%NQYdI=28r!{;mJnf^q>ilh)*!MN-jodQ?yJXCpJ=SEwRyxoLeL!8|EX*@Z%u!M6 zE%rt)23Ii`KPV}cJyDr{t$tD0Jp}Qn(Y&g8gHEkF(Y$}Ki$!=lI3c#m&WeTm@Ym=l zoh1iaV_R$ai<0*~>V?Yt zb!YaT%W^&s8N^3pfd%4J@>i`$6rtE--seKqgfjH|kP@kdVpxa=5t>F0rqH!v8xPMlOL3r&D z)Ca%^ZV3}ZbQs^`?j#pB&$Y zE>^S#Q59|n3rw}qTy-#&%>5JMMQKMi9nG{0VW{?~W>nSUf%~;{7!R=<#qG23&lyZs zgiVd>PVbv&ZW``p3jqr3Ikgg9a%-ryyri7$Hy^ngo7kc)Z4(CK$`C-``!(*H?~Bi1 zi_w^)Hn^S8+5>e}9TgtmvQ2BKH2+>pV~DiwQbyfm*|Lq(cTD(u^M>PA!h%x$4FDlb zQdDdjanU)~x!Y%g0aCb$R7@%{6h^*l`FeJjU@dQ!WT0%Zzgx$}!`{CJbYeYIWm

  • +>4w$(t6&N$Anxy77bstqP1|^ zUYw1q_DSv)=+UC|Rct;r#6<%`0rGKFHd_;Tu{lRmY%G0r9(D;V#H#kv^(;Et`b=H- zcm%YRnLd5?!JkqyTd)N1zAG~>_glEL zGfz{G#^9mqNSO#>@Hs}C4Efz3$0zW&xGEXbjODYHc0!JUpHVS0jUgUhlsVt&VsA0-j>Tdt+t zceVKE3J_g8>pL9)4)fB;2;R&Fg?&4|A)Y@ugG;fY8p+iLA!JXvfm8A$P}N(V1i^+0V@^Oc4a`NjT@g#TE0|wNJej z<1RALr9*U-Ws*c(&0A@$0s>Sfu4mGai^d3^{=pg=UN>>koZjP%f98HRdhOC(8BkLN~}m#!ef%2jwL#q;Qs69 z7AnI(nnlu1xC63PMU;#?KILoqSq159oE!wyg;I&S)%#3W!=Ux3AL!M0Q@TwhQ?B(^ zjuxF++7n+F+Hw7;0)jj3JCcB*vM&B)rs=XaJ2j%e^N21M%^?>7ICI7XQ?7jAm*l!t ztucEoh8Nq@bXKzYmspj6=lw%=iRyG~tH%q{+AynmusvR*6xM=+zddHe1QS%94X70y>hdg&z*Igkc9YqqSVDh*#517TnizrR75d1u__Y}{Z zkf<#>y~fx>zUzm89^6OiWo5M3DSqY1%2!WW(Cy+LE>vAxNjzhnB-IT-2o2l?jyHcR zTTHl9r`P(DOu5$ie@o58;c~uNZjyH%{gO*~JXu#$IOMuLz(B$@St$0WmS(fEXpXh_V9a_%bv39MFY&~gznW%2-03MC9hrsZ;`2UDDrhEOiQ`rQ!+0b zf_ZBXNn_0K%n1XN~tTW`^_yaS3?TE2Y6xmG|w2 zRMHr0-P?WJ>I?TR1={sbv8)PeAQ|BJ;f}O{_V}{$1%q<(s`T9 zm^Uj_t{?>>9#GS`bxf&{rRTp|;=1Lxe|5pXH{T@zh90>g7V&BM=>n}ot6sP`m?eU8 z7T@T?vYZXRpFf>t7d_&Cr6c$8GEJ}&*w?4Hq+q8f*Hx|jP<1{klL!5PVi&P3u8!0S=$HY)mS$vzA^qnyXnAuD{4*%V%&h`51jhAeS3` z^P%o*YG^1O#TjXFDxa_Lsk8r;l|-`w2wf+3@+RZsBw31>9~px{?hWEjtI$_R zeTf)U^7A)hAmL{%g5S-%;`iSBR;6g{;?utfZ(I3co+(TB!8319;wAaV6zfp)9{b@C zp4fw(m~KD>V@u3@;GrmxKt~>NWHG8*i+MGZv-@_SJaG@FDK^^0SkzdALuwPbqS-Y9 z$XDHYtH7B>iPl(Gk@H8oQM7h{inrA9WlTp-kEPlue6iK(lhC2zdo1KWrfTs7w(x=KTjz60o;Zl!hLl7zxbDs9BsjE1FwPogyoL z|6pMw%7^9~Q5>h_d_M1V4o~%?rTH7i@o(h%irbCm0RwQ}*3`nE8GAi4U%pR;u!20} zDq_sQ5*t5TEosInKmk&7hD>b2Kv?H^Xmu$E)B-U>@g&-D6x#ylETy_2DR&3#6 znkyYkLTS8n7Z6#7JlFQx*SuEqM+-vij3RhbA#Pwv4z>@c8qtBkHObp2G9~s9_8T+E zBcSaD1nY!EBO;kG+jv&F&oLljPFvBUEdhKP|Ky59dH_2jWuH6|4(+)`Je3el$7Yyynkz<87EKLa(;-z z{LtrTkm0JqN9NUmJtFEmLa>l_#>>o{$?2{`+XP%UJsUV?soxa{&=4S9=pyY{rj+IY zJ0`z~y;ktzBo&Q=J@i&@KOPzx+~YDEdNF#E)^r`vg#) z#Cp^5tC}k}7hF>3r^*kq%?CDq0X$t(Bu-DfzrcvesqYeQ^IcZbM@{WblgLs=mrYwW zTG21xZem`DsD+Oyk{CQ{ja=2w49EjUurB2h18$Ie4qz8c;XIM~9JBa9jPZmlxIX5| zL-$7K5!I;dj`^hoYVN?Fr`g|HQ?U9!$0AKaAD=Z{@T2-Gb3tJFgjq#EV{$-rWqVw}<*RaVU=U-b3JKljzy*P}4(=&cpfq1i|a zid{G)J%?lD1t=gH4Mx=?NP{}#GQ&>B`hlxrFbFyG=$WNL=SzGC_4o%hmUP}Meeq3_ zGJa}j=pKf|Pc!e2GW!Oe+VxIPx58))%p~_yyjMQhVUepVp^80)+Uo41PU$7xK21D! zZ=;Z2yCO7SLLlojVR&yY^|K%t5xG!d#5?b=Vqg9#_f(iEnQcemTWD4D`F&x`2m6CpdfWQv^;NH@ zt~lcxE@HX-1P1*!^>)~&!P;+%j+&yJ96?o7iPw6?pFdf(uSC8!&ST>2I;hfWN~$g1 z!*l)uZt7SlqUwc)SbgL5It8HL7dQ)O z@6RRF9C7%qHD?Z@M4r$rKmQbqo1z)C`gPjNkm}*knw!S!ziCri{eh_&4$Z>MKvDpq z^|DUbIF@ZQH&KLWTc={X_M{FdH5Iz1c7KiN*EY6f$E@dTbRgXNxG%v%zt$h&Px1GW z4H=XepSj9AOxw|)i>5Rr)NdP;yiOi&%!xbXvFTF7gL137Xx43!tLYK~YLBy{XM{Xx z2BQjl&>0IL^Jq$5V0HxMThO^ja^eQOerSOdCS z{v_!jz@M@zW-m!+uXdN1hFU{5P*t2@{y#U?ddrw zyY9)wUw#AJRx4eAaFhI@4eIwkfxhWKROKkO*Q|$poXsGsTiDv8WWcBZIAP)qBCjC3s_`-#^rxBq(JUcyzgwLNInaac7+HD$e*O%HC z1#wjg>m|Pbv;{J*Vc*=t3)-Lm_{&dfe(Ko&Jl6<$Uj#iR`9e<5wViGKD;Zw)az=R}UC@3QL~0#~S1ddCzkL2dOyu9+-^mm{ z9GFeo9}<{%1w%HZFEMTS`N0+A*5$yG{HaEg;S@KD;jk?VkR?{y5O-UiT>}j(Z|9GZ z%^6b{gd$xKd}h}G2t7>uuST7=iXq?9TY`FKTg4CqZo!n;4K-i4lqf-z-TqU}fw_&= z4an=n0j~UtJ?nzI?tI#LNq{h~rP-2;c8TEh>CD89)A|hzQqhJ1@uKWT9i>W~SY^|I z98=>)oc%sCMf16@R#TQjE-|a5EgVV>08UOmwly3iJEAW|PrDUsoE)4_o zjht~)}$Jbur}Wr95=yq9b*cHfPo>)%28Ft?0JUPZ$PWwL3aD{NJUzlcriP&dgdiE zhb(ac6o@GT@4||w=~_69B5v`48=mND-Gkg6#I?3A5OWx(|FD!@c2&ChU5D6CLTVFV z6NbOp9SI+v>By^7_(NK)=>bCP0)RC6WV7|`z2R92W~7rNV>4lzBNxc6_kQMU-hWuF z@U_AJ@8>o3?^BprA3rb<7lXTf6K1s)O2NRggw>;QA;SB|8`_WQ4X9N--xGXD)?z;) zR>I(SuLt}Y_B_Vjb#&APQ_CP82IvmNn4mQxqz0=sAFh`!+I^@r&)IekSVUkZV8dIG za4%0Tl(!3KDf1WM$kjM8`$k7|MgZUv!Z$`9zFwR`QsYMrnpvDp8k6H487ShQWWH^q zV=PU=&cLsOD0=G&Yyz}p4wuz@D2LGsq#*it+?bKJGnFM_14`3Hvn6RarjO6tD1EE_ z62SGUQ8s5}Yg80XjIS^SImu^p2G)M4HyG9g^vL8K1rr7Ve57500Uz8st~(U|9Yvql z%{0MKyWctOKbwKijRSJU!g>}sh?Ii;9Cc&pa*D?CFR2Q`;CG(=P&)FbDljIp#_hDJ zb^gtU{oPbT4WP|Ir}6+G6AS(pa1BEq?)@?JGAW070&Q$|@$jJ*a zTsDqbUUE}oOxVu2zTte2>*gJeTXk}B<%N4sj(J7@<2UW%R*~ZyJ|$}>V`Q!O%%o#y zFT-q1L?LG%&Ce5t?^#K#^KWw{S6w`RiQPGBiPr}8DrYjoR4oVUR#OtDq*KT zIIFQV3VQy*Y&df{cdPvaK~zU8sJ1QidB;=Zsl=0sq9V4?cjIb?^KN_qP4$QtL@ZZy zvAVcB%hN{w$IboC80h@OkSboShR_X-c^yg^k~3zn8YFddhMF@8inYdK4-#|M$l7b0 zOc|uWh;UV$O{>)e^-!47uQHR@z}%qf#H*WzT``X^%1;&#=a?UV&$0njN+zk5EZcJ? zpp(yN2o`=K)pS;&4#Pu1pYHJ(wEU6FMs1+;05D>^jE>4UmKFL2&E@n)H;ayJT<>-5 z%^%?WmW_yb3Xx7+vDr<%9e(ltj6Gu2{| zjG>G-Dv!RKzTFGJ4cg>ON67R~V0;V{>v{L5$Z*0dHKM|ir}lv&>))0ozK8@}77bo2 z=&9vsgQdM>e7_d!^!&pgikfNgVEDE#g_2q@@Ut>C_`b{{ZTX#kx*fMN;c~R?hG1Pd<61nRCyQ?J!uXyPn`jz@7F+@y{ISpf4)6w5Q z9rHPZ3MeAFBKj3&XoV*yvslB5ds@y2ngberK~wayYkl(Atin#P5(}>Qy-$V;@SX`p zrRx{!_WL+?rGh48VUMOeX~{b66#KOQeyWgX{+4EH3Dhf)?dWr+{JN#%vkWE)jN#*8uaBxSZ^+c<#UExYtH>^!8&7A zMk>eDL^7s7fyw!*Ev5t0q6()R5D$3J25C9nrJ?zUD|}RaW!W>iq*nvuM#PWG`{*8? z#TY@|;fm4`r*QaixdRWUu4g@S7A#|HSW#bGUn;p@-Zx9cbB{U5pNa^yC)+i+5rzR0 zj_y^0;WzSMt>mmc{4ZGtL_(tf7YV6SMAZ!v#%a2c_b|M0JthRCJJ5`J)N4Af++X-R z$8PElKseD#%R(w1&H9BcW5SGI{#ph`a2+rc%Eiwd-z{I3h|)Fh`T-1wemU+Vu8@jjz3AUBr)K zmpG+08HL0sa@?a=_Il25cdtvOY!AbCP)TPzZ_y>g> zgHSH!ooW3C^Z+r`w~?kj`nfexSJ;BS6^D`M*H&f!I0*2tqt}DrVm+_xDD>q43psO( ztAdJ;Kw)o30frAm3jZ;6^f!L48Aqt05>A$WbMvvc^R7Cl9{>e{Ac&57aqo&Z7+uz3q4GNY?@m*7)3U52)AeNj;KiAg|d@I1opn7sE z5j2CPa%K5Bae=MzsS0p)q(0Ujh+xZ+^0weA?P!yE>La#qL$hC${x4%K)_<^S){;;j zzG37H86J+pdqJ}U{GB?fs4@M`7_8u6;B43tp$dz4(1tjm+2p8BLr+ivgiF9mdX35P z<7z5Cuv8jnAxRc+rl`7@CukQu(WhjQc4U}QhG{w4RK=c1W3J$?h_ZEo)uOyKsFdGSRW9fV=h%pcIk=EkfG zTYpboo9RfUj0Z;IXK3~Q2m7BLmH%&=yMIHA)$Qvq&lWtqx1e}{R8eHLByZ)(RUTv~ zeIvLIm{klRQL$)EJ&l-YC-)2>ZtP{TP?1rYn6aQqhgE>!(5l+z19PG0B@aE%{foB+ zGxmE?P5b(8aR9t-h#{GqzFrv^I)KE`Yc%Z|+tAOS8`3#6Op@?>F3fIRiPX`8FFNru6gvCov1QEpKuzI^xesjJ|TUE#C zcRPNSN)Z1ISo%~7WSN#b4Q@E;(Qc7qraIIekbi4q&n@h4l;_xz0G*ed~$ z%+;I4o4iV^zt?T#L9HR7S)V`VO|pEwQo4Wm#v|!J?2W;|%M)q%+fwJAH!7k8Gq$uQ0oU(>3#=@*1(9;f-=HTCU}U9%5+326~2qxiEx|qW015 z?}xt*G0-5HSHJlQ_pr|M#>_a%o3T#m@$+C&SlS2yQcyl$@VLO<=s(+(bC_k}x@uCK*E z_AD3*j4vN<%25NQadLaoqCbCm6!jW$ANfj-5J0@C|0ApmLsm5bm^G*S`9iK)CTVsk zVdv$eqrcJbG?G86g7Rn^on*Wuf@nN}L-lo}cKyBoel3*m%#5`gQlyL+m7<^X6*i{d z-e|3BrvC6h7C?J{^L(#z8EJG2KGqVc{NHGz`#;U|V=>?^&^eC0G4b|7?Ejt-Y3CHC zGOP>>j2u|YUuI|ubiH7TwDmdnr^LsJ^~h#a20?xL`~1LS#JO#=?mHq0wlRogQw=u( zJYW8yLsbnI4iD2&Wp&$gR9Z8v#f#k-NcO&HG_O8H!#vSAKlp*$Rookq(agQZ&PO1d zv68gU{(f2_3LWcPd=*pzmC^e@lIAilANpc+_wlhSh(+y!hoirayVj!*oRyufk7g?FM0mR`wd>DMN&I8!iR3Qv>GIg1}UT2pNfueJ$<{5Ed zGH+IP1>+_>MG0x1_Cr3hCo;PHLTGl*4MaQoT$~E!ZoK;^TP72yx}UP*_k4q2$zsP< z;p}oSWxH-hYkhF@KJq*H7?|2we1~WGUk`eRt(b~3e{c`=U0gU+lyZ=KI_rXA)ADso zg0t_Fzjy9(e1>kNdC!>yK-#zo8z{A+Bo=)INDNLc`IS5gsf=!Y+jZ;uvQ)jl>8AqS z!PQKb>!M_@#oCr%N^ih42TwcC$l$c;Q{EkD0}vX74#_;gJARjQbPyf+^lUx@{HS(l z;sE^OHMFTlUK;(5z+O}cQ-)zM-Z&9Xg|d(1ZE+jau!aHzpORZR^fdb}f-yH1HdH7_=BNSN2RTgis&! zgEBI{3@^C<6VSASrs2LROhSwulvmaT#l9IYI5zlOI~6pcpM62^}k-* zHUz)0@h$=l8*uB(12C79y@qRUU{P=L{{a^Fu>Ym5&Q_I|evVM5MB(~rlwit;Zs-FE zpY6$^c#PZNPC(v?q$z`W0b^sX_53Zzn!-lE41*NZBQL2s2LWOP$$$mp3+X|pikx?e znGIFu-vNpp%r&kI<$B3vccBKzp1U&asxGid@0||ZnBWwRs47Vj1^yqYf@Gk06CD-a zw?ICCe;A8Vj72eR6U`X@SkD zeX=FAc&#?+%Mo7)IDn;*JbpqHQ()kNQLG@1g+($fizcjkAT-4;`sn&`7zVI(H|Jy? zI$V3Z7dr!|PMBQ#`>hVRQ38v^7+(g4-^5x4dyk@V>3oNmXQZh$xIfa-?d~3f9rWk5rq)BMr@0aj{}Hla=GVFI(D&o+ z)JSk|3>Z=1%4HBIPxqs252`q*8%^ueSpg{6XKMv8cZ7|FRQ6dx%+7~{UxGn$mvgHo za|<*xyn=A&@fraDincE3P!sxcGNIr?Q?ItJ)&J)ldYWgkKR2yb)tXc>m6bErpGvh2 z^tpQJh2xDGTcF0f-(7R&Y zP47-_O*_BnXHZL?R>HluOZ*PmiL>MGKHbnps+ZLlO|nihO^9M1lEcla76ZHk9im8E zl1vnSNqv0ieHQogjypF`rUn+xh1(szPwmaIjx;=gDT_88b7Qy8zm ztf5%K>I&;RcQi{HXAzZMm)@h~=gsClx6>}c< zcE-IgTv0bmUUU`nQe^T{{25cF$kL9lR2=SknfiyMK-xl zFXHu%sZ%vtfIeTSer-)0U%D`a6f`7f1yU9Y)>H^fypB1yn_2zeT8v^y8YUDd%S-{DE&pGzgSC z71*(9cvX9=Pfs?7aT8xnd$dD7eIynLv=-?gjp+GSO+{UYPv+~*`PZl4Ug%t`f6+y7d5M`Dg z@mCmqaR;lJJoDx3Gy9ZtpQz!>&B$-=XY1_65fNG_$Hx7YsXAAd zvpiO&$5d>zysBYc*>~hi2j^>)Mi!aGDs5}$ci!0WT*L4q!ky)+;V9U_TtWvy;jz2! zqVK~;tU0(Yfv7hAL4JH(lM5o5=4E|nrKB59APRz-Jk&+mCI?aCZE zsF+{dR^HMKMJ)Ce6Xl9xfna(pv!I|@$}79^%baw0mY0c5n?SPewOdO2^Ekhu@_p~s z#+KXlodZ8Z=e@^K3T!^fLx-4O;!8q$HHuqO3Y9PG;z;RrD4Tk58 zA}?Q!bOegH2rIJqTRcAjR){PUut;*InaDx}e$WQ_{b0D4nR4VJaX{xf?dN{s!HZCy z`YGe_nz8MVy6)C^;IE&-x5t?2J2B0U!$Jbj zN{Jel_Ov=`DB54Fna{N4cdg7qB<2b3MT-8k)OS0&^4&8!;sjaem}u@*gLkT_e?gw4 zCV3EYGSyX(`C1GO)iCg%2kT4ZD?Y`Gia5@5kg)GfgwTg@cHeBS{8vn6x7oE=jJKmM0JkemSZe@7+#2W z(DZi>$JET61*dGN_}5VeaE$x7O!|xytUifa-anXouUUV*CM+cDoHCw7@FJNe@)j=^XjkqVC0)L~Oy~Fk zlOQ=;h>Q@@c%;DI#EJZ4+wJ1ld%HP!&`Ez4z~{fJPWMrwxqBO=lwQWG27yH3@Pwbrl(TD3p`!Lv;+ zk~w>tVsG_nWSAoGvO3PKJ$+fP8z_oJ$Bj1Y4k{cc)rr`TZ*l%r5b7lp-QXV*r} zV(!hKkvRjhW8sWrYuy=T|Ek%>9?7P;uaTED8g#%CTo)3|QD1G9WZ?*OP{mo&<5Xnn zl#Bigp5x=8&Zc>vsv}hG)IKxf|K!)qH$N>+`>x_m=iKrfpu`VHYCcvdvGrUEWSVxIC2yM+i^Z=YKs zV7U+Mk#X<*741}y=0z?gvwzh?;WzfL{|GxC=ygv#MrH(NeI;sKYKJMXocQp0X~;!Q zapK&3W1KS^*HNGuQ;A|;Gm+~Ju&v~er#Fd?aLc8(C{WA@VX|6s7SX`-F;iv3KI_!q zIJVq3!6S(@TR%6B=wQubOM5OY)8-8kq z2@EvN&RT^>)Np^JRH9L070i~&w8dWPMAC<6m@`b8Odq@G{v~Z^TQjG#ZFMeNH)-q@ zOmMkByc8R8?malTlbiXx*P?M8>DECV_|nFIHi0|s#(%^qc`grzW?W0)9tsQl~u@eV*18HRf#*+!=u6bBbEtJ zP&Zk?I!KxUsEXENV*!k}iD*Pn#HX&QL%W!ju>@z-1t~v`#yqDl{3|Zk0NHCMKUV+T zS-Rn5dXx4qM`=wi!c+)=|?MSA6Y!!x$cMmwe!=K3g7dB69QR6i-}+MYZU>7D+y zwv>afFeB43tFeD1Wwy_+GQmLmC}tO@<@e1km0xN3X{ANi)tWA?xTiEV6bfoSVDCFO zEX+>EHuM}{N7>YLI4oJ)9%XWS>B-Se_?g74C#>B+R=gt~=E~r^>z1L7IbOZ${QbR{-qy`89k=}a^MS2M}lo0Aa zo^$-3bN{b?_sxBApF0na$S!NIJ!@vxXJ*apRa2j9&b=bQuT*}4M1(%d;1UTq5w`5G zr1%?_fWkv|E)Ajqbi~cT?;~}CF*SOSk2Xr}d!@GZ$!dol>0=3@ZHx^olTTgkkJ@K~ zOc>Z95O+C=yigSYh>Wr2!ITllj?DB?a7+Ba1rK3Gs#mi!!6wj`EBi*DR$J8Cb37*a z#2cj!yk%R8oC>(Wp`iY(S7s_lg(`0-Vy0xi-Bo@WCO3$> zfF5w>shq=Bw3M_He-8P(4G;T^-i4*a_Mvo3G-&KqXtwV427U}z;&Kp1juS*kNUHCh zoK~{N*e|*TAHyblh5$4u{&allBxPp{aN7FEj+UNJL=L_L;D4>9F7A>2ZcU(>2YQ>b zPVdXL{(_>Q!7s!s7FeI*$!Zo9Q75a zDaQK^hD?3E35T#;6*7wJ@`)+NSFjJqO~G1y+HP?e!LT{6*C!yZCP&%Ogq;BTI>B4V z?mss&HzdzBG-BjzMs#`iJIW(qwN^Xa6|CfU@k9#^%~(Ax+Ai8)j6eVNBcT*!Vs==p zTKG5}kDP=m{yhKU_FUfu(_(LHcha}_K!AhnV?A*=U;H(kdaf_-iLv!P0^B*hcN6u^ zkOWwH+vDrzY3-d^+2;vlB|Nm=p^HV#?11h8M`!gdJ9+gzI(D^tLE zYYp`|Fn!dD_`9xw_r*jAVFxT4)ip9zf}4R}4v7HrMs=B`XAk*_^NN{^_viDMRJgOx zs5Y&I)z|B|fa&fq!_*Ma;H3JSc}jsg^>9#s#un)$U}XjMuEpW2lEqU9fcC?S=h_UN zTZzOe_1>+7p}G&Pw5#Gd!bpA1Yb3;VPOr141=?9WnQZ=4EyXX*^!!6YoXWTWQMn&l zsJg~RX`-Y^BQP(~xx=$Mq{uXkez0!SVafOt(R+X>%MUj)zx3lL!0#eKBa=zr<_ew& zw?rU@YN6Z^NS2e2I_n!EU|4&`NoNU7GNC`IYjCi`nd+kk6+3gwvcCz(y`bCMA zl#G9wS`K$*X{uNKR1;Iu*b#a`rR~&@hB1yhyibY+=51=RU2QWTN)Qhwz0IgYL4z5C zmm+c#m3S`JylO#qZ#z7{;a%z!6K`NCJ#Bk*ud{0Umf{@G6Y8j#062MQh*QOCvC2wN zPfNFjPb~d!gWBjC?`K{1Y>!*7y^NK;gDs#PAca)E~%0GNF4vjERj3S2)T>t3mHyF75ta`k;9qB10{}|T=7lX9z1p{n(t~!RTO7JxO2r+j1MA8S zRiej`wBF~1;^hM+Rg88>^ge%4W71uG;%4iCeS{BDVHec=x=BcgpJ@Pl(~^)7W%m6n zC(%TEJ^rf8@Hn+EOD1D*pn#%ycryMsnn5hm^M}hV^fq+yE7^bO%t2m^$Yq~re8P2; z&1CIDr(J85@ub;Z;e-+%nj5CkfM_lgny9gMJD|unmgG=(bNo)Mle5G;`)!p{hc zL#p&|cWy=n4Wj8H<_ap>1{-p8FK~Shq8(5v9-1Q#hcgftT*-qbo;bW#RHS?_bc~t9FMAx7w?O$gSrD+)@~{xq$ek$6hBF z4jM>&a5)2%tt0ExXY0*&&&x!@jEKF*ODaNEo&$ZqW#ftdl@gLk94FVOFNyQhz_Hiy zo;G+DR8?U5buK9(E`O9&qJF$7Kzzu2wLJA>7JgIV2U(g~ke|o^lhFrr;pLP!S|gx| zB{sAz2qms)Io>fxcNBpr^;t6f9Aowkhwtit=#*X2i0I`?+<9XEB!aPf z`@?78EfweZbcA%jEDWt1?R)d57m_* zfd1Dg{b?8_(s`Y(~VNTLi@YeM^_yl{hjhxVTD*=~4Aaar) zkHZ%3l5CSV*F}YZM&}9y(LMad0?nX^WzMPnn7z6<3}?+wq1j>T=P^5vYbXlIYLsGL z8<_kY$iwf)F?LfS45qkF+c1WtA-c0AinIWe-~NSFRQ$vY=P{cGG5%xiA?3WF>yWgr zV7--KDW80Sr0qU&3J~!3xOwI)2Qm4}?KNG72|I6`JC%ksF{$1Ve6VTfr%j@Rg$Hdi0I#tOXn}QtQ!p)2Hp!hx&Ow% zA&8ayj&P!h;(7r&mkQ#+o>UG>BFboan90jG8_q!84|_EL@K)(OjO0SeT;r&F5q=`D z;!X&WpuR42yT&61_(2=0WM!;m^I`l^La`FNxqT{#5=(od5{?5#s3{)aa10u4V)Mv9;Fi zE+e0UkWtLX-r+3Ok5XS}9Rlw5Dy^LswPil@eT&B^=WOdr^@J(MtTa8Hr)zI1h~Du^ z+)2ChTe_~bFjyzNoMbNBu@Ok^1AMw{I?4f&Kg{_Y65v45Y%k~f#uEsbg*`99(nhrs zS)FYnVI72!-0mVFaeT@4J3uF$ps?&IEl_71#CrXXN20fbVoeAPZhM%zcUP(Zvr{bB zfS(tsK7{?`bz4=#t;OaM=9#%j)%DKMLqL&}raG&M+rz49R*qp3k`r<4O`XY@g@_nVpwa~l>>1p1caeVL zgo+735WBtob7u@sbM#PAD730bN}UFtE3--7VlM|_xfUk(pi+oMpqZM@y2a8aO7^{d ztjD_8mPkuxPPsxOp?!ttT@Xcd1Ot2HXfTA`-9~!LxS2RHUjjO@*L_vlyg&k1`3(hB z+Uy*dkFBM*>;lh0W+#0g5q$uaD-o;-CW?(*@@fN~)&m>ntJB+9KI4Us!tvXF56w<~ z#7vo-bP;hX^F~d^uUxMZO_9X`LL;(wc=9c3)_Ds_IghXy9DLWJ_~qyk z4_MZwmYqum0F!~-1t|udi^p)a(o=KM&wJ#o?}PKHW^;*Sq#(8*?eyFw(~*P(9RFM3 z;Uzg-?}z|?rJM*e(S<~p-y77~ohQJ*)cQniocXJBs)r4q zLm+3#b&rmrTOB|#j+-fShQF#2Ldm$2j%>D1PWz-JB+fdR_Yucd-r$?Q_iv)aXPdiK zk^q2X2;?VJX~uHoYh*S2(Ny#OsWCC4xUkxX%I#IZl|#XXAnb#;#NG8#y@&h8+KuMz zD^i3vtR&mji^nTUBqWEflSeirByW2QRwypC=TEpdFWc-8HWF1C>xCm`l4c8@6GLY{ zf%M0I0C#<9Rue%;tZ5`l$Jrap0$h*S+A0)i86;x-9SnL?)~ zM}(R@CncJUh(dR!>T=`v6;F#pPPox0`@@<auT=Sm}ZjvyWS|}&UA#eV3?Nj^vMCyAQ2P)P5&o{Ikw(V{d4&_z57;arM=Nitpj{sL>9)IQk?evo1zjjT7Batru@kk z25pm@qHrqyGDHegpQYIedMME(^iq!Oe2G^2e`W)TnW#3NT05${RE|@~9_nXNUUp_` zohY%}FKsqNjmEz*C!5SMpQ%d`M`~$#03ULzDa5GTi{!WPJ zLCtyW&^nH^#E$?OJ36>`DX5Z%`R_A7x=+L@f6=vn%F788a#yU7U>^N^al)hUJ%%e94N6FF&&+P@z#FJgTT znyOW2N2H~dDsDvDCGk+$PO`(Eej2i4FRq{ z0{$56v_a9xqL?G3LUF8mWs2BXfqg^XyrAFB>=;v&XzD}raP_${Bc=Q=p#AXW%5-0TqXCGj_!YONOKku$GeQvHYHuU1nJ! z>SERK{Y$X+k(4*~lkd>FQ~qA{x30Wu^M*(jFRcnzwr`T^v;(4FKU0Fc|I3d`;9PmL zoigg2=>iZt?Y&e@%8=?s_-YLe)~W0|87)KHVBBZ5JUA>@OQ5k*Tx=4@UUFg5XOgvT zb%)(PjxiOFoDacSt1`FlaB(Okue14?WXkO_+O~AV9OD#2(@Ia&0#SkcDWT-6zrHA4{R0ccQl`M^ zF8uz!^ojAOt3g{}wA~)_Ctv@U&CfE%T$ckc)fSY^d{E(@`YzlJ*5q52t2srA%vr<$ zBGnc2gt|Oe_XFcl>D&*C)+RE0(;6DYHZ(L9QEX1OC3a3H*^6{^*#vMaxX`82gD>H% zr8d8eZ$ob-FiiPiCUV~8xje@1@@$naZ&OrPlfPN$&O6SglBu*oca&nez0dh#Xab=f zRJ1nY@?+cBw}2wjk6473@OkJ!l-7t?C5p{U)iKb;2#A<9y)6#Lmq3;epZrI4Eivx; zLW|(VW-WMPnd!)kkuv?Qc9_4H?>;#+U&?HHQG{&u>bj?-hZNl+Fl`wOcJ*-ZxUEnf zJ}kOgaR7lN4^5-h`!uB7URP%&dN^Rdo9qT8&Z#86u&|hN@|pOd(aSt0 z6!OXcD(5ceslkY2j3;TC5u>Rrm$`VQN?zq5?xurh2syPAQEAoYXxkIv&*<{qW{Qh! z=zR{SJLR!IT|Oa>u8XJpNXwc^s~;a^`4~3l2IZd?b)%37#jZ#dy|U9T3RySc%0~?e z3AoRHB%2Adsk(Kdt7VWIt#KyAw)Iimejr22Z?l?o87fss{3y~$Mm*~$$1;G*Ch302Gp}d7G#(^6)Q|3GIQfQ|Z{g&7>#*XB;g$#7H>qK*lR8j?zQsbt7T3F3F z9i%!;BX!Vg-&T!?e6IXSbFtt>mDTv16W z77DrO_Ra)b?GevA;XL`xx?ZkBPZEDhMUTLYbCc5Te`w@n87-0vEw?{-ho#EjBs zqOR8#c67AcT{ABj*?QxCqBr$f%{15*s0je%rSMqxCV!FJv{eh#k|Yb1rKG&oK24`_ zM(9bM2Z=bms#bv{qj?^jVyEJw7*d4Oo($Vx3Hm5@|5Xa2)}OMja-Uq>LE2Uy;?o=} zC@AO!p!rt7GlT!RkWC?U9Z}TD;B@d{xi`7u^?s#A`{2b(jhR9ChdZHJl|av9bkorW zD$$Nw>y@sQ=g_xj6{HGH;}z>0!WKp2<8vX1sv7+Fe$KsuF7c1#u8G1RA&YL^I&;K4 zC~rgDMDv?N^*Qa!e=UKb{{D_-veB0Q5pI`fjjvAB$LEaU1L$;TJORq=t&mLB+X zIB;q_Pin}`a-702)=ku?qGstFUnjrCA5o_a%CBl)Z=_B)n8+_@jPDm_Kw`=qut!QT z9@%7xZ;F1_qemQNQpraX#ZC;#V`$ZEq>ipQH#JOWu4vTKHvjgcxh$5&v$!dsc{X@w zQD={ZzedF=s@|`iZIer?9Z`Yb(L*_grPWKpLH zZoBO^fwhW}8@rZWsbc8Ep906R4`HK63+^*%k1h8eI=dI8oSvN=9`Rk0KKkW6v#G^e zcRuTyiETEmSrUcm)C=sSXf^xFrqb{!+R1+{oB2BA(^Jisk2+Wb>AZloF4Y>uw8 z((>}{2|5^x*(@ComakC+X&r*6FNdLBW`~3=Hu9+8H2FJQ2KG%e33EKCM+RR!#{Oew z<9i&-Fw-4=pQw^deGhx(#jp79?$t=Z#THAW&bQ7ibBY;{12_GwboY;>mPOd=JVuc% zTHMrk)azc)kx@XH|czM zpt7Q?x*gWvqI2DfRKt<>)3IyN7%Rr)if1(u!66Ir9taB8o$$*wqf08DRtLd6LGFyN zk}1ij&`b{TBR~oZ1b$y^UlT2BEJp9%q?Y|IH5&j>*I!lSgO@rr+M{Z^B=dd_;5x1e zYreG8m$0l@^IejEeu*$AqLqC-f_@}k;sr(4ynhL$;QRtY6=8Eh%3TU8i zt<+EQuroydc!kj$LpcOO*Qa(NbZ;?9UXfbP8Eg#aKDJX7Z$wmxeXY%TCWbo1GxnP_9(2 zqdo&g#8Tx6avmLfyVYr+3a(?#J3cf-PALIx-CXXbpA;O&;9E#uST5WRN9B38RcA&P z;KGMo@1X6v1LzcyEKrSksY&ub{`J$`U2m^iT=|uiJ4<$T89sb5Q5zGODmY-m2x@;Cw{4tZJA?B_B$| z5y>DJ?)*U}n=(Ps!lZ4_-hPH`Q6nL5$H)%DacU;!agfL-VuyhR@d%IqHH zln*<+o7*MI@%9r{I^1go6ccnPvEvcYBTJBBz1t`l0|ynUPb6CVJ9=Q^m>GGkDyKay zWJVGQh4iiM46W3QE(5wQ7I*4Yp4=bLP4IKWzYq0?{@T!2rDcK*?7Z`7wVJ9n4juz; zfsgSX7)nFyjfxZiC(K$iUHf4-3O^n>Ppd|nO*E%;kpN=ky@=<5 zR1!--eSU9S*^2{S`dqis96PRYNo;m~kF~gSLl2rOw@cjKTUsGsfxQFGqc z=r$}dKHjuw??p1_Su2f?pW9MCes?ep)IVr1_CiPsfNZ4QHYZdp%Dx!sxwa!el`*T$WvRP&xD(TOte_p;xha|j zcDc6171Ry4x5~^G&Kvuz2Z^j%a7_g!wGOpNoG+xiA|!;Z^2=&WpEmu5UxH{pTiyoN zLqvTdyJ_oN3=K7>ITHT8uv_3$?7Rjbp^xw@sp8mv-RPhvW?a06RSLKFRM)Swg(~Nc zc*?1J*9p?~N0r8r6_~nJO@V2LfguOmz#Mz_=BG9*qG znp)RAqywr@rw*@a-H5ICdp!~EQZKfBSaW}BApzf|wCqu^A0CpVBVK8`?8Z3oJcm(W z)F&IdbyE3k?BM>0h6G707o!7Afy;?0I|k!4CaOv2p)Z{aVZ!jp>{lC`S|IlH%k2%{ z@Qu%J31t+kHXYE>FSjpsqx8HPj%3zdldZ%zSi(cfV1wR@3Lg@ko9LZp+Inia=Wc0h z(YH;+CgBeXdF1M?3M#BnhLbicKWg~=qBO(fIK`WtnzX_7Q1xRyJ!Yp%8cWd;-S5e{BH>$0yu<%5vJ5AmhtMbx0+i}ZYO=aLl`Me6H!BobsO_Ecq zk(w`RX?dxOt}QSlR31+!=)1Ih=dMR&DF*gV*JNi``J4M4Gz>k63}D;-+N$#^*&?JuXi9s}%@u07Z&Nuu_@CwXS_*<$u9hioV^3NTq2mO0S&G zh}GU~!`ev5xFd-Fbb|JSZ#cioNQ6}0(!P!neQ|b?hXCC>M3Wb4PSau^szr(@aLIzC<2!q_2WUJH7YC_9s;A{idc1Cbp?Yy`tjBv3*DSNd()<1e0B^S!(6^q8=bU>-b zag-ZsQCsViBXc*}PRlI2C#%iTHVQEn7CmJ8xElBvs);iiYH+WcQKxuXeYzlHg9%r2 z{qBHyHle5daOV;%hGFd3UEI)H+l@=3Q@dN=K>SDb!P;j-Kn@SUXuI04vIG!KDdFYS4D5Ut;6{} z$16Phxvv+j4A$2?mDj&n(ByHMGwa?XlfASX8cVgv?`P}xV@aoit|&sGdp$$7 z>6b2<6Tg0+BCdshjb6fj*TKx3MO!N^aV`OQwlLXkGc~^ODf_ZdU!S&P`M0a`V_9p3 zH%_N6VR^1;brv%h30^viJErpgk9%m_N-sMxYLLrFun?L+gb-8@c)d4L?94fn2XcS( zC?ub{naYmVZV&JX2t|q>H(|F`AekSor?~R5p0ppwc8Vt)TSBW9;EK^hFh7#^!jq zW0nM$l58N5#dyu3ksDHWuV*&1{T!UH)vV>RfXe6-w|G4uKBOF4Q~6;&33XIwzU_o9 z-ZAW9nDx;|32{wmAyd@Pqj|C-PluhZYBx7dt5q-erraB1`>yBfOiRQ&`>W20cNjn6+TIS~2ZTF1&>_&&0kCL4^e zRCp%yXOyFPqD9|IKw^fIk*x~x*IKVXz{u1?9v=U6~ zpptZ?%e>Z24*FPs7#0_2(OQWSydFhqGvr%(gw4z_^ed`8&m#B`2&A-7&$V(FKJc%e zPWtXUk6g_Zca7wc?;W4ZA?M}1)hUHhigu5UlB#n2P6&;tLt>PzH*Q`8ya-fWsVvzh z22vtven-F-8Eyen#S6B67?Vw+T^=mFF_9J%nIunN`X@x3(xadL7&YvsjrwfLg|IK1 zNz-!Y%Ac>ALQ_?i>4SMY!tYIi%EJ1lD*IOh4=HWrdZ<%WkuWCrWEikn zWJXZ4OOe8oi{AYm&|CdaKySPfIB>u609R$oU(u5>xvL6@e7Ly3rDb0b{K+W&u_PnF zD0O*p#y*U5j%DAGb5)LLj^e-8_;#XQ2MonjnPg*nsr5rqo|$c}SFOcuq$6)V$oiln z@ShN{0=qe8V>ENO)W`#fDr9he@}YBpp1Bg_p(N$pq!wMe@w}*Sg_Ho8qled|XMv_D ze~PEh3kDy4<*4u?!ud0{1!INkH~0O0SXR~LG&!U*SOYkwLi*0N)wMMx~jR|F&FHU*yO@FuF&(98zTo{YImaS>5=7eNH zD^eN-^!zun{Y&oKjiKQyYmvltOgSrE87tl9eij)@Vz=bW}ts5H{@F^$5jkooJ zJa>mJKeXO(u$qRIx8kUA6k$Rfqt_+Q0x~6U{-XU|eD#~2aymyIkbs|WRv-F+vz^go zh~9WC+hxj#KOujS>tHwt?=m~ddf)NQpU3?$Rt3X52nHf}*{e)<|Ad4cZ^wvTsR>*- zyZY|=@7$5U+Rr_zb*stIzv_7TfAM|+-|6=@#5G*mi+}DE>tE)pqKEfxbrOu2!0_`o zR2L34olnmn|J4S`uX!6?0^OS5Dk z5KSkyt#`9uTA)4+E2+&25C}mLb+Dof)sOzd45FM|uBqBu&E%Q!@m(Xsv?Lp)_zjoP zD<_m8efAPAJt^AmV7)G$@j=4b;fm|U|KakSOIlLm-QtxM3pWTycIS7x9L6im_ut>4 zJ$E|CB0g3hOm8JKw=r<7`!`ehdo{@(^)pdZBTi*y1JNqX`nyLw4!8AH7@^n~n>{^& z4qbMu&Mm8_;Xd6itmw_Ng?K+dJgMO+0LW+wJ`c|2>{Z^>%64PxJ?#(%F&U)l?c>G$ zPpqf*sb+3*)0H6W+n`O{(fT+eW=`F(_oLdCC(QK#;t(JC<&_!Yq&&O6$5_^ z%5)31kbg!v)>ihO>#s*wzp+ucmVd?2^Y~L8{a%sJ*(g;VZnh%=r4Aq!yrfdIjXn3B z{fs*;o$w7m+m@>Lz*|OUc2#A>aP9 ze$3we+`ZUVi>|4o>?1w62r912fDH{=;Vd)7pPKH3IQX2`q|+58jp#{sQVr)VJk>3c zGaCKUd*f{0Ln9XBhj4QyUTXg8#8Pb?n}{2KgL_#qJT*rp(B=K zA@6*{V)o8szECba`k!I|S_xmnIgSd*$OIEAJvGAj>^lq9Q9>v$LH0kn0GprZW*cQG znN@SxMXKzMalgpDMSjKiwMCu!2v6?+gjyJ$G?pxGQ0WTpWt9K`{35R^*Sqy|yOk@G z#~hkgeHT46mTejRUogzn#qOBr)r1FYR`O2P>eO5pGj2*_Aq@EcxZf)i%JjWQ_ry?H z1az_-Jd<3y7Ja_9Jac#!z;R|g!=m+NS!hf7e5%yxOf1)2WpBa(f^jdJsv6XeJyp4z zjNk4e#em4yA1?`0RWB4Oo%1g_)PKYBx%Bj`J!V5K(&<3G)#_pJ<8}{*NHFZ=uuK+@ zka$(=@yn4}#NuBg%B6O^Si32pkhdOR3fElC4LgFm%B-Zco^MUWX7*P9`njvZs;8fp zwPBtO(Uh+*X;d&GI1)wi3-B;YRB*>yf!4!bNf73lPOMcB->H|T18>!`yLiuq2-WNy$M18uttUW71XTzfS0Wi>@NME0 zm6YR;U1SlUWY>Yxc8wXMD!1(x-K6{%k;Oc!b?+}gYp_UD3zdZJj_`gM95$OQ?ti$L zK5^m7JX=l6<48Z@zm0MmX;IQLs4`3F)t8yg)srI%|HCl{|2-(1-n7*byv2sq$5PSy z+&6ZHGjhuBv0Q87@ZNlD&UoheaU}eFt&UYjIe*V+TLs`8=f$1!+B~moBHA7Ws%C?WhK8UO@kSrV+YGIpGvCtcaPW;$M3O_ zjw_`TcS6eevAtVdgG~>vn}+Qs_4bUdxsIXDPuB@?h}N`X(pBPT!{o4WGK%gDfr#3Z z^4SKk?}rAK>{YanRwf^_VfjjS9%~(bWTNA7E}qZ%(>!R)AGbI|XlC<>nRTFPkc#4@v$dGR6OPU} zz7xluYl>m{3a4aDS4vnT-CQaD&iQ!CsqXyt+UsmcmicZpm8CcVh(Z<`ZBIAFPeV1p z2S@sRD^c)irBHPfhr}I)+6v41Vvd7K(onnTQDkl3#&C(nz)Wg?%asDXc=XPBs)Bav z@Hd^qm_x+^Mf1%)8xBANi6*i_X>^8Q|)q=++bi zft|pCo!sH&aGG2%#kmwq==ttJObDVd*RS~ol+nQF^F^Bs8z#*E(iO%Jur4W3ql6i; z^LF?&5Rm_^2A{U=Kke5Vm;C86KAE*Gbk)jsg_eXX=fQ zzTi*oay7>64x5or{5H=wnht6_3mzVQiOQg0t#g^*sxox!0Uo60BwmnA;@dWyLHU0&+E z2@l4VecR4DVEh{27T8(=;ij+5n^FxAxt%vTHvZBu8ReX(6r9?_IYN2|f70?I@b=sw zTdL8dx0Qb4Q}%wh?YrRWqzZ+{T(gr|-sG@?B@s__?=NZA4(rI7%`fN5&EMQV!ENvl zombb`MmCstHdC5vW;#+%al%DvyC_kcIv!&T>n)lzh39{qKjOA%8fv1Np<4KCvKof^ zk7145K-pkg>Zs@N>ZIdaiG}O{ervGbIPw9jq^w$V6KsHct5$fESRTq%>&RC!*`X~f zvobUwEqy&|EUmqYPN~IrqVCa4dEa85&W9)V z%;d7(E5V#yyG7-bM7tv(aIM-&FVd{Q3muI7|0MU2kf`=_aJhB+G$fWaQuZc!^F7O& zpFC>Sy<|94m-a>i^r%qo7oiur$76gu4$;(n>F`$D|B^VLikjfgHQdeYHKu2xC*@+SW()ZG zYOG1-1tb8BSed&OVSJk|FEKPQqQ;;gqx0hS;^+URti8nn2K!!q{4^r?h(IMVpnCHm z*Zmhcd^+(q_qndCPM@*Wd;EFEQw}o=bB4WbduiKSy*uxpYT;Q^=V?tcQ^8fH#`CKE zWOTpIFCP8N1F!y(VWeCBoul=g%pokDVVt`0?H7i{=2%S)MVwK|?0tAuqM zn@Dy^| zt{4j%`_FrSi}vJ`)zDv_FR!?FmEdIoWHx*^FBc=6=eQ(x@7}#9Plo#X91pi=wY9Yg zaDBbsG*Y1BFqos1o}NB2F~P#Z!W#c;Ge@ci;(t-kx(x zv_8I`lvG{kyciZ1rf_<+AG)&G`8h4^*TDvc;{A_DyuFLJQmU2Z<;kyJeXV=YST5N3 zh*0gw!&5NZ7~Bh&I&b(uc5rZzn3x!-@M|c&-YD*A6DJvq)Q&3JO2xs2SP#DVg5S5G zuCdc;=3gGB@y~fi%KfTJ=2S^FLNCP^soqpmR_<99$jw&Ii-@QwD=U*@U-IPhPy2K+ z0sHIM>(pf;FQwM)3`1gLwZiFvJ#Z;jCMJVi|B|Z(R4;5t3IKh8 z+K|f`al{42wSHpR(yRy{AD?zq_R2U~c4MM~6hITQJe})Lu~)6Eq{NXiDa#*s&m*Y3 zyj-15JKxgI(iHH3=d_UX8E113O9j*Lozi}JzrCNrA`eiJl;~P#@#!|0tG)_zT-(o( z8~%064TDWbMn@~|e`kOH?uV+DBazv2MvhSf$QOVs2{zmB^cOEy%NaZWiPK+3t%QaxItzv@WUQq->T?cl|7e zo35u`P56_zOe{Ufe?Kqs?B?ZEDJR@QwqpE%z<{~++V$t{THJv3}wodW(3wEJ9?Q7fc)_VA&J$N^PdjH{=bb(r%ncy5kbPWreEiZ|>96 z(}#wJ67~4xk;`cb(ON9^7=U3r#b$|1S2B{+9O#^>G_0!a$^W!VoJy7a;5IOE@vS(Z zjV8k0+*}57dbHO)>%2Bvz`0#}?`rcwwY#&k_ufhr0^xx6-gk~a87t61`1tzj#<{t> z^Npt5Pbku{OR+;zu77!gFeQF4JG^^x}9@vq-cdpdmos*e#)@8(2>jp9Y} ziz*Nnmd&Px8x0LkOuhBJ24$>#h`hYjrKOhLlN_ZaBjS^Gt`PsNuo`@jx@>4@xajO9 zx)mAb)%ol+5ySPNhk0VY3^tR;*qb3haGrkf?;FJcwQtexzqsklI`Hu3qSQ;Zd&F@v zx_AEp?gpE;l=hP^;(M~-XE*tbYH#1Y+fiyuRMxfse;c^yHQmyZKhf2BUIXhP$W1td_+t+5ej{ zva_j)(h?LH7+6;3LZG7g6N4nSb3RI(TmDpl5dYS^dN5=8uN5OX4Ey@AJSL3qKbQP~ zt^5mbNJwHS{zVT&-KoC!e||E&DuY5bbm1YLC==&Z9~p+rVa<;|%CX1EX>!-x)4DxZ zi+i5D{Jcur@9OBl^JE>r5aPywM9sPOuFEa8u&`?(plZ8s`HmHr#HSHcj%>cs@^Ux+ zM?$8$lYHA8H*&HaMc@@_zmzMob1VM9ix%y_Y*2SL{F@L==)9>qkVH@Av|NWo8iPTXd zK2sGZEkED<_&Sf88g)qqLOcJQ=U>!FLQ>nhW1ud*j>hWD&u4fQk1bTZi?aG)F`cMa z^Zu>=UIz{)GitGx^H*KHy{3UV1oNYKGWY$z}<8V0ZVbiXGK}2bQzivRl z$ItT=vVNG!&dvgJe7~Y{ZI=)7D*R}#uXd74Nt}|<&3P}B6VTx|k8*1HUJOLn*4FCn zGoki0-<-WTjQJs1R)_5yBHpY8548ckc!XeTXZ14}k} zU|Hv{xF6ULSad|}y(fFC;^+8!wyMr9$=l0I5W6?^(awX$+25qY`w=ol$2hZxgM9B? zp)IV+Wy46$S|0x?hSq#2qF%+|hWv5#ky_g|@v@UvmKjekFRzN#^W7ZmV^$+u>6Y;4 zQb>mZe_87Iw9jX*$9Q0EtzXq=gTq1wMj?Vgmc*n`zWHEOF0E>=&Q-qE_6Yq?nPrF4 z2&s3UsjG}_XCCXPTEy9qD{^1RUz|gLWSRnp=e<2)#2#)**!G;sauM_33vbOTWPPOA zM(y%GBkb2FRW*_2ejU2~Z~T&-$Ji&+f$L+I_$~AaK0wnd+5$eXEH;0J z3*B|dUZ|taW1JYa9;$=29$DmjEkoL_*ZZCPS}njso6M;T?AJ9>GOek0Q`eo3?~sSJ zC6OVSYxcI4?#gE6IOrEFzTK*KQ|~qW8ZIt=+6pvgbhISmqoz5DHQ8_LdX3u%45=HCZqYCQ4iwa#e7l`LDFR?W$zur3wjhls%m z-?O7ofeJjIgTq4_E`Ha$HxfiARbviU#wLn(bH9nNA5A|Cbe?8O60)Dd9!c?jUFY+4 z^B(@0U`l7>9_gWF8Svy>YyM0mZ`^p2HA2vcNw36s&h-YIZYD7#RIcsXG3?+_ONDpB zbwkwZZAD2*gkD4DkC2BcPKWL$Ae(ByqyuIRSZ}7w^lC^wUdxH8#@RI9qn)I=fVdGQ z>dnYcUGz`H0Pdp}fM&q{1Z?7^`c8>o&~HMl@%cV>9Xd{z~HoVM`y6`xby7WgOg?d$fBXPJl(#>1*; z)RrQ~xLk2G!PY7RA{3vD}I-FlIAMt65BY}>Sxe#TD1Bev)T zVgKVS>G5&RhSIV6#M!(2K5+2LsY8k_mPBUlL$%7!Ci9% zNdA+j>*B(u%;?sBf_Tw~ikNoqO#z$5>g2VJD}GqBds?TOYqZsG?4Ok_$771)1Hwg-uB%d|2O5^ycFAtpKVm)}UVqVB zT@(IgGx%|yiImyy?0p(?MTq7Mc-|fE<^gBlp$xKh3f~Sz;*FF&ZcDj2YM4?Fe}_jo zqgqR+Mq7k7Uw^_>jy#nUxem47lB(=@Xb-v<`3Vm zH#`f3!DfG5$`?3Zp1x6jC*J~(O-lNJ-=w^)T@dA+JOkyNFA6G39vfDWR?hq`12kO|89>AHQuw9wZ*Fpm-wH}ELI%~TIh}5 zc^U-}t;Zgf-gqi%uSgTz^^El2f358b#8I1$Epw?4Xn+W`O$8Jyj+Gx_?+Sf}s;|br zmsT{;LQCJj9X9Vee0oUNQ+GmwgWsyDF2}TFq)!w3Ny$?_A4*H;$5XRzPnhbt;a?B* zwB!Z?8f!I~kA&RRk`MYVKGrG$>Gi>+QJ3iss!rE?i*A ze}}HbOL&>MLtS~gLd?AO=XH3vuX8zBa!77u1`zDc_!bE(hOmdhm#o^ROe_176=!UD)lz^tBgq$m3690qk- z@Hj6NVD|XU@RoN$!yA1a&oW#dMeBw)c^mvM!`x|mleQh6>U+?(fIZfA>p{w#-v z3zy#_K?!Oi;QHd#x9ofj5qM@@J#;1Hmh$43B-Jr@`w}Y7uFO^qsU_9)tN>Gbi#NIX zg$c;-ay`W<>^EXQB|BfRUB?lc8WQ~wZho__ z`^L?;CDf%Wzq|5B-}1Pa>RE$2CP_Oc;7sJL_Bxk6I?$FU{T8NP3+5{L1M zcLXOL7TO@>#L5Z54S7L9{I=qr;@q*H-6p)G3LaMT83F7}$Fp^mj7KdB1ey^xwTI%R zI(EKXc+tP^*Y>B&dSC%`PWYlA8ye9o$*nbZw&W(UmgVyRDH}h92ak}9GQ9K#PkPe| zc$kvh%ht2N%DZV5f0~%t*K=OB?*~k8N0?iv#O}w}=7EXw6`M@GNTQ5Q;h?hRWF+ls!W?`EB9H&Q#%H?Ob*UU_oaG-5P@s!pzV3r=W9jHRaOfnPIIhR#ShGMq|YafXW27 z18vdgZtfEV1nAD&pX?s$v2Rr&l$&a=Mb>1_C(FypL7dEcE@^e7Vm^dqxJ)c}Ao;jr zxq)=1LEw`)pViZe5A-EgR^=H<&AK#vUk>8vuMT85l1C-B!PUE)T5LRkzUH>8pZj@9 zuH25Czuu^6SB`!Doqq98u*DnzIdDW3SNoaq(Q)MtcD6t=i0zIt>0gW%VmNAOuUa$#J()R#x^VvEIL-rb2c^qZFyS z_oXm}%Gn+XTUt2Zb3M8+!L{oe;DH=~o9FvIRcvUZe_c8v$_MPp+(|^>ksqhm*U7Kg z^orrOUM|Y`Pi{-Uvy;~C=znw%)KoqA9YeE3OklG*Z8kZQ+k#y{cs=>8ZHrpI{A|Ke z=OTs(Z+GUD^Udp{#Urq9MG#d!@F(NeFZJIqfz0kG2>Ja+At5Hx;KZHq&;VWJv=Q3T z+*xs2J5u3?0OLpB3$(FW+5i{;Ay(;nd&u&`5BHO>l4=pglPQGe_qaL1$C>E7>C*EB zM?%$H(57eHSm8>;GzW<~R7|E*DHjJbquLrLr{~b8ZBawxXE%Lt$9|sm%X9WvnCY7k zgTPWs!;)1~>E7(2dU`fuHx@4NC#QaT?WY-#2PNG=Lf^N{;VIH62U-5fDeXQ#7vG~T zg8@DYomU=lTXdq>FEqZs&KMm8rk(JwPTm`|!R3<0+v?L5ZadnvDP9!|9&bmprwG1` z-raJ>Q*-aV7j#hx2EEP@nf!q(SZ{}np|8q^xN;G=aJ4G>t(*-0@m_tRN)U=80$DY? z4`AIuA?1M#lom?o=rUEnO!N%j=kMchz*v6hz|yx+p2P9&I!rO~sh7&!{J2EiP0LR= zVq*TTQerX85-UWGq6KCLk5Ec4DOzak;)Dxj=(l$vU$V7a==Njbh6C2wr}tiQ-DXfe zn;9L~USB(;p7XJsBU<1iK=ck2QAlcc#%9Sa!3boUi&y}#!^OIX@^-!S+xt=JOu${; z(QM^lubHj`i+p9YQc;4-6*L@bmMnz{(t|i&)ym|Orv`K981|Usm4Dju8OCFO4(8DJ z%vf(|8FW-5+I z#O4yiptC^MMlaCLj!R8tqd1`2gKm0PytUk4A#VlNHa$#`%1*xXjxgp3mU**nH`ER9 z;j2=Y$7=Q2xoF10{_%+kYKETX*2-bJuDZ8Fi_7R|I6aW|zf=&jq{jOX@p;B$PDkOnpQHc5(NFg}Xz0%Ko_cD-rhdn+@}X0&1}o19RDN!95(%N56kesXce!CM+-)=G zd{hywhqCCiV|)JIW$l?kLokSaRo{K*mIE;ceOiV{X&(mch& zKY;4qWtZzb6&9U?biVUAgIuEJG7z8Zc)X9%p~6s2lMRkAp)=P&gOhh`gZ)53hTbbJ zfzalyw(Y}`!D*Q)w0O%=I7Lxi1jb|w>>blQIS!g4eyowg$8#iNVX@7zVEtQk!cOo? zLJ`0&y7oJ{ji@w9l)tClB4(kv=5gj%@1<)dSyN1%VfzRBxZX9QXd#?bVIk|S%=PBO zcK~Dh&e+OmeIQU@Z==Mr>hy57m-STd8{p4TXTJS~_iPDz=H=SuyyBQCI_@EMx4ZTw zVVu7Qxrk~TdfY9345`+M+NnUVT?z42FT0)9PIQ%MglV|bmB>6SwPrMd8>T$;*Zsj0 zkmpfOSMPbDQ0uZ2gurF+t43ef0dQ_NR_Y9nQ?K~aF76do8290a5si}ZeA)pn?GE2= zoMX?cZlCth8%pde0b=q7KHhf#03*u@ZCj(NKmG?<0svsV#^ubBhbX!vwHb%UXu25w z=%8R~GX}p(u4gQ_Ah-DE{(eaC&&hUFA)pLdPI4KM9o##oem4mDoevtLY$lVrrt)T; zygS)GBD3KEZm>eO$gjhLec6P1U=w%?g`xA>*n%{IuoAScl&ZhnFa?_XN;cWN2x z*GteGEC*`c59fODF`IYJUnyXbzo#cO(IJo57{R0^blY6}>AfxGmWrCz!n<6!X|5bv zAaPQQ>Tuz;ZX!WPlFfSlUO;sJ6yj|OTzGw{sT$;-X*A<yh4v983qyGgL%qG*u^- zloP^E3jHX*?k$lo@t^6us$r=)%2}J?;3?nSH7}Ih*g9lQ<+ob7w=uA;i7xCah+XWS zn(EVzpb-Y3)flI{W1e&s?A9YoHX7&3sjn^$w-;gMUV^jviz3b}OHB_y)DFVYO*bZS zySRJ`0LUDQU8+*wYHogJBVfw)C62mT8gajy&xD_vKRozW{A2#LGrq4LbW*wig zvY0Oz)?b$FAsu#MSw165U6GgQ45s>+ITR zyjnD3!yflP!UAJ2l^rbF)uUPsJi;ley#6wkUl^dffo_c3W0c#Y=&zb0)wJ1t9X4&s zIWM~OXhw%N6=fU+dF-%dF!jg*5`lfS*91tIn9#{DjP9c#4GWg*RR|t>r%a&C)uBN5 zs*BP56bJy|BR=nalF_gFQS>SFrxss@6IX?k(^-Ye0iSi|NUT`(vYFaA71f0z-_g=^ z(;pYwr*R&oWOd2BP1*L#Y&XzAFKRRFhPWO^k3+!+PFDW-Sg0D&uEnMgFYmKlbA$Sn z{mdR!+}C&<>AL8stp7Y~E|8Zv4$=rzp0L`r_q@Z(SQ$MwB_8wygelrRn(m zN5gqA_RpGT77NO^&-PQ6MieAPy|1pl$G_2^UGgsQ{b@}apkF`9#(udQDrk^0-1lIs z9i$?lbCh{_xod=(Utqm!^zrIP27{yf;E+rCd1`o7%@)~S#s>&ne{=Q5&H9t*h@fPw z=wDQ)Q6m`>SB5h5EOgvX{Kcl*aXJ|aId*v;jhuEVqS1szWMrHngN3uE4;^HTO`QIw ztvn%L`@mw~mWPRk;bS&5+RJj|SNgMyGG@P;weq*H)4-L7$zfiBqR)hsXHnLb#?#>U z@9DY^sh%N+pUE&SkbH1Mn2IAt2f04tfNJe0n!dy9k`%FglNBl<58OLPS7DrLOcYEe z88R`3F2w2M=k)JataV8}FQbmOmrMAqP^H61Yd^Hu*vS-Y$^RAi2+jD1-Nw*&kS;ZJTs zmpcn%p(*O`7RI+|#2TH9XYEg;BF?Xq!VuaSLtI6Nd5koG%E;R6;6GH-rk+-iS;;jG zsZ9D`?sn@Qg5uGOXGbdSVp zCqt@or~{ZbluMnPKXXBesHSRmy)1uJjSe-x>fr2TYPfsxg-$Qf{Iru?ac1$8P}Ht5 zBmG(#`D}Hf!%`&Kt|=1@&1T=`8*WRmlq#^)6UU_K=;6cndLHADs%5bdh9#mvdNV$`pJ5L|aQQBw8!%(NPgIU9q`5SD|}B2j#b&=G?yWjh807WzI7t34GFe zo(tUWeBLG(t2ev5ogp4##3n#{>PcFjwWdyI4U4Tiyt`jY;JG6X*N0sjEgh}I&89aw z&Pwc7&a=A>T4qAzazGma0t{?qDZ%uTxdnke!{ApAd#ewDrGc}>Jd(Glp|kpHkUJHB zWoy33_C;~N&4Zcg>G&5Q^V(G{H*E}h67bc~r%MFM-lSI6YK}PWyP2pD7p`K5SI*#GIiLW|CTDdXIKjkx}b5jU=4 zI(DudqqmiD1U|cd`W-}p(lCa$XmuZ?5JE#i9%wfD)dFbD&%tt`#v{zQHu;BMmYW=x z1eG54ovsTq@kcaMzhceDSw%-{WW2ju&eY`OtbInqopnXuWUj$WsI*0qiCy(A&eX0c)Y@O0~vgUe-!Smo{6uR|ZNuw*xPt)jFb(p!lbo zC9%TnOm-AQwX^5P-Vg`DRO8v&GI*Sv9K6|Tz~q3xZN_Lt1e*Z>&>rfYR|l!@1L#b9 z0^qNrd@eS+cQIvA)rd#~;ZFJZ;5?!TQNE~*&rQpouH=jtlUW*&4Eb@}zh+FE#^r}1 zL{@vI`Gx)T@RnAH#yi2tQ*Jy0yiC#yZZrVJI(l?{KcT7#8ctf8l9U9N`o$j2+osiQ z&S>e;l9z}JH{4a_Y+c*GRtHpBuatBj654FpO;9a=qCG$UQ(f%d(JTaw;U2UYJZ94s zopzuwy15;VOjVbCZlcV8X1AJb7qnih=jQB1{JUT7LDmYYQai+~6NLy3nOeMf*&>k_ z{?aQwccH<%*~^_7IEN+0M3~&DE%W?Yes#fX&)RQt69pd=)h^(O@{Ee>&fU>VOp3uS z#tz9UH_&_^*5uRDQfmb*ARrzN>OCJH9rTtMw&?P*&$=3qp zGh?Ye)jlrt&{KC_&z(m@_f{of~*n44Q!%@=XRi(-rKUe}u9hrS9g= zm?@Wn(F31QbHH;ZF-ysd@|5{h`FP1C2vTe$ zELkqo#s2s8#^z>QRFr{@^|n>W!eom`kpup@c^QBEr-hb&pt99>x-DvaJWWK7;#KA8 zT1@wM@5`-qiME^Vk8Da>P136W{5WHO=EfuJ5`mxd?>!*b>8H1KJ7Lbk%D9*5w%~uz z3YrzR+H_c$Nh{&6jyRDGnZJs7Tj?cOS03ij!V+o_7+s|Bo`qhx4Lb^O+eglQGy~VN zGr?0ckBLme55b}v5^MXC+5D~ZJhf5^lc99we1@{{H*~_%w>VASl=`lw z%j&Hbio{aI+%y1{lGggv*AH8>X~oa07KSn=dJ5jA62Bb(zj0Z(tJp3VGw))T?AJm1QB?|j>>2N>UOJC}w>tHC1Mzcp zuL`v^CKDaNT=$=dqM?;GNTw3MB3cV){PpFP!@+ z2aW7XolLr+i{I{8r_AM{pw_7nfwnTi2)NC*Uroh)>g)A5lfhso5NKS@ewJv#ZqVq_ zT~zi1>goSGtl+#l`VG_WQgz<-e%!Uiw#wmBQWjmzp71pJaZl0ri<)IO-hoITGO61# z9A?m(5ZJTJx_co@Hp=)Exe&t3nqFF)my%-q_h!@Px4ZKBzH*Y{3~r{=?k58<)Q1wh zN(MoAuR7=&fYQ@+5-%x2rtSF`rNZ#4Bz=85Ty5EEx^x{ffu=D{ktuQ=O|mw*q>PDd zahJ9Td*<~R+FYQ0*&cZaz4^*H)Wdu#LC|KrNx*56AYU}3A88j6)?8z{cYEwLLHxQ* zSN-{fho*rHEQw98&hu=9cKk`qPBSlc^PQ}NKgWJpx_dRE zQCyp!p-D5#G)1BH48`^Ul@9~4$@&Vti#2yBLhD(mvK zPsaWQT+qzJ*9?ofn0vZy&-)dmK5?`{Rc~v9lTPqZJ3U)zxO2CABcIt!H#XG-h#X&S zEaGh-6U^7(nYW(LI{ezK(@P~`yv^Z2eDAg_%-We%P=ME!H%ID$qVdc09~DpxN{HU! z9l@6GcxmIhh1mTuw!2E+5ufX5ygYgRK1AQ-tFjy0h|w95@B{o|k}q?rr#eK9$F*q5 z#<~2peIR~dFr$_o7JS1+j9=;elKDsSz$<6|53a=D?l-RNDJe`v~BWqUaF8{+yG#UCQYRt1`RmwwH; zCDjykKp<7&tnw3%jBNtTLjS1kj#L@~x#rhJ&H zQ@03lrmnjn{SGspz6;793VWrG&LMM_$M$Rn=Rwt=*O(ZC{?_8{w$j z40pRfz+Fzg(rv8B4KXP6i^y;gujwcszGIgz2fqX0%d2C)E*DGb3~{4K#YyGK%4S!T z^x6+YJinhy9z^R-148g_Tvu)S>C%bw6)le&3gL=wfmAu^h1R)V^C4DE5*c`RmgmGp z-H~9kS>Fi-AiC*$dPzEwVw?wPg^{|{xi~@8Je`SwL@`+AKS9K|2ZvW3)_XevBEFW} z>Lm>ud?RNZ8BZ(`q;~_EDC+!}Zg%wEYL8z=+W~Co2p@om?9jUzUWN~}-9ORE$suO~ zcGZ^;d~pzmY=#Fec+l#V&H8=4c>H~=!b-IDzWp*bu*c!UM)hh{OfZm}vcyY>`Bn73 zf1a+((g=%=jGn^o<$l{c9v;+mesx6KF6+!VY^SQdP1x75*`v@0&lIIH^MSf&THZD9Uih6VH5GeD>3l)BmaKR8b7lOCtg{lN+g zRgD;e(9|F!U7W@Q6C95apx!Ox${V!+0d;2bMSQG(!m0lpjx*%wVv231i7*42*(dkL3?zY}i z`cA*(7nB0V?Cw8vNUd*_DvKtOv;>F$V^U;c6|c%Dm}#h}DwG;`0xAO{I?j5oOaL8Y zg$3hlo?;BAL;edo2m038LG#3D*6C&Nnf{9z=0|_^6wnCMqkj>mPin_MWdMNxfRCyQ z;Skch_iXgVIboR6Cc4@TGgU6oYzNann;V+0PEe|UXseL`$1?mku>7C@uulK!9Sp*! z$%reoIbUJ>G8ZNlK=1_rYsPkCD7zeC;D_?NH`_OFVDZ#{YR}(n$5XHUa|N;_|6f#E z_kUyP=)u?j^nY=g7)AR3!>IrN{jihE0j%Rn`cEtWJuI7i%_#qWa^{S!N09oQfnyF4 z5rk<$A^zAzR#qrG_J4m#VpDyNyXa<<3CHO$v_D5=^UuR_I_`@0R?h!$dp>6IZ2o#h zB4DL7WZUA~uQFbG#y&LwVbGhO+`7m_wP@(x9(ms+Uuc@%t*z*PpSm3~1)=q49)`q6 zCy-IzbT4*)gcT2=nKMGUH$Nxi@&vL+B9sQr$WB9<{|7U~(2ToEM$9J3VUv3|CcKW8 z&@}Rekp}YCx(=4@16F?O0{$2AcdX?kkNf(e@nR5Fqy$KpX=A+|Q$``KT>UZ|hx_Gb zMkkABog|m>Hs+hMM=~{Cx&FIt7*GoKzxPg=w8TduVMBlrm@i7j|9M^Q11EBje)%f7 zdUnRLKT|`03X6?3Z*iewUoJ`Zp^tW-?@0hOUoYU*=!uxi(3waFXFRQo@~aL<3Z1e1 z|2cV)GfBdTX7RLHi8{`dLSBMj4lsnMsbRAK?)xYop3DU7^w(P#?W0eI3PkmE<;090(VSfjL153M z)gvo^Nb|0<>byUpp6E%inEN9jMNGxto4lN#Bl6GwB(&pWkO> z{Z0Su_VzZ2VXuyCc1$lnJX9^aA@8}xNE^5P^0L&CO;Fyio6Fr?i}Lk+dp2^C#3{ic z5Z~~A8-A5Zra0E?2%Zm~QBnoB#A&WNJTPlk-lJ+Z%Pp=XK{#PG>2}%y; zEb=T45qgm^&u0?hKFNbqpU_?>S%u5`Zn%&?!=xDe?g&7<<-#3*?mp7_-8(pV@OkNV zuKh8%w7-fatifQ4*LV1^agdH!O4!z6jhe%8q0z-Kf~ zeP$7HFfl0Iyzf;52gkObQH!OjWu1Ft%MP_>q#?EQj5b!MYcw)pI70)aN4hG50cO>> zx+8OX%Cda*9eigWIUKSZ2Kk6DuHr((9ORaL(B)Vn$5rPwFV93>5;H?-0nsT+X|c33 zc@;|pg%n}*$Y}B{-YF)d#GivR0xA?Y+g|NwJFbx=ZkQlq)g${Q5D9S-6YakHm(X{4 zi_OHMqZ)__tP6)Yhx-gcH?W*xl`_<1SF?GuUKE~QtFTWo&}FDwz3NZ`o@umvP-L7} z&8+^g>#>Dna2w26mcWx3QFLkFLQb>W9rJSF$Sl^WK3}m(H#pwG0oil%_+};a6E7bt zns1!>6?=TWI2POLk?Q8d)4}$5 z+U;B6aDAb&#{1{8x^mtPMt3bN-MJ5G>-k!*(*<1sBZH|m2X?tkVGzfWgMnej<r_knbLv(b2@CYY^l?l^`F=n z^2FzPEl?51KV2h(gViQ#E6V4JhUyPQ!t<1L^|7ry%yGf@pGVI#;LgC1#A_YV>QI5i zJLBNq0y9x5waW=N6Tjvd6=(*5j!NmnAq5txDu4Jxhd=-?XiyL2JT~x%+QV-zsZBD3 z^%*O8a(QRHBqdA~IWT)rF1I1HJCb?cYX29j->=SdP-$gDGSiy(#`oZg9eh)S=OiDc zdLZVwHC#Qb1kg4&1rLU6wi36)p^eQ5OLXUBxj{DlfCh8? zx>&UMyEeOAVv|z5Nfd_$JO2Uu9I^kEBqYq}=?qW@L2e&KqEir~f(NJ1xxXZ-TG=SL z4Y8JmyMTN{NdRd2)h6bTLr}~!X7+-kgCDiRR=C* zU)McoBZKz?VR!4~nCSXU+~*q8BlL@(#cdkFi%39WPv9clc)ZDb;PDw(N`_RAD~b`Q z-CS*uylL=6+B!yke;i`$;7us4_XqKO8`mz~_hBf!OA4yhUM&*Vo)2U=1p@ns-3{*D zRZMGNOQfJm_?6KXoBXmIlcVi*%ZcUen$_|% zGbgs=yEYFk)Vu}1@cvruS3q~G7NuzPFCyZ26=0m($o3@5h}bkf8p+=3&j@1z0*j+x zVtvm8UkRDj?n4o3mLk&PA%pe~bhPZ3cZ-?zV%x0EL+PlpfS++=BgVnON=vL$N#_ud zfv0-q&WFuhI6>ww+Xy}nA%Cl$~?;jdf9NB(}tBUxpQLl1Y{d$OkV6s9B!H-t^6BRQNxIA4) z)iT@~g?m%s(!g2~#7s;CbuH>AShIx6+*n;^WwzOG+v=e{IXut|KHTBAqpcA}uPy^# zsB~YLYbSXc!dC`TN#f}@@TZ|cT;v~+U#3AQO5Rw_@f~tmn+iYIwI>ig+Zz-^=cK67 z<5>JKud8S3DW<*YWRhH zSsMJrUS;S}+x;T!)1FMJ$@>0UsR9s|K}BR`vTY!AQL4)4L5i12=IYgRxh{YPs)~&+ zh(w=VSf#B{iy>~)XlBs$cHtJ~6o0dhS2!)u6Fj-iEneYbagbHT4Jbbfl5Ftxtjk)aOq+ z%6lYGBg@@4%3-K8FTAnVV`3TdIJa89pfFi&m6J%k_zey1q{j%XLnou#Ja#ZoJB-TT zi;t5Dpq4~g1)015@-!N%(UT3=(-fGR zW{^Wx#oCrR#It|p1O`vbb59z!!<&&*U#JK;nJU&3TXaovb}Mv-v8EX;Vq2zI?tON0^UqDowB>F zp_2KCC}3@L5b)~z`Ap~tYoLg9u9*a$dNVvv=t0Q$?15`mIW~WB>CWbAuKBOkkEY}v z0eGN$iQO+^!Y-w?*h70zEyDe?sd|D09Z&g8cD&j7#X!BkF}J+=SQat~ugosg^H~*O zafBl@c+xsbmoq#1`{(F4M0YY>Cmr^~(iAz530wDMS2%3CH`qxVA^2@ggZ@J3Kt54po?*_odobeIeProb69-b`SS<%RzI9 zbQ9zO9iWQ3(MZMr=K(>%GE4x{B_SNY))s@6L0SB<7G0P2%H|6l%~}i<)qDkN1J$c! zJf)1lNxt`=(V=#r{wIuC6_1Q3)te{Ro7X8XphkAA{?M+w*e!Y9~n9KUL zsJWf>n^o_v&dORITxz>B#1Upc)J^A|3(6=FaW!W{_n*&$hQ#KCE95h)z8L#5ABdEh_xuK8GZPC@jm(C>eT+xqyGZeHhXpHjoFzSX!6l z(FN)+h_a}E=5Nl`y>IQUam#xpe_@t$r`@8dDBB$~`N=@@L*?%-ec^jKd0>KXVU)c^ zjCb!QA5K|Fa8X{gXf>EBh38_G1--Tb7;&#vZS1jbUO8>7Iou0ANW4%@!Ra2{SZo_4zFY&KQ1ZU4fuW=*Y^6MHtcmj7Lm;{qCb)+4ov&_uh>EPyUiA$=uux z5k=w)S&P9@)J_h3S_I+o{T8$p6eN4oeWX`vzC`2>ZFCVJ8{b~+v?Gt?1uqKP&1gev z9n4)TQE@6006t3JrN!lQk*hK30d(vjV76Jt3y7`@Nv7ih@QdAz`OlF0ik!`qZP4SZ zo69`U(1S}X8LJ7L-C@P4%}i?>0lns#sijwEgsP8TTXk2v)N6!v^0nAl@c@0ie1!0# zL&=!9QCHyb^L^Vi=k3vaQ$RA7*?VV`OrY+F`$&o>0PWFtzOcf(@6i^EAgQ&@(Rpd& z_Cj7@hE)_lNh-Xcvat!>4rK;{c+EDr_<{9wE!*y}ODK+4I?ZS9kvqeUX!O>SE36C|Q4fy@ND!h~eUk@FQ!w7m_CiJMnmh3FVg>CmCXg%R^!IP@4nHYX|qbs*0L?R=B^M?8i4< z_WSTFOJjWHw{Yw5Mr+uu7|1 z^E{VW0rSXDfF~Hz+IqKV7%mglAZ7RL62Pe=6rQ?3h6B|?pji!i_Iunb?%Z+V@ZhOPFG@E+!mcr$! z!MMfG4>wJSt@Q4$@cOd;50v#TyT&(Fgt;QpaRnPjr`6EW5UzBzo1C_h+iXlM$_}bD zHoXvdZ+q(}#M2-1O!j^Jr}r>W{%;U|nGNOH_e`HvlTx-u2)FxDy^T_O0#232($d{f z2IKwuwu&A7*xT)XN+r43ly@(F{PS8Hky3k`#C!ls`6Ul>7U!d`6SZ}vc@`NhCAY%# z+d#M*o!saIwJQ~v(vm*3BMWo;n=#+uX0Vf@rIXO&<71|}h&lTzJnkg<&(DURq3ubY z1UZB6+ZSNWo~QG%efb7CgwphS8On%H;totWxT+WuT9Bka=k^?_NgC)Pw+t`F0bgL#E?OiE!j(~)R~bE><*zmyVf~O_xERwk_u~RL0V!;am39yY><>8l4VDd2 zFZ0#V*-Eqs8ewuPt+qPqq(AQoh#(|Z@|ZGZJ*^9F9#!4-kYL?dKBHP_=vrybPrGf! zCy#PPBij2X+$p{6r%g`w{~AhSJj&?4;b~p+J@wqMl*P!3u%k>*x9(ukFUgW)!T46s zBf#gRdy6tIOFYcl;VAZV@)}WY>Sz-u-FE;!IvgL*BNbK^SAP;j!l%U|qoxmg`VPT6 z_*Z{1!W*dyfARW*Coh2`73U{sM^LD?p@3n9xoZCrh1~mR@2{M|zRNSwXU12Hkb@y_ z1GSD08r7xR?Mk9G_Xj;5QKcNeCd7m%@{FCTRaoqOm7mOKJ1g@9e2gBx@oJ+_&AM8u zxIKnU&%-+kd~eibL1MX3(`ymUpj=+h?N+e!0Tbpz#+ex99!(BL5Y_tgZTgMRG8Z0G zQJ2=6UGbb%mp&GzvnRDD+d)syD~sjkU2=MTC%-@tA6g5t8e+bGGOFN9&wbowab)P1 zeR}cMGVD-)cncYE{wBU~Unm8^eVNL%RA$xQ6M{UxgbW)DAZ9po*?V|h7oY#F*D>(6 ze#_+%2S(9;y0}}+2UH*L%-@dlr;C#~`DrgUIq+!J7r#CWs^|VN-)eqz=p%siHPrG< zmc+*R(Y}nw?~1CZ6hfNb)nZ9d;8kC)*D>74ZViWft2xlOjH(I@VoxsX5m%p9i69l6 z|4IbyAqZn&XVYYIM5visR*Y|D4UjEu`u3}%zZ}^Zmafq@^4Ar=YRa|^@7ym`7N_K8PY{OQoVr>l*XAreWSge|1pv1Jh z5p$`J`H9`m04OnJ8c#LB?=z-${T0zhgwp=(j8M3I;vi7_8^OZ+@X06UvHl9v3hR#X z&=w`=?b$$Va}eyU%mp6e=tsNBYBM}OQ6b&Sy>2sk7IN2dS>O?`CAJ7RN0{`ev2;I~ z-Y{t+gFxH;u2Xg~DHt)UCuU_w%XjxatVPW{NWJ)|t18Ur*PP??8-lykw znDIVND}jLx6YsK28>+Q5s#P2hnpF>d?QX`1IY#W0AeW3K+R;n5uXYHTCsIeUPiU;U zEfSYe(y0&R7!v%J*@hX2)q+T=u%;Jyuc(QZS_dA_KdYTyTF|^Qxf10)ddS4RZ9M*_ zZQre1PoyuFD)^`RP4S@7Z$J9hzPQ|1%n;;dP>^A6FAt-@SOp;ipWK9e!w}%#?1<1&2Vc~$ zC%k1bIwV{>GVAegmYvvsfi}1PeVqtbo}PEeQYAMDgRpdO2I3}~%UQ~9-CZ}@?qdT9 z!7J4xF#r0vet0Y6WeBIKUK}5eoBdj!>-VtOdppPm5lL)q6-x=|a2VlzFkPPf3)7d0PEYBA6524lHq@wRKrE^gZoUz%>F7IZMINtr z9>Tq@_9%=QbKXIsQ^Gwr4gziZ9h|J#6|XwD^)OhAn#3tW%~l)-YXJxqc8r$b zOacDZ%cYp@a^7F0cfY92`sZ;I4K=hLHuyJ#M)I3XH;2NBZDW{)nWV7Wy}vj(5WL2K z$^C3{$}(e;H~YrvdfOvP;mU|j?|dNUX@6BW9D|J6GM0^3XX@!)XdqWuR*;kNh*jKz&TFK1dP%c!W;&q#8+wtwpH0a)YZ5Qg{DY`n z_fcOw@HwpgWNi%VfWd?KPcb9@PP@7tQJBYkJyW0ls+u^y(Wzv#`T|_Z|L_-^537EV zqBh@NV=ZwLCj%eji^4d2917DH^!+VQdvQj3+g(4PDz@72OOnM3!aq83>p+ex zGKGhsw_OhD^){b=3M}@^Jr(Y#4q`HZwDXhrA*5gB8 zZ)8goW}FpszoxC$aJmvvmWa1U1@Wi2_HvMLH8!I{=#eOs*(+I?Cx7^UVt^3X8u?c+9T06qc}yHU7HO_bn&+ z=9{F`QIP-h^`pqe6)e6}K;!iBg%({m?-?o-jCwlHQLFap2EI518u-}PpB-9g+ zhD?`QPBo(x%KaClgY^ghi5RP(4@bUCv zI~xL!WwqOiIUiF&%%TzMD>eoAie`y;x^&~7e35Bfhi~Oh{wtiwMIvFhvOW*O?W)@2(;_}x4 zY#+XCK8@ly5^F5e#CB9ln~zKqT$W8j9Utrib8Tr@2dZo@Ago^|ES3i&69xyWSIR{T z>Mk$p@^rO{o%kb@DjkztmX0n(LU4leS#!j0hU>RC31nY)vkTX;T*C>^n!-qlD)#sw z_8#O-4EhS_?)xUPR2q&3pD~_>mfd59`ktYG1teOMs-lqULuy z@ywq&iWzXus*2v2<933oqOJj6=o&BSZLU)I?5V+$Ap zv$lgWapSFEh)p+omyEo`T=$7(!TXbDGbfJ6vaQYUBp5W8qrew7kuX4n_|W5VkFB9y zYYh;~>y^cpzOT6LJAj!uIe^p4oo&yJMA_nP>PK6m&z_{7P`!NA*dz%vS9{Qnv@e-w zR$eFM*U)TBX)0uX$5vUtMgtl$H5@3iB|mQB>by-IHS6UX z4fJ_g4pmC8J_F+rnxBs1}H_Xep zr@wICV=OVhsV#-9F9h9$MA7$y4bcUX;_=51|JpC--~S2Ip{82q7+M_FWSHz8zE5gtSWTp`f8!lPP)*1Lnn{Pfy4lGcp1#G!CDXzw5+g`qfO4%v1j$Z=OO|Q8;Ct1GTAqly ziZIKQ)|nQ>2kXD*b#A!e4*;vPiFNJFUFCSkos<@{p|Y%Gl~S75iMh>fE_5FWbR5E4 z{kE>NJ64A05M0K6KWJbMcA+N!_cjcEIIZ+vdy3KLz$xj-rwNh6DljUe z^(~cSHql!1iB02(giQrs)1uz5D!K#v2R8S5VU43zr9}D~N0A*Ckc%N+ajo&+KTDZ2 z27AZ?aL)p!FE6>hg_GgwgNEitKr2$cb}21SX~GWfS0!eofkw5g13Qx24rGl5z{}QY zj86p>p%lErI+XpIkG>G9s-jw~rwV9snaNNos;RS$4UJ7VS1Dp8CGxlBD->U$ zkK1cc-M3h%m%Y?PfoW_IM_O{ClJk3zkY5l zl=g;hz4O|mULjxBveGW;qW{y>l}1D1cJV=!5Gh1TQbr~a%_*gs0@9P>)C`tB2q{c6oPS1K4eKqYI}|U+6lv?J!0nG&Ep+rVmG_r zR11I%>N2ev4ey);bUk}*N@7=mtgJh;<}D3vVI$oDr3F>@Y#Lbmy|yEKY(Y}}^tD(m1t!he{>2QbI>qUj-selSFL3n21zOfA7-6xZ6vrMWn z=F~^47gU|en5?m8{A(sLuUwe<=nz$JiE~*9@HRK)W7M6i-#>_KFY#ZafA+2l*eWhH zLY9s9+&nlQD2{5l$T0A}s>~)T;gYiRRQe31VRwnk`NtR0Gtu-{U>W81;l)#EIKC8w zlrKWx9TGABfO2dDnk^k}jKZKDNC@#RSK;ULrnyCvvo*?rZ})%h^>R_pPR^#FFS2io zjfjhuS-KUicBBxB@wc_T*^V7WYv0$`W^7*e6b%KrNHkUXRLd@O$_%sI;m|!H-chyF z+M1sw2dgi0Fbpza@pRJg&(M4>Z*bdbZB1}ccx^hTmF+gX$D+4xIASztf^SC=TrFfa~oV8Q)KK3{*+5>TPvgY5y{~pckC^{(#Y1upw`4if6+{ zcJ^z0kOUCx?Wy-cGdD2`XWOW(nH4mHk(4~Lvi>DK9i(kgRLCZwroAv$uUl85MjEj5 zL&xZ!G|#>n$WPmdRsN&=)^g<$)<+hfv5+41I9+*j@Q6W?SGff*ut#{1RWoka_gSjW zXk|FmwWA=})1;lwQGGcJ^5_{Y zIQC7nR#rvO#>7fK-!efkzt3hmpwSFJW*mMHXr$*kbYIsWjDdLns*KM{D=)urp5XM* zV!21t**6B3591pNmu+ZfJ zbe&1pHG4}~$9$9I=>$pIuN1>hBQa~k6PqiSh>?SB2TD`8+*H^zl8A_+ibVccYt7-i zNmmgPLWDVRx5=L!V{xKc*9=%U6Hh+!TCRP%W72 zhb*`$ATm{2v5ae8E>t=&O>|h4(3iT1Ji>2`%jGmha_+Ncj7w~-mZSzo!&LDQqeN)h z#s130D=p{L3%a~K;xcNs{H#k(m4mffOs#pmpEuwvOLQ6`Nq{OFMK_ zAppSa{ihZH?%M$=%yXhUMIS}>nPE^V@1u)QepuYm60Gth`Yl`;S0cR|LY=5Iu8fRK zzx5MCU*RpixV^?k_96wb3MGQ=rs3CQ0VQXQ$SQ^^xVVGcLBQC-P&iYDWx>?*094#gS40=8?pp$KUZMsb`D4Z$P?hv`&O%W z9jy7XO3HGi>WU23RK1{2t;v-V9>q+$gk=N{ef1c0%Tjvfuq$Pu^1>?hH}NnzZqF=R zE;nR1c84MyH2D7c*&TQzFWMsL9emH~SikTj9kEG%=PAuzqoKaa z|C=j;rB+ql+x=uak8&NUz#O#vL1`_C!hXF4~cKZ;{J#5Il(n$hyMB~LYU`Gq=O z`I9*YRgg~v$la9XarT=AcflARH}6+DjBHH58u!!PqZlC*)VcB#Cy_+GI!cWe+*vef zq%EmXwu0|N_pkco?$Gg&8~KlcKQDCW4brpG2c~p}EPWc4Xdx=UOaCo}yvK6aetl^M zuiwr9nRYrDS-j|P^TO2ishPT}h!dv@p_>um)1Z%ontnER-(N64f{y0BT7OxS>iO#Q7AY0P5f;ktNv39Kb+jjk*Xs9_uv;+9NWk5hl9sA^F*7A8{ZE9b6M z@yHsHi)f$p!iURPnB;O70R|l0dGK=Z_;05}+I#rK@WH?R5d&SX-f&We+sbwqyY*)0 z&e%QvDPiHR;1Hw>w}RP$-^A<|fb?zBKG*GcBa}lon4%gkE5CCZMa08x!(xhxzw#O~ zhateq3oj9}PW;W50CS@P2SM%&9(sV9JJ0MNtYLn7Qu2v)ql<}{C2gAA1b2YLVdk9M zab%4hZYr^z&xF@C2+8q&lW|*UVsPSDfEr_0@$H@syxeoSJ_r6^Y+A@n=axs@7bjt? zAFpZTN1<$S2PuJdwAQwSXXz)f|x8lwqKkcJHamNgrov~$_;cO?LCM$j3+Wbxcc5|-;kTP)Hbb?fS6_S|hbAajI0LV1 zA;LqPgO%>_7=J-Cy|MZl8_G(**mhkzz3+Qga?2zPxA3T^UJ;Jd+lIgqJi_g zSDap*-RDx%SpE|$Vu+t`WX+ow$svmqyLOwAQvQb@ad?rhfaVOH!lE1{#cdMzLVBcu zof4#@zroQW*T|?n0TLzgA|Nb)829^Mpy?=~4=`H(UDZ-N$q(+9N?GLzo{B zyC8-dU`cpi(m}GA95z-qwx~1IJJj02gOO#kNA;>mJFEBX$5VRFQG)+)T@hEP&cVB} zs{wjPzR0B9ovEK~7C@j;)~#14za8iUuythP(NwG^?vNd0YG#&LKjzfH1VDWAN@9bB zo->^TWt=bGaWt+~P*J1Jf3(Sgk_}p5b{49DgL3AGy^!(O*pfnc-=%F*F}142{@$JY zA1qoeC)2&@NZm4az0})!x4<&AXyCW|Fe(C1uSX8wzr8h4vC`t!`(RN$8x(nkI&=Pp zJKpZS@=+ES#Yzpy@Gr^+92ROD!t5@+y59~+N#(jH92tuv8aA^X3#H8{|@1#%A`5LpsJZ?{RID#wn4%i;5U ziOHev#TK>=+T1Aq>#UkrF({_8AjZpvnKpCNx*;ZZUK~Fq8{D~e zeJ)swrpq~AT+P|PNawvYWIOg;j_-f|_3>qvy|X{C>>>nCyJum_6Mr^VZ`;n<`T_h~ zRbKHhbR<5yOkH_Wpv0gp(ZuhemZ+h9ctj(AW#xP#B=SnkebI+#7wfB36mg3`s2?BD%jqfy|Fg^=!eC3@J^R{cvbN3qWY>Le4u0wt zVqd(j3vKpbdCprwxWJk2+l;wfRZAt`KlH+1d33Iz`eMDOhhMT}DKR_m4G7=tmrs`A zmUdyu*uk3<_#&@69iMnSrd;f=%s(nVZosrp)c(9CSS$Iwt?b5o%FeU!M%mMWih!i? z`HixFsf_>1q1F4;Z$%WB^b2U1nculxlku1Q{cCut1dTy9cIWM?8gI6u0>j diff --git a/doc/indigo.md b/doc/indigo.md deleted file mode 100644 index 3bfd391..0000000 --- a/doc/indigo.md +++ /dev/null @@ -1,65 +0,0 @@ -ifm3d-ros on Ubuntu 14.04 and ROS Indigo ----------------------------------------- - -This article provides a quick-start guide for getting a fresh install of Ubuntu -14.04 ready for usage with `ifm3d-ros` and an O3X camera. As a pre-requisite -for this article, we assume you already have Ubuntu 14.04 installed (but have -done no other configuration) and that you will be using `ifm3d` version `0.2.0` -and `ifm3d-ros` version `0.2.0`. Later versions of the `ifm3d` and `ifm3d-ros` -software will work as well until we end-of-life Ubuntu 14.04 and ROS -Indigo. Finally, since we assume you have done no updates to your Ubuntu -install, we also assume you are using `g++` version `4.8.4` (which is old). - -### Update the Baseline Packages of your Ubuntu 14.04 Install - -``` -$ sudo apt-get update -$ sudo apt-get -u upgrade -``` - -### Install ROS Indigo - -You should now follow -[these steps](http://wiki.ros.org/indigo/Installation/Ubuntu) exactly (we -assume you did) and that you chose to install `ros-indigo-desktop-full`. Go do -that now, then continue on. - -### Additional Dependencies - -There are a few things that we need to install to successfully build from -source that we did not get implicitly by installing ROS. The following commands -will handle these pre-requisites: - -``` -$ sudo apt-get install libxmlrpc-c++8-dev -$ sudo apt-get install libgoogle-glog-dev -``` - -### Install ifm3d - -[ifm3d](https://github.com/lovepark/ifm3d) is the core underlying C++ driver -that `ifm3d-ros` wraps. We need to install that now. We assume you keep all of -your source code in `~/dev`. - -``` -$ mkdir ~/dev -$ cd ~/dev -$ git clone https://github.com/lovepark/ifm3d.git -$ cd ifm3d -$ mkdir build -$ cd build -$ cmake -DCMAKE_INSTALL_PREFIX=/usr -DFORCE_OPENCV2=ON .. -$ make -$ make check -$ make package -$ make repackage -$ sudo dpkg -i ifm3d_0.2.0_amd64-camera.deb -$ sudo dpkg -i ifm3d_0.2.0_amd64-framegrabber.deb -$ sudo dpkg -i ifm3d_0.2.0_amd64-image.deb -$ sudo dpkg -i ifm3d_0.2.0_amd64-tools.deb -``` - -You are now in position to install `ifm3d-ros`. Those instructions are -available on the main -[Readme](https://github.com/lovepark/ifm3d-ros#building-and-installing-the-software) -page. diff --git a/doc/kinetic.md b/doc/kinetic.md deleted file mode 100644 index 7ba56f3..0000000 --- a/doc/kinetic.md +++ /dev/null @@ -1,68 +0,0 @@ -ifm3d-ros on Ubuntu 16.04 and ROS Kinetic ------------------------------------------ - -NOTE: The instructions below only apply if you plan to install `ifm3d` from -source. You can, as of version 0.12.0, install `ifm3d` from binary -debs. Instructions for that are located at the main -[ifm3d project page](https://github.com/ifm/ifm3d). - -This article provides a quick-start guide for getting a fresh install of Ubuntu -16.04 ready for usage with `ifm3d-ros` and an O3X camera. As a pre-requisite -for this article, we assume you already have Ubuntu 16.04 installed (but have -done no other configuration) and that you will be using `ifm3d` version `0.3.2` -and `ifm3d-ros` version `0.4.0`. Later versions of the `ifm3d` and `ifm3d-ros` -software will work as well until we end-of-life Ubuntu 16.04 and ROS -Kinetic. To be clear, we assume you have done no updates to your Ubuntu -install, so we start there. - -### Update the Baseline Packages of your Ubuntu 16.04 Install - -``` -$ sudo apt-get update -$ sudo apt-get -u upgrade -``` - -### Install ROS Kinetic - -You should now follow -[these steps](http://wiki.ros.org/kinetic/Installation/Ubuntu) exactly (we -assume you did) and that you chose to install `ros-kinetic-desktop-full`. Go do -that now, then continue on. - -### Additional Dependencies - -There are a few things that we need to install to successfully build from -source that we did not get implicitly by installing ROS. The following commands -will handle these pre-requisites: - -``` -$ sudo apt-get install libxmlrpc-c++8-dev -$ sudo apt-get install libgoogle-glog-dev -``` - -### Install ifm3d - -[ifm3d](https://github.com/lovepark/ifm3d) is the core underlying C++ driver -that `ifm3d-ros` wraps. We need to install that now. We assume you keep all of -your source code in `~/dev`. - -``` -$ mkdir ~/dev -$ cd ~/dev -$ git clone https://github.com/lovepark/ifm3d.git -$ cd ifm3d -$ mkdir build -$ cd build -$ cmake -DCMAKE_INSTALL_PREFIX=/usr .. -$ make -$ make check -$ make package -$ make repackage -$ sudo dpkg -i ifm3d_0.9.0_amd64-camera.deb -$ sudo dpkg -i ifm3d_0.9.0_amd64-framegrabber.deb -$ sudo dpkg -i ifm3d_0.9.0_amd64-image.deb -$ sudo dpkg -i ifm3d_0.9.0_amd64-tools.deb -``` - -You are now in position to install `ifm3d-ros`. Those instructions are -available [here](building.md). diff --git a/doc/melodic.md b/doc/melodic.md deleted file mode 100644 index a670fff..0000000 --- a/doc/melodic.md +++ /dev/null @@ -1,66 +0,0 @@ -ifm3d-ros on Ubuntu 18.04 and ROS Melodic ------------------------------------------ - -NOTE: The instructions below only apply if you plan to install `ifm3d` from -source. You can, as of version 0.12.0, install `ifm3d` from binary -debs. Instructions for that are located at the main -[ifm3d project page](https://github.com/ifm/ifm3d). - - -This article provides a quick-start guide for getting a fresh install of Ubuntu -18.04 ready for usage with `ifm3d-ros` and an O3D camera. As a pre-requisite -for this article, we assume you already have Ubuntu 18.04 installed (but have -done no other configuration). A *minimal* install of 18.04 is sufficient for -following along below. - -### Update the Baseline Packages of your Ubuntu 18.04 Install - -``` -$ sudo apt-get update -$ sudo apt-get -u upgrade -``` - -### Install ROS Melodic - -You should now follow -[these steps](http://wiki.ros.org/melodic/Installation/Ubuntu) exactly (we -assume you did) and that you chose to install `ros-melodic-desktop-full`. Go do -that now, then continue on. - -### Additional Dependencies - -There are a few things that we need to install to successfully build from -source that we did not get implicitly by installing ROS. The following commands -will handle these pre-requisites: - -``` -$ sudo apt-get install libxmlrpc-c++8-dev -$ sudo apt-get install libgoogle-glog-dev -``` - -### Install ifm3d - -[ifm3d](https://github.com/lovepark/ifm3d) is the core underlying C++ driver -that `ifm3d-ros` wraps. We need to install that now. We assume you keep all of -your source code in `~/dev`. - -``` -$ mkdir ~/dev -$ cd ~/dev -$ git clone https://github.com/lovepark/ifm3d.git -$ cd ifm3d -$ mkdir build -$ cd build -$ cmake -DCMAKE_INSTALL_PREFIX=/usr .. -$ make -$ make check -$ make package -$ make repackage -$ sudo dpkg -i ifm3d_0.9.0_amd64-camera.deb -$ sudo dpkg -i ifm3d_0.9.0_amd64-framegrabber.deb -$ sudo dpkg -i ifm3d_0.9.0_amd64-image.deb -$ sudo dpkg -i ifm3d_0.9.0_amd64-tools.deb -``` - -You are now in position to install `ifm3d-ros`. Those instructions are -available [here](building.md). diff --git a/doc/troubleshooting.md b/doc/troubleshooting.md deleted file mode 100644 index 2d918c0..0000000 --- a/doc/troubleshooting.md +++ /dev/null @@ -1,36 +0,0 @@ -ifm3d-ros Troubleshooting Guide -============================= - -You can use this guide to help you identify and resolve problems you may -experience in using the ifm3d-ros package. - -# List of contents: - -- [ifm3d-ros services provide no response.](#ifm3d-ros-services-provide-no-response) - -## ifm3d-ros services provide no response -On systems utilising a single core processor, -you may find that the Dump, Config and Trigger services of ifm3d-ros package do -not provide any response when invoked. - -This issue can be resolved by setting the "num_worker_threads" parameter -for your ROS nodelet manager to use a value > 1. You can read more about this -parameter [here](http://wiki.ros.org/nodelet). - -The snippet below show's how to set this parameter using the -[nodelet.launch](https://github.com/ifm/ifm3d-ros/blob/master/launch/nodelet.launch) -file of the ifm3d-ros package. - -``` - - - -``` - -Alternatively if a virtual machine is being used, configuring it to utilise -more than one core should resolve this issue without any changes to the launch -file. diff --git a/ifm3d-ros/CMakeLists.txt b/ifm3d-ros/CMakeLists.txt new file mode 100644 index 0000000..5a82652 --- /dev/null +++ b/ifm3d-ros/CMakeLists.txt @@ -0,0 +1,5 @@ +cmake_minimum_required(VERSION 2.8.3) +project(ifm3d-ros) +find_package(catkin REQUIRED) +catkin_metapackage() + diff --git a/ifm3d-ros/LICENSE b/ifm3d-ros/LICENSE new file mode 100644 index 0000000..7a4a3ea --- /dev/null +++ b/ifm3d-ros/LICENSE @@ -0,0 +1,202 @@ + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. \ No newline at end of file diff --git a/ifm3d-ros/package.xml b/ifm3d-ros/package.xml new file mode 100644 index 0000000..ce68491 --- /dev/null +++ b/ifm3d-ros/package.xml @@ -0,0 +1,22 @@ + + + + ifm3d-ros + 0.1.0 + metapackage for the ifm3d-ros package group which interacts with the ifm 3D ToF Camera ROS package + ifm CSR group + Apache 2 + CSR ifm sytron + + https://github.com/ifm/ifm3d-ros/ + + catkin + ifm3d_ros_driver + ifm3d_ros_examples + ifm3d_ros_msgs + + + + + + diff --git a/ifm3d_ros_driver/.clang-format b/ifm3d_ros_driver/.clang-format new file mode 100644 index 0000000..817fd6d --- /dev/null +++ b/ifm3d_ros_driver/.clang-format @@ -0,0 +1,65 @@ +--- +BasedOnStyle: Google +AccessModifierOffset: -2 +ConstructorInitializerIndentWidth: 2 +AlignEscapedNewlinesLeft: false +AlignTrailingComments: true +AllowAllParametersOfDeclarationOnNextLine: false +AllowShortIfStatementsOnASingleLine: false +AllowShortLoopsOnASingleLine: false +AllowShortFunctionsOnASingleLine: None +AlwaysBreakTemplateDeclarations: true +AlwaysBreakBeforeMultilineStrings: true +BreakBeforeBinaryOperators: false +BreakBeforeTernaryOperators: false +BreakConstructorInitializersBeforeComma: true +BinPackParameters: true +ColumnLimit: 120 +ConstructorInitializerAllOnOneLineOrOnePerLine: true +DerivePointerBinding: false +PointerBindsToType: true +ExperimentalAutoDetectBinPacking: false +IndentCaseLabels: true +MaxEmptyLinesToKeep: 1 +NamespaceIndentation: None +ObjCSpaceBeforeProtocolList: true +PenaltyBreakBeforeFirstCallParameter: 19 +PenaltyBreakComment: 60 +PenaltyBreakString: 1 +PenaltyBreakFirstLessLess: 1000 +PenaltyExcessCharacter: 1000 +PenaltyReturnTypeOnItsOwnLine: 90 +SpacesBeforeTrailingComments: 2 +Cpp11BracedListStyle: false +Standard: Auto +IndentWidth: 2 +TabWidth: 2 +UseTab: Never +IndentFunctionDeclarationAfterType: false +SpacesInParentheses: false +SpacesInAngles: false +SpaceInEmptyParentheses: false +SpacesInCStyleCastParentheses: false +SpaceAfterControlStatementKeyword: true +SpaceBeforeAssignmentOperators: true +ContinuationIndentWidth: 4 +SortIncludes: false +SpaceAfterCStyleCast: false + +# Configure each individual brace in BraceWrapping +BreakBeforeBraces: Custom + +# Control of individual brace wrapping cases +BraceWrapping: { + AfterClass: 'true' + AfterControlStatement: 'true' + AfterEnum : 'true' + AfterFunction : 'true' + AfterNamespace : 'true' + AfterStruct : 'true' + AfterUnion : 'true' + BeforeCatch : 'true' + BeforeElse : 'true' + IndentBraces : 'false' +} +... diff --git a/CMakeLists.txt b/ifm3d_ros_driver/CMakeLists.txt similarity index 69% rename from CMakeLists.txt rename to ifm3d_ros_driver/CMakeLists.txt index 20eed28..78ccdb0 100644 --- a/CMakeLists.txt +++ b/ifm3d_ros_driver/CMakeLists.txt @@ -1,7 +1,7 @@ cmake_minimum_required(VERSION 3.5) -project(ifm3d) +project(ifm3d_ros_driver) -find_package(ifm3d 0.11.2 CONFIG REQUIRED COMPONENTS +find_package(ifm3d REQUIRED COMPONENTS camera framegrabber image @@ -16,36 +16,14 @@ find_package(catkin REQUIRED COMPONENTS roscpp sensor_msgs std_msgs - tf - message_generation message_runtime rostest + ifm3d_ros_msgs ) catkin_python_setup() -####################################### -## Declare ROS messages and services ## -####################################### -add_message_files( - FILES - Extrinsics.msg - ) - -add_service_files( - FILES - Dump.srv - Config.srv - Trigger.srv - SoftOff.srv - SoftOn.srv - SyncClocks.srv - ) - -generate_messages( - DEPENDENCIES - std_msgs - ) +option(CATKIN_ENABLE_TESTING "Build tests" OFF) ################################### ## catkin specific configuration ## @@ -75,19 +53,11 @@ target_link_libraries(ifm3d_ros ifm3d::framegrabber ifm3d::image ) -add_dependencies(ifm3d_ros ${PROJECT_NAME}_generate_messages_cpp) - + ############# ## Install ## ############# -catkin_install_python( - PROGRAMS - bin/dump - bin/config - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} - ) - install(TARGETS ifm3d_ros ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} @@ -104,10 +74,6 @@ install(FILES nodelets.xml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} ) -install(DIRECTORY launch - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} - ) - ###################### ## Node-level tests ## ###################### diff --git a/ifm3d_ros_driver/LICENSE b/ifm3d_ros_driver/LICENSE new file mode 100644 index 0000000..7a4a3ea --- /dev/null +++ b/ifm3d_ros_driver/LICENSE @@ -0,0 +1,202 @@ + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. \ No newline at end of file diff --git a/ifm3d_ros_driver/README.md b/ifm3d_ros_driver/README.md new file mode 100644 index 0000000..bf05705 --- /dev/null +++ b/ifm3d_ros_driver/README.md @@ -0,0 +1,72 @@ +# The `ifm3d_ros_driver` package + +## ROS Interface + +The core `ifm3d-ros` sensor interface is implemented as a ROS nodelet. This allows for lower-latency data processing vs. the traditional out-of-process node-based ROS interface for applications that require it. However, we ship a launch file with this package that allows for using the core `ifm3d-ros` driver as a standard node. To launch the node, the following command can be used: + +``` +$ roslaunch ifm3d_ros_examples camera.launch +``` +>Note: Please notice the use of the subpackage `ifm3d_ros_examples`. + +For further information about the internal ROS nodelet infrastructure and how to apply this to your application, please see our exemplary launch files and a short run down on the nodelet structure in the [ifm3d_ros_examples/README](../ifm3d_ros_examples/README.md). + +### Nodelet - parameters + +| Name | Data Type | Default Value | Description | +| ---- | ---- | ---- | ---- | +| ~assume_sw_triggered | bool | false | This provides a hint to the driver that the camera is configured for software triggering (as opposed to free running). In this mode, certain default values are applied to lessen the noise in terms of timeouts from the frame grabber.| +| ~frame_id_base |string |ifm3d/camera | This string provides a prefix into the `tf` tree for `ifm3d_ros` coordinate frames. | +| ~frame_latency_thresh | float | 60.0 | Time (seconds) used to determine that timestamps from the camera cannot be trusted. When this threshold is exceeded, when compared to system time, we use the reception time of the frame and not the capture time of the frame. | +| ~ip | string | 192.168.0.69 | The IP address of the VPU. | +| ~password | string | "" | The password required to establish an edit session on the VPU | +| ~schema_mask | uint16 | 0xf | The pcic schema mask to apply to the active session with the frame grabber. This determines which images are available for publication from the camera. More about pcic schemas can be gleaned from the [ifm3d projects documentation](https://www.ifm3d.com). | +| ~timeout_millis | int | 500 | The number of milliseconds to wait for the framegrabber to return new frame data before declaring a "timeout" and to stop blocking on new data. | +| ~timeout_tolerance_secs |float | 5.0 | The wall time to wait with no new data from the camera before trying to establish a new connection to the camera. This helps to providerobustness against camera cables becoming unplugged or other in-field pathologies which would cause the connection between the ROS node and the camera to be broken. | +| ~sync_clocks DEPRECATED | bool | false | Attempt to sync the camera clock to the system clock at start-up. The side-effect is that timestamps on the image should reflect the capture time as opposed to the receipt time. | +| ~xmlrpc_port | unint16 | 80 | The TCP port the camera's xmlrpc server is listening on for requests. | +| ~pcic_port | unint16 | 50010 | The TCP (data) port the camera's pcic server is listening on for requests. | + + +### Nodelet - published Topics + +| Name | Data Type | Description | +| --- | --- | --- | +| amplitude | sensor_msgs/Image | The normalized amplitude image. | +| confidence | sensor_msgs/Image | The confidence image. | +| cloud | sensor_msgs/PointCloud2 | The point cloud data, i.e. X-, Y-, Z-coordinates. | +| distance | sensor_msgs/Image | The radial distance image. | +| raw_amplitude | sensor_msgs/Image | The raw (non normalized) amplitude image. | +| good_bad_pixels | sensor_msgs/Image | The binary image representation of the confidence image. | +| xyz_imaege | sensor_msgs/Image | A 3-channel image encoding of the point cloud. Each of the three image channels represents a spatial data plane encoding the x, y, z Cartesian values respectively. | +| unit_vectors | sensor_msgs/Image | The rotated unit vectors. | +| extrinsics | ifm3d/Extrinsics | The extrinsic calibration of the camera with respect to the camera optical frame. This 3D pose is encoded in mm and rad. | + +>Note: Some topics may have empty data fields. We are working on publishing data on all available topics, but have kept all previous topics active for the moment for legacy reasons. + +### Nodelet - subscribed Topics +None. + +### Nodelet - advertised Services +> Note: the services are provided by the `ifm3d_ros_msgs` package. + +| Name | Service Definition | Description | +| ---- | ---- | ---- | +| Dump | ifm3d/Dump | Dumps the state of the camera system as a JSON (formatted as a string) | +| Config | ifm3d/Config | Provides a means to configure the VPU and Heads (imager settings), declaratively from a JSON (string) encoding of the desired settings. | +| SoftOff | ifm3d/SoftOff | Sets the active application of the camera into software triggered mode which will turn off the active illumination reducing both power and heat. | +| SoftOn | ifm3d/SoftOn | Sets the active application of the camera into free-running mode. Its intention is to act as the inverse of `SoftOff`. | +| Trigger | ifm3d/Trigger | Requests the driver to software trigger the imager for data acquisition. | + +### Known limitations +[![O3R](https://img.shields.io/badge/O3R-lightgrey.svg)]() +[![O3D](https://img.shields.io/badge/O3D-green.svg)]() +[![O3X](https://img.shields.io/badge/O3X-green.svg)]() + + +# Additional Documentation +* [Inspecting and configuring the camera / imager settings](doc/dump_and_config.md) +* [Troubleshooting](doc/troubleshooting.md) + +# LICENSE +Please see the file called [LICENSE](LICENSE). diff --git a/ifm3d_ros_driver/doc/building.md b/ifm3d_ros_driver/doc/building.md new file mode 100644 index 0000000..4421c9a --- /dev/null +++ b/ifm3d_ros_driver/doc/building.md @@ -0,0 +1,93 @@ +# Building and Installing the ifm3d-ros package + +## TOC +* [Prerequisites](#prerequisites) +* [Step-by-Step build instructions for the ROS node `ifm3d-ros`](#step-by-step-build-instructions-for-the-ros-node--ifm3d-ros-) + + [1. Installation directory of ROS node](#1-installation-directory-of-ros-node) + + [2. create and initialize your catkin workspace](#2-create-and-initialize-your-catkin-workspace) + + [3. Get the `ìfm3d-ros` wrapper code from GitHub](#3-get-the---fm3d-ros--wrapper-code-from-github) + + [4. build the ROS node code](#4-build-the-ros-node-code) +* [Building subpackages for distributed systems](#building-subpackages) + + +## Prerequisites + +We suggest to build the `ifm3d-ros` node on top of Ubuntu 20.04 and ROS noetic. +If you have reached this document via the [noetic ifm3d building instructions](noetic.md) and followed all the major steps in there you can skip the three steps listed below. They are just a short repetition. +1. [Ubuntu 20.04 LTS](http://www.ubuntu.com) +2. [ROS Noetic](http://wiki.ros.org/noetic/Installation/) - we recommend `ros-noetic-desktop-full`. +3. [ifm3d](https://github.com/ifm/ifm3d/tree/o3r/dev) + + +> Note: Some users may require older ROS distributions for legacy reasons. The supplied ROS package may very well work with limited changes on older ROS distributions. At least previous version could be run as far back as Indigo and Kinetic. However, we didn't test this ourselves. Please be aware that if you chose to go this route no guarantee is given. + +## Step-by-Step build instructions for the ROS node `ifm3d-ros` + +Building and installing ifm3d-ros is accomplished by utilizing the ROS [catkin](http://wiki.ros.org/catkin) tool. There are many tutorials and other pieces of advice available online advising how to most effectively utilize catkin. The instructions that now follow represent how we choose to use catkin to build and _permanently install_ a ROS package from source. + +**Alternatively: If you are looking for indenpendent subpackage build - please see [distributed build instructions](distributed_build.md)** + +### 1. Installation directory of ROS node +First, we need to decide where we want our software to be installed. For purposes of this document, we will assume that we will install our ROS packages at `~/catkin_ws/src`. + +>NOTE: Below we assume `noetic`. Adapting to other ROS distributions is left as an exercise for the reader. + +### 2. create and initialize your catkin workspace +Next, we want to create a _catkin workspace_ that we can use to build and install that code from. +For further information about setting up you _catkin workspace_ please see this documentation: [create a catkin workspace](http://wiki.ros.org/catkin/Tutorials/create_a_workspace). +``` +$ mkdir -p ~/catkin_ws/src && cd ~/catkin_ws/src +$ catkin_init_workspace +``` + +### 3. Get the `ifm3d-ros` wrapper code from GitHub +Next, we need to get the code from GitHub. Please adapt the commands when not following the suggested directory structure: `~/catkin_ws/src/` + +``` +$ cd ~/catkin_ws/src +$ git clone --branch o3r/dev https://github.com/ifm/ifm3d-ros.git +``` + +So, you should have a catkin workspace set up to build the ifm3d-ros code that looks similar to this: +``` +[ ~/catkin_ws/src ] +rosuser@tuna: $ pwd +/home/rosuser/catkin_ws/src + +[ ~/catkin_ws/src/ifm3d-ros ] +rosuser@tuna: $ ls -l +total 0 +lrwxrwxrwx 1 rosuser rosuser 50 Mar 26 15:16 CMakeLists.txt -> /opt/ros/noetic/share/catkin_ws/cmake/toplevel.cmake +lrwxrwxrwx 1 rosuser rosuser 31 Mar 26 15:16 ifm3d-ros +``` + +### 4. build the ROS node code +Now we are ready to build the code. The following code block shows you how to simply run catkin_make without anything else happening further. +``` +$ cd ~/catkin_ws/ +$ catkin_make +``` +This will create a `devel` and `build` folder in your catkin workspace, which contains the required code for running the ROS node. To test this you can easily set-up your current shell and run: `source ~/catkin_ws/devel/setup.bash && roslaunch ifm3d_ros_examples camera.launch`. + + +The ROS package should now be installed in `~/ros/ifm3d-ros`. To test everything out you should open a fresh bash shell, and start up a ROS core: +(Please don't forget to source the ifm3d-ros package first if you haven't done it yet.) +``` +$ roscore & +$ roslaunch ifm3d_ros_examples camera.launch +``` + +Open another shell and start the rviz node to visualize the data coming from the camera: +``` +$ roslaunch ifm3d_ros_examples rviz.launch +``` +> Note: `rviz.launch` does not include the camera node itself, but subscribes to published topics (distance, amplitude, etc). A camera node need to be running in parallel to rviz (you can use `camera.launch`). + +At this point, you should see an rviz window that looks something like the image below (note that this is the view from 3 camera heads): +![rviz1](figures/O3R_merged_point_cloud.png) + +Congratulations! You can now have complete control over the O3R perception platform from inside ROS. + + +## Building subpackages +Please see [this documentation](distributed_build.md) for how to build some of the subpackages for distributed systems. \ No newline at end of file diff --git a/ifm3d_ros_driver/doc/distributed_build.md b/ifm3d_ros_driver/doc/distributed_build.md new file mode 100644 index 0000000..007f38b --- /dev/null +++ b/ifm3d_ros_driver/doc/distributed_build.md @@ -0,0 +1,47 @@ +# Building and installing for distributed systems + +We have structured the ROS node into separate subpackages. This allows us to build only a subset of packages from the metapackage `ifm3d-ros`. + +## Building only one package from your catkin workspace +The command below allows you to selectively build only one of the existing packages in your joined catkin workspace. All the following commands can only be called on a device which already has ROS installed. + + +``` +$ catkin_make --only-pkg-with-deps +``` +To apply this to one of the ifm3d-ros subpackages, please replace `` with either one item of the following list: +- `ifm3d_ros_driver` provides the core interface for receiving data for ifm 3d (O3R) cameras. +- `ifm3d_ros_msgs` gathers the ifm-specific messages types and the services for configuring and triggering the camera. +- `ifm3d_ros_examples` provides additional helper scripts and examples. + +### Building the driver package +Let's say you want to run the `ìfm3d_ros_driver` on an embedded system like the VPU itself. To make it as lightweight as possible we suggest to only build the subpackage `ifm3d_ros_driver` and its dependencies on / for the desired architecture. This will look something like the following: +``` +$ catkin_make --only-pkg-with-deps ifm3d_ros_driver + +traversing 2 packages in topological order: +-- ~~ - ifm3d_ros_msgs +-- ~~ - ifm3d_ros_driver +``` + +### Building the messages package +Typically a secondary ROS client would only subscribe to topics of a shared ROS master for receiving data and configure the main driver. Both jobs can be achieved without having the main driver package `ifm3d_ros_driver` installed on the client system. Therefor only compile the package `ifm3d_ros_msgs`. + +``` +$ catkin_make --only-pkg-with-deps ifm3d_ros_msgs + +traversing 1 packages in topological order: +-- ~~ - ifm3d_ros_msgs +``` + +### Building the examples package +Building the examples package by itself (with dependencies) will result in having all packages build as it requires all three. +``` +$ catkin_make --only-pkg-with-deps ifm3d_ros_examples + +traversing 3 packages in topological order: +-- ~~ - ifm3d_ros_msgs +-- ~~ - ifm3d_ros_driver +-- ~~ - ifm3d_ros_examples + +``` \ No newline at end of file diff --git a/ifm3d_ros_driver/doc/dump_and_config.md b/ifm3d_ros_driver/doc/dump_and_config.md new file mode 100644 index 0000000..9439bcf --- /dev/null +++ b/ifm3d_ros_driver/doc/dump_and_config.md @@ -0,0 +1,407 @@ +# ifm3d_ros_msgs: Dump and Config + +The ifm3d_ros_msgs package allows us to configure the O3R camera platform via two separate ways: +1. Use ROS native service calls +2. Use dump and config service proxies + + +## 1. ROS native service calls +Per camera head connected to the visual processing unit (VPU) of the O3R platform these services are available: + +| Name | Service Definition | Description | +| ---- | ---- | ---- | +| Dump | ifm3d/Dump | Dumps the state of the camera system as a JSON (formatted as a string) | +| Config | ifm3d/Config | Provides a means to configure the VPU and Heads (imager settings), declaratively from a JSON (string) encoding of the desired settings. | +| SoftOff | ifm3d/SoftOff | Sets the active application of the camera into software triggered mode which will turn off the active illumination reducing both power and heat. | +| SoftOn | ifm3d/SoftOn | Sets the active application of the camera into free-running mode. Its intention is to act as the inverse of `SoftOff`. | +| Trigger | ifm3d/Trigger | Requests the driver to software trigger the imager for data acquisition. | + +As you can see the two services `Dump` and `Config` are also part of this list. +### Dump +Call this service via, e.g. for camera1: +``` +$ rosservice call /ifm3d_ros_examples/camera1/Dump +status: 0 +{ + "device": { + "clock": { + "currentTime": 1581193835185485800 + }, + "diagnostic": { + "temperatures": [], + "upTime": 103190000000000 + }, + "info": { + "device": "0301", + "deviceTreeBinaryBlob": "tegra186-quill-p3310-1000-c03-00-base.dtb", + "features": {}, + "name": "", + " partNumber": "M03975", + "productionState": "AA", + "serialNumber": "000201234160", + "vendor": "0001" + }, + "network": { + "authorized_keys": "", + "ipAddressConfig": 0, + "macEth0": "00:04:4B:EA:9F:0E", + "macEth1": "00:02:01:23:41:60", + "networkSpeed": 1000, + "staticIPv4Address": "192.168.0.69", + "staticIPv4Gateway": "192.168.0.201", + "staticIPv4SubNetMask": "255.255.255.0", + "useDHCP": false + }, + "state": { + "errorMessage": "", + "errorNumber": "" + }, + "swVersion": { + "kernel": "4.9.140-l4t-r32.4+gc35f5eb9d1d9", + "l4t": "r32.4.3", + "os": "0.13.13-221", + "schema": "v0.1.0", + "swu": "0.15.12" + } + }, + "ports": { + "port0": { + "acquisition": { + "framerate": 10, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "data": { + "algoDebugConfig": {}, + "availablePCICOutput": [], + "pcicTCPPort": 50010 + }, + "info": { + "device": "2301", + "deviceTreeBinaryBlobOverlay": "001-ov9782.dtbo", + "features": { + "fov": { + "horizontal": 127, + "vertical": 80 + }, + " resolution": { + "height": 800, + "width": 1280 + }, + "type": "2D" + }, + "name": "", + "partNumber": "M03969", + "productionState": "AA", + "sensor": "OV9782", + "sensorID": "OV9782_127x80_noIllu_Csample", + "serialNumber": "000000000382", + "vendor": "0001" + }, + "mode": "experimental_autoexposure2D", + "processing": { + "extrinsicHeadToUser": { + "rotX": 0, + "rotY": 0, + "rotZ": 0, + " transX": 0, + "transY": 0, + "transZ": 0 + }, + "version": { + "major": 0, + "minor": 0, + " patch": 0 + } + }, + "state": "RUN" + }, + "port2": { + "acquisition": { + "exposureLong": 5000, + " exposureShort": 400, + "framerate": 10, + "offset": 0, + "version": { + "major": 0, + " minor": 0, + "patch": 0 + } + }, + "data": { + "algoDebugConfig": {}, + "availablePCICOutput": [], + "pcicTCPPort": 50012 + }, + "info": { + "device": "3101", + "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", + "features": { + "fov": { + "horizontal": 105, + "vertical": 78 + }, + " resolution": { + "height": 172, + "width": 224 + }, + "type": "3D" + }, + "name": "", + "partNumber": "M03969", + "productionState": "AA", + "sensor": "IRS2381C", + "sensorID": "IRS2381C_105x78_4x2W_110x90_C7", + "serialNumber": "000000000382", + "vendor": "0001" + }, + "mode": "standard_range4m", + "processing": { + "diParam": { + "anfFilterSizeDiv2": 2, + "enableDynamicSymmetry": true, + "enableStraylight": true, + "enableTemporalFilter": true, + "excessiveCorrectionThreshAmp": 0.3, + "excessiveCorrectionThreshDist": 0.08, + "maxDistNoise": 0.02, + "maxSymmetry": 0.4, + "medianSizeDiv2": 0, + "minAmplitude": 20, + "minReflectivity": 0, + "mixedPixelFilterMode": 1, + "mixedPixelThresholdRad": 0.15 + }, + "extrinsicHeadToUser": { + "rotX": 1, + "rotY": 0, + "rotZ": 0, + "transX": 100, + "transY": 0, + "transZ": 0 + }, + "version": { + " major": 0, + "minor": 0, + "patch": 0 + } + }, + "state": "RUN" + } + } +} +``` +## Config +Below you can see an example on how to configure your camera via a rosservice call. The JSON string can be a partial JSON string. It only needs to follow basic JSON syntax. + +``` +rosservice call /ifm3d_ros_examples/camera2/Config "json: '{"ports": {"port2": {"state": "RUN"}}}'" + +``` + +## 2. dump and config service proxies +`ifm3d-ros` provides access to each camera parameter via the `Dump` and `Config` services exposed by the `camera_nodelet`. + +Additionally, command-line scripts called `dump` and `config` are provided as wrapper interfaces to the native API `ifm3d`. This gives a feel similar to using the underlying C++ API's command-line tool, from the ROS-independent driver except proxying the calls through the ROS network. +They are part of the `ifm3d_ros_msgs` subpackage, so if you can't access them please make sure it is installed on your client. + +For example, to dump the state of the camera: +(exemplary output from an O3R perception platform with one camera head connected is shown) + +``` +$ rosrun ifm3d_ros_msgs dump +{ + "device": { + "clock": { + "currentTime": 1581193835185485800 + }, + "diagnostic": { + "temperatures": [], + "upTime": 103190000000000 + }, + "info": { + "device": "0301", + "deviceTreeBinaryBlob": "tegra186-quill-p3310-1000-c03-00-base.dtb", + "features": {}, + "name": "", + " partNumber": "M03975", + "productionState": "AA", + "serialNumber": "000201234160", + "vendor": "0001" + }, + "network": { + "authorized_keys": "", + "ipAddressConfig": 0, + "macEth0": "00:04:4B:EA:9F:0E", + "macEth1": "00:02:01:23:41:60", + "networkSpeed": 1000, + "staticIPv4Address": "192.168.0.69", + "staticIPv4Gateway": "192.168.0.201", + "staticIPv4SubNetMask": "255.255.255.0", + "useDHCP": false + }, + "state": { + "errorMessage": "", + "errorNumber": "" + }, + "swVersion": { + "kernel": "4.9.140-l4t-r32.4+gc35f5eb9d1d9", + "l4t": "r32.4.3", + "os": "0.13.13-221", + "schema": "v0.1.0", + "swu": "0.15.12" + } + }, + "ports": { + "port0": { + "acquisition": { + "framerate": 10, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "data": { + "algoDebugConfig": {}, + "availablePCICOutput": [], + "pcicTCPPort": 50010 + }, + "info": { + "device": "2301", + "deviceTreeBinaryBlobOverlay": "001-ov9782.dtbo", + "features": { + "fov": { + "horizontal": 127, + "vertical": 80 + }, + " resolution": { + "height": 800, + "width": 1280 + }, + "type": "2D" + }, + "name": "", + "partNumber": "M03969", + "productionState": "AA", + "sensor": "OV9782", + "sensorID": "OV9782_127x80_noIllu_Csample", + "serialNumber": "000000000382", + "vendor": "0001" + }, + "mode": "experimental_autoexposure2D", + "processing": { + "extrinsicHeadToUser": { + "rotX": 0, + "rotY": 0, + "rotZ": 0, + " transX": 0, + "transY": 0, + "transZ": 0 + }, + "version": { + "major": 0, + "minor": 0, + " patch": 0 + } + }, + "state": "RUN" + }, + "port2": { + "acquisition": { + "exposureLong": 5000, + " exposureShort": 400, + "framerate": 10, + "offset": 0, + "version": { + "major": 0, + " minor": 0, + "patch": 0 + } + }, + "data": { + "algoDebugConfig": {}, + "availablePCICOutput": [], + "pcicTCPPort": 50012 + }, + "info": { + "device": "3101", + "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", + "features": { + "fov": { + "horizontal": 105, + "vertical": 78 + }, + " resolution": { + "height": 172, + "width": 224 + }, + "type": "3D" + }, + "name": "", + "partNumber": "M03969", + "productionState": "AA", + "sensor": "IRS2381C", + "sensorID": "IRS2381C_105x78_4x2W_110x90_C7", + "serialNumber": "000000000382", + "vendor": "0001" + }, + "mode": "standard_range4m", + "processing": { + "diParam": { + "anfFilterSizeDiv2": 2, + "enableDynamicSymmetry": true, + "enableStraylight": true, + "enableTemporalFilter": true, + "excessiveCorrectionThreshAmp": 0.3, + "excessiveCorrectionThreshDist": 0.08, + "maxDistNoise": 0.02, + "maxSymmetry": 0.4, + "medianSizeDiv2": 0, + "minAmplitude": 20, + "minReflectivity": 0, + "mixedPixelFilterMode": 1, + "mixedPixelThresholdRad": 0.15 + }, + "extrinsicHeadToUser": { + "rotX": 1, + "rotY": 0, + "rotZ": 0, + "transX": 100, + "transY": 0, + "transZ": 0 + }, + "version": { + " major": 0, + "minor": 0, + "patch": 0 + } + }, + "state": "RUN" + } + } +} +``` + +Chaining together Linux pipelines works just as it does in `ifm3d`. For example, using a combination of `dump` and `config` to set a new name on the camera would look like: + +``` +$ rosrun ifm3d dump | jq '.ports.port0.mode="standard_range2m"' | rosrun ifm3d config +$ rosrun ifm3d dump | jq .ports.port0.mode +"experimental_high_2m" +``` + +>**NOTE:** If you do not have `jq` on your system, it can be installed with: `$ sudo apt-get install jq` + +For the `config` command, one difference between our ROS implementation and the `ifm3d` implementation is that we only accept input on `stdin`. So, if you had a file with JSON you wish to configure your camera with, you would simply use the file I/O redirection facilities of your shell (or something like `cat`) to feed the data to `stdin`. For example, in `bash`: + +``` +$ rosrun ifm3d dump > dump.json +$ cat dump.json | jq '.ports.port0.mode="experimental_high_2m"' > config.json +$ rosrun ifm3d config < config.json +``` + +Beyond the requirement of prefacing your command-line with `rosrun` to invoke the ROS version of these tools, they operate the same. To learn more about the functionality and concepts, you can read the docs [here](https://github.com/ifm/ifm3d/blob/master/doc/configuring.md). diff --git a/ifm3d_ros_driver/doc/figures/O3R_merged_point_cloud.png b/ifm3d_ros_driver/doc/figures/O3R_merged_point_cloud.png new file mode 100644 index 0000000000000000000000000000000000000000..a0c2163bc2b46405cf049c3e20fc3f75e98ab3b0 GIT binary patch literal 763340 zcmeFYXIPWl)-_BK(WtNi14z{%9YH{PQITGP3P>@4^j<y%!0+_aen_vCrP;Jl~J^$MfU;@m|;Q@)DDK-77aMbImp87-NP$hO1nIFhNL2 zNUo`=Dn2D4p|mC;A^&>mB6w%Y%u^oxc>hw@z~iZz_f1zf7i&95tD7Fau2wg#eC)tT zpHaPtiEBZ3FTI^gY@j*hk45(PH(g^f9c4mIk+ZyIp@0(kk%)ex_FIdd#LANy(T;F= z(_aVAnU74SFP<{pdF(Y>E=fWHxnu{P%0Np~+QP+2(9F`s+)B{L$rU^<35o1|A6GLA z2P==8=2kX#&T_Dg>N?m>J4-p3zL?fsE!Rg@wsxv7-K=z8!gVcPI#@_q!tTpMWPPN; z1Wr~SW;cDD9G%^zedJ(&%_|N5fBv=*?B-uXJRIa;23n7AK5}uhx_M9Vp5Wa(N~cg@nAly#>8R1zp^1goLG}q=fE@2#JW?0VD3X z`#O7=`P^}K=Qy9@Uvns0xm&o|xq8^SINv;<)6Cq((?bph1J`fKG?+X3T;U0F@|A*n{SN=2n{ATILc0N{)28wo0R?hC=5#(UPl2Z5nn(aTA z4gbewDKW{vuAWaNt>$EAW2J9r>0$dn?)%RbRVzCiTkyO5|L)Otv$F!LaQ^#(n_xoc zYbo^iVuJ5R=-*$?`3n8t|MTAu`CqN^f0ygO%k{rnf&bOu|3=q;m+ODE0{^SQ|BbHy zx0Va?A9!cw3^1KH0B<_aP{jcFU2s=W)4c@#_+PRNAtAX*qNeyz*JpG!#W$HnuXevK z=55OyUQAk*t04A+&0*yn5!2ku3OPm-?>hz7DS@n zaw$6~yO3G0^MhqER4~0_;q8N!fppcRxzqGOz5de6%YKE0Aq&Sxo!rL8dYCRLJ>zSq z{W~Y4UwB4^%^EJS`K=1a3mU&~HpdwV(1$f|7pkI>q>K6wf0|&BN1C%cc!*?$0eq@X zWP60FlvL^kziXiNY5Qn;9>0GN)~&d}HCJa&80wb1k1sWt|Ji24e76xlKBGGV@qeIy zXp7S{^mC+4C5@L7yQo*6PJSwT#gWpBgh)!B=bFn}$5n#dV6-kCnB`yQRuM7ub;|x*=zGJTVa zX#(69qdcuij)-~t$T;{NxihKgZob4f?JZWtyqU-45iZ3@DTJTD^1Q_dq!jn|k#^$7 z;9d-hK=mR9l3?3|KaAu?Jm}iuTDk}`d$Pde>4X#Ps^2y_zsmf7Qhf+ z*6klw=@9R(AuVv74@b%C#RSs?;-zG^ed!PVtsQL?<#UtysHMfggzg@}D;XO$%JNCN z^%tSrea5>Zf5*-FkN6biRx^WpJt<|8=gPB|k)@))LdqOhGwkE@DJ_>H%@9_;{vJ+r z`*=yb)h?1ayXQFK@_>S6c%-?qSp;JzG~uO6k@t)gM8)__zrlL{VNhP!!4<5O9{mzT zh?I-OL8-G+dV7h1W`_WeE90}wVkzv4UDPM-LlJzYOQN;4XLnSl#W5XD@VIMyFH#`* z41+8JzGeguLZfB?@5n(PZ^Mk9$P{|S_aYy{s7uNz)%9#z8Po9%9>?0$ur?M>u;EBs zfu)&2Hw9cj7DSOxS|XlZ+wHqxLZRysyjAZBkHftFGyJhwgn|F5=By|cegvEKt50|g ze}dV^YbzQCiHR^ozUR5JsXkp+PiY13=8HdaRX)5pta0}3eX)+ng5P_j)KmQgOZ6o` zr=|wZdR?N3seVF~oqG;ahm;;X^Dx!*OjPA4alFmOZC%4JoA zM7Do*8DP5tOS{H*VH(XhYX{u~VWSM))PTCayMzjLJ$afqg(~jec#Yyy4Ibc7%$Cz^ z8NTRWWdM(4zk;)%=w3D8y5ZgF&-z(zRD>v{;Fsr?v$U-Y&G@oP5#6lS z&;&Jh;>5F~zOc9yht$M`YgFt@3T^iVYKyO@ecLe`C6=}=cqSfvD9>V)NU3;BWp|*w zH043uzLHp>Ry@_O`CKN*Aatu3EFA zW3j_i_~dLkdb>z|j<_&*(v~@EOp6h8^BHkQMz8Bm{1G*c&`@@i11ya>h3~7* zTo@d+lFW3=%5*8d5zsDH~T>P#!jQ;5S08j&5u9zr4)VQ_t%^)OGzN(M)F@U3M| zuYQ3e%|R(7<$-|hy<`=b)!<=x=&-rts3D$_OKXiQ` z{OlRrzW-RoP6+C?;1C(9B)>plyh%^V9m@FAi0Ib*;68ht{MpmsRf=S^Amz!^V2_m! z#)obN1sR1BIYD2;NfIRl38L=zs6uq>C1z_mlvD!??zn_+);yuW$}oOe{j_`NzE2%rKTTJ ziSJlR$S@rQOBNd?d5ntu1dQ##>StoOgQs=g5R`C2b7+a{{4r_~1Ci8FJpF={65UR; zSJ#XZo)lU*J!xA|HU6>MW|La58El@ImJ<|!BK&#h)bDfg)Xt@L_tMrIi4K+#`z@Wv zH)fc$d5oTn{wE!ssc07Iy!a=oa8Z)ll+Cw3T9rZYMa`a4pUA#W*QK_Qv^CpmZ@baG^**~fg#6Mj9c?f#QnXcc)YcShpG-y(F!ml^;S+i86J|J<8n^|H_ zrm3f6MTFpT;mlV3M13*|HfF9nPn>jz7}IgcJ7e9O#ApgPP27t4#cz zM&|$u1mM|{LAKobZ^C9-$W}?BJk1dcF6?7^uJ;pWH~tK`x{u&T?>~^0uAfpxRqlGfpO&4#citn#Fc6Y6GBX}Z&wPHwF9z?9aHbrtezg^81kMz?j75m6*e4iTeni8C6iUL=)(R0|AOxtnc_3ykbR^F^( z$T8KX`NLDk&MjS?FV`0Da#|RP zddm|@w{>r6K@SFtw;nN)ZnF#?04@&{R?6mHYhYbUJsDBm{dLpQhfq-qRdq!~` zMQ}6>EGgLJz;s+Ex`h{Ps+b=fN+k2e%+?l4>s4_M`jCCnyXh2+W%hjo8G+L-8PAw3 z2wka=$;BL3MD?q$yW3ya3QfaC0l>$PyK;u+n_g|xW=8<{iu9V@3DU8O8PDyyZnNsy zEOMMkyP(RtDk@rF9<&l>HUD12_tE@WxhOo+9|p~c*fH18#s4Q(Px#G)4gZc^!hNV{ zI6=YK3?&I;u#3Er)8vL}v4^fcjjc7Bk?tm3@(e3&1(zRFSWIdg@Q`(B5=FH2@vT@S z&e6MOzm2pcoZzUV-uyjpOq}ou;^Sh&z-=G-A;jl0IiG4u841Q-d%V1RZ;9j1>5kIs z;yuBN(vbTgtUe(7s`4DXd(+P7pUll@9;-PGiO$vbm9`c^4nIQ-z^;#zu9OKOqK@_2 z#IgF-kM)NkhwwNMjklni7ik9Jv7XiK2^D0K*eC)l?OW5#yd#~8pbJ+4a;#865c;HK zpjMsWCLZte5qU(1+pIKc>H^{IaO0iDOtDgVk~L!eTS#q6i`GQ8T2koUYRPRovIA+H z&P%mfcRO5X5sSkgNZ*Ti?!HNJbN$WA=x(-pcB@meH5@2v-s~$OFxra3%0*A}iLe^=(4ooTZHk1tK5V&UzEdY8-u zilB(WI9*MDDc90VxjLEjo41L@Zw&CVM*4?zuCWEbVS^?@DfTZn6)fgAIj=0anMB4@ z(t4p!Bij%{V?OH-Be$B&EoVwiFbZ6ugk5Ghinac>j(I`BCiu0h%2X;OgNDLZyw59< z3&+>^W-o)o1<#TtHyFCIHwH(69kuji)ivNd7OAx*HM9$E)oV#Kj__Z1&yk(&A0EQ% z!qR>{B^?U&`}KfkHSO^&O1sE(%Nn)3g8(>UM`B$Y5#ud`dvo{@qs)veO2da!$E>)R z61OYOrBdFkG;s!GD{4%+P$2%DiMNFwJio3a!=;%}ZxJci(wnKV7XA;^G}#nD`NzwM z4Tji$lr*zpLTf9^vpZmgF5`kAuF3no0XB^28(B^E&~@D!fBBiV0a{Z(HkEM>^3!A; z0Sx^6+w;n0U($hr=2J@V(Cd`lB_o;y@A3^h*kY=lKuI04wTYQ~4|%Nj0FA5^+?Faa z$TDTYVeBH4Qkck#UySOaO=$2i2)0%|Rqfe6js~74 zs!^gxFroP<=@OPZ#Pz&5fkN?sATUeTu`ID_1=6||mAroN@E4(Sj0wAr0B)n9&VeqEjJ>MGQ zpZa1AKJnkPiZD@M{p3XUNW`X3WMMR}yOB9uBTdKZbBKNSZ$tVicIqs=3bRF}5{CP} z3KX3~(D>^F%@}u4!wc(8PQKxisY9x|J5)2606LpJ@x;hAH>wI68SRRWDPwrtNbyu4 z?5)ewTPhBbQ@;&SO=``&;l6=RoZ(90I|Ue38d{_!zp>I3_dM1jGDd3hBFks~RVu_S zn%=(KT}RvIiNw;@tCe1@?F$w%MV;7QI|I$uIv-|kBy^Z`CAxD($OvY20gZAMXE*DsF&d2neBnH^Gk zUO*4Ay$f+o-rd*($JY|~_T=r*2Z8liWXL|FP#XDcGN{99o^%<)e&68V`K5(vNsR6W zxjiOx(Dex$-ys&lTOLxSG{QyW$z9eYR3Z5MZ@3{qPq_bkn9$b*aw^H7{O1)SXPu(m z2wCTG$>lxispH9m)zyFRfV&=y=sT4!f4+E3!j>V!a%a|n93gE z4RXh>ff0dYu9dXT0mJl$UB=5G#XB|TGV0z+dOpaxIwG*yr7WR6r|fIbFxJ${s#K9T zR4Gk8d+b#i*)@b)yV+dZR1)C?Svudv>IkQspdNa5^d?_XT|?jiIX{p@`s6XKvx z1@F~l8BRx^sI#>nkU9zULie5N@qO5>e1B8ESrdVopLZH_dv^{zoMU%XUXDBzVA8gy z2j_H6Mb9^{Y0qzD3=zA<*Ag)NHMGMRLx3&7uTumyz$m143?vGEnRG72N$D@hp(<if$J(@~8gJn2PS!Q&*D(GvHr zfZ6V5keQ4LxCZTlN@F-VcW2c4^?`U*OVvwFsAPIihQ$jDCe)=CmZX;uAI|(o;lYoyWZ*5 zv%*mpp264nrd#&e;4DjXfyjqb#QxzAxjQ=0VtBB>#8j*IcEAajM8`dyna}?0_uCGT z6PtWrlT6!d0d)5W2Ekd^HqcI}*`p`Sex#WEE)c~*FO)_am_v3ZqrWh;?ORuDU|kdL zkPbO~>PL-2q+EXRX#S||8yVf~PAqvK7j=TBn4q89aVUpRr1fjCq?3b-Sv)HT&h)mk z%Qg8u-y~-!H3QMPJM+pCDvOY7l`88!0(VF7CwJ>Uq~%1#sKghkl+VDMh5&m2x+92j7r{0Y%&Z`=m#Xww{CpvqelRb+Ur(2KYCr1+qKdKr& zS1DvDFjY!}3d1nEJF9a$ltbfiYiHc=&cA94u;=GC{;Zzd6WkxMVJ~-?a!wEb=aSG> zBZp?Lt)d;#o~AI4G>Q~syMU3m{IE2uncpcSANnB-#w#^)Jf{YU3ag4IfNlN0Bbg5( zP5XMAc!z3iP~16?ZD9jDN-orB3e4H^S5pPsC9X?141O*{R4 zH^ad^6ZGi^X{=00^Ufpb>Zj;kknKJBEK!#wAKJg|0t5M$2qjHj?SeWpmTQ?bC50E9 z>1~KwGjC56XLqi;z7u$rXJDPfD-6CTO^U18K{A~0%PkRrTAqNT&>fyK*<|85cRgt* zf9M+KDooN>+D%MyHjAW%`@^Gn*8Gy0!tQ~T;q0ArHRrcXi|94M#DyCznG)NTjo585 zOiOQ@%}3;oXI226B!A)0gC5Lw>qfO)1(9oz{ey()7TV7YAO57!LSCX7N`<`Zr5ezi zYMwZf)daXBFPdlCz0h)+EBW5mKg+oCDOifDBMwq-b#$zZWy4R@C^)$6Z5Ucr758dstz@fcnRuoT;vFP2hILq~cUIFyp{Y<3$v!;d#!)hw z24&5NrUEq!`%S2=(ZQ+Z><$#u0m>fDBhtV<(=84^hutl1j2-%07qx` z+f4S#z|0@XoTqOk<@a;iZ1|BEwpig%eftP;E8k$mBebG?>-rayEmMsZG50vd)bT~X>{OrTBY5Uh)+F`n8@3p52pnJh--SD= z;WU|%vEua~%oCSdGP$=6VNb@cl(zbhc)x)d+;lH~RPZE(7@S5buO}dC`t~~^bIsRI zYl81UU26gh8!pf>GjjLFh97}yC?(_<8s_F=L6SHNh36+)Slsw^(_8<|byZUl`r zs7uJ1-F+peTB9IKaYjk(OiOd8DCa?JkXT~dBxjFSUfkjjD&n@u2!Im4sx!PXAv13Q zoX}{@1q^X$cYrh1jOy@Rs5!Uz6-`HaP+i0O*|?V>Qy&7l;&`TSK}867mhl8a)b5(% z8uF?2SS~CLeE3wyL0QwSicCVNZIbbshqdpHsc(cl^HHar$IgSVLY|{ktG9n20gz-^ z)rGIfDU>r?tbE!RId~70t@8lcqbihMDP18c29C~0nWxN(v2xW0^T<%)NdSa? zk2c}@ElkMN!`@$RN~KPbtFYr>>kw{%{^eD?Ba&=aviCAjatduCk>u`K-ey|7A%baX zq}4cH^JkX{s!nE_YDYW*!cY3I#EiL^dV_9w!D$5;I@;T*K)`j@t1xUEh0Ct?yLgRZ%07kfZx5 z@vatr)QzzHbpZOGQRt5O8PHBNK``pz*u(~HxlPFO^t4sC%TDrtS@zH|2Q|X^Ljo-A zEjC{apsxw0rLVF__qT$wgS!*4o60W@F=X-dgw+9o&8;>Yje;(Yqqq}si4OWubC($5 z4c?)-m(cHR1IXDu3pX|ZYP1QapABEgB4f7>IMrXiOi!|#iJeqOyxF(mn@x}Irrzcs z$yV66r$4myprZ?VKI)h7A=D65NI3lxAUBG9%-wk#QaVx9U|Z0oy&Z7RE#3b`2HL-b zqzTuh6Ha)}Jn)&a633z%m)AU#++$*(jWS`s!Z{f zUvKjs`~=}>6E5(hURfe?_Bg=|(Zyoe(0C-zC4Plve38w4RTLmerR5r~JrfKw8sp|E zFMH}bm>mVEpRkbojeMG{*sm`m{_z5ofr@Mid46wy0%1AjQcx&KIjfK2TP#29{+fyx z+sx^hkBGiaJW>YFeXSq=zx#%m(C(Z5b z$xGGga2D^IU^?azDHfSsE1^}e2CsT44vpS-3`XqcAXn|%(n|(pNCX(bj=#4mto1NY zG%?Zm03eUY8^9?htzh+Q69VUf?V#Ic1l`Uaf0Wue;0yLjwUS~T0h?)lGTK=#>?Hef zBOOQsVclg1=SSRGH0SDNEa7Yu)Uxx-c~Iot<4-MbtzYXM$y#N1R+qusc(Z5m|E-absBn4@KT%I zsoZD#8ncnEGxN&DcH>8nKfBbZ0Z-ScU&b%AavhvH0|Z#H38Oh%9FG#=L$pFkBoT z$qR-$e;J%?)K6iW>OR;4HQ|bG8v}@LP*DOxE(KMoDIus&Psnq#ulZs)&5Cjc^^?sT zAb#K4DQo@Jez2uma9$vy#(6NPT{2w#SQ~14Us-}bQ+YGGs-dq^IslHEnpKv%zl~j3 z*1YFzG=*1NT}-h<1jcR<(}AF^#yW?r2ipsLg6ti!H&bA>N)ZK>(XmME>ydiJ%{HU?_!Qd4X*YM)21!+=h#X#-45_{48fP&T1mg z*jC@#mOAxao-#VKDQ$7sSlz*kb6me>Rj@Ud!q>VC@s<<=WM#aLMU}tvhwh;$$c=b| zskf0(Lg#n3jWB;U`=eC_0o#@`BXWBC$a91>TV={4{Ac&xUZqzBDc}k-n?-7ygNUUP z^LVtSybNm#s}7ySj|*!!^2kUH*}J{-M$n>X<`I#?f;+cA?x(&ET=&QspX*<|D~MK- zN2}g*rFE&HM53kuR=nKOEPQK2oReNvYt$0qklC_^93>ir-e!At>)`5c$s7DvXRnDF z^F)g>m3RH$jWG%laoz5{LyogMWTBoW>12X2VUWo7`r^7 z_@m$^xKMxGJumz<$)_zf4=FUoI9Z5p%Cp;8^F+Wq)U?^eKq`&K^K>*rbDw|ND*WIy zq;YM5H>)WM;+xL9rEYkZ(z!xrZ1%qYw@BUkC!-e3MQXvC;(|%KZQZ){(X>`Iz1ZS7 z$#|)!x7=^{-k8SlO*>YyJOB31cmHGgKYW@%d>#G2b-$A^oN_RN<|wZnKb0Cez;`Ih zZ4VRK4SDd=PFbLH&`0a6*vYEWz}|}M_?w7e?ziE957J+_9RS0=$4-aiqSwtG2gFLk zu30>?(r7tEkekL=&N}hwXqr`5TBI-yPO$CL<9C+J*Ql^TSB#nlk%_{bWU8ybU+eR= zB`=8oSqVHXsuZ2#oJT`e<-EvTope!-2(DvKCiHV(IO6La4ijV6qj7+Vyg<1e1OZ+I zHjb*vW!)RPq!NnqrnE?2EJaey*{6cKXAbC8; z)Ruo-^7HN}E3Q$xRNII}g-ZRgaACyw4!0~;A$2@h^e+FWuHRk@(J+v%d)U9?$|-n8 z$^b$(Y9-(gq>{kZKIuZ45cW+2o*C;&nJC{(ZxUrvs3+OIw#9-l{Sq zNCf?n2cty3pI>Fa_t!o^{0fKz)@)_YJvH1L*J<_+d4qmyM`Xk+SVwDxc_Yft_MKz3 zK}+rJ?U5n8z_6Ouz)^H}p>BO-Q|1Z%bVc#H?HaPQz*Xrlg12;EQr*7Fgm>pvT@el%|b& zsry!`WM}$)6bp`~$nG<|J}{i_Z(Dc=k4wvq>f=bOSi;9|T*uz`dxYz}u4A4v-st_n zXoq1YVHU{QQ=~%VUzhraEjK*>!vy`JVYYJo+qeg_DMw1ZvQ%TrKL#|N8)jc$89u7B^Sg)g)XLg zn-upHtKHkF*a-lVM%sISfaLHK*mFXa1*>-KgiVvVO*JU>RKs00Sb*K6S(B)4Jkle) zXY1*F4jQF$c-BOyrZp|guRWyZ2wgDV@%}9=FfDiIxNc_LdgUkAp0oF! z;VA5sLej$Wa^$T3c1SZ|?!3&Vg_k{N?QqKGD%#)K*!eGxulJuhjw#Wq_&S6gJC{L@43?eW#N3`| zd=bx!I-;IH-XXS0yJ>eS-ZmBZLV&HU^*>>0aea7Fo*Qm@X z*MlIy4T#M7<9V{tazem6$%U^xf{iI=tT-XW;7LqsQr?Oe3L+^@oIdd(R7EnpF^&j$ zOd;@{O~W$jw)v4HvXV=|(PcI=RO{^d&vNC_v*ic(y+d@o{=g&A6^g>#3l=Cz&zQCu zDjg=e+(3+u#pnIr#f3cLAuY1mMDPg#9TFyq94XKvZ4G%-wxc2BIg(gePf59%&mzL;Ps6+hFW|M;iMO*<-e4?|uKVo^JAcoR@ehC6dK)PlT zz%;o;Al5x|P9h}drnR1&)b@YouX#E-){4K7m`yaz3A#pGxyppb+%9H(K}{4H!25s0 zZUwGwsVp4_z~iRKxfdY-Jp%8Pv+0%h5p zZ1(^gsNs~MMGu2d=zSvhefqJuC&Akcu34RwOwIzMeqa7=U^p6Mw87N>U5zz2dYlup z?4548IvN!9j#`66rA-ZkPjd97HR!u}Wb4uFJ9QsuHlF1MHA+{5V zoPxV15fn(pO|>errY~#cwA42l z>+8IuL?$~K-}_ijndd(#k+R#oRSjye(o`J*_uS++fl$}5@O;w?IS-+(ANOrJ=-AEYZAxd4)8Jj?qQLHz< zeUN4$T@6GuBobJmw|`1jdLw#8CLJ?8v}YqLTf2wAX)I@JK(TbtDhH1PpmN7*48#^+ zZ&x4m>#VL}A=&&2go3!Ohv~Qo{cfgya#0dn61K-Td#7bCu3lfM$vGy_@i8fN7}4kB zrGh%jh#qKG=p(N;kf%dyeSA?o$FxF}^1wy+FqkEszm(K${`k&Q(mGwz11UXuPV+qq zk(P`>;7m=MY^+v_N-;+$>(whG+XTNut(nm6Sxw4zzktG8r$fZ>y~siG%6EJIyPz-- zkZFXJ{C!*s!TxAQ#-41-H{y4d< zu~BE(43*WWs(mGwe=`>O`~K6w*s1KYin_N`c@Bu#K6snlX~o(#IQL z=*c?-ss+{hDw7Vo_>IQ)QKGJ~+C*uI=#G1sj)u~}NXr}(&6S%4dmqC;_r>-ym87)H z>8=T9D727bth)3?DoB8v=5)@p4j57&8tLzcnG4e22ECRDD3CYcyCk--{7=gE0W-6E-8dQ$Vd;+Wv1X?}z5 zbrjlrLV2ZXpm#_>?N_{1SwE)?0gqrk!jkyw&ARJ_xeDt9D&BwMhq%)<4z~0|oUC%2 zoZ%>A?BaBj@5?Y9E7fGTH?-8rtV4O>bY3+qE{|c+h2j37L_M&&FiveNgyLnp{^Z47 zoehy6jQbgPp1RlF}q&g%#@Vl>U0LQuB} zshQww4CZec)|pU@3*g!S2~h+Yc18rkEYbvp2~PF?#y=QC&Ce8ZorSs~90#4AeAD`T z)6hh}MQ^?O1Eovy>iRxOz)g1~m~4%ZXFAdp78D{C1k&Nh&HxXYyDIv_-Btgv2*4UK z^?&pOozUHVexdoTM)Qvn#bn*074`!eT81^jx36!sXdR^3jW0l-0OB1mJzra_fbk_1 zb^&p6|2nCS>YX9QdnUJOJ~0pu3qt%sW6BL`V59t4uhc9u#jG&-S z2S|mZW|5NHB8N4a_iaKS?NuI5zvw)cAtsTZjssBk4U7D+FRAuds|+*pwp(4u*OKP; za-(1mb;T{v6fyK(GP(a_faRw&_xDy8b?dz^{*-!d!d+(O-QrF8vvLIMR)V)HMEQ4p zI290LF)5S_jHa14aY6*{$S&AEo87sBX?gYQm1LwJBO0@|x2^pRH>%+LOlz6B3 z^cBH-`jy(ZZ2;cc6g~=J$;LuC5@YtW)F(z`WU3{NA`X~{BGGv3L-}pv&8Mk!UNIrS z?|I%-a|(JO_DgnZI(yiZh;EPOkIQ+Y`~E3{2z3w!Q-5Jf7FUwz70zW5e;XU)Ux`~Y zqqUU+`F>Y8d9>w7RIhCqhWgpfV)jTkm=|q6*T84)m3&$43@2jB&Q`X-s^qPQ!->UD zX9CbNWx`bB{2af!mxsAn3gzT0!@OiN<5$8p>qbRRHS8O@#5tu!XSP6>37|#>_+D&w zFL$0*(upDQT_VoQ1#9;>;oo+B7YjWudEY=I6W4}9c&^~cyf%paD=`mRMJ?z|NZvvQ6{Qf1e_FBW3yUb#` zepIJ0@h5}7_RD+)i;#-!AkfI5ofE`+yKCULR{XA_JlN9CJn@D%8*FoVWbzcY>t$vq z56GdL@@qXDRAcD(A<2q-60@m(p&>;QQhHfQv}qCkf!To8q4W;C0(6EODko9hm+q3~ zfnFRfUX-3QIgobhcRYfDFLFxN?cu&ljpNX*DV$U9pl@_{or*l=`ix8$EgjZ1{E}bD z{&08fuztZePy_dI-1lVTR&ahktr=`zFbo%y*BOC$3_D!x&C~SC)|0U*LzMo~JN5ScX61)1(;wRw)v70&-Jq*EQ2E58AhqjH z@*{a^VC3LPBZYo(_Y`C_Y)Dr29)-sbS`n_q)H1n`)EZ8EyVagO3zkii^8PhZd{U=z za;aW)-^lmLPAeh>I9R-A*{V79wT;W#S6X)hPJ|^oN`OCX1)RMLqkhBHhA#li&1$!> z8_iks)v$hc+0lvKCk#1KXb4)Xe1Psmwzfq%O<0pFr5P$aP0W)4wXY&^Tba1+4lVL7 z335QNeJh*=#5gB$TQv0feDTXq1dE<6?7z*(mv_ZJXSzt6`VK zm3wZUR0FB_&__VLQUZ+zxhIwwwe{=4fC{seY4~JwPy)s{~{8PY<>V&S?dbq4c{y< zLyet_f_?0L+Wk=Rh2^|>_BV7ro8Wy1Mcw3Kfp8l5EqeV5a$o{$4XJ3gj|4_5nG_}v zI1xi}y2-!|BG3;7n*e9@Gv;m|{#;0+8huK-Z$`tP)``l3Ic-bxzi(-9OgV?JFQlK3 zXPZWU1unqN{P0UDbIWZDr@+w_w?VWFWq>R8YOBZt`SlOoHnpk-5b4<5{pCe2@Kk_E zWc=;5HxQVbfV8W4=`226l*Xejaih_W9!Lw)5*>gOztcOp{X@?}aa4TfCk{Lye1HvH z_ym#E()YQ^(ckr#jvT3IsoFIBI@~AeQq8lsrwc!zEpyiZr(sm^c?x?MYDE`|w3F|a z3TQSpsN*-WKtNEHC*ZKqEO1sDdG(~2dhT{%+P4AVg6ngn?|nx~E9|`y%_*B|+D>eD zE2#%AvpiS()p+K)J1tg7U@LGEi12rI+%SvNu?Q=b%2W75kLL-26nM=NdC43>8-~%_ z?>e5r%wv9xT_`ut*>hnhScg~*wv%RPEg&`kUnB=dQH(auE??Cs-NaRWQ0A#11z~&A zswxyYe|#SKbt@1*AnVTQ`re4*E=U0h)nsZh>jh%c86iJ4+34~b=;Zcma_3gcTALkd&^ut%6W2hF)Nzc3h0~u zCH2pl-A8t{`9|R)g1`dT*i4ZUPRv{63QWm$KT#EmhDcduptbm-+Ge7F=BdT^;sf#s zsGh3($DYoypo>rbjz^_Zi4S6V$zr*{8QdG-+<>Bi4Z!O1yy=(`dZPE+@8h=~JK~W{U zhJ2^POsD2=V8cKVL1Oc94cw|8uHtNX&{2C=kdVTp;^}p2Xgum!Tw@e$VgD_HBcd+_ z7sgZ?<`GO4`ojsOY?4oAt(v#-m{5gmD!Y6u;sX53AMZqPO`taS#}YrfYH^KL67Y8Y z8=oM3Yk)<{r>#tuGilIIwy$z3cX1M#97tsEjR{Q2J9j5otJPSQ*BUtb2+nL@Ke|mhEMW>eQ3j|5uKGy@tYf_3InTC5D%EY&3&@NeO$;1pw)Tscsc z*EWlQ1PK}!MPX@nS+VcynROpf`9P6tBTjDGQ=iDhvx8JAfSu8cBjP^%tg5UP@ZaEk z2D%?&4e31V?lmi_#!^AzZW@GZQ=8(tfp(v*348|2FJxY%oEB{s0UnsWW|3%!!JO_$ zh61>*w*5jcLjgn*RUg|syGYgGWL~27mk8>(t*MQEpYPbLJwNIgqo&_fShYnsa{vv~ zwomCmE#!X6mREa^PwGQ#^c$zy(!Wc!If~z*{~&o25(Ml%50E~_MDPF3O;gJXgq(f> z*2fR|W(xw?kb*Q1=>!Gh4dZFpiTiJKA5h?7+kG!ffD{T&bxj&mblI*$J|rP=M1qEY z475DF3cm=b>CC<7KPpFyLm$-Gf4ZOlD5>943oo*rSVl)9fxRrl&mo?|)35+QIHk82 zX(;1!i}GDST_+2SUCW7be;$F(do%0{>b|QvFFL*6@L76=Z6@um5pMjbxYiQVpvF3q zLACm6btko}K-fGFiufgUgn}GtDc8Juv%lDhIH=Pht@BHDmmwYgP#HLxEoYK)=FEr7r;z?R%9%aGBC}qP_OOO(|V#%@4A&9x2&e_6h4Zz zAC_IGUW_HlMU&XAScFC0vs->l5~uR^L(p=|g1RBwNEypYs&VdLWV?XX8m@j8JbqKm zc}P8A914$v!coo9+VA!clP?v3&=V(u{)AG}E2S#$c##$38dHhy%gg%9t{_v!CNeHM zzvC5tEy?;t#eUg@`^zdP&>4Ys1DNtFyX$o4orQcK+k3wNjhu?0V`r5^%vK^h>i%y- zpIKE9NnXGETYHncHJRHyt?MVig-1iuc9=!JHL`FBP7ccJ`&IRoo9&M_-{QrkRM z!jT5r>~BPCKWQ2kJzDafJf=7Td;qN0LHUT0uM)hq5< z)@qIQiQ4r!ehV1&b9trN>hy@r@S|yYy5!{+#s)S<3X3G7lVj(Fd(!*3nt(r*FCL!> zvtLdL)lwC_{C4qFHjwd~>c%`|E>j7^uxv0Zwu9 zedb%OcFnui>~Gxs!{IC~K!1N_dDQse|6}U98?>>0)&f!>x zW79E?y`ng_>`f}lcI;!7nPX-hnH?lKb{V05@9w?ddw=KQ59d6Nk25~c_v`f>ulGkX zg-fQ%e0&zxDGKEz1E{j`h9-MBw@qU zr*NTFKdOJgMeP0k95H?6)FcQO8&1VNf~$z7h$+(at27ghC_0l1r($1Qb9(6F7NX`H zA?LZ?@=$b0JBPG2p3!BUd$PYFdpp>gdOD7BsgC%nF>(W$*v+eG}J#Pkk^7Is<3cuoE0#q|@qz9fGtZyTg-f}s6OmQmKE8ax=e2*t zLo8_qLR~dup#D5tQ7UZ+6FHCa+hloL#t`;sAO&5Chkw{4?H~fkmV*F-Mv;`!`9U{dj!)zS|32VAzf+@myo>1#Hdn`;e5n@k&|z%)&|EY1OMgT&>p+BC|CXs zqavT-JrobO;TI^}P|AJBa=}zhw$|n?e1&fh$}aNZSDzz!4Qq*<@KzO@qn2C42u;$<*Q-7w4$`V8IPWtW3 zH_E!K&52bX=^?L++R@gJk%eCKtpCNC$dBxjZyDnM1=_P4e5l~F1Hbi(dK$Z|=lHC8 za4%&-M$1OZSq@-oQ<^+%y%GtT$lo4F6!ngmsxC9qA{n5Gp0t4wN2G7ct0X; z-whjZ3?U&XboSyW?b3$hl6nignk8Zb8u@lj(Jy}T?EtzFa;-^t}OH`r!fQ10n( z(n}EPkubA^3*EJgpAey}6VkLRND&Ws)LVPmwBJpZegD_y!dU#^RCAA0_t`-;G@5kq zf|OvtOr859Ba=NGt8q$mgymHA^OJ7uH&N{L{RupqCWvCX@*=vI9~zu49^ z-3t~?H(dW*+HhANLTo#=!h$+B5qv0!xI|oeaNCuNL4eSY2AR?wvYIjN?&Itf^%>q0 zm##xZeJCf4C>V5Z;>!>p7Z&Ve69dYFwL_=Mwz+ZIE)h_5*CwcSx!0(^E|+}Ypf)&B zVAvsOHJ-7SyME6mT~)J>)(U)c1rx)%<-RvNHqiV6X`T@~m`>et2(9@=T#o1}J;0vq znJS($Y9nP*YA9a-AZZk6TN*9v|D+mZCfrDSNbyET$W83Yk6WerrB@ToaQ=Rl*bnmj z%QbyV;34pgs!@7^)g&g4)v#;O-;Go=N^k090`BrUjuRZHUF6nDGO*e4k{u0P|8$M` zJ@T12)-8AA!?!`Qmg#N_o{03}!RDt)P5g(!_|-s;1x;Bi3zA2kuH|LFfp~bH{Q8OM z;%QD}q&PBEFw{30y2^-OEhDUC!&}9$rE*>8Ps=MT9+PAwPz1Ny?Jn^g^ule-U5dV$ z+=g~~w_=CxH|aaL$+JP{SpEUxsdWh%7Sz3e->GfI$Ks1SkSfHRk(E#^-8!(_dO|QvG(+{ z2cFI0*Gp#kO66|Xte%JS<0OPN$s-&7`VK}5)A_6#PnTI~SKA2Lw0^cC>rmVHcDmPt zW2rYgb>MBY6q;Pde*Gz7&>ZVy8ocj2LQ6F?gb#J5OEbyzrjBDhN8~ZiBp1{Utc5Zj znhpQXemXw>MaiM|(AG`NPsjzs@_iOV*+)g7K@rA z)yWDF8#hwUKPM+VSe`Wac0uQ!b9WLZIc&6LpMy^$EuXx4-&1@)i+q^(>($f4l7Wam zL^_vc@=KW|&oO1?NgrL(ORAIGGaHAxn~)s#RP35-n)*QZXT{tpPtA;5(9k*L2)VHi zSJCQ9o@lkQ&t9*atd)t|uUCEeoVI5cP!0@b2ewAC$Duoze_4^=Hi1LRSd@f(W?!>Z zAxFPS85`42+BiJ*Ao7qgJhXAbCMXWlDR;dOYB4U+6wl@XYdR+23^9$6PWk(x4UWTh zu}*Z?S7~*hCmF(#!ClOxed)&$S%QCl-XA{M5$)8%nTT>j09ZmvF+^MbdX+Q;tyg9GK zpRl3X$A)7Y6Ti6+P@+YAKIaypV)fHA%a|)05=#+?>rZ5?>7=E~ngr#_|LO&uj!l56 zGJ>7JMuq4?g@@g8wSm85$n_9DE1^f8*56Si2NzlI1NC1-B{crpD&I zpYd9lvj2ThON zM*Qy#6~#Z`Len>3w~M0b*;2CLGE4ur^NjVe?*S_FYtmj z^roUcmv|=eRCU90PP+ZwWPj|iA0oQGfQBV|^h4Uz^D}vE3cKv-;gw)5Taa^dk%hT1 zXEecVo=3*AV(V<4HR_s}s^zi`L6L~&|%G*|+=-ePM zzR!)U*CcM&u3%MZ_CcFVjg;gt^*41mcImb6e^83#CDWjAp;_*EC64T1&s?2B-|!sR z_m)Ivj}qZYy`j)m)Y`d_9@;f+F71v{OgK4M{|8?Do`{p#6up|T#1#1)y84o^avmnF zh%yyQ90%JGm?0D>8)fTk!lA3=s5uMn)TXKL_B9Zt{GuT2m=adMyfodf8ovhH2_mls z>-nQ&B&&jGSvo3~Y+hvaqvO^F0KwhE`A-vg`tolLrDY0~pqP!gn@mfziwZ8@!mln7 z{i)a`Q9~DCYVI*An^mP;5%izq$s}S_dag0-WwSJQHyziG5O#2^UJB3DUiU@(sb|dErz;q_pY+Ocm+|q6#JDJ@TCf{;0hFlqY zTeMG)xo^Sl=ORz3rdIX%Why1>T|4a*f-N=alF+6wOj>fY(5%h#S#tfq37g2{Z$C>Z z2L90QfQCLJ zHo~v76|`Stb5<9wNS{D<9KYJSA#+4KMDP+d{dYqoI;5bSEtO)j#*r|j|z0S=iJhJSp zvg>!|tA4guPp1!t)EetLj^7V$MRttBP-VvL=lL z*iZ|=e4b4V1BT6wBfaL%SD_&2%%nDrmSHF94`(#vT$#jkKFnT_7d;uNsDbA+xTj~w zq-nQrD9K(7<=j=p^?MJ}QExYGc7r3cYVw@!4|1H*ol-TJ3<1^XmK#@g21NHh7ejy3 zr#t113*T2i5LUuw)%0<;3z7&kcj|#p(J_ehfU@9u9zPYUg#nGUVJ{Tn_lL4Q2GlDz zDN1mTjb33OF!f$z;9PlAlOX5hrPEH5!9=SGiO6Qv<9tEka(n!BBdJ$Yw!nIlBO9W^ zw|W6*%lT#mofB9=aM%IFiwrL)2+HJ&HQqjkVDaK6_?|Npkl_|jS7oU7c&WL z>8zuPF!_|c=&akqz-`6+tZS=2Z%35)5k`*en%JzzFa-Kn<+X&bS8?Z((3BxlxfHt zsb%@5ay-#kmNu~>0dDt_V3+#i07 zaLB=ODpCjj*qFE!-fq`Ej@wReR@u{zeUgFjPT-)YY@iW7AHy^6cEr{9Gh|bmQd3Z0 zevTulWo|c8)gIIg3ub=XbdD!L5izmas61z9c+ch6At6WEx1F&@L1AA%ZcyCp+k~>( zy>q%Z_!C;whL=kQ8VTL8@cL;ZE|eqheXhK^z&8p`DNK=UU4^u+z1UlrvCB8E;`(Kg z9m|dOro&I{E1y_6c1hP3k~rcnE3Y&u+_8%vi>6G;xOiaYnCdO=&eFRffVzCGo#^W? z;uDxK7A=j@5L;I&H9)vm;N&No;yz2UxvB9q877#vdHwj1tQnJRJ0FtcO{HEJ2t4bKV{G_!KJ(olq0U6vNvhZsM7iN&^Gn%LY=7{K3na7BCN1!_W71WE*}C7 zB+Zyhe6A8Si>3StTm1_Gl?MW4sA?g@T63_z!5!lZ#f zb~O~0n`79bx+_yG-r+B6mCLc6*SCbi4(XHU3i_QUWV5t6n!LrU-Op{Lxe^efu>1V| z?2O>^!=OPr&Vf*a-9QWz5Mx4S%c9onRO1ag=#E;1&W``KFp=aO3{9>j?joO6dPyRS zpsNDq*A<-P217wNxZ1VxD}uE87B>2t#pnJo30kdVTg!gd%elKV?LoRRN&C3Dj;P^L z(fE;`U>)HiL#aPBh}8-W{MBepeP-7$ea48V`ov{=5ZRG!lden>3G4W+hwMNq7Q-(2 zfoIQ8lbC&vUv}1uN%srq0FWu(EhV+G-my~~HaJe# z(%ZcKy--dVbyz&xT$#`^5SCq`9CvSX7VTMUbE_g?Uj|iGA+tU(5v@gGO0M>~%*uZ3 zHT_|Q3?-_$-st*{kcP9z{J@F>=3O zg&y|4qC7ODNOrF-4ZQm`Ay&$Bf>q>)w)21vS^p6GbTw?}Iar`QT;fNg&l)Jk$n%u4 z6w`~{%_f&*=VN{;!^|%k-g(cl+q7K9_g72D*uot!Ev1ir(Y?q6v_nqZv}sSDj}-SG zPR_crQm-=OoKGb?13IBIx7&lb%UR$CnWvaePh{?$oTz(F-31d5t}4)xY6J5ILxW@3 zm?D!fo$_H-_Z+%CHDd_7)2@>oNstz+TJ~IsqSVaq>@@xS&n4V4HU2;t9it~?o|ZfL zjBLuR=dk;Mp5`OqX@jBFn9f)vuK;WZ=iw}N3k2*+*%Os56^ zKmiHM6dCAN)bmh+$1iqZ>MhVT?BiIELr3VpeTrV^ype^>Z zYrUwb#?v1CY4*>|fV9Z&9x9N(1OVH4sXv1*{o=lPcF3h4rULLzBO%>M>#JpG4!K#Dw7<@lMOu*>Q$w) z&PVhd;+udjz3|&gr(N*TW(V>)u)O}C#v7bP#Bp+K2T=ezJH>`VUH;JWPWEgMQ($bh6PFj=L4 z7Klh0Z&()UO3P9++5(ns2=}#5jIb}lrU4BT{Df~dGOyV~D8w*IkWbySm?T$*a>pqrmd2I`X1TNglm)0*wfP0KG2ctm`X4Ii{g0+g-^wlf@e znZ`k5Nm9;f_R45yxMs{sT0$vg;n-8uL5g?0I>*<0(td%Y1pW0l^5Z7h0jCltIjPF3Uxt~Xgj8lO^}A!jUC6a4)<-n z59YTmg%3{N;1iMMo60r&mYU9zitYRI7{e%Id!&LmqOj}M5+5RIaED_UUu4{pSMNxI z?K~YNLZ{n%Zyfth(m(&n;*LFu&--HhHBVJq#M5TkuAp9aACfzdJi3!MtS`IBfgMug zxAh`!-!YNocTm2zK@fcLbHH`nSAs3+ldE!SWNq=s^UBHt|H85ck4$*k*gpMQ zto~dr&_Ks(i8-K7;aB^>>5Bbu8P_ktzpO=WI}@7-*Nk~{=Q{-uJAQydQ5#s{Jns9M z_Gopp8yHG}c>&Eb*a_f`FXVICwjp$wvDTSMO`y6F;1KkfUmd$8V-t%UrbNIqrur1| zqnJ)0$?&HQ7jxc_NKmP#r9H92Cj7a?-ZDwwIJK*&j?R3`a?p>~gExd+g_91TY5>+8 zutG=(h6zi*Ari#_L)j9ydkEce@X2!yL58H7yB*); z$|3rqOp4S2R}&B`NU6}*=u{M@llLxg1Fce_*Sj|2eT>nSd&X=&)D#8`Z z&1AdEo(i?8oH`lrCZyOlW*Z|F9J*PqZ|Mt?^lD&Wuo`=K0t11Gg#VcxI~>^UX!BFFUg6M|iRqw!bzlEXDCoc_(+MH_nMEh6XxmDEt zwDF#mi|~3BRZSkDQk!k&DPct#x*C_1-pw7N)$!!B&~aNI;&teRjvaRcVZu6o3JAMJ zUW0EIAul%k1Mb;+6yC0^{rqI_?#1J>QJYtJy}?KE3A$YIeR@9c#;lty-PC+< z$2S6}Z?~UMt#Ko?Ft7=$)=&467p16D$cv;K1>h*c|DQ31d#|wW`poFMPO(0jw}J zWrn>|JPr|JeblMsTC5YfVTkN-<6q`j^PLmf`*8rV_$LcM>KDi1X(RO%2CrnRNuYcm zy}{KI2l|$Hk?{BOs5PfWArDHz0uc5GX^#M{1iTHb*)YF$&@_^-6`sb!S9tKN+ymKu}Yz|eTKAtD{X_-9h@ z!OGS_(4)O4D3XjC%2cx8Fgfn>ziqq(Mi1N_?gyav);5vEc5|N_VfM3%c#LDC6x1Jy z=I&4`%?FJ!$6`)jkzlB|7xBq0(r)Ekj4Z*wsbgB5DRK)1W6UD|BUP2+2pj#EkfQ+J z#u)8UHQWwZgu8u9hh5fL#w~Xzr=Mqd|9)^_vzA#tmI{e|wb7x6csdr;JWX$kG!gvJ zICKpoGLML0YBzsrCMuuhZ46aA_fm%cx-@(k(FC_UvvEj_Lw10L;Q;54Em`K|1QU7j z`An_~t}YQ=ukJJ%6qzmVvC7^ARr;!wUoj(-soEUS79c4J54d^+88kFway6r(15DZd zbSI*d>ud@;*7P1tR5uzdos}(+NCNX$lm};J`_#5hN(R89^8kChDC*&VO?stQ|Ld9k z2SvSoEBrD?os*e_!rzT-D&@Xm;bmo8r^EA3o;FX=9yP;Pz!K4Lmj^71g`-5da?|To zo+V2k9{H2+JuewB#;{P=#Jrxd{Uw*FZ~2ENEY;DT6hbdHm{T|My#Mb(3ngF6KiObh z{M>I7HRk%n5c|PNc2OVo{!L{unS8DSJopi@3T8zL=;pwQDa7Ae%hpT%Fspw(TglDP z2k#{N*MtI;)kx+Kpr62S)@^oM5ZeBM#t#>W)hhetc70(*tw}JayM52nJGP?nT#xdQ z?h}sHyS ztj0abP~Q927|G8R85DWwl8a~cU-{X>$io!bT328RRsvi3Tuf zC6VM7`pCUt*~L&uvt=6{;t9;XJ3Jb1nay(A5eOf`4%G(3iZmu%FvLEurZhGt z0CFEQ2Q=E65p>|{T&?Hj8~ZEfEpOw;zT4g9*WeuAl)sJUfZ>Q)%Z!-br> zH)orbiVauzT))=_F%r{icqSyuGuUw_cet8(Q=*8$YuTp{u^&{4Wx0tEF5R4g)8nJf zZgcUSPn?7PlQaR9D|-rYmw^PyVywPrXEt={einKlxVbvwcv@@USL-xDJSf9D z+3xZroO`S;iOyuk33O0ZS464IbK%TIF7D+JRk{83+x8=Hun#;}YF{ej-mB?7Jlv zzJFgiD{F;?+81`Q7e7QtGBU*=d@M-23-DICfza>{71ZJz*u_-nMZZkELJ)&?=M}dv zjsF<*t$F{i29{PR!gi{Wmei+8VJlr-Un;X$7`AOxws1u?i|4yn z2BsL+5#2D=bkv)Zip^!yA46=PqZUGFOk@SlW-9H*5*9PfsnMkfvP3D!bm?$`%==PwDAAim0 z`r;_Nc&9vr<6!%T_2kT2?V!3_7P%fr12s6;(HwlvgQ51e&37>8Y|<$)oeje`8O%7ZdpxD$`OPcXp)yKA(2;)RY6966;Cle)n{tp&y|0^2{Yu3wusTAy0#?s< zQDs~^t+ibH4mK@g&xb${NQYftBAL8Z;7age3|y=uX{w%6eEt$nK(kM*{BXF!0{lKJ z_^?q32+|QM4nGlOtNr^q6)bG`>8qG=F0$*hB4oP)ep>)7YcP}s_9=)P*|rFNmLSYf zWl;RZtIRquA%NJNSJd?ub>UvW+JY@`kNd@#N`gUKN(ai-xaY#hXH6AT+#V_}NlUiT zIa3n&AffsUax;%Tch)P}5?HO-%A+X+|G?tbB~&L+V^#PHre9dhaTELX(pA+^8R;?F z`n|S-3_g7s`lHc43Zk7#-o*~jrb_JgUhTEMDA@m0qPui(a?ti4x8uk0|1&!*yk8r9 z7^8A{}3~dM)?Qn_#HZX&tf{ey2!ON5ffTmUwb7MYD&v4 zN@ae)lQ+@+97R4$>S)*yp>edFot4;m@ALZ;)f!Xr%FXrY__isWfcD|za>6yno@Azf z1!p!V*7+}(nOFP3fR3aJr6KK_Z#i2CKg=y>`7>T(Cndj8+$zqNt8zVlcF21$EyKn( zKs**+5vO8|L7)vtHbM*ypN%&A!e(yq+ZI9`KV2stXj)8i;;x_-4V4fyajeOn+?D5E z%kDGa?K4-f+P{#zvg?60)4j+1k}q1BuJI+Z?0j=F{88KAMs5 zZp3;PxPP}R^Kt+$5Zb96=H$C~muL7Z(elqluUE#g+Bs7{?0HflT->;C3rm|bqp&Y> zPNW-@AZQaG7eL59=G^wMJ`OW+R2KvhoN)%ITEOzP=S6ik`yG!odnAsRn+jblQ+?l+ zrt{&!mTF=i?^YRhegVoD$x&rEbdJ;*xm4Gm(_kNkm%rd!+^Y)2kWQ#c)eP-S?hx^1 z5NtMMV>H!NbY1ZpDuV?#{bM5TazLyxwb$Orep$%?25{ZT7!7Kfj#`jL1A1z%ay)qN zWmTmou86Z|w;LImGQEFSR7VU0>GEb8C~4;0eiWAL91);I0U5!#MZvAWcBgOtk2q+9NokM8$QMx34fvay)50EVpfu2Qr*!Qu#zSaak;X4 z_!hcK#lPI&x76P3uV|9f+y=J`ByRskQUPf(Ugb~3sEynPyX``Sj3(J{K=C;E5=>9K zH2bKV7>CI;Z?ZN77KU0{TKxpJ@&-DU_p=d@aYRb<*{*~qgd=l3ZPGysCsHh*KlIFD z)5I{a3Q-sh+lU-a+`ve5Yt2?e2DyE&s;iX<Smosi+F6m`Ba(hMej&P569)dUi~z^%)xg*gUmOf3&0+skP_M~^o!aX z=BBVyF7{#P6LRj(zv0xPNE5QBKjnwIplquy7OldQw0H1KCeJHYaPddZipbt3@)?kF-BTPkshBcP*y03RZi&wG{ZX%4v+J1DDUwOQ%cH*5h$;H75$W^# z{|Q8>LB_+TUxGG>2V>E|DIti&51w{(e_C(89lG+W>*JMWy0ApBo&wdzo4kDL9*<`& zQ64Aa_L&J-`WXOFz%q5^u9&*y_9m!w9b8uh7>r}P*ckLpYLh+fW1C7$f6ldS_RkFS z(@ksO_>BT+s>OO`qp@!bKNcou@6PDkOVCGFgM*p!>l2us0kBVa?dzv(sl?5%7fns!PT`l8wW9E<;rpXL<@EQ_JWTqDtJ z44x;Knbv%_y}d{PX6&gDDDS4T!7%5Sts5zN>YWy{R{7A?sID&=1iORM!%R)5?vlnx z%F2%52eFB1a2AFACk^Yt7+PLo#@1c{s-$}-qH4#|FzMIR>E833>))`0y?hD!IWE5- zAupRp&D!>)#*C~K+11~ z)7J;}R_rF;oOvKR*`ybt*NW8xFA>6Jwj=DP)c zxI@&Vf?7)dmjket|Eljyk)Ss7`uvp95Vg_f5`9Z?V5WAVZ_vVQP>IG7XXM(Hxjska z3VKn$gqGXjT$^7g1LoV&!dy&d1q%p&u@|v0hk|98Bw`{b+M-pzN-b*@Ykczfg~4RD zH;_!-maFIKYb0iYK+}G664XPVdowp%PSYreYAc$q}{;^i(ur@ z$-pi^H9OzT5@VCSPu8-{-32xx$>2+J(JWcij99mQh)E9&X9O##dy61Famtj_1B)@h;7GNB{g(&f?B=Gf?aC*YG$&T^65B z@D73>znL|Cp_sx+@lJi*^n+Y^V+E9h+6iYj4LLXsQk0mvt4QPdU-R`%0 z*6=a+V9%4Rf!SAL>q*nR@D)fU=xAjrGz=lf3BWZY{30&No43A&e$nNaaawzvUCJ^O z%WAp#eQ>tatUE6I`@^BxagOYG_c)FxgU48VB#O_S(X%eeg#_v?iY0c_EnMfWT=Q)sl%OKb z$@Gsc!B#3QOE==gdE{W`mvLn&-oT*=aT`B;2e*qSgFAH2+qJKfy&hRN0j5S0>cTMo zpmj{Jd13d$IlClF=0$HR~ex(T^X0jq1b4Z!uyz zO9(4RCQrDIGQJ{S$_!`T`g)0n69;5|E?yj|{?}-Yda=BdfTpPDrz}_!JKsIJ*w3dj z`vGd7d>_qre(SPMS5YW7SYqd2K3fW|F*Iyjp22!B;?J=@7(Suza9qn_Tgl6h&@29T zHB`Q=Ba^-fHOORoO;5}FZbAN84H;JO`=Nc)L0eO4dVpAdsh|jCqLoQD&~f35-R_3u1Q9jl~$R`(8Y}uvU=!mSufFNw$`F$Ewd^Ck#m?i=qughasf>gXs|;uaDce0P?Pon&t_u~odLl#`f>-;Qx%7!#-v_ZV(kR6V~%P7 zC{tM=^fV4^8A0e*a(wS(v>|^&5=D%?Lw8d(9(b1FQ2SCJTSYhnf9 ze|HTO!{graBn8=P<;b*rIh$j%rqrC(?>dHC%~EaZ z&h$Yx@H*>=w0%7wSJwoVxL0?06$ENv-4YLgH2X2Yjg_qBZeBQA45b?WaU)}OiOJrS z-s5{-(D<%jgG)GL2RAxZNPwbQBDAhmHwJ5y{+#0p2y;WNel&J{VZ;yj$UH?yx`~Z` z1pntPY^Q2sn6vJKvzX&T7oki_0#&nhw-}H9!be5|%Ia$-=&AomnZ|4Z>_5(?zuo_b z<{QI08yhe#kW(10*$46(ya%)?Vkp1`VOFbjnA4zyMm-R86BWx(kUy@u{u$_%K)8k1 zINsTsOmBQRvgv+aMk-Upd#%EkgALQbVf{5&Pf}Y~m+P9KK6RQ&AE7c%rHyY1Cx?b2 zkBIu>fVtY4mPxdHi=a9z>zKbZ@EcK-*5p&T;RYAipFXO_|7=>z&I;;OL$n>&-I>{G zR+>^c*B9()xAS3*@M)F$H4bEd=ACL~7PD?o|Cuh?DdE_z%fatUW3q#FXJtSc4@&9< zj3NfkJ^APJnlD@+J`Uu)%|OTnz0vjYm-W~xPrz9=G|*Y8;(&Y^3(q?~Z#{mCKM;Ov zdVwZR8%U)?>l6dOjT1IX258G6z8M={9rO@~+M1<<0>-wN59#e*o){XD)N*n$gMV$s6Y~XBXUOI}NBtwbLBu}pWkP`LRce;kZ z2U=tyhB2G;xZP<<_wfQ3i9oR(ewsCZ)ntalCp z=;ia29SLT?r8;Wm4-U(#@v3RVAha+e_|-QzbgU@U8`%MbPmUaJ8E|2n85I4K{Mo+! z`o5)O^o{k5R!N_{-J*(l($SBelv*EjE5{Q|;Vc_B;2lu1Duo)m?&)5*I;?{#n6Im9kCak3b^d`a)Qgxy>=X% zte)unB|jCHpRzj5HkDB-*L3o?syUv*n!Ut5_DU zi5o-gS>uJ$^5&eop?N+d`l)JPyfT4JsqQQWN}yz1|A`;sY}_onMNG4j$X+4x86cd) z|IQVRxZnL>jHlHmD+3bv#$d^-yoxyzWXde%j!iG(0^v#zO|r=ovc2`0qkwiIj5+oK zV-_HotryB$Tlj5Ga__??NdG>-JhX6~1j?aT;1)(@lIz-LgW*i<6GAT0xvMVQ1oMbm zXX}!XGo4Ta-H#Uj2Ho!wdi;@w1e_692Z$b|N6&m&N2iW?R*VCANRg>iC4>C?q|~;(nJ|m(`R!f=9LK%@C0!(4-|Qo8GA-wtll#BM7* zuX$#{t(qV1`^-XHkm0hpFJ|G(!ipXh&2?*eQIZ1X3-gxh`asQx{Yu_@tyl~rj|}k; zIC{59$kw{}JJH2>ZgGj3mLb=D@~Zb0H3kJ@q4FQ-`)|+eWIhF3lwC-!>$gzn7qL%7 z*BH0dO)I!ertITgz2R>i+e4UGR9#jH4iGCcsZE`{f zBj0g)0F(;}hKb4(y1HGzbv%t``mce&BU)VRw&LaIQ$M@`t>iGJb&g}Gvd;Q6|1wGkd^T&^0Ztn zh0re!eY3UM14{S}5$9L85k*k@xD`+?TW+9_lHlFiTtg$#LW4@`^`%{(G)}mWk+)Ge zH4yX{*ljela=aXq6KvV48F!990a0g@yRx?y_8Qpq#a$9OAfi$A=NGVicF>aB2D=>` z5RBxtTz03yDefj_ZCIgxByNzITuXdAyCY{%ulFul;MZ|=?X{(g`eS;?#9PzCOnfb3 z4e^7>n;O4!c~hYR@$+7)fb_|!Cb*T$96V{B*XX8OU2T#Q+0!gQ<54`zfh%3dLJ3Q+fIjQ{*>V>9E(w}Yp{~Lft(*^zDZ3ui=@;62hM7Mv z{499#Pw2E=aOFKI%Et4bDZ*gpQ(#mEyp#cG`duG@q9!A6vo<-hJ+LX*c*!MPHKk4;j?ADB4Kvv5i0KJ|5 zdrfL0_LU(O21}kY7NH%E=)-GcNVBmIkdYQRf>(LUVU*7b|GuC&%R zHsP~Tu)r3=xtpV@J@=+OZwHOBTE8uHi^Cuj?}^AbaXzt7Ni|zFMCRsuLlz(RD!%{n z1CHy5K}`lLK1n9*G0fB^pi7~{FJs8tBnv$KAAenVo$U3-IB>W^#zM5mxqG#l&0gw< zXHA@T$0;(m)HZf~P|4&jkI7v-zjwK7@-P4?HlpNcjtlDPmjjwxihkm(J;W@L~F7#y~xG=gg8?$J5u&K!ghvA z1|Do=3*Vw9Z+Bl90Gf*)GFO?Dtw`rri(tO!hL(6p;?8;6LBV72DA z?v&Rwl72L~f_!h&l4G-ZMdi%6sDE(gPpci@Rs(CM206r7S15=V~`?+wdns#bQ zs#DZuh8AC?gM%M`^`A~(+gJK?vG)g+L1w$z(KkNC^N_%(KR#rK<7@U+=3oC*2YF5w z=6sKcm;T*VvFqNnkTkRLz3Kqh*_H_+??UL*BZJJpFYH-UHTY-6EzgIjsH69O{M%&z z=HuD=KX6s%>EpX++QvOACrx*qG$sV0fm?#r_&b=xIb_6a+Ir9+PT$>W9~HEW%7)vO zjuMCB?-OUbjE=Ko4>||iG%B#=OnaWF_eU!d@d2j%L-XrhdNc8S&kycLY{~Q6w$0wi zS2B={hgZb3l=apNxJ|4?ev97VdZ46gCMtmm0GbP!shBOpTN3qu$zAoUFrF2eQQ8uK zU&OU2?3&t9&pMfafO{qx4V8N$ft|OtoYjexpCUt#b9@J*#J;5NK;XygG zT?l?_fG0jT6x!I3*8ZL;mc$_i6_s!w zj~XCzjmTk41=k9$@e^`RZSql`m=0NY=)OBhSIAMdI(2yJ*F%dPRym-KsNz61Ck2(0l%v^1OhjUoe$Uoxg1hgQIP9fvbMFR z*XQ2J{!jsAP1CWv6`ktbovB#D0<;#(t?$74+nwxNqAx!TgRhvQF0>c0c;otk%SY_B)?4=138A5qd0D3IH_ z@Ns|6idsbg)qGxdF}iOF2>Pv=8kh?P9s{W4U(M;ak(gh4#bGXUz(4<+$rc$Jd)%HFZ|2Z@{=#KGvjL?9 zGqn)asuW?^PHTll7P3QfK*_L{25FQ?j3Y)2m@;l63Awo#+kn}YuR zhP#n0|FUV8>+0jZ*Ro3OdJmGKzK1}MzB#KgHT_4^^m1S^==o0<>3nl5zTcb+H#;#J z`D@yIc|-KIVV(a+(|2RFMBdAFmeI$98oJl*uCVrjLJ_Y&U5|9`7Qo0`NJzPro&+?3 z>w@b|DO+}Y1?asj+eb{=`|K1k>v%LU8J&G*5e(wig}nyCg*(A$^TkwUvMF)pQ*r$u zt)Kauy{aD)VQ=?d+l%q$=6oPb!*-4|R%@Y44kytvS-^I8WhL$gKbZ zZb$Fn-TGW^oThY%-7F!G7D>iU5dXybV{ZeJ2NVoEt=NyPEy?|EWbOfJ)yR_5v=HCx z=TZg=LTf;EqvMwPV11?DkYAv=-7|0Q)2(x^2c+t1JQ(LHGbSm(BF|tYUw6@J#U}2+ zq@&SO8`YRj=Com8Ah-~vv`XpCn<;f<9RgsFk?7@9ZHII8;kAAa*=layUCg`;pDjjB zUyv_4qAtW6yCfbgAR@*$zE@J&S!%Dp3cqC48alS6Lqnp;X5p!G{~C-M2AdVW3QsG; z?FW{#OD=l%IY`T*4yQJ|Q$qKyCWKd?)9mwRayNfDxATkAZ}@_oDAW?n!=^YOAaoh8 zSyp=`0P;3LHn$4;u>f`XZOg0D^oF}UpUXUPUc`!I2$9)Wno04@P|{x6v3Ne{Cz*}a z4|EbXLMMhnGz(h;pTe8c3@U*%HZUB(6a*+rj#=IoWWf$5)0Edyx|?sh>;~y5jnz4+ zzMmQu^=Oi#su^XBMZrABW{o?tzT^F^MS9c<&zZkoIgg**vS*3|rH&{H7;ZV-xD;?y zXLesz<-hX_u?2TrA_fwEO9pK5T)PJ?J`GU{qxe91J5t~-r9ra(?Y=O~UPZg6$c)RAy& znVqfrz<4FILCrn7`31tuz*H;#bk$fqrDpJ8&$lg&wobz!<{G`JvQjO?>Uy=aV#8Im}D_}oerpS&WP z(o46(`*8CBZorlvQ{?q*m!S_9$1!#N$=pq!7vXfIz3S=Qb%Ccy{hq^?l9&*7 zbxC2q*~-8+1g^{_fL5;4p-ot^UgxeZx0d1T?D(~weNo9HbynvE{-GJhtU=MW@F({=tQTRR)x1 zAhIBPrQg0f3Y*XU4Ovau%lXpt~fE4> z*bl_#_aaxYa5eQYw?_`miV8vpkDF}gO^f_|9=f7F^UPeQ7af126@!RmaveKr2>*LD zOQD%p>grlePFpO6$*=7Dyd)U4+TFo`y8dAKS5l- zqWK4y`?!hA%Nqt~FH`BqY3GP;5=;wDG0SavoT-f_U0~c<`h_az!2!2NCHhfO$32?n zBh>HU9yz)eot*O0J6`eJ&C<>(!!t!pX5~r`zB=EGSLgVKjN4UI7D4Gheu>0s<>w7d z`99-h5W%8-qT3_Kj>?;S8-Pw3sdA>S8Fs`{=glcj7oqvOIRX{i(O zopYHc)v+)T{cYR+J;e}4`;KvL>+<1tN1$eLji0Q{ziz<+wjW$H|K57slbmUqnH5%x zG*qttA5U)q)%5@UkJ}(92qGPdbV@fU!j$gr&e4npQ4tXa(p`=Q>6DaaqY;S_3XBdJ z5+nalKkx7Fzq7-6ZLsaI^St*y?&I;e&!>_5gNE()uZI28kWhyDCg*t_LW5Mpz2%$p z5nBS6A^DPWpXO^O;H%@6oe0f1;a6Jvkzqr&GHI4`>KDq*4k8BLr->t`uiq~RV?3uG zq^det;<=n%25Y>>yu#MqR3ve&zT;Q;vB^l2Xik4Hy08MDbMS$kvoVJ#{bKlmQ2C?K zV;;1PL)*`#qp$+XvuwuR-kHh`=rsI>nMy>d1E28amF)o4*|$amt5~llYzhz04_dL^ zN|ROO&F@1$ADhw1@VeI@ac0vtk^e@!kTt%b{n~)$31W8_BL9*+0CQ_m~ z+fUj*Xw;(ZZivcGuC)>&n6qu3Yju1ALv(zFF8Qy180x3|FdF(JK!K-77S;;V*la)5 zeO)?~y(;DUsywDft>9neNqzj))K|j#h3oUj>VPtFM3ilyx=ra^UpM2<^R`~yrd~4! z@9Scwl$JCOxrctG!?p&jmlEXAMGje4uGuylbLsX3X%&jX1t${d(3793RN~J5iLygX z>=mb-rRO9+X3Ju91Y9+v(kXES1k4!xZG!NyJ4`!nIemFE)a4D6(Z9HR zSC3*s#Pj!o^0F#D>XqGlBj-BUHjE}=#0Wt;5w(i9v`Tk95TUOsH>bczzD9F<_(7p9 z*IyGVt`5}V$QXYCZybV58yCBS%@FE`IeoUGzFmH|MEO~ojYn|1n3u0v>Og)z2-zyvat&NyTF|=*QkH5xi_znd5voZVOPl}S}$8Mh*!>#Px zttZ(93C{g0ACm! zN;YjfIrF&Byjf?B`Ip7aqSs=@J@P-UJ^T_Y{%3dt%dOTq>96G77N49oK4m^H*P~x# zOA4iBxL*PywuPCaY8vK;81wq{{9^6;{q(_PT7@A@njaL%Nx2_XpKzQ{8De z6G!e%3`li-EVZJ!E&U|5F#YR`)5N|$<_Rd~i6Wm`a>itUCazlKwob3&#$^=i zXCvrpITQO5bGwuW0_L43ad8RK!P<(fGW^y@&hg>$Q5OjbG|VrBcr+v>IQT$e zw%$fasF=pxW{qF}LKR|6jk3-b z8MxVIgIwMm{e2qh;_~qOasA7WTU1n3>`^X{Y-z%hHlm`U%)SdHoeoM^noGZuW2UZ0 z(PIv(@l9F#FJ2>dP6JHV-DLHD9*R;(x;5X!euq-{fyV2F_#I}Kodvo z5mb|Gv`O}<0@@(~w-h5tfMwOpQ2*-Ur_KrcRHb6PVaO>LD6LdEPwC_5;y! zlx=$eVucU+N_o5V? z??gM0oxH)Xa=l-|Rd4dIOe*?0-{B#n*lw*yopmZQc4ToL7a39C9=0bVrPu>CwyCI_ z)cyE|b9@lxBHJJRHVC`d$#SU6Zi7iVA^EeP_S==6YS3hmJD|FmcW=(Gglcq*?~#_Nn!A9!{j6XM}@?Ay`rZ>{}fcdAu! zKfbDy5@EK-QMD|osNti8jp?x6CZQz*C@AfRzL&VVJZ`fkc(^nY2ww^Rd zs&M}>b}#SNPg*hEH7C4;AHhd&4ur!OVdXB`!Hmc(3UNWrgWL_;`JBM4noVc2efM|R zeXJ1q4A00%P9bs@hLI^>$dO$u))4t5o0n+!aiXi!z|jr&>F6))OTA516%-a1i}G{P zGwc^1(f+U2{|r}l#(Zd++KoS28t=ZgNGB6RxAgP2Z^g%hc5P{z6$U|*equCFFaWkg znHm(=o`!}yCm*t}9j7CBco^2DbC|sU7o?Ehis;&B5{xv_VBvw=BG&~J^L9d6APx5- z(SfnIM_DATov@@#+jJ=qzGg-(9*Bk+oZHS-_N)~uV?}}`?BVB37)gG| zksPLqJ;mg9sk{(s3Z20-PTgE4!0=7jm*dmz*3Vm)flPrZhRw$GJhEV(IU>Ng=PNHV zLkC|g(gn;p9KRkgCrx(z)+(_>Umkb3R|!g_m6y)CTlh}3GHzf?rSNN?kOi}QwW%Ig zL+x2&4iY2>4~H{HgCk+IO)6Ftd`?_YGl!S{+!SF46h@4aw{M+?#YfG6h}Ye?TEx?F z=v&)+$6-f3uQ}^G^I~`sd{IyA1Fq1?QojcKPbMt{pT2d}%1|+}dPOz#8sU&9T~q%E zwN1Tr8lZr4R-E6XorE#O+4_{U+I_OAR|vq3{-#9CDAXuF>qr2nRBTEkN-L7b#*gd~ z@$JODwwNmZ$+cGi6ZZe5Y#LD%&|U4p#7-Rar$G2T6 zm*_cH9nd!6WeqR=Bn`M&C-z$eS@TX8@aCRYROr$l&q^r^XSQ^Cc{rKzf^X6hvmewP zUJUX4Ha4ftRb%MaVwO>J?F!mlrb(|h(4P8S#lu;KK|3PhRi5P00F0r=BukTivBpF< z^4;H{+^%D2ve43|$ydprY`pBP88_<(q>iZFvE}t9^fdvZ;D~zMll%mw+^(B2VmlfY z`{PP^KLyw>M{~Fuk9wm-pCYqytHeeskpQ&GcDURXO zMLy{xgWLM+D-6S9P&k37UcN;539oV_Z9jfAQ~oN!;a%p@f&U9SKJ1Ut5KI$MG)tbA zQjYV^)}?=_wIf+7IczUc!CG&^s;Zt(sx4-)IzmKeTR2>IARB(rNg&f;63jD&yoE^R z?mWrW&ql&C+4@+x^UAd^uM?}N38l%`qvJ%-!#P;obA1P@hTN0b9S`)gsU>2q9X#Z+ z*(VzS*Mo~CSKkvwLX&&yQHx%KOJf$N{H$Jvy?-sxHt)bdS(&am5*m zNG)FTJE(#H%Wgne%coO(UYQuPP*o0*HoxooCTAtGAp`Q))1@yhd`0!vjlpbQC+hmY z!^eB)*Dk6ee$Xk*U(g>SP{RG z;=N|MQ z_@{4^)bQ@!X zT%-1DBuS=e^PKGL7ITVR7UFRa^j?1kK%J=BvcS!QRGP%Nz!{La4XWoysaI-1Hn&e= zSg@XKvdA&Iq|fVGw+`m&uV3r^zxG_!d~&8R@bz84voi4jfZZ{g5i5<>@jx%t*(n$KC_m)nyJ(=&uW1i!gpw<@rZEgB=X!2Sf@5qXiWc=y&T*0|q zcLp=&Qv-YUKyKGcWhcY{R{eKJo#zKPQf;pKf!%a{(yM5?n)Jl%mHB9)v<4zC)*E|Q zA4Fc8nK^H5-Gz9bJ{M`19E9dgg^ZQdJgqb1HT3TMAzCnBKRWm!lkvv3aOv=|O?tCD z8=US#0QGHQju?hQtV;+P!x|*lfK-eg0SVoU$?jWw%dtnyImZbVUy=({Jf)DZvRd1H zYncjqT7VtfcxB#1o{2&ff0pY?J0&a*_T{rrXWeqH*_`7|ZK%no#TLE;JCrhC*67=& z>)2I~opYHjhpe=@fd>*|3l9?YGuyN4kZapTkv0FCW1biV-5qg^K()rNTTN;v_RTF% zHZ7~i0`;(pYK~;SHDhI3^doH9HF?|aHz^(NdsygOWMajHINT-O1poN9^@<|=T=gwl zSK1*S#;Syzb4FYOZ)q6_ONPcLk!l{cQ=Hkvw+QX^y(OuRJ!Qiqy9j7BFSpDpwyI*SQkW4Ku8- zirNo+y^tv-ukPRdeN{j7PSvh(yRnqXhRF`MEYw-c82wF!5qMQz zwFBDNFrsDnYHIy4A_C%>nvw2c=Q^>|95N%8+m%t-*`S4Mye45CnAJZ;x_{{4zJCX~ z26ivR4QLDVbR3qF^MlR$aGiD_25EJDAD>+}{14|^#EaSf*OUeil_}bMs~4DDU!gd^ z#(+=P_Sr+cdn-uP>!k90DIg4cvSpe22nt=WYTmwHfaD$4W2>-9{TJFlE}zV0`pigi zi&b(GBUV=D>(k2wo?_&77;NXM3gW3CHL`wxBfAcIe_X1Hr19RK%**zfWeoZf&NbHyL#DFp))xm2?dFM6MDHW?<0Jb|a0dRI$FsFi z(uG&mU}2<9($QhuO=&GI0hGNosW_Jw{nR6r!p4%V-_nK4v|4^}es+_U0Dth|won>m zQ_9k3y;9(iJ}%b1=ztXge)fVx;n1A z?K=4~h>wB(wzH}ErQhGyJ9xXlKf}2Ok}qu}u@kC|#6PO3S4Z@@zfzIx%oTW2`;b-(o-beY+-rAnOy$^DC3 zQMPZ-TOocc34PQKd#&R?FP1t?5R#5CwWYL7XRoD{+oZ3y$uU*PT?JDopFvgOG=+lr z#ClZ2Cye!_A{uk+m+Z#KyXpn2@oa@^)Ak)wwit$Ksar@Z@PAsx84y+~_?0DJ;H?wT z4L?gmuh5IA(@(($m!33-t1M+nnH>o^dk(_hKiaJfi1YYHm)m8V#`Du1A|T;)qG-nZ z4r!N5n>?L*4s)3J*Ij0|uzRiF<5d29B$79riqKk9wObz*>-Ii;zvBVUp=__u?7RBG z7im^|H%6u*fG7p;j~R5UpgksttBAj%BH8K8Urgup3(v?Y>C@4-@u}+TO(&_zg38wzBw-PJ-<2A`?MYf?h>-$?YmpdpREFJ z{h@&FkxW{qeo64ZQwd*Pc+zHM^FNZ+nwCD*O8Du&+wxQgdFe25IL;de_ys%4%yZ3< zNTGhMxKN=X`%BOj$s|NgKPr}-*?=^NDl@Ea*?br~Uq10WH*?sEjGOo-OAiUMG!Kpw zYnH`Hj{hvYtmm4}J(cRR?-e45*g6EP>{F(*Lr|wuA;3-HlCt`H)e$i`WO^l>JuJ=SLSSz@9bBSst5NdRNXv>^!W!h5 zV5yb|+EfcqYKQ?P5t=ZO~^;87LY33I#HEyBJQZy`Xqm*a8U2=dCqb(`2B#jr!01NjS0V%;RZrUr^6I~9 zd7KEXk6qUGgXYequf6eJ^2oFnq=?`YCiU6n#nv%}9LWx(z{`NS=v!W`yQgG1?Ye3~ zA>|NYgaD}@tFvbHA~6v08NV%7sQ=+oOW*?a3bzKkd(CC6^;U1WGTL64Ek+$@TcoD@c=vfP#+a@+0^VO_!Gm5Ft=nJV2zyqGTnc1^E@_>Hzire=edM+ZP z3@2V`bjy*TLZ>u@KMKxj&%Ta{btS`381V&sxqhx87wgu@eL5bRbz5SUaObosnxPoy z)7hIfyRmM&Jyqjg7IQY?TS_#xRCbW1%8#6{7?|@4bxr%^#KsHTI!fPB<9KaN?=^8Y2==l zK!L_DV??o$x2iMQwDWy_K<(5*LTjQ{?+s*aYSE{E73b7E3z+XXXVN17^}TIDZZOk9 zu;JEZ-jBa8anud@^d*C_?)q~uXIttamQtS1<3LdTk_xeAA_H9wG4CHGv1g;5lbt#V zJQ12oXa8Wk!4XI*DZ-s4g>nXz4wC{J!dCjG!f7NP!BLf)scdJ|R1Si#?hmfnP_@TG z1iomPXX~uJMucJg+=cTH;x)`u&xOiV|2(hcy3qv+uM@d z**&b3L9f4)6OlouW?drfn^kZv=95%VK|8$3?yvxuI;OTL;bZ;UEge|oYmr%d)yQv# zv-8kNvpTl3*?}r0oS^lU4|{fU*>~&Hgvz&*Y_<4R`ySUG=H2s>402q5#==pBc`yZO zc54=>Yv(oazU+g=+X!=H$A`*1eDe1;B9(^Ae&9^%h2<+)KQViD9{afLgg4rCa)ymL zibL^i@BeuL7D*CGMJjG2P4ln{5e$A(biU@C#)HmYaVpc02J#Cae6uvALl}=soaFw_ zO|hBFGebCHH1%_Bn_GnRJCu+J+hzb>y}}-4Rc&&`YxW}GEDX9GB?1H|er>%5xm}OJ1;5VEOgchh1Dd*WLOErF-S9XqdJgmZJ@aF5ar%xFFwxK))nnR5aH7%<)uk#i; z^VXJ%WEIWwfMy-LvN7e4-_)zO?_ee#_uVNS9?^t4t4sG(b^-=y4TD$NcP*?)j*o+6 z#c7a;4g_)Z=o86q@81|FPSuk#V?aHAV9#rGLoCWu!%_~8tc8vyQObW zFt?T1*HwHz4=`=Z$2tkQmP|(G(&Zh|7m4xKssCegqM~jNC{o$|Ct*fEoAknduk6Ho z87@OWr^^vT3>#GBx4q&i@^DyZ%8#;py@5_G(5lu*XPm$JKia0L4~FY}kYBr7Z?a3j z6nP?uz^NN4Q~)5VKG%4mx#aVStAUX{WG+78_w5tsl6!6dlt^im~+9;I`52_y4d&i-4=HE04YpT~*MLt|~Z05#9{41mf`ZL5& z`Au)~(!d9h##hMc^wTmr3vsF^%z%lX&zsxV$n7F24*2wxNK@QDdB>w=Oc}oSv_W6>{d6HTnH5uW0@#E{+F~zegI}&c=3XfGW+pG+ApPI( z>pl8`CP`Jy-*=71IeBvFujITJDSOOW-h20G+kqve6;mO+sN3Y;gO*>h@zvd-3H;G0 zs)~620lqcLp^-=%MiQTjyCqRXoMkt8ROj)`m_jPF=&$s-YF^5jya{1Tx@#|9L!oeW zP1TX6kM^1Du$X;P|Ga`$%WYAaGPkzvtK#P`lhW-4L6J(@RQq;sPxM!d*S$AbQ2`xD zK*o7%H_RYTT&DNFdqxO{P2vO>N76=(iETJhO&3AEb$7uAKApH`(8mVAuol!o*OqdS z;cq#J6&zOMF^8Zt6q(#z6SsALAEl%$fY-pj(CadDh^rejF#{JZpT!vLVhKG!Q*jD(8JEH(})XnylAuNC^fo`jwJziM|T#z^z_ zzo=QH2TYh`exNkdmu*2rs*5|xarX!z!$4FZLVu(6e$g>tvDnb#m@o72`} zRiLub2uAfH%lo4A4tk9JG9HV;`83q!XIx-BbUcuE*lEry%cFaq?WBZNyqqylqgJPL zkOw{d;5rsNyHH;xb7xwgYeL<0X_xksD1~=8)>qKmcq0Fe)mS|^Iy@Xp`n_IH`fBlk zcm(CNs(2yH$cSNr5qhxqQ+R+45dizh~8gK1Cgs!pO<8HfT(STTKqV*sGVnx`z zzlWl!rbb*0wb`YZx=G}6fo1BXrvFi^#qDi+UCtN~8SD_x8d}5zb2hAQzKh7N$E+*LE;ZogcaoYyRTP5aOXDa7y^&AV=~R>_Cx;<7xmBt(v^zh4QOX)-qi}d zI@%ByTVtVAVJ@of-c{&5*dG0zQ5n|=rq#o+6hf1Z)?j6R7(AK;Fd%#=idIYjk z!XIjjk^1)UD#-nw$?dv@FnYh}dl|PK4*g&FToK16@(=%~^F2EFJ^H)LBA*%Wu>I6O z)z&L+@$_=^cg5S=fg`YZ<0&2F+A;uzKH5v@`bcgn9Un9gr`($sMz0TKa_9psE6b@J zj71n#F=-#4QJMH+tn?fkN@)ITFk{CJ$+QaQ&b8leT9t29#*cl|%?L`I>+i&u%~s?o zGVwxDQqV<;W)1Ur9lH++WNj0$8Rz>q{yAJYz&6P2{Cfxk z7M!)gRRSbbX{3>jJ@b6zMdBzmQ|;y)Aex&r%o)VW8P;u$5ucs6zz3n39v)4^$pkd- zREwG+y6lq_dbgo3t@ifRNpKc^66FwEPMBU zAnKzYI;d{pPm6ewxTY241p4DP;WBXuE`m*hy~slw@g`PS)dlrkYS{iLRW&MsyG_lw ze3ZR_rOTH;Iu<>2YR*kd3Flt*ay<_Uo)TU~7sBZd&*GKF*Ml(j`&4 z&vNIiJJ&aRhedU^ad1Bc657X91EO7i)dyQ&l#uXJx>(~E6f}*T*{`4??$@ul%#^Af zT>;q)XvRVz0#xeJjH#NhCBOArR2Xp z=n#qxfD>+=T3Ef@-rgR(%PEN`SsHjLsQ)=ZaUmy=g>onYF016Qcvmw^M9TG@^|W+s z#eT{THu?M8JTr$`)OBJa_seqB6s4UYYnrMmUz$i*qFf8S&sBBZ?cSed?Es+Km*RbE zGQt`+7WnO~17L_Vm{qo=q{I9(K|Dw3%z_{}D8 zS#nO4^%w+s;J_B#(_@M~o1))c_eT%TBCO^MX{ZqCjF1vD!-gk3XUh?X@ZWAcss4iqB5uKliuwgP@cUjMf;q6r1_3$tz8RzLHItZg;M8B>WHi;NC= zU?y0JQ^@hh8RE}-(U)ZQ`5C`RR(Mas9#Ti&l`Gh4=sOKu)0@dPTOg|=n9 zPN5zy5SEi}0I3l*v(jiw`dE#!Y1WH85QYr}bL)3_48#s~PXqN73NbvCOMn-GK5*HM zGO?oWV`UOnK;y_wBe?W|)8Ffz&cpT)Ig@RgRe$BR;R1OyN!&pbYo>vdc!YEET0);Y zlvml>^&7LhptY-2~0 zpQ`z~c3w75r)7m0s@tUh4M-S^A}-n14X!??clu0M%>Z0I<0WB|+5SOgA7iT?1eD=N z?t68W9JFAKXlq^`3P}YeSkDT_1+1)^cyRrQj{as?pawv;05u{I809h{KvCS!eD*AR zl5zA>?r1FtFg}b+ZSuQYIUCe~Hsv*V=iEOv%^oDf?d6*}Ch5}bT({XWY~KrE7GBv? zd%qYj7ezP0_UEXmn>cYKA=HKCdJM+tT+r+(UdxlRKZIzTuh=F~Y8g4)KaEA*tT*sJ zq8!RA>Q==tZ)La$0#}YONi1MufcNJE?bIEepX}KY8Wf44F5sdcc$enhc|-xGC*x6~ zFLT*vyAZN|aSSUn+$z?k6}w+14t^yH65b#GI8oa@3KD*puS>&bL`w2au#LPg(R4}R zc_4fqeuEV>sMRJ(vpizvB_HcTBu9rpuumY>_&r?p>mJyDs+y1u_W`k07MP_&kNztD zFsk4|qA$PMvfs?ef!uRr7QY5Q0om}O;^Rd9qM)miFlSBrpn6memQOdcl!DB*#L zVA}m9?dXU#zv|svh%pVl$p2?+4S)WBw$^h%@vYyKYjc1QvzPUX6)0($(HBw;>AM%J z3ZxN-KN2=N)WeY7p0>P?E&5oQO}lPeqqBxyQoMblzV7Cr|C@KXu?RN`5-;zaZ=mx1 zlG3g+f#qqM7Prlcl@mVtn?O!M;kGR$E8&m$6i zk;oKWR#Ae-pVbr#LE^~ARL52pX1qW|1V|DX1C$X4X%$spRLt7|SQ((U2Fy{SMOctv z*f<8c)@2dK2fyKi-o5^I&$d)GeC)k$CNMfmQ|tP&g@i0sUc9&rCdWAaWzTkp-=KpW z&86uetY4sm18~{u;gAZ${sH)nHf($p8VyZu?a;9Z zBSJK3MqjWvRWhd^DaL-nA|%Fe9lMM%%F^LGB)LbR z`sRzP)}N)t^alq^6=4rWlU4izTl80T z(HIySBSlwpqPqk+Y#f3W&w^e^{1VX23~xEENVRc#4tAo_I$Q_E^+CIz=VlsZt}KrK zFw~>?2lC+~b%4b++M#zzyqse}1#%Z*g=TgqbGuRt;%$&l?wAE0)IW&sQZ40GRJb5x z3IIA$oJ?vg9~m#@P!0E*1}kr^jihah|Iq;Dt`>d3@`xLPibOkoi3_0eZmDa60(NHg z0ivX$9NzH48l|mzB@^i_ANH8ZV&@4j9_SMRb&Uiyday_N2R82Y1aTT8CXQt*iBT&<4y2(JarqV!rwOmK9&(KCK@9 z7&H&~nudD#r@RI&c}Ek!*)ik?iiaAV`N!|!OQ28BqvpHbha|3yjgjr~Y?f`oc zmMsjN$~+{FsauIQrPS@e9vby(`_~}N&}o7jO*{G8{OV)(kLAhdGt(Mk5?-RxLU-KB zpb_0(aV--%px$>u*_7b zamEmX{IQwRV~cUOGIJfzPC3x*^Nq*qFVxSgAeZaww^y59Bnm9=i7iF77F19e%@QT_ z)zQ_g1O7-h{1CbP1dWNOtI@Y^Ru)VXv&hGU?xo9y0}vhVEHcn~n=M6^rOxK`hF3l2 z=1n~7;oe)w<%e`Nq*bt1EO5eC^37s$P%G&``@f~*@mW-!LSf_U2pI}AwZ@Ocjk$?$o+k7)fVcU4 zZziRkxWwyqyGxx(xe6VM_*0`aZNn^25Old2&-V+|l#3i>QJK4RE_X}LYb%mN9Gsff z{Ctti0Jke6aBAp$y;;ZA;ayi?YsD}7X9^&4`InZ6UvXwX)S7Z>&LIy|jr^4aBB_rp zCU7>)x|udH(L<8!h<>FF+O3{lid;^#q*@x;@-^%~JY@O84SBi#rv*E$&Q*hkz3`(A zN%`Vu_(LhOwmD&>rnrrcmDwYgeY{t8#~l(manylX+UUa6j#|u?2J(JVA|+-W-o3nk z>9)O+gB&Xk&Y%>}NTE(ggl{bWTpVppq_#cV@HAIJ`vxt-{1kD4EJge?_Pccf)2|Nj zG8PphYC)+2zEez&E-4?%>WdP!t>{x+k>YtF8ROT6qcXgZ>y2 zwirC;2F&;0vH;S4Y}`55s>=A-$QJ{6nkQ2~@qfwAml`X=V~ zq+DR>Juq3K`+f+J+gNCy`Iimr;`y#SGe2)l4ESm4`ilZ(F@!hCs2i>CHh*3DE}d}y zagP4;sIb|H;^VLb*|j%Np*1nQ`OB9*9!ohU*2fRnVt{%6&$IHnn7@Zu$v+#>2Irnt z%Adsx);>JC%&ka%JUJW#O|BqAaTCqP+|uzfYL|E!K0KQ1ma-=j>8w}JJ2R|VE;`ir zmctX>%P8GO^I>|5WR&r-tGaaLPS#C1%zwS$B3^X=hsXcZ?1{r_-Hw?_grz%?HKDHKFkzXL4HuO&S zsDQhDovD0=3L-EeD8Jt9hErVXhnC0Rv_%R_to$AnoEXR-hk&Y5FyHlPiEB4rT55U< zl?hXetT}R9*Q3v-mc7?5+xvXrFQH%$+BJU`C_Y6(C>?XBAt?nicT7bP%ectNt|{8-iG=Y;LlC z@L_R4ogI4NWwc1zH|MK_(cfa2DkUsbjkqM@SHP#a=I$*9J1-Or#*v*_p}D>IRWeHq z%ruLt5|p&$Ny6@Xn!ysrxR450`JxWFz1O544LZPE_1k zIZ?f2#IESNAHiQW=o`pTWg7IrmpSo5h(ubi59}h5gfj-S17#1B6{J~;Jhb|_T(-6_ zaibR1V^P;!bfx2!?IOF}>aa~}!!>nF-{1zNk_9Ql)(d1!(JZJ|UtrO89J8w4P(Bql zkejZHIQcolINMupxDr6LJ%W$|BMf|L4AVTJSOAyY4Ae2ZmZ?4L6fRt|y=PV3yB3!E z-?gM!$H}ls(^6bjCO4YH4;^0FuIF?Sn3l8#Dn1U3$*_8A@BPa~-8AwU<=Wg48A_SB zq%8L66QoAq{Znn$fIQ_t6UB!~vo1=in?FV^9QA(}Ylo=Dxi6#{y2fKgpL*%rG)I^_ zCX8f^I=E*X^(@ZIhCjmkG{2!CM5xX3jDX&O{kJHrjHn>#>L3UC`j?sJqS~sW!OG+t zi9sLaOOku;D$>@+wfKF&(#8xM`8-n{32m@hT1`c4Y$Op}`er0TJN8y41x~%3P0rUY`$25&OvRz`Zt6^`&AK% zk$VqcyGRsu<|U?cAxa}AEKja#Hm>&L-ArMY-MSQ>AX=ef)CcoMDA{l##D<6p>y9#@ zcab9nKO>b+do3}qtmk8tveTf#Jv)tM9_?5*@Mrc(MbXC>W&meB*`3r^j&|642_o!+ z^O;rkj{fUt*Cf->n{(wrxdWYCO%H#z!$bXK_UzP|cYmXz?i~?2Pt=5mQH6I8p(#xQ^3>M)%cKtVj;&oxUjXp13XVzPc`@&;*dcl&?$3QL*!ZFBn5LIwNY z6E#PziedKS0(T1q)PUof<}F7%*^`63QHKE?DMW>c-;Q}+&ktL%72PT5mJ{ZtoawJ? zW8}Y@rhIu?$@R8*&?@hBnUB*TyI-UE)8gN97)9Cu8ya|{lpG{^Dt+`0^tc+0mP6;t z&A`4NPxY{%Z5~$4r_vC90YFPnJ`cLq`=csE(a(62kJEi)!Rfft5ZCe+b@noR1W)G@ zPxO&KBJk+?6rRp*O+ces?~XKkMaF`(pgdatwMi-Pi4hlm04LoqpDa{%8e%+462yX^ z&o+yeRnh|TWIKVs&%`1O_@d==yYSO2cWez$&q9}1M6k2>i_2jum+lb5teo+ zW2wm^Obw`wko8gCtt+Fd!M=Bnk)OYr;sT#yf-`Bvl@l^%ySz(z6irI2l#X)ix0>t) zL$O4qL*RAcnm2r+(l34q{jb0rVG&*f9r|Z7T%GjIeEd({?iHJ`7dAMY zYPlqL`mBSrQ!0TET}2)h&N<* zL5eObc_%_Z^D7>O*ho0i7kEeNJUZ0tfyL;3K^_$eAwu^3c zj0dXJ|D21-$5E$$J-xmRhMs^Y4QPa59v4gqio71)Bz3SVvXXk)JK#cANpqVVRUL^H zYO`r}uHWQJ47z?2ZhqZIF~aH%;TO{MGI3O*n*C%dJF(!Mui^lRX#J!0rL^RZf-$T? zsX!7Be*}zE^a;?u3xfhl+gB!Y&qh_u95Ywj?o~6H(TtM-hO>srOu{^*;vQWaDc9@M zEHL;S9%C~pri;_RiX173l2MKt8}PG;V!#->mQNV^yvyM(cU^Os|evAfbh=PKdFgOFm`O+^?Uxyt0^>mD;OROn4p|bG zL6hhkqHj@$^)u3DjGI~@_x@)$v+^iU>LdV;?W{_ZQ=0_>r_aC&`mMG}x7uaVLGVf_ zn0}PZQP0r(^gswOljW72!llE-@Ea06cbj!_VD>JulfWCZUxxK_(q6j#i^}PbJcu0;!pKn&?XVNQdD;xuJ1M@9Rkx=3Cc2Ru#e(_l~D!N+)7Z_@wD z&+&imvI9fgH1BvYxmoHfDDHHAuTh!66&Mj=5oOZ~G|eu3ug|Px!>0;8gkH6N3Rs1) ze)YS*w4wnaZVE{nqxDV+;;T<@w29|)*+M(H*JV*^iwS$vM$;|PU(G}tbR}tBzQnL& z+$**ZTI)GoW^GwE&zK{RID7byXQUJgcC-=k8M7w=Nam%FnU;byJM>vv^vqPtK-_=~ zq{AaJE8MA8*rEBg43z=C9WVg>p3T_vBwevaXnBPHb!Sqs+o4Qj{Ke$J3v(zqP>;mU zY64;)(q@4FFn((7L*h-^l&hpu`ke57=^cl&tY;F54dN1BDN=*S!}kGqvExyOO%YIz z-T`#N?2of^J8@fu=(0ur=xaUNGruR^WTRc;G>nvY&TKJ!;ANaw^#8~zE3#(wE6w^Q z1;4@jbZrY$D1S_q0$3i(LNQ-x(+Oq6sdBqSXG|Y|@t=Jmar~gE)dASth-ak+E-(Dl zF>mYnGVKLDKZwFcy=H?E%oGjr2VDdqi&N=b2etV1G}QqW|Ld0)HTe7fZ(%1+t27Q! z)BaQtlh{LDCt(&=Z=i9&-8C#zqf!t5?B~>_G)kV0k{!g#OU7tx{A9uoAJ-}I} zg2{5d_khy(CSeTPB`sv{_~+9cnIamr`!H6fF1<{B8x*gImnZaSmD8#L>TdEisN~-F zHd9;5Opj4v6pa~`ZsP>Zp!{4eYTkM>T(aOF!-fLG{LDKmz9HI6Ek)g&f?=rRk6J!q z*oTE!U?FQ6uqR)0dS48)V=7;{%5D`Qjz@gkYn71_;DGksq5k}dMc4TU=?$nr>H$kt zrtkH4-Td$!5s`X*<=xheLh&m2{X0=r59K{NxP;wXn6w)HuBPeynmbM_;{M$69P8hz znrK&RsB{+{pI6AF9*N1x&rkKcTGz_oOrw8ty?0tHd+oPH$>tBSLRFoH;SJZIkaiaL z;91^b!(o@5%?s5w#hAGBhN8|5_zfxXtDiae>$-92A9Sk~P9m0t+b*Z~shizv-fk9t z(5-wu(0xB+w@Z%a&$NQmGs@r^bw$m^sqoi9$%XTu@4O^Ol{}IA{GNyYSa~P;efyuH zQc_F9H$nrFN)M~-whUP!->8=MK4GSEAX`TU9uaX4J77MXFe zXVq^B5;e<@EI=H5)Uo;$H+Zj=iDFaXVWZM@)o5CxO{gRSEeAG9cuB~N z?hIBDTC?>S0;L3?4)_{mSPT1n#hRgS4;wvN+Q^$@>=N72n@&FuVdI#!v( zt%SA4T?YP{%WI_(U4L(68VSJ&U6m&flV_#S9OtWsbLGozYVsZQLEN4REAqeo`royg z^c4^b&Zyvjd}Fxexa!rd!Lb`I+c%=mGF-`K>opo2-_KS_7=@QhOOOP;V>;fc>aAGl zjcDP-<|Ae|F%zuQB+$2() zS5NMdaDj0QA7O%Z=qBa`I$y1Qqgh?Sg|O9qc-ZK$EuGaZK-#`pG6gwPqrS#7&veej zyDc|I>hDY*tVA^RwbRaqZwI1s+-|UYy;wmOqvZ}>njHOt6g_U~m-$nX zU2h1>YWrY|-uH%boqBD_U$VLBty_$F$(iMEf#1ICv{OHM&Abuy>)~meO-25ET^-@8 zz{%AFb=oZXga!r1MXIbKYK^rNcd9^BB zOXyThkAA7hZ*W4Z+e)j;pBgTd&@CSA=PW=0?OFyjQ2#9nJ7%4HjQ|kZn{hj|gc-Ud!KKtyw z?|trbpXa{Q*7~dij7ff*LT(h{;V^9Tv<8 zvzl<%Ie|)bycY`Smx?ytGY?Iv+~;?|9?M6}V9PrYWKnL#Yv#c_qS{@*49{>&x%?TZ4+m8tI9lc$H&Pdcs??+F|BWd1yMi z7G^c(J4GlB@yFzbRV$>LE&YokZ7xE>gV4#QMpRsGxpkH4Dv$!#Qs>oKikO_-c>|8Rk4}ui$ zWEQWVdxla^+Jm^V+iU_#d7baz`7=G|j*ho1hJxir|gaJt`->$~-{i0HF_ zSp#P9#&3(En_9@`JCed7{(N%{o}m~^u2=tj8WHQ4&+{Qx%i8~jb6X`5(m78EIY;{Y zzEj4;jVO|XBBQ5d{^lWR+ZZp^*qKO%+MJOg`bkZ3y94=y!Q+3l2x*|5qm^y>=Pl$> z_NKAPU4AZLs&LcrXWcIoaJMe^-{=bM z5nO2Do8&W)p1S_c&OKMyQ(D=zz?dTm;(thI5HovlAH)}9pYg~+&N397C3-WxV?c8} zCx9NG_STCvW--~Xiv`Lqzw)a>s^tskDR(uO3ZUdT(N*0?-w7U+*(8&TDyi{1O{(-Q zswhVzCbp=ag;fa8P+eWs^&Bc`mfO>hnGI$!(S^%|sZ%7H+QuQ_#nYVD?i(QlBFTMc z7&cxQ?u#NCLj``x1LUS_lKg8o2B`>-(U4HpcT*C!qwm4w5v|Ax3A$CwB!c&Ti>mZ` zT_9aGrInPUX)Hzym+Z)Ja)b$8Z_pi*&h~4w+h{K~<7mI2=o|epXTai z<2%MSP->G5A3oG!>eE6xuJ=cLd7PX@SCu13xIr!z2|S;`LlTqeFgl)Rh-}v8 zDeFV9KknK_D<)5}l`0z#i-zO6e0vK_HArMbj*+RYFEL8CMIRPiV~Zn%NV)W={fv!y zE4|Y|P|KS?hefNhc0McUXnle6d$)2&R2N?VJo1xP_|stR8O4ay0Y>~DdvemU9g9sp zAN7ou=FF-3W__MrcdSvX6v;c2MP7Zlvlw<$O40}=dqaWW(uz5K)7j*4+`3my@shu0 zMym5cYCe zbQx`;KB>{5bxJuaOr+Fw>AK`u=WUzEOIxVCDU6saRtz5v4%VWli@amCoXEA?Y{BK& z#i0+8Os%ky$XoYHLLQ8q{f=4?-A^&O4p=nFLcGv}ySLj4EL2at+qR@1sU4}L$h*SV zh{u}8!q6&nmv@{CRDLaMq>k{cBxlAUfCNU{?DB_>gah(alS z!@Lehkq{?u*%OI0ry4qmi2J3{upIW~L{YSDYg-FS}klrHDKP-ArxiDo>0GOfa;zWY7&I-7{5Pl=0(OOfhb$(c-- z*gj1p9e{zzhu*-ufyT#Q$y|-SsNQt8)|e;3WZf4{&ZDaUQIfOMHP3td+{>FQ{cQ?j z=`v}PpD_mi&~;8e&l2l|S^AMH^Xx>z4h6rQ%yHYoNW6QtvTHqkg$?MJc0VplFD4BxB&X~P2W`Im`1?^FzBgm^ z#=P=CIS-w$2%?4Z@Skf0vQSa6WhVN6VCL2&o>r=L3tr$L*ks%#5h_Hnc< z_gRu2d3do(xThlxil2+OV`^3dr3LA}r-=rw)XAMp<;&G@0^bk-TVz3^eaKI;_xtwz zH=RqS`x`^as;H$-eF4^+7AFC}VBe0uCkJ5|l4g3_Igj~t)BBk?I8A+lFXB004t0j+ z*G7SZ_Xf>Bz2z3)X==>pk3>@5s0pO6SrwKtBPw)Qm}62! z3(4*|{{k=j#f&|XOk8U5P+RbQpg)02Q{NmiymxD7g-H53Z>CLF?AJeBx; zy7IKIB;48HmNrsjG4+VH0!#fh(NH;Et0vyl%iLD|*Xuu^U#V~$KfJZqsyaKZp6*8& z_CvUuj3`BuilDEHrKwHWP zcg}}`liw{+=Y}?tg8GNm-|~pkeylC+Dj9aRA%D-mwaSyG&#(-fg%$b=9*kQYS8!E1 zS}(r)fJ{yndqUq|c@ts1$kaC;>(}NgvRZfpRoq+UEpebjBf9WMD)zDd9my>ks1=E$ z*`w)RgN49<32(;AZlQoaK{`|z5$?s{d0H4;I_ZPeoy5Ku+gM*#j0^UWk zkwli^=gnFf?90tTqHNmNqH-S=5R=?t&{AvB?frlF#m&Dt7o`d@O5&!{32MWm`stAe#-1M3x5v%C_3GFOMzu;@XS6=`Hv&V zi)CQZIG()d@=?OZgin_n-<1>wy=t@J43`>*`;AlfCP0mP{h8g?gif7`cjw64a5;>~&g*Fp=oi&{uKV@Eqx4uelPCb7Xr(RGT0PFIQh%{@XqGM4zZO^1*I) zPZc*+cy=Yb<(+1^N@Yg|T(M2xj@QzAuU?lkFFFWN6?HQ)d$_FZ%9Nd#_f2wI4!r(`rS2gN=u|MM4tXD3UgVU6JY7=}S(xOv#x4tN1z^ttQ=@au&ka%*OJ-uVST>dfg%OhCVVyEAOcw;OSqM=)OGshi(EW)FK4xl?EN z?jeZAaer@#bWv)zw1yiaYi7)B02v2|X);y#yzf8N%i= z($Pb~peT6Fb)G$4uIyCrwnh5czr-TBhyh(^Q6c)aS@@^eDo27rl~d!ye)HrDiPQqa zO1{M6W(EqJiIYGMO z&DqC>U%@at@9L)ZCjJAR1kZ)5rGQbexRUrkPFeE*-Jp`;af+;F-2B`qc`#W|50+@K zoADD%%B)`1X6369?0NWDwK44_t0qs zk>an;!Bt7$Q|q8FH+AVWANh({vXIO*&`lOXXFru&_nR6U5DpJ3e;Nj^q7!Dz?VRYA zwbpAsNlSJa0OM}S-O&%wYvYNtPw*mfEFqJcEkBFiq-(`OFTMa$2r^fZ4i2Xb20yrn zYSUoOo4g23LI67Gby*KxJHPD#_RyQzquH0GPm8}xo0c$5v8wjH)8ad84Qr=&9TDhN zy^Rz+gC8z+TcppzUW#iU^B_#Fw?Ssyjo&{bprEF#aFZNxH8qO&P?^p1JdH-LGDckLuEueVX&hSUfD&-WM;G&=oV!DX&vKG2i7a3H}+yC+#4@^Iq# z>n6W(c)wG<>S1*+32jXo{AB8wa3;t&mq}Yz1=)EtoadX9Qr-;Wy_Iv?|sEiT_MU+M$HxGFiJF+bojnVMf430{Yaew4_aj+3GfDA^>jMV%swEZ zSIpD<)Is_!89hxf&Dmy|XH5^;?*C%hAiaK98Jl8QVpx1^eY|U*jwY8>cUWwnRHG%D za9`h-x2qM6Im7zWrHb^LGOubW2XD$SpGN5fbtuBU_!WtiW#(nC^mit8 z*E-L|cdBqgPkPs<@NB}gPwo8b{wi-gSDapApKPi+w@Tz#=WIl2q>fcuVPc%e=t-p1 z8H2f*J=AKXg`7p+q=DOZDvWKgI&Ow_Zs?#!APTK`>Z%ux(~=wHIN|~Q=4yd;Vg~l|cp6dC&x}2?$=`$)-PY zoRxb{S$4RP{-n z1!X=>@DN1<`tojxKnmKxrPtWa)m61%^kmDu+4jXR@Wk0jA<_S90q&BOtHPy3D?hRV zI$5Xc*M|g)NKLbJB%mC<3iZmjA7PZMudLtsCx8*TDOC+iQ{Vv_QuJ1RZHjC@)H{ZC zZ?w8o#gV+0KfhG}*z3o?v>xpVPF&}Kp}5-f<+xS-dOO6%-;0_6dO-3>B$SkQ(m3P^ z==&MW(%XvERj&tW?KF9YZZ8%*&*1sB_`23Wwe2^Z>H^u zE7b5d`VNjida{esGwA0sfy)4G+IVn5D7R(@s9u*tLC5X+{S@yQ@#j3&j1aB{zy~qt zMUBMKrL`;UF>~FzT#RJ4FU~-%VpX*2$cg_z#=K!xNZo&2Hh)WBZ zb=dSPoYn;Z@wNel`j|x{j54&*tB}U{k3{fwO0!WVhMQ&jk4~Hy6CHc#q_lNa|NP1# zUG=$C>G!%ZWpp7;bcC78X|}hJW-+^)(x^+Qv7KSJ2FU=kw{tkIVXLJ^Sow|UnqqSe zyf3;!V&9n1Y`od)YpVRGXD=-r`16k=^@Jc{4@vAFb&`XoWZQ z&Ayk#b7k*3NT(1yfaWT8W%h+yg^>A;b;#b>TUN7`NF%n5ne!(iE#ioCNjWjwp#;|;HWbpU6IQlGSWhF*l@Chgh2=imjj zmI-F*TaoQ)AK+~Iv_UZndJ25%B}Cj2kI#9VgXmyyatK89;cHsqbg;S2L#Y`xp0dF$ zOP8iUW8N_-u7k1YFH<%p#duU`}Aa3Q1)Effnp(sQ+xyaoG%l`j566 z?2T_m3+Ts7|ItnuWE;Tgu^}grdunLxGMx_?9WttI(iGvPw0+z6YTNoWqJMIw-u910i*M%pd;2hMiuYew&@T2Kj!6?wFy5LF4o^M6R*49-jJx}o&^{7`_}O6 zU5McHPpxpjDnp2#(B^02_nl)^p!Lzu9I^P+xSzMmJ7!kB(IE3I7Qtd!LiTW$O|{16 zTxS;hqv^?})pC*>t3)b`0|z&4@Y`bjwyq{3#$f4t+EpaxNymrjJ(G?Rl(7{{R}Y=v zYirB{E2=TU{&wYm?F7kfPc%wozej+Yj!x)*(7n>KiSn#E1W~Nz(c_(+=98dmTCjQP zWb!e6b-73EoiP_kDcu=_KGTwTtqiQ=Rg8#3i?i~7cr#rY~QQhX$B7fo3LmL29sHQ2{kMV`}VeMZHYdG@#xhL!myY{2aIwn zne_Lxxc7yW>n^7FTQBBoL>$bXxqsS;PHq6Wic^dKPC|p)$PIxQ*agzjE(fx(hg$=3o7billr#=avrID|}}nt1`J=avED^Xg15WVe&FOc^bsB`Wg0|5C#N**pHqBDPFnn0IuHVYS! zbs9ySqJH9xOAkZD|*jhJfJq(C_)bxiYM!V_R4fjCrxm z=l)kjX%0(##_+LBnbnT@FBRNn{SUQUb$149l|F^14ms9!r298Z*q(M1=75C>k}NChyAt|tH%|$b z35xX29?&aXrVoRPS^#dgEXdO@yuvhQVR@JD4#@3*b_&(Tx8SLfz}tAxae&~ANAS$Whu_r z$Z*(PnRm>zRya=(J=K`vUH!HxN>6Xuu#8A-L605ziW)M!6}#rb1BX^4GQK7=xM(hx zW*YqstB8$ejBDs^(hx_O{X9~f&(BPy4bplSg;<%1CN=wzxpko9#?d7Y3(h(ur5aT% z?AH!0q$&81)UWMC)L{_n7k|oL!V%#0X3Nu@R7|dmaAuv9D#}i?F&yjU@*uKD5_2YQ zcg@`5vCA>vjgSG-`}c=$au&R(?8I@_(F$)1$Cc@)b(e>rG6+2+$%1HT!$=F;F;iOkZX<3vtZEFVmF5tZK`SF*vBXPzYpW3;**76&< znu=59x@db9lQn%A|62yf4)g4tI;b za|pT9xUwFcD*{zvBTMiOz-0pH%sJUQ*QJ$*&x}aOo0Vw;=V9Z*+ z#rT3f(0n9rO>QrtOO;Q~O~9y-c>z*szklZp%LU(l5PB8SNdMMOD0ut#T}lR%W65!u z0L0i~^f!*JeOyW__IRCHW}eldUsc?BT`OF^@+npD{Y&Zk9*k?>$hZ&S>_JWv2pGymb+O*i;rDaSr1dCcPH^ce3V z9f!P%T&B}6-6ubCTO;>vI}W{C{RHF&V5*&)XL4^jhYn^b2er#tmcJB)Te z0CT;Q1K65CTboKIl4r#y%+*+!FpVQap`4CKVVgj5i$GF}RFt!CsvEF>zNoab*N&u) zN^+PgjvS&N44V8FGrkbE=??I>+Vb@E< zkruf{AV1r<3~U=;>rbJ!pN| z>zNg@D%D;SgAuc^%wE1TEcexpgL#6&lTFe%6vlcgE)}sO`sR3;-J6q{TC(rdX7Z6& zE{e4)MvUd-;x>eN^<~u)cF=HwFeiMoDahz;5M`*n`N7)hQnFkH&@@0b{dwl zLm5m@w-vSXOH)YgYw&==*kc^{*0|{e<%XJaTfx>0w!6(%tX<>Q??Knz4v4=0t04NU z+}5o6v^ZG^Ahws++}aI%9D3TL+6+d;x9~^C2X#k%dOw$1lT@s7ZekC5#=Q$s!6g*k z5+f?R&g&NF0aj`_2Jxh`;zJ!Nao3+q~%ChFmu9@B}dn6 z0R42n`&2ECccad76RZ7lSDk220dqF%nj6F2qGfU^v2YfM~ zkv+t~1hi@5-Oh=C#gH@;~rsNFG7eRCw8FRWc&eX`^xpE{dreBz@IB71vi-Y*w zRsL|eCLFfN_Yx07tS31AU2eq7F0KGTx6sFWrHA?flf(&Lvv)10W?|Kk&;BIS5MGsm z={Jy^Grs0EqOqcv2@YFSN%B^HIK3i7TD+r^NNzp35;_>OeR7Kd*TYdJ>A>8oS zNY$|FVY@hi&*s_LGSrbTAdKwut{Wn^az&<`&X4CuB=~(eXM!?d_MCl)7m$>^Qysm^ zO;u!Zk3o?MN>Jr#p(Ipvg8};H?MK_Sb7m1oP|Pka5Hz2^Ua1PHz>j=HO6yw(rIhN= z{#6H8h#)h41!<%#Lkw};AM?wX#%K6V;8+&oo-y6uoK?MGh6(Hk_NXUPM}u4R2*R}P z9}2L!EpjQ_1*+Q*?^xdLHK=xp$>bS5Vg!;xODtPn8_O{Z=AA}J1DkVv0TaOM2TE73 zBB6bwbs2-}jf!pwX+#Vhnuu&l?qOU@_r)DzR2rM6gSAGwcs|ptnH+QUz#o{v(dtfT z*?@;V%hZk-X2~|;T^ob_zVjbXjJ*?Hr-Tj4o4MlZhp@~xcv20>AUlF=$L>sA;b^9rFpZQRGg&E?87<&pBM*PcQ#naiyz%(#!h4Qd5BD762Xaabx#& zJpfZAVoJ*8@Zc+p@qkmD@nq1SJU$pu)`V4O>`qX6m z&+qx5^cXQarx;=}jXhIlk2mX+iw%dTHn8tA8FW?PfR`8l5{rl2+F{!c1+f7%$hnf16!v?ELRbF)Fakdo1wQi;{e;2#V&dXB0DVQo;LjU4upt)txziF>hsx z%#vZe{?{q95l=umD2$j#jGe8hBBQkVEZ4|!=wMb(&DGGPhn3i-fsA3AY?qG<{f#}l zZ3@*;uSW+fR_ZfDXoM^ra<}O1=PsPnpf@A=d^W^20n;;%D6aH~eSNgE4jz|zxzcN7 z-eFVhJ}2|(v&LU9Fy_DV`CfG~74F`~nCBtArJI8Qq`9}|V@D-rd*I@vm(jv7qS$pL zzQ*kP)wu26o@OzTc3FS^ZW~jNQz*j{nkhYkq0A5v9q~E)qeedh$4*YHf#O1laHGlw zP)^#!MI+qWlB@$)#sapYJfZ$=dF!dgO#S2B!9_Ib1Sfo@ui!9}ch4FluN5|%uWM`? z6yeJjGAw>92DcQ-RRG;TPBsDJZRee4gU-HjQsO601T>pM1Fn6sd(-=*og z9)MBlAz=zEkAf;5g{*7Y8~pxjS7)~AXf*t;{AwXxews!_hU2CL7p{suxri}*>wzBp zAue~`@or#xjBIPC1GzsmN|RBcDBXQsXdP50P-c%B&=Uai;kgs8$E&u&>4yu?IYdf~ zOv4D`2ie~FHb(L}pI?ks8R+ov0qy~wLPRkc2K2NNQ6(&`PU^`;bPJQfG3)}&IvF1w z!foBQ##kfvgNsi*wJ;7t%S%yhAmqu?g%RiAWRe5Z@`QVC8T6mz6!!AIJvhrtkGXbn zK#K6@6f0sY)J{Mp!NC{|iV08{u>ROc`4_%SGUvqg(vQiR6lctV97v9q{jVdBP!bS8 zpyD{x>j})L(?!KF4T;($VN2k@Mw$ohi_zH1Zn#$*WdIsmz&R*$aC>t+a5N8N|4MZAUa->@g2+Mo?-ecH=RJH-rz~#wgv8YB*bYRMEF?oM5F*J#6Pg^GoY$!+ zmbMvB&=Fd_yQ@a>g~~i8fUGB4Bk%j#@ptWIM$3qZyW?Uhk3rze-q{y4x3X6j zfPRQaE++HbgxN#tAU^i-tO>CIJ0rwBtE0FrpIYsRxMQVT!ZKK{#l+`TjvRzFus|)_#V(DG};1D(KiopN-p& zl6G!pO`4pAY_d2^KoUJn@97J1kM*HbU~l{Y_~*fek(3&r^bE>uG>Qe=MnFLk5}BQP ztoVcQ6FbQX0BqZ%ir%YJimGCf8#gOr$v*q1d&f}8J*`<=GMj(g#EQGTCX`gPpI;0{ zsE0uNAlkb*o<6aZZvdoP2eSyNu-3$KElp(SzM*mxKad8QoljCSp7iab`f0KU*mhjz zo~s2uJyF8tE{>~Zj+sR~En#%m7rHIi0!sKK+FL;Z{a)+LKzAWI#@nwW)K?OB0?L}m zHE21ADc`0)+$1{yRzCG5zINT~2wegi?vHjj+yA6=;UpHsluKI*L|tc7w^y4 z2Nv4Yvf3xWfna57cndQ7QZXeFWbT;I9Nnk`8m?a*_7Y~q`x;Gu0Ne^qrvT!&U5dsV zUIU0|=c`gTE&MbE>yWHMtv&KsTSp!ePW_t-&lY=GP>o&9}>sTIok1}MQnz@LEG z^VE6)%3)PALO-CB0u{e66*z6ecX3sgG?} zs17LuhoU(YjFE1gL;xM~5x9v6{VLf-zzzjH5&I#)%l)#A!<4NCH_U{wujz$szvg{) z++P~aa^Hxrrk^Vjm$Hnio-ynDRa2g6q_`ZlydM;nk5DVwv3c->>09!0f4 z=$k6)PX|(pcsekvJVq~x&D70G8>K(rwkvxq=bwaEzQd4PM-o=;?#A(RW8%z`xX(&` zI{;FVo^XKuO3h#b^0tWr8A7ai_K(4~@9o)wRxskT z|7(qTT2IL%cCL{QnXN3fKu|f$pFTzh6aXv+z`V(Y{ky{f1?QGX*V8b@;8y_!<9R8C zAiubL%XApAP*7pz6T)1BGTAXC7d}-XcQuLmo zWKZNH)C+0aCM9W!a-FseMAmS@)q>uJ@xCTtb0-w`{6>LlENMV8Da&D0#}dUQ>RB?t z^Dr3p-C{I%xnS}4u0X+ytHLD-WXayWe~C>rp2>r3ydc?taL6_KOIzI?xvx1k!3_`; z=qw7vytT<_S<~%4WyLIgrOX&^P{t+zssR7+!gIzOpZXfP3BkB}5DD|w8ns#I^7@ng znub<`B>jN?=ZGtjXU-o$PeSV6BsW9E19v-4_5LTUCxck6lm%CHr@xm%&+$?4)bZZd zS9^8E)rMLN)%FWO+#=T_G1)vLtE7SjLt|ZrJHY=?fHCk&)OWpN=&778#I7`%N43c? zPvm35T;@C63ah7`M6Jz+&Zr)DQAD*}RD(9J^WV>nkMm2_@TP20Q%N@N8GQ^WK9{Qn z?=nD!hNXAjo?lNcm+v<$%|A@zo@U>4k3t&coHgjcw+I`59nu7| zZ)qV>*2^)Cm@P|HhJGBN5(OF^zaQ;$DEqjd8VuL>0ZkDoJ8;e&_D)q4?o?=ZyW^cw zkH8*HWR9e-M7vkIiMr3ohh+mbg0v?@X(}WGS)S47`S^^% zB+LoLSQ&iAoFXp)*7Mk}Eh%~YDbbb0MErQjXv(P9jD%9Rt7 zv)-C0ORHt!d(-|g#i%wQw^>c_j=qtT{M2x)yJxk$lQm@yy7LvOB)s2&PJyIUxC$QL zUHmOM$EgIt*BLRu~?e zp@7O7F7-fDL>pdBkS49{16j_SVXCw@xPtg>skz&^oF#72|HH?BfD;Q8W24h;K&(ua z;~d`yU#bhQ6F$(fJ!U=o+fe0XgaO@5FsTGUmzR$%Ia|2rYZki=X+#%A60Z5nOwMBJuJ;1;B5+I%U>QJBZJ|;Us!iVQEqEXTs9_3E zV5tDzLc|@0Cx<>q0`vO;)BPl1_EumTVH%_GNRRuM|M~#yb>FCQ0fIW|o!?LI1Z2@> z%-+{cmews9X5H_Gl?vCa8Aq-W&o-onJaupA$egEeQxn z^zcUG!MyeJkE_ox_Ny*EHkhU5o=62{{H+tQA)l`5iv-hz{1#`SzfCsh zo^}h((s)i4Uxn#rGKFb4mX}VkojbMKCLWZ@DU>_B^9P)&wwwy=_Y7v4{#SZ9PBBL; zEBT8g+~T*NcCM#1%j#MY)?wX`zhqO zinfpAmegJ)#fd&_SPMZy6+*clABgRXslmWh3h4?Mm^S5z1!D z0Al+%Z>EC>gZsOD%+&B+=18N((B6`43^!}q_js?T@U=X*pE%5-U+cGSl70Cp3)Mhk z)eq@jBPA1Ty@U_m&ubR@-7QH??sG|2oL)#qa$#;5MtvIHI`yV5{QXm`@9g|lb@yhT ze^ z-zmdG5?k@>QJ7im3y2)E{$#}Qt=1g*!#$%-i_851v!^HL&)n}_y+Lt?LXAdjkJWs( z&NWa#9HE=Dje*SX*G~5@*pIaXtFbM5^y5 z)s=N0HwmL@(Ii9-+OiOBIf|{SGhKTW=j&^+*4W{yX@c^p`W+OtH?rVUsN?2;yrz3h)+AB~$Y~5{KBwqE}^c5zMCUKUIA$6kqk0%2ZD3|HR z_Z>368h!ZfnEvT%%%5i0P=xu5CzwsP8E_6&{r|X@x=%LoIo#+MpL#PV5PXt@n&)?5h z>d++2`fKpvsEIVhn2JJG44E%%CEKv3B$mvrg#I_dgELq#d#h!Bv8C~%zjF5xd!EP1 zyA`L;oBT@;HZ7*hED=fDlg76)sGr#?oj|!`$vW)-++hrkQmSLDRty$Hg#69>bQ20@ zo%m3!2W%#|FsK}6u#eDBOUVcG_oX%)o}6pod5huEld}E47U1B7aT8ZkM!@EN3%;Ax zER-o?vg==Sez9NiS{4~;lp|^$eH{dnV=$;r^(N0UoAK?>e3AZ={h7RcCdA zhcE&`x|*z9Btb>mh|H$EdRmmCYrMI?wOFvd9-dJ?<^j(i;go7X0-Jo1E?(z(+yxyK z@5901aAC?Gp!yJ}k%En*dyP*r%K4K4m?_^?k>3kct@Kd~d$*>zsDQo4-@S5?S@%DmMGV zdkwFfgL=@9V#=Y81Pd-2Jfd^WvJe0=q%A0E{HQ%$aWd+Qg84gv=*&1c74hRXSY@F% zsDpP6rgAEzu-tp(aZj=zGJ)PwS-t zz)2f438rH8F!vF@lXj;5D5&HMR5;YA{!qy7w}|Pmsoe(K4BI(V&&UNCCyZ*feyb}0 z^|?-gsH3dyh%qXojjXeH%%XPQ;$$JC)t0jo?9m3{ZB^~g``fugTBX;hdX{{HZ$BgD z=gtcmIzRxuC!aOw@O1%0;J?Ig)P$6;eZ}MI$q$m%DRTM7*h18=m<|2#T>aw$VM-Fj znv;m@RgdR0{u~!P(|dAjS=9Z~mOd{cZKVAbPsiPB9#(dC}>(XaVd- z81zVvqR)mgWLdzRC}CYCtP=RAzK!@Kz<`QN7$vED!eX~e8}IsHfp6aB?MEtWv!A2a zB3KtQ2e?4PVM!qxu6edlW%@hG!jczHN?Rt%G;!I0O)Y;otwJgg1MVH4$H@ zP_BMbs2r{yf5$ADIHAG##IEveB0e8$$|bl>`b^PkNoT`{N%Lw#p8GC6yiGlo2Tw>QQPEvL)94lb#~aj8ZW8vy45$VM|@fHbCK{j*hO1N1%ssdqKq zQgAkEERlPgQo_Ulv@-!5GgD((v`m{f4a6%y9*-(61WW|#72=(2V~vKK`{)Zgo>zC< zV3hmLMg|lR`a(?-wxVDOdli}hl2zgj>OaL#J|J`6=xV@=!SslQ22XbDeh2dLqR#IV z+S0mTjHN3{!5O@O6KZ~`|N3Xev3a0<7qqp^2;zZU_@rjwJykT*6h@V^p8lN07}YOd9UL|$y@>mlWUGkM6Ixo z#`Lv+yx?W9E1#&&v^O%s zaZ_ONrQR4ZSL5ur#rF9G@i1JLMj*Z((J%yZB1eT@&5BNAb}zVUs__UcnJ>JLc?| zbAO0U8iGAQf2T%rpUgvS5Dc7$R@o(^*h% z=FEZ%Ke5%u+s-okmAKr~X_{<@QP(CPJVE)TW9D@j{X%h79d7%%ns*OI*k-R|qg z*SzLVv3p~fK)*!v;Go)n&9Jr-hHD`M8DT})cPas6IAHVvHX&N`fsfC}h)HZ-l^asp zbgrwPJ_h{GC9|=4iI5Vcqs}~?JwFwYFEP5^U~tO5Y}2H0vu&beLR0EBo1$S-aos8a zqBjOqkqO8Zr1Sh7tsUrVlOz{xfP37ZwelT}@zvRyPpHU0pk*7T4UD5GdlKruo$31k zM66!*f{*nFQAE3Mu}%kY8;)+aFF7y%#yMW)^EQYa7Vxy&u9;?H-GEJRD~r9|-~4w8 z>hgDKn|tq@CXuv=8lj$r)5m~uL3*;Y@9Q)rh7?-Ij-1tk3ilaN(SU2Ck+bO2O_gm-EErM6R@&noiyMz!RVWwOUSSMg;*39WFCL(=FE+f^h7evd!CE%J=des^w<$@(;|1}zl? z{XLiQ)DbpS;LEzNxwEf%v?_IJfG0uGeBX>%pvK6QlotfYk5ePQ>vU7lLU1kM-??qk zgly0zirjqPk-yuo_q4a1)A?j^K%scd5etUb><40Bc|B@F`%I3HlxiG z-hJiSJ3!bsd{)t8MP6%wt%QgD(4~AU`&UqTo;0;b+XFPhfS>`SA&@opMnU*+esnV3 z1~TS_-}Atk3z>_4&T)#-?be^X?wN5^k{yblKHdh+jomxYj#(P$n-53{TjGkRht+N? z)u^LacZ=q_ykkJd6QI3y1oR|NDv>f7Ew3dzz{;iqYaS#UH9RgDw&%qMpaZH7$ptc_ zInZ+h(E_+b=-iJfkNqMyoreb$#(<6`ViKhcp$B&{jojAmfob zxhPbNbUltOfSviy^Lyfyg5Tb1+lYULenS#W2NznQ^ur2wn55z7HUVH%EfF|TQXhlOvKx;>qRT*vhyd>+2-yo);@^0@-EpgeWHAvUNyG3_P zfh$-mqow_jG)b;yd;PZ#riuWij+dOl1R8AT{kq+COwR8u8-Ga^#D&5v6JN6tA$%(1AhkP78hpp;pEK?7ZXRs?C$#WA$8bv*ALmNkL6K^xjPd z8a+7vPOomahu+Eg@xX$pZ9Mk%#kKtxv&Q`5163i-)voP7{twqR#>|7vzzK)|^g38N z{yvXt3;sd4@1`=SFB5so)5*0Md2YVqR6NrpbWp2_qD*H;MBoNn)eF{qe%K}MCCl@) z!*ya*Y^wj2s|vc1;NNu(oV6#z6$Tx%dL+7(hl6CcXZ?bgjR4m*9sk+fC}T&w4~i1f|_3M@?P(?O9YyQnH;%1$5sm`B-VD(6f$gL#&As!xxr4qX&=v$|FY%xhim(VvF9 za*o%RQHCvrhl`Lx-NsGJ8oYDwL|RESWwUd0EO1AZX#V=>|F@jq^qIHsTBz@Vte@EI z+&*SdUT1~U@OdesN-a&B{)`{}=M0v{H+&Qy zyNX3juJ`q2L5f^H27bJc1uH9)H&k|{-kCnpP?o%{=dYt>21gFLNOHeKk z8N3E%#hGH})KkeORS$z)3Fnpo58++2Gkvo%9nM&fUoU#}I4QdeLS$Q{=ElakK2~P0 zezy3)5dW>AIpcBiDCaw;j9*}qQfsEr%=*a0`iLlc#Qv0l<4N{lRr8=ur=y^P9e3<- z?l{xo&<^Kc(#hd_o$TLS2Kd_FMaE9?HH6c14JQ^3i2gY0vG~xf8E8V1$sT;1=-S;? zX&m8Q%pXesW~fg@&b3ut++^N~)w#u;5b7 z(P+Ze2`%BT31^#}&BV6;c8C=VMb+)@ITt<|Iv9Ep`s)8^`s%PK*Y0aU6b`63r1T*M zsR8MRgS3=145f5;w+hlAHApKUIKa@|DxJ~{E#2Mu-S~dLzwqJ$f#+V&zV}{h?Y&8R zrbpu*3Krp~?vcg&dlqwdKh%^EbYr(msL4^~LMCl8<@Lh}-(J7=|5sgjY%Ho$hm9nn z?ZBELWDVEJnTqZ$_h6~9M5xXuq~H{lc@E0d8q>eD_etaBrUeg`_#j)3YW2Wp*R}|$&cp6SFHQLlQ3pg~?`gw9H2J&D z&`&#yHHN9M2TndCo28vqv{DmXnVVzqkB8^)5P!_*Y{L)_eq%>xkn7rX?d|ae;jHoo zmwiigf_c#%=zbC`dcw@1^y{&!qDk5{JETN@X*&U-$oGnh-rA*jpQ+8Q+aw+GX}i+o zwjG60iy*J=iWmtnTe6E2s+CpvDBXgs8SFHF1OTy&?dg%-D&SPHMt_ctCYq6G(w!%2 zu_KwFea}-?Wu(AvpK#{yABbOos~&jI{u#QrnE#c27R$8N(4*Vcb|HUV1t89)gq2-? z$j46I+fv*o-2$O$&H|Qn*xxosY^eqYN%Nm-jg}|Kymz zn@Q$r58$d1MM89d3Zy+#Zf!+t90{?^r^{M8NK3i(Ug-nMR%vU41J?crg!%y zB&bB%E@a6t6Q|0fh8WWK#Pa$}aJ-TbM^;?|C6ZV$w>PJP+4@6F-^%#BUbw-_TS{t? zzotug(p2lhq-U&Qwf?5+EX-5#QkHqH&GJOB)*)UeBs~V-CHEUQ@FBPxf ziy?tuoni+wik=0H(Sn&1H;#GSGS_^xM!QJ{Qby})?7+_ zD5qlG4&uI-5fwAZ^2}+S6T2zP7+XYdBXat3x!qHPH8$G$7ym>a*L!$U*q67!Vd%w? zbB)qoCHho>0^RuyJh4EoV=wp6z#eiab+>q@$H9Hy=kzA1PXN-0 zx-iSh5f74{o~ZbOJT)yP?=|MI&SaiC^|I`eU@NPF=M00inTf{q#=4=YF~xf23vOXJ z!#Mrd`7fgdP&>ojCe8VdWwi+5@5_bjZd2dvewJPRXD%?#b@M>e3Tfo?UDepiKadmV zr#mqi6_C%%(v<<43AId#sW^El0X_zT+6u6o2aR zxcl^}y3Ul4U;{c^`H(c14cBF(OkOl0neYpRTag)eF(@*I@I=^+nwU0VeaurMNQC|6 zj!tc?taN8K-TZ)(RyH-^amq;Zwc(8fW1r|gfOxaJO(EZMbb|V-0sKH6vWI_;!ET%I zyJbMS#or=fIQ0R74-drAo7L_p5xXJUB#q!(j@y65iQlG_=I@N?VqU$teRDNsX1LPC zsxEsHKS;#}g$$NxDS)*FpveeX*w{M~aGiAZ0r|aA!|O^wyu~lMid~bsI@;F!HI`K_ zlFIyoL)xR{siz_qQQt{=HgrJXxWaI|o_zDnVUP-$pmYaf=9fhgzSR1)vETYI9R}kv z!va0{UNy{*sPZM2wi%b|7-DMujpZW4*-#5|jER00Zg#!7qwH=Ibyw_q=?OZ?Q=x1b ze`Rq+O9z)si2Z2|FSVo1mEY9kEr4-e#%{ha8NW&7VH$TzuJU`G*%^DO`CsQ4TA%Am zeIj|bE2wsPD;>%!O&p?pi+E!5<)bFpv{_<@B4_J^anv(& zWsy=xjMtwk;-hN%!Z!hC>l(J4wQahz6@}+|@PFG#t)OBD9@D4RPDu3?X(uAq#)_rI ze9{IrLW{=YC?d~-bPB6ve}ix?Y9B@1hq;-U)I9+{0#th(-uLx3RlhhlRzKy1G}`pm z%?Ok+qiB7S^ipZfE-RMeWWtJ3({h=}^268ufguO?tzIo)f2=O;Kpu`JQjihR&UNAI zklBC>u;V|DI4O&>(9#!(@>FHZuek`O*FIXvU0ZBF+18k2r*95yG?&fTUs@O6Pd^FCM)Cl9;HqCVZ&&9|g|Hi{%FCy=- z&OY3k4yn%S8FKMn{5t^qf2Nr~9HiRf)=kd67qBd&>_8%5q;T^SwV$cTuuj&8na7XE z_7JxZla%k3{sdEL_ed##sg7Sgf(;rya@}!tFMzKhYPk>dIWL~?%6t40$sm0sO9DBR zTsd84#qdnKV(ERa-(J0D@a_uDQmA@f1Z9!cYC8PjIU{b>cc^xZZSJ2DbydBQxWvAf z7y2fR`L9RfPQT+`!w+r?r#r3sFq=o2oB{=eP8?=fZsTaaG?zv{m+ri!n)&g|KJmF! zr*!vXvy8_cH{>8veRZZgyI6HWH?JS7^m~Ra$(lWh=LiZNsv7~2-@s7#`7VBWtu#it z`5K#Yw>(1XQp~m|_hH6Vgmwvt+8-dS2*{>b@c#J1EE*)Hl%Ma{D+Em^dEGy9z^*>L zkqPse8ba?7(R$QZ@+`Q?1tELwz(g~?{aKkX_W6t0K4gP!jP3T(zig>-0)H0iQ-`+y-6q-^{~_jdv%NEs5>~5^eD81-{CviB6oP9KOr6f%fXxA zB$+(JrqZ-PFFkhXGyvaW5fgUKA+sjxoj?(I$}_fqNuR2RCM-mO%1+^6unL) z^ZTqMkrp~}$~X2+wJx153dDVO>jZPQ>PCOtvS_1lUv{em_yrRhzd*@g)KFcPuV_)I zTdNw8t3SIKc~FAn5T2>dUT?0sv1tJz+yT7vqKx6k?XgNAlL8@J#CAm~%eLGqBA!1g z{-_;|gZBBjm|zcHL5;JWrxJ|s`IPO_Kkz{JvGzdF9v?ei3sQu>=W=-+c z`1N<-_LLubrpJaLl)dRZ;te4a4WEzZyROtT0`WaC%n4l7mNk^I$ z%ac3yM=^?E`&iejTjppuE?0hk%Fw~Bs;=-ixo$m=i$P{onO{*UJ5{C>n(-wF-p$hU z`LRkaui_u=Mds(YIj)9#Pi`_99e+KWY#Oe)lE07CcOw~tDEu7z^X;un)5_2vsY&w= zVZ2S*#Ilx1OL$Mg2m8EPH5-6ol2vT@5Op=)mm*sMK6jt?s-jy`_pZ$yu`cYCwvbI8^h8 z9m$#aIrgy6o{>Z0qCV{01G48AeL__)`X$uW3ww7cO=rbnr$I1ng*$ zkIQr$}3G(%Uhb4u+O6POftE{ElJMg{R6@8C21eU>o)exiS_&wF7mv+> zHGWN{?za`q?)&oyGU^;3ws0w_~W?XwaE ztZDtN2LIDkIJe8&YMiyfI6X!0uO`QRr1Y7zki9^P(_a=-D|#q1_%I0A`d?X&*1mk> z@Cf@iYDH;feK-#6o?ds|_7gW9Bb@J%+3>H@F;BvQTmSZNi=2XDew6+sQ_naDz5F^* zFo?Gxu&b#+nd%$ucx=iYEt1Wa=ZOF7ltssNuA-h zG}})x0N+dwt4&RbEx!ie0HSkc{?9zlipj%14lAyY~wc3_kje$1up1*|geQsa0Lu`LK25NDx`iU|e=6 zm?EbeXl%dY_DP3wK0{ZU?Fmx`wm`llINf&`jk}y?X-2UerI1(8 zv=~2F4fXeD!Sq*BD0)p?_YP&Bc-hxhp%f|I; z!KwHhcJ0D_i#szA-;&%Saj3tD^IDDg$^F$0f6y5ay|YRQJAZEN89VTHq1W`@lf6%R z%l|+eu`Hj;{&Sm~|NDMqXrOxK63v!q*~3b!??2cU3cHx^ya7MN0wbQra5c2 zkHP{kXILZ|%^c#YypnLv^g}380aB;zFbU_amrG?7cCvZ%Ju9D>+s=_jSsL6!{x@T$ z#tHSU`c<~;VMBGv68n`O>`W_wYO}`p%#fefjB2bInv5OWSGVWII3HFSdL3DJMYSC~ z8uUp;f3z=uEYGktPM@hl+=C2lY^TICcw@?{Z-Z$5mBT%oeD41t-%+wO?bV6|Wbbi# zAOxpyC0&Mc?giufBNZ%9u`;p3#QL7idrP zBDo6NW2PdJra6w|_aQ^X;dzM=o4o&tE2f0d-koNWj{ngy<>XLFpH%@SHZdEnN#=@ z_B6S0xS6-BxFnrv)Xu5_W8wiCREbp0kyn&o-r+OF*x5%ZXa*CvynT~hdpg#_-7+B6 z5}-xQ7#4iMHP5x|RD=+DZ0k~R^)jfz;Pg-nRx8)G9+^o%s{$%GW_%<|T0Ru}o!^NV z8bFfmFcOp?5pB+C`b8q_+Qeeh)d*S$rMg-_iNQsn-hFG|Q7Qd)E9d(=P6gaqmV^Yg z$)RXkNXcmDfV(?YN8c~otny(Y@s?7D25qY@mYK|^$9Th#f{vaCa4vL}0l$Z(O=azm zRAZsw1HTbP)XbP$^e|b+Hf2;!qZHGrIhF%KY+7QKuym)l=2vZOkS&3*Hp6ZuWlLvZ zf+p|%RHl1TVH%;QlqWwq@rGejMXE)^e6s$#QxbX%NPO5IrpS08m0eeUb(xzQ!4i-c zI%&~W>D?6$cVy$DB;_MDW?|8*gPYt9`!Hvb@Q}hsRSleSIc$LfabcdL!>j*QOv^@M z*M!&{QQ0Pn82`i(qqmFSuhXMrgbx_`z5Yq}x(|0pir53~I-}uNA|6H8hpWZ!@>pLa z@6Zd)+^xli=Qsmrb94)s?AL$5uBf0F`fV#dc3>)Ec@a@gHD0UqJ$I_U;iC>wRp&U{ zpuc!x73^08=Fw*<{!8^R;Y~4*yh~NKCxr=q4+KV0xoTB}=~Ae0Uu7p7wyIO|Vv3ug ztvT7LlXatK5N};;ZWQu5;qpdvlDgjNpH~>b`Ar(Ev7eV zFtn_@1mR_B3QZOWw_HSI=wiV6>>WZ7wZ?6QAbe3im!w;AHa@TM$zUHVRwZ^%#_8~h zIcVQsH4i)S<@D|9>_XYw^$)ogO?lTIDBiXXmT5EXN~2bj=rfrY68h^WhbSzPi>N4E z6_e6BcMC%syN|r`wr`x5%G(>h`Gk4t)$q)oqmG#jfNgoRE3GZU2&ncm0C&W}}$+Gce}pWJ{zp0VhceYtwJt zP{!D@d&XQ}JO$`o;yWk9?#;jkXRd2lZKUvgTU{`$E8YtTr$PQCj~R-}2+f*Eqr-c9 z5Ep@1*4$V{TnDVNRj<6tai`7b1nilGDZCX4wolhtU87BVU!mQ*QWDG7_p;FA%oNPR zHb!vf%d%l=GT|gSbQ_)Ax2?A@3!KScD{bRjry-T5il;7RHoNME5h7z%G0kdh17}a> z>AM#_dht3|Q&}f8&>d@YQ)Y5(jNXMuVK$+5GCTl`Q9?a!CYsF1Y7m zpBO+$3oZ&84dNT^m8LUNx;M>hs|1>VzBW~g&|=;g1U1NdrG16Qk9Z~>blP+YI7TC` zT4WpmIT^8x_2%!+Ex1r2d@n$Uty~Yw*OQu~e+~%^`SX1+ z-sP*Tg7;*W1}#aaXk8}uG(62+usm%PUY0l+5pHU?n#~w@re~jMzu@{(UTKmVR{QeD zYD7nKnj!3bp7TN&iCu4l==|fOgqjF)_o}yZ6c&`*Jff!c_u;QsDI4tFjM7oE?q@_s z=7r8JDPe8pDQ&zB9sb8d0?q-Z>Nj3FNQpJV8KHwZ*_TnFiAU@HRW+3wE3;tYtmM>1 z$58d0RBs9nocs3SGAGl|nvaD~A|wCaP`+773KeS|R8avY*&Y`)*}ScI9GL=^F$X?M zCnkFNIuXmCJFZPb#iZK>IWa1ye+6swGk*U@z4K#|%}!Be%Hz!nuf{~|rl zNLiea4r9?`!)3}iS;#t=qPNl;dd7hp&0=L?FyIuXV;R6F<+|d|KVl`wf`L_`JR9NVp1jzA?@z(>qv-f;}bBnN0S(Vi5+Uh zBetNmj#;EZOmfeoRkU=t8griHL+vt39qSks!-{S zxnAC9lD%>mf0%hwsnQFh0+ElAp?yQt`zazkQ?!_3nvaIatDfem)s3T^JVzZ+hDV38&_U~VxLsf_K z))G)@m6U*gp;PsWS>RYmDQ(N+j{U5nViaMPZBhQ+j5>>quKk1Sgy@SyAvHxTrzKlu zx?D_+q>%cY@;6a!1@cx6407MtS_dogAu5E|bnG^&BK4GcFU3a03o7h%lLT?}?|DeO zeQeRZ6q)8;IWf+lj{i<75?&rUgvQFx_!PSHX6!BR${%*`eGY7yfy){NYhPUIut4~9{ZbBMBil<%a6Mrz@2Mjo$qCWML%;W zCvo1JmJy6=uy1u`;cCQslR;QJ+0C;B)u$k|bU6c$Si4eNDu*lVxD|-piG!HVFKn(S zgE*46In3-seO$%0E9B=)>$R-9N^oj<56~N0wat>I_QlAk)WmEj9|>~l)T2QbSnVXv z(xpKS+-rKXUo@Xz-YPA0ax|A@tLVvKT|uQOt)oZk)4rhsXk%TbPw!bX(3zFv+Xaw< zsW~kDaZ-JN0^W`lHzBjBSlWyoFtB%%!P?^Q6`NQXn}~}omB+FrIQB+`Wi?KXJXaoK zaCl7&hB*&>p1b?ApFiAx`J2upzEih{Cv4h!y}IZg?;i|aDQ(A>-wJ<9t}?VS>xG>1 z1~gIOJ`K5u5j3dynOBn+`3%oI3NeZY^?u8^a709N`X4N@%3JZLsqa<(KCZPxa8tRW z=wxnMWv(^fH>drrbrW{hx5r=okKV=?oqduLT~uXj9nSw4qC-H<&Fd^|KXqIv#%wM0OY)!`Ts-JWXMbK%eQYU@z>H5)*nZ&(J^Oo*F!F*NW8gRneeiY?A!Mt@%~AC2 z*F|U!6Bn-;=|k9H>5iIS^rG4IHD6`85BF&ZcEwU)hFH}JQ_OuJ(4xMnPGVQ2CGkum z_(_^U-RZ)8I+ldQjfn^Zyf7?wpn8U7)w1i^zT`HjN=RUW|D`Q&M8pnU+egJ<^t{sx zH)GeL248Q`0yJa?@Uz8fF=z9kc%jhU<{I9cHq;-Mm}(@h3VLz;@1qUfi3zw`3>X<5 zm2Na#l@-5;-G%^Bv~JaUd4D~&Zz=V`iIAIf3;x0V^|Lwagqr^pfFN_3cELHN_YHb$ z<4I9(k=!J!(Dd{?4b8SEXD(>Lho@h}vgNj66||;6i}Xq@$M1%wrKmw0Dp(R61~@4=lyX_z;w%5-Yk?A{S)a zCz5mFymZ(k6LvXGUN6;oCpqw!8xeR{n#QQFs?(=>24uG?Lk^N-l?p9MUMr_J_A^z> zih=*Y-l#S>bYr`5V|Huw0(EW0Fu z&}5Y`G;ohU%68%F)x9LXu~G@mXGF9XymmvW|Dh?wn-tVG)jE*E&U}nF8 ze!xCUQ1w4HTvZOw((eXD#Yy(vu61nvKZW{#p81qAFf{wVxww3gy)JO92u+va70J4w zLXIfqz*+}u`sjmQo7R|VEdIC(gKs!jf4H(rDOU2h^xxL?lv;!H;QQ;R%Gy*Os&?&; z@2$1qlY_FRJ&spi6=s6QZ!PgJw4Zh$2SOv=(uAV9!%cR0otK`{*~XTMb91D!3-|lX z_;m~Kc(E08oLKC<9T<-5kZKWM#y+dkyYCG2K4lw{PJX`fB=-cg6=p}+N-A{c z3(eojN(Va20F9RWiPP96%_{cUJH5r{=NRv=?mf0hI3$P8W%-1;|${tPBH>_l5+_AM>t{0*m3a?z*!uY7w@2hUmgs{lbmvx0r5P|f$88Lwmj zS>D|+n2ht28g_mit0WQ^n-Ej+PmiBW=Z)V@n<$$u3VMf5fD7)F2Yj+(+TU@t3vjiO zxPaU(R#zF`eaU9iY-|51Pue0ng8Z9?@e?yFJH(d9_7Gn!*}#+g)8yy+BTS_OWXpi) z^&PO?yd;MbN>FgHT5$+Bj3YtRZpx$q`uvbk5xD8^$Y3X#T79pEYE|RvHsWa3g? zEAWK?<6XYu-J{(mm5@|Y{#Qu0M%aOFX835$_AdF`x^bk7NogAH0MHxOSEX8Zh~8e@ zQqw!Rm`^HzU#gc;jgP|V5{PV~{Y(I|woW!ReVF6P6^eS(l)Aq2$af z^f>L{D;f)5B8zF9zG2bUA7?3p$uCwHjJx(yt7)Hv2*_@%wGph!t(r(gTA03O4{>oM zVtli#bM;1yRqs#%8xAU0J2!QZ^*bd|#O8|zx!86kbZP`%9lXbNa(Cce2A!1Zn9;NeFqtClB+g*eGW|W>cvBkbV7@9Zkk9DKFdML48W?T&T3& z=3cTrjJVJzp<^IR7>>1TNNARtSb|+?>T1euQNu?!NpPrgjzK*@Nv|U81~lm#PVpAw zg+eu8s+RA=lnoSe^e%6CwwG)E?(U4cZ(iK~>o82vxepXCQLySQw&b2{;5YaIBMi-o znL&s#fKI{!Wk4I3ifNlIdw3S|0UpU-@$E(NwD%^e$^$%AiuZ?=OM`@;5sYDR*B^|% z42OuGGw?ckgav}oxZG(Gf+V|CT?U!m(T2Zwg{cnK78fM7ypl7M0U0l@&6a03XU*V9 zT3XQ{$h~7Z_1ShVi7xX&>#;TmFS1+Ek{|I)1B7 zvFh$m>)Adta2E3bc?EZK>sD}c+r2Q^xno|(GUQ*@cU@Pl>Z z+HZ5s_D#1MdKBP#r!c1h#ldirJo>1wb5*&zn*^u{(*6D8d6#I~pBn9d#jHf>OghMb z@-3sRpIDnjDqppUky~59ZtK!kz^|j6ib``>hZq9!s`ba0MaQ1iHUcMs8_M)$`X>)+ z2F89zKnHcj{KWNyO@sp1KH{A3*xrt{+T zcu0=tx`y!^DuoLf=CWUs5f?fgG1q@`F2e#_ zi<)%FK)wOWn@JQ9oTlGo&|jhSmN_8@$W9B)Gra0e$n z)m6^Ym&gr-Ai+)G$`161b`9#=|`hZctlXhZD3Mz7d(5nfr$}ykaj6Ar$`Y*zBW;GIXZ%)a3!9*Sn()wc{d1`b! zwQhZw-W(gU12!^wc18 z+zl|2GFJYw4rIAZ56=ZJng&St)D{T}=O@H>Xg*lXD;Cc3WxV~V-_#lmN%<}P&h zYg^YeGrla3Gl4$UG;`6Y1f>`X?m|F!R-e_Vbd0|OB2xqPf0R##cjM*YfqxRGo`&Rx zEUxvdrYK|ZYDv(1vf@FC(Fx}s+v#TR2%SUkuUq8#xC#*;xG)lz5oT3{3?;fw+9qt< zTE)f$Q^!Awv6p0f;zZKxcZ05ySMmy-?scj9QFrFsUdXZ1hR40#Il`Di^tASAR1Rk) zJ5^pDgA(rgc~Kq%y?ScrDqKCS9?yE62k5P9xTplboI|1ntWUa%l9uCyw_(a=^iZ7j%y8RghoOq-qQ)A@WqiQY1)9v=(sN(XEXw zkmWlxB8T2sFUw>Q(M}@E^%Z#b3ULH1?=bW?cF>#G->EYQe)5>`z-HHiN11_mTQMv# zeX#>9Fuj~DZMw{YK8nw}-W5x)4zF2Y=k(kTFA1npM%YAEdJs5Wpfpf0Kr0`aPWo`_ z{}l@>(r4&C)21~)JJ&C2AX_+owd|A#d|oB#I(8Rdv=uHUb1(HvdmHWTWJVnFsz4wC z!ikpV8m8FqYQFRx*4WIOANAuXr%XMwB%HO;>q2c}@2QLLqCzKt{3f5lZ&f=v>9lA( zxHFrH}wd!K{U2wVnQG@BkTD}+oJ2u47+Vlskg?sYaq;i~FA_DAVIIZLDAHIh1 z>U%^4Mzx`76z{MBSS|$_YWJ)>C5C{(qtVp}Gs5dB7L)qb-=w1OvQboN;$)#(m9|3B zi}j%RgtknpDVngFnT@d_q7L*40E+d@fS-L7CG`io`KBuWrg7A}aPeYJF84f~+748* zP}y*7A;_B~>E56q`K9{Xt8h*EY{OmW0;|3$o2bafA2}R`sj&^hN(p;UAOIIY8GPKm zXp;Z)%ejAqLY+Ne8Qi)TmHGXLNsT3hnJ~qY*GXB;?%tE3f86pz1c)j^bG3zy>7*1V zurm?0i}~xD|H6!s&kb>2KfrI)SMwEVGJiGvj04P^zpnAISuYXzeNNexA-wSVUi?$k z-a3VDgw9h?)v@6)vGX#AJC zG%!3|09%jAhR~cIvFxm`h@|Bmbt3rLyL$E<#^WSgUM_r}@L-M!aI@JW#*nm6bg5k8 zm}Z%|6X(9QFzgx8XUa~qs9=V?dyk03VATxHd-q*uB~Yo{?(VH24Ei5=AQ6K&s+N{E z{E|oW#g>om0N?0+PGd`GLvRZaK9wOQ!*au!p@Dc6io=x8ZQX1XF=jf~jPdsPH9S1)`N+XrB6g~P09@i^$K#IU|^P5?Z8k)7*7q8!@PHxn{qFBx1Ge zxs+KN&Vw$Rr{7cW;GJiWhkJTwd;)uOBPe=COlQW)|733E@z!PX+Htu@=+Spncv2Bz z_+@2oCUktk0qEEy(g%#wPUP$AO4B^89-Pnc-Z=u3PL-#RdTPErv|7RBtxqfs3q9BWnF^DDiAgSp9gRX;Tl)`UEqOP6ZN z?O631?#L5k3X|~-XYE0z0rIM~>~}Z3Ck;(>&eK;O_guO~cg64q+3RF9#96HwoHss!}M7`tNwyJW95luw~c*%mlb;$dBt3s;iuO*f51t zcWOjM9m_=Jw`Z8k#l2&OivOwayMRK<8_fg!VF!Ax_B%{|(*?kUKCkz~R%)rA|MLP!vHzz6b<>FP??Xf-L_OH)Wtx(js8c5PP<_n1 zLQ4{a{N9JF5B^p6O9PkYu_*iCA_1boH4It5RA{WJ2!7P)48aVHmfk$VWO#h0PLKN7 zEV6UoDQ0BIY&}hCHP{<I^KYMAFlm3=X zUY(P^YFO5XL0aFt#|cnODCPf*38cXY1yu$Y5*p$5KYc+*8Rw2hMvN1$QjnclPPLVr zu-EKnO56JPpa!$^)c>iL_3}qc1^V+5B5Mab2Rfwwi$RF6U;;lWQopZE59{g=8*@mA zv>ZQb{ar}pr|m(IgYq^JoF7>y=eGMHk3JK1%S+ikA54*IL~vEYEvg9fAj%9!#NFA? z;}HVmeAk-!KkW%iy<_xvv(6{*;og;45BN#%+xHjR5NxLu&h;CA%8gQPhtheV!mj#W z4S;gurlQFvs#vD9BqQ20D%$|8?*c|o;0@hL{HMI7+)CEN%EGJXR9^dDT zn1Eo`o`HptTpm&Bq-HD*8fP|r7@lHh)T6g))A(;+4h&v_pDec#k1it0KB(B`dA9G5 z^1Ba|T#j;iF!pk%y+@=KK(Rx)qpl}V&P4}jO52C4RNaDp!y*c230_S@53W!+XS^`4 zjG8BQ)rhMco!lPx@;hQl`QQH?{^M1fE?DdUFinp|Vi|mc((p1{`)hk`ZTu@&%=3~H zl6YGE&o97_X}g8C>zf7Hf`*S>EekpH$s}sKkdN+sC2~(`B1JbOHDWniW~=J(+(fFP zJ+@3%#RaUNNg`fI_@Rw_6_M67lmnTCzAWPO^Ni7hV#6Rc_cD75hXEsz^tmx(np|C* z4}Fq4S+!aq6F#>%rc>OY@&7AJWr(8*Cvuk}Pux&0&G;iJB zemaUdtRid9PS2`h!8R2ex>7oz&Ix%fl7@^CMhl5dmBEVl&drC+SnZ7y9t*(}4iyUHaDN?9@1la#9HK{{BzB)NeWl zTIG(YOx93R{F8eWqU2e_K*&HXy(6ldox-kV9uEzWT$Okd$jh&Gk|c@&&yf zuhEH?o0Q5a8oP#FBT)3hrfS3vAnhRdQMlQl9zI-Lto7zCnmWKugIP57GjO<(dz8H1^-WXd^czzKb0LWO=&=2`_z%oK3Ly z5QORViU7)U-(IO-H(GO(JO{jF<9X14m9ZhY$)(IYEVCU3Kf`0%VQyxx`X->Y^DNz> zbnWV>(vD9}ON1gvO)HabFz*@U!uNByj$fQqrif@jMYn7wgD^)PTBYK5$geL+-8|v- zi?tS}1)UF$+)#GsVq|%_4Ln0yN?ua&!{hbV))(F)kQytB@{tTT(or>4R+0)_{d=O! zDpyU841-9q$*`nv2(RyE$#%LERWQ53iVpAnm$3cU3S8T;PbXNOkLNQqY$%GTHM=)B z>y2P8tMuI_7<)B1XAXWg=i<3dwh{`;!`DoZvR$TA^sW{);fml7!4|TXkjkap&Q+)C z?q@p8cUE=;q4H^m_|3lf#>PgLVew%$&2{HVC`jo04#YoJ4?egv7?RRu-dSI}@Ev8! zTOPm@SKIs<`@EyP+4!2t>PyjN1DUgQJEcx@ki|z@^JoRHVffd+A zSoQ?8sB|pd{;x?U43P2Te?Vs!tHy(B-TBLN3{Wx>(x*;rjMWUFDy8ZeuMtvxv#Vp~ zGYCVNSAYo>xR8LK+T3r!YMeEO7tSRetrBg^h^_DO1N+P{cUO$JEDTVpOM!qLI05CX zlg-vsTEM?k=h@S}WnBsk>1)`GlAGBaskJiY20Vg+c~gDw<8gA>dG2~%F`)KIsy}jV zx@(oUfQ}bO@TYd;?*VpF0`euTF1D1o3HWmF0rP*(;kDC}i*9ynx_wk7<14=8fxqP; zVKDdpoi;-1;ins=xN;DZMP; zU>eK6bt~>-VO@^OQzJJ%^zFZRjQJoH#v)Q2k>Biuw&cho#%bGsxlV5FCc>@zZ}&@< zMMxHD`%S4D|096$Z}GV%@=up2I^9$(ztEV4?>`#DYgBCLxfy_a+-cQxKah-GAQJv{g zDlxVT3o>C~@M*r?ltaYM7Zrsj8>x%$>JC<$?u1U>ps$jeUY({NzoY}{GTh1dSAza5 zQ^mOWVyYDIKL+*tW$3s;hwKPG$h<)jSf0w)KBa3 zW^pw<@ehay@wN%R%E0h>+RxqpRVWKWM=pbv!6=Li-?t6*9K&f*hxY&J?|A3wf8puU zE&~}zT^r-~;hEKV&u*EfyYPPPzKnj#J|3%pdbWVNTb8u{g|3JEM^Zb52RnsRu?2Z? zV_l=_AcMu>R;@}Tc}JmiZbiOqIn?o%homOA->xd%_p~JqDB=Va!{=EDFQ>YN{eC;M z<@{&(!|Q2XLObu^Len}8?CB5RoE_Qi3tF$JWZ9JWKxA_V-ddDJ`_!0!+v+(M9^>J7 z;OZvOoc0tr4D&9}{Egg(w-zHmyOE4IspRW2+az-XQk-3#_}&xDfF@`9kk0)E^;K7x z*BEm6DTYbEr7Y)Vq57&g5*Ku;1kt@I)V=pce2=mOc=`DOy~XTs`|-{bW9Hu#uB&GP zuI&cv^O6IgGd2Mu4CjF$nP)xX%0`CHU&`w$I)5+NI5{&s5cC2_YkGPZ*-+)=7;gTi zRPQh>0&aKWn=d+yvie5HV%6;oC4vWN80Jlhz^TSNQTR~yW$j$f(6#rHOOl=vJzukF z7O%KR0-rTT6{4p!5YRC^KU`jB{|G zQY=?Qog3kL^*r3nhv2Vmh*+BP5d?d#hCnis#;7Y$!b7-C#!LB_E2eIG^(R8;JHl(W zn2fn#_K)f`4Zdvi2K@tufG?z9Bw+Z8I0T;?y|e?ObG5b=jHuxofdB#FIAHgdyW*!qU5I<;Xnz1xxFnvGT*4QC&eJO>>}+odDlcy9RxoY4(O{TL=HatcZm2o&*1FYP z*Cb~fjDq-pyq|is&QF&KELK1`0W;7jxDFYuBAOxR)34d8M?PJfFC8iorl*c1DMjby zeBAni1BR)tC|Ap5B77CSe0y^gZlp@n#_sw)fiEOchVs$tJg;J;+gOBAE&RhFtr=~R zo3$5N^zJoATR=urJL`>$U}D)t#rop+-Fh3yz_WMfiUp>Trn&u_Q=&&m#;o1idox?I z%OVwP&%Hy$vkk55sN>T&bHls7NO#Lb1;fKOwVIkY-bc<9w`k@tx=; zpXvflnYHQZ0VpT+@9Kc%M_F-ury7J>)$hW-L0ih#XNFwG;QJUkgA-UC71QL7<)qFn-&X z_F6&zhPlBRQ#1uFF0$%*H?{@ zKLIORdRfM|t)Y`DL_Jr@e%XJErDC<#AL9rH5$aOzUBA(^=B6QsIH~5%sr!x@gBEf} zWG*!)H;9%|n*YYeVsQr`xta zNz7kO21!lyPc&uYOuNhb@VqOi6VW)mlIunH%Qi}7B~?VbWFm7R<*Gk2Id3et^VQ+w z+K~^4P7x536X_6bOx|UPQhP_%=14S)_3(A`cZ5uj47T6M1n1IrY;s44&=TiauY3J{ zw(1`QTOV2wO_f`ldm?6G2$9tD8_|{E^VN6!_f;@Hw4!T)x3BOipF!Q< z5?Q3G{SGo{IqUM1FO&q*>fV05nsy}vwoTRg}5AXNu#h9&AjAQ{JB#a2VssRsd_KZ$3ow1cdT_t=QK zAAgnMr&a4tzWYFhsNIJjy{;MGy;fbP%sJnzMCI~)h_Y*N zYd(|_?0Qx{x#Q(BE8HI&^>p4acgj9qB9WwfB1o4YG@M1A`5yzju%KBQCweX}*7E#{ zcR{n{6ABu{VaX8^~*?=+&mhMUg`O zmxcT?rL!+iv1Q{nd@jDHZ_x3be-Dm}RVixsVs8qGX5askec#3+bYhF%HOz$9$QZ3lwKkPfNIJxm`rhh(OZZrBw{tdCyN!#jdnhoodvk3<(eKBL6 z4#_P$B8HK!xE2_l`z2wKsEtu*W405Gv5MdIq#}QMv2yI=P1!>c7Ch|*TUgE|vVW&T zD{87|WgLF_>z@t_ffUz&g?tO6Nyy5dpM?@K?ndb3jE<}KNp2@S-u&(t_ePuTim?YH zl+dp=%)iH0?*qpChf)8PQGI{%_yLtX}36CGOY!1SLT znsE^Y*S!oRZWi}RG1*H{lLO1Iob4(zGs*t9P&gWs@osJ|rBfYO^e-umdL8*2lh;c` zZ%9h;JS7rpHIjS{_`}|KhV`2&y?XfE>)YkKiY`W8% zSyCdenl1yc_cy8GkF$EyYn>Iwx4XY|UM4PKfmZ2z_`(Hiw%sDv8$4Wc!ilEI8)oTy zwM^x$t0F+@b_P|UQkKwDH&at&Z?Wz6 zp0#hHt-gumEVv->&rK{lmq<+IgD?ie_8wsN^8diIs@TbA?bKbGP0Z(_x3)#y(q&}ygv4JdG7A1s~jRjh{6498BCemRUBDb z5!oQHDs^9u0&SR%QtPKiV2&R8_1kWf5QznkI%E2QMZ;QjRhV)T(!GT4Rr(Ej^>*t? zlVOATZvTqc2q-rS9kh_p`$Fdf&I`z>&|}z?P0CNMj+L0}7*2kW7rT83yht>DdH6>} z&De>qguWx?t} zh1R@DlmFX9sJLilGKdA`(rKpMExLfpWuAK&E-a8};BxNPD9x4XuQL=8z&tP1-%>w? zq|CzWDj9a0tzaWvH>-#9z00Ak4wDhAeB1og%U7y41L-cseDg0aR?L zcE7N?(D{0mJ{!ynPcZC5O+D_ISA*&Y@A+9wZ;ra^5IlB1 z4%=m7EapL^0e_APNj3+*OwDT8JT+y-IJ|Z8Al@7pcB39Zh1A>+&IyT76_?Cigi%IP(HB&UsZE#a&u;}5FNntazS=!FccL$d9Z-ePZti9rEB{t9Q%n^oPntp+p zXsm_~a?p)p21Jb+oGPgBmQRV*txoiU8&0FU~*uHaSOmj??e+Z zBAHzH{9xTo`Z=y&)Z_1B$*EWGVJ%#|)a`rwBoK0Rdu0dTe{3yr^W$a$fB%rd4gDsj zBaY0t%DO|>_O+0|I_OF+tA@{Pjl0}r>a*3VT^f(ituuK~qPL31cR@e!&zj)j_F4V! zK|_7^%|d!5%=x!)fdP1+`wsYBa!E<8k{YWU-Ag<{j3O+mLH|Xr6`1@BiZ!`C**^rM zC~I}xph27aLj~&5Al0XO$kLzrTO_CVPEo~uT^4B})WLHjX~0u3G>A8ECM+7ml8#mz zXwM9qh&<1kJ(-Yp;OX&h%9_eZ4{%8xpy`E0S+m-V;NSmu1pQi0Qq5D#5f6?Y?*;Yl z@d2nXSm;5(H_WN__M%ZauJQcLq4=>&Zu$*G>$9O{Um2yOjy7(61Q);vcSwZ(&|?si zzhn4u+cItNtKT1xH7{EI(2Nvox0tT#Vi{Z6Vaw-$c3=rB`AHvHl4qcZp2$7oSx`&k zN%;XsZfn-hs>^GmvYCNTykk_!NN)ANibDspVR(D4AmE7h=9k?{zPzgBxF{HKBla<+ zwBrPNH#w5jkFr|_(N<+8z^%_YSfuA3I@euSyks~aiKj+gt8?(({&e4swQ1@NATz#`kZK%q0%>7N2o?E*to)0Bocf)DmmIi;$z7^XlC?51zQ-qSywcPd=tbe zh!gghOhBoF^jPhWm#<%A1ve`r)%G8(PDjJV4woQT*HvjXw}x*Mxfi86ZR2ApmVRtd zjDI!aX87Re`=Lq|eg7p*pPSKHNIO%d_~^s! z8ML$Fl8QDLpP!^rUVHSR^+Sz!MMns?2~mCmNK}9IlWsS^piJ_N!jfg#-}t&pe98fo zpYaUjk_P@*4l&PV^q19fjYVPRo?7;$N?O4`bqUju4z?Q=rQT z!`F@JJ2bSIm7u!6)-7F2*it&)a7;URcxmx6T7Xz>yhb=$Ic^yhgS>GfAjA?K^R<`O zN*(}oBY~qZ|#Hl^#Js{91OKXU=8 zCl0Qwrj~vBd)OSO$0N48Y8A+{df--U9Kyf(FEOX>FM)fMY#J)!(DNSZnL?$JdJJTS zbS^0V=iNHSnRbcLCchUm$h}S(=kzsVrxiH~IvW`CDco0d`*G6#e$Yd`3?laFHqZZ6!kQoYh8t*ke`5w4ivgp3x>c6~S$>v%FZ4~bDR2U~Bf(1_S;vOv; zPOc2!vcyxrqb^+B%4;?T3^k7xLK}9QQ*Uz%kK{>m#i!9Wwr_K%Al-IgB;|||-Omg+P zJ=q-(TKtY(vcDi?3CfpYJW^ZnRbAyt$x%&CoP5zMzFJ}`A91Lfm!eF;ilS{*9lj;B z;iXu&R>FqKHRq_8S}sw-vatMUAtf_Nc#VIi_FkoP>OMa>A~T&A2-sZmJ3g3a&J80S zKE_G&rX`A7_EJzk4#}2wYYNr3=*?~_#+@zEwGGIjo}!qAYlJi7tj&F7^J_rX>>rX0 zozA4DwBX(v@QqXBP|n_>&SO`n5CVt>ccb4Zq;i*8Z(o2IjF$z9F3?JxHDX2~*S*W* ziOUlnO1@_nZuk|RIP6<)U$`l2NAA;G$oA+bb>Fx$!_e`2R^*ae8duorlTqZAbb_3N zK&hJO*=eFSILPFna=EQi#d=XhH8(6JUp*Ez3wpEceV5XrTB^a?2R`7lHvFfMTvJ0( z)Ow@x&&Ky2To&$4G%=V^;k(8aRde3WTa8tyRiJVZV+w+;!4*2RgO#IWC5fn{4vY;{ zZ4DaaxXxxf^!zOQ-$>AC-~U?m^Q+4R=THxcY7$Bz2%qOlZzz|YB(SM(lq`OdyJMIG z7dJCOh?ka(V6&dnvuW-}7Lyp|ohL2XV)PILmFE*ddUc@l|v68TY* zi(svA=c(=Sw>iWOtd3Hdd~ZkX!X}2Vn+(!8!YI6!jqMuqyH^+gEMRryo9Lp{Il3)6 zb=|9F8%=k3o>02y$u{N%j}ci}&b5%eJh~IOr0!d4|I|9e$}gHKZI^g}`o(FAxT!+Y znt6BAPseBKJzv5o*8J>8-lA{w_)SL{ewa&`(0VD9=jsr<1?HZ|SBo)>Q`llB9oPpZ zBezLKVdW>BHs}wu)n+w>yLV=9`Ipy- z7%0xVX(!45Z+;5t`6ck|I`Ex~469}CZ!KhglG*Mcu799 z`XozwrE&?%D+`r-XM}6Gr&b9YFUW&QMTt@=$D5lB*eCUP10$6h%jEB1y{MCcsvpdOo{_3mI1`NBX zBv?soz4}B3DP2-QFytsX}TRbse2)Xfz45S1)M7Kv~x@#NL%J`rX{8)y%;JE-x3k zzQ=m|;n9eu>qb!-&87mP{R4=V$;8q)ZLN=A$yK&4?(OaTcOQ?;iiO9kIWC^N#BLk0bj-HX z8w~3ibG0_}Ivb#8pTZ>IL;ITTE`!DQN}7_krnmh$nxl@oGVViH6lQCl?}yA)G=6+U z-J$2>%ATgS3WQy<8SWCXqd0TQ_rzdP8xRIBlX=s{OLXmX26-iX!1GO=4Sf_e^jMmIJIqt0`dsc#M@ zJwETjw4lh;+tDJy zqvt6SC*}=6{WHYO$S6b{+Jf{NjT6b$QY$7&kb0r+iBMljlwgmWppc*#h{SVCbYT#crJ%N2k_H!5Zxth5w8~lD2i=;@mFDRI760^Q*=**-v{a zOpT8;ussRUbJbUvV?TMU7a^+jsX?Dx`L;+I#&C-*7H7Yess#t@^L;GftDCb-4YOCu z=WyP;%1KZ$RA^kJKN1|BMEZ-Me-}fNeYR*U(X^b#JnBw;YHNuVvpl`=cdw3di?UVr zb;ir2hVNCBSF1VGQn>NBJmPzrNTNk7wHW-22cUPcqo>rVS}JMPus}?n`DwaKpS7g{ zo~42BtfJy_2+X~=?O4Z2!})EY$#3Z|5?hd`o>#pqKW7ib96Fj~;unO6-{AFHnUQP2*{J^hGhwOEFG_ z_!%YGLXHj|#E8MfF;>Uta6W&77sKXydrv*9pJd*7UUps%)$tF{_(IJar5Ch71aamB z;@7s&K(Q%bXF=yZ*_T>a%QfnHLN!dzvKLg?j3@K32|{4-~iGqXdV zoIv8SBdVMXS*nqsgY!~qP=Y@h>7gm9`G8-SH8m9Svc_Q%N?RjOjaE0T4Evev4y#_8 z{oQ>`g*~Vh=+y$=^I1ym=M13xkpg1CW%A$DT+;*S)AymVF-eCgd`O7~Bj@rU08HuN zs3;`IKjM<`E~i2Jt_>Y`l9qgczs{tE>w%GMq5JPwaw?tfhKKuE(TI;?bJZaeD>XMw zxs`TLZBNn z9IJn%{oy$+OiLqWlf+2yjeUAV)51jaePWDXN41#(mxi)=Uv>5D11(njBWd+S@e`QG z_d?+m@iH+Bv8S1!2rh{%<@*%@21-cidr2Ebo?)*$vM0CH3Igu3g=&UYCv&6rg)+CR zihmGuN!R zn{5+fjD30&fEXCkJS@Uf-!cuxT_d5xcaS*-v6n=rKNZl?bia6txpcdREid{DnQRlm zPHZht75V&9-%I2YffZ#-k89th!fzp{KnN;_c31S*SD@g=fJNJI=icWpnev(GOHQ=z zc#u4T(+VW|2_y=Y{G`?H2IaRJ*f*Prz^9O=EX1wr0*M;))|}=kvWxxhNcZ!Va2u&ZTL*nQ&wc{xjs{utAYB?` zUDx9!`F)pug1XX5K61QR_xiYH4v7o~6bW(ACJ-F&vDTZGEVewxS(dig-^v9dz6p2?J@8Jca=oqe<8 zo{xh3tAVK4oT`1#Z;YS*0@>4BBr{5t@{Xs2y-KOceHD9J8Wg4qC0ed^c~k1>@-#%g}xWYL~+ zB;3efpF-riIPu++LH4{w2PY3+?xe@0%1jYPlBTCeoky$U!14STNO5n%-CZ8WBL54f zpYtP(gS+k&>t1vKOd<9on&)Td*?lH&gJCZ^Q(M1`;krl^uv}rK*Fk|rC`$T#3JV3v zs(O<6u-C%}#PgcxBAq1GN@OGM zNf+#a89^735o~{;=J-Q==kIM}#y|FClIpfFn3iH$!AUM??D!8BLv_mC8b8+jT3wKH zFiMX>$40|tn_=!XQm-_E?~hA0?M6~rmyd?v9!CbdD6;ET&xKd$nVP0dbN zF=9rP=tqf#7a{}Ls?~utxz3(_vt8V1~^sX4iGRBXCed5ezRAQXAkkfas z&k^kFoT4R3+s#xHoK*Z7S9Htqn_F-K$2MtQ(H)$ zym2>{8dSblV#I*Z+K>|Mwn!5-VIcoRs(~&F{(wEzF!~$aR5$u!;$Zr$=OFo_?_p#14kXU}sZDjR>)hhXm`JAqX)QIlXuO zWSVov+hjuI)??y|;PqZNF9CH;iEPkf9B4<%^35lDy`IPh+7tuj=7)qQG7J-`@vGX%q?G*M8_m-vfce(+9z8vzqKse zZX2Q`czw3vqPxe%vF06RXsm!<)K*jd-91_@^MRMl=am_#D>vXUd(|k%glyVS@*MweYJNE@&4|H1-%31H@=3pmsbwk_a4`sMC znrZ$txU#MZ-Q93L_-uih(f@pvZhWGA;k(qY8+||Z_DoSCorFce8rhk`%ub^Fsgvt6 zFSBnfJy5-8-3uJTo=H}XSN}fyL=2|ScWSZjW}4x_0#>S09Qdr|Nes?`Zok3vT0(J> zL?bfV>}-RgwRoY4?7 zx|zF$w z5IYIA;?Uh?9ahDT*{=OeuCPjP>JG!e1v#1J>Q#f)sppSx0kP*d#AK6%TligHj{&;# zb3SzI_6eRr>c?AKwijildheHSvm_DO-Mgl%mA<*LoM+1FSIp{{61|6-_>a9Sn)W-L zG4x)~-NMui30n|`cs>HCMF4%ZbbGmu@(6SPW2t)v%*;Gn83$EHi>%zeM;<&ev|J^1q%@rw5sjn!1be?6klI)A=4~LGB|(SPP3f2+ zxjS}GCDqqGhN@jP)oP6-o$k|4|3)HXsVKMXt$P;uGRD;~2yQGAc_E8B0TzF+4ZZpV zOIgVYKYAIeN`u<`J~toNR6nI&1GRp*R9oeoDka9{TaVCvv=_<33ADL8MUM|^js6tY zP16uo)ULXe50*AnPep6FQjK7uOEml)5}!{afUj%M!DN}Wn7I9#AzrpxxtRDGe(N#O z)$N7yb^<0;fkI#hErwwKTYw6r@{J7DQpw?ff9dy$#r(cTqw}hPTn*O#40^G;%3P>z ze(f7%j!44E*>ahvfP$rt!>NWVbNuNO(`dveR_~iz=%``uhtp3!zqDqbdFUs(nxAEN zq(QW=l!9BJqLrn8*6L+(z!N-XYHf&^JoyrxBRJGKg`Rl1vE}{59!U zh&WT(xF_TYN_jltP%v#V3^z)_^vPQK$YLLVj*eg4Ldp4Q)pvA0X#t3hf&9|JXd}b` zI0jxe^`)-aS_B#Y^TVLA*ZV(q4bax@GH%2h65lF7k7Bk>5C%HapoihQh3_iR7&(Y8rIx16n{Lymy=V;=@?!$}+}!*rB;I^S za-ZO$W=Df92$9@pVM(4{CoYzDn?G*(F3aTHhlks7$$je=4Ny`%gSd0Qffew)`@B0Y z|GRwLzof`^%o{YXSo`bHHYZ=WilS1xj4wCaL5t z4Ee=7YN~8WO}`$UD5e(A5riLc^hBqA6kjCMjNx{!s?O5dZK2f)s}z!@o9m}p%5-sj zziiBXBv7+p$)vt(`+}T@K5e;H5aOa-v&F}9Zuq*DkA;=|U;ArF?`8LNMUfWKa}aCK zBT_Er;ZT7oeree7&VV~sI2W%BP;;E*orjSMI**i%gC=r@r0Bh-pAr7e1;&a4 z@h!5mCgP)dx2W>F`_IB`CWJ?`vjQ8E7C^Q;N z$zv0P&+uRBRU>7%%XR}e^6lykb@OmHJ4u(ql*(DgyF@tm0}1Fn&&K!%x4KYo_1*6) z-%>XE3S6h6LuKRcIbGKU9uC2@#C46oleX^juXrJ}&|bNJU#X26CSB8CpS{0&Rv*6J z_z*W%rVGnf0dm9Jm&}dbLJ~#o$F?p+SCxet=$t-3|x>Zlrf2H>o4ObT+1fW3z>{Vn8@>_BrzQ!t2 z?Q08M*{o>XLpwwj_?5)C~@Qd!!GCEAGriWfcO zZ7e&WANdb)D19OJan-Ka{omssT)q0)*ZjV7Y4I5er6`NdcCn{aeOj#C{s1-L4ALh% z^~zbN%u#=pY|WhAf5k{ zpxm}91!17L1C)O*Uq(*5?w_=9`Ey$%QC!4@4Em=rsPe5tlz6kgUeC}rNw#+P9o6%H z;fGEo+2%yr&rIYPv|mq+;1zqb2#n{h)_y2omwBvyZLGV!DRbr@;nzg8K%_y{c*pkj z9|ELiehGOL(^U@S^7hWq-0=InV%TiqHfd)*0ppA zwlvSu%@9^Bl{nrv+kQxl+3+fXHHZ!B5!P=~l?{u~*_7F>YYwaqPNgUp$_Q@Os?tT! zu8e{=zXw-il3X5FIcLaIdO6oE4)|j>`I_(raqBMVvZt^f1-mlrEfg_NETq~rc5c2* zHMM5jxVXcjg<(kBZa>oO#HvZCA1eE(@pb#N&u3YgA?w<*`91}D2M`el!Vsq}nh&H1%U)tN^h& zX`)>!!=}(O-W-{i_2ip!Lvr>LA37}Eh{_TV_s?gB{LIMAG@-fsV+ zj+Oe{OGE|K>c=cT55fZg6%P1TtVLJR=`mw372dlB(_krQT5Jo#U&4*xhBnafI^n49 z_ZOnN%bES^Uh1P8V%bSZW$3rV8v&8;=~B(9Z%mcXA>dxM1a+?hjMkwyE2Qk!jIEEp zWLY`JryDnLmE)h0oA6FH_ew-WM)fL#+G?h#BX74NG;G=u8h#!^5 zwvLZHJs0QkpBo}f4eCscr>?PUDnp5n3hGD%YACTQg}avUC=7G4AT5*Ya+Ryo*gAB+ zUC!kuF2iXiLUmiJfn7ncwrz}Y@>R%2mffXr5=9CECCESL<$rMK?r&gqE(#V_8Xqp> ztJ8Uo8K0~ofGLaBVSNDdV(ogM&Cfy-dX5N@5(oVisr+cl>p>4&a>s`Sc{qaRs%dgc znfb$L;SGU@*?4s8fscq%jUy-V${|RbnTjTfypGC=t#+w6(Zi-c)-%kR|Hynev zwGz66bz2)GlXWTV)7V@MKtuL*;sKi_i;n!bZUQew5sdB++otkDC2}FSaU2o5x*$7o zV~HG9GT2@T#XQ7{!x_GAB60pi6z*&EC?;Cu-cE8(DLfZK?+V0ZT}~oHlc~kYhF980SX5IcO#bFC4}shQo=# zy}Fi)N;H<8Qz?wm_tW0WOqxRaC<4@L77~G8ATGGpZhv6-%|;xc)4Ej6d+e?`^5tEe z>ZB=9UTNU;mSb01Ao7{51+qtwOuoT8^^MusO!K_PTr4r!4d%Oh(BjdM zK>!hUXjyBg8xGC)EN3%5)(|n8JvLPQ$&)oW5N9ZP_(B`{`ncVQBEcXbq{vCjRUPyy*4fB(q+JN2bzeuETHYo3wW@ z%U@VYrvnmtp!SIVC2xOD4UZ)DR1!J^TgEUg8FA*eo4)?~DHKZlCHO zzs0yKl_VDE0|SF{lgRs zqP#Ky%mKmd)#Q)v>FL-XHh)|6b2~M(etvCrvd#isf#uP*U@U+#)tQ^&O3GE#wgMRvGWzK>S@mnJjaj@I*dvjW2r5?9MXXAd|7k zk*f|?X|%3MSY1tA$UTqw;-|t+!0RYd_Yk}83VXz?8x7nBCJQ|8|8?QNv0q(m_e7WZ zB8T!Or;$QkESmDYh~i$NTz$*4IV9`1(!(#AZD}-Lk_hwzQ~S0`P-Cr z-#tV&Z8+j^6TQU0nXW3UhYfz)z9d5@<;r4eAVLS9k*mJ}Ne=yPfE>D{meZsyF;t%u znw@{9fyY+MQ15B(R!Z=dap)u!dLvjiB*RZZ7kBn28tA{bLvkM-_A1kj#{)D z<_G>F=eb$`-EEuI&!fr$`mbkY*=fc(fSQgpPqs0Zd;nfxmZZi~SIXB70GdDxE1`eO zM=egzHt|a@$XO2&9q>u-VXNc!A;{k3>&PDij`!spe&9cYzinB>7D?(WOC6v9@Ed$Ji0cUq+@t=v=4r1y*vDvA3H-(QL#EAZMM2KcUP{g^yKg` z@36&r}Xaw&LqZvRwEC5*0U2RIpKDSFc`oNP7EctcR?&v@V5YdfXX$OiLy&5 zKDx~Dbxwp%YfyC*)&V0Lot?}0H6V2bEFgevV7kHlUV9SXfagbifQ1-Z@(4q2lX&Xj z*ELi^Gcdq0qe+!rFBSfo5~A5A6~TMjTO<0nN}L`qlxMg|@V<7Z2_%m)4bG13r7Bpju}-gINy~`NduoefL+5$!`1MXvRreEqj9_jfm+SZ? zRcfe#c!QNzgWi0p{V=p0&Ceu6TW9#z_SDKi#~6BNN-a)xr>Df8;pC#dp$1VM0--d> z(6Kj3m9hQkK4_t4`cZ~M=do!MZ#W`bb#{juwHZ2PmpEld$-A*s!uh#y3D>N6Immi} z!rS^3UlEYYZ&b{{Xl2)KJ~j2+;=<%LxtYR_e&ktGG(v#6{tr{V=`BojP5xl){vqX) z&rLL%5)Jg0GI;y-(fTh8jPIa#UJZznf27wKyP6r6-X^2eI5yMSzISJ$yc0*&?C?M% zl3x?E((uwu;5@^90zkQ#kuKR$J9luLHDlXpzNGl$ z90I#IkzEF=zrZ-9<*Ute_e??fIMNPufhP+d6hi(2Vt6#|hl+#0xKU43$tf2a$5htzaF)0OZ(YnQH9fw!`FCdOiQ4Yog}-7LfqE z(MZVk5z3>DPc`%)Fm`{kd&#!#imR;7jXg}u6;+9lav^y9P--A@`*+Yify96cWfX}y zDX9EpY1Ht)8%1I37kOUPq=ktf=d*Hzawu0Xpt2!S&_)$91MI|+gIbK?llCVPKOdOoJ_B+VHEk(jQ zaRl1YQ{DAXHLNLv2!O(FFgIdk=By8$D}UIr7}_5G4zRo#WvGj%CJ8hJ5CQNb3wYL5{8 z*GcIzJyYb2f;fdSUfUK!(X1>xm+9ESIsVSeZH6qDGbEX1oJWpnk*IQBbn)(P_QhBK ztxt&~2aPA?$`dW@2y!rW^_9Z0eKDLlezWR#g9P&hL}9?g`5K(H#JX_|S-y3$8`a{& zfeT2i5DYCiRVv|jrXHiHU0*7Bhxwa96@%6@c$eQ9At`{7Yh247jJ6wb5~C)!mO}h?o>0r`zeuC_NDs@U!8Z6;{0gsf4l~!I zbRD8^_4hNC0?X-&aR{hz8fd!Xo*Lu}`P=5#kE*#F5Wr)v0%hu4^p{?H&Gb0HrN7%J zOHOQ4MTwh+W)Q$^s&ia+dPgMy$x&PIDU-*UE~3ldDeLxID&9UPbFXM>zLn;fdZ&9cEhedu|8qk5(hrsiXuWn2=R!1a2L%Z$|1Br8vyxH^eM^}gQg3HCkXvA!Fi z(;fFtBi2}z!X6OjM#QELZ z(+X+djH|El7@S*;|DkqZI#+Gy+s7lQhjS0Y0h3lIpyUxUA9)Fy98$OgfHEIvB&O5* zP=z@lTbkY7E(*Wtv8s$MHz+%9#V}oJXJRa zb(R4+aNIy9c+rqK%Jn=_38lrF!(R{ysvlW}SH=?i0tSay`~J3PS~8_W&TR`=vZ7O( znUeN-xZJ4TzGN!$(em}nW+a7l()5kHQ?A~a9*KLxV7WxGP`WY64fYN0n5HFgiN59Z zgGNiJce&*5snR!0M8T=xiGf?G!d~u$CB3^p&fgu~WzXRM>1B-)b|9Vg;SL+rhf)2A zmx)aGF#=8|G1l;mFuUEWc0-Fg&%`6M(xYCSPO(CiFfgfY?S5m ziB~KSp>MC1|fK7|JzPpch$mbqVl!(FV0- zq@i|;Q2RV(#b#EnE5*9O%Zbqe(KXlK22+_~EOWey{4%K3ad-_vukMuyfFh-0LdU03bn%jRWK>ucQ^Q5}!jbS5cj{*J4Mek1hBoXVI1S)o|5g zmuXMh>4LIXmrr*m{Mjy1H3Fk2Oo>t%9V_h6L?c+59t-H(y+uG^O$U zHun^zC2J|hjw?SCO5|}^iHdA2hTxaU#|1ritalPX!3t$y zUz461x=Ib!-?oX#@pdo_abK<0LN=#H|nx; zT4eds`%ARKrJ$svt#U#B5^iGQM)LbvY4lYw2|7We#0DbziNv=MatMFhL|h#>Ncn9S`Px;OG%s|Mq%E!6EdibRR@?yJ2*UeY ziuS{Yw4Zg9BZs~^Pdv|CW{N>hDpfv$1aef6Pk?XYp0G?36aKaV9VV2_zZn3_qfWUj zwY3i@_O|};&Gdp<_m-`}At&{z4v7<%i4(Pcfm4!{&f!$i|JC`6U;ius8WsRvLdpHt ze)NxtApemI_ry!_1ZN$G%D3|0hj^-<#Sc7FUA+l1vSIIi%auG!MhGLyi1S&@JtT#e!KS-pflQ( zqf$tG5YCs>qBgMNr&I}yHLQT*ffl`8qYF$C#H^qRpw9=?a?cw^0r)*mLahUn!W3Pu ztxclG5D?!dv^)feg4-M70bShYvAu3K!=hdbFf_mC3)TAaL24&&RaDpHyOFmzxe4BP zsZ?TXsZb;RAb|_ftVWHY00(^})8(95q(dj@su%DY+}`@_rV>_ZlbPdDBxbFs3G2x} zfJtxt-uKt}fs=K)MSNaxuW8+N@Esn|O6(<>8jg5ExzHO>$s)^BGaaQj_Yr!aLH=MS zj$T16v6);Tg20S-KVGJxrtq@o1wv#eXA?uc`OSW1O1dcRYJ!^YTXzz4qtg#EUiJP& zn#a#q92&=q|6F!T))!I4uo&zew$vLLWG!#Mmut!~f4krjvp`?&#jNnDE_V!<9{l#o zyKlvAf^Y(@nCh`#s{YUZ>Si@CrO^YrCyK7yW%@4)8v|aE+hJBFZWD@BS%;aodS(87 z4@y)7%NhMfkMX8AL#O$UTG=;WkApBF3`v-q`%&VH0 ze$qeFTy`@1d`evBQJ(&<$iZP2l>51-fR36T!R+kFnW)X!pNF?g-Zujl39W+N0wSVGAgF1@zd-WPziyCZM6doUdT7hXR@M`>L@o@C?riqdDr zft7DIQhgrpPSW-BJc_7d|J?vzsAuQ?NtbAhDi<+bFHLq^Z1b^QihLSyJ=o-rVL}vH zAxIO7LKK{gGCQ<)czL~I+&r-Pw9(;v@FMjG;HLFyMh(~wxTwEhR*sMN6-ab+s;pkL zm5%8vz9Q@sD2I1}03pP+_yI7bPX2U8Rht3~yWRp^ZRk@Gb7#!hKh8aSPvq+a!WXFD zo%KXJ-7A1Z#L8U2Xi9YoDBU0N^>kfD-rNWDn_q>8Jf{hO{c5iNLAm-A3*CTl0kWim zfl?3?03b);l&uMbN7(Tc`}U||SIJL6kLO&aeDbiV6qHtq8(`slUOkf;jgSHI!W%k* zE^6!JnMc&dy9oeUDB#VzGNhN#Z*6)RyOd(ybF$%;?d|uw4g7C&-L|eduPQpH(8NU~2z}nx^vBN&Sd)SUoyQ zBTM~ptHBEn$&Ibre&_Ailq*W#0{o=<1E+iw*Rty9c$l|z_dW!4@We)Z+@fKE zr>Yx9cr|)YER$$T7?w{LZNky}5*6v7*De-0u_|OiF%&2OVW-%f>Nz(CPEy0h1Jc#zlj&vm(1{rNi}i)M2P1DRZs=C`7_zqd#JQSVz< zQ;4I1%m33Tb5vC8vl6SZVvxVcEqWKKUpjY3*^ZlQE}nj-g#!qTUfI1G^Q(Osr)lGK z_93yci%&%*<{EjW7{oc?>j0`cYprz(;O_&Va-d~8{N<7Ovd`luWX~Ccw8v=)hP!Zh z0Nck?JqEy+G5!HpE8pNQ!)-HocMz~EqIZS?K@|K?)iwi2?y?k+5z=`OkQ!DhiYx;1 zB;lo;ZB0IM)3jvFJk*HCw;5r64^ZJHo+|-IdH~M+*jj*_EO?v;hKx_-;v@Iw2#K5# z9&NJ?=5j%(vBElEL?x7t#jBNl9&P9y|L?4i?{n{~&zu1v^#7)w1*5QyctVE>H}5XB zk~Q)YC;pgI$_F=IvR-%G0tG~sfMFG}Yhwfzws{JMn{IV)(7*V{P=2|X16>($^m2GH z2zW|r*NV)B-ZaiCG#SFk9on9k0zH-qBP}h=sp@ckcP@@8tX^X4_xCGJcJdEnraj%3 zI!oeWyl6(^x-9UW4?J7Zr%g<$qrBs4uQVTRf}_WL6^|R6@ilZ-n8!{}8E#9ZIea|O zPV=(L8m+>t(}aoUQ$BHfI{jWYjT1H=uMbM(4l9{uVvT!OT^+hdAxlpaNcH|46+f}5 zJTcU%X0jRilf_o&#Xp`hS`gCuFpSNI&CkDM%Dgb=KqqKIJ+a^tCvEe{umhrgWJx!i zLHPNmi9%j$xH@RcSBTsK!(hBeO~;BFW|aUgnjlV;q~IA-UVq70n){ZET$9vcYu1Cg zZA?y=_vH>|DowCfZFQ1u7ed?oEEnhcW7}h#oda#TX1(PZpBJ*D^h|>a4!TY zUV=k$clZDH`QCqq8FEP`lN-)HXYIAt-dm@e2iJT`WL_iCF!tW2*!A!;ulr=YpNl)w zEKi!`Xf)I|I5zulmBKSc%TmMV%zY@?HsCHinWGvN?VGW?Smg`lb+(ZX+{hm-Q>OeZ zn#=f8pF2`m&DOi(Cns&g)MBB}BXLH*bWBpePCk$Otb^my$`pW+FblR4a1ALg(0TjVTpRDU17y{(xC$6soCNnQ{O;*ppQV{m` zSc$4od(_Y=&F$A`UZ4sTLiJ<;PImG`?|8Syd`*kk&7ubJhI4C*WpCvOT8ka$(aiBq z`3!gZcGAHr(2M}EDv;0fld`|Qo-#Fn^6ReqY44TiMoM#$o84drTp%r!^vrtcCKgY&@H(d2ncIqhuOok`Jm&7$v z6KbyaEv|h_J9944Ji-39JFmOzIDwz5bv{+IA1Jp!_u1XdK2P`Fnmaw{xIVvS%WH6# zx2hviTZm^-&a?#Z<=m&Y3umE~yk&$_zM2t3gHW?jyx| zaGt|ndeWrtIfHt^wHA!Px98VQZWg8U!}l;Rp~yR7YwDb8C&S$E?T6AOpKZ7De3l>{ z^FmCG@o?}3DtcsaS2nM4KBm@qxcwhB*`I<5r%Pn>6oMhOMPnP(GW%`ZapzEsJ9fmA zMu~#M8km7uyEbS#q?K=TW{B)^KPP;hT|`s-ri_tv^`=ty#01;~{+mr&7Q|Z5uP;-Ho@O1`6)d$Y$iwt+#*AB(MN@K*-~rn=#6Qd8na zKjuYejbA){i)H1YV&t(NeffPX)0&lMfg32kWhxj$JIb6oKpvu#OJPtgNc;TqyJE_Y zq#BXfgFUqtzBHLuNz&ryQI{3mkENq;4X@0^kR9ynofmJ3J!j$YpZ1!=sj++6PkKn> zi!$dz$)2zv2Q=1_S1}P>nF-%~L+qK8kJe2aV`4%@njG;!0aiH74YYt|2E?^D8uC1QoG* zkx&B5@eRQa(=Nn20MSg#`pt6zF$4XBrfG1)7C^04`Y`=0bl5oXMu>_biWw5j~%| ze`!c`;fb-N{HWcIw*QW+H6*zMk2a9qss2cseGw^E@{JwznJ|GrN5N;65I04`<$Vr6 z`iKVvKEZT9e&Em0jMHd`-{Zs5JP<|q+5Ok)AA<(CB-+@V35!M_X4=x4uO%Krx9guqbXvIw)zj*TRf1$n9!I#^j@a;<8nI< zzUa)oesQ#27fOkXTyVT=UO$H4?b6!MAQP!R@3tQ!MrC z$;a>TX#cGV`4Z&cbaEF|wlUS;x6>2t>IkluK95ckchv_>JVYct&&&)9@b*<(o=fre zMS~dN0=#L={A}^pW}7U`#o8rT0`w!WAz_gEin#qu)>SN$gDi+1T&wlVBKG@U=Ul`PlOVh7FGquM1Jm z;F3>pTsMCkBdEv&IrIPhML^To=Uzv*>2@c6RZjCO3$ zm=Gp!14;XMn*PCx^G|OV({Yj*;N#j(3$4`XIO=g5DG?7yEkI>|ImAqoo~xE0Fc(nL zmnM)L%j-VO7r*{#2zC}e5g;A_h8QCnj|4TDO*%5u6mt-|K3bM`zjvw|)HHOTtUPp9P;6TFWLp-WOJjVO^*$)Nz?9ttQ zaO(76(+22Zm}w%jMi-C%QMsIY%Y#yE$6K~0F&3Bh>z@mWpH}7;w|VS;Riaz;TDXfY z=%+|!GvX$o!0J@skEb7-5}3y4jUtO1aDB;AP*%7p;Hs4sHCa1-sWrlcVmjRNYtRx7 zXo5juaEx8o;To6iH;JYWYN+9XGg+6d@&Zx9HXcJ}sf{q^Z!MrhBXz+*wUrAIA4@cu z!?C5MFE3{t*|^%~cYJLHt)wZT*O;?A>Ayi+zI2bAG~3xAtwXtY#rXU`wv*zO{_Xe@ z>_721G8raf$}@*`zA+Ow^Q@ChGO5xyR($I6a&3-iC24vuPPoGxr@s`r?DKxmB-V-g zYm<=ETF1m;bnpTJ+sie}gkLtKQcS$jxH&TU@;v3V3!;M}Jx}3#+N(Y-aM|+-7i=H_ z*9sNrO13HJ@MEl(l7%z;TeVfN#RmVL0xj)D0?<@k@aro@u}4ik$VmWwFB2^_jv&#m zSNG%fVb}sT!0U?~qJ1wADP1Oo@->&HYO6ZbYt?SGl! zi8h<&x};=3E(NZ~$&B_oSNLW5EHo6D5?4I!B72+QXRY@n!xPQtQ7KpWP4*W7dV|86 z;h(TsHPpBE!2Ug3%1MLt+=OuK{rZ@T6Y=Xr4Ou<)4HK9d5qgxw)}}r(pt0Y^6xuOD zc|GdAOEepI2zfCZe!}fn!ANQ$v)K2O;YHg+3)lc=e&iC6U3mR*LCS1Ka3r=1%%56O=1&#@jWXQ0UR39~tK6%3gWCAFR}ZwR>%LS! zB0)_r_eZA6W3sJ(&$QgJl|?FsYG%5+4`(A|Em#(6Z12(Q;Dd5|6V+1EK5DPqRDgmEGNXy$3w^FL+C=% zvTVu@!%ntR1|%C}h3DvRt9mS`qhdq);l^Frh$N^%U-pT~`g)3dKLM>6esp|ZB$O$c zs3!pDZ8s=Maw}^{O!lfh&)vH_70D?Nd=}VAQ0|Klv;YP2c0|r>qKmcWX63DDqQDR& z9N?A>a)V{|4rps(xhNeDi`}T%7@$A^Phj)gz?o#1n?kRV&mE7nDeXH2N-6IfjAKP- zXGkkvQ!MPw)+`$ioolSeTR;B07a!W64GpPKC<^FcxjiN^aqDeS5(ELK&oJu(6GYTp zr8X4!g8G_Tq9#r4$&tfl<>MP(DSQ6i#=H%P_W5aNaYF-lnV#SWm$$aQ=74-VS5gRP z>l=8KUb>RM9h<0mg3n&W5jD5s_Ng5ZjlD7yj?itzp}y{FdgR-kG2IAA$M~`$_R|~h z{mq)teG1#K8Tj|REUM8VuKs>%Un!MhiCM{&k?WlaLCtMNn?I(qu$3xNpL;)PlJ~~% zpm5RA4))91J*nr8e1hSD=DE+JS?`<;bBouX;i87_#Xl~(g&-oWEvKgyO4Lkdr>#}r zom=#&c(f=1lV8k)T?3f4-}B);{F<`e?P2%Mn*Za9mGAp53MfrQiH z#T2r>J+~;Yf=B^_wXC$_^-j3-`vLOjO(W9nHm-h0SB-t;T|dm*kjg{>aVhQyNaZuB zABc$}^R8q16S2M4zii@(Y^|mM+j%9|YC89JeYBb5a7HL64|6+&tAEVJZ2c~Ti+n{} zxqxuBos&1HTwIzb=dQ(P_h!@Q*Yd3It|IXHY{5Ahw2*KARx*0ZMuu9BRgiEOM>VNR zmsuBQ!N5BJe|P2Nn0#|a?cbTL>y=f?;GyqT_=psb8ep^7eM<6R%hg+U3rSY`zkL{{ zko$OG#edv(&gXaIvkq8zwI=Pep8PhIE+2&Q2%Gw4UG;XAzA+E_`vmhMJ4~Tw zx@mg6z*?}>&uUCPQ~m8&cONf}6pF1Z9s!<(cXB(e@)QEiLu(fB`w*|u?c{K~LHmnr zm6&^z%iJ&9_CF^r$aw?rc6hjy40Vl52F8SBUnt|nkTJ!^EYq;O;Lhx1+-w%%gZdgu zG#=0+mN?BiEU`0j3EpLv**4zhC3jya@I+HJHh7+^{B3gQ%8b@rMfC~B?7j_H8qg41 z(i_sL#IPL?zqb!Ar8~5xy;Wlz1Hd;#Dqh6I`TD&Z3H?7vmB`>W0BvaC6cYM9nq5@9 z2+1Fs8$&?8G&89RqR{zgu6yGT9|KU|cvdUDDe|FV>V!sI8F}2B zflmgOoHk=>fqa%Pt@zY3BT|}vB~3uD;4u4Fc5Cma1wAp>gk^q65uRgw)U56^k>ubf zS9`g@?=Ww5x(tUKu&0Fps3{;$$A9X^s$!CI#jlmb2>v-Og1lNqmptOb29i=h~bhJ^}C&cmgO02A1 z+pN(07PkBxwF@Q55*zvK7|u^H?dx=~GS1HoW{wuqERi1~yp}Nb_<8R22Cw?X3H>%qrHjDaFl6mBqcFm;{Sxj-CM+z1a9p#C`Cd`RR1&VUlM6Nf0m-H>#8z}`)1I8?W01YwT=jxtjMg*u}3t=lg{2yZ&2;^%S( z1sY@6p`LYWvK=NHB#2W{Z$eh914(R>t8W&rj;L+dWj3twnKDMOFA-CT4j%pKM{-kq zzaOVRsIY(Tp1Fa>Tb^6;h81cw>9I?k_UC6pmESZAeoy<8s`xMWRQ#8F)?2>^fHwvP z*k+yT>Eh+%t&K8$$j$J_|F1t zYGLTWpd+$`a(OT~4vB1*uj|1#AntjJNaYNy6u9L@z^eQEfIfHi!YbYj#(KP#WhDHn ztKP^#tj^%eC0dUU&FnSGIAVr>-X7mlj)orhlG~NUR%hl)a)y?89lCsV0ZhVD~iue!pl^@&3%raJUVv$ot{YCj^I2rvD*QN^k$jC7UEn50~anl)M7wZt!t z%L9{p?U&0_Q#71dX6#5ldp9q8^Hs^Ox3PtGG=p?wu;b0TMl($)I61Z+0!X&6Ijudy zCJE1pp7#L5TK7mx-Q_ok)h3k6p*Bt^RyFdx=`l zvZ#*s!Mj>iaBS{&znG43Pm}R>Etjd4N`zbDFX1YPt?t6ijW8air?U*{;eFBtdi1H% z1>%vcxF)hix99j?LVR3Nhn;Vsz#3?@mdmzM0t5AQ!FNBlkSJ(6rxv$TgK(Kn?lVMP zIQg}3a!jqM-7cwhtSe?& zQm1GumzEFd5So~r5S@tCua=xFN%u+x|ACF&l%P3@sEqMyOU@b2(5e_?`Ga6qH@neu zg{OKm;b)4VUzSVX8%QR>0-*ylK3`9vYB>O}bEEl}s$H3#3x$0hcCX&vrF@CVD&}jl zG)G9HNA_tXz(mrX3(}l3*q{`?Db_x7vPdUT#rLvZnuOiTuf7o5gk}S)x zm?qG02ypqW@VG1%680lZc?#Gp@0t_AnJ}}b|Mt$>h4B3q)(ulmsl%{MwGL!XHRmYB zzc*zBQ~%MW^_F?Fi%*c6;h|?8Wjpm$Ek-E_5I)%$b}6wSwi{enW7=7{W>OV#^N(UM zaKDDmw)XZGmwOGMgT-Az&62WU%;)&(yK!)dZATKbUs}1aHn%8pQO};5d)Vg8D^8c)X64 z!Hf3BQ`hu!UxaD_?NdA1`EQ+_K9@FWKb*!CO|?hz&Qw11^*{pyB7F)G`vTEkr?w$)!oaJ)T#NOA#fsI0EYNbgFOImGJn z^WCG+T`}UC^NRC6+ws}89t9+AK0x{UJ*j8G%qPfa9Dm7QQp|`o^Le7!UEW3{y1L_J zq&0I@(hyA2JsP+i7}K!eh?Wk8VE4(BwEsnGFh8F_V-4 z#+Qp#KdwXl3@O$m%>2Wq-8z~|g?v3RgJt;;JN$BW!R#H$fH6#+_2TvSFx89G>aYxE z*i!HQi2U9NovmhCS{;i@lK4&K4DN$&4XR|~>sYc-)E1Qpn*KI2-4RbB)2a;#+H{mG zP*x>P0wwmd!>40n$p9(^D6wZX#9ml0Rv*#ge}_!vKaS_m7r=A<=o5T@`3c!#Oe0A+ z__doijx$-pqW`=2sr!ph;sahanWl!IsQZ$e6E8c)F>a;sg@xAUUx#aEn-o0gF(U}v|7(w{cjjh0L=BF zK@h(N%}Rj0D(Haav()s*M}-HgFl)vfr&AT)wNd%a zL?eNp7ir6jku6h0QrT?gi7R9raFyb1&jDXrKJU!0W~R_t+k8yk;~xL_8Yrgn1O;5T z=hIykq#Q?siX<}!BU}@{=&A}e40?&lYO~*tUkQ7GSDtZW9Xf`|V8(x2>)?Cp9NTE=kwU_&mRWSmPj#drU zB#gycg!SdqvFCY_)>kJn*=Aiv3sz=}$q>YvRe^W)_=2qU{!r2EL9K@T!@7wpjRG?@ zt3k9$c&3uu#g8pz3S}d7oxW=PW{V}xR=;a7#uiqaHfi&;sNBaVaI5(Z<2&)t7 z*xVNs*iY`4$8}?h-KB#s&+T&r$-ij%V+$XcTVE<*AqiTFFTAr3q%d^F$#HlTq0dbb zpGoqS{qGbJ@Q~{Q)>85g6a9$vkT5t(l4wP3===&~ZjYXocCAY86_42% z2NQy24<_&aV^0zPHuJxr)M6ME8jD>lG$C_oH=9#?ZMLL?REqkgFQ~fA6w-TFzs;b7 zA1Vyvyp`b}7OnR@C(HA-bc$mp>OKX(As9~CplXB+6$$H5wvWl4mvuGYsbtTtidEnR z{}mgt?68_de0UqlQCT9Fyxvft5i+}0vtB{ypY$mXf~VOAv8&``}& zF|cr2xz(t69qI)7b-`R{N*!;3M!0jUzyy;xnw_tPTa6_pAQ?H^ag7}ULKQ;ezF&$E zDy`MK@(A2MY1LXJdVhYYqa$m7dVk{j`oA6(uL`2CsaZrPy^dW%Bc6ErT(2Fsy86kx zy^l@rqUc@91c!e5O3wu>nO2hJj5zNTs5f7@jk1VRPFF9rK5%i}51OAm#Q*eD#hJ5J zeu!Obdl%=m*mHPc@@A~zZ&sSv3W)?3_8Te&y_Qi={OBdgUk=P6O8MfNg4XN1bVs#p zLxfj1N7IZ=R?~jO2(xDqwbs5&*1lk%hLS$DyQ%6fT@A2}H?0Pnov(jrFvp+}bX1g1 z9GdX|`@oi0^z*LC^nPReEk%Qhm0Vjo-FyJ)b`RI6B=JSZr$5i^s6V-r&T=g$c#$iI zE^U5^cN0a4={D&0>o>fQu=|^JIgJNgep)lkC=i~BgI0aIeXaAWm%!9+qAKpLiLw=P z*yw+~A3)lmBGpBZchTWDT`PsPFrcx(hP#=kX^%0fgbaS%*&zBJ4;<1<9=^J4!-rT z>V%X1Ge!WcQB3EAya-U;9O2G=N-s*QoF^CckD}(W?FM;}G#{Zbn2<7@a5#mAw>nsfmY+g2 zT0m&~n$JcA=v?n#k(t32!dD5&=Hf-^>d2|%`P1$b9Py>^pzA#;+cOX~wSV=$G0R$k zB0Ft1ZfXo87i)RH)#+~(_lvEj%1MEED*?WE6#eQRe;wNX6LO`n zJ#_ifz(3FC24nK3)3p#SXdbSe}rN{OsV9Udn2Im z!U1w*25I$6J2MMb=kj`VNz$yDV8XAL169me71%Ur-aS`-P zT9O`el2>t@Ku(}AY^z*6$?(ND^dom7C47>xHr!)~a+7Q3-=iqa{K}Gqcrhu2FbS+V z0)LsuC;iq;%H4k(uiS6`zg#8tU#>zo0jO)_)PPVDB%Coac8Lg^=mC&da}Gb&IJa77 z^`6uwd`gY>*6Hur!#8K?smehhWHQ4f17AFhexC_m z2z=RPix!aSP7ky$Wfh|o!hZ1g_57Sk_&~IRFJ?cDj(GEAobAt!Sx~la`_eRJ+s6_= z#powZE>@QXnqmZZChFy1@lvdfhYGnd{JTbWM(WJMR@3MgE_Z;oa6Y;EdMe80kZt6Cm^U^T4c6Bf3b&X z?~d`>3;w{NL6R{9|KrGBniM1(CR9_D-9EuQhxWoK-<5YbFL-UWq5ZbKGDfyY)epBC zm8^SgY3T8JGqQ~Rg>5dIsF@P^urlCqN!BA!bvj*EZDPv--H!Tow}D|Ej}VlY2$k^@D2i)FvN5~kAbg}Kh6DQLasgC zZIV0weV^D*4da_^`T+0f$j4DkYpn|)pO1*fjhrSU9r-E20rit77~{b8Cm2PYES<)i zAVg9k$E#_GoHbu<;|%rs)nhOhcHWQCqH(gHS9ut{nCWcHOhK8seQn`P_JjOpCw!;D z)dWOkSMU{L`c?X1Km!stOVs&WW4b2J2)ky%mSiY=TNgV-z|j^%#txQ!8mf=~1Al?F zzMW?eEPLy(bMgE#Ys3-jia2P&2S)tPSnugK#-PZpA@tth_M=K9z8m{B1uouSfh{MCWvNMInNEw8yVNGH z^7(zY18uoh@4C%?p!CQFB{UGsi8f}I)W4c{9`vXE?~rM~hz^~5opdCVQd$E{)v={N z48(c4^{4^!dHP}IuMXn++{tj(96vbI*^pAAE}MhEgL0{r$=`36#r0S)n}QBBByR`# zK}Y#-;ulPpcq-i|!49=?3nAxd3pWS27h2D_f9TrhWnCMRSCs|e=l0a7e?;NR?&YX{ zGJ+~4*~iHK7r6*TD=g6fCAS^iSfOjsaAcHvR<4$01H$qvFC=Ok z={l*uZGNKwyDL4mn?bq}m5QHX7?hMd(<;)NZ2j>6y#PWnDL-1x{OgxHNt&4$mUeV2 zv9ek^@gym1$6?1FljSN&irvkD!cAMJrEAl+tdP`=7pM*xcbxye5yO|Zc6uN677zg& z#|gyfv3Au*u2Sp`Wwar)9p(vH!H&2#{bPVc4SUAbj9z?l058B46H#9~*4z$*aQawF z8-_!g#|q#%F^Ttq8i(QB=BWoDC8-KwQq@I64PK~b(F5gp%~LK;UpDu-W7oh^0)vQv z!*c^3{I&F-+;`;_8g_Pe$bkH)XJe;_Qy!RS`#8TVQRVj&W%BvcGcr!XpFp_vM*qRh zR?NAA$pcfwDP(W^(>A${fWu|Nn72P&B-<$YQpZk8io;0VUIip!=qU>_MYIyI3fpO8 zT;kZ{D@SPAOE!ZYz!W+!CPtO+LZ2>&m-ttG$kXrEr7q&hU15r5`@e$AUByYJ->H_! z2z1m_C?T%Xd%k@U9T`l;1ghC9Z!lYEn|Sskg3G$I$(lXT5XK&wUL2Q+lJ57$S5+l^ z(^x85$%T2njqoZb0_ky3pj|aU0&+<^{Y=dA+{|*~*(<8_AlljO9tWuCinbbbJep9# z_W>$ax!u~#kE+1)l~p9Z{n(H(dMpch-ff-B#AzCzUHpi8P=T8Hbhg<{k4`d0qu~mw z@9u0hg(@Q*`FHCfpI5Un*yg#Y$S37VS!iG_Jm(K?EV>DNHV-#vcRu_WUR`5j;qr1K z-wisED6~Is+!FIsP%3gBrchDs?)_u9v+yD_bP=;#MkSZXbAUJFCBI z!P-gTiD7#_QA)~#xYxUWgQr; zep>Swak^XpC4T=7j!$p;36yh1va4FubG)EM z_C+f$+>*-|t>Ocb#G3?uv!%+Ili$r~cJde7>2=QPRnqJai1d#F*1;}Uz1FG1URyRP zXMr-XJNDbezTlKBWq#jxKKUe*B+b55u<|5yYSc=roN&##1j}RT!7FE_Ikl%l>r`AJ z^*lJqPFO_d(U{tkU;U7}^;Le$u(Y%^gbZqexiD@*YM8+9y7eKjLl$tAxNiNfh?Z0$ zgH|at54SpL{lM9zTAR2VKG8b7h(g2gkOWV%6j0Ipz@e?Fbyp zthZ6CyR$g=EkVoF*DB@nS410n0wQp>}b++YdLLf$!in( zN3myAPPjNjbGXZuDlD@w579{)ghSEfnoI8y{eO;XS*|7Ar5#x}b%5L-L<~2o zAY32~nP{$&F@778+t}#Ii^2{dtIv%*mDTa!_JK9a`KF4L?JXBXAL6u+oSz_k%|Q{$3RldHO3R1oqQ5A*ItfTsw+Ou zdv#vKm^zKFr;S}JI5>R(h~yAM<3gDL% zGua5mnU=#lAMz)?(Eys+F``%vmzPMSPXyH0M%Gsp7d`AD{tW=c0!@uG`7&%iN5)?o z^>8*Y;XvkIRk+}cXllSnB5F1d7RJ&2yG5?wMJE)R3o6~Y?}UwLEbN9=SYL?&@+9!{ zMMG?`*=vi@`YKstUtrf&#f7J5exFi)lTpHXETswtptOn#&VNL-py#*QHg7XzaA867 zP0c_I0V@Sz4A~L&#ITlWTG;71*_vvnQZa9@Pyw30l>v!+F&U~S(AMj|tg?_qu>7!& zItYFpwv49mt>t_Nn;>3Sa5KT`QDlCDvUS#0wW9_#9(BSo|C_8(uLNnW>M+fyyUilH zdQ+9Wi61X7)=-(N#b?4s6H&u&Vh8n3E8}73-!Se13F(lXOaj{u`ZX{nZ9Qmj5*1Kr zXHg<+vy)DXV6M8~2$W0j zk8nYP>=~0`O}s!8U$qV<(h9AHDiUMT9xcjc&GD;+CP+(x_h^`n+;JzT%d{^SztQpZXF;9o!Mo8P{vUN2G5}VzVa_5tQo1AC?8F2syensvxmivHNNmCtJm|z z01SuDpY_tT8)S#lE+qyL%M{nx4yg=>XT9A?rs*J5n|AqNp*8K#EE0XuaMg3#O>`d) zAJ;(?87`&mCIc3Cbuz>pWGsY)NUB1)4~SVp_gH_X@ZJ|jo_@x-8dGx3(iB@rUHfb- zkmpUemO@oB`XExmIOrTyN#ox#_)_=X?!kYjncMIG1RF$FjU-X#&Ghwjj7U>_FFzIb z8!Sos5%AcCuT;D+=Evo)no+h1N}tg$d%h>Tebg>@RbS7ljO((}7Ka+9IMv1f5oO;5 z(v!aL6?*bM5Hw4HTKfTf5FCKa6?tO$kV=7hb^D=@8dhSTjofAU1lWFq36id>~c9qOq963E29T-R_kfW-wS6-1!o!k8f( zYv=|1_2;})-SyjYdutEwakme6CWn#`j6(P;<2NSu(r*r#Jj;_i0RLe`wTBc3pv$D3 z@k+RxUxpm7xwn2>Pv?ASsl5tjV%Yy-q=9cxKKIH*Bjj-O7pJnAws_5@ATAt7cM~V$ z@pJV^K6M8jz!Q`-UgwvgtvB`Z9Q|`5d_)8r5v!qZHf5x5G9%$M+wF~^@BIdm{Rz@h z=5-#E&wuvVGpd9OsO(P%;3sHDW^5~0^iuf4IbT;CM&B?I7eZf-yE;D%X#UgJp z&LhF7hD~g%3(?Bp>d1S@Vsz2MnOB|S&@M&n^YQM?$@{=yS_@7;pl>}>gdvjBsCFAFra-;8WbhTF2WO#PQ?r(G{ z?K2x)n;f|<6DS=4>D5f3J}fIt9p6i{Wbqa=`rnMAJqbE0z_OaSw~5+vZG-I>ozb}t zfl|+HnZ@%~9P9+gx`%F-`J5p@-949i3U!W|(}{e~ ze);=CfeiCV$KpK3Bl(e@aE|pOJwo089b&VL{~n>dTK%J`x-sm&mjRM5q7zTMv zYCI9G=T<-&nvGhk2<=@+2ny)gMI#}<^9hMs@uX<6xrr|qWO&o+^bd-I-V^SB)m#;6 zcamr@LGS@MY^*%vwvN58mae&mrRZ(!FAKu+1p>T*0%9?KQjlj%4xpc=_-Yr?%3pjkIy7|Lke}2;Nrq-2zPSRo=1bjCc ziR*yAq$i!U1S(#RGFL%dd}La$Y!44tC# zw;>e2D)-Q4oAfSZ^2>D@3!Bz_T$af}W$#F90OxhhPUHA7`&%Bu2|$xPg#D`p`FuJ< zYK>)_>Nr3}0Udw72ZE(|Lr(4%a88g;9EfFITz0qHap)SN+h<>3b_*zF-yaZFbGtNK z>&m{I>b|kWy1Z*h5uFM>jT6MlEN8N+;T@KEcE_3UDSD=suPL0@fDjBbX_NL5!Gi3G zqF6i#RAXp1A-;ZEhg5@ItfW-N5Q4bAw=g5|hGBR!O`L!{&zIJQGs{d7ve0X;H61N!Tm%JIHb}n#7>oaj98vMj|4hNE3P1*g_5t2A)SfZI zV{$rubri0`^ObU|_jBU=$=oB;Y`m-t_4?F2yXeb(n2rMBg0(wy^<4jcJ*< zR`Xu%l_qsJnK~mJz8qKN@tcz1m?i?8(NhIrlLs34tZ=*NziIMzbUd~+JULEVXr*Sj zPb(5S#?mi87fw!ze6GMacxdA@ID6F*I>*G$cZ`NMjzH zLFI93PhJ(G1xy4`%Q}5ohh1$Wl$n(ckJGKZ=jeg~jIkehO^|=8@Xls2z;v+~%nzQN za3CS+m64^7Fg?_YeyM$GdkbwssUK1?cuOi^5x3YW4cLNd0jS62i!H|{roCVb)luO0 z6$V@d>_T6vJ@V#W(T??ST1mN^J-QPDCbS;T1oZh^#d?<5_gBFOl>#sifue^69QbSN ztL}ftkk&hv5;3FSJ+istzKvlE+>|DVfnqZoGVi>Fxe=kK0?@CZg*3JPQ2zQyo-%_q zw&PDJtbd4;T$o}yc6Wq%`O@O272MgB*Yy*{o)um1XO5Zk=4r=6PJ78lQHU=_!Wj9n z=-VU8Q}~YM3!j@#-~YtNv#(rlykX{~))R_zqvZWzKop*PeC!=7#bfz%3r^-$;M;;`p3Q4Z>WB(g3z7zH zp7M3lC(@AF6L&PQe7awKIc_ydXFTgT*LT1P;hul+W#(#+t4y5=sy*R$L-LU|**)+V zPDJG;kQ)hNF4lK<(j}nIT!j4XAX!AGM`~<{*E{L9->KHHPnr}w)5wDZ=uKBQo?%{O z;@P3Xc`|F;oDTzIwRhG~)%+KyYS&4r`TQ==UbTeavXu2{%}kF8U}!VuaascyICH+? zbFsrI8BO7%z!gsp*?Rz@0Ko&({#QfAP`nEIFnXy#R`G$Y(#!F6wR3vX!+F<>Z;W$q z2GFx1z3y+#fzm4dQB5(Zu7$jJlI> z=uNX@$n5&hp@`r39gEAt7W9toW<*#81<(AY_X0mOnvB@1CEx7#b4RejbCL6|fdJu` zs|6!U@4uog6sR#F70nJY^ZKZbdF>yS`RPT2buLO)7q<`*XyP6g2MpN7-0M(6y`$Uh z%?I^h*?IgKbr`XfJh@w*ebTdD9dU@Z=^~tOZKikrS17h)Q3{7^YE~Jdca3J#hDSss zSc^JGXp#+mJIj^UevDk(LIWNyS*MzC`2rod)rOuKdq_%MhOodlh&?`h(Hs7)zz z>J@_yV;~)RKK^Oo19U&f@TgWQd<5m|X~s^?E%Z{oJ^gR}%`Bl$3qbdki+!)7`XB;{ z!3-Rx{v`-dHB$Ht4VpFlaS?yC%8srV^Zmqt{+35i5n*=z{KPU-vDJ%o zI@f(Ur{CL`F1q;g;ywKidLnQLg)^y(R7D*RW={z7x{cml*LR~0F*W1yx)b}XQhb>v z4W0$S4m30g!e}KLW7xEC9D0H29$Zn)^2apl$+$a#_sMO!D!XN-GNk@=Cc{p8ogE7- z&H!oVDN5LyxQYi3lwkYR*E}!4alWn-ZmiXq+mgc+-mBI5xcVqS!BqkRc6Yfhoocq- z{-=egD`Gavn-WZ-=c5uO{^S3O1wJAw8-j^Nhb2`sv)`R6aY6z(x24+7gtbIm@^==B0m7QFbM5<(HaAGNKq{uZ;(L)J97>pkPWrZdZ&I?T*FL*AHkF*I*gyXBpBx*vE ztZv!n2*M0!4_eLDw^1hgm8r^M1^$4kpQ_xz`btKeL2sxNze4TsYY|XDN7g|A=jeHr z-2wQYm#L3n|IRku`kPYy45AVQEI52@Yucqw$2}z`*ZO7 zL^0NC|95ZU-c~JaH)J>4n3ynNFAJZVsKH#&cni-2?5;@7m?G7bP=MVyYN017 z`3=QCIcP5J^E`rJNWF7d9uPi^?Ys%6b^2Vw(FO~;?z860J%SuLl=q#3*-L%nvchDYIiDsSXrH=G4jk}zdY{s(4gXg@20iv0%KKeL`+eK8OZfO=OLc?lR z^@&|OrLIZ}A{50S60A8FrmKf3Cx1IrKTYccf26s({{F2T$0O==9jvJq+1q=6&(>u23@4#G+1w~tw33}FYx+G$8 zi2jA&x2(cE3lYhdygxNt4j(c8-$=m!g@hU8i5wy%PjUB7=zFCMg5b93dnV~$jQ0VP z`XgdMp5TtUf#BYCy)n%z*A$)*VBYy?&uYjzA*3db;dC+CF>E!9KSuz!D7SXg(kK<& zFaOuzj7>B%dbcq1n=Nem4DARUV@RIlSQofY2alNo*&NH=NVj$vDLMfIdyfr46AnOe z!GH|^^959ALePuc1IKHxET~1S9a?-9c@#Y`&%*=O1O{@Sc2d2RN`xm>4_*wGc&|>X zjB$P~d!MkOa*QL=%VKs^p;+$pZsyQX9b=fl)c!r0-V@ooA!tBQhqAlsGR}SU`F?R6 z0PX>0JRRBRc3>8rvNx7G@XC38|5bG)Fb`HzJ=~a7O?}!0FWF2z&Q&Nyz2?0Y$!Ha+ z3sfT2D=VN3lyV9RXbt+3z`Bw?ZgX%BGV)z{&u}=4dpMYQG?@5!%2?&96e!C(j<&-= zP~kzm4&Tk+K-UIVt2vw#uk9mHY$ky_B#jlEX#6$7UE^3VDGQq$zT!pw-UFIYl&_Ve z2m$aOk1)?~ZHt9?NM*sB^b+Kg&&R0(b(g&p1n6}t<(m_&H}?qnxkCaU&xjr$d7QNn zx>PB8 zg7QQwSK3LZ$S7&;s2dc&!gNY+V?y75)84D z0N}SI!*CII>HWX;fUQj_J6PV7$46}3+imeo*ln8UyY$b1=~r_Wn%5qrpITtVviq0P zQ$bpwP{On4j#sTS#VnPZvr!4;jjpVFFtcW!B%;(wO>TeiBCTjxW-#g~VCt0t+SY>Y z1pb%lEVRT_R8Bz3&!l0UJGAab%Q7c$b&1=!F+-0%Yigp=GMgRph5tKo>a>K z25gEzNMzr*S{-*suG)vxRT|cJK^mcFZ{knjs`t2=GPbLtz%|3E4>^JF*WESC(npKc z%iYFmut@5_*yS_B%MAbl?M&Mkv9%>35bX)y+AGyoLK-50lPkSVk6Wb*{U`auD{oTb z&Q7Bl7YZd+lV8k1bI{*g{+2pGQ2!qbkU;o$ME!uUd;uK0$uv{$HD2tHIxwBX zD0*(L+^?np4Vu6GaPRI>)-I&GWvJk4Kk3GrjsGK>A#SfU6v#)~kTw8c26nA5MXfS* z`nm(NocX$b2#a-k1&Gu?Z;T9_fB$b;46Bk}-h(siPq$X(JU5}&RAFIsiIz|Pl=?+6 zKKrp+Q;v)0Rs!_{_Zo~&-hHy3@}o4;MHD(tX<_wREF^njtv?}inJFJ!-wpdIpBJ*5 zQJVO6kxsMUGB9X@e-cI)5{6Z_b&?ME@I*{HYavcg>vOlh7csfP-~VYD*vlC5f##=! zt4z--b|q6A7kwq^yjG?-J2Y&-Q**IR9BNl)6*VUfCsFouNBY8VAOYS7+v-K1MuA#o?uP!8=g{ zS?rjI{qIhy4nx^47LeiOsM^|_$s?IPuFEmIp1!O(_>LIaq`;SHUB8>;pK<58m8NGh zIM5>{--U7+=ciuBb`)jzWnif`e9!Bvo&yyo;Y~Jw&hF3Z5Je%Ck834pV-!=Cx;|H8 zn zi<;`?zR9Swst zUN!W}4(*L7ff88LZGV#pQkb?0Du2y$yC5WHGwSjgygfZ_f4c6VdZbEyEW z?YctB+>bxb`enjn>D``PLWSAxhd4OGMkMu ze;+6``tK0olQrjP?m@2@{0o%d9@$pvQzbHRi*lNwQxV7c&6^tKG;)4~%%A$vpD(KE zLgh>g{rsG*M77aWSSJU zldN(aZcYH4Uq#SN9o9w&37yP;_;V;H@mjh167HSx5OeSPg^Ydd(GQ;!wIZl1HQL^u zeZ1JnF-UK6SQjz@Qh0jPo@}T9-S9m{t>K;g?qE0gGasB2FoyiLp#9hY#RI0$w`I+! zeaZ}%UFQ%x`Oin&Rx-c z!?jWI#!2Qvz(D5o!8`MIUh)PFtpY;BAH#G^4cv9!$Q>xDdb)hadG_zGi~8pKEoM4< zF2n{d`3@`9)T`k5y?|zY7HGwrA2J_V|9Xe&0SoA&M~TIL^!mQ^milsL)oY<|&8{11 zmq6~cd%NdIK7cb9GhfBq+%>H0Sfn+2mi^$L>F3a*fC-!hJp4|0gge%Gs+(22(vCap z6n%M6@W9P9iAV%E82 zrNOTklqs2^(hEG0o^bkGVi?EG_tE=X5+A;!P2gRQY$=|9o46I++8Y{48{Uso;Z8Zv zgJ|LNQGiz&D!1*5**OlazN42Vk)LjilS@pvbqb4HP-GTspEpGJ2%=GsfAlwQij}|# zj5LHT1HbUrzB}W6vu`*5oIHOQ|E4&OQAV!_?bKmrNkFMIy;(rZbeDZAFzk+00Oc0E z0MW0v>A=T$+(xmPKKy(GGn!mJxZ27M(yOy)U5e!sDbSN5ckNwi(`Bag0adly6fS<< zHb;YvJhtjIC`WO-Q}m`>{IEta4i*8m`5(j3grfIqf@9u0?FD+xqh)uZeQ(2NzVPK1 z%$NC*c47bOn%7&g(Q@O-sHGg5jplO{w6Cb&Yei40O;r5{I-ul~K|`|#!cEA^ME2zi6XCVm&WehF@W_I>pSw#50l%L##aM>qjS4D9j;x2!4AL zAu{gLj2Gux%BMHgPVHNLbo!}U=+40O4v*?o&)}5ieUW1naWzF#pLwTfY4VesSxeH| z+k_l&@qj_v)wAES{e8;=0$#^bY%@`OB7O*EaC+RiiEnnz!gT*YtJ>^4E#$?sy#}fc zu+iJ2YVPfa4GhQHdF*JjZK6r3V(7B;BpY-oRUzmFt*AqQ4&-ieophZ@PWuj;&;Rv- z1B5oe8ma$zdky&LVnrLp&2rwHkW)QH=W8VSDeh_j3;1Ix|6+6p`p9K7xvB~EVa;|U zi*Y^d=NptBEh~wCw%02zXvkS5`N?U%S(~km_6hx1Wa{%=foFF7X;Bf2ME`G-w7dyfEeodCa%p^c zM>%ww$(ANqR!l(N`uA+c8&ve2wEvRO0-ZM;r<54r*IjMou8&z6ngQ7DIdcMM4pt6v zjra(ErS0}9^rV7*@DB_NFAp!o&Ll|9tO(`ucYV&zuom1qPOjnAa1|N->O9|EsG$sj zKrXdQuK(Ga;0mNy*HMsd=I=_F@f0_CfPPyk=+$1-P#Y(~%Jqh+p_BjI@J9D#rN#ghi?!L*qV5Y=DtDANUK(oBNL9H7=HJ#<* z($umum4f!H`nHrAwJ$xEoWicSj!qd|ViGyBAmMY;!F;*h{8+x{jc9+H20$HZ!q_Lx zcTkStYESa${N(c$szf$RV=16b7H;wm!hi+&NgM`PS1s5C|8FC|Ogges@_TLsvNpYlz&GNRYs zpi|Vo&hulQ!=8}M_5lBVs`b46oW>71=06Kje;kj?mj+&aI~PbYq>x+0W7 z+Gc=NodH}i6vPfZPrs|-y*3pdE7ey`T30nD+1cc7jn@hYO7y$)yK=B|)3>8XWR^R*qfWkX&T9vaf-o9FL@pC^u7T5dg5tG)vZ%e@%R zH0U4tM5``0?I@jeP1r3PinEsGq$KQ=4#>R{Dkz*R(i8k$JMHLC^Q>DfPHVdyV?vwI zZY_GX`&JYQz_t`8bfF@C<*Tt>Ki@0gOD*+HdVO`(zfBy7eN!YUVozp&KHXgZWiDv%rGAAzYU+#=6jT8BH zR%p!t38_NsO+jK%m0B~91OxDB%b!&Y-*e?8$(JsD7}Na(P)*8wYlOD!%&Sd~QrvQw0ob8bBX8_;7vrmOx&OD%5Qp_I}# z(EePHmEAY}%MgPf64PaZ(5ojb>zsLAE?1lc?VpL;+V|Np$30d`1M%8QO?G&7H}gKf zh!b%g%WewZ$c=K3>-Yobt3UPg&!3E2TE!K_Nd6p@c_%V?qa1djpz1 z53KK2A_(;x1%Fr|-xTiEkg8`!LBx8z5-(egmo`kSN4!!v&_W7mMVsVq+fERWyhpbc!5)`Rnk;ilGW?p|k`=-G@bbE~U9R<> zE^B-Z&mFQQdX6^X_GL=z6|#!WU+C$4UBw%7lk`_XmFGS;7KS9#Ut1_I=GZXn9k1RE zc|LdSg)W){ufB`Nahh=f=L@^u5*l2eduzw2^Xp(i|8^S@Oj45aOzn1<>eZDg(9Bh+ z$?U8NqRl(3NH;ZhK@YsewWYi?KH#2v+&CLoSX1@-R%8dQ2bfByea!H=X4gRv-A)Ok ze$q+b#mrHZrg06q7gaQbH=$T^SN2ZXSjWNaSHkI99~F32-1_2zmQI@RDQ|!NJE+Sw z(X$8&TJd-cTsgGF5Y6-Mr0fKk3GSRV6)I-wZ^Lif^GAuHqg!;G_7Tt&VsV{)Oku5o2yQ+u zJ|mjhHiFNZIR&+W){dSRTn)0$4_@!MUk z#aX6}lmxdU#m`>$z1~n*=7H1?Z>R_$_`NmYI2J|=)_%%jo!-k#v8l&VIfbg6*mLm` zIJB?hfZG@FXnErUh{f*&e*`jifx}Hwbnt#r!-4wD`|9{&4|XI-8~04*60(8CnY=#i z-PD!b{6Tr~y_&`tS75=?(4H3TX!BJ>y$|X2+ILOie|k+XHdZxVq#|U0-wAlzXYq|T z@KD((!lgrU0)DVmQ9WBazrb_%0}MjF=9c?uqx)R0utv|mklbDO{AUL%qf_vXB<4T zv;<#{V+@t}dU|%o@4EWpms<9&=dBku^p6tF7yp`{$q;c3imVx&4Ure5>OR9=*@XpD zYxPdvdSc zg>Aiym$7l@49^F-ZL|R{sjT!+UP0wrDFFfa+v^!8PG8HdjR2WdG z?x8MrW$PGisCfCtVZ+U{sdUGNeM6G5%?C*AC0t5p_a?%y_S~=a%vWu`Yss24bBMoN z4>Ddti{zf=%pPGXXToysUe>C~Bp)|>gXGbnnW9Ew%;>IX1*8`yL-4mthR^9{p1T;d zG$mg;x41)z8z5pS>Im21%X7%*xm`#UUL=__=1naqX!20z6RA1pg z)u#ohzFTAXSb-kX`JbGFUW5}pPTX~CK|7U2y+c95twCF?Nb*y15OhWDql?*&qS{f)T^DsLERvDS3a>)mpoiQc{=aq$3MWtjnMyd7$_mc zXt+OCmIw9{wT3Lk`l@!*2;)_=d==qZ((==hlyXq#CiQ?1yAlRIQOAv&-3_omHvcA3 z`vEPMVWQf;C2wp5Q^e#&xd%O+M=I^!n<_2qRgu#mO_L&E>7D9P;A zO`cQCCM7i65G6MoK;JX>WcFU#IXiJw1=kMX?_U0?Z%y%Tipq`w4p1Z{rq_7$NXVSi z@LXMcH|6-xN+~)PJyE}S&B~KMJW2(7u{y=Sxk}~!cr&62>EvKYbIJ<_gX4e0&UMiZ zZXD^kXmGs5t0hx+E5@e3B>CMtgBGZP3yy!cgm7g=P{beKB>>gB4X^HYymp8xe1*9# z^Ph5e6s?ZI*KlB!d9zZN`Mzp&k3mZ9339OMuE9L}5&y`+5HUd&5FwE2^}9L@Hi8aO zw!k0Bmqz)QqxK2KQx^p7SgW4V99YD719nu*5Wr_~EI) z9yGuCc}I=lCL^ETWa%}5lcC3m+?>`chr_H&V;RV_sjrg(XG4&vE^V9wMW&s_w@715 z<{Bpg$QP{58Wsr($S@*v|}%=+(KQ6XZuYzd&DM{Xk2Gt9;G+M^Z`}z7d}!Qm!pVW1PWhbzAB*~9R!DOF;-Q6lIGXzAtBaU$MoE0DKxp+7NRv7U7XN_az zqutReZRfP~uHOq>erXtqdcwRj%0)j}?LfhDWj6n1>4-5H9lj%8)#W0fUHkSDTBtHs ztQ~8c-L~cyhlrnr=oNI#Q&FZomD}3Y1zfzrBgW|NWxf{3Cr?Hn-oxNh64%IadEb=g zh%fJn!3A*>Qpf@Dq!X2y@x>9Hj<4E^od_}+(43S`n9FlS_Pbu~!)J6=+4NjQnBy$W zS02#t$g}1vWyzsC-;|ruzCvZ?@_J1GVa)_QiH%ng1XAFAAhy)t>6u5e_Xd9-4Ik09 z@te=B;_+IrLfqiP z{fWW|1HfTt%_xQ^3YV?o8q6bBG_5Z81UGsNMi1I3&B`Upx3Wo82p$rCyU@iIrdIzN zukQB@{`$@;9CIRQO!^PE|G+|uZfbWM%NMKEs0TjKtdnhzV|4B2`;aQ8c4=RE#7Gfo zBV_STD&Hr<2{!%!`X}KJJ_7?JS31)SDl3Chp%GI-#Ij{F=jPeC`Z|A1{l)1WNHz(Y z?Yh_4h0~&l_NmBZW}b-JM&~*_3U-{8&lEX`r$6v6%$F={Yw2+LVwV205Vc;ml%@Em-6n%RC z^u?+CTE6OIOqL%Ag&>}Rd!vK^6@fsEw^D@TzJ$a%Ih*0(6n?BKo9A8Z0XVLlox@CJ zB+>ti!S8W}{{#vF8C**D>Uqx_AQ697lmQk~qi}qy>JTmXV z)QS&k{kEdntGypnbd|ET44LZPu;SrirNW(mtgh3bpP6KdaR?^R#)T7@w$`^x2t}*@ zeY6_a`Gon41P=dl`6a|~6@B4Gs*(mw$iv2}tAlObEEs*%(Aw}$<@mFetF`11t|aL~ zLGmRfNlV}lV((Z999NR<#Zo2c2SA+FzIZRi^wY4q4q<~;Vq@OA9LDu~R z?X9t6K)$HA_~|6i2SHKuaZMT&fMONFtB$gGOTZYtx1KA8Z6=gDLt~ZUQz|3f%9#@;4s%8=K>#zvirI+xAr9Ue5;?7H=`AdieWZ+8@05 z=bvZ>jlM%9N~op1*?B4#_xOUY3^`h+21H@JH%Ns?sk+JdRC+KIEM9F5Ujh8jg68HM zW~tm%e23iDOL5dD+4WPsEHRv62h6)KT;~$4BuGE*kBL7IhX{`(#>h0ex8tqeM>Ah# z&PF}Jw-2|EaoOfSz|SWR}GT7nKP9NAJiGCCIQu-s8_3&`*~tTuG;*4u=#^d z6A>IZ2qmG)Zd6>ZtgU#b)u945DG9DHl!I`}5l3@^M4I-096ztegFZ^&P3|^qG)EfA-T*qxPVYo6z6gPL1NY>_N z0Qw_6NEIO-!r9jo`nx;i{X?3a_80GKKR~dOBB_dgSO@LJA~_~XwD87H?{V(M(VApk z=9aA5AVl9^GKu=dkngi;M=#U_^ZkT)jZ;YH$|2b&@64mc4W{-8NKAs5G-z!_hqMzu z<>ddM)M()ETabm5g(m*e6Rmj3=B%C<-%QKjc1&|Q|FWL{o{!EZxF2_c;hkkVU=fNO zIC(kPT{HUrXZMGYh0MIEP~p~2;AVsc!N!F&DCV7JnCTDaQ6V$m1)C(u zpY?t6`dVmAcBs2-Yn*ng1|O4pyJc_xynACYb7FKgEOPEZkvV;@Q7;l$Qen#t%sE*E zEnfKXO~f+*-ln)@kp6~0#5kz6ZPpIqTq}$}9$K!waMU`chHX?u``Sq%SQ5ssyDw%W zqAfQGFeClu1hirOn7%0th!BMHxvzb*WKkLK60-z?zoFY;KTyixsnBhKKP_jHWi}rs z>z=P!)%&zTcfzShi47Jm&6K_KzxC!fUUOGmoZA=bhePxv+1^|dbn zuSD6ISy{pfyX8HF8O2Chc0LULbKalWw@xa!YLdfJI#_!aB>L%f`5WkldCeHTU@3`N zTd>tx{`zk+gT=6%g|9gQI8rwljP;r31GG^^xv$roMyk~Cgf6=Cq zt;V@uA2wpn#Ly|@L$rsTaTR^L;y5~0H$FvLul9UdKgqNk_G3={p|`-+nB;bX4fMUD z7vWHhIdaTqS1TH>MMQt+MuifR+jVo8(SWxBqxS8OhehmwBZ>J7+Q9kBDGRf98S;*) z%DGy7{rK>^oR5`d7F1+y$pOSrHc`DYVNr~XxF$<6tc>e(+aM7W06OR9daXpSLMk*LO2tul#o| zJ|W{uC9Jl7=rMog7GZRw9jSJN?Oz#ep#AlIV8m)&1geR!Mi4XQD%H!!o7y4?(npk? z01drfi07VJU;dmG!dL%ns=VlS7-3da9vniw?dVwS&U|H3_k7k!w|E%j<`DtwW?-m& z)$|yC(U{#9?rd!cb|tTbh|<$W1l!%hcF?Aqc=Rc!#ob%?XJV5(DCQRpF05k~D)ZHr zed8x(`Z!0q{HAvfeSlpH5BG;PeD4&7>AW(JJj6d&@m>fO!b;o*`s|*S0S~%|&@DS- zE>8MVT*FePIHO2M9vajeq1ht6x9=0uEGltD(IkmbUprTnEB#6oVpF+98))uc9MENP zx`xSJgb(EkN92N2Ae z$Br%eS*8PQ9cS;Q1`3QHP`b4W%8R;AR_>sSpCm(V5-KLBf5t0!9fr5Y6it3=Z4Y)% zf%^-Q-47L+wc?5mfH|7~&8*IX5P9w?=QjLcSb)y~Yv@wLKI#g**zNA_($oR$AqM$8 zL~gw*r>mKmT)frM2-SS;ifj5Bm1MDXg_DzRxBBW14I9DXrkgvOakqw7 zV}gIlbQh4Pf!ypP3!f6T-4e&qnPJaJvTVgQD$REQntfBq1fv5v9TO390l)_vC(s_> ziM5?(2Ew}s6bdId_&0$WSJYT&_OAEHDE|c@kb5_<#J;bg-#G=MJeL4<9K>$vZ7B@1-7po1ncsX+#(Ov;8NMrj@ji8rtvf1<^tSo<+MeLm~1&`N|GNyFxi7Oq5#m z5zyMxo+V%tMCLtgQA0dPB^n7KH4LycJi;G(xEjY~$Bxd=asp|F#5K?@lC$Eh8rSlZ zuSd%QQI_*_>XE(KMV01=-*kZuiFX&$24Gap7#ic&t#VFxZwfpw+1TF@dQdY_R!)ii zX=_L#`|1R41*3MqZ13{{+S&=K>~;QRQa2L+b4dw-Pv|U&H+rzQXO=)`uEn?xBwO@9 z+S_x};ZByD)wJo-0pdmPM0+CYTQUhm?nA5}c71aKE<6Pt_lmuZz7DaNYZBLf{9x0M z6_9aWt308ihYqb-9MdSXFVfmEJYDtQD{WnzJ+mT3l&%96d2F^}Y_|TpZkc*hlbl!U z@4kxM5gkbcX`t(ax@F;uA`V3;8;vP7ks}2^GzZSUqc+rt&+Ox`a_7UgH?uFo zotK0;Dj_Hc5qP%mGu8TGi$!umDd5#v48m0UlgR``mI?J!`)M?T-P*>c)w zf>WPVeUFPn4I~s7K7szee+br(*IJ7q3Z1)^sn?npNugT*!%q7<$BMn*5@rg`HV0fL z4~ziW2X9h$CuW{8(Z9gz^jEgPAd*79Sm-aVX<}5$Tl%oJaYC=*m)r5(_v3_WKJ->? zXnmS4+et#Brb<9p@x#xjYL5X1rsRV<8!=_XK?*kIYFqxiUWLUEyJiPfEFDWYXJ;JP5U!oq^5Q6R4(uaXH1sjOaJ7rQ+x@8Pv!t{l7$!L!{;JzBPa z9)rzhxfrXxD_?ycHs#5qlJk{M)g}caZ{D9G?m4Ly(4S28pYsoEB!Q)&zm;A0DzMH4 ze)PSA7y)xpzI8JuRjD4Xo!9T_s%L0b(s|^+%u_PR8u;es5Mv0PM={+zGcvCMDI(?f zkOo*y0~l;NfBczUbjADTDTz?$0q63PegU6D4jy7CS%NJF71MkKOKBk!d-rusn549A zcW%G0g&HN=<1XQ2rxzC%WcB%;dRfBWcsF0k&dJ%0Zye}P0vJANKNt_Aco>B@(kjpS z!Gu!5F;zq0;p;zrXl=rNhZ&_fnzm86o#b zF3`hV++F=a3G!Zw=82U=mqXCZ@XPiAzXoKj1pM|Z@@ypS3`b)sJBXHXtI6)f(S#-E z{*mu_y=b2U-C9h3vGLM#gDSwx!s?j1cL6vZXQsf+8{LNXT5+72hdoS#+E*W1phDaG zd)~!TXmu-8>tDA~w%Xo&M;m4nVQPg3cwv4rW#GvIQH9+VeeO_rE9feS zDWo@6X-#xQWUG*>YzA|DD@mvsywfZzfp&d4nM6TN*hgsP+1+*tp^IsYqW`bMDf_<; zr#sfqVDp2fXD+~2?IV-?on3NSAgy0b_ThR zl(n+?OovwCvRfLfcV}#oHZA~dPqeSx)*5PAAvxSYWOAB+31BN-_c(UkVjPqfEM3B^ zzgv_RdaMo}n{E({N?v?&P&h9MGTX193mprtUkus)N&NdsN1#}+>s8&s^TAm9nCz#g z->)xXTZR<@*V)f$TJbA)P`A&V-!mNG(el>21vIp)n07UCv@e|x>koS8bc0%g`gMz| zT~|n?`NH8l2M0x`eX41o+|X%LH=4+_+o}3$%fBB**&}MV9VozF*htb$Loj#4v%kQc zM4(B^YLUL_H=2t)U1vt&bwii5lcrYzBb$w#w`=d6+JF(lr|J)Q5}viVRz^{_th^_| zz8j(veTJu~P$9TZ8ZBF$KbF+Z_JBZ}bkdoGb!|epuKg2u!vSWm{?j|e#d9~L33)}c z|C}}HCb6JBrPuMRB*~{{`^6cscj7>4GTjdxPq}RxnF9Z{({@I)T|gqOp_&X#IrlkR zJdWkA%*_ZzPAUti7u)W%*raTk5YUAMPKsi_F(8??`-jPd;G5FM$ik%QlD>qaMpK5Ko3m9ZX&8LuuPW@JkBqkFP%p> z<%y1|wpcj`*w0s8AGGl7h&$=uRINwt>qC19%YSd2WGpy_f$AP6BD^^$fhx2%SBbr! zka-84E)N$WG)I)Q75vh4gwK&^HZOeN67Z*HJ4QUqVJiH5k67qF2b`E%QO0nxre%wy z%@ENXx~MREW!T^{BE0_pTG*TWV?uhITm^161$)2GhE)y?dR#>QuFH3r35TV(I=RhV zYtF_+cMrpbO<@PW#FI3~j|t3nlTjzZ1n&ZtGZ;Pr%O@I)loFOst|g>s8$OjzLiFY} z9Eh$z!K(IwcIu5hfI4-1^kOiHyEF?$yLSAJ>wLX|1wcIW?@=WYp&K)X!WmNl2h8*#~{M$asMbgC$G& zV0zM`+oKAf)9=f*K2tqMovG|of%h!NC++bgL3s>7>OEp8vj1UN%R^AB631Sym4+Ox zCK(yM$2u}-j|ZGM)3SfE`d3s@(EHlK2(!4(4+lp>Y>g9AB5@d!^@#}cqH=loqRz#U z`G5>o-11kOg#@88&8hqUuz~i=i}3Kl`Vp0Le%G}rP072F5lVA&EQB>P{O9yB{i%b* z(W!G}+sCJvkeZj<_&TMVeo{3j>~)4AId?J#v$N3&TN+OHs(-&k>s4OAw9)Q&Po=>d z?@vG&_>JUbioUL&7V7!rdQVBsAATj4$48c^>+8y&u!BtGQqG)!kGO{am&ZO!~ z)NkW^?<(}X00Qn5)e5w!Y67B)+8N|#QsvCHcjfh#r2dCCy@=@8yODIsBnf!TGB1Mk z^wDXt3QGRRw=|6qBvvhabb_kNLy{kzB8xhLs`Kdpdj@?QON8OurH}}|) z>wG?psZ(!BPa?~p&Vchs5ngz;O_deCkkMP<>-BLtgQL!+Z3_ovyV$~a2)rM9Li0tk1xEdbA zI3;1I>yb5`Ic2Bg-~$Q)jp}6!@l0C=u^zKJ5G9dUB zZShu)6Qodm&NOHYz@kZ6cu;oHzI7TldsbGaLHT{@q=+A1@0QRutUwmPW>vUJN6n(E z!;!!s6c05$qb<=D?H#qfDf|2OW?ZhpaCB%V7##-u#-lc!4%@NaY$6kYRfuVM<8Fb()wI16bXwJj1F zMux&sribaE?e^iSvoX%;!%cAY!TEu<=u&S4-8+L>Jpo6KzUn#Aah|D$rAZFu6+h}Q zTVlYU3h+NgIgeIfDR3rZngWUx&ue#$OZQG}btjjwu@v%wue?ie;iRAAy^|C1esyB$dpE72RJ5*d zUN21TgG9e9rbscG-hBA@=T;S)&okZ?5bXaNWS+yVM0oB2F0qp+F~)+gB-f9y*uh^qv_%T+L-W^#d^KcQ2O*cudgc_>|rc&67h%GPu2 zzeI8HMcTYsD{)^b@-&b&e2G4mSR;L}nahaAwWLR_NVe!1% zX9Fvq2oujwFxsSV+~RYU662EI%{Cq}LXr6jX--fLT1yL_Y2i!XqmukkOR~~78{0)! zO>hxmPC)6KcTse7S~+leS6SfM3ykxAvLgpFXZQIW@Hr5jTsjGvN;@6dYgAkpdA6;4 zJUR*L6b6@G-85}R)<#D9U!n&dWhAW+i#yGhqF$hZd&Y&-W~lfVS7V2qVJO$=aaQp2^TN?h%7A`w#5c zd2^(0hHtNe z0#nv4Z-xv8OIKh&+Ld*6fM3Xbp`SdDp3Jpw!L$ITR5Qa6O>uCQ-Q*=rYMDiYOocCB zX45<-(E=dB;b+ugq+9njY?0*p)DX8C{AC2W%w*e>sTv zE!EF&SN>>50n7M#$-bnG+>4D>%ncCh2MvC8@ARk2fn=q+&gM(sP7SjQ#nFTmZ+R{P z;J>C0Mqc`GL^AkAb#8fKnf#h=wFTYX-O>3k_&B@`$oS>ojI0F7&|Az2TRF{(+SS)2 z#F7cv1AQBu_oD@khRF`6bhQJLIu5B|!azzc&cR!tlPZrOZQhk^&gpUljFty%oCT6H z`4hI8kLZ7Z5s%xT`sY&_NlR0bENn=p`lqloOv0(pGpYUTelK=yoQZltCd)>c;7K22 z`3`N)neCZKmzbUPIe`wcu$lMc(Yu%i3}a1es8@PJ9Pj_k(}a-ERERy4! zA1{%h@%;3RY3vjm9}QH0jesV+BcJ=|_L|R#$dL(DXz!e;(7xo}Zk((jq}+22eRzD4 z5A1rhsQsAm;ADX1!~|SM)Bhp|Gacb~34Y=PL*!|~FQh-WY z!7IJslfREBIF$(%Q3V0N_33thW2bFU-6HS~pUhLOUCgr6B-7Peoc9(RR9_l_wrO$} zJ+S8X##9DfV;;+uFUj0g5ZNn+SDBnIAIf_&Mn=}zV&63cRyeeJ{+pNx^-YO9>0UWrfQQaWB1&&qzZ%K?@G8=3?-c-ytCfGJ`9TB5s!}u{@-{cm8x1;zgjW zp7r|d?!}98Q`fDAj!tV<_{t2DcCOPm|U`%0=O9tu|&6%9lUD53;K;$ z4S2H=*@kZ2Wkw+^A4J}Ju2}y z{+HVWgmCvCuV!4pzbvx8=G+OLpE;HBVDcX?IhTH6onrXID4ZsgM`$_@c3L@PA{hk? z-aC@{r#;Ce($xh{hCZI{r^|6$Mo}5Gvqao?=qBe@IN{FpmakCw41je zmh#_ppZ)7yzg!e0JPV-|Kp;FqNm`A)e&`AJrjV>qSwB{Pn9ii%eO;S~@cV`+7bOW` zL$=W`oXoT?5k7N-etL&DT}~Wl)Jx@8?n*^JJSlPze=631$PQ>D`MbIs zxs;~(Zdn5R;}<9x8Fn$+2i><6zX^W;an~f4vDFET@=p_Zpi|_r$UA7qMY!6VG8X@S z@~*ma>!+@sC`_t8>qUvq6L-^*ki^(#>LsT1>zd96^t76B(*wh48JXxh5%GtA1B>iq zUw;2X0DE^Gm>Yq7lbibV_ULtkzF+N=_#M4_7pwto`Ki&pYt#};Uo z=?PzJU7LTyRkU};EtRZ(L4sWSo@x*=f1ohF==r4n9~U{XPWbB1`-R$nB*bR#p%cxD z<~*M%h^On4Gn^1$9{|RE_wmXeOlnyi#($|SDb*#c+U*4o1ega*uM(#Uhr|p2f41zd z0*MHF|K62whT={#fG8lQ*#XGG*9-ul$yJUU%?Z$!9CS4io_>(*^*(dXIx7GRLd+<) zX*ggn8%qte`U-#kAK+K=e}EqXq4Xc%r?YYLu?iiQw&DfLfahCtO32^b-1uzXYVJG^ zMYY$5E+FgNFIR>D6MMllQMygu%yw?-EKI~yVc^9(n8V54Afx!ET#^$z)h|q0o8Y# z0J31w-Av-6kw3<4@F(jtAIT~e8c&p#n`HQ)Wtdp76_IvqKk2vHMB*;G2Uhn*&c+u} zOxkXb!Ut1HH?0($s&OCtj+W8?{UW0TmySq?W~&SQ=6$VmKUYS|Cl!+ukOj;wR$l}- z%fj!!@68dA8I;R$p8e2kB@@WScbe-5dk@P zwy6K`Vyd}@P~b}(aD_d=}V=eNdm?`zy*EqVTmIJ3ND6(Qo0 z-G*cCqaDeBhTKjNd=hQ0y6+u+@Loau{AcJ8zWLA6jb^*oJO_&U3?yvP1bE>yAvvuK zW?moBM22<=Wz(`%KByUf{gW@H!RNFHemcJz<%?FkMzedc=B)*G_ z(d~7TL*BP5Sv1@3WubZ8@?`&uXQ}*>6KIdsOT4{Q6_)9E@UVW1Di202TaGS;d zN7Hu)!})k$D+!{D-h(I!f+%a%AP7;D=ylbIZlh(@Xc4_eFOeYXBFc)oqFW`RuU=MJ zz4!OY=llNtzzj2n*}cy__ndR@84wv)f5I;A)$DQeo#yE+Wkb*Q$|d~umwfv`dKtNK z^3``eQcw3{@~|R-*JYJh9xq(1&Vc**(%SH~WndeAJ+sDdo*KM9f^NY(kg->hqTR*P zfZR#4P4l{$Vfm>`y%Pu?NPx|Jw~%F{BbRL1-ahsgpZjRm=x2!ese7xlFsas}-w*=~q!!_kN;`kmo2Isy0v?F97)<@^zP1(C zZm&Bs8Uc39diaNt=P!Hy`bD`D6WRX8$37p_5Ma0do7X8@USWw%wdeuB$gBVN{ZN-r zX8pYUr=kL_|5~s3c~vJhua?c_2_8U*R&HXp@QrY!&y9yxe-Z-I=cEVK2QL!jPs+lu zME3*dU9Oy+JfPLI+kXIG4Ua$YsI7DbHTT=YPYR(4&i(_L6KzetMTZ%xUZUlv!lOk) z&uUIY7TtG4czvI)t~G4M*OEUYWl_pY$@<)2BfjsW&gXm#|4#*ossb zaymD2?bPyz<6St^(Kg)lxw-;()r}wOzCx-!S$KSNE&uiQ0z~6-LD3hO@*row#fP5x zS-Ekru=M)dz(gOZ*SEKXm4}|lhm)HGrKVymlceXK?Ivx&`^Q;7w z#}AxZ1h>nfz~KXrWK%D6%gSC+Uab62u4z>-1A~xhrig6<`n3`sqtVwU{_}2o60aTx zH5*6b$F{e}TYG)&8M)L7d6Wd@Q|0W!d^#-}AqS3j-Q_z%cbzE-|6nJu>-dRjPbZd^ zPqxM=h8UUEKV?f>@K^DW{45&#KMpGIe;~TfC&Ss=4KJtsVW6&yoyof96el;LWm2(H zpGoARLA3@i@5959?!e(1Cn`G}TM$W->hV9F=abyZeV&*(=E0FRtW&pTBqpu=lttoR z(m&fHCx}P*5}sq5Bs?Y7cUJ#lcsK)`+WP#c*KG-S{ie0=M+Mn|#+$NTcE)>*rW=HQ+oxj2Rhk5n6E*e$BgpWC+{DGy{gw71{9c{e6 z#^u`IQ4h?YR~<_&ZT!;ppj!P6P_c3OM$JkUhG-uM>T$u!6pcycN!~j~ZhFoE=Ydy* zMpcgS_u`!YSvYX?XWh5UVZg;H7}Z)GguS%6($6$s;Mo=72FC+RE;r`!B!7S6qV~3Q zm%L+R$s%T#vb7oNPqDQE4Ul8XWZNF_W=^-A*+hPJ6BD<=FnlewaYmrd@6(S~pHD3< za%EvqVfhO>t;WLuph#cr{IShK??+z-G(NuXy9*N{u*&jU7mjr&re+&rA9WW1SzwR7 z*o;o?8h{guC;3jYv@VVuIW1f`K61&jBWBUDB3v)PZrMK#D7EF+WFt6UFsBLwO19i* z;fW;IOMwi}AfJmOocBNHql704jIzbEn_B?ZmZRGVkT<9rfGAW)-bxa%t7CAvUCO5- zQ6i|Idd^GmKKYST=IMt>U-v%1o>#8NB$|8|#5U=TPm#@R#^$umw2Tm=+1^nyIz?dk z^U93J7&Pcjti(mYnY#jlq5kyY|hmi+{+M`_f2o*KL$*ZDUr`y zQOvw!sXu4`dG|1Q3x4bhhz;X-(!B>({G+nnP84vG$yEk{PuU@L^`WBeLHi3$gL!Vf z&Yy}jeuktnTl>9us@1;eE^Mn78!5z~5w|KSbI)r?B<&Z>b0JxlL0c97|BI?G{)wvm z#xt>Pk6@ZrVXb=)QYq{!fwhwtYIeX8kT^W?dY{=^>)`5Kew(v+dalb!-OpM^We;8X zKohe!TmV(fwvd0=aVC^9I+XMV zYqMZ<3(_ieB?WcZWV3>Y^K8|X;_3%gR{Zj#yOkNMizmeeb*MBrQ_{f|36 z58E7iQz>KH@4>FN0T75 z^Dyib?1BWGgii7F5{BdI5yLD(0=M1yCSwK7+qZXI^!eZaG=?F86Cr*5O}AA=oZX1T zmr7}{J0K{RdLfk;q05>II+c0ka47n+0pxli9gW4;{gnZIXlj06FgLCQ{B00HhL9lD z-Bhtu@AW(@1olmjbJs=!v$}s(+`De~BcgugzH4z2HSi@a#3ZuY(1PWa`&)j;LPQO6n| z{P;!dcWn=nncj3fHNQQ?M6AMNemMyZ_`lt1$aAVSZ7TRuNnw_A>=WbK-4j3pagN(Q zZ6yR~3+YDtSh<~BB8WF<*6F z-RDzVN`9<;MA%C?`tvnx$zq7=$7+`~ed5zAMwOF@MMOn$kD2VzwI$4qDw%9;f~%kr zvdqyQ(m2!2$_XBk++`IZ0$$fu_WlNT(!=)D`3P`p=i27!Xq%?V`RxyPR|&kTcQN12 z_Q@Ddd2XY4m?|b{b~x@H;dOVkn&(jqM+L^nl74t6d)7FT z_t;NaZrY{%x5oTKR~uE&0c756MEw4=YxfSi6)C9;kZU)K3J*9uQ zDHS>t@O0Kx{P#W?#AgZ7(i_6@X7;fY(D!A-T@QX(@tas}yZoq*Yvo^Q7;#)WBpFv7 zKEZbh59C94ScG*q85ufh-7u;FK@z?tq&8cdbi-p~%Brf1AiAE|Z;CrAM}Dd+$*hmL z?IRG@+RrT&)Ur?N97U>OlywpCX18lnKPWMhxPuOVwp2V8m8E{$L73(>j~k1^TJIvM z8w9^R-EB`wgB8M0ihKWjcX;Arid34wTFr$#;*kwV4)*UZfOl5Kx&HiPBv#aFRSTGq z4edLYiJm!4ar2i6+qf??hRWiC3WTd)k7O~0mS0aRPUTq;DB;nY?0%m6G7HDqc4nqL z$)Q}?c*{+J+83^tkL*jfz_mkP*!jK243C;j`d>QgdOSkzv^h30&HttHQavJkfQ^Nt z_VM)~^j{A;$4{3srM_J}TFIa~nLGSg1H8BP&e6gVe-S0k+a?K@aDmGGLLy_b6#0qg zTif57x8)6oF9JX6^gtL4>Q_4!&s~_DZo8d>t?R@d{w_2PhI>80I#aNz}F3aqw@l=xVMxH4dXHqB(k@;K$WZZeu&0S zl>YTKIJ1tfFr3dZ8Tk^ayRM=g^VUVgw4@@W#% zh0G|c_&v*`cQ&oGWYtWG4l$ORLC4L-*X1Z?3kH4&W>-*4BS~At8!}*-` z=*oIT&WYmC_wWbw-cw-qkm?e1g7an&*++dn_A7Z4f|?z(bYTh~9s9B&-0i&A zi*U{4;w9-vkWozL(IpQrk;edA)?Hq^kTl4$mSg*b=I=)&%P;8M(JH40>*j0|uI;-@%z#ac}y?k;Av|t8Fg=!yF zX8}_TZ#WDJdpp;!?KR}E(@P5ea>VtD+jpB_RUEwR#`WvI-YZE-Tg{Xy#B^sbdkNTn zE;p@sSkvK!EB6ZBmNgtXWxguYKRBU!bXDv!rKf%%wC!xVCBFYDhg}rCUkhPaR>}|^ z(1V2~UO}o-wwicu+}kg7gSXysr*CBzNWJU7JRc-lj5px#Wv4gca+7{P!!*{W4{@(d zu-%Hka7DQWY?Ltz2v5?nuicw?;3~0X~LI+gEFAsfYp5$~gMMWMA z4jyW1%-ht!5&h1Q(>ECj|BE#rG_h5+FfgFs-j-h9-qw`je#6*>_xAfTEx8fVvyT%E zKwIFzRuJ{jc~mM4u|I=qabjJ>FgACr#W6JI1yn&sFk!;46Owni?ej4qLZxA{L2!S9 zlSf+HG6QpAgj1)5a&}JPm`gJrtu*AownFh(f6=>a%qYC?Vu6CNe*e8 zy+@jMoxDfiV_&+lc*V&dZoqy5ZfG`T>V9CkS+zUa8q|!gQ9t)NROWN}uJVxlT^(G@ z{vfYn^Z?mkQ*Z8xqajPj=JsGU`;Tt*kA@HR4ePCcqrbI)x%y%dzN7O5a4(t$rujll z?&oLa@Keq*%uuBexs)F3D@;k7e*-smB7FE>gYR=3?z)-$!##@*Fy{B*HZQFXUE7(5 z#N*dJ*CfV2LMP6cnhHVB+ls3z$qkxsH7#IZ`_=<$p6g9;vMHU}#M9)7teqanR%Xo} z%7|e~A;Q|if*l`5@c?UfLLS<;T>?z%8ch?`UqpM}2 zOYmprjG!nadPL#HY&C2Yb;X99qdFO_b8973S_q`9+`k~UoS8eREoqb3DTxVs_nFwh z*>?)%hf}|bpHS+>2S3&<;50a#gu+=NdQt|>U7+xp9Oisi3e`$mK9d0UT!R)M^kkQ` zyOaKLP{qVq_*)ZrWjnhHpD#EJZ4W$nQeh_yuiBP%oF%|FR_7n3)$VxbmEIQXxcb0}=1oVB%FIj{ie-LfdZslW4 z$P|Fg>wzZTY6K5p_$xS}jcdW4`1+)f@;6fpu+Ef2cqB6uii$wfZKkZ0s?Ztm@4uEE z(iYM=`xk?Cz4oK7F7@Ifd;wZtKpAGFDOM~Q9fOG%1Z4l5Kn}cn9b4JYp<3a`A15TE z1#dgKu`R%4pFY(fSTmxoN;%HBxw!^i8w5LD&PHZkZ3Jj#t=mrfs{#*-@1>fEL9B!;QTw_0Q^;2>A> z=g++M(jJ>tyL2f{z7A}zL@aY)6=`A{NNpqfP-sf9Ws2$N2_IVIj%BApZfB>tloaui zeA6R5xO-5^id9n=Kh=qOvZ+SZG3)xdy{?By7&=0!Xln##!I*XNW{zoR_x$r}12KZ4 z0B{(ARW05yST_h;RDWrI!!ba?@5DUzU__mK$BYq8QTyEDhT=q1Y31PaFBuYq(31G< zr<_0>Zi8iU^SH#yd-M)K$7TMKVmT+v@C8G2UNT(6Hxlh{ofm6p&1n9f6?61enxJ$*D? zONsnt*bJOk(^ziKA7U{oq1F5BJkj4JeZ;HfqyH;t$V`ZJB>p^m=%tAQY-XN2{^Vm| zYzikI@GE0?l2&156O&>d3_c754iKNWD?Z@UioW5V$ona^B@Mw`$glDPLNFT1dp@E9 zM-Hb2i+P3W(bUZQ7LEk+&!wa!V~MX%+Z>9)xYwnYC*~x6Nos_Pzd4I-WvN5&_Ih*v zFPVzALNYBo?Y-((gKDWzPx95Lfa1_?;wrFxpYGS6@qUkr7?<$Xe9>c)jkQA;O#Lh= zfAY#xNL5W=l{~M&&1_IMatRv70-S}J-P&|uU6g5+*BWkCSDV|gGn5~+b`@MP{J!#O zl`tq!RH9mGQjfJF(7eYzEYXRcE|=9dcP6Y82*5H{(=QGGT({#Uie9XPYa04VIq#=G z-gcta*Gn_jpL%rJ`yM*xVG^b%Zs26JnpMrN4KheJp^pudR|D06>jIMClQb=r22YKF zoJifTP(5d7K~K*^+_$dtIg&Q232=fAWne%vod|2+)5%odY)H5LmYJ()7-He{D?N

    !SD`ac+cYJZo}{no%F2qa>OrF#`qJ18@R#G5d(f`^>fVdC<&J@ zZr*~}a0mRMmJ_Z5JIwX?b6u`U{5IwLZ(vSf>vSv6*#~-fa_twR=MQ=31~z{x&&2j? zxcG|u=~(u4b_^e)RY_v#_oiq#152eMc>25CR`@L0OMK?PZy`Uh-xEH2%>^p#PJe(e zhpI%e7(8AuInxgK_&|}}KNehYnPS;&pG{mtHUC4d$@*NA^V#PLhCPE8`4kJ~|6~~t z;_+?{aVPVsaEX(rWWO~$%JGK2F$x?7hQp5nJV0UfgK%S~#dWuI>G`L{Ge^^}_SHD& z+>|nI#w#}-G<{}Y-_evZZpLdm8d-|XH^*LB2&bK7rVHV;vvZ(`l8U97B*GD=!Ld(Z z^$#Q5;3X+<#fpo7pP!+4y*)vh{tQl-s04x6!g!>GBb}qs>9=6Fo&dtr6As@VD^Bn*r zGyjEfe)e_M$dsLVT<73tZw$SVK)Ab3V%}Q$@8R<%gu4^rY{ts(KZz}?>$x2zlP_$t zB>NWp+*`5wH(=$z{k(at{5Q3St@HGA^qHry_!`357MA_1+T+R56Jk$Wb1C-zw*EuC z{vJ9y=F!!)m=!JaSl{qwn{b}M>i>7muyvkjXuCgrj$`*>*^?hmJEF8p=cS_;3Xn<6F9R3&SVnVrf?>O z_Pb3ea$`Q3Hl0o!XoJm%x8SskP}W#6&{3rSfJLrVGZb@yPk*~bE}>bQ&bZLhywe&S z&bL~m+7!;XAUEx66~qu6=$~uhjMtf+1BZ&_#mOw$nq+Y_j?eO8+#=iN16G|O+sKq1 zv&gmitU9)m%?q~Z0(os8001BWNklJaVibtItr(%%WwTdEDRdjVN<^Ta_?t6+=CpKQ#wg9VQx*s^LTDllCqgPfG zsd#uE5}|}}OUNKj%xwD_12{FUNQIuXwQc0IiX@AjMBTHtmM;|owfVNNKi8Pz;mZe% z`#3Fv)TCmMBba}csvUy9&OWC2^N(#|w<9uS zi4R&l4wSEkKl*TyA7F7y*5|u<{bGc01bYzd{U^bP2a4R3^O*vQj%Lg5Old&30-Prm z3%;c23W3=*IejgBuis*0-eOJGXSX9bFQu6GQN^!*w8+MOiy!ALeq9zLvSN(7lyXfk zXdK-YFU|U#Ar+H=%=)Z%l5EXeYz^eQc*#JvODt@ z%d$Ri7$~x>U$^tN5WG3+3KD2v+9NOGnd_yHFn%%dd@`I@U3JZjJg;jB&Kk+Jjk;fK zyI%Tl&FQrEu=CXYZs!z(uT zGC26;OHx*iAq#N5pN-OgX!Xxv$`<-9&bs?f2%GaCSB4|6BiOmFm(DQX-L-U<>1QS2 z@nnW+XIWI%R2d$5>IP;hNllw7t{;?`3Yog+$q}}^^~2l^oX@xU6ZvnzBv${I@N*iV z{Y0oZ_oX0Uf%Thi|oC?qIaeR3> zGePSp8!_y$1Ptl-e`*GTgzpqI9A8X3VHlrEM_@zgaG24vS zOmuZEj$}Q47E7@iCx_u_Hiic*05!go{28I`e`+edhwyZveZc1z4iZOI7V%;iv z4#k1rBCzKnoIRN9H)9qyouWQRFbht&Y{T%%;j#V-N-jmXyTbKbDfRtESkIsFrfdw# z>8r5v-^TFD7~WxoyB)Le&~sc5hw!tvoy4Zq`%P2o`*675ZTPu&pyY+&`qLQR!SFnN zo$BuWGgt-79@)xS-+PD^D=wy^ql1M{?!fR4u=j&+L&=K}?pBHee?h75_ahdqZo5k< z_1%Gzmm=IJqJt9dV;J56y1Eu~!%~A^nR`Ej-`aq+S7KMj3Q$!{e10O5m76pZ$n8+mx@2F-05d(L3$YOn? zPvLQs`~%humaIK5z}+u!LqFM`3(81aQP^(c9oGz5Z^Ve?i$O~l%T7gMuSsEVow2g{ z&0BEGTDrK#lwG^5ggq<3ZGy8=)I2?R?ksZf;K62tG~*TNe8UbuL<49AO!9F{vrDUj+)+K2dohFFYPX)y4;i-U(K5a9Ze(0hh?&?%KzgjKm&0ZH z=UU_^E!?UgAGcU{RR4F%X+>{KH*$`mP%)7$3U^8~S-pyZ9S`s-hEAW>tkS}y87%<{ zljcmOY{;PXDn@;MN{|oqvD6r?sh045DMbH<&}r#J89N@(*IJ@5ZL+qtgj*4$6J^|r zU(Wf?3h?%%Cfg96)vu-S8%vJ-^)iOgd zgPv-g@mfe|W^HX5i-8l@jN00EvZBaM`wYcG7I%voF=X8kd@Zz^(Kd2QGh}-v%Q}Cn z8Rd0bG&4LEN+7!}f(^$8aa#mEA$uIOyzzsZO>WKk9Q%7g`|2P9G65FY0TV#09dM={ zFb8P$40d=1tI}m!RtLPH22KLP4)Edz4{tUx?SLO|Ho2mw%&+8p&igxE?n9eRZh26# zv)kaPXK=n$>~;jDPnj&gz0B;@0ZXK!BV^^atq%C7Op?oc%52PAB=-kg_`90vyW7#% z;iiJgZdY*BGgy=Jk?ArI_FLTYsN&FSz26wnLH&J&ntSJLJBVP8NzdTv6WFW=UBTXh z$%P>(T=UC4Q!0M&))ics^Vz@Nr0nXt%(er%(`6P)EqA;lZ!zW>6!X@Le*VzF*sI4n z;6!HE@bIyS)wOi#`7>BuwfwJ#D5lrxPGF!Jvo*=$S=2$<5Rety9E`F@&}r-6W&uW3 zd&@?m+ch82nr!V@m=++Mt&y6Ll1uS(w;{Ra)G>` zh4vnfJ^67awqL_FpI*!28-B>MyAE+^-#du`i*C4|p*`mUa3rvqpUe<9Jns0twVZkR z#oT?%CwTHcg_4&76)t5X`|MSG`lp}c{``L4lJ&VI=d;5R>~RIFq~e|FGRMc@*nf}k z%*VeODI)c(E3!UsaV(r~8Clm!nRjEdk3+0xf-19lgfXsY=mV2zKJQpKYK;Sj&>-#c zaKzn(a4V;U`dO|2HJ?2=>E5?C_s}^0c6Kg0N!8%>GzP!i(bm>RN5{No|7*r8cCXdd zwYb^;UZ>H>m~8^H&3H{r$kk+HckV2{WDf?XYZ#t^SumrU`PZ|oabU;ra|sNuig2qh zy8k`4V2FqRQV`e%X5r|II0xf^mNl+@uZ3_AV|Ziu*%pfH+JFlvr@K*dK4xKmnCAe( z^)U-O!}2Dv@&`gW<1;b5k*GW+=TPpsgi_!2;kH8|?JXEX!x&zDLcH8_3FY)97~V02TMFx;0a`2nL#+J$r<5_Sg`d3wSt0xc#H+&r>S0UWZQQFHD-XR0;kRDUyvT$-Z zlrGNR>PNE0PEjD2Cu%NMQa`{p-p!96O-m#iizd%~nh zXXhez?kqN6h-$_wau0YaQ1--Ft4cVdll*JY!v6jH`1J$ZIIlHMcGTxb@@94{wE13# z&6@TEPmhdiP^%hfR&A?h?8RcR;rJl=Sr%@K&=R**4S@Acm7o>U9c40=B=($u+^`Q* zL<~h{fjt&bm@-LEm-U?LEX@urw3w_ND{0TrR`B8mo-m*S>1r8!Dxhz&gqskg7ijP` z*Wx29igbG!ron49V7C5`O1G4;#{=v{fMW>k*#Yb0Cb?-JFEB_?>*I4~3*4%}o2$W7 z+t5DTsnW3t|fGFZliTZL*xSXv4;B;#_k|wre z`V)bpA=pY43R9+*D4q^M-{}wpZdk5uDQUpfDB@N$;0mzLC`KS}44|sP-omtrQx&)s zfmbzf5gP0a<%uJi;#g^hj;>EAYaELa$s60%fI>opuQgfYMvvK8 zj5+`tzCci8%f`@sw6;y5)kIF!S+eJxDw6F@ zgr6E8YmOaY*a1^^K(`$*iUwjwfTtY6#5WAy{oVk#Mew0Bd{%$S=ZI%;bIxZ1EyrwE z11`1{?fc>S@0K`ED(>yKh=0RiXScysf3CMV;u&1|wSc{!GKm47-05R{MzO#S*g7O= z`H;Yg3*L3PAAz(-JcHpc2>$hp-Nb;Kaz4YWL&&RNkdOh>)NMWkGkOv!&v~oKF?lp0^nF49@8(b56R3Jn44^Ncfd_JJywRkV#U!6r+vd)+l;e}EIX%k_3$f7lldZ?9Q{@G~x;ufg;h6WAa zCmX(NfX-b15K1m3uos}cW|MUH{`)KNA3QHQzrRQ=7<| z8$Qy{Vk?QU{TjBL>v63-u9ervZ+Ki+T*sWiCI)Yqk3=Kh{@iJ>9R3UKFLpJ#O9yUZVhH_rYM$G-n0LH=I++=qY| z`|L}ADfWMQJ%;xzx8{7D^(ITVK<-wbE3Q=h#h-Q4dZVJUG~he-?fAL(a;3eCx67xw zzhH9AGdM>oZcA_A2%lqu3j5LCw=4NNdwE;K`JV{;!x-9Eb{GxL9z_GTM}hrx_jaBp z_kb_1|D6ueIR4ha+C~ZF6JM5TN+7@RXacj%X!gHm{Ia46%r@gSGa1+Pk^Ln3!9=(vgj+g^O)K2J1a=38H;j_! zFu394QTmL&ms^99OR)0yg~xLQ;qJsNI0$D~m{tbvqnthmD}QP!>f*rdl+#yW7JeEY z$0&mvc81^IiIV4^@(pvd@NmeeefWfSI3M9`k3iXaJ6w&D%T5Auivxd5Iel%&q&-y6 zpME0~6BCSY+sW8>eh9z?|8Wn?{b4RUI*wV`$Qf#aBX{0_a0c1xijYBj06+U4itGNG za{6YjPdrQJ*B;^V$9Cg9*vdDDZotWX3MDV&x4ge&rBoE06=54c*1($8fNag9_T`Rj zk58`0r}xX*{nnVfa>K;%VR1HEcMSKoMv%$%h5nyqNCcI}8}c&3dqnRrrz zoe1QlWu}q#57>*Rs>EZZ2xe52tzY(L;u&>_gt%wTNU)6*{dlOE}GF; zz{JC#fQd`!dmF3QO`_Mz?FomIWfvH&s;;>$O&1tXgNw z*4VE$0Yfo^?6i+v4T1Q$&_1+raWeb0L8`bf(4hT>vB5f!+p59cnh$Nwdo~8xm4IBJ z{bcQ`X0y7jx-JDn1BP?12#5m@LhF-K6-d^VNbeWC)7MG{X z9Ptb)?+BRpF~x(Mv`4L74Y;nP==i9@jSDvBEjHY(LFe6$;HI3<8&YM)&W7QB!N26Y zxhe#O=Skfj_xD>2IRaZM&5#X`ZQL`MV+XX^0jqL87w3EqxPp;}7gi6sf-|K;*a5rN zYcE;x(Z zXGf$c^m4|F^)|k|+{1^9>!S7D!eL1$XS_$$EmuCaMZc&!H?RTlgo79Ut_+Xsivtl; z_9?5M*-CQo`|o2`n17$uPpgvb{mGrgfpc%TpSf553E%$10x{s?H{Q>Vz2`<}pf(09 zzUog{wL8Ea6nyTPTPWIBVC9xjvQy#7p1|t=Pt3wbeLU$hH>b+jMQ{!aykUdF{U%3; z40gMMr_;ZQk{5G>e41N%gn#Jm24G=NnPpOOFP~tXE@HqaDLU9synlD7%v1wr1L`2` z1aJfmB`aVb!kPM+FD$=)?gN`1pT9^n{c2yDXaZx+c%`r7rAyCmT1dT4qvpI> zZQaM|QmNRIONZ@IIN>~f6Q8%w@T*mF8Oh9_pOEjr7?u~Z@w(+$`EStGwU|wx{eAAH ziyIEip{r{!@`ce}MpFpqDb9F$Ba^Fk0^zmlJkG7o7w|LR;44^sB@Y%~L7gC3>}NlK zaJIZ+*PpwsKBi=E)f2P%d#uO~x5kvstV>3qY_x4jugfk)s!Nf7#3J*xy4UbPPmxR^ zN!~rRJfL$xXi(&!AoD;H=b#{)4C_#|Sar|Jdfm?Pk@FOp$CD8#E9WZYT-9jZds@bd z6&Eo)Jp8JXPi)5NbuairL0N$8sE?dfWacFSEAo$(p~viJ4{X9YDEN$F;p{oin%QxB zj4{;wGuVFZoA~_jF}j9_S$=posiSq3fy`_@_N1n?KP+?6KDD8TD`Sv5?&G!#+;%~K z#Uej#kv-~@8}aF%2w98M7Vd0CYD|N!vZDQIGc8F{EsE5HLLOCQ=lB|IovWF+O!{PF zXlCau=&$JVq)_C1A15v%zeA@j^k^Md`AzKtqpn=*5%_H=%t)fBP zguK?N-*UQ=`5iVQMkipTb;A{VAac;k2P0nXgRf}xiobyQlizeXUm5_0g+?3U2 z?{x%ArQ*E5gC*$evHVfk(=SL$MHTHS8v|~6P|@$`V_1{(AqN}#EslLbFt0_i=60Vo zp_K7%M}xGrxGCpjrrCOWpG1wn18B3I8EP;+V4$4?2K zY$*GnBN)tE9CQSoQn7-%+hZ$maaIGm7w7!Q)Anb@BB|(1DYib3)NxnW;**|3UaQgQ zl~^0&YoJTbs_50~ljvWS)t$ruOzN`5HLqF1&JeGE7mqopRZ@4X*)?<8nzw9?Eju3e zzUhXg{wSG5I7O`dciFP}ufu1F@4u|a{Ze=vuL)&~*Z4X9N9YH8zcup?`|OZK+odGx zw!h`-J2ue&$+|Mt3O~!DFwd;p{+6fr{~OnaKyJzEXVDu!%Xvz&b<_3HHXpk0M*jZB z`=as9dEkcV^wfl;$AK^W?htqXzc=#C8=j_^`@C*v?xPNzgObbfc_+7h^UL&SlDxae zXQ@=|^5FaV`b#1JN#}pCL@M4gP~@|r=kzM6Fr?yZz%zUTfOB~-bNMJwkb_)6UBWn^ z?mHY0m$jFZCx~;L`A+4ux)*GM5-zpor@KG`sT8G;DJLDs=%?{%(@aXBz7CHvHV%u=>A+mH*ZW_5D?pypT(! z;zs9Ra5g@S7`}+g#)qL}9xGN{Oj}zU-Jky|ZEbDr82D!%1nxTjPqCc;(#Iwh|4a6A z+vcyb#StVkpF+t?DGvOVo)F0V5nA%>GL*awEC0{0$o1!J7dYEbe&Itd(Ua58ZZQLt z9e95cXRjdtqxyK1>QczXiu@xW&kDC25@ZTV953ANO+_4Ekbk_so$OQ$ys^ltyH?^H z)cM@9AZ0d8_Rmu|#{~Jk7Vf-y`oOXx&T&CzTk^F1PpFN9uT_>#GhQEk@aF+#<)k7v z?vt52^SYH&Dgv%D?Ma-3h@@dRj#d~Rp2Ru27y0y7ZaDi)Qd5c@U5il{UCzeQX@-Y~ zxuLw9Y*|a^X67bw#x#pDJL2nk)Opa~X~8642LM5l~CaVql^e0kV0+B0K4`YPPP=s=0bu^OTiSD*9eq&$R1uYu7+_!pBXBh!wk` z-=Zf36ywyvS;FtN=TNc@HzGmg4PcTzI&BmP0lBlgCF!;$S=Ux zHd(yua-Su?tEIjjP6lYpj^MB(xFW2>K}T?1&gUrbV82DDRGcO2?NsxgjiF_W{Saii zEURBWc&wp(E2Y`82OYr~Qn4ufRQoOBz+itp@4Gi|;l50ggU-pnl}R&cqQAyzcN>sFm4S$)v)8o(I9P{I%Bp4)M}~o%&LZu7ZvK@ zY@=*34eO24#ucpmJ>k9m7kFWC|4aX0{PRo(|HYQg{J`qh|FKq{B}%f<>Sv9gV`G?J zi!1$X^nHH=b2biSLs0hOFi#^4`PPqYVC(w_qOqzLhrazEoCz$K_w&}jSwJmxI~WOFl`i=B2IP*_eo`d0?JfZ66 zdI;=P=!tv0-o``21a=2z;i)KHxce{*PtNe8RdO+NganwYO1DUkdD{xUS|+ zyC-bREg0U>@H`&DEVu;ryeO?+ufqiP6vog>N^5_Oz+N!J*S6dvDW_#9lf3JB`pS`T z|My@P9>pv?64rYuN1PF!a0O2nCh)Uw#?QSOW9TTwfjc5;<3`D2C6{Z~ZT?#`()Dp^ zuiE$WEzZkz;bxx1Ec`H%8@j*ugY3Na5-$1g2RQcFR#vRInC-uQ3wuBGHk7;wvv5DY zXYl2`#h`q1Sms6yPcx*2^EhVV-e^6Ux#JbR1_wS`Wax+ydCCH;eP;=Io}#eH#5-yr z&rx{C42F&w6dn(~W8YPbyku*BvTJWBL5xVcxEA)DAd)W5Ug#q`6@|Sf`KLnWm#Nrr z{UC*BObXA`{od9tD`C$HaE}SR2?IG-;RObETR`5^+h#j8+sB(UPMdMF28iw4S!~KS zHRBcSgFg$Dm6HlDp|4FZVc@n1oK`I-JTP3uZPn{;LTHc6N`PGn7#Jx=-kWwsOT2DS zgY=KL;fzf3Uq=Hf`*!k%mMPvB9OT{=*KwfxLjK+8WX)3LXK$WVnj7HIId zEzH|i(muPbWi4eK${^eEfPA3azA$A*Ub8ic;-RXRCvNnmO}CV>V*!1wTJCtDRo}Bn zl$J}52e?&1p&I(jhTm&a$2LJ!ri`gbvUmtXvskMz6xWi`E?Odaq~i>xmR?GH^8>mL zRqfZCtNM|Qu~YMyjcK`JH?G0dnwM>=qS>-TF@v6IEq7a!Hg@B>UwUx^S$r`Vn zs>>Vq8r^s?Ba)>aiW%6Ifb>+EbX7|=dohD-;FE8&v~O`-UkkMt5c$r z?(W$m^~QqlYtej(bpyq&p$)o04m;18T4slE)W^7OoC35zJpH)vsp{;BF<_EhQ*@q^ zABdPote)YQ{RnXDAF5|>ZQ^G8(+#(Zkt63{EPf(I_?nP4eJV$D&S7`^CvT{{OoW)$ zg3kK%CaOn3*Tu6prjc;I1s%?c{Ks3Xb&t5ZH3O7 z9OJp+Q27_5GzY{;Vg0t2+7ks#!m5-Z#9>&5DM}tf!}r1S_IpZ=Pb_>fUcDEn0W>tP zZ&j*7TQyi@#6rO|QofhpdCuse)qrm^_|>O?i)sLg<6RfX{=!xW|MqHxy2ro`wMs$V zD8JV0J-%nU-sX2YUHue3emKmn)7@AWySpkuTGht9h2>iwdSdk!QF=EbM3~BTzT9wd zECjmh=-gtRhAO1)Tz<>GO8toDz>P)0C+dln5wD%Uin9T*@jTWF_`yz3$}ifTG~u#J zNzP>KM+}dv_W~hI)X>FIyCiISFY~I$hA?WQnx#{*6e+|);Hog zd82P~VrroscXDeyt#?C(dn}T%U4(v;scB)tB7!Mm?8c-q=We7SmThwybh^;&NxW9!rXr!bx<7xdzFxVU{= zK921wGTasddqNr9J+>wyaF5vcXQfDznK3!W@F3m(eeRY@Lf`(qW_B;2zNV(;Ui6Y% zX131LinlZ_=i-nAE64x*nnWo9X4P5c)SAw&^al!s=3)e7ZGDAW8?Y>`mIZEcETP*6 zRqF}z0ZIg2a06-yHh**ry70e;Q^;6=9&$hrGW|01HQPLaMQ!(+o5ua(ozG$VL+1?V zZp7~vul}B{ivJ3Pl8_a3+$ItHkSf}tg&SfdI+E4bn@wRa6Mj-Lz4@_eUMh<(ci5`$ zB}W^XYyKO}fnET)#lqbPeau=%JF~+dgi29auJadKC%KJdq7n9R0S6N=6l@%F z?_X%JR5aPE9M+Yhnb&Lef|b%2Yze&?MLmSuM9FNj3YRgY7FPI;kP6sSFS;Kwr5}-? zrB4OwgyoVDOWNJgrcCXnnakhn0Poll79j?^S%dGtY4R9>U$^&>EgOgZ&A4y|YPIMi z-pT9$;IkLNB-j)j4R)Jj!Zzdryl$Q)U(b$DN2K^gHdAoN;I(KXcSo+f;d$Fp&@Q>a z8{K=mR>?rHg|dT8706C11ZO9?QYfPv+qTbByn_)PXY@~o_<4gE)6i@qmvH`EjV(q8 zt%Om_UEfR{GOQYvz0F)i*^%+%mU(Ao8^Of&m6}7=0mw)*GR(FU)n9|TlljM_u4vaU zE9jp)DX>==r8*&ta4&O2?aTUCIRz1wP=R4dh@B)i+G0&GnjpbaYzhe>5! z?|9+tiFEHwQ!qKV{uRM{F5X_dVLk+aKH+`upCgU-YO*_WP{cS%iT?QF1%e1wB2Ux0 zgJ-&m>C(Ut)SYrxho&?3xo0aZBAl&|n<&aEvXZUrYdeBO``_Y?mAaul4qA`k_f-sB zyl#3wNk{#o-#Ka3(}+ju@U{AB#q{+t>IwQ#5aaudL;b${R>4QR_G;n_urG3oRm=h` zG2cA3QC`o?LSoK%$y|Vv!>)j3r|a}nbW(Kz$PBO{BXYq zI=&LKGiiV3Q9?n?q}7*xW|?vtn~ zlc*<@oeU_UULC^zEg)E{z^>no$mivdrB5Gcu|4uqvu7NX^6wlfRr5dPP|i4^v!=$N z&raw@H=Ag$gO>gKx4>B-?OJgM0WqmtHFR*V2 zCsG(Tl~Z5DD2vhF%^`%q|9*@oTLNWd%);BR2`l^d!$&Fp0`xX#~wASrb z?3f?j=dj87?)&Ui;{)l_qyoGrFnE)4;|2Y_i}ORmwVT1&0#kY2c0^agxBH$abg@zH z%hx+NmK$WSyLpdnxCo-bf?B5d!f@tij^v}1l3R5Otz-)V;I3!d(dKDEUnX4RBas4@wV}Z^I`p;30ubUrsf)z^&z-hxE^^V@g$Ak)q+beYfhh($Gteg_!*&w8$0NnYLPEB-s(gqS5+p zN7x^8SP^r0Viq$M9-?UC;$nZ*(@I*m=)XA)H@{1os-U+zhV;V=3YeQ)6}y>aaTYOL zkKz6%@j`r$uAI;bgl1;X3Trl}hZhDUwuIby=j<^?}6L@c#Wfh4gRc$0QLi@>C+;ak03zZ`mkkhcjdE3C$S9Qt6-$&a@UyLnz9MJgkmLlVdf9p2wBxuG=9+ zt@y!B;jNXhy0DF-R4eV#sz1G_?m|d*_9jj>(>ID~Nm^{NaQjJanAJK|x7lcA=DK1x zPaA*Z^dm~RHaxwE#(UaP{7Pq`ZC@I#AUZ>>z#tB0g?1tJY9aDo@cK&U?3gM z0+~9W+op{@Dri~*v1?y`@Lgr*UFE0U6U1=sl#Vk<<~26!_Z+hpx>it2j?(7USQ0$J z<;b%8pghLyag5?3E{eH>VLt`))A}S09WmT@*`G+?F^oTfldvG^H97ERm`pGPSHvV( zlLDisfaqcKls%K@$(jS+Ba?jPvxOpO23X<8WgWkV6Yu+_f*I`Mwcc(%OOe!cCc7+ab<5fDl*eg9c`jdTQMF|>47G(hNmog7%)0f;s5{j@? zl~^HJJv3eY=C7TE+NQ(iYs2l{Z&!ocytDF-U?fSS5DQnpd%38el5BG_nDq8ugg!}> z=qHLpq_R^Vf8>2w^~oBY@J^n{=@h_Y*xR9J1h0<^af}usF}SA7am$Iy>Glai%wcM* zqmU|TyHM$dHonnAqzqa_gCI%1_Qz*eP!%}}y#m<5@mZu?MWD+5ELMNKynEf*;*ht< zQJP?>Y63R!siNs@*qqb%(ic)Uf8pH*yaC!?sH!T`I3SsD*or3%!N3VdNi@qqDS~Z> zl=pfY9FLLSYF?R8KXC!^zMTasi(TVaiDQhboj}uE1#17WzE{DiF?*GB&@cZL11cKi z~Q_3_%Z~JB2lkUE2`P0(%GxJV(w)=-*fZRbRfyP>bvqU~`{C#~SOx2o@IBi7&5nqg^P>v#Tgi zo_wSm+&uQXhf&pYE!q8UDF;G%3ghYh_wSzsmNd#>GlEST>X@(ZZx%k@o-Fs`do6eC z!zxvNrfOLr;O*Kw)gr^cpJ1TRu)U@;MsCzk7Zj%Ap{Kl26Iv*Ph=d55iR#|g zZ`Vk%AN3W=7M^TF`tvZRWr6z4@y~$%r%8-6!X%$0m->kFZ#HSnv~GOuR|ZwtL~C+k zUhh_Y&?e7NB)zmX)*dx%(iEikNXO`$L~C2e!~+vKdl+9{q=iL;!TlonNGp2}Mg#Rd zsh{Z{t_SF*=D!*$KusS7&=_SLicOZtmi)i8;<)y;#u4N{NS$d-%;% z9SaU98xInXNd5l#SstJR@|Q^gLO7&SVKQ|y_WA&aMcC6NVcuxR6U23g&>~-beNmjZu&_eH>ia0$VY~2_yyzE zg@YMU14>M567RHdoRw88?cnzyeePCnc;bX_2iEbD2M_#rKp_USqyDgb9YL959PbZa zpg(U%3C}_RBzqfvMubsOs%YHQSh1P;*?q43*pb@*Ruj6{n){W;(d<@OoF{l0A0&~o z$v3*__oiHG_+SRyfnD8h;lc$UlX2zUobv2ON|jf0Rb;LL7Q)78>^eT1)AL=XbifC+ zIerPH);Ba4&SmHkADF}}EvZq6iA8iO?=>#^gu6oeDS&-oibT_lWZ#;10)`Q&+-Imy zGWH@6^5hVegMXJDk@EW@JVK(BkEk&|>N$JKlLsVeDo$YL!9rA5pavbyQmhuNvESh< zU1PgpYPGW}CR}7l@3WE#W~*bU;N|ViR@EMeMJlfXtt_?of+{lj z=Zmiy4NO!A?10Q=jiJNTJMeRT!SA_-L%S?xC6&#rtY}U*%(psrWadD*Nf0PE0xvrY zqo-&uNtc2#eUO36VoEwQKFZ5+b)XB&+UIcMqZM8Mkm}fK#3xiXEtobLS-4D)+(5UC z9HLGMQcL_>5fC9HKt|yt4yzfV5kILelG(wdL1`D1qP1+v|C8QMj~dkipob#>k%Sy7 z1=-JA3iqH4Xg2^c9cr=%4(4FwX-mq8+&mD1S0=NPt|AtmJMP zD)#1Db0(s$dgx|O_yTqvt=R8M@urhv<#Eh;{_^Q zj;~|ft-^OB1%JGYXj32fkvZ-{M79pr^s&9&HT9S!G_g~wpc+>XT{LNpzW&uaj!HL* zg8Cschmskj;9qgAe=!*hEfug$fbV9Lt9j`dwy!1|^G*H`j9145TKI)1rI&C}t0NCd zG-0WdHZ*n*RoA)d)0m{tw*^Y)tt);HG3;=XBa*ArYyl=WcHjJv2r#hi@S&%;Q~u<5 zAbVRG0Y=i5o6XlPeq+(0i)kkk$OJg25=Q zmXskTi5H%2ML#`eYiGY(YeCOXza)x|<2i`FV>{g&bYF}sF`EF&O+K3HruH}J zI<%dojs`#gQ-XsG5WsnSrIXjvgpyQQbdPWGEzF0&w&s)f>|f=eQ_Z(dJoZ{w90Xa0 zHZP*3;0}x!5p(_R@$o&%EcnnRANO(!6_K3Ju+pRY;OGl#X>V%{568?NWoGl$V(@N# z!)N~E@{CGbI*qrurv_%xtZXTlBfg2ybiyUfTi$k_Pd?7lnRPUsto?a<@R)j*vuA{) zHnPpU&)xtG^mVDs9?Hp{uv4byT2o^&H(76Zg^#w3(Ys!C?eANz{oYv2d!vym`$GRZ z^gWrHJo=6=Af$Jp)-FDG@jdws@$WoFu49f5HF>GGFYwPs*GXr)=WtUb;BSPqzIovIhs)Gqr8=Zus250oQPNvW!kkKZ1So|JM$1Eu zHC=8_Fs)KvI31-<>=wx9aE)-v`$8 zP)l;zDLEMHJ8)24j_}Rh=p(dmwr$$gr)0*2yHs&VP7i-gzEPyTk+FnVa?kSM*&@P7 z-~F7iWybd+K5|oZWm8v`f6Q|WjCV>P={>V`#n3=<{SNKR`w4z+wz<2uF9dZOdU*PL z(e(7yNIm*6Wa4j#gW(AF%@z{EWmKEf_Hj|%gKY=^M%VDA8#De71zL&e?B_gW0WD)R z*L*ktx}u1N&rlT4)gX%TUJwEEpdI&0G;qTjE3?#6x0`2ROujVpL|xURT0i(V`1GBT z6emOKXTHg}cw-|&)k^!xTo_Pc%|VIDcZY9&in~ zw2KaAWC1~)ZQ^#u7ULIL+Dz+foXKAoJMw-MPj6bdv%=>qS*NyphJ9;)PK%4kQ#<-w zxNY%|SD$}0KuNRy;11jjjz$89UN7Rd0sCc(b+OJHLW0{3ex}!0@LgUfni=jc<7!LU z6c*ZRmFYDXE~R7;#7%-C9d0Hw>iMKTSxtUTYj#qu_bO7n?TKErVApCkdZV7QiIBFA z?_Lm`ABg{3OTz?$Na2cl_NXv=PaPp*pG>WrDtd+`>?J#=i))eML+yonG+{GZZ_hSL zd7sz}ZodX9eA`qOY}Ybh)i|eq3Nly0GC+|rY8Z;UlejtF^TuXb)4*Odm7}8M6Fg;! z-ANdjxl&u+Xl2a27e&{H5q9<>s`#&8Iyh5U!+FA9ZK(5l~h@I+pcz8o5E0{R2}DbVI8DM z#C^p}5SOC!^QTgff&G+2-Uy+z6-UIg%Eh%R&aan;TZ>o!K-G=4lme5Db24LIB8S$?HtoLKFp?e|C9RQ^yy9<7*nWb7A#RZ99K z6i?0y(;T(hcq4246TY`q_&c>AbTHvIK!B~ATw^uhoKvum9l9bLoHi%e7rA9g`T2_D zZI+z(1*<&0Na$Evp3LsVRKti*yJ7J8_ci?2@o11<$6EHa=LpDgc?5Da`3G0PVR11) za>G&Ek#o8B%$D90yg!v^zx=T~9AqcAhc4Bm$RiAc-?M;8^oMrQABy}%G z-rP%sYBLN;;MbjHc~iEO-VC*0`8^r_{OO+_ijF(9&K8JaGL`K9K$aaCUFafVp^N0N zU@q|~b3OiCnKiWU(AG26KhrliSuEPr*f5-oa4q)y$2&qQ2BrXn&9p@11%kaZ8RnRt zB*?Fv@6c}#|0+RNb5&T+!Vz86lM>Xqm+2)$N>FsRja%N>EBTr?;)A`qt66`Dq}Bj> zP53n5*1k8h$LwY}lxi%}%#kvD#@5ziaO^Il8UXW!DpF_*&8TiK<)KY$H9l=jsO@o} z_!%GALhDX&Q*un|l{Qd} z{oCese`=5DsZh(sTKwfyovZ%HQ?A(;9bXGSi8$Hg-?zQxJtqt4e80tpd1**vq{Z3L z5ZA&)f^S(}Jy2(>OUWHx)ccMpCskwqf(&d1fyV(`5E{@E1X2U6cq&9;0}ZWzW|-Vr zd^b@bdm@^+&hQ~mb7}sr-0_Bn**x|-IB9G-YWpOk);t8riw30SMJdw}*b9&K4evTk zD?FSkJX8uV4(GuqYr%m**o2K^5RzU7h`x*^qAv!Tst<%N)s;tO0%&AZq?adEw{wv$DEIHcoTgTd(Life$r1vg1Ls zjCBmj$Dz9f0wOc9M+;}#;5c2lx5*vN-aS<1N34{iI?{Mm+9&9uam)MgNEnE;2o^S* z@7U-E3f{Mbbo0{c3_`-iNe!8 zv`12#pTHJR-n%}GxuR30Wff*CSH%>tU@x;Grf#KQeV%v4_kHW0GGW@-cuM?c_t46;!gU;d;=;v<&U{M;UzFvM)Hp#x4Sv0CS#lrkIsQS;KKKR)%IGVZBq1Pk9d4Hz}4(coY>D_r~(G3cx+@81>E`6V>ANi>GsA;)% zhE;FAJv|yre}bVB7IqN^iYpLn7>LZ>{%DU}L^E?fd%3Gg)LC|lJo#P>0)b*{^dFZ_ z&i{X%hkZIe?KmrK@q$nOeNk~dc-HTyx3?SVV9?Yk zGYl3j$+_PNsebW3gzDNJ zGxR^9xyvH9jU4~rfO62R#QvSif|ETZ^5*Z8V4>%!9?pV`#QRe$`WAe3ZWw2*?QUkH zO`lA4u=!KsmcE2+(EDH*0b(^p zTfQskpBX-GG#$;;#+InGWp2DbDA+a>V$n)>1V6Qfano}gmYZ3ZHn0C zk=Vb=<6I&dvR+ib>R;cj-m~x=p)htk3uL_9D2zKvR=&obO@=FP1_x~+BTl&qPc;g^ zXku$X#e+F0o#eMsV=K2k{Nb!!823g54B{10X);u4j^@ZePN@jF@7l)4xp( zcn-Cs!Fiv5s4Oa;PtZ5HSi+}@1P~xV^Ce$|vA&%!bp&B8q_@sC?mE3JVd6?bh z20Nu#gG{|h$M#zA_w%gyR&e3lee?N`+inD{T#F5SrS+>`ZK*&i5lZ>2 zte|D-q)bG#!{nrJ?tsW4momI^sr|lKMiN1<7=7h5?~AzU(Rq6?51K^%cT_-aSC%63 z4~NB&Jgz%FBlWkA;z7#wVIkFnGC`!wU$Hkl-`sela*`*F4WA&iXqb4)-0>*|A5{!O zTcv(QyI%sM#GFgUbe*{%l(j?hT7)}_MmnEi+RZ1DkpqW`V-c-XQfpNo)=A5t!-MQ; z0{X|8E>*&GVwR{G=3hVwz=(u&;73NGMl1gQ$^%`Yd6j*Ue!{~&k5memBNd2v*G_{d&3tcwBH^e+2X%UYI z`9}wBGq)3J(`bG7;*_2g4Y%rBk1kTzwFSXFOo(nWj+OKvQFYvWXPWa>VU-rPE>VK7 z%iKnp-w4e6Vf)eJTQ7q`!&-8u3Aw{+dwjPn?yP^;G|ZXjEP+yRL}GCaa*wOl2c*L^CAD` z{Ss_edN17~npX=Ptj5P8XmZ-`%rVlb=;$I`T;T z^7dU8XxlSsQO{VW(xQCJRBozzEPIu+ooutlZ#b9E)5D{gn#w=&cGNkdbLl^}CucLT zB#-Cu=6}?W*RwPWqAC0!unlLo;Y_i@cTUH3i~xJ>mf~Wc5art%x8NT8g~|11QS-?< zx|%6V6K($%3{s{u!$@sC=_`8$#wm-aiT|E9bXN#lnDAjcvuv_LQ3&{9#^*wvL6O->h@x zKn{VSTeN?wW(BHmK&BFrE{qvWmihpu<1*39pzJ`)bk0D!{%ibv71hjQQQF^mk{*BllUE^P(Z7lPJG%n4sF_OI5@PIaQBYAm|uq z>nL@VaidfUre>U2|8XjcB`Mg7Zfi)c;`P(g*f6f;m3oGfc-1Fn#2|Ff`16(2cVA!F zzu)lG)xY9D=B*F>%xI@do_$K1QvzO5`*#GUEikTbO%}H+ufbzw{uG;3pMe5}T2nQ8nNRuZ`XEc5KaJ2e|Hu&VV+wn>^S0U}w@i&+1pxsxNh*Ulti-Au-D;|@Y{0NPebQ_K4ySarMY^e z{XbW+{RTl=S|7%yZ5IJ??wJeBoJaUlpog?7K8Tx=L+o?43`6lZ0onIsmAjyVc_vLQ zsC|H1CH8YQ1ZC~JP-)p@VHqQ`XGZXBr8%3t%-* zIF~)XjY(~6Jzc1ZiukX8PrUmK)2>yj?Dxr>PK9`m~jMDqmYvsus{;GLXjT=o# z%IsIe%Zv6+VVXduov?{*52+fr5=sNOFqh2jHRz~nFwV=)|7-wQ4r{TJsdUl^x7TI~ zcR)M-o=d#^HZv<~luh7*r;+1w?m+IwGj$eO2UD_97m{!@?MG1{9 zYGC@YzdKX~zm|n@b6B`yO>SQ9kJ-vAuvxFp?U6L8GiBG`D59rf*XG+Zc!49iYml*-{iZwJB>!p1#8rfm2_=jIz<)P zqM_OyF@>MPUm_oZ6JS$4z{1lXNP2#+>QI!6oZpP&G!Yr)T|m!2448=8m&Ius&G~zB zVrg~qiC>RfYsRRCUoZLSk_N5{=&96ul}wx^kWsj&IUat}G0DX5*q(;#nkPrQ$NW6x zb%VyfV$5wS+?KvJR^tr(LwbcE<++wkAA#^Dcpa;D+VW!I$n$&=2!dsL$c$>sAin^^k9}Lk0M+d1sWrs5+w?Xs@Cw zJ#aXW1y_PEq#`p3sd`?dB*NOnw|WbnJ|Z9&ti|5@8%y;FjtnevxE&05B3Olu(~?%9 z6Gi0_vExbnL(0GXFyI>?js}?@v3MUoSUgffcFVEw509oMhbe(DdIBfx-ZyH(Lm}Mdb?-ar!nw(e1y1uZZ{a4c(tv5WH*}8!TQ%~IRL-SaH z;TH=}R*fmU0HW0_BP96wN;u4`*L$v?gUw43PWj7VR`f04>cZ`Ywi2nj^bG?RvwIzrd|WY#n#(C6KZ6> zc%}j9?QVVt@>U$U;7s|O6+I_hhW8_CB@F6Rs(TZRshj|=++ zJ0)d%q9nl2VmNb4Q_ z;`FU(c8McUfHmQn`9GTH5y)+c<%I&T<8Hdcpn>{pNYIvJU$Us4+ZXAVY|hE#X7}ho zy-&oC744(IzgSF01RIKn-Wor%7y%!ZNtS87r0?c+@yU_(KnmPUpF2^5#Vp|n5l)2o zsGUKQeHyqd34?2BR;H#!c?)y30#A2-rRs2}w?0&xQ$G`rX$rlS63I6_c!8OaFb}Zp ziP@HH@xw)JxO?Owl3)Sb75H}Ac|*YUX}*4-Y(fs$ug8deyK}M zs5!txI4%Crs7uYDXAk2Ig03ahT{ z-Z5sl?5hO<%@;{JqLKVnedGm8PTAA=u$5FW^Vt|-fxji2=>!?uTlFv$LiOTmLe0mw zHY@Pz7}ODRHM{9P7GRB9&p%zlIIowK2q9?^5nUCUN=}9*mh?otL&DqGE6SE9B5k`2 zR2DJLdD)thZAHhC1XyMOI_5p3h$H_v0R}>fDVs$SY^%?mabM@_qiF>a?A!)r5cEou zYbr>fm%))cy z0^{j@Do9*v=-V{aw8uKGXza~MmZ~b?mXx!RNX2`y1Q=S!B@G-DhGlVRjf;0MYr!A8 ztfYxCbE*;8TSEx)P0~nRb<}p%3)+wZxw)r_J+@3%FoB3cNR!@SwG|nX06Qn)?2SwuT z>Ew8)0b$=?B7Y6k3=1GD-Mk7XW%MS@!lZ(SqkEMun~QRfmlTf z*PlO+-;kq(FLNDRzjX?75!rSmmjp6=GDY}xgMo<{@yr(H6%pYZk=3t_t#W?RZ)>!b z(`mAxOQL#}+xQV~H@t;`@A|zf3PRCex`60sy!~SSgW>@c@Xdd#aktss!rRlzbpIEG zKZnKZVqk~mkpA0BEbm*Ch-ad`?>gp&MxQ7(jTTXk*W3_n4P%>Xi+k#mUQM3^pF}ze zLZbjnUnEMw1+iy075*VO{bFHU?GkGlk-(cHg@1U@EdBm(Yz-4!@P>utJmk%LO3E5v zZ^bupv zw&}<7V~45mIi_OP8(Q<;=7#jgRYlx{>p!2j{u3i^RN<2FZ9AshVc^wt+>r*8?=xya z|87vxTEL2OFgfx(*mm9-@A_ujqk>|l-$3%>TW`Kc2PqK#%E)>xQi$?81eKF6rZlI{ z@X&j<02jK5Iw$S;?ZGqjoxZulc_=pK6(X`$^r|BQn$#*1h=DYR!_laP)&(rOLft~Scz*Wrp)2snn`T+ z=sU~JEluyjc**cCY9WR?1he>Uu1drh&u5DI$JAU0y{cFC$4DYBu#@Dld_pP4Li=0s z*hYpa&2Li3!gRwl=m1xgRR*b0l{20wor}{_7O`Y7O=^@a4GoU9W3=b3tJcTkv!9D~ z2*zmJ7?^AjJuOUjKT5eh>k3s8R(q6MpsMdWsA)ikwY5K6KZy+ap9SZKVzX5|@6V$; zi6)dJs5Dq%Q3eB{eiG(w@0?^d_%+#&ZM1^_7THO_Y8Ge)zw>w95m_?ls`V74CB^a2 zd9x#RSeaOUl;REa#cHkwD@GT|NQ65C#rGkoS6bqGe??2aAfu1qevX@;f0UHso`WUC znp6}^Xl?%BlRq9k);=jM7RuMkm^^V{LeQ^3wd>+OT(t2T82;04QOM2=MUvSz^_(&( zq?vU^sP&-t0w#ywDbfk~!V4(>FFDG)kx!YC*2)-8F^J}&WtScqiHd%5E|=pWkAZZB z!CRVFXX@)-O{{e9zjNfEvlWnE+zCnEZfpgSb$5T5Jp&T8)*R&^2C#^~`nu0;kSSa~ zgFo|+7W>cfd&5`7+jCW}LgA{2*P;AXQB4f>FDJyZIHzoA(ii-xhJB$IUdD~_mWh0o z9kGbzhJAbQ1#>#zjqk(&7H#BS=Fj-N&02l@0-*ev4#5?8!^@YlzH|4pjm0vUj#v`# z))C%Y*UK@)bb6nmG`|LtdgrD*zDFRyTcwD3_EaW#5oKf#=;@B0$(XQlwnF;af5m$e zO>B##`(fS=5~8~`-Q2n>%l67`AZt<>(hL zbbTbR<6~qus&$+iS>P=-SLv5hl%oI(#-oJz3-9XGnl}k7Gl}UBd|Poa3l8gGCiGZ^ z7at-?yqHi)O7pqRjo@{7`dHlW9@$oUaU<2&+rT^Swn+iqwZXWjv}47+#&VHEwJ=TE5nj z3ruTD+cA>)R-hLz(CpCZ*$gr~`Oc%I&jr_nDNtkGTbXM@t~&KzWNMmK)4ro^Ov% zFuh7MYWP{X=;g1ldoML^uZuP{RkV^ub^dY$+2By1V*q%rNMP?Zr=6Uy- zw@KN{`bAIXpoy^3A*-eWQ{=Zo0-umcwiM z{UQJtMpP@6Fp2U~0lls(B!vv@Y?>c+=G1)W9QL{(dh?ca_3&x|B7j44)KmLg#yPO| zS2SO#TwBV=&ZMRH3689$d$hSiVp^lXykziNvU(C?fT2bZf{WdQe!FpQrg!&qm}N)z zzNHquul4wyUi{jc5&L?800F`D)yR&ijMez@*&mH?kXD+lQPryX#y&6FzSKm!Z~zQ2 z$Jt25)%rF$Vb1GES+!nGwuK)*gl^%VCXK!U1_``(K6&0nc>eX`F1H~@Dd^ZlOYaZR zBYL*7yh^VTU#$XdF|SI6B+4-kF<04ecbY#HP9WouKp)N7!)_1 zvW;`q^nL|6gkzh$OPUVLls@n_lHtsC++!@yYR2)Y@s0UEF8~QBo#gb`{4C_b_}e#O zW#wi|Mo^;{IJe3!uez4CyE&k<`YTbpl~iS8Z0y+S1M+?1VMn%5Z4Kr;>-c;Pf!3$} zc>JS>pO*KH2t7}r=W20eYGyP8Xa>M6bJ3GzXh= z+x}lR{(@d|O1=r?=gZ6A?sqB>gq&`Yky?Jbsn!r99{DRPf~d~1I2(kmV}HNv1ZDOE z5o`S^OJtRq0-gQvni9VrWeJa{WoZ*sTAJwCQi|dW-@TAjDIm&4?H*Y z*uERGY)a#$dw4%W#M;8G%;e2D;Q&N$!{FA+P9T@&b+g=8>phY8-IgAPX^vMB|NZeD z;YtG?kE!sSTYeE`jNvTsf!l6gN8_-slDJiXsa^@_kOJk#+7h?rD!uy=@~{CQVpyTMq=do>GesmA>9y8N6kOP9}?;JxWm-KB7Co z-h$bfE+?m7KN3$n?2~ug)_(@tmL2yz>=>=xzHnT$t>3RUskE*LD2i$0O(SE04Zp>g z0U_zZ_f^s0-!eb}RjPYtIEAeGrIq0C)OMH;)?`obuPG8d>PjNJSM;0K2oc<+GT(hVFK99jlj)S7GJmap4aj#rzH-j|h^XJvYC ziXc@weuV=_36LiqkHY%_$Ce{|J&NNe@$7WAF(bE|VjL*Pdfd&1sF&~9HmsxYo2`Bo zFC>j~J@%A!oeI^0&V65f{OPA9LJO}a@~7X@-aH3h**$OJqZUb<`a7adSy_V{>>fnm z!ou%7c{dXVDT|vz5$kkG{mr~#xYelBCu}*o397Ls((C?00<>gDE&H<+)x`hvzL6yb znj`J?gME3(#Rc7BE?}0Da#7CqSW0@2-)RR!!YO~}@|>dEhb`inFk7Nn8OSPU=@&8& z`P9Pr_Xmd=Utsp=)&j=Wk)BqTp4qq|*`sOy)AM1(uXEPy^*5v#SMZo`4d%>w7LC7C zjkZQLOZnpcefs!Dq?0`ZwT1$2myBn7AZi^5xZi%w;ZfQ(S#}bgQ>G`*G!S*w)wo;D zk}T{Vjumy`Uc5$Y%42k|!l;ckP#|y@DXEQpQsB=M7RDKU*zFdmVdHygw@_OJtobON zo|w08?{%^Os?KEZn7&ho=ZXt@jqR@iJGx?9)?6op9~Hd!QBQr6_C~YC@bB3$Cy*-D zp*inbxf0nNaG9KN>yhc2IjD|t;JA@{;N8w%>A>rT|3B4OH!r#CXPiH*SD&!b1Duu? z=K*MTKtfxy8$N)8#1AUA=7i#thkR{Q?cHACRpGSiAql6IsU`i>jU0}y5o;BR_}S8O z4p7yx&ajm{cHQx>gFmDO7~raR_G;X$59h+D0m|kMWj-lR-lb&l**luuN4xK&01x1f zI6~=o)>P8dQ;ovrwTYr;J}FB#ZK>+)fhxI(jz<^aYj@r5vj4}^Sw*$k1#7rC#R|o( zSaEkRP~2UDyC%51yR^8wySr;~iUxOgC~hbJS?io!Wd*p|;hWj>zR%1!@`EOonunGB zGcZxAlw>x#7TBJKSSE{H8ptQBT=<+PBnFi%gocLvf0qZg*=n#9-X%Z{<0M5c*wxh# z8>Eu<;1&C~%+CCgB=eOYm@ZptxCOv7W$k2-k-0uk7jPc%)HyO%Xg=HsZ*o@ZuaDmf zp7PGG4-DvG)49Y1pq2R_Mfw}JK&w*Fk0aSevi*k~shCYda;%JA!A!w01S8cb8JrN; zf^16TtSQ?al~QcuRR|j_JBhBODM_pKf6i2Ws@0d@VmOhx){bKLEWkT!24hoe{4u98 z7E?X7a-k8g(8N_UzB;jJoPP%Et1Z_>AaUo!EY(qj_5dPQmEK;2fIT@iIZ3T^3sj9U zpr}c?#O@ad{pz^D=5ORpyi=cGq#|j?j{-u~0F9_-#2~V3Hpu_~nAE*;|8%JtrT^j- zo~aVLYc3h>B8&vht~vJEUA>I5yhK^&WGM8khF*P*M*kG;>e+VekIc+$^O*x1GRRl_ z7+5c@0Q{YmnY}`=`EDeAXk`i1OJ7Hl1w}&17~twYqH?nLNU1ZJsgUD zJ4%wjT111%>pCww~$~D{esQk$C#nJ)0x*LABRx zxMJ^^rt8CmYaWOgg};^XBICWl1tu1qmc@>dy>8p4G}sj;iur3N{q9_vV`U)QUT@e}5s);&+p6PQ}pS;%2OhVzswjvZ>hGCjSfHP?mfi zYmmi})bKfXa)C5qZ&*W_r8&~$k%s+raYk*h85;aurfn2}8#>vj;W4z2ntWemxX2E) z_1zoyK5FsJ5c+Yunf8wpNr-sMGce+#aO(oz>iRNHcN{mabFjhhHOFIbWaMeg?zLJQ z!6Z?^s*Z~$9*zk)#cG|b!SH5{TL^yekB&BanrXCh`K&SPyI)4c=3zr^DwN3_jd4-R zaKBUqi6wfP4dQJ_fH=noG`G9r4LgNdXxOtV&C5|hkSu9cqboYvM!lM7cdog3-UkPab+FlHKw85s$A zrwo!s(-_C^W!cRu>0o}6nk9}a@_v5*hT0|-h!^Qnz~YpjDE)6V!l z#Y*g_ac<(LAe+a~o2uS_7Gdx0^EpvIvHl{l_v=@o$Oe<5-Z+k;L_K0-1D5~#)?z3j zMg)5a1fFA?)UDKt%me08C~@za{9;i`z#@cFIH)Q}m(M*L97H}(cyRTZ9xpF{Uzvk- zJoj`xZx8u6y`J9HuihDI9+Iv;13OFiEydz>E2OA|^D!g_&S)n_E7B&}K$|9PQ{0+` zdOfRcm@C)|fBSBL>cE#2pNw*r#SAf;=~%@W#bl&UEz}iCmhy5nD|QwaQ6PN@Ov!Zw z@p;w0nF?7y)dRMS84X(-AS6^BCle0E`B z@<2jtd9AOgTTrSlo4O$bLS4NZmTS^l6!1*DZ1{V!n>4G~m21AWFRG0*9r65DC@MCZ z=2UOeNEwW9&MY6RbSb~~#;x|RVhtH{3*O@&n6Gy)e4#UJDT&sJBKc)SgI%Sm325+O z9E?SQcgj;Kbq$qCB0QY(bmBUSwwbe`_{ zX{79w$EAr_U$hWsbO=o6_gzQfAu3Ety#Xg)M#7|0BOk29HDIn$mP}8hb(&k!!&pkB z%}jw8&K{Rl8JnQId-$2wJW<@S4ud8)J*L(P>3}K{Qpgz%Dd8p(xIxYoVqxt4Q~RAE zKxDW`(V4jwM1scq3me!?Uebh}4_%oK^@K~n&m=kVFhI;|2yFWHo|NZX{H|d#B1x$? zEoy=A?;=*^(UUT>>*f+g2DFG|Zsc(RLaRoym95@_m#t@luZ5thCe?;n_(lF)FqP~S zOiu)-li`qd1_#aBf%r;J3XKd5uNyLIfxhfM7WMh}y&rche+<4n{2r%a>70t@X*IAY z&Uf(ou@_%+JwRcm&>EOfy~Qhe*vzwfA5H%_p67cJm(*VM(hkWGYkTtZ&kJuU@dXCh z6Z%bY>lC!U0)`*Bi7V?XjCB{kqTjOvnk09AFxtN>93I;tRr0I#>}odN_Z_QiTm?Y? z^;8Y`4=ZN(bt#x{z{g6Ru!Jb1Ww8W5_6JJALELX~2q z(PLcDqP$o+A6{WAE&2c!fGRccW41{++#x}kZN~aKEw-`?<|HxLC7(Wav9Ve;nWiJL z>wk%eQE?BBX-wl4kqg*1eRtD}pGJA8qo*N#-gNj>MYb=%q|1%F~qXi^WUu*H#s?wkn=8>Lr zAc6G@6A+E;ba#;MT&qzDxtQw8K$;!;)1FlxO^^eysc2cfD=w|BwuQLdU{?{Z47LAq z38yBssSX*~?Zw>gw67l3YSm?bXcr=Dcak*^)s(TJ_Iqdj(G}Bp- z`2sh#w&P*IYwT2cwR%0<+p-;NGQ)QFwKkCyl?1Tr9-35TjFhcrAhU@k&95WdISq#Ns{vtd{aq8RKXILE}Z(4 zyg!&+1iq#S#-z5|861^g$%c-Yt6tbIYyqthT^9mc&OwVHFDFfwkgwcdR?E&i(SCNg z8jsck0mt+HrRW~%A_Je5nr!$kdb>0r?dM6?kCQs z-+lf1cmrzk7=*!U_FSphtpo9T*Q(@%H|Y7w;w{+WIc(WPi&a^-Va zQT|3?7lZa2w3?{xb%o9w&P@-kik=!+HJ(!I`vN-K{6Klv#WbKdh-$zHfm@J>sZq18 zUa#*)`~xo5(2-$mSHHh#n|MK5zkUF?S!f^5ItI*tkOF4#a*rOhRf|S8}Zz zbmz^m8YnD1H(8IBE1^WvQOa#fZ$LzabIz)Uwx0`?E&@=@c&I@AocGHCE?w8shQseJ z3xwDP^?L_hOjx01W>`plD`5BewVLeez{Z+!li@KE+7yi{tr1%}I4P|#*+P>#X5GqC zc`vzxms`zwQpHmF=_s|#ae^;RYZ)_Ri~u}3n3!DA*#OrdGV@hUV?NQ$QAY{SS_!00 z7v?5OGj44B+8kKDkQ`z%C?mhBA+zlZ2Qn%R$Vh4x{klT;0IIK^qgeowE%n-zDcl^# zmSHu(^GL{%&5<4<`QAP68}`bM#C~N%~D#Kv8E~75Kx_e{1o@tJ|29)>& zv=QmE$yaYU*Tr1VvfH1~Qwce%)ZeA24tLF9bhUS%A_EVN_Ze^*E(xd){F~XkXWn_{ zxTleQl1G>=b#_OJ8JaEWcMCfgN-719kQHo5y{I^NE2?526acN-f*BKDN$`!I9umnF z!l>w*;I6yNhZ5AIP_Ak%8pa~p^rn04#&*c2i>m`Js-+j0CW5J^E%(o#e-yF$J6s7i zF8z?z%=~@>_o5%RepUU2!`@BmwJUJ;17rIVJ9v&NmRp#8*h?? z9v2r@3Lt@?`WC$b&RN5w-xQtSp}VV`T76&C9S6D>ANSw9@RFF^Bq+NJPKogGjhvlf zULO2#{U!hXlLW@4E#>vP6pj-sM^wc?A5Q$T_RUm+&15fmitu}f?NN(-^q)%V)NZd# zX1WWzG@o40DdKzO_x`8q^|*NWqc?16LzH3-vDeT0bv={U12=)h_t#ac^c;#+IvIPv zg;aZH>E=)xh$K(7L#XMqVzV=~t0htn@A2%nz*ZPN7zP`pyuN?$f;}DhmgDG>8FG146aBkG-HC~m1&~tLxFW@n(^YaVV&;Bk_5UK<{7;?lu!(YL_Wi z(22}TU9Eg#@;U6yi7%JzlF z;6N9FsqjSc2Lt*86C@u?>dMDi2QuqVr3!_T&4QCC9&TOX@4q=QHgi(z z%zEBipJ56s1`I-shF@0o*v_bt+L-2 zZaqDCrArrdrGG3NGv#w&Z8x1^jkW7Z7wM=*(uj6au8d^ykIdTalfqw{4-3k&dppi~ z-V42;AWTh{uq=RNkdRS_H4i?A!rH3VAO7?0uatI)5O;|PSygGX%1hDVnn=Yuq@c1m zEo;Y-N~-o%$SM$#D06uD^ET$nLyu=8E#n|Y8=IFL%GpG(PO z@0#6Xi+3jQ{ylEV!2EQqNG$`0pL?@+%!QB@WkG_3fAz5cuR0pE0{5^^ZJMsWX0OJB zXPBPZAz`yzxjY>AKysN{BX8TEuiYz+iL)+!=Iu83iH*-}x-3bNT*{pq$qOnif&EHB z*5fMW8_nWixmBg~>}R)27_ITjAI@*xTdO*>#v zIE#DB%uTNYKhb|Z{EGhXr+vGt=meELHHgDtka=tuc8l~}E?P&ZhN9C}o zXrTsw>-}2bl7<7)op-7?im8gjo;P~O_vL(BxYk57sK&}exm_lM9D&Bt%~V_b?cKOkl(Rmeky z*AKs%-c4$nx83kEW`1fj7ydoWotq*)B}!(*Q6 z)+vAU`}Sc9%47{;uoH?L)R`c>jVuLJ~4Qd&o9OfYx1mc%sx_(i*cuAASHkYAKLURDIl}-Zy$Nt0Ha|xtZL&C} z`FZ^c(*cJ>fj?AZ@O0-Cea8folXit`262`0d7$8l(ShfO{3A2zy8K|Q_!$Gj${G0S zlKCk|F_dZ=K5%p1`gtTKgSCWEOZ^Uor@{yX5||G35~R)~w6e#h226hTgA-LHn{{yp zeeM(rt7o;%a~#VShw_Q&BO>%k*rumZbnfx=LJx9pAm@d5YGXk7vdH6J>-rn+=5$h% zKU~DSW@L|a`fQaN-q01jrYy*9u2`U;fDrOK_r*}lnt>2`*K2?1=*W``wBo%?99Kh0 z(BUZMhPO>WzWYyv#nM0jKuTFmSFH`(fx?B z17}RX`pUaI4tsQ6*D==E{o-F4?8Z0c&8!k-t%g4bU=()Gw`tNq_S88^%d>QG*ny~< zsYN$C$WO!0C&^!nvo!-WR=v=+bL7V9kasKQo(gujP7*%<66mWJt}XY3Kdz?4^^M}( zKsTp(vg)1~L5{n&--NN5OUlftoO3Y#aWqI&rk&}$G4gj-@DoZ>xA;=TXfZ_=Zi?bk`M2KkZ@K4kCHKnaJfbE`IOZPc!ztu?T{0#7N!yMjQO5YslA6Ys(c&_6ug$SM=$_&V3lwC)2mB z#O%>AI%}n*Z9-A2`rk;Ek3~IK7dEc$+x!}>{0My@%?WoJq0<6svUxxU8!;o%AnSGV zOil+)>GC}B8T7{zPGDEj@V~$aKMf_p>bzq(8Gu{bcVN0)%RD_W9a7V*8AWiLFb6{F z2m+A?i^I=?aI!OhpRAi)9H7mjkdaQ*!Yaqxeb#zD()wt|L^{c~hvW5bQDqJ(%4Msf zF34)y_g&vxT~lEWlXidZ17nUWBZR(}G94#Pcz8HGb@k!8EqKoUzaoN}1- zwH~v!DZ~nUD(UF9*s3sw@{yRt9fc4Fpfkv4~y<%W=*L zZ7Cmi=3Whkp*o9Ieiv&@u5^Q0=RKKKCe3%TW;8l9khCz5v{{^)bPBS|(}JpVt!coQ z=q3J~99aKc!qd1CS6Zw~+mZCt<0=AxDpTx0?}C(7F6DWJf?ONU0#XysIsTIPb{4hw z6{`WY#gWftoiOhJTJl>Syi=yEInIEB1EL9oiqu!tZo{{T)J4>;*Lt0HR$_!sNzi+> zwZr8!m)4Hxh=5U^U$AJYYxHW%cC*Ipgbv%ZL>fXhufMZJpikls>kkc z^N6NRYQ|pcWJf$jcdz5lJeP+>-fv$8$GP`G(=1$=q?-G3SuIk+P(0)Du>WHL(wPD8 zGN7u?jU=KwI89#G^`OhV1iw_KtE)lysV+21-Rnd0q?~6n%m*BZr;z&(S-FOIW^DPU z1SHdgrTh*#=W&>!v(wLQ3*s9`bP81dW(-sGHqf$szs_5jFQ7reA6Py2xBTFnJF{1? zZAMSqB_&qldHkmpRl;djm(3q6D{}GzePuE1h&>8th!ggqYZmwViOAPKy(W>#dWn^P zyNOY5U?erl+!>dq`-4-0bIQ#`csIUVFE0_KXlK`){sUd+?+alg{uku$O9u e+M% zet<`wnj(4%T~EII-C{>wOHb4lmzp|iY2nW?d6ea$eht#NEq{$Sh`=Mj5=OP$$4(d zSGSghuVTjRW@yfO@4v~EK%&0a!v)1D!xhv!q2CBK@7UyP?JYIYRv60w`(UhaANclP zW%Qwv%rfS)S3=UnmR$5KYE5PU_GfoI;c5|GwBIPYZHfOM--UQ4|BLSw&wW7KT3&dE zGPI5Fqfe(@(tZU6evMM~8>8*h6Pd)qD=ni#)c7&?M+I@6lpmtT>I~~>|9By8$DeXX zUh5=m#2)btp|C5Hvzu`#H+Xy$iq}jg3-Z@iyKc&PI%}+p*sQQmwOyFuTLS$#U55DM zvsSa%VnsH;t4W2rwE$@(A562vB9AFQQiAs%=I)^JC-7t@lcpfPt(m z%2VL)YXKd9FFGVS4H!6E@nao-*d7C@CusWD56o83-}w9;h5XrbhQpi&fQ}uM=|x+F zebm;ab{GabJ9wjDE8xoD);w?RXrzCBLZ%@%9qN`;Nk=RWHQO zF!XmL!Aq|>1V3I^V&&s+XE!k54VbQH*~`n*lg`c+%a?m~9`b`Jes$kcg< z^5_m3m9~Q6$6b%tIcT?{!KLIO>DHfY%|CbKSI@ljTNLR|Z4wn%+)J1Q^VcS&heN+_ zWKKTHeKXL()tn&EA6Gc%44BuLW$)$2YP=2w1vYmAYnJJ9&e(%&Hb^&WOEb$@ebs+V zKCJjnYGieuxL0PDZ8Nr9yVwH!cYtEY-h)#MCq(yQu(q-)yqc;SgA`93iXibtJX{Zf zxr;J`L-JwqY==BGb6<_gFNJd~x%1I98DrUaQciuwy^n0_wwGr=j_$kTnkY>`>QsLa zUD3{!nro}1_FX5-njyiQZjxYE)MGg8Cc23-sWmhQBl^q!HG80pZozDPV$&TfeAydA zyU%~0RD`bnek^@H7E@c{T&pgu>|4{4WGk++?y7t%r}MQla?nX_^cZ!vn+k2i|278- zC6Hq8{}T?)omrMy3XClZm_l435DQRUyw`YbsMJ0G2)nZ1|H2lIG5;9LCro zLW=^v!yI3FWxUW>oMAnt*v8H4^%Dz@8$-5t2Tg9<3E#6?`a!pILAFx{eMP3aj5CLA zA%CJKiPGv8v+6>VL*}BGYw!3cY%4MS(#Q;6L{Q}SIh{GqI0P8f>M?Ua`E=0FZ64G6 z2_L4PBXmz6dv$fvd-UM~9Vw?@0y{O@zs=5l#V}PtGi;zQdm`5>LGHV@yIdb3i9PhF zt!#dHk-=bwhlX)41v{qiPcE$RF8 zqt~*)ABa#CnuWl}Q~$tl&HX?;XBJPvnI?&x{YS%EUgF5lyT6$kW9ua8IJ=zG_w0ApA5C?;}#w^*o7 zN}w^bi_sZL+q@k!RM1};yP@6dpM>Wv)~RGtEiqTPI`|KgRmQV4rgi1#^NZl}VZkVq z0%^5K)&UgqKgt!l@@m=vh{hAORVf9+HRo9hLKVl8$jL6m%2rJpGhA~-jVWW2$msl{ zDVf=!b?FjDgfacrz)LMY0Ijv6iI?CO&3Y1tYn3>xMMNaGQjQvTrBlcNibHTk1@muY z`3ZZR3eR9Lpj|42kl&4b-K!2s@rr4xcDhZyrlbC;Ya=Q1vwUb~>Rk7hJ*oSj2*8e5 zC81FG@#1I*)$)&3UJOKnkeoba`{PzcN7ozaP?)|>C*n^_3WyU*#h|?#<{#pReHIwL zQfkf-!~yDpwU!BDLvAWL-aXYHTAR&m;aM1!C-34<7L&(wS_>993xB~b?02JIC;|)S z-TV?IjKZof5%Fed)?&{EYo$0VZf2iTw?6|fD^eCb>re@n?^l!AMfMI{J0TTW;z~HZRwHUDTC}}YnH5DE!$ymPAnE(eWyOWYQZyZRS!^+| zlWUJkEt*c5{B?El7zMwXHl5q4u9%BfR)x`Up|$pzHCOA0cg)EzarKnd1t9t!Y{zc9 zN|QOPm-$1_UwY&l zwQ4e}^K}+nYMQdY2XCukWR%(_oceDn+jF+ze1BP(ltKbDy@?LUsW*sdCMn*Jn-<4z zV#}GIxa(!Gnx@AsULwgz4003)Hu0JTo#8p8M{z+_!x0?UiQ&FhLszMb0!S52RE`%@ zS-6ydl4ERXsn@zc^isqeeEcK<-}%>5Bi7)}uGiIF65qq18$!R}mncq_+bLpRwO+~w zrYxn)<*)%dC>2DEd)gOV6Z3hfjW#vmmO7b-+gOWX1PX4)q03I@KP5lbuEa2pQDkgT z-6a{E57v}6%j^5;H7_5G&9Cr?POr3Lqyraf@2#m1o_@H$1lEwAn5g2AFwqVjYmRZb zVH0R6Oo*V`*SH#Yv(yE2((@J`wzXhg=QIEL#N8V2C4=!L5yU`!V3OcsdjvDMWW$pI zMc`#;^1{CqKl$*ii>8)jc2gmKO(LG?OO^l1%W2r#1=tZ{v~Q8^oCafEfVO;w&2Loi z=3Tu{=yCcIjP3h8vy@*_9_V>Gu!`b|q2(TNg`hHeK9f9ux!U(z3IWE8a*g7z9Lx{% zz8`dB8a6&=L=@1>B=3C%6?`(RJd8MoTE*$l8Ah={?;90Ay}gD=?sK1R+NNNluymyP zeNKiY@xOh8M?u@X!L0#Q-N`%&jO3Gtti18eil@)v(i)1JN zE*)f4j@TvNszb%hM28Z39!27g5mdah!HKEyjZ~jCvpTaMQGCVtSoxsW#*1EbgY4rp zZgYN0Q`C5*7Q(&0D)IXQ!(*2MQ2Mfz3yLy9HN)iJ#RnyLXa6Won|m@#fqzbO#O@c8 zQft@2Ra)$y)f)+oVD8%C(%Btc+mZ40Glroq32U{ItDoZOllJ*$$5hVcI@}feD}y&k zd?alI{%7^9^)j3xd{KIm=W+w$2UcAHR-^1MUD+_*P4?5InGbdW0Rj6D{6RC!x5#C` zKVAQdE=mxdtP!re1S+cZyUb@Kx>1dDQ;7$~xrIOXdh^rRJ~Ic8h8LMO&I(JvEQb5; z->#ae0em|VOp8`2>0C$S9@_JRH$~dJE}OaiL{Me@3!TiqZ5uqpPu(jpKUb?YE|I@_ z-0aS^PkbiVU{?9NvcaKzP1J8t*XooXza+Cl(BIQ&tn|nZ-cP|1S>CX-_;tbH2t;d* zDRu5j|CT8ZTY~X!1-wMBXpFhB&xz-xv!$W~kqN!i^b0L$9)6A`P5oTI2ieJUpKUxS zSQM_90xFipxZU-5FIO?4WkE89?wh;l5q}&Ry>;PKErRbBeq?4pl_{hL>?4Qz1e{;O z+1Yu@-B*0wmvmLC@RoX5^hf*|OmYvJzGU#cta?$td52`x*iv_d=7&~|zum|kuOMJm zzFy;(k;Md(50gSKz4CJG_o%&*k5Ah@QfjY8VoC@o)=35`U6M3X^sl0j=&iIyfRTwM zU@vvmn`g8I7n$+R{O!nd3<2cG?duO}k9k)U4D!=(DN*BEx+(^F(_R@UK_0iX!usyv zsY9$<1z;2=91r4v-N@d~2+WVZ3eMV))kidg>fG1v;wHp6x;6JMOi`>O zw~1P4biycF4!{2G&BusOx@{4n(&L)PL&B&{(o$roXY7{QyViC1p!`kcl%@N-qFHw_ zR=w;kZLrH~{MgT!Ysx2a7?w^WLZOnI;aC?nCa~kw@Z25crbwAh)VWldvlExE1j{0Z z%)WK*d@~@!m_E=ocr_{d@J5EW%nAIAFTy*g`jFg?vCCW3?ZbXq@^U%pxipZia*E($ zuwK&*X*~8$k+gJ z(N#k?>~O_*ojT&}d|>@(pSvb8J%3ELYOo!muBZyzeI0uNR+~xaAp4n`gf>u8ZG}x8 z=>`9{N@Q+9;(^3Z!8@H1CE@E>Ldvv?t-rCPvR`6d|DAShVnm-O2?Q8=N!R!mH0f>6EVHJ@drR`f}*3RQ^EI@G9AM@sC=ARkyR;xGO zO5iTgA|6Iyn$B!u48ScZ)aPslZx+vs-DR6jCrOv=pywMqDzDn1A#JC->fAE{L7EI2 z8=ZeaD_<_UgFXbWQL)e)(cgD$R?n5MIa}slp4_7MB=L;uwCO#PyVZ0A`P$#(W7VqR z`(mBTBBT0FS+||!9tC^@e!5mUdjKjdUQA+$c3ZFR=*dZvz*tpgNzQe?k3BQ)k4v;4 z``Wces#VbKsLuxX3L4)w#<+8y{_G$Xd2!^j+FhIiXb$M5jRcx@5 z9#D0PNUx{RacO*ady4lqZ<6xKkoc_L4bT<-bwA;{LvH5i5EieWd_zaNqrdsPDhW(Z--#m!tv{2tq64qXAzp zb5Rj8dX>+drf)hf3Htf1F{@e=_?OC>`Luaq=d5P}I^@`z)poM#@rBCC&T9+n+lL<` z1m631(57 zPeTZ0We6r>qoc2`nmhEb+t0ZuZB=&|8?H6?l0esTG1u50W3s?bO0J&xhosMoe-YMd+{6Z|&Du%5N>J=Wzl9-}*_JK;24uI8E8u`q^Efr#G0jdF(`ctaOl_RrjfhH|EvWa9$h zgivt0c&i!rqhEV&I102@Y06L_a#jmpCmMf!>oF#;)Atw0Ds8VTF@}a41ZT<*U9%db z2Z>#iQjn{tJ9|!`7Rm4a73VZS*6q4~)+BMO)R1fAoYmiOyg8&*$0-d`T$Kw_fiNc3g?9>IeChjSILH`qCrU4$J~YkvyS%bT#N|)vCM)IOb6V3dn5O8E)djoh z$3Pw3Q4oQzZ#VFky~q+HSH9O4;n8^cfLa#grRnRvhY$0zIMfQ-7@Ef_oa-M1?>-Gw zs|K3ZbS+#v2g>Q==XRf-H_-CIKv6i?)k6Iwm1Z&B3T_jnqnW@ogfwal80g-r4Q=M# zdfZrbpN?CCG|S_H?h(3{;1%gVszX1bd;KJ6cskV2duA2shj>7DZLcK|^+5A}ILIC3 zP!XEbB2Jl~LN=CnGe+g?i)Sqa{gJ=CFWLiRkew<{t4ku;u5*kkWcff`_NE{z@7df` z$Ao#?w|==5^swHCaOs86^RSikHDYAmNx?uMukTPxO-86ExjXKi>qRBV`r`R4hmFyD zYP$Q=I1_wBx8Cqy|J%DkZQkJ*8|>`*@lFQl?B?-LWm(r7%x5OA-2#3OO-*~8a&OBy zFR0zm*_&p|EkZ*Po_1+En{VhBw4=YLOV=70w=rQF$Y%zOT^9ATRGTTir=(M~+M~f{ zu@3-hH~FUJf?M&k{cp5I;!KDb_iKakrQ1y6n1kK3=>%u070BdPbSs<8EVR zVuT)m*>`aG1}w0z)h{oVhXCKC&Af5>R~=ts-6N4@*m-)Iiel=ygX3Q)O~iu`Gv74| z`LgVV@fS1Erzi6@oi95#(Wb&@fByX0a(5>j`ZS>*;6V9lx#v=3KZ*1_H|S+DMvU^s zbt-{oovUdq)AyH7;Q9Wu?XL75yj{Me-+k1N+L>#M*y01S{nN)k}U%<5su|AYNDH z7elWXbdg{JGan*2k{B_|O?AKURO#$Awvm64Z5cB)l{H=%FF@HXW)pgYv;2icoa(l_N zvC8gL$GiJ?sJQ%kwt)M1U;X-VX0?SumtiAzFYj&ZicGPpSr0m3D5yeryKv}K-I}I* zF}54lhc%<8w}wo~ZfS)PJhwjy$MXNKgo9-dRg_3*P`(XfD9fy7?UoS%xGC%~V+Xl9 zqT9Vl!GG7K^H!~$+qjODSr#`7gMF7l4LhKaxm7NYzY7aaZ_eF1ZG~^iRWGOtzb^6^ zPLJQ|3~b@oyf|8DLRTI(_x7;+p>)L=(ba$y?+GAOvgcObywJ__2Pz-_g2S8M#|EAs zbvB9eeE>C8tR>GNL*Wgq7Cq1ZC~XSB)73E0eX;!2yIASZR2GSooB5Yc+p~N{bDYGh z&6SRF8V9$$aU=TWv@i?y%GibB5%jxXr=~1v)MrGF6_++jOO)35ts44hR~}9iGwCcf zPZ-Gdi#njm1W@KUW^D$d#bn(WQ$3+m2euX5>_Ud?Mk)s}M7P{vMW_(&)oVb%Al}z2 z(&}Lx-w3L;aeQHHhV;d4IgW)WjptR&x9AU>%MEC?6nz4nAY@8uH=S{?!^|stSSk(> z|4S?`L*ha{V0b<0nHre8dKn@>{^$7DRd3<%3>2O!9eDNmX5QR?QL9EYALeX^g(HaW z;}*BnsH4{x)sDS)+7fx^ym}AcfY$3}p)rDh3%M-DA^t~WanF)>U$x30RMp_*F<-oH zBOsCQK9`wi4_W^Tj)YFUa|`*s8khiO9gyCl`A$;ZceEDM&zNIro$;1!cipLM- zc}!bZgr(Z=wtth`6<5u&eNpY%1!tT*CDWdr=C;N$StD>%+gJUm`u&iOS4yE8A#Wnx z&hdBcsAD1MgS=<*2-40$k1yyFaGa-XjmfO*=#pLAwFGNsV58&naMlC8rG4z^y=T@8 zYI`D2B?N!#6WW5h(m)lpi;;Ofj?IdiZy0(I_df609Lc-v94!8EFR2>%50|>vP3P;SCYP9E@?gAPyR+y(^U7 zC)P_?P!f(=#mNt2AHZnfqI7!r0>rEHSXYe}gz(O#GYAvCc!Iz#7<7Uw6{rsul%=X*xhX3UnZ?d*ycUGJ<`@~V0 z2xdh)-q<1?aUrtC!V&$K=B43s*MAQjvS>|Xjs$R+7>&5{ns>65C%Oi2R55z8=pxKZ zK$9iM!VWQ^L?**f-b(9eb-^fnuH_yJ!ddKa;jjFFlMc|t@d3mJzzub_D7%ae&%zJ;=m1Uy?Gz)zl!oFgD1nyNGZy#|*vTiUk?Bg#KHgs06f$}GV81wa{ZY!Q z?sGOQvBWu|VEoTW@nkZSv2cFoCIsPC%?&%fbV6UDQ}FW)LrtCfQu1HuSp=`5^a zMSVO>rzKnE)3m?#;Lv0&E+x{H0Cjf0e5OhUNvYT4Z5_gHs1UYL(lUu*rK5Hl6}b{a zfHvgcbPa>%nhhdWKl+acm@8wy9$Mhm<0f zOAaXuzDS|)rq6ZZ8EXaApF^^8H3^FkwU|vK9pN8BlF)t3nVJkd|GgU(<;;CdE$v$K zxjEz%uhVasL-Z2R*(X_b&b46q4$qvI21f_w+~ldkPJRVgkMy$|cgEJkD|GXx;kDRZ zDS|n#J5IDpT^U(OXBLOi%7K=ta!rgVQcizxqTxe;Ff}#}QSjfm)ES_k9amIF*wx;( zzGPU*L5s447Df(bU%X?rYSfhy&@J6)Y3{6iJq%)f{}#}|u75^ZX#l?^#AF|8j0aT! zGpx?_s95lSEI{wqNn6yrZ;#L;(aX06jGb-^mOf(gezUkdK2Q3XHijb+bJL<;d0wD6 zWT6G_xPW^4?xyMZR-x&$DuVuOB>BbrNfZ8Sab7DZg%B#6%+#vXNZ>Dw5UWp?E20yEoPNje@MKBw*<7coSgFJ=mM ziJsY1NGEh~AQO|I;X8`}rkuBb2BfdMS_>wdbADZnbT@q~Z^s{=MZUi#I1lR-*882Z z5O@UsRdFnBhn%~pysKOzzuXtEKJ=Rr*B3LT-(TAZ^}&2>!WP6p=W&W34v-v%UA*bo zZoCS7y!H6TJ4s$ZlX8iYukQ8^kXWdz8H+qlWRM+B{;J#v(_>d#F*%NhO7B1PF6gbj z0+`FQQs|}E4g4I>OMuKu5AsP0OGAx_yo75XoI*m?Y5?yeFv*DAK8Twv$%_^7^Wvuq zu(FO=++XYxX2;kYFY=M;c%<50o6NWUhTi;ch*{SlM*{OXJZqswO406s;|9k$@HpjE%T2OGh z+zj$U>VeN{Pq~mf@uR^PULgUNW<&^3P|)*2@V0$j$QWz&19TBCxF++`_PEOO-@d+0 zEG0S|NP5O48G) zg{gyPz)kTIMwE5z!RkKyw`8vAVny)%2Cf*XRqEFB)HV6aU?l%@aVa-AjXNxJJZ3uj zKzw71a4;+D0Nw-N==MGZ2h!3G2|&VEU<<}8r{G4F^MY35_556ihaF@biX=gT25a#% z0Z94>3KG^8ECZop`r(89B7dLoPW%jt#hhc{&^ke`e)$89N4(MIN~q{}M$mm@x9E`c z!NaIouM~-g1iSnmW&%SHa_S;EMh3i;t~}}M{$Q0?>%=~;7KdeKhU_6;zsyqx2O^SB zD3QOSS3Ix5y*#35+%5mx?)mXVfixR>_{;~_JVyf@L7D!_UxDuXAARi(k3l2>3&Bnr zQYLAYRtkX+f&XC)rc3GYm`$j#>;&mZquCh`m{KB5M%zqD!Hk#|GzWd90|CPVBxxR* zPV5#Q={D}pPZ|(*FghdQb$Eq0o1a~gv)P_KzSd^P{JV%|>9pQxwQZ2~Fgc4Dk{JXQ z3#{y&j+nogw;JI&=Lu07n#1T*31}Jfoy$F2^|=}&Wy(QppxSWcB+a9tSkr=khtKwey0s={t7AhpH41_Fmk&K=9_yBCZ7^)Dk|{p{H<%-zC;`t#ya5zMrU)ZF8-) zgYgqoDoM`=>ru}l39-^+uvYliQ}wFg6Odg5=BWN4mGed!)925}{wF99t87y1xCBN+ zDBE0^&^(A3`=z3@x+BA-7!@;2YafaeHi2=W+mp}2q6|~{hzoMnzINpD(teq{(U(}> z#Ia;C({cyEc~P&rz!fw_wxri>+&?U_vs)O{?S8y?-iC&d+@0 zJ`dWip7LqKg}*?B+fyGI)mBz*Sl`Op2Dw`Z$^9t`EXFAoh7l?#AJV^yHmfJr3J=%*&&;eXC$ zUBsn29=#=;+eq7y-=;Q+7BDogIZmkS&6#P6U~*BlDjvF zP&pGW-+DRcI`(%uy0^qE9V_UW=@L4HPLUT+p0gL)tWnjvmr=%sA2U>O+;9mpQRKT9 z5P%S#wd7|)RrMYLwRsHY?VrS#c2(2zcXd=u0n&WotQ(u z;PEMo50@eypR&knkZSAhU-#JuPWEGOo?hP>Cgk~<0w>RR#pVj#G?81ddx z#6zCV{r|E?c}nFCF5IP-UwC(e@?Y6FSI10!!(#HE)$tFgdzJ8{NqEBK{@<$MeevxN zXSYQ~?$#jk#4CWvekl93{P-)@b>0lAe{xdgmR*j5v!KM3OS+Kl0CU{Cdx#hBo&y$u z7O}Gm>E4J^KF(2k-;HUV-?;O?Xz*vC)Q~L_DA(9{mfGDf@YpZy)AbDN=ZDk(;O&t> zSzEe1`3fpqX@<0}uT$IdIiBl0a8c)fe|!B(9sjpRMQrI}>zuL)gnd~A9I~nxL0NaT zWa0R`SU9ZUYeV?_$$$G3h87(D?N7hR^eK}CGvxZQ&tly4{}P@tvGspBZ%wffJD80E z9pTfmrf78Uv^#}8)ty?7@T8-E_rQ*J|A2;s@c)e^#c{)ATFzTGr{boB5AKroH&uf+N5n> zy?RaBW+(U9$vlI2`^50@Fe4)?2VnLs9s@9Y1w{hChKGl*Eco?(=tLSo+8^vq_m!&L zj-4)zLJKp@Ac8E?jj8XR!3;ZC)!~cE*D7u5lO1d?vuL^*s-CnB6K(x~X<&v5%GN5& ziJc5qRViex>inYj-ntkUscix3yRSyNCboAHGi)P*IYcmv?KP0@9A-GAm${V2t`S5q zr`Kr++q?QAD65tgBmDCSUm$|>m|^phP&SGEd$tohCLegJPURPCJpJt)&*!hg_Kpxc zOL_EDxABGFgoo@6JXE-g*jaYTQRdA+(Aiyw$vS2=%hh4XO7CUPIcpiJ=Ewk7yONR6 z7)o&q3f$HwKcdUlFN<@a8d?OWRVTx)H4WUAlIn4_ZCxSp zr67<3U#c>DZrD#SE2z#`ge?U`OCu2r3ky7WqQi+3C-}&z$9ZVU^#mZ?KK=wrw}Fu&^)~ zK|Y8#EezB^g+w{Nb@>v0aq~vnPd(1#v(3ME-r{^jbyzC~a{{LmQ#n^7%$Q7w4UDxE z5J_yrCzfqc^DQWw;)$gj@P=)iPE43l=W%t&!Z1*Z*f?ThiGsEcF_ndyvII75{H$PC zTPa{COr=Q0fZfeHPB-Qw!`s-^Y*1)5D6|_?v#MQ~T&NRdRoQCR!tE$a<Z!=j3X z+m$#*jC-5Jd4J5JgsX|?Z-egeLo@ zEZ$#=*yu_g@NDiWMVtvu-r0(AH%q)dHj}?lr(Cru+}WU9wV|s(t^b_B-7E=@o48vg zQ{T{v+N~1rFW&xOcC~a_qhD}oID1?KJgpV6=gsgH>xzD|h`dQ#>@Gv8Wry@D+X7>r zdv_0W?|sX-clQbo-968ljk5^}j<$KHR?BD<0S8cDie*L#NeW=aZ ztCcl;((w-ls}H{yU=f(TFt$WR?yB9-E!|uBNU6fXqbGUBc#4%j^t)6au{iSB$B{?w zVmNjW zCvG|FL|*}7nUA%ks-KCD=w~%YujxE?`Ef)r{fgV{3w!smKTv~1q{@K^@$~nG z0oOV)mMeLXyEw}=WEo*UH)y5oyoT>m9}n{=NH6tk2AE|DbBqE*Qx<2vD@XaBT*C+b zm4mpft}&MxnEm_uuoGC@Ke#4ov-|I}lXiX(Z{26AO`A3k2C=-wV*qBafaq5vs*yA= z4I1Bn;00~~X}|x+<&`{8AOW&gbx42D(kRShhFL_=>)4ZSi~8<4q}xIGIn3#c)wCi| z(uSy*p+1>I1YLx$dfTjOGgZv0vQ4C$O{YnBh+1V8(jCI8&Qq&2X%sqG)ht%^JR+D! z_zQjO-6AS>s81e21j{hPA?mwr8U+Pr6N}@h7$Gh(vR4E`zZ8^BqE@+%M&T-~>e)+d ztC*Ru#RNwL{tO^!^ygV2_9xFC$9NV}5oE!>3j-^UH9C>sa=qU*YO;$qDJNs#$kLsbqs0K`NOlQs1zO@q8n9iAami>l8*~I2O zdB_^XAl|G9vnGKlaGR3f$j$Qp8@KS6FC65r7hc`r!EH%`oB|tTEy?6uo$?Z!iRByE zwa~zADkbj3@(sALs09PM7q$L?e*HSCG))!X!wDiA6&dY zgRV$nY9Z60lUGTc|Ji%@=s1r1&i6AjK!YHQAUS+BnyV<>aGqYfx_Bv0; zHYT*=M7AZ%mSnqIq$Cm|si8zcRHI3PO%g1;8o1TCy zb#+yJ>-+s`c5E!S@1`_RJBpUV9!yoW#Icb!F4r|1+et+lh)qYDjf+KJEypN&-$E+T z?A^4YjE#3zkpCAU?h%2rHfk_tW82I4GX>6u2lNpNSy@k((Apd zVB=^+%3dgWyck4{|8H<294F$ikuh$TGLE;~(8Q#T_lb{n)D?VbD9c{Mp1somw(;*2 z4d(57CrSX?(6@MZKIFV_u}dnRGhpg2sW|Qmb{ar8G;G=*D+a7F%-K5(3-%rPkPC(l z8-uuOohb3cjhV7X58cDAx3%-F$40nKD!yUZx7$qmPPu~1zC{|?CKWHbf)5Og(B(wj zI}?$+NAcI6(#%+So5FowgRsq@Z2tZb_oP7Hu5eEX{4tB-j|KGoP7Z(U&0p8V!0a)* z#PDnQu)Z273!v_j$cH6co`Tc+(PqRJkgjRAY-*0a2OI6cPyeY8L|A@6pAHPhs_T{9`p0IpI_k4ya=XsXAyTl~};4WG2a%I|p?Cn4sWS0yfIy{2H{V2H^ zB^@G1B=;fLSGjIp?2?MLral_>1Yz&(1jQcH$JJo&gm3ZV10$Rw$2&R1gH-q=KTYIx z=}MJ(Qx;;sVFiqt&m3?Wn4+C|Z0gKh!*BY{Jx;VDX&bbn6*o$BbS$~)#(tY8*DP*l z!_`U%-wT_OR($8jiDqVIS{Tnw94%n>P5ywk0NL++To0s;8fkBD{6&N(2zzbA z+?;#Wya@9vO*$5VhN&9aik9;7FE<93MvL2soF%{<-ThUQ)(*m68{u8L_DMVeo?zYp ztLOY}D4Atdd5ks6!Z~{f<3IN}!o9%Cp`%z*Gg8Od!&&*GEafFK`4_1JZB3xFl50?M z4cW>F*~&`@?>u(-*rIzqLD+i>L2*|C*aD0kcsok2H}~UQlPB#FgsTT|wXf{SrhVQ; znBTr&nUWh(awC?1B>`>i@)HR6j5+^hU=C~aa>Am0qoa3Si0o2S&Nl#AKeF&63r`9B z$fB@1ptw3%z>)=!9Xg-989`x*_NsN~MB*na(~7}%?ZG;9DYanMsOnn7y4()(vmvP! zS-v$fi$U4;UYnpWrNK)%r?e+*%Az;YlAM(e4Zt2yBU(Or zsg2ui_NhgTW~{_Z)=yg$W&;LhMkrYtlszy#k^s1s_AE{<((cSywvBYphi#efs8;B#f0 z?=!$`%&?6awNDOZxj!E!B;*$#`+n~Hfnh8$#&)UrLfPh_V!-pR;6-!3e^v~rqrGXf z#%K1DZ*h9cqP8>Qy;())6gaCQsg93~?k4_&?+S*%Q`d4g!;7m@J@iVqkY zn2SWtvgBR`#XC*EEJ&{NLxq4nQt{!|oZ|(yBHVz;vCshQy!l*2vt+LT6KDqQG@Z<1yMp;j_AS*8h(Z0V8Yg!+tNL`Gpq0s9PZIt2JgCtglwNeDw$l zilC?mqq3DHhFQCiMH}|cBD}T*`w36`%r^JIl}s^mAcHkZ0@en_4um_8@M53Y*(QKC zlYp|-!IcEXWee7mg2=f-c4&fZr3=uYtL4w3WCxZ%k2Pvx`4-mbMn(qKU&W@qR%9!e z6HsZU!4bKZFu%p*`FV5QFBlo*m@&J~$T7cQ%EDeo2Hvq? zfFN>~6FJKl0JB=wxRyw1DY-#=7CkgW{g5arw(7Yjhy!CW-~WSvZe zKc@#dy(y7^vWGVv!J83OCbJ8evQ9d}n-j>iW)8VEL3!RzSVx1kDyL`aeECX^7sf)) zoOzjz%LTXBrpWBMhjjNgocV|==?wp^eN_U;7A^)H9IaAbrCGAEr)=?@z8BuI?;dkD z?i8ImRc*abT5&_Y%cu6<$7fESVtjm@!)K4+S|ahBZDyQ1wI~5*<*Z_0VuZfs+Bepz zMGQ_`thcf31yaZTR<}-TDq?U>1FV&_2C)X_wWnt}W7CsX6zhTZm`w}v zb0GuK2z^#g|F3I+SEA_8Xc^`n;|)5L(Z_57vj6*S?ZrUtV(+Zw+kG~#+{gLz=WmKh zEIt-qUFeSiWo24XY}4NB`AkTuZd0Du^2G^Qn+mj?vhjGWq_PPswg=sAET#h7x_&ld z7Vjt)`Bd1DJ^o;Xvo1WgJu%AttbmP% zVQT$W@xZtpEk_d7?k~!l1-0cmc{^WEN$#KQ3Alm-($vmHs1DA zB|8Ch&-qp&YkbrIqP7zylE=fw-*s0LAiUm49yhaUV>WGkjxhtyK0c&D_jN|v_{pIx zd*8O6FaEDKe&FZ6&Xa~I8~PU8rQ)J*@wR-(fA7ojP%+@5Z*i}YKCT)M+IzMsravdx zO+^1+c9ZW3DSgp+&B~CWZ)GXIFQD{!n}L6+WsXUqrH?;n z0YXOW9PS8;tkm-wdE{5&QVwXFhg1#WehVdYKpQXakC;0CKY<#Nvjz>a#n04)DfA7A zV$GI>hOcNQS@-S(``P-)t*kno<(2KvUKf}>Cp?bYWhSiA*JS>_*1LSurtU;t;62rY ztXGmfLGdcUcf#^{)+~GWHNfDRnHiQ}*v%RxvHb0fTt0$YeUz-Lf5VS# zuJb=W`EMCratA4YI{<%P`(?b7f{QQR&+4Fv6*-*RyN@X#JpM~W*&*7LWKOuuMh++m zN-}NvOc-C;rFMxcN^&{O(ECtc7f!S>3sOeV;!*rfUxM#5ZD|GjN zZNYWzF?GUGPmoH%Bb6-YeT%Sn8&E@d4Mn6(3MPGvak+siw{Z_o@;7`Cs2fmrhL};U z{bVCFD0|+Nk;^P0!lA~xp)6BxA#d4uJS_%`TG5Idr~mWjoiNbytG&5n?b>y%3H zw1C++S!~+0nVma#bN>8!hKG-}26Eqkfuj~kd+m;2%-(MK8^68~o`vu%vK7s2ZD!Ug zIY)JH5+&ymUgj#+ZF5uyXMq%9K11ZB$X4{Im|cz%P&SUBU{O8TiCvD8^902?gxkIV zn6>&yNpgJBJD)@?4ssdSY8dwpGJ5gD~sP?mE)1>?`Ax|6w4W7zNpWW@dQC3$H>54 zM9y*mvXz&wabM3Pyz^u$FPS{wNl@ImfL%Ls;6B3qtqm{QlpZk1R;me`R(PXWqvOec zeXP3)ig%k)&om<#pv~3#1b%?YNY+ADs z2kIKI?QieafNs5tpR%-7j8vOX1-0st$tMrv-_g=Cz5NpD@s{!`9 zPYIm$jsKo2*tns=kjtsduJ$y6tTDjaEO&gQ$$$1~SFqPe89!qfva!VR z!$VnqARn^ciTKNs%?2l8Pt&n&C*quMv0ExKz#~Ih9?XXfyMp6}Q5&cAF$2JUpOHdN z1791;^8RAL*N3vaBOh|Y6|8k4+NSPfzVjRGkcyA@<=A1^wL6+5jc+qxZR|~(0`AR+ ztac)X{>-NStcBd7@Gn}(t%|;Kj)R3NrGK=Mw>??!`q87)1m+xc}MgI)S0LGgWt zDGQqE7z44B=6{-Z9oWT39()g^YNV)fX-h0w8=--?2$0e-3^=HZW+o|RMEA`u-WbVpp{@|l8@M!5z0PQOqMGl=okxb+; zCtN1%GV_r`Jt&g0OQ0lIA}2{lhh64EP$UIR%{t7^0>V5{7SINCLawvV^quYn>V)~* zlY7?P|0s6(>ExInDg^xY!76`Iw)wJQuAcWT&Kvcme|8YQB;yIR8l2tH8?vIfl(+LO z_VWdvMp9)P4e9DhbKj@TvT5J~4Yuq&%a~?0kaY#>Ee6bP+O(Ndr>d<6Pb+S)KG0i> z$=&j+y*Z-gGkfz#3z&Tq4V3NMr@bv&z}Jm6X!KSGX=54A7EAWq56jP7b9v;<5#|+I z!gu*~_YVs5gn2#M*4>}RF4q>US29J|nN`yh3(pnrvk;_`3-u z9W1{M;mw(JwISRYtkE&T-f@Jt)O1p(46}9qI_X?Rm|u?N&mp{NmU@CIsaR3TvZ^wN z@Fo)`t=yz|#9qh$_~0&1ZeNX(0^us&TmLjKcfqRiQiOMjps*3)U3t~~UH7)zIQh?4 zGUYC3<>OVB^e9&3LuOpT%Kj^Kl`kZ$+cv3Ko_~>A$>ywcH)rJotm;o=`O~C5LE5*B zhpR)b?;F_V6W2ValB)>{+f6=SASmuc$+ZaYJeIG4XKQo<%by@yc@coHcMIM9k1qmY z?_y-&9Vls&t(-E)-hh%0cKNBqkG8x2ODMSk%U1*i3Dn3|j^9w_yf+&ng`yH>@gob_ zsc@%60?Gm$-gpEr68Q60!jerv!jc6jWVEz!rIuX)$`00yr(@bi&MEw~25DpI;=+{x z87clYvy2lH(>xts=FFLw`T2T;GZ&HBcMody8ag_b;9C}}uUx?s-`xR{ojZ3iGc(f~ zlxW2b*Vc?d+41plMl%+p84K6Q7Y|;pYN_Gn-MGew)~QA0qc8zhd!vwpSE_hzg8rr5 zngKf1#-@?1ZM&&mOhV{5sB3C zLrZsRaA#goi~{XFo6aI@T4LBu3Cis@y|oZo*D}O?Z8;5K)uKcOMzhie zsnVCy{%%Yo9L+qj<)MF71pY;f{5>J1f3PY3V1Rp4;H-`)eZkg%`E826KX_~TQ@(5X5TF6t z@ESm3GbsB+uJ7u8$-gKNzBkY5`{B|SG@#c$52;vwIA%N6fN|`TTUc?rjmujunFp$d z2HzTz#`_QKWaVkWmPa=7^hciM(w5k^W!7vTacRp1Ufh3_Vfzm`zx*(k|DEYGzpHwX zwMw!xDDqqr+f~2M^~BH#%U{5fJ@*=*aC6)q6xb0I6Cn12@VFp6PS|C}gqMKiDWLML zEKYaC<*)xdOAMg;_0FGXy#69Bgjc+p-j>~aR- zr4Vi!sH0@f{D$h_7)q`LIuKqB;norEMU*^_>RFF)*JGDE5nemOZ6heOqhy9$p9U&p zFgE_y=NmW2zJQWb2(J_2F6GE!2jR|;b1z&cofi?_6vAyt4{z?v5foNZV;bRVz*25f z41ST#$1Dkj#C}zs`oyp-&31o-Doe`AAZCnG$4vH$}X_W)1t+|8!%QvDqRUojJ`6|K0D-s%5x+ZH;%`7lq`mL|_j9EZarxEVp; z3O#^WnAD!LZo8nbOD`L|Qbo=x`j+RkO!0I8b@19n!km@!isEcQsZ;yQ%6X+h*_xuS zBZnJH8P}9%w6@z6Cy!8GrX`Hy7@W}qsePR}2B)gXIYp_X!I&MKty0d|^mXX8xoHjL zx(N2Q?`3elimWS2hV9y8CV7-nHszEJ^?<>8l@d06sT_rxmY;PI^pR^7m^Yxk*=TDv z>gTSmu4EwXzWeTHeEf3KSGpPNSQmjir^}aD7xbi+2H!GT+Pge&C#=_=l$o%Q){_qa zyqch|mZPvE&|t+dl!k4J9|#)2YYpA7c^c%uQkr2_L!+1%&=R_z0{PDstk$nd(olSN zfIBCUyOhQp&ZBXMXMj6_UFhX8np$U}@obEgnq~LwQ!o!d-xpA?K{^fhN<|GQ7%$cu z@bi5+{&28L4b8v>&9HsOFlX72It=+GDQZ!^MCauvaSDfKQa{gt>dv z9P3W0xYHcts4F<;3fh3H zLT}fjs2FMGol^0suS)43 zOq*s-=c9XE;GGckeC+%_q&R*5ede&={ z$E85WtS*40hygX>K8uofpyVEYDYXrNm-esYvHq7B*?$%d^vw~2w5Rv`oZdeI%$x6+ zEjz#HyJp((mtR+Y+-|P-#C7C_*EU__a8rJ4+O(PR@vG1AdOT})1O<*aZP&~=Ud%qe zAY2MR74TOFf0$*T9t7aueC|PVAHIj*?EgK!bXHGfoilRA0730b_~}8qYQN6ur*_c} ztdxhSjsFUyC6^nWDo~o3kj6lqL6Hn_IR&C_9_B^!ob4rzwC~;b->44$2uj-KzWNJ5 z*}YQn-hH|s@u5P%hl&Ahz+aSXK2g@sos#Q-IfBA2?D8>w=kO6e<=)8$`6vF02l-_N z=ygBOs5?wh+-4FKmyJm@7#lTxYIHEq5+Dn_@|Jt2x4@iMwBlxo7^rP-SI2GduC6Zb zyYGIp-DR`w<<|4vidMWzv>3BD*&swL4XX!m&$MPo+(a*~m`NL(tH0SAp*wf(T2MAy z@tqIhS=VLMHb>;lWBF;SgR=xh)7kgZg!xGDJ;L1_`&MVX&XWD7KGc0U5=Mo2sc7_3rB~PoMhy{wDzm5Sc}#zVPs$} zk<(7Lq6ZiKaSQK^;P_|L2yc>4XFS&IsPU?f0OqmY&T6vsp z@?qu~XG(U_k$;H{Fe-O5GO)ws%F9@zipW{U$br2GZ*0N( zu=f_i{4K_3c7(_g*yW>FU5k=y5_T;>b@07}`E3meWV9!(k{ieloy0DCWGg2Su8)%T z0tW6I9kNr=+Z9r|l1-ShvO_VrrivG7KiN2(bVMc6{|o5=nNo=aWb7x~Ti49DSh^U% zPg{5yf!k&P-V0SN!@AtY>u3Nv2hNY+%tm;f#usx!@i|hQn4acK7se79pYL@29jglr z40b2m$$ev(4)9G=yXBL+R`AwL`P(8`_qxttCtP6s@+awlH9Vb0bg zmf4W1U~0{Sg2Q(TM!oK!@m zJqsx~5REXJ($Bh=5%km)c|uC<8kFs=g{07I`f{88KQKRnm(sGuvZl0OEFlkNb|O&> z)JAYqLW5g%@X}gR)N3YorYM$NSJhMNpzvEf` z@wPWpEN0Y>)~)2d2nLX?3*5S(QrGXto|N`r&+iD~c3=(2J4{=knK3&CJc-7ZHtEIg zQGs(gf?4ptWs(0a&F)MXw;RA2i*P56TyZxV+*(URD!KVQ20)JGjorgSGj!KSxSqh- z5aGJ|JCy>@6Ku4j1jJ0GG=ugYsS;V^4Nk=8hq64B57}Uro%1dB842Q;A^WtEKHlI& zJk#VedzS%p(`LU98{jo&)W#l@nC;gaHtjJZa~%884!eSPROT1kKa!0FznbJL6I@xF=_csT7CiyznrZ!+6H$jdLIlaekkCx|8E~FO*&tAX^j8l z^XFOC{RHaN`&no1=g#{dp*ryl0FS+Lf|oz{N6E2XUiy2?KL4MHuB@hO`(F@V*n{X= z!P>R!m?uSQ+23%9PtE4J;Ae{X6>K#EuJy*!eQ?gg5qxOFOBqj_-w`lQJ5#JeC*3O9L~k(}Z?geyui?e&PGgrYVwW#1SpJB;2K7(}cKI^o;86Y+Ai^$%2-o

    c@A?4j2*G_pU)yXU zz>k*yWQ1MJkQ22?1J;<`aW;=)y&(Vu$Q2?54&_2yL{w^ zD62i43b|BK4oN^+fPJs*O|}^nh5@Ip&qgcE2b43~(=lP;&M5{bs_a{_7q?9yBZX@j z|H~#ocF?a$JP6oW5T>D!vaHGZrIjb1FQe|IuFYa=^&Ebnj=v$tnZ<%4h z&S;rpw@u)+33}!fJ#&h(VYte9MPVj@4x4hjjh7aQEODvHH+FEUO3D0o(}KfON9gOw z(U&%i-ALCVURoqxvc+0JUwaNWB{&=%fjX4iG%NP-{1M!=(5zVmgEj5*8P_evx{*On z*$E@D72o@I=eN@zx?cUQ>);hP^^AVkOiXg;4WqUu=s_V3tG1X4=$p&YlTwswHpSsU zgR^NgJ`}T7LE}U}ZJH@ZfeYY1A&?(dNTraU*0Q?PXs}+#fC|WWDA;3;lUnp0Zy%p0 zO+(Rh4rGs!>)oqxza@}&t3(-A-l>xPpYjCq9?dkBJt{f$5m!(&Y})@>viaF!z}*H+ z{iVJfKU2_bw+tH8O`$QHy9^WeX;<(O!=jBDvU?0;_BmJZv@7^&v;I>}?Am{Bq>cOg za{S%lBcy?e;0{*U&#_|tbNts|&#~M1-tLx)zb)DPcroCZEBNt3kT7WLXcq0?m2B=X z+duCKzEHBse>C8)e$(c`C5l%bf}S4_xaaSn^ko~lRbQj`qF9ih)HT!g%@SJ;JM`6} zY5>COYcM}oD9PpPF>mWYJKX>K`tSY!c^MzCUq-l3prkaJt67ha^`9a31l0vP25)0d z_dE?*<9QmAxv@&n?1JS=b|Tzye(16o&GHGK5cSlD@ z%j5VBh@fzm>cJNgp1^AMy-7iskFd*25N?KSvnW|7TghOJg5^Wggl9-; zzguf`8Ihyc1BAV8g!wk=bg-$vlXl<2@@oihmTVU$ zZ+cN$mrxyCkCICe-V8rsox^%%j<3m(cFxi{I!h*D?k=M`xQ#HMMIN#i)SUp?${51C zLbh@t*(Z(;sc4sqsp>o8jHRWBrIjg^ zT*=6R+libd2yc;8nDL^uOI7T06}x=$s%sB>Hxd+YBU@Q0U=rDwN;|-?SfmI{O4n<`$i)>T)HH*=jg*PYg zYZilTRU9JiyJrTYWnGc4g$YYm&MA7MFk$2QX$u)C1}{|cIs}!a*#)dWXEtKA-NJ9T zkV@fO7QSWSEfWbSd%gNQW@E){+ITkT>#4&VpzN{Md%YDm+`GNmQ})%uPg@Iq%Sdr> zyh^{&KC*tsV(?0p(X>USBa3UE$-#*#e%jKk*bbZCC`>>cuT4uC4^CDYYR^(>&r+BP z$j>%dv`#HzV0uLR({|WY+Or&*9LCECDs5TZw4irB#HmMAGT8=8c5Vb8i@x?82j)i@ zm>r?7Jx8T2i$la^rdsilwyDpEmNGyad=Jxw&k=2a9cjIZ(P6VT7x~`Zu`5r z4Ze6rfAc`cP06UG!IlLW#bO{cf?E^F-bGAVBUkJ`CvZdr%Yaef?*Iqn?Fv=_x6;6v znwhYF3+~ebf4haVLwm=%M+A-?;XW;J)|ob7U3=8ZJsN0r?5N>4TLbs7-p5%VC9K+5 z_P8`?BljuIru77=n)ZwZ&7l4Jp)9gTkxJ=m z@(l0Jhtz=w^C1WNa_o_c^S;F{sVMh%^MPW(u#rN(;9DBw_ATC-*X;f^PQ(YcgbbBz zmY;?Eu8@>nc(PZBv@#OzmHa3f#};hrIKI@$EdX2!RS(ExE{Aa{E; zf@Y^K_Hli^b?4$qDsik<-cR(*#84S+p@o*eR;^(g+00%Vf?RI0%DmoObNeF|w7B1%0W&^b_CL8}c*7fIlfOv_tt!@dr8Qw{t%)am2USl@EED zl?X2JID2@W&1jkA^9c96o)}C7C{u=}fJ>$vOt1pYm{|i%^mo7I-tF7A-Iny%ThWRe zt6$V&%zme$uCs1;NY-QB~VAk@}*ySaO9I=vfj2xK68ciq5B4>gyKSOtaCzhYW@?mj5 z+w$8W)j@SIMdYLs&{lXggg4LT{&XT`td9v{ZwBG%(Y~PAiIQ#D<%K}2@FKF6sjEQQ z>R^^I-$}MIwJ05P2ycdLWdh+&)AeAQ6GIuEzkMYa6*wD%w|4nigcp#lR0(^xAiQ%oOgWa8!k^dW zs4|&NK-oc2#WQ}geoe1;h!P1$Sy%KLK(<-BxHk%s^NNadW z${n`;U)LUSJxlL=n6PF&!@M0$>2+>K1F{Dr4X}C{?Gt-&RzGX~ZQYEfEgT|b zUD4mxO^=Z+_EVPjkxjwD_LwDWyk!9|C8(sb__P4oH?r;7)z$SKuR9kH62*1+V%fEu zu`kvvdz`ue{s{}lz}X%x@OvHlY!8vxLtNC`H(EzR7qZ;Ro!&Ebl9pOGD@JFo$;B4uS3@B@B0M{S2G@}+Rb3A&+ z!f_%-eTz*SBK%Pc&lS8)Dm(+m9(D!#_iE4p03ZNKL_t)CU4b-UY>!k4bM~xn5%?DG z%ZL1V$;NS_gejLo1G@n4&4+xVWOKo{xJxSbn9pAt2JQFfLoNk(ux7(qMqklwuM57F z$RIzM5Bck|jqODIZQ150jVJB?yq1Q3&J}#7Y_m%$Lf>MC)OqzA|5uKKKT)OhxQ&0w z;(?V4|B^-i&XCe$HV^!_fbCJlAAi9{b}Pz{+6?^22t$Xnc&Fbyth-CXC)SZ&C9)~ABRtIaIC;BJI_5DXi2L26@B62n$+^2|~ zb#dztm~8@UW5#S`9->*YL(ik6&ChNv@b&}yAq8jlAEiM(Z&01PAKi(4@-Bealw$^7 zHz=D`l8s?6_S>ef3(Rf~dz++@-D}Dtj|uOZpzPM5K#CO8COun&BAo_6{e@q75NBmX z{_c?fb?Arb9vPq`a+nYU0Bffx?3tneTyTW;E1PX(BIb^QcuAz9Gc|Mo%{Jw=OjNPk8!6|D8Q$SE-rGB z<&3e?l#h0l6f{8Dm?b-toVyLpl#gYM>u*8EY^;RQidNi+v3Bjc7769M6pQUgu4O^e z4A#c`w4%{>A0HoY<;hJLEnxNrf3TWah%K+qw_dy&Nc%>=h?>ji;loe0UI1@k2v1;_ z*DqwtE{dRVg)kqXWDUztBRs9?G<@hdFiy52h@3V?4$Kibb%d8*uz%d=&sG}0_3}DO zLf9K1Oy_arfJK;ZGij@ltwdLWvW;{tAt)|cz@`oJo!9iF)#sbT^5+N&EBH)t3;q?0 zP5l!nxs>l8JWx~83IM80S(P!NzuF+c69V6|5>WO#QHRH!i{=@i+qUJ{vSlkX zGZ80G9&c4*t$1Ufzeq7KK0;aOa=&BQ67Id@4!&{xIktyBUb~<$8BkOKmCnZGhxl1* zj>5E-B`$Z`+F#aeJ4r6i15cSlds;+_6 zz_%D3wUEY__K!+78=WWtUV05nwT_l8%>Z8<%JRN^$kVP!{A$xQ0NV3rSsm>!`?rG+ z(2?23J0AK+j=BQdi8yE4=j)q%Y2Td>`JnNz{a9a)pDG5F`ny@@MEu6VDr=mGuNemK zm%p6lw|}$BsuSRz5ftwYv{!dmMCox`U-xFkAAiy2m+lTIebv^?*=~hbH0zaL@1RwY~}gvZjbm#&~lhmu6XCCv5FQ5~di(l{SE)a^1+*h|gqn-MPK zVV?QOVH&s+IZP@^-GZp@AXd3Vbw{gCF9Ck>amKHVvt{B4U0q$wK5z^E_D+-cvp6TG zxUi=a%b!AcVRCJsGd{CVd4j;V_)iB$2z-lwsATEp5@-8f;aP7v`Je_4w8(g%t3l!HDcPs8t+@ZJ@cXxMpFYZ#@iv&t=clYAK-Q5Xt^L}&h zH>FwKgqMDsNzoV}#x&iidZNb^D$BKaa*v?;4f?X6_m)TE^Xx?R#2l z&eDDMzFbMKwrzL0XWp(^Fmwid)vu-Nj7{D#$~X6rzJ;$2eYri%xs*$f6n*xeQf@Q` zO@)7&D#xm;uuQMXh9MU-3Kv|8uN=!5P~9;$02KGMBSZ+ zi~NXY!Gynd_41`^ro~%u5s|VdIUP&+ytqY;Pu(vDWx{;Z^){EX)2)@8_`HN=YaI5R zrwLN^VotQ@Qil!um<3~;98rd<2@zkIzk9b6Ks0S?EEPW%@aso%9V@AFCO1h!)=-bc znIRvg7{ZA>N~>hQdTi5AuErn#1z8|pNn#2U-d?} zV}*fX4(d?_-C9EsAIg+QAsPgTF;igUv3xIgy_?4ly{9iJ%xOxZlPDzl5B^(lQ4STY zlvb-MSR;dY0xq~?6)=~!Ayx;kenA%`=UX9O+NHq)xDs^p%3EY1)uW((}(adK>5 zJ<($#)Lc;YYL7oUHWW8Xlie?xe*o<(>`qNDIRhHO-+RFG+^~;#w9&%2i51q>k_3s3 z#BU!ERl~n+M}1P=eIuxa_Zq@3nf%DS%7%+?4e?jGhUp})IzN2c_V<;^cK4JSWYct- zz!o@+-g^o(jYns-TO0-t0Csnsv*#kay2pQZ(DVpW()#Ng(zq&ja2vgGT-7{ClHige z&mOA4K3@N8TyEz4&fg)5ZYXrs?^nZGY~B=>TKBUQkF2o`|0VqookOU^cC5jCl*HR;xm#w! z5DLSWP^8IErOS0Gql~Z09aVJpnrH0x5p=60SQW?_`0WEf+!L`_9WyeyJPXH} zj}MEFeNNH?L>5x#Q)Jk`k$`scrdKc=3z%~%$CeV;}{rb#Mz%=4DeZ}5bNiq+t5*M`Rtn!OABm|K@7h3f5( z-kU!Gd!GO4BBw6w$}_e8(}39cYHOK<1pLk_AD$o)d99aS;FRl=%X=+v2A%5gaQv-%%W z4MM!lP~3EA4p*MVrH*z_9UrYUO)EnBKy5bS;oNMcKaxl@E&aJf8pEx zWYHV$93)3Mwcfw=wHr-wMqCa3mBdaL4o|kl)cK8+guolOah4YY^GvI47^&th(inw5HhKC#XL7i(;(l&3+W; z<8rYOa*4HEaJPD~`ROMQ1FQxg={GvRO|l$t-Cq4lNj>08tdADQjkpHEzKyqEqpZ3+ zbyVha?qcg^A~nc6OQlDb3d2)Njx344{802AB?xNjP(%Mdv{9GlQLp5i4m0=S?Qiw0 z=wm4kS0;Hihx3-Z?u9RUsTWmE7XbpQfq)Q`AH+u@ZojgZS<*9!03rOspMy-83R3In znpcQ2Nktd2A=0+iu%+yer>%K5ekM_dB>`lsdk5=Xcx`A%0R9NYzx4;A1@PD3+m1Ai29?Lyn1mwm-DA- zd&{$?*B(I&&;Tx z(N?nrI2%DF))U>>7o5j6z@JzD#U9JV=|}QnkbOVpVA_0_s46! z-$*{eCn^D7_;MwWRyiH^|nb*zj#}hEEL4qV0bzHlh-e- zQIg)fSxvws6NoF{eqA07m4bHXfc|_tz4Da7ggVnjaW%}eCy6S=um1%c5Xb^AtW|o) z>3_bF#Z9XF5Pu>HsmM%~_tH*B2ojK&{5l*@mwTsie%VPWiAgKWxfaB6PV?J+c%>Z* z|E6?V%x0poW+mI+fYCkX>%QmCfM!6ev(A%h+_?8(9{Uk z_aUItgytY>W~tx*xy};1qJ?RLx*c9q!puTCe~v$m8H;iT=`bE&2#@7HC)T2wuYAK+ z`UpJh^mijX^gjecA)sxNi2ggW|DJBWQe>u^Za?a`#$)r3Rx#zfa}?K#Lz9Bb+TM4@ zzs)S|%?duA&A#bh9DRKrzpZaHHJ6K2eCIx1FIj1#q5HC5Duc=E=&*zTGu=)nnOrxb zbXz)A^6T>zEDUr@pa2X;$+yD=F7sVaw9iO*pF(>>;im=i55aFPn993!4m&dC@Y{M( zKy$gD?O9?lD>4m0pWh3q$59@h#LDB^6F#*yby5ud_38|*I?*d>g2L}M(^X7qvUaOY zo#wECFdE}yUg4<*v$Lzv27s5kfG`6)>Gm~^c1}EPZ}rGJ!WvU=GcQDxT4G@i7(9ff znUy-ZreCJ}Z5R&xvdm5v9};D%n5pN93twVURD7U|&@ArvpfKc&ya<%1WCsV;_zzWm z@~ia}4rlpdc*Ad1lB{|*JYo^kMOJ6xF-uUw>Vwj<`zNMV*8@Xj>B%mTc4kfA+|UQN zzg@#G%{~4ZoS(-Ab^C^g2iJ#XSuTH9D-~N(=WTj%cchS}`f{=M)#+5I_|Z2`P3wUw zc?u;>6p*&OfOGTGit!k`we$XsMrHLlIeO|9nsd5V zGNbVMxY>a$O;zL`oC69!Y(Une&EkodT+WnfhWd1?DCSUStae&>-OJs#OXDf_d26-# z((^Q7Cz#j(nP`npJWiLco*#W8S*O~rkN$p@PQQ0Ke8ir%N}Yj%IM0fh`1B7-*rT3V z@&l+j9r7L=@vZs>M%yX&im&9Bm!mE#~L3(0U zF6TN?)%5o6YZlg2_G*gq-wV!YliI~lRO*8CCMifcbmPpz)%@++RcMIPR{>1ZgKb}M z*S&&8FJf>UekS@T1i302IsUSXTVh;&(#CrMZ@_uoGvh5=EPpCq>2Ag`wnxpO37Y~+ zeAw46T{Q-vGFnV%P_FL!QtbNxMi;&0`&Z9CsxBY>ilLnMNy0m|#aG+DE_ur*`uG+U zUL9bp)V5f=N((vew1qHbi*H=VK*38X3=#D@n)z|98dJu2OnmWU-8EeyzYMUVc}rrt zSyhGF{8*fJeIBz0#c5CZ!eyT)Qr2v3$4+0OKh)_~!W9S};^*9=MD=E?LIvVhSdzv9 zElhj7r?;3Zp2iCeD)Tv>TBA(@kUMN$MHcI>%Dxv&25gEsXz*CVR`A2v6($&-Tm-EZ zbElt7-OSk~kma<&3Fwu6Bcw3$TpVNfkFzfeTWxv$qy8!!$+;Y(Nye4%CQW!l8B&sr z5&FwNS|Vo0#jWCM9;_s47hDgXa(#WH(f(ZPI?rLn8CAupzm#8$H1QQ=k6?+zP)_U) zF|V8tzPW`xd~M&~Z`2r#h`vvDszJ7BzvNLO(^J&!euqiuC!iwKt{blse(`G)%f8+y z96HYkZ@+7#2_)of$6ct)AaDZuq^ir_lzF0WDgHQ&nspszir(~nLLc!zC&mkicpw`* zyAYg!QKzb)mr>xEfTIJ2iBmObo11Hs4ekFCl+XCq_;PH`|Jw-?g8$GsZ9F7Ncqmx7 z4l|E%u9&KatcEcK8|M1!ggZK}YYlXVb-JkF$|lYA;=);beFUh;F5AK3EEE67PO&Q!;5Inl(6-3qB_S!!98|@z4f38pbp+% zz__5uK52jUXKYku*BwV&DnV>x6!g`OT$6j-hsw{`E%rCo;LHF(2i zoCB~Tmn2rxrG<}Nw?bjpEMakncJVf#EdqQ-!AZ@u9Sm?8H`LkeLen6e1WOO2edfA@ zN57Y;URCu_I?ca{^mU8;aul0&JY=$h!)5cTPZim`k@z zd-M~p-}>}l^CFr=jm>aHZ7BOXi?;1h#M+TLF1fb=S&tN6{0aFR5&5l5KHV|T4YD=j zqwbl{99pfrvzFR=yeZv{(&W0KEgAKw^vca>N=L3{gq~ULWz_Bo@>DLmDxav zOFD{62zMwC{IZQoHn_Sr;j{Fha9~xT+Zqb*Vxs23m_w$DI2w!(FF|m^*!$~bQnVnV zG4rg#p4D;Cm!2lXT>H2`&Qa%3^1jw?l?Vqsmm57RCBK)8bSQ&rl}iKr&{m2@KlQWss5^6{9m^%-pLQcA zU*IAyMFWs4r1@SRG+UcF;)^|%X>=DueM2JgfT?3F2djb(3!-l=>venx3g1Ow4+W7+ zZj|$!Aq22ti=aTVjNosnRp?(zO&EcM@BjXc8j{emexb8k-Cg~&$b6mmNV=V4dFA!l z6I=%;_SH7R42kRKZX76(Z|Tk-$`&d5E+HF}6>?9xLCpBAUbUX~Mc57@H9vmx zzk#X@f%$Hqv%r49_yEU$DzPNoGVAz%4_Q1?Kwpe%kw*P5hoI}-Y1?IGUTyyvi}&09 zF{>?4e=|PS!C3x?i!Ix!gN;gSxzrQ}6f!1$4B>w_v%lGO7#XtUZJ$0o>q7kQX4}<` zW^sD5oam!*ZnF3%V5+MZIqq#03*|4JbRD(N+iCC0zRiMdS~dL+x1;TyobVq5e#jCE zO5g3%;0;9A2IqW6hK{CE)8kcS_{_Z3@rLG%)y)UTOznM_kJFFL=>X>_MXF=9Wbf_2 zw!`E&Ai?(pDVpPGp@e8BE!JDLSCj=Z2^1|>sVvoG8!OYxjZo6_&FW+~D&nvDBnKxy z=W_-?sS;`X6b1f|KYc!qNeK^s6t2r80%u8^#CS65T$D@?rkT9a;iZPXA65u9dDQIh z_Ag(!EfK~Aa|C7wxk*?0!}*(T4KMGX`Yas|(^n5^3F~7`UGp5O?Y?OBOfOq03n#$U zBjqybQcqza;v9)xUMTdWRS)KXPY6Tj4|5<#I8BR*6+D*75=eEp;Nj->Z+3QNN0wU) zqJ`sXOt2^P^_Tg1#?Vzki$fy^i91ZV8r?=>+Pw=x08YgsnO+ za7hhK73~of0I43Y zTl#E&pj?45c&r(h16MdLEi`6QLzaA-y<%Ot`ZwBrh@n8st@5R7c^ltUK^z*l&-%~o z*>KTrGJ}3@$xLh3QR-|R?BPkP#h4FA4}VVRwYTMs4`_;44-n6Plq3SGtQ-q@{G{%l z#y?kNV@#D&L7*pGN>2Nbg) z6C-9TTJz4ZfUe-%c+gbsP!^ReppSmU;w6Rd$2 z64mfnzcuVo3SQdU?qv2FDH)3MGB89JP8me?j@Sk3MV5AhokjWX>Z-`a^*cdBEoI-; z;s_z*kT+xrJ2A=C2JB<$iURdI#F$?#q6GPRYbF#Hi8W7g@BP0JB`aa6SsN<3RmRYU zW6W%Ec&pRhucP@bK>_{zNKBBd6obI7WSWqU7`WEZB;sd}Mk`aI(6d9Pz4Pe#Q)pm* zg3GlD z6{Z2R#iC|EHMy$;Iy4!qb19))b&VZS?o9ry%d)}TwY`r zkg^)S;#k+>wYTih8HGy~T;zTVxxA-uv{79cp2+||Ts4;Gy$285+o~Fz@7vNku^?w4 za&+%Kgk}t9wLJNH*%SM15l4FOmhtmE%%ky%5rVrCuD5-KrQX5R&$ras$nZxh$;?#O zU^s8N56wE$N0-;^eDVh12x|1)b+K9zb|)v5bv;loUZk3wsBKaJbI{l#%`7x+zfV5; zuU#?yS09n^uWhp>_3$qwU~!Z?8Ee*=nEY137sl^am&63aN|1xIR!(VNTl9oSPd9L;@-U~lnLq-87{l!W#G2mLNov;(|>>Arq0{{f~dwo z+Pk<1gi6TO1S>Y{$5-_!~|3tWc zZ6B{`Q617=2q$DIF|SV@_l;#~@gn!fn0j4Xf&YD7HKiKIio7og&bsWmGC^nt6qcNO zz@FzpN~Aop#-J=EvNb%}kgSB+bG)dImA~wZHXxmTq*eohu^~1o2D_ptX+gOO>@9q| z6&DVD$NJ}?eoLO!0H|$^Oa)l^)l=(Rl!;fryEW|UHLOD7;j6ndBjPD&EXhU85+4i) zNMfTa^doQZZO(>8mD*Wqd21*IHviO0A?kzz-h?+?qzeBvhi%KsgH|q|IO5SnW1$&$ zRYYax^LX{t{>)JG=pdS%tgFznJ4e;)9L^zwEFY3U*oEZ{Ty3(4c*cI^ z>j=Myc}KK;IEaEY-V!$($6-m%qHkB0I&zh;73+74mXtf&BD9M9u0gR>7>jYK_4fqr zexGT`@lKAZ1P?g`itCMC^>GZcMcei$ak0>;Ja?!+oA!QL3+s_VxH$)n@ibx_4dda! zt3lOH8vSW+zJ7}zG-^??3t9@@Zh7Y?5nTpOTV>1CteX@NBqn6b8$r_DUYZbNf^~X= z!^L*%@cr1?NYTZ0ap!={2G))Cx}+&7DYY%vM=mjqFJaShf3JoF=?H=rdFc}U`8HR$ z#3j4!ZJgSe=QW0sikh@VPX+L`ak(q3Awf4roJIf+5~wAggR?S>!%UHl(vbjaphP^- z>hu}7(%p!o-e6_L|AJj_9GT-ISKw+#dfC!LF6jJQlnb8}lULi23B~*~wiv(OZ|=4ttAQxqhY>-h@ja?= z6y9TT*LH$5&B;-zMM@9f4#T zkrn14^Fm}pcZ=RQ9OkD^O%p{(D$Ts7Gm=e#H(am&(-O6;r205kBTW@1!Y+glh5U8s z>w|Xy5?qg#%wkuB@>r)v zO3HXN3QpGN;-=emOUf`KM>fj3?7@H9_Sr9wh*Ee*I}OEhSw+#k{P;c`9|+6!1`BCJ z?l$-aE9v{d|C%WiY>)}#T7B?~wd9F7MT`%;<@oe1b+4YZEiJk&e>mPBA+^NLJnNq0 zPD@*`8A=aHrJ74BOFdbZFqPgX*p^Zi=X+*c4a~4;3oc9Vkv|F562!n^iFl4i z7Llgw6R@X%Hv-1$7njiUtovZ?@P03T<7thRyM7WN^z?cyd(w_a3SCn8OeBb0`j1G~ zYop6s&usxI<>b_u z$W|-UxDef#q_gE~ELNM&0oA*jMsyVjaLnX-qO7b6iT}prw>>15h!L7$C__r?Rc0^n zpN{FG`!fhvk1%Js!m@kDm_X!_5750LG7MIP%?k+U1VcYiAgXs@s%L9Z$f`0peN+vy z;ITcZLTHZ8s-0o`3Bzv|p^n9|j)$p?$2YLzPL0t&k#RhcUF}@HoTyvbbw9U`6{#t4 zS=g~BWLorf1)s$N;G>BXJP-%!b&NVoKPDZmN8(@ zFkutsA}3yMo%O(_V&#n8u?yO$5T5Ax>DLl<4$C1(F$Dtyd|+fB$kw!@!H(q809&)! zMNKE&Rt|*nl?NWEI<4Jzs^P~TLE2V022F@Tn6(3c;uRmoF<`K94iV+1aq!oG+u)%{ zNvit}bZf!YjwGehVhkaqTKm|iXf0{{JQklrx8)H-MZc0!c>?oLSJ%&?BMbrxI4mTn zva2mGBtGIJ`#s%XI?$S<8xRb$eQqT|)?S2wAC)WnX?fR;(It~JT>bhu$J+L=I+{~_ z=Rdn#B`kZ;QlZi0aYsC~_xR<_B-oVEM#6;9@6XIAfJ_e{l!&&5e;(gr*-Ljr^s>XN z>DiHm#LqihoO`8PgCb}DvTt-N+iBsVtHGe9BA*>E$0G9R)7wPY zJW{Y(k1w$S3j?=}ut0ljr&9$+dOJ}Dr%pr|OL?+O^;nYcGMx&mB>eGYx2HlIVTI&z zYVuxikBf=nIZu3ZtyOx6 zDyT}dv3mr+X*#<3xXfnACdyCef01dz>Km;WQ(8bKNW92DTR4pQ<>hO zDjEuIfWH*jsf^k>bVD-qhKBP$Z{Y}wTUyQGgI z&IG3-ztrtOreq(vo)`CW{NHD#yI@0e_rxL-ua5K1H$D1SG!H*P56>(PWCFCv1KL1s zf$>Mug#s=I^F|?UnK9Xa>-+;H`Nrf8$2e%jGLbQwD!;uSKM{&H@P{E1f<)c;GT#Ex zvQH0zxOA~==xP)UyX*%?SyoB5+!g^hClWv_o@~N8JTEB`#+UB=u3v!@uP6!pA--7! zb7;?;L>GOOV5MyD3mEE%@;hFF{Xdfv1+zEiB421q;s^wT5Ub%|f-X@XI*|_LG`Rzi z|Gy|z+wLzc4j)Z=H%`7SkMn-~8_VjvuEd|9)`{F5d{#L^1TDm!)o3)@P^tMRpH5^Q zuC(6P4D|(%j@|-7Z;=?Nu)~uqi!lF@ROkG1YR8zOpuL;(Q5hM_k}vaTHuH19Kbz}W zM63l0<0$I;>q75fNtP8IIy$ad?t{pe0v6t}B)?;v5uU|1#S{`@D5jWb&^vur9#mTT z>k^Xv#{D(W2^H2mCxzBw)MNH|>fa#t&exqcBp00UB<3*H-Z2U7nlG`F9aD!B89O|K zWwAQtVNS9j`W0=mHv&O&jp@CYv%K|B6Y-zEIw*j1h#I0`9H)rN_XezK%+e@%_?L&< zlEm&vxC_l_n)yijj>TFCULB;tb`wuIBxm9+`hVV;!#L*dwC}epxg>|ple>D$f2xoX zg(t87*Q)h|qk@$hdYIvU`i?O?Z3kuan0Kk~-T{V7pvYmE{ivkP8kk;-PV2^)3?<8u%=npdq_H8p z?vjq7L#tj2;NFl4nC~KG`94r$v(JwTWWW}fj z(<;RoRNWzUS?jCS1D*xnLXi$*qr7X7nkJA0^O#9B=-={wD3*l`M@ex_L=ua3lo6{1 zQl3*%vii=?1~oeb`VD+>KeP}^Ti6|g^vqPXVE*v=wpwBe((t3SLk;))C}b78GJ?rC8Kye zZa2IgjZI{~e%F0Pv8-mC>l?IvseWIbola>Y0}I7W5c=_;A6Wf<$r`D48i~_(QzR`v zJw}I8J|-+t3yh~U{Z`FLB`hu@gMlWfk^cAi3A(!31xqo3aU<~)bMQ%0%-G6OPKcn= z9QTv_T&spZ)RBNjQ&1XzOn%c9M|K?$6G2Mlp5UI?uO` zQlXE39s0K|o$3IeLK`{@!!X3~wwJ$Yvn!QpI{cm+usx$G!@M46*JZ1o5}|wPoCk3R z5td|YBonVXKiq(t&76xge_XL5ITN{WWqkBR6Bv#>K1XEqOn9=?u^ag5{puU}R@f72ahO=8e`I_@Jt{JI{8WkXc99B12)!C8b#VQuRcFGK~rtVyLMJ7n81!R z&AfimERgSOmUJjY?KRiy+$23n{^IpxW9&t(hZs0g!XRzoSLTXi??6~}K3+|t*E6AH z?1lVvykIx=G@rv|q2F8K#v)4p%juA{5|&ySfxpc-i&rKTP_sh5yXM^j%Bnb zR%ooRH=WXmE2g5_%L#}vj7AK%Uwt8{qBESbsj${{@ANU7(>U-D?s<$C9*mD6sbKA4 z`vH?a1}jlXlz7@ifJD%aV*;5u>f^xN>TLf$Z5r`Bxm@Y3aF*nskj!JWN~>P2QRg{M zPN=4pM`#Oz}DfFj0Y4u zj?l=PDKHpEe(mJ*Y{Jg9iY;`!Z-$KIIYW^aHg4h}id-Cf0OMhCSv5FMscZK5xCm zm*-EHIl;FrA{&6Th7~0pzQ_lIw?Id+!+(q0_HVqB-A2jJ?)hG;Ttv+i536~f$nGD4 zeo3nn!l-oPVZiH2u_hup5s7xIb(|LFN>?0ZM0=J%qe+?GB2E_=(mMdfhxB^kDMY~2 z-k6UeMti}~9-2|EqKR!(MpwH2D37?#)Qx;x^>Y1(^AAC1yErwq*iGCz?sUJ7Em_}C zT>H$8v!K>&*XbemHwOt50118NY`dzb2W%gG22LRkXFN;^4uM?uVWO;H|Xgl3;f|FyGn z?b1DD9RbJdx$5|>eQ(#)3aiyDPC}kG49A>l!!OL5VdK0U-9PA%6Z39)S@p@5%>1Y{*GQ@DE+#~*Yl1JI4w^r z29JAGhDG|@L3-kkn{NP{1zD1qMmrP8xzVBXZY)*##iZ-tK-cbAV55!SEuDhs{%2wA z$ZkOvV8%Y0C-|nhg2S!!`d#VZbhv@+JWeOV^1EGhhNe{pf=b5GolSKdyYgyA&jRld zdY)v%9#z9DR$vCJ@+La2cCU-JNx_NY2mq@(!gH;s!kphp2sa`l?ETHx1h18ryf zMh9`7=@fwa?}Gn~#voffe!{g~L_@@=e6M!9u=VjNWIHF89ydQHeR>>#g;TW%A4!EfV}6p71?Cws?b z7n_?&M#|xATC_l>;dH*%T7_M44MVN}nI;pLTeALnx`iXErBNndz zBQ%VL4tIHD&@KGlscod9uudof^vSKWQ7=jpzAY1gG>*m*WDsFRc7!j8OOUK(S!KdALNt9ByHxKT>% zMEX0WWQrZxy1xaJv)L^2+GmV%$yjKw(#*W!_6O7bR3IA-u#@$ulRw0i$7h= zAlM#R ztxitB-DAt^tHDtI`fy#gP_OXo*yau3if2>kiFQ38!kb|{C#~4dYd&?}aBl`~J17}7 z+`gQ5tRZ+EG1P1!RP5& zezm=k07NSqfFqCJ@-^?l$nZLe4+}q$Jx0`Q zk}HW-U~JgZMb?arkf5 z1B<6OTX7Q2>EbOtW$9V3>n=pDXhMLW4BC5tv|j`FM^Dr@l-4ki>uS`~k6SpT~!FpNZ>O4iN;1{N%s2i(J zWViCyQ+fYY7fwaCky+VE;Q3ZTb z`$;Wpg>U@XKZEBXNi}EFGp`L55K%)OQ@M=CN~q8BN%d&R03PUGYPZ}HFgzXb+xM}X z)U>Ftlo)NG=ZcK@#cWLIIcyZ7Ot>YVTCC!`3T!-NTjJ#WWBE8a|0~R4Zbf%JiMHZ0 zF37%jP#NJ^nT>DGmPFsDugEGPXCPYyAf}#cBy$4-C~X}Aur7hU86@ix&BK)WG1FDkW~oAba`k$xa9wJNx{*{LV7H}A-JG>SKXv-uL6OW9!hQ};LA6qNbb ziGMQEUyq;{i`46>Suc@NE%h2dm23Oo%fd7g$h$QJJnA;?RKZ&4-lxpVC28tvPADqq zTVMYnEYUG~DF2@LCzSbZ-v$aIQ)|IL)(yZ?>J*Sli=i1L2(yj!H7_`WSIH_eQz22M zWgVdzLWp&o)P*M9m{y84OF2M)#swCy^qhlO7kdXDGk zb@twmb24`Qypq)Krc~eSQ>vq+HJ=9<=t1>({k>gL|yn%m>^=U z6%GVTBvX@%-|6}cg=hx9Qc04&*4Cr~#I=L&B=Y6AQj~tP5T-&1z1TS7F7m)f-Spww zJZBq@RKQY?pNPc}&8GPdK@l5%Ha+|ZtVE5RcreTyY|ev3`)*PNv_ZQ@&jD(R+o+{i z%?O0{auAy_)QG!u*qG56%$lKDvfic+i>N^kj%XuJ&kI8H2S!LhfUgYyh<*xjNfu1! z&^O~GHL9(`n%se)_sYJS@V!-e6=bL^*!)O74@h@?TQ{8VW6Ry~hl`zmUVBPXNXv)1o0cbAc~vJAaY?_U_tmRD0fI91}k zHLV%1v>tKnWvPxL5Ay<9OgjjT>KGA@wzJ0rf*25BJl$}z+a89+BtL$IFp2&q1ojLa zNo^qK>$X@8eldNSDo2KTgeQw4u&EtS!!KRomFc~%lv)3UGJA#|qQ|p9mPPX1%K+=h zan%pg*bQ?34KjvkzrKMO!mxE0VhBZn2g$)C4CUdgdrKzA#8fVJv4meX$8+RHPxkozkEy!(1Wo7&u z()O6p17hcJQ4|9_S>$^hyKbAGPi7x6n3u!sK|?%xe~sPUGBrbWn7&YzLs^KgMp3x8 z1>yCzN?*?4SFe2=`qBD@?l#1K#n_*SM6f*~4^00m_KI)P^SC0Nx2g=J45?EOMuTsTn7>BHTUi=|;Qn+RE(o7VF+(aKL_>1d1d*_Ei_*T; zS^y=tB*X3Gt4^gy%QuF_E6`7sFDRd*%0`>XII#sKn?t28ga*Sg*X7QF-tMrY`=Mmh zS#Kc^FTy_i;V~xl&6i_*3yzHCqGY|7d_-y*8pLygzS$WrX6z|b>R}Sy@a;impqSM# zEt)2R3Z%m|T?M-xl2*0t13ipMi#Yhk7O?G}fx#T(#06JK+&{sh2PlCoc-(zD=3<`f z?ffTRh>gz8p%l#7fZD{7eQB}5p_PBFZE8qPq!*cNFOUZ6;nV#&QcWZ6UKj8uHWw)q z|D;gR5MnjpB0emYUAYd$`H%2dXT7x<^|yFO>dU3VlUCuGiE*;5`10@xPohsk1 zJfZ<+zW~Y@3T_O_AUmSv{}K9>x3Cd>K6MPBp=E`mLEL#V)mfxMzrK?0B0RLlXpg`3 zwNQ5O{9pp@`cDuUGngP#om;7QkcY5akcK<$>?)9{E10@HXfbRlX04fpwEg4H8(2`q zIYCX!V?b&NA+p6X+c6H^BFbkMmB3t5i8v2}PndqZCqkM_> z_LIe>+2jb_mrz#c@NX2KNv?SNAR3`8s6T$|ihcQfl5j7tj^_#F3@m4i$UEB?2@JOD z6{}g0H9HI;b5{*o$7X+87y9&%-_OKq!QQpB`MD*-;N{)fphd6AWx|kB_(7^-au@zs zIT#+GquF=ouMmpVn$YwEMId2_kp)vYWL@WMxR%y;ccoMRy5}!2i>k@`skBwkGjtF9TVP7Kyc?~%N zYJ&CljyA6uPd{nud*gN`ln(J~wN{rvbH+l_*N2Lyj4b|Lu>^;DLJOtaz`$(=J)ZWA z8nQudw6*E{IAKWukNnzn5U*^bV z44+OH550HpSWbzhe`Js}#5r>t_3%4@@%WPyTzb1Pay8GX8`>*Yk+O?%zg#d%4LMLY ztk&=?=@?K3s*v3)2OSc=K5n+glx@K z$ON(Oe)%u3$iu2{FgTJZk>3c>poy%*MsK>pR-{22j z2+#S`F$08;*gg`KeC>5$=0D9O(hD_EN6}DJ`ZQ2lWLhG!@Ff)v43R5iGaLq6BXdjy z?szAY$vMWSV**77=a015YqsH{OFe+KaOE8@RqAJ|#?Zxk*-@V6AK*sh&bH^e>cLA3 zlEb+-{!A(~G&flZ-8VJ}2P=<}QolA#=L2V|=lnT?xc4MrFfFHm71Ae5t#hf@>?}(I zkVYP#o~hCVSSZ}-Kt_fSZD7a!sqJ#^9ZRlH3)qOJhJPN`8ho8i_T+D1- z*t6`k`a6@s%?H0;Us~X|Apa3Nr#n^Khpg>a^YAprstCdB`vNX*pd<#L;NUst zL~{sWZ|S5!8amoFbQ>p+i>J3BRWnWjA3K4Sh#cLUCzKPWHIZ??$ZBL(7L1B;x#LYFHT{-Z)Qf3f9DU{`$@ZPNV@VUW4pG_oW;hRvS{QQ|UA zlG7?-5P~eVW;Wg)_)M7w&0e!S*VMj1=J5BnGVpEbvI%WSPI=Pw&WwE}bKZL^xKnez zyCc4}XzHuAxM>-WlTx>dXZMa{_L=8q%Hrm+68E}BEnm*$d%eT~lhBO@Ak|&b`bbA} zma95}fvlM!2Qy@1)&EZccKzytiJxU$#6q2`$`;X5w2pTq96*iyc3f!cnzs2~G5j{n zYCwVO-4Mn*f#QvUpovcjfxY`=Hx~JIOK~W#QiU#`;#MgCto$DA6mK>1+ndK{Vi)vp z8Go)h;Z+-|l|MvCeZ+#&_b?#*Ow;URsPEU%qGf(ietY?_(C#`Tziy@s0k5vDSWj;iY`(!ms;Q ztplGs58`*utT&V=LT(t_YOb-z%~dhwO3m!9yMlj1QN@m5g^GK6_^=;p?;h_``w<|L zv{I3^Vs&?%{T|5{Uu~PK-?624VPmVeWYT}I9^#2GSXvUk{UEO^nL^LsFTGEA;P|1V z%U?yJom_-t*j~l>_$mKm^QPmA@X3{@@hi$YB97<}fwItfaxvdKHjh4hBTs?L)@Ni^ zEs+}jkVLs;kd7-ebv9op$7ir3)w?h`cxpn3zyC3~TPSkt5AcpLgM1=8^G;vl=$%72 zGMlG49X(}jXNKgUN-u}0j!yhb9!xI zJkpNCx_6R5H|t^wSy*sc=deCWg2Rb9sQ$%5>pHE6Yx3V7#i%P-evT1fpA#7QnhWfB zFlRwzl=6~b6j{~gZ4TRWcZKH${z`btQ*d-wI8n$Ja!%l@iCPFvcEbzwcS@+5LvF=} zVpy6{9ep{$dd0kp$EUh7(emH$ z0aW!@Rr{q|=Pj+~wyk~QTLs5ebR#k+I^)>}VfOD{j&KsdM*q!^3<~y46o3PE-@0E! zq=70phNXDSlV4d$7k(6FLFu~}Vn+hbhJsG!yz7-7&+`~gD_78>BDq7}-K1{9BeSM; z8_Qku&m&O55qEH>@h8|N2OZCiF8`jg=^uze?o1a$ao&TXt$zLKw>}UP3C_5qe!qu> zVLB>E>rP!WXPzQ6u5NwVc$ccALv9Kmlx1tQ^Jw`_;tqQx81h);znOL2CPNQ?Bu08a zsL*>P6uSUot_xDjo+COdOChbcykwd#^m^-UgTo1L;zboPys2F@^L8sqYKxVG>`ybo zRlVfX7>h>uV5_|m$}__3E{mpoiDi|dG=RC6aLI0Uyyw1-CmiIx1OOL==82&pqzRs1?F zBe)ub@{zi!{a9=Ag#LTk z4&>DYgiXLd)?XwL^mX&$;esnpm2eK8pq?buh{cATX&PpbZ!Yrdsd*nezj5;bXfaCg zIblkoa$E<1^EYegYBb?@J;2hSr1}raIc%i^>dwG_l{r$nlV)wtIPiHuXYZUF^6VX; z_tC`u>QFDlkhMP!IzL6?iifM(i5~nt7jS5oNX+|3x#sI#jby?(bJ%O&M}-92?M{{f zU3n#?xnm63)UWIe1`gsSQy*x7K2O+w=AfRdmFG*=1%Uw}9+Cd==6e$1CiG}TyO|?( zL`QJ)z`{ZqCp~2D9Qe>pxT{_ zB*h%QMV;tVYi>zZt&qp=K8ik3e5(K=4iUHa>jh@14||%6y;Y~wNX!v!eiTy(u&Rl|Fd2dL;P|k~|-TmHI5`VUOytNkC|Ew5R1Y|Sl z{P9KRtW`HTwTROtTV)etZ?KSvLk6b*z86@JrN>bkhzg`fl~}YPvz0Ekw!o_WEa+7wecu3tI3Dv^_SKUGjtnJE zxjyKyEKJ>h%_itKBHAtk*-=zI)Qh3t=cMN5G301kY7?`-`@_aS&JER4E$Jo-w@f6+ z<#c$b-lvZB7fsflxD6Y?vlWlt8=_8OeP<^+8%Hjh;K-&w1siKM+$yT1q^i(xD*>Gb zpX{>wBXna&V?nwQThSULzhwCsvgx}skie6v20PWVFr#eL`G&KQ^TV3am*YEx-_Q#8 ztiFqX^^$QS?ku5Y<}$;9U9}-mrm+|0PDJC6YzK8yxuiaY{(zC2=bcE{VZrHIvnLQo59b!G3i@r=Bg3 z{Wt)F73@nJ@PZXADWy2q@!)z>#ycX#@wDWWx{`d*fOx(isqEe$*TbX=TgGhRRGUkT zBJdAm(ludC+DIwNZ#mM2^SwdN--x6@YC@-E$}hfbq37Z&DcJfgoBbIa*6oj4+AE?e z%Ms{~=kW0GZD*y`=C3*5GP_S3sJIqb5O*A)T6@a&+K4Wvyd4lA03@vwiJjCMJ01$I zc6uF*`R=(Wt3kh|FD8tr7{>z_RNHLUOsdgbr^qx_=jY$)c+U4*+(DF38jm9zg%H(k z+_n6R@3Kk)FA=t`8NEpFQ!=bePdYrnW`Jv6HBNoc@i)4)@2cF7WO1#{u%14-5syo_ z@&0-6F3v)zZaFGD9B_M|YQ^vcs7aq?<{Qj)7x4*y7VjJB4$1_o>W%_aYMU7lkXgO+ zs&7s102<>t|;wNU*nv@K~MLr&c+oas?m!UGu;e;uG-Tb~iTV1&i0WO z`nq01l%>C#qDojEJ1h9I;2;bvOXhB9SSNVX{{9Yp#>xbsD~$kTgo)#GP8(GxwepSE;UMgs++u$oB(ZP*FD;in+j<(!s zC8;%JYP76Y^|zYWa(e(qAQKBnUFSQi!xXuYx{s}p$3PW*@z1#6eKD<_=}niUWQWq=S4&g$uKDYNrzv(RDfE1wB6pe6Ol4h6TlMK5v9aYXF(hPC!e zbjYa2zF@qYA0Ffgy+W~SS9gqa`}f|>1}|Is7PL3#yi zO$KHqI>J4P>XQdHWBXbH!ehknad)MTzXm#2B(wPa-jLO<`Y!fY*(MB-zm4L?lW&_tX+(_aXsHrP>oc zQOk)WTZqxOLQbRZ3J=|PjmK=AdYVGe@Vp#>!qkE?(9EeM!rYv}Fe|~um3_}j%*)26Z4*V4!;75Ih z_HF-RskTVpehh!M!N*4Zk&tTx*;-9UV?fv#_zBWqJL9upR{@ugzi;AO7dFq)Y9`@O zA{=MePRa_>OQnQ&^)ua*B{I)3J2CqzfPClv?a2Wp2jiwVk-#UiT~UVC!+;@chzi#T zJI_v%t`jvoG22|U?aDhQFD%Ktm}q@^e|xMHLzzw9mzs5dfo$Gq+zr_$qoM6eY{G%AJ2P@B3ck$&9ByLF@PV1 z#3JBAv1k3;XjHY?!ymMfR3=+E_=w;Y3)&72)OMGJrKQ|lvWLsS{fcVfRB;h(drt#C zU*a6m*{4~&_}$U(R{PW^QbBGv|d{mXV0)q@yZ zcvUbwS=OxphoDVy;t5CCqf~L;s_oZGt=>gj$urHBX9O8kLz_8N&KAOCeU^jkrY9?` zu2u^-2b@U?(7$c4<2!e6v#~%1uzN=NBv75d$G=MlGZ67AtuwtoKXOMu1U>O$&83^C zp(XsM|FNZ5^-;Xnc_;H0Mssd|>4-UbK7CXWCKoKec(G%hcImYJ_8=F{Ayl!w@l`-~ z=t6QdYP94KvfBWj4{AMEoMK_W&K81}L_N?b@@9e`v2Qc%n`KzG`sk8NPc-oo!5L|v zo!rA>N$p;+nYguf1J*%&G3s7GhWKcHy!x}n5V0kVIe%Dk--QQZ!-0n4@di?DKSlP{ ztfRiRa;LX8to_m4-EYG1J9hgRTALT>fuPxWd#@j#q@7hrwPH)HGxb_B3})L=mY5{K3=Pf>)nF> zP2AFfGXe8>Nc9T>WJ;+=`S)tc&WPi77bID~3_z(e0oHgvFG%j%MT>t+Nm8oE&Py zjz-{%#+_^wneFujal_jw>EjMMFR!{Y;PYM3WB+gCo!r|Uoz2|*Xh)>uO2A{r*5%qR@BZYT9erA1?XQH8c)DdegpDg312_TuzMh~FM)!EAXlPu%^UtRENG z!+giRA6dT=)ig>Em2R>+0FrLR-#_b>u8n`td}tuLRjKSm!Chn&Z-u)j4Xo0;l)!if zY##A=0uGw4k%;$B14fJU2$(?YtP1qHJ%wZoa`m$0N}S2+TD8g6;6Rs;`cX2a(VfSK z{KLal|1vo`8k*D)NSa4We5*+yqn4O~`ak02PNfGqqd9J5rK;f09ZumJ2l%mPS5s5V zj=QmQ$&j5vNW+Bg1l3M@M;>^$8r)7@ei8rOl}y4rWJmP6z1gG}mnL({LdeRMjIz-7 z1sXS0jWzY4h?In6KOs&?d{)8brbkfXQ%2)gWpI;esOaL@qzTTV^jNXxKj=jqIGvCw zd+FEmmDBJxOi&M}3!3e7=VOb;`g`)!kn|GVtKuv^U66uSFy`c6DfyVo;#AF}c~L#4 z*}~J-7Hc6(WlQ8u+nimXY@)1{V^GF@Iw3Cjj`m9XA}b(vLDzw*>y;|DnJF}qnmq)j zbkTk($%SkUjDb#2ET!|cCo}XXGkp887DYwpC~cIHY5HNc{<9A&+X9+wH%Dwp3JvjL zlwhtz(8n0aQflSyv=-nXwW$3HJI+AdTw}K*EiS?o{;eS0nu*tOClp(abfdn3hJ(c{Q^8MmZJxH4w9{r#1s=Yl)JKuENyW`* zp2(gMNeg?4)T#C>BS^odurJD0ED2;Lk}AnnS0~rPPJGcv|K6xaB*2`0rLgRRDYl}@ zrGWCFjUKN;w4VgmmRXNMjTZJ@o2f(nwZ;%XI0dr>_H=2DNsic3mjpd`iBRP#ok@1< z8s*hdEPCNheeti*hmTqBDXJaRX6-c$+xDFI-fz2=sKTo$IM^?*;K*nE+R3+cqRwUo zDEp}IaoVzFA@9j1cPg`>&pqg675W39dq^mZ!{@yt=rai#BVtBGKIxsWI2E=Q9oe-b z*}vXj$AlbDheyuU>2dizlE*~kE8T|}TX5aO9+a=VE*UobD_*3(Dl31g)h9lByc400 ze(|W3ud1XVoo5YyxO>*XW=~OaQ!~@9d+q;c0m`S=;*f60c_?ttamNNZhEL#YflxqW zGh+;$5G?x?s?X>kq1RpL-0<3R5I!diyQgtH$sFT!BWR!H}yV;Cz`0m{8-VJN1in`im4qpjxM$|PW= z`|>r0H~azLVfJPD#}<5B;68`8V2A1mzuSyw_Lcm8M2zgjX|dCxh_UJ;lK<>(>Ol9f z>q|ZzgZsltV66(Qyx8_w3tq)|w3ItReGWFzzBl_E2~Ac! z?R8kEXYvtnIU$dRvah?+8;RL@bP4sa#L{zja3R(KTBx}Zy2=qO?cN|ynD^#i`3?jw zIE`H&4LtSkXI05?3M7Y!vqhL5BDNi$iEidlz)x}stEXcRVhIQA5eKok7f9<1|6{yqc zM-z2uuJ|$<8~&ZoS_4j3q?T6s$MP1uw^>6>Z>FFv9m8J9kWHLjm4u1DERo{8LVT!r zfBtmW8v}bYpeqGzS8W9AK)Pg6KRaPloArw6(-F_+f6l=PXYrIlKOPDSYqCBSuVWv> z4R|F>wWY$gq5Y&KfA==)4e>p5SbutNx(}-%#Oby&=@MtZ22$S`Yb0^GI^ER9MbYIH zz9;tv$k%=r!Y3bGyI6WVkgL_u3hStQ{Cy;}*g7>WrhXnVF?Q0x8+=eJxS68)@`(%m zir6=3&vRYi`QBA8B23aduPqOf2!6x=zGl5aQ3pu12%PyVOh@Op`Q?#Wg~>Ng=A!{_ zQmo+T`8n1Zp4`qH9QJ3IZyyyk6bh}+gS+lxi!dN}lc9v7V# zi|}?i5o`sHYydjLZfIKZGs#b_+j<)#w2860bh2V^!nM6gb0g+%e2CP=39q&mc%c_5 z@vHVb8;l8rpWFU1OdZB!z^yBQJoz)x(9p+Mom>RrEt83E{Xga;@58hRxAV-pq`END_n85DOLZU*02gAE`jurUK5g%ZPcphg9b^jfQ}gZLFWY-@u?3JVTUTuA zK&m*hSJt%KBRL{iW|)d2O-M=O<1(J}ft&NL=U%uqNf$t{8GLlbOJ|y4NSb~~f_9ST z0UD}lo|s;UD2eIRR}lE-C{>iw?^8_GF;=L`SsPb&v+-FD9sSY5`Cuxx;}nx$O_fjs zxSEM5@jBQ@^g$-G;4-RaX^pdk`CFlox=;|zt(?V+G(e*(A0>do=~(yY1HalLkfa27 zx_;;zvlkki{-2iGI3A4SZpTK{GU{{yH&fx^SGo-+@B{-o=Tm$<_bO^?3LLK$>bk?V zxN{cya=6oXxWSt#KM=*Dppgg%ho({B3a^9YVTX&d2{z-=wfUjL#^jAMSwa-5n@z1(60*=lZ*AmDyCiz(FY zgrrzoF?m`sFSqV%D0W;vDE@@QOb)9zZ*}R~s|0>5TdKu(*;GzmDre%5&n$_EV$^M| zgmXrmmrc(D9iUdai%^8S*R;r4(^SHDj&Nv*YWr`xL_d@nFe|T0b}6P8snA>5xEuPn zs9%@p;c5cLNEzm!@t3n5LMhQQJ`d(3g^@@6O{@AOy~2K)XQX69Pj@udC8y=A3?GQGPj}2SQy+48wm1!H za?xP#Rvnb1XV}xx57Jsyokmggd(bLPHgr)(4H*1sCT={+mBs07PNb!8*6cr+NZHC( zr4OlP0{&UZV8iaDxrTvCxr3-hAM5WO-?^OwtG^jc>VS6$bnNzB_V_fd6|eUV;RmSDpYts!pKP6I#Z-9fVN<9^?Wx_aWpGPvFo1rz$*1dk4W!$$ z_3Yw^&S?Dx$qk#ku`WtlsQMyYjjh;W6E3Kbe#_yo>69aBYrZZILx)HHV!b)2Mr3_= zq?94yz0OzbZ-9X=!BK#bl4xD2q=mgh_3a3#lC@36`p$DsM?Z!7_9>8#!TnrJY^Q;q zw#rvN>U#j#ldfX%dwCAhv=)n>6QY?q(SgPSYO}xm$OQ4D+l%fpc0SdX-jiqzAhIa1 ztI7@jn&}>I_6MK!^cYBKo>u9E5K*C)|26waaM3O7aB}-#6L)@vZM7$O2&hX9O#Pwl+#R{AEcT4W3?|0m& zUi)|c>L|^Wx7903zqfrE-s6DuqQ>D$;i1R{@}q&wI1QHbf`fx!kgJQnyq5>*x2`Be z-iswN8P~4aKnns4?z3p9zdi}-y5B6NdSbMvOi}g|m=tjDxlGNW??P;r32tFS8-6+C zO_!WKS+UEWCyMu7)4vp{*QP$)72uyaJS@DcTxX44T28nNPwo`oRDfo^_H#lUS{IM1 z_q}(Sylfu73{4mnElBG*rs6E&2Oq(j&Fh9i)%nvEI6ZX|wf?<(mNq?T4-DPoF>S9H zTOp6|e~lV)^}_Y$(+kfKOEEY{JevU5ktM0ik>vIuo>ZR^(%YxJGR z-A7GQl{29|e`W?uD zds;o%NlAB^3fZf~c8-A6tCWFM!ljad!{d_r4jaN$GG&^d9qBSlCe4djT}O35`mG2y z6S+U~dbDy#<>H&mVJ<2{=|s!8DIO9qUMqT5GFYA_)_K*2*#NW4%IW#dHZx60 zjqFlFPe_&_Os&iVg_{dg8Mlyii>+*0!P}3Hu8@BqKao&$xhYL39rc#R@Vu?vxWduj z`ol#>*g5c8RGB9=A2dJzmCQ&riHp(Ltl7^&NtJ*#Ip^8|QGl9&nB=QKP33P#rEQzw zF6)xo%*2x-={gz6g|4IT!aB6n&e%jNQgPRIgzBotY|EN8@#Wgz(N>K@BA>C^GGz+1 zznMN7rT06$MxzzsCRe47JQCq>f4O*I_hh zCokgwJ*{E8j3V8QO*_tb-EwDZ6x_ z|IH(Dt2LN6J)|1-ESTSzlD^vHx5flDN$ut?;N-^y`G0qQdpmnBKl{uWH^eP2vKKq7 zrWQr6U}YDTyO_G(x`qf0 zBI}y)r`Lt{cVocXD_!oKtwNL*bzyaz@JMiD8QiuGHg~48SF@n<1`ni;HBQ<1g*da$ z>CE?Mi(;p5=-U>m$vY;CUYJR|0$wFaPAE1n~WXuY$%L z^d9mpn=*J;f}hRga;U@^4SAgq^^AMuP&y^pJJ|}QLhh+}T zlmIo9{~sOo1%0xf2QEF+vV-Huvii1}f?VZ*%thHR4006P&6gFkD4)@C8Rtyb!T>c6HctCn+8H@pzfxw`<_rpT2`b<6?e`65Am@S7?)<& zVfts{wQwhtD46nYo*Zh8W29u93(5-do5sLpgj=Z`Z<#Mua7M~vDqUqbwNw01bBR>z z1WwLC!HeqM_crTq%BSPHO5L`nvcNDk+3U?NjrCr^Idl8zD3_vz0Z#n%I#_GczH39d zSnEUt+C@{}b#-rBNZWr`^>!=uzr?7M5FFxwHW#x#w$$I0er>EwPe~!6*M;@A7_?F z1cq8JC_08+j8!OJAt+!m9CJ?5uYAyQMS`r{SrLq~c)6h`CskW!si?iY^`jXf@au|j zQ6)}8cf>+s^nFY%*pB|BF5C_gn*hE`W8MmkG^{S{4$sY@=*$+4q9YB)ddm(&ef zS%-E?E0$$oz%Osmjci$~`pH_qX^*yYWY+V)3xxEip+3B&x>D8VVPJ&phVWl}i&4xd9*8Do97DCbHCmz|6T zkm-Y6jBK`;$lGiGoVgoW0f?{l+uW)E)H!!Hpf7v~c%<@hx2(0Vo>~OOUcVc+^lSd9hpDTYEMfVNlBruyl@Io*+#Y1Vr1aWI#4I0H1uoq6tD-v! zw-m!W*h_u3GA^ZopCPHP3CMWjEi_^mg`QE7bpW@*%+4 z`IiMd;XQgcIeZw{M*jDUIsJT4{x^6W#tk4jQ4VMu-Lr(X>JV)vW@wxAaBOBF9X=r$ zI1yhZcN{Q`kuDJ*UpNMDA0Xw4G9_CrIhi9Kzffu?l7J1l9~vLF6ZlT5#WZpfiG?~R zgX8`}+NY{!oErC#5s6i98}pr&piIgBsbp$+S++6eup~aUs2+$FWMIprIx@B*+?ywq{u8NXAp{u-mIp)5YN~73o5X{hf;N|Eabp-uNN&Bvym4=^ z2>F;b9D>$DpMq-9v3{0v3%d8nei5?&a~_B5?$;49D~ZdZU8+T}EAE2v(|8M<_hOIZ z!COUY`F08Tqck+VPH?c{QiO}V$dr@j)I1ZV1l|T_#2x80h@s5DdxSSD|EH}AVVoXA zU*h5yWj2kG$IqLmFSGIm_&}C54{isIb{BWF{U4L9JvxT>uJ*SQbgwf`0g%4ku`73M zS;BLOs5}K~poI)xZ3>MlRSanh8I)}p`4!gnP-(R}aDFJV4GVlBd5J_tHj`7bJD%nQK=o`9(}=L8Vaeoc?H2c>A>Xh4R>*tfb^DuAfK zV|aC@sPds!51IBbmy|)KREw^Y+pw`^Te2T8 z@T6kIDQ+G)Co-oiV~{J;qXgUWOs#?HaS)fcwwE<9cAAEIfUpxmCOW|~P>frR_UX#{ z2HCSeQm2(saegHq2)Ly38(|R(`n9!pwGtFVORn{0NnQa=!Uz2PnTq$QT}6PP-!h*v zL<~$W)|`VPsx*Oleak~KwSagq{dst^ihL{TTOL4YYw-m?cfI`HX1~Ef^zb#vSDw<% z6V_Kgex*FQu`!J?X5wDh_rpH2|0qvHr%4?PC}U@Dx`QW4i^j9lg^E@E-*Ji0bE_teT*d;#Glgk1md$Bj|Lnq_1*-k#gFzJOC% z``iS!l!#|wU7j?|;$+kd)s~*`e&S_(&h^vel>v=|&k1Yi!@rwOU%S5qcm5T}PulAULf?w`k`{w$wF8j!chZj!ZOMUkA>-c>I zzCUNn#QY}J>~E&5tM;==q{iNFEk#Gf;vr+2Q_(H9@+12vk?I z37yk4w!@Yaaz)T7)OTj^@E(fny_vtH7S`7H`MMa)E$E74oMHO$2*R4u)Mj$~#=yP( zB{Q7Guh~Y?Z>;?ns1Ky8l-k$zN3wB7A&qaxnAJURt<$hY2T5d_S9e8BPrEjmkBZ4& z@C}vCzO56P2VR@Kkn(q`ndy7yiw%PH?}s)brn!2iv=CmGAJFqb@6Y#My5xoVQfi;vT#Dqg^fWj|ZjO|wK2C;?DfG9k=Q{9UT`gU`iVVZ@P&c84)zV;BV@gmVjJC6_?}j1+ zPr<}TO#;s$p1&-CBnv~ssPb6psGzXj&-JdL9#@LccmV>ds8BL+TlSx$Kv4xe3)7RELCm0T2>!n)-DA28Vsp{{JSxC^8gRlt7u zJb{$$eE>BdM_q1VGrqR0r9V|+g|QHVJ_jIgjM;|YJ7qqcP?3x|>E5cu9>8gtp6&AN z<`((p&t2~9p`IQ&I#}E7r$i9Fdk&+L*{eu+BqO9G3V&l-C4dlCPx@l&~AlrR&fK#{YW8do`wSPSUCNngpIe6fTv>!R^82tX=9P+sy7p=K7}dAYs6o4{s zk_@`Z&ClfKzlh6Bd-yl2evk)ONnBjda_NvHygYXKanJF#-cRyL?T(uFdM{Q2Noo9d ztVyT71CBRFI*C{QTNVl#)3%%mDl3AZIdaK)+R;EmUteF@WH`24KexZLv$L)pcGHAI z?S_LVMF7u#7$F$#Bo=zmhPd{@y+P# zu%?ms+Oq_6nV(D;v8szhq&&5=iOHU6GbLOpN!)nIt}|#d^m=AYehp;hHjtwoQ(u^h zF-QsL*pQ$ml>Fk@=pq~aqWddsRw{wltJy;Za-`#M=xq|66WP`?3s3aH@`Fd;e7!Pe zwRjO5Pdt8f+B1#t3`u+OCjCjYb*7AJjOqe|gW4~dyj!K>KUEfb$NzZyAz4Z*OCO@Ej$v)t7Fs`U`*`xU{ zPvB^6OyL+{<3dh?0sUVI#05TeoGx0=)Dvrh`H>&65pf3h#trlI2NRMmT% zMJ5JQUni{+c(^#w;Z66Okn$8j7v>$mtT6&f@I(wA9yJH8%^W0WAN$ z)|0j9C;Gb4_kglEQieypLcC9?s+TPvT!!)9u9xGq+PsUi!*Wh5%#W%M`avX%zbtNk z+6jQLq1>j249?9(m}>Ko90EP*ku6ps^Zk2!nGv}i*9SIg{4#r9U)t!%nb>L-pk9A{ zd2AqCL`B-hc_5-s0|}93EPcbh*q7jczz#MT{M&A8OR>95c0gm&rOqy_H^@gpFqJwI zIMRF1S(!yWi4FC7eMvsssuXkm!JedMb^Nce7Amr4zYJ1)n?RDSw`RDXEpl+(Kh>Y-1oWxo_)$h22}fVK&WA}f z?7ga#a+YWaadM`ClQ+u~J(JaKNWRLc&MyPhLy*I{_wysBYX6@FaDIUW%KOU7MTJB? z-s}&?-HvaI1z6qF+EO_p(GJq_J_a@ZB81(gG|yLZ1K8D6VD* zi8FuR>RP`q_P8x_V_)_v#Ngloh$i!9bK<9yWM1~Bcue@ce z#YvzX+ebbW*(*3sS9#>}U-BeQ?~Wzd_80o8(2IX8&YaKb*#;Ri?P$1KiE22N$baepEFZ|Ln_BmIbax0FK__BSR@= z@!WT-n;GHH9iwVY!ITKx*O<5C!kQz3#ura#f^S1ZanC zDzEML(zAp%X98zf--mAq^6P=()EZ)LO?2c{MkIqg_BPewjd*lQ*}qI234B~|`%ffT zs*wP#z+}(7J|1F(qnp%0pSnQ8WLSbas+!U7Wx8A+EquL%*ozs7T#F=5#e+%!ihj9*HpEzb_d~-NrbDQjJt(Is!Lh%vA*0p&Mw2ouCBc{Eg^9LbK?MDg z@O!3?znZ`;kFVLhv%#~HiskmC6k%0rHeW#0QG2ZTRcT79WGY{)U@&Cd)(}dc6RXEe znG4hGCoj@Ym1Ig`t&V=aKaOfVnT2a6Mdz__v@^$K&DYu`8b;x|;tP@}ZPRG#KMrp4 zjtCe{q{WdArQCw_%Hor9>**I^tmdqD4dnc3>ioVm&2=x^$+~KSGdi~8so+)yp)p<3 zCC9I(J_m+rqH6R4P?@Yb7gY!T7}(C)rV6cRe-HwN=1<$RvKdoo)Ufi$Tghm!8!-Xh zGlNzhC`~$mYJGO}#O4j>=FNUcnSDPD%=t^|fSOOrG*_T^vTo5hHgK5EyRx?i7M5hrGi{CZ8 z27$hu9F1myD%bpNXVBUUn@*uoAGg=ar<-kXvr}R#3M*=XgT5YBbbm@5r2My65|6>O z2B~H{ES_>2M)wa9Jxw_m(W7H~fRvssPI^oMV`PfqbyJ6v<(>?{`brEs@D`!l3R2!VVmtCTukGo(w+y~i_d*a zY6-eS_VBe_9Lhb+I*W7us&jOQT)c{E1Wi>ewa(+Mc}urfI{GFxwRVhnv(8N9{bA_O z!q!W2HG+suFE0cPENkQAVLX?zkovB5%7UST`E#X^xBth-9 z22H@4oCo@)ByY9yeko^qzrH-$MJC^~bet>?P*7;y*Sd2UtaU6%>LGAOxcixJJ>}SHO(j@q3RN-m1gfqN7gz?EK+efYJ{JGYAf{hMgCsfOBv(vec~GeM*j*cxg!C1P7n5RqEe$%k*($Ah{MzF>Eamv{WLNl6+~yz7>D}qkt3mp zj9?8hp`<<{>(_wUx5^-8+h3g62L8;yN}x+W=DL{{A*cW5kf5ik3>0$ppe}F{IsIA|GXmKA4{KWaPM6N{+NR;sbuPh!2e*kISx}P!4+chyvPG1Zv z)NG)`pRtfNwh^rc@RX|&a8l5LiH<3^|HVozE>F3X{0g*ZcMyCmnI!;#*094NtZh}V z5(k$#k*ZRnW$JL%hHD2fh`Je6HlS0R|1k(B?VK3g)u4gHB~;I`d7#az9{^(+DOP>4 zLj~g@UTa+^**(-NhqT^0_`{$uUH$yZt4h&`gRbNU&7lH)Pi09%A@#@t?l=>TJ9u7| zVHGAW-?!%Q_iv0X4wf|jX!R8WZSRk@Ra`taFNG4Uz9oBp*Ab(}6W7v$v^QiK>1^-c_jI@PUA4-n!0Q#J|FhoM*5bW?37&!h z)zUe^f8hPi3#qV!NgHsQnO#J;&s%(Z((hAr!O<3{0VtfpeL;V2M&e5zDlL<@?s}<6m}Uxz|M^5d zcnlGtrponwkbC(hoCk9H_KrUHZ9oL>Oq_KM#xDCK#ee+5FM6)0K5q5UT2wKi9fE<%!Ucuq$kq7i&@xvC$!hr8+ZOy* zU*UO9QIQn;JL6XNr|)=spq%mw#$fE^c_}l<@+{d*t7D(TY9lTdo>g^IsV8l3ePwGq zaPtONFLR8A*3|1A1{SI>*QQ2lniAiS09ui(_W!;cPtKgo&Yz zVdr+%v5(qD!?^yhuf#pJf1>1Me}e5`9fjFB&0akdp*(-Z(^IKGyL(Cz9RcCbs-RaCb8McvxaxB1e<4+`?Cl(Hj?Ov|9Qg#~lfdgQelE ze&v4Kdi5^GL7g!h%1s2F*G)$k_T^0Jn8OJfG zWGaZj{#ZBzk%Bf1X)RD5pGH~>7=?9!Qqg`dC=1}54SchKHl0LsQ_Q*=!=}$BYmUcA zaJ}6}%JjM0^!dEKniD3}?LLGPOo0jB$&ci7Q z#(%lY_Wxs>%2SIfyxiM8>?1;f*|R@*`)47c1!mmGN=Tg64}TpNy)3CKK+&3)#rJaf zUXG-2h+m|hZAmMFvOVe1OFkbLPW1RuMa#?5mKHJL5Ce++dgMM4bfiIAxYfHT{nHG- zsiRJ|TCDm=c-Ot8sdd;I98Feq|Sn<#Fnj3?eoZyp`Tby#`-daK6r2#_E_mf9dKiLDKkB|s?0jGS1Iw=6Q5oMhs}mM0#c zxZR!cM2TbhOJ*hsNM#Y-+OaHKRRXn9q}0>`QjH== zf+X;;boKWA@v5pDAgFx-sJiFipu6_2e*Nmbci+8t%gDTEPh4kwx5m`Y1j;&kR{hu_ z5uB{c_?|MK<{56gW)kaZ!RXk9V-t+Dm3AqOYrJ*SEc@eeAj;E$ zlDdXQg*IvdG24M6W_!HL_ic?Umf)_Jki)&2(c8N*sHb1ZeK%$B<%}CNn`VgYe*k@ zOHghxB#j+YL|O*me3h(kd)x{)>rgW!F{&S7C28u3s5#BWkUwm#~ro^NZAEL z5-({uyT_T{ITftaN*cPUBfRT!vJS^Q1+BkKwedAuBa3uHIt zqLnl*GbC5+d4}JnlS9O5l%lLll{sYzZZOWU(MmEivZ>`f(~R#q>m4hJV+$Nx&=aZA zS88yZQQ}fVamvpWj&l~xa_P=G19h$tm}|!C|hDHF4$cjrxer3 zbfn3;4tw1qcW6C~#(LOMn^O6*n#z~mQyC{8*D>RISU@iV3=R%?>Xon^wHop3UVABm zB4i`aV;^5Z`_Le}262kUW9Vf(0{G^w%YmsIxbizR1`s3e8U&iE8oUA$ys zcHYUd;N)0vawL`^Ugte4Vt}?~@?T@ZCZU_egiYi*ERUZL<_?Yp$Gs40#l18s)6>(~9crRes^YTa>=brq%Vet#LH4A>o{4eH-o?+_zpjojb^12ioE$Y_ zQ`bsFfSuD*m>YB|-mwcO)`DnQxUrN{ z)V?8wD^hS0WYS>EnGxhqo}jo_qi3}0O*~b7CaB}4>PVx`mXR24s*bQ?T>I??)FAVP zro!L2R8l(Iyw8RIrd%KFqTu$cCK;~Ik^d8&JFnCzIdLBAi?);ll|QUer;P^fH0_IH zC`;om6j8etl`s3$>(s{BAA5PF+X*kk{y1#2gjgx%HbjV*6TQ6~fk;?xS149BG27R- zng0H3IeGFVhYmdw7P1hl*GYB$aKyjX$#hyIvuv4 z!)kVJ=M0Indz?zjrNb7S**S%7>WfsfQ#($3v#QlHY0NRT^BltNShU@8aIz;E-=hYZ zs-x?evpZRza`|X#hO0_3k|m9QGj$erp5v|*oFNiq*EW^2$v`!mG9=d&p5_kPIdDfW z=gjq7nLEV+IuTYPAZ7uy36Mi&gspj>qr%kAig(O7+C+q&(P*HcbyIc5_xS4m9GDd1<8)tDGXO--T9dte^!G^y1vmw57~;N2;1ZqQn*Y+wSeqR)m@B+Df%#Zl*m&IGF$w`Lu# zGb9gL0=>n?*iWAKX{J`Pwl#b9n|Ji^;0h)h>|+A^nBbD+39jra@y6tn+;qwP+!ylyJUr1eSK+}j;?4o#8&mX7&No!r|! z()Hcy|EQ&MWc{1A_rDd%|GSR)Z#qU=QaYuPyG3nVI;|=4_MV;>|M?n%RK$fEj8tDb zK`vW}*Un{#*Q95~5);-1?Tmqdl+7+U?3Km90>2dtPL`@Pp4Aq)Re`%4Iopti3Ilah zo<;Kc+w5rE3BqFEZ*9TJz03P@e4FAbO(M18mHbu<4MhkI=P$828$LX79gH3z zRdE^ZUR*9p2@SJX=k5K1t>61jK*E+18avKTsq)}0i%EmT)D8|dhWWv!BcxncStNVw zw@+TpWcfyQpL<5BYb8pa&GEh`4{=}jG~??YqUzmGV_x$0Lz)&1CVW&~-dK8|iyy?$K-Ra`3Q`6}s*-`^_( zb%sxt*?IjG_PC&QPOaN9FvZ^gQpDWvDdl@yuKu~R^jwxmkyWy~TjY^-0>UC2EU`A(`1d z9%R%4#3wZ3B`vT%p4*`Y%X|ViQPObsjMHHW){gd|n>y8$8>nriAvv~ZoHIM85Vk-o zX$ZR$VRs;`&gZ@{5t!O}4&CfUD`}i9X>6H@v5<0k!kFV{Q)L!P8f$6rFR3VLYUmR& zq<4N{Cvj61rgqFA>~>~K8mEcz_|63YF1HiBW9LZ*tvcf^YFlYkC>G8ljS9ln&`L3c z9Y@%)Kr!p4Y7`5z-g)9^r3g;0hOnaN5wieOJF1NDi69L;mF>mT>F?_5;?SW-!j5%_ z7d%+gTL1gjXD@b;##oT&sdju))~HEkwdfI-kN2jSyy2}Jdh}texeA3-MN&1Fk+oZ} zHC5N|B`Qmi7HgIXmZ&n|H7ho?Wr`-t5pBP4WY-50p{0U`UI6o9db1X8^ONlA#4OCUL5(; z?h&tXVO`M9I4RJN!@beh2rI#n ze_4k;F0h_%xpz+q?59ManvK-q%zIpRU9pbK>Q%&@aUQ!m!hczq<_qm@2rG`8QluJZ>SDr*=$nbZ;>rYcB*vp>yQcBoCz;x*h*_URZIsL9718MrvHI(OpOk$uwr9qIq%c{;PKrh3tlcIU?d-w!RIPqn_ZP3Y zlz)BvC}K)k1g2^(nGH>{qj08(QITZUsbxk*lB&BZd)CW{HL4P$E-~A6b}UQDWTH?67BUJWw?4o*$I&=J zRf1~`$uHy_?jG%7vZS%id;j*GQ*1LNG2nwa=UI>8TNiIixjblz6|a_E3j4UgJ}!7m z|0WI}U*L=P#7V7jNv(0Y>ybLs)6;z9y6!i9}jLW1VWSwo0rg1f?mB%xBVM-{p||2~ROQ zrC~q*((hj>qG3jK_SFwzMFb`Un`+}sb4_6w@Pwhavz;<&^mU$<~(aGER+3218 z)%3S9*EFxIDh(iv|3$Fl6FofoX!Dv{t%zHRR{!@ly0(W@#igWaUR(EC z4m|vyu%7yBe(1#2JR?riXt_7O%2so7L|ql#GM~;cy0(YCPkY3zcdVMQ8Srvw7yV8; z1e+iI3*Iohfr;{sG=xp-3{Io^7?&i!N2=m7AvA80m*Z%sI5vADH?I36KRJ7b$&OPz zxo{(8Y0$0b8Cx^MZRIicSBAMgx{v*hn^Z<@n}uu`5Cgs4#EqnoF+)jCeg3?MK*H~C zNYOKQ2R$bh8GmSB1ZhOjO{JEd+BuJ(`Tq-Gi zq=fsCR9q4(DshzX<3hM|p+NiMs#UHn!F5UkoJ80(2-k5R` zz$33iD`Q1;CReP$W~u$L-v{u=fkLA8^^1_04Y8W*-7sf%Wnxtjv#o@zuQUt`Q;5}4 z`T4fRp}KqZW2utrVkT)@t62m903ZNKL_t*jvg;FD&sOI~4T)AL5;Y{X7E&}~i$$a? zK*NwU3PnZCj`k3d78q$!=8qyIC2U&{Mnwh$tsNIwalzi1BBhwdh}c5mT#<>GvNE<4g6x9B z9-pM`P)-GV=ZfUpREF%n=|hyF8X3_fhI6jNNZS^yn81igb~dIk<2rlio2uDt*XwJAyw4Ld5xR#X;krY%h=qJ@R)qG>Z+5l%i_MVKsUe8tq6^x8v@*n&41 zl8q@<$6W7`v%XsPK}!Vd{1o~x=5_vfWD8$3b-p>ex=7j9vRm!Cj&I)kIQu?yh&vAT zFnXwmo&8g!x?M*8Z40N)R{6-#qwKiqC||wj3^UW`xbey=kqFFpZs${XUrSq}jjOk` zll|dGAp*C2s-H*$hAx%t{cw>x#(Eg}$1Q=(IQPz`<+1gIAoH0t#^n+tEwPWjJonM4 zNvxW{j=l8bm8C)aS;)|nhxXxmYS!h*+36Nb_7`Ng{yN(ZSkZ{WUuFuVcgRYdF1Y48{J<;j3jk_g})gFI=yF zGrRVAs#%|yEu*BHbGVm|BZtSB*!5ZD@ByBBqo2_1Z&L$m#8LL(8}d3`qdn&-QT=O; zL?Gq5yy4h~m~d|-LWGhyMM=}x_xK^z54q|Zwf*5uM5Vz5ms0B)4TxF0qj`USsZ!v& zHJ{=K`jJJ%?LPRC3lo3{qp3yd(>&o{j>tnO3bdf5m+@qwT=G%YdL=WSePRlVpYLc$%bY3;)MUb-h1yo zL4CD-`;GMVZ4Mge7em>7KEzht5>)d#)n)9M;#mi+&{WSvEI}l%6KUBtW(j3`Y{*5+ zw7kBEuuWKk`9hKTtV6|+xI=Q$xw=iA7|QlI7)bKADGy0HEWuTS1Lr;L<_yW{oTJED zl!A6^CXN0a_EJOMd0Oqqj#`4pY{5TRojhg<62M9CubVnoQ6~mG<9#k^%p!+o061m| z?#b(XFRvpkHCXU2vzlhWKXdS9Zj7qbf%(v^9?K;^7hwOqwKB+59Vp)VZ0V$hx9SRFY zGVRTQL@Or9$91w52Vw+P#<{A4nba|Al3c~XiV93kr%*0p)Fqj=bXbrsvNo@pv=Fv+ zR}-!?B-eRunfGNK-sF+7k640QvkC!V(6cm-qExZ~AILeu{;Rj$&>gfF2LF5j^ZPp1 zae;MQVBVu+9rIiW`XqyYIDkDa`1o5Nrapa?W8=rD9RCI*KYBOWA9axR4gBu+Kg@TW zcksV%P4FkbcorIv`CJ-mkR5i&-RwXeGG-d{PMyqOrm-FqjQ!!km;JMuQB?twOO@q=TOJ@T~`?lQ|-Va!R^4-E3Lj@^8$Yd1s)Z1I=kxk%YoRG#C!bHxJF2gfKo z*BZUH``9$Q>vGuGRXu=Dm-5 z{{a%-dS8L-ld@$rl#){B9PXVhue71cWW(sMbM~`@V?)qS0dWH($MZL7v8cS;7fTu zdFr0O`CFk%2a0GaB*1@p_cV|x_jaij#YjyHHQ|B#) zL^ey>Y})8ELo(Yw>`DPul9H z1}4jrw<{gZJlTgsav;QO@(fUJ3SD${b$jKpd(paQLviSBSP$LL;RQ9In4R_VVTG

    OK})RKvU{QW*}S*e_Op%)2LD*qwbn5~=F91Tu+6^J;jV}4*vBeZ z<4*%m^V4r#M=7F_{ih$JtE-#2_H&%5mU!RL5eEO~KyX~+GD#s*B>yd)OgT{lTvYd5ttkv_ZT|$mdw-B3UIYe>^Nv8=5eP9sjWD!gDHRdFR zV@2}obT*GBNe6SIe%|+Bb)J9E?M^`+ z9b;Clk2+ZjwHz_WKd(tcSX9%^`|A_P_s)Er&$uTTJZWKVIZi^)lRb9=yQ7o4Pkfv- zpmo`-iRO9J>8qhEv79WIr!z=7gq$+=kx2PvK^aP$AY8iNxx)xeWEoNEL-M(=-A`xURh5GQYK2&J4b0XKen>I7hY);sbZ5e0)-RwphWpuOK8-&nsvgf?_APpBMH;b?mq^+eh z#p|Rq0w=qGlUqQ~x1pPDtLAstBxS>iTp?D@;7sel%=Ya!2G4+{&w~E`ZL02_T_7tR z3|Err@$zF`N#RV9Oi#K=y3Q)nHQ(V`99JZTb45k8`pVd-B?<}hH zjH)D8_DI<_J;b2{Tt2$(oX{?xFY~i3HUn3%5a?FHIVL_2N zW+GIGTugX2Vk^YT$4?A4Ny3LL!GJdz>|sj~MOhUCd?@EoN6}DG;QAIa_KT~STx=!%@|5DZ>9K=zcwzPTB` zhRf-Z2l1_FmBQ6mUAkVW_w!`yD5B3-WL5x)vOZQsZO8t%vgPK_19187ALHx4^F8kv zk-!=}3H;FH)jaBv#}Q#+_UaU#Dl#-H0#dahEIypNg!^Yc&VBk9n`N$7r>}1_h40+W zZ@ZOc3D>0<+@^l(5l?yB5EkerR;OTSR+61`ur6ENXB&zh;J#&!H8dwNW+nGj4gSJ4 zU<%r{43f}I5^Eeja^`CO-MQN<6M4FHliqcbzj^fWX1ix#kj814Ic?ya&LP@uWn&E7 zzHJ|e=MMAb6JD9@0}>!l8|pT9ph8;PL2ejAoKoe(*m#zYf9WKqv7Up!H-$0|jso+_ zp~&dL$(=#ZuY2y__;~Z4?%$B$%l|3L>@)4$a#sxFCdu$Znf+~1FlK;SpoaA)u*B6R z{(F(hr4V9VgZBD>@9F=bb^ zF_R9IwE&x+Bll`+NW4JgEU-kog!mfvuRg4`un#rJv|+gvLROVz)Y)sQ0uc`Y1^SSbI(U!=nT0s zP|DhxQn;9%I)yVuh(W$n*%`N56r1gyYIUZF6&C?1>yxyWmoW>F=}aqSZP_7LcF1(3 zmCALtsH~0Kbh55PHdvNT$;w1m5c7Dxlw2AWfscU0q$2G>z=> zV~YsYe0_w2r+*o{Q!G!|`eZQB@H!FZMja*{vL_r&-J~IGB65fuBKx_I<~gfQmbh-J zog+~9jurPlhf!9O!2Vo2-(vbeWjJ`<-qj@9MZ2Z4W$Q!e9eHHkVAo?Kh=he`vyf2( zN+8~7A!CO6I(mQh>#L7nOw%cyo6^%wIl}dc)JKuR#PTJMg#n!Fq!0zq%@#A3_afnp| zzx*bXNsb;Za`NQK@TP<~59M+>u=$&wK1VXy#@4M@ENaxf7WJNAe#_-DM~@a?mTPcF zd#Em>N=@#VqCKYu{HnH~QPQZ5_5|yrh9t3PoJh*0-m*Mm3nI24YDgL-jfNp<>=}oh zQ-LLN%oZd@dx(}a+^j=+&$zNY_Kwpw+Jk0`!1}miNX~k>x4ycz%@T-~^8zdwlGD4# zsij=nmibKUO`Yx~`}nwF_c-@>#O?Ny#zUh$P|~=?kj$lAqQJ?~9&X(|&W$^#h^JgG z**V3;9X;sgCWa;w%z4*)wxsctEqHY2S&kZWe7F?jgxQO3o`3FxV~-<^d4$~&mX>OnTGPr_;wG2B$0p3!!Ml|VP!a8p&rcTdwZ+P>oJ-_Sxc#A^w|mF$?GT9#0~ z(4dU}Ea>mQmRhYA49s+Ob#r)jAvjic)?v@gIGJ^6Y)xRel07ryjC5@Ywn^1pQn-|& z8W9u;JKENB-eCMl=N62rWY65VQpUC`Wo)XhvZzP39<_d9oP1IzRd?AlH%>;R)w-Hw zPkEd>54!S3=nrKpCf>FlUZsT|pu2o$j?)NxY{7XyhE6^zDv!UA&_z}p;WQg83{Zn}0~ zL)WeWk_X;E?b0*UE}f*ABkNlgS7|?RCGGpKp?&{0DwmyLVfbNho$LKV=9nA)7DQC; z?8N7@K!pe{9e63UDVG><=HGR0`_2LOp8N{t<W)yYzGa@3q0KNLN{ggC|ao=-8h;Rq3Jf;TrFW7f&? z)cjldKk-3&(izpi1;&ee(XDD@~5$M+&<4f?mX&MT?3(6Xze8=25uvT z`_7aiWh0idF^;2HPfsmN74##EiT$3@1W?6IRd7>rpn|X>2s=r!@H9^D6kA3vc|pIW zw}1E;#Oe&6uCsrAj4yP@5mpCUDT14-5T!voij3_*#o)%h_et-6)Vu5?ic>ye369vW z&&g_CU0o!T$=Ch3nLj?X+_Rv!cOzT3Ug6!VwwL@o2=VeEnM~5v)g6xehFGQLw~gN3 zjbZs+VR+ly-o_i=@CNGj`gu-{ulNJm4@CEKWW$F|h}8t&rZz0UAztWU%<<#LxcAJ3N*iQW`RenQ+c%d-d=IEWY#~h{XAKci?lpQ;D5L**u)+h^ODn&pLIk92Va{9MrjuPziq}j>8Z)T}*2aFuY++t0VC|@2Y~~O5!*9`N#IAG8FY@SH=UC>b z>B_Ite^4kBaGqvkW%nv`vnUT)}(|1y5}yV3LO>GC2+V!*n*j<5up z_ulRl234S#%6gL~C}^S=!*Iq38KX z>XIOrwiS8roW2q^zd>inJ8q-pK7aPo~ zKc8}PbO?)1Vd0!o%S4A25V8QWroJB~E%t8tFvxa8iI$Tn<};ygw{Kw#;ACfUa?=UVM2HYC2BBhh<>OWJ zE$r{#)}oLN2UJ6>w#H#21$ zQzu~wdIty2vplXCk~wd?PVZVaUBJ%R7?Kn|TjZxAV0q_l#rKC~ptAk>!2#Z!b$GKO ziCTj90PU9GQA_amw%~qCaNHxZ-(?GCfN$k>HZ8dazm=WfGc;(k1bucV7<0>9S=}2< zS~?b^h}v{UM;Z$(B4IttV}OCdEdc1IK-k)%?N$n2F6-?OAzltxn!swwgS9omkVn*J zXT1ErHTrpV@X|WI)ylG~tBZPPJNvGBGY@RMj2|jKfU_yxfG22*tJ()FW zvU7_EW3zJ(MomHtG977*s${4tl|^yVyS4}zHHoR|WXq1SK5kR5jha-Jn3}GR6K!q} zG)Y;v7-Y%<*fBw_=8y?3j4vwm^=%HF3NA7{;I%g%umpcvko#I}H?> z^r4)?kRiFwklbep{-%Xs_;jJjuVm7USz<+(-<6z6-)eW++CT6I=36Z;U&?RLLNG{k zl4G{!@Vh5RIO*g#>EyUHouN}$WG5YRlMZ=Z$Epg&MFNNP!+h*Xi6JF}Z&C#8I^E=5 z5g3}AWnFik+!+Vjy=O&S5woBO*{ekkn1gjXHLxAUo*<*2PtiEdN1cn2*W> zJhH?>-k6oxoq|Zq=g;V8$xbe|nFd7$7oIGhXLW3M3bH31OrYZB(0;$`lYGAX3Cv!d zL^=~(hu>!SbmBeOae=X5@xiuVpi|E?>*Uac#c3zYdfjA$_uV*?Ih;wgfBKCXc6+@|Ff#K=>3{M{5ll5B^IU9#SN+Li!**dzT713tEDnLxrEG|w*(V;ovxfid`Ln|r+8+`wsAwUrck76iC|sL z)Ty=`U=*1*B)1zy$fP-J2~K1kHkmron59^F!W*Cv2rrLT zy>CM|m8G#9n#IYTMp*5nGn)}s8+yJwP}ll!vS*OS0t16@Trt0sl|G;v;`NQ}jDw{K z%r#0dX?iCB03ZNKL_t*LnwxRRKMzv26-Gr;IC_xG+BCnP5b(qVBchD03F2>iGw(ce z5^?qve;>aRd#+Als)&^oWY#t75~C(DYLblbmPOUFe9X(7^>bsBdXO<|w&|FFQI$c) ztWlHXTqhu9v#!dY9b7X&w(L-tD=LMpN5onl0h_Hl7s zZfVD)se!6*D8$~KrN zSe=5g(~*Y7^#?gHkds+miEHS#*+ufSgYq*w+xYc&LaxXIk|wGT@JU$c9ZYj zv}oCQ7#b;uErdR;l`5Yk6Jw-dBKG?{yrg(jdadoA1OOKET|_ z2npa%e+NL)2E_8p;pfjABT8sH)6B#Ll&!Ew%tnPxT+dT=awKoO6a9$R?2mK`hCH%$ z@Y;cZob|J6{cT#e&u`SJNdr0$2g`@%)c4s+z8Z70WG-+1#^bt)F)tZ9Ey41d3VxvF7~}R)Tb^9-u~0m3 z676%rxI}XEPbhk|abFGEK+mgQ-xGc$4vipRHi~js_H$(`mSC+RgIw7tuo3vzyw2BO z*NWM$unqAtJP-VP=(o#MAG!NQJrhEN2=RKVN6yjJ)fLtcD-^F7F&h$EAufi2D8C~g zHY7v5(r8sqy<8;iYpF8qD-_WT$+RU%EVF)1)*)#~PG!4`LhlYZ+*-X)Uyr^P%7FXHCRy_k^wOb1UaKDDX*3@XHwoGLXrnDI1a}fxGfL`)t8f zp}0t0{J16P%j^92oI?dQH~)!3ky%4}M65v1Z#<8bb+RXLa+9Ppmm{psfS?t&Qqf9d z4rxpy?F7Q=Xc^>4B0LMWl>nd63Q5@zD;1gb%>m4;bg+_Qky^IDe;dOmpW-i1&IZd0 z=Zcse%7!>A9ZaE zQ%!5OE0Wc>AvWq#<-aDC0v1&MV0J+ft@&h=umu?GQpC*I%)wy4fTZ<~k*hhuAbVlH zNTz+UU9nx4VS%_v+rpt+%(6@Ex|Ezv3Y%^{ z?-8@hvu-zceTv)96#1gQc#=>nS=qEM_FZRcDCKLlWx4BZS3~T+6{z9fWZ@3qO_SiQ zqFBQQUAsp}?!QU>(I7dp3s3}I3`m-a9M$wZu9M@&HJ{`m?`no-rIM+8hzg6Su!!p> zrNlZ6Dfwz^f5cbWo^S#SWS_8YC3t<@JM(eAH*-5oKr)>nCM?WewarH-ck}%wi$LlQ?7d7q4})8vlV8`6)$4XlmpG*z{)SEza_ z?908}<3`W*OjvH)5FtXmp6lU|ms^R5zx-cz*P@x#;TIob^;KBmq=FDDqp|&BNm{=Q zzt)77YY7%iovno;3E;$%!Mmg(Ng9%}w;h0HNL-JYjC(|Cd`Q_GFK2rkF=SwI9I*ru zD^0|ZG<>_`oFZmpg99py))tFMSsyh+1~$j-rcUqk=*$~~l1E$K`<10WotZR`Sb}*&a(B)ln%CKt zbNKItA`5w)A6SA;?{nzpCPmf`2{yId<5r?pp^6-uL0BEgp?Rb+kHcxwt;DRYA&2Hy zOg$W0XNFj9u#(OCrN4h0SDr4BIs9FI(4~mi?3~lggmoo3kC^qB70wpPtW7hxp_wat z!;?iaYtmR#_we(PvrMe(MXuez_Vi^OKYk3ODj9j~U_h=G=870K8K_)yWrs|sB2s)( z)@)Omvqn`i*gc@Ejy?Ng>MEPoY||MO-Z9HXrGQH44AmqCN}+4TT2wiqeep$yzP`v(Jho|p`Y1kOav$1`7(sWK5%zJsH>z~8gcsa#vo3LmT z*0Q8*t6FsMngPZR9VGL{bU?^Dxj~vtpPxrsqkZ?=0hjraQJRWapPa4Z=Ld*g9|Asv z(@4`)&Bll_M}jgPt%GbMy8^;42E63}#AhXzu!sqZx32jVg(r%EwX{#PE?b5-Z|0US z{SCi$?fHF^+@vCA%O0Wqm%_%rZ2x)NeZMgrypDOqsWB&mJlVKz^465eTTVOd?NIH7 zIVa1UljBeHJU^@*01nfg&QOs<08A}IvUdm@=R_9gL=JsZo`G$H6ekMEY4x3_do$?C zJdT^gadV`T8HzErZr3Hd$v?9RYT$I`)a_lXZnb_qk2t-U@D+BFE-Q-BBf0DH7)plR z;Mnd7Z0eL%h1rgwXytM2HYe>xeL?dgbC}BW6QFHpImMKZi3c!y#5$LwhMn z+q!(|;EX?z`dXIZ<1K0mC$FkzX9+A=Fr zU0DYgoqIiUdJGuN>-<#C;myF)rq1y~k#|7IO4T)}UT4diPjai)BB%p{~ z-CU2b+ZU;20g8p=-eAZ1>t4+ce1HG7;l!8_s}7l-X1(%@={IuM^fX^RafYw1AHb-{ z;4jmi#&9K;CK&V-Jz42Mgg`k9keyc~OTJCViYqnk@a$9M7Zxz5Dr6rTL%-}AthnHJ z-}zzQIem`9asfGcmdw1D73<~7T5-YHxr0HDtWlK|=8NS0*R$%inbZSf*RBbym{2yw z4M{%kk+Ka*KA|rnWkXz?ZQ`&!yfX0qti$_6opn&uf86asLXlEX8e~a{1*97(=~lX7 zLAtx7ySqUN>F$vA!a{4qd1~vfZlm zT4^`Ys%hnp*HEv~lB+iRYTaeFu!$5Ezum#h!@2Jka@1#zpK>_;{KDyEQJMLLfv}^q z&iPHan_1=aE6$!n$9SjaK|hHVK|O++xLlt7?UG`P(VK%Mo(sDa-yV-|ZD6e$%71M5P%)NdkSe0)bWN>PY^^ z3aq;N!Oke zzxeHl2Dz3>B>U?DT>1*t*czH@*tt&Mv|5gZ8;Sj;(^A-`=76)mPT@CTG_HN7uV8Gy z)Q&#c9@4x8`Pf3pX40&l+qWz9GJ@5S#P=}wyf1&+6-xXQn)U+|vvmj8R}Yn z)P(Lhjarpwc3se^kHRH_f_~msYG{oE@x- zG;NoS1^&;HoK?$w_g^rh$GYXXUT5NGf^t!hOZ!D8{#nkk;USD2NT+kV*A4)3DqS*k zJrlEPh$un_NI=`2Z~f=z1VOla!mN!;P_H-ooNVCVn3}e5;s&XVjBYAYSX+UF#qdw; z?YM9Gd0*hMd5dqwf72!Bf&3wLXp!ne;`K4PS8;v!BC!hr-^%h(ph*j4v^7!6lM8-; zyJLX<*-Xq*n0*^(@r!u(_4iu9c$xE)EJ~f7W&zUh=5CbR8#^CBaRkR2*ADYW04@2R zYxi9ZiV|GCD(+ih5u4QkzcqSR>Ug8Mhb$M*>zw4FqA`BfMk&h1;m#xr@;$a2pND8v zCpq^y@zU$fI(YZ3T)JN^S~bgUT%J2MB&1liEceJ|9Z%um7ALdc)Xx|Ep7E4RQx9ti zT^vqvG=^4VXyAZ-DV1K)o&TZ=Lb!XfGeP|&Mr&u-AIA^BSnGnI`gaYdI_zZJw89xu zg<=c_r|&{ryOA`KaSKLMOJ(L4`!NefO;k*m)q}!7JUp6I5cJxDm%>E$0PsLW8M+`d zoK9uQ2WO(TymE0u8jaP6c{EZ>VGQrT;^R=<-pY7_jkI3ujz>K2yCYmrhXa!Ql;(P@ zq-a)HQrD5<)na>-R5b%ry(y+8qs)0YmXTHJ8s9g$Sdd9eR2Ab#gTr}@1v_7*_>g&Y z{>Da;gG;+-{T+frKG@kdu}$Gq(&AtXRxsC+m;v43&wNSe-fgQ)uY;SCcw;pkSvk`j z8l-=Cjn{_fei zk%^hv5@&Nvl%K&8Yff(-7N0vBRqvzv*Zks*gozyAq{kH)6e3fa()zDPAzW|i)lgy5 zN4JI_=<4wtn+`NnVOfFh?D7$G<{nVYTcRh(t#tH5@9Ry~AM=qKTV4|H>uaVP1W<+% z*~Dz6lxd?V4knXw+7Dg74&O@;wP1Dk19gt_Xwqr3eQH$DNqzn)_m0C)YNFD3@P)x$ zY|jMTZ9Sv0VGKUXV9lr&rP%5GuI>}QnWuJLebX%#;J2c)ob-44qZyh~dG{inji6u3 z=f4c9@Hz~F+1{`Ba@3OEs*=o zhzOk3&PXF;o4?v5hgMD-3_aV{X=Km{Fj@ar6Ot$18Sm`L|*r-^~|E0WYEG;RyPQes{XwcK~apE2h+nr#a?jqX@w%HX+> z9cQuxs;&VC1e7TsFIykzTxda_DjO&7@*f^S7V&P@RwtuCvn)uv|A!w}`&s0Y>t-Kn7F!FnzV!SZQq-VlH{G!ux*gU`}nUoTwVIY|@ifZRs_QDaEln{$(1rWjF$5CoAeT};^3Cqw^Gh$L(%JXh9V2K{O`?snhu;m+BP$)uy`U|g!Q3gIEw)skO zYYnEvjVts~j3$*KDrE$12E%gx#{Y^xBG#-H@e(WN@~Tk6VkD{-%{0y6Lw6(W_HibSL~PX}?PaIbhI(ZE+XaC3u?*CYdBP@>$kxUxONJh_vI7xL5Axs{VZ9 zOqb0d>u=iff-Pg$W$<493ekE8E%L|pU%3Ni$Tjt?_ws#gTMMo~z~;K%&Qj>VW7dm5 zx~nwC!%U%(&is6}yX5l)CNm6-&waePk;c$DSHxV1SG>CaL8xNdr|88iq`(;KVv_B;&QWI~aG4~G|$NiD`w7WOaU!geJo>D``P@iKMo@6;c!V_HH#X5qmk(BHV-3>2W%CgcdE;)=XKdVY6`#45WiEy{T+t zie;)&G>a^{UNOe3QrAI+11qN=IzM_Dfh--D#XMiv9lH2!Zhg+0`()_=&Tz5Ma5?{; zCoDY&mX=l2sB_pBMp#+6GcaM3nD&`szs_bf%twwcPdCc6HvCS->~Xki`{*R_xvn%D zTT9}7?GNDK{qts?8qSv8d9}*ywn~R9WL(*N%x#x5h0}UMmt5%5lrdkBHsY)gS=HTH zy(FKI42Ux7|C`Fom7)4@Qlicv9|cjcYYrFHK7B^|>O8+aQbnM*|{X;SDQ#~g#df(x)usn0F)$Vtb=lL2zq3yg495$ciuv=7+ zoYxgp)?NIPoA?>;>B1~_Fanf}QR|AP!I3a#gTcB$pjjIrOT<0FZ%vPGl{5QxAi}qX zE?Sl-@^%&TZ-jCSm@cH;o8F8+4E;BwcL3)B0nf`aK^qez6D-pQ%u zeeQ#M<%Wv6qc7U2!7zU}0`H6OK`IT+R5C<~t)jzx4Ri@94d~+S1w<{9K|z|%l;d?6 z9Zw8x%=?^{57%0L%``nT=z2f+1O&VS7yn%!H`F$QOJ@YN;r)Hg{U8x-=yqeFsm#Et z4)ssfVL@6$SOZv|CO+57F2urfyojsP6VucuurUc*rC@UBbkR2WT@R7bY33fPF(FdEY=>WLk#kI4BQRD?b?n2my=iC ziGV&U;Uzp@l=Jxd&T5osMA{21Y@`p4c%$ZXxPE$W$=z}oqsj6AOnM1f{_+( zm-`r6iyw&}4bFXFr0bB^dP!sYedFvtv=DZa$>Hi-uxg+UcfD~5tHneD$q zYyXSt*4^mwsr&qJwzkMLQJHuGQOR84*7xtgsAw4*CViFZLQ*~Y_h9upx{?UFCgwJ(=m z8BFF$;t7(Z6RCA$@y>sq`IXSNv@)rO|CNd0XQ*idk@M*8=dAOP=IO+q5{03mFyCiJ z^SLngzpi2_IQ`9W{mCtEbN ziSjH-IkpW__j0w=mv_d=0it?-=ao58fb@ss)b$1tsl|a#uHnO8zN4?3qjxovR+v0=@b~<= zkEaTVREpgi<6<>?dO1{kH3FM(me&7HrILpCt|B??f#>*SqqZenf!X_4l~bhs#dUAL ztBvI+y(1o}(op1VCwoRI|9YBNZF1_hXyF=W>=+YcI+%PSTl_*msv>W z@LL!(YNK#ii$@Oy2C><8z0s9w>;@^+Fhl%Yn*wFl)oBOoTht*6ZJyeN_o#yp%5nc1ruRR&M+1`Cd+Nxa zFbInHKWEqIyc-WGcRsvQ zrnlP+GQxrr~Qez~>(d|H$ zr!}#-h(Q@9x)kFWA^RIMNrUL%hg*$>x=!zn9L|?K3M+6ft2v0=c2=YZT7C5%Y*xBO za_|uT7z1*XSXrM|54zGw?igx*H160k+VrcqX?#2;p8hp-=YP=AFHMvNmQ3ZniNJFc zhiz{LZ4qZ_nm99xavq)&tsQG5XCpk@NmHs$x|(?U6@!2)_gUPxVDMfg%3-=BOkC97 zxpv@DKNXM!4bYV39(2D@nYL}Fxck1go!SS46qkTeVo*5`LAkN9wK8UaxgT(#&-2~= zlqopcJ~TZvXPKadV5+gQ3Jof{*yLo5fVsEuNrNWa5)3tS3hFjr@zKoD(tfNuq%*x~ zgow}8?;jN<4KnjYP_qd?9}WDYa@N-G6_5GCm!OR6ej;@9X0_Qhv_e*AjdNl&{UF)( z?@O?ogG9nCtvNpd{GU@v7(xhI--h|8;}m`R;y~&7!%H$ZcX!^>=nB@yX84k@e@y=V z6}<&+-TSp*R4DMk<}}rbQl}s{*L&j!+e;>Sd{jEJ6CQLsV>R_~udkiE(Y4{`o*hVx zM7Rrth4Qz{_$wvONeQ3CbwBS@m?V#`H!0XMIz-U2Da55a_&G7b`ACGkn8VM*Eq30$ z;^#jj%m^R)t?F1R+=`l4T1WE*os6!f>9jO#KB00xFWsUTl5XdC@r9x@YrZ-yA^|5Q z-4VEjM}+mrqa7uzW!p5qzKe1uGPWG?xTT-}v0&Yt-P4}!J3!CSVr6qz-7rdD`PF{4 z0$1pg_jh5v@}gHt;&Sj$2@U)Q^Lc`p5U~)XL+|~~7Um54|78IjPXq%Fuk1X}XYl+| zR7G$(>6Uw9a72gn-2gr1M8G?vCQ%yd5)r6cU6*G@p!~i*c>BT4^1Q+>zsn*yo1!4` z)wz=fk(dBZqbT#~>$478pF)40lA)-ooHxf4#A<#z-p|HqqM9^Wm@%)TihKr-XDB+DtLcBjoG+bnwap{Cnp0|Sgl%P>Squ26P zDH6b}s(_b$ML5+s8`jB5Rm6 zUd8O*e={X6*z(bPQ?E1agXcc3mIfJPO`MaN==-vfgE^|OkYkbK@@zJ(ixnG`_S0S7 z==Qt|$P~bAp0;oB`mWaB7i)HSoi3}EoBrkmTBNiOPZL)i9Fj!@;q;v@a>GFZmLZ2l zpyR_9%33g%-H3~I+RVyWK8c?E`atI7bWJZY9JxE)1+*i7ZpE-!3)Z#Izf;tY{dz`SMC+xQ_WNk zeic{0G4fmfgbtUB>I%vWWiU#`o8(M$3iZf4Js=`I3;~CHBad^^8d&@hEg7lqry;{4 zm}CGS0BTC$e@?M0Vq2XF9ha%^Bl_-`P5j_@sdd)_RMANDNQ5xrxZ{FRN2$#(TBikF ztS-hn*AN|ftfUD`;o7{|TI8ZC3}{eZl2a-f7*!1XPMye9HWRZzekP`t>#1V96ndne zIt>XpMpvS>0i+0A+OS*;;SdX~{1iMEP&l71^u(di_4jw+qR~d-AzBjm+-98)(kmX3#X7_=`|GE~#Sp?F% zlT7l~iq}XpNJ*n73?1S|I76WGSwxIZUjjd@R5xv1MaJ%4L2$??rtogY$whH-sk^1Y zilSxXoGACK%3-x9ik>y+!^A%kThbNUjt`}J72=QDD`p@q;R$J_7r`x!_J$@Y$RUHd zo|z=YN;MzmVC-&H=Ge+wTw7P~V>rG7>CWn+ZiV@L#-aYSKyT?RUJ7Y*HFJ53G?-Y) zYJ5$EkdKZ)2Evj=HJ=uq3L}((+zu33*Ne+5g;|8P>e$W+sr4L<+nLyNv${ro^Jx4G|gLuP1muMsk>zU=iDVs^BM%Z$6qC3&QneSm&c&ktNi`O06F>;;Nb zlvZEf;A>MRxz5m0Zz_~8a?DENQli4eS;1sGSD8Gz@7|MGdv70cF7ZdpveSHB? zD1FQ=HZv7SO{J%}_fP)uxW^owvu+PJ_+3376MP)}G%S>J@R~~||K_Gr#qW#~cTU7s zUi)WEXX0BSyY(-n$!G=UMDsk!?@i;fVS-{!gBt`Cl4DHGT3n%e&P*ml{*BhE5UhR* zX>rofoZcDt_>(u9wPG|peXwbk=(1LSW^jA_`B07_kJ9V%C4s*Q)#ZVUMMsfH^JXMV zks8iq&sKd*keDE2p2IkLv)1hrq7I+(Vfb?v6=JDS42a`;S&pd26xmrrQPaE{5gzM# zSqg=T-#!-isXYhdW@zc5F(|%T`6xqP%_NmzWfvC|=PVGGaEv_4&sf>7*W7c|7n%NQ z8xnGeos3)8&LQ~uOXrob4+%~UsQmS9>MH2d`Np5rlt`bJu>K0qe{Vnc)M=mHav@7Z z3*xPO2x=^V+Uu>7j>%*$Jw9b+f%B%!oKKcMdOnNH+)eDf7)i?GIhug;Wv_%hx_`z7 z2fG((bE@y{j$04$Wcc8v>&)VmLg{{-L==gZJGsqFzvp>9i`Ro8wG{Jxb}osNya>?= zXdbhmv+xI@i{cQ2tIg34RJ(Z@%n$Vc(XG{jLU%}3W;>An=&`bE_C(N4UaK(2SBfj& zY6OcYDH4NmJ{?dSq8YAi{^<01B`8Er_$j8*Em+~BqoAcE##*SK{68E=4NSf*KzZP> z(Mv+58Z3B;sYa1OGVd%tDoSBnv6BP@s(Y8ppOQm7w6~9UCv$mI`-jeJ>^(9_Cenq# z%ig+8(Qt3>C4W3m9VixKon8*lM+4H672FtQ7Sq`EG@aDyE3NI@^D1eiykZ~eEEr|- zBjonfR~}k{tdm{WUMq#}h%@Q`U}qxfQKTx1)f*H8*&{z@I=y{%qx54|&tYr_aYo8@ zi0(S)#rYI3$J-tQ<&8^DHwu$&@BWy21M~l6)}N-G0xIR(n{CrUZoR*@QoyeNaQJuV zbe=plLVt&U?PW&2p_HpI`pirBFR`h%-5k$m-ZZPwd4&jHz2knvgzi3mutIIi0!y?= zw=~84b!mV*SzF!$0z*OR1-9xcwiI{#V}iLtbF0JA#~?0ovHqWNFKmIv`toLAjv%Zy+|4V~8SeE#e7q0Ke>=7^>D`A* zn8nF{sGZ5>tBzj5Z{gx6-kZcyg)Q9fmv*HIZ7Z`fg!cc-#$5da>AjvS~TfC0lfj;54YRlISpnltvxK zhT19rqo8K2zriZvl_L5u7FB$aK$l}Gn}HG&jyh^cmidapfUd;wD;47<3N9gWr$)Bg zqbo_C_2;B1<`Oc~=7$Z?u$j|v0CmW3HZILA5K_Hl=0}od#)-+X$MS>H)V`|wsRx={ zN~C8eB3++SrNM7M-_=;LABE!v<&{;1i?wZ=!RJ@;FUGnDg5NQdvbX%WwW<=rJ8Y@H z^9reC2I7<94w2WFmS_*2YJ?jWPNQBT*XzL@WMqH{bon*D*ii&9^6T`HW^(o~fQlDI zs$)5x;Pi7WT6A6jVF`Y4sby3kj#G=kYeF_grBX=cm0;4^jXFa^ps&~OoBnvW5Wp!~ z&9q8x0!@Zsm<5TsLJNc4H3*vRe|1$-tU2FnNLQXa3_bnyUZ1cUe>Gf% zNQNbmqvd5m6ghOpLl@PszB6JwvO~b;y@6n#YGy9}#A8gAyJkHe5d?6suE|r~>8-@wo_8dw zEuBY`RUBPke~4V;k*RyWG%RC#`G>Z5wf-iRES&OXEl&N5Lg4zCj-VD(Ga9H}Ib!P1 zmf4>=dU0aapr4PdDy=w|!}ffOd}GZ$Y^wCal`{RY!!sL z-10U_iGI#}>Z8&h&POx2^tseL??26N>UJ5e;qlowNl1(+d6pTdbm`|=xGTHy57*VR z(y`xSx0OX9a@}#62^eMgg^bKAJIaPYVZBq614|u;-g@CB_uDtI?GH=*yXu(FzfMg zo-wSl?R`%?Ud_t&VUV%lE=xFt8Q%pKT_*<>K1L`z6&Hp;0~$piZzu=lZ4i@NX0qeQ zW5uVx<|}BEf$^PDX539x!gKdjmP;PxZcetyjdz}NS@~1@r(|c;QP79C-dbgSna!GS z7Ai{tfb^fC^$8B3u=BrDBh)O7VAf@fm!;`$ZFo2Ph`DxSenUjjGozkVGIN04_~smRos$%SSNxumkP=hD9z(7X-|HRhBVH^GM_2Vkl|7 zYdhj1LmnlLYcG}QpyoC?z#xqCVWTQA{Xt+u5%iR?(37x`4V=BewR>dIIvxD824x`u z_B#&@Pd7HGBw7hHS?cgeZ9bszJc=ENW+kpXcj_O9P2__+NkK}CxfLb!jd!` zqvgnAj#HxpR48)0?td1|Y>O}>gjh8lpmrpd@NShzTm1+#Cn+U?G+Hqf6rk!}I0Ykx zVtmtybD23jDuzn_&|peSTQLk3;&K^;#@=@=Yy`V{Ppk^9WsaS;>ilquFy+Y@Y|fe} z7D@LJg4J4I*hdEW9jc&Yk_H(=j#B0rW5GSa(DE_ZIQ}E8#o^x?Y!GLhqJWWF#wgMU4wsyP~D{LEjEbx zn@*(q6cqFu(4^1m;5Lw%ui?qS9X-DhPd(}WxaVx@rn>dseJifZLa$AXH*?33etA;$ zL-u^MHal=g*+_W?DT_S8_Kaf-mvs2~pM($_X|D`UqDZig!jBV%v;?ZHqY}$}Lf>)T zfCT}49Mk?sWY~}#saEnj@#>y|(+#1j%cnny2|B-XbF4<=%aCLm=OOwZxmx@tOJ;x3 zPk4369GzOLV!;c%ZgRhVNzI8BC`Oc6xgzQ07gD7#q?*@d>4r^bfC~~4VNi-iO?Qeve^LT07M*}E6VEu9oLbDsl`q3@_ra}jBn_#}Dn6iTM6ltt*zJL^hQBSKh9s|#$q zFdO;s_nH?x9`J;Vb8x>k<-Fc=~Jc zaj{|b-+$1D67~e^N^KI*l$hP9c^oauu=#El=`mxzlCk5~Rh41Wwv)Z5F2ZDS!#0Ml zrw&W6?cOkP8=6=<^0o-x>uv(WiQv+BD(9lgL;_eiltVg|-O|FxBhI{P?skliGKy8m znOW{mD_VtRQQznwl4p=pE(kde{jVta>GBHCu-_w$2!S7?5 zl0~6BR2Nt?eo-w!?oKl}AKKt#>`qu|L&c|mT<}thx=XOpZlkd(-2U{C;FqeGv9;-0 zpxrZe;hai|;?$sY?2Mpt_0bM&lRhut$+91>R-5iGeVLZ|hokn_+yW^suvN67fg}ey ztx=tDe3qXv^uxXVV5hyEPvpk$-7L!ey|rnBLzoa)je9CDfP>HJC{G{2Q}{MSr29K! z>?c7Td-~KUqWij~0s4>skVSRcy6%%H8}iCGpD(fO(Xo)61_8Cbn(dk~ysWV^tVCNw zkIaUV>wA6s0jJ)N)Eb08;pQ=nin`#B1|I>m<@O)4s))Wh?`9%^-@O@FtV2~zTSQZ& zFB&g6T4)-3LupYi*rV9mqa+i9fQmu*uA=1gd127+c%0AlW{Ift2Zt{J`68Ux_3?(f zvk;v(oAc_hn6V?_kXS|~b^BE~>Ad%fQ?A5Wq{UiR{XaybYp_DU!s=opv)9hDr@>-bSI<~B z2@AKgCmZg{`7(+5W1nBo!8?*g+XzzP2fNYTcklTsnNh_>G)et@!xl_IjE%BtEQ)5% zEoWGL>x@fY2|;pIHm2Gau%hmEJt}h3V4(>1;?I4y@BiZF%R9nZpkFO-K&rtN-$%ds zHi@?Q>-m)2vdD_QY($akakz|jP0PXdX~HKvxoPdJJy2dVm&AiX1YkV6J>Dc>6pA~c zS96F?EZAHfU{t~tZcbyP8W3Y9@*A&OL=hEeb9DKfUm~^1 zpG8j}zF|f?cFcD#g%&>2tO+lQ)1<-2aBsi>Er4l8qxFpnw;;7s~exgnApDYH2F1#A40qb7Anfg4gF~0vOcu@25U_JP0|8##$ z_=xIf5`w57NGezRO)+~ymDyTQ>y$`eA#l;Qx#=)R`!DQqZ0F|ld)^K7pBugr*to-l zq5(Xcv3i){)3>yrkMe>WVZ2-G2r40mh-FO!YQf7TK00??L#xbE9u}kPu-0y_Aa}w~ z2UZ}1hHaAiZBqG6O>#6qx}&^%8PoN+()P2M5+@VUT-jo28q} zXzoZ1aA1cOsWe&MHBV3gmRY^{R~VD4*xq&k_+3oZNM31@LkMA9FUL{sN|r<8NDTi4 zN0$YLl(+IJtrj(m(r>_m>b+?F) zd8reCacYpIY=m%=F$t)^U52CU+TO2bJ)-ZPW=EJ4FkM343H`jhS{^N%qP~w7dP_`{ zceEE#9PbI;04n=zAu{Eb)?G?sWx*3N;-zAgDzFCjYpY;p3Gcz&HOSBo9_iIe4c#c1 zV+BbaEtl0q;2+S$em^A#JDmt}I^T@u#5v#xxzQ|W&>_pr8Z_6e7h{b zqxYH5rIML**w#z$^a1dn(7KS|i^4Ijk9C5#Ytf(WuRDB#`lf^2H>EI5BEi2PPwsxV%Ul-YuP2Ag>U!}RHU;kiM4tK5%co*g>=+tms` z%+||8nnj)IqEN2?%dYFq>*i6v!g3CJT=nY2l;aMg*Ie0+>8Uj5GbgRt6Y<3WBDQb2 zI5Acl-~Cte?S<}i7tzNcrC1W(WzyEwzxbL-P!vj6FfSuXs_0M7wq?uZo7`W70_8u(R1NHzI|{YB6GRajqM}A&BNz%@)q?w;A6QnBmhQE z!)v4$gKm-yO?W5p-)lExVtXI&Oy+%iNFs1gkYmCsID5VE8_cac-t-gA1l$GAYR1)v zsb-IG&MP_rPvJ_w^rTY}<1jhA64Hc1SomUxJF* zw8oLBtz1S87H^TQbay>W{wAm9uKY^4ie;fHY8AcNOH7irpo16%dBQ9;5zZ*%gfw1j zu7I3_jj#UjGKjWeOuuQz|3dXCyc4eJM;qks<|Mp}-v)=XP`MDr2_dPTW4+jU`l)%W z%A~nNhfA74{;&UPFPPL>vc)Bl>x|E{PeZFgMeL+4yP8=)mLFYRH}N;pBmgRG$!FvJ zXog!*E~ak#VXG+6rc-vE-E(T6yI2atbAfaIDR3 zw4;7#p|v1fN^;_ZDu+O<1-5O`*Rx=x^CyxMpqV6-#L z*s&;t^nK+kB#uGFYJ7(KrH`LRti;(gsvUNjfMXo{0bi}F?OV!&^VP=7AWu&l6h^Cw z?@Kt{=@Wb-`Deh7iD0g<;B|ajW%GC} zLc>r9dRR(RPB7emcB|!cM7sTX`?`HroeP}uOIi>nt-9a&rd^9Pe96`i;63*IFFqcDC^%~ zMX~zERizB#|p}KmaXDdGP`IN74mh!n(vCp^Wt%oQ)3SiWkMOOJvF17d1Gpg_uoF z^%qAo)_a*8LLAb)dNKW(_D8FGtyQ!u7v6}~S1mMMyfn9L$P7VZHDX_@3mJv+k*Pde z8p5A>UU*NbZ9Is5w>;Hf-`)6wL_9lA#a{uM^5}mn_2&g(wEnkP`+om>77uy1x_tFP zmsSm5lhx#t`(AF6c8p_l`2S}?F)cz$$|+BFRWo=TXoll3?d1Mcz^^UnHy6iZ%}0qW zM^VmZHPFMUBg4tgnjLBflDb$ST9xXP>hxyZ09uxIuE_v44ilM4uI!Or9npCe$+^*7^oJ(<$G}d8q;}NQh`^NrC$76_b&W}@c(nNAgoo1k* zESbI89xL`umnp-_#iTloYbFcTzE`|h4HHz(*nSzWv0&6(iV_%t;PuO>eoe2BRm>N& zvw}wZepi3|GutU^vck&lyHAWYhUlt{U0+FQuC2B`r8a>=PfCD&8K4?f51NVlb~ol& ztwQvGG5B3-^S#zultQJsBv78DJP9-<#TCd~N*fuhQk7^lP$$DA7S)65t1#Y+VlLg? z)uw?%1Z09vY7$L_hXU!N2t320 zlEUZG-h3!(3hREB5noB#SK+CF#sPj-6+Q7?g$(`6Oc>fx<4|}WE2Wa{QoUAIbZ`(u7Sl!23bmANl&Bi^M#(&H3`Dj=Ua2RL^ zWQ-F;@Diz8Iu42~aK@q+{xsRd$`&UKLml$|3HD*5dI!z^KRoTMv5YZ74_L$ojYr~#?obGv2PX6vE4Cqi|pRNa=ooD(H75PAg$|cMh77zK+bx! z>#uZa-kPl=*EV&cI0HL+?)=>Gs}`NptW=3cT6ZDm;7-98y(&IrBOStTB#AuME^mOn zK+xmaVNZufOrJg%<*srbg5M%q=iBFJY;2C>;2%{*4t&3d33QH5*m)iTU@Q&}ZdkqW zZ`!S2O|G@}`m@(QnV7hWd+=RU5xhJ$bNz?KciivjRWi4$9Xqs;KEl>4Q*TVYahm?V z*?yV4CZqV3h_l7a-Fj%_v(WMi?-!Bhv1;Q3TH}M#mEb^9Sy%m3<-@8zT*BZ+^z+o| z#}7O$A`$N4nyl*r56HU2k)`wBVcWxs%pN8~l4iC_+Hb0LZ-x^Hc{WKEq8+^s_Jpy# z4`~OQp{=o^UAw^K2`8OCR>IK_H%O;J10da|=VNHs2Uqh*~jPy{*UBbINo?5rk1x`J({U>#pc6HZTy|mx4 z8CNnKQ%AbOsCQZKUMv$yT@O(mOW@%5mGCeu^r~=ak6^~;HhC2Ok*>tAU9$DBxyz_b_O2Isu%)` zg~02Sj^Ll(d=E6xz_2Sz-aTIQ0M^lFPv{1RMpkxY-jg-W6{Eb_61#eV=48rs$iE1X z+jhGYZ#5G{%XZKs!-7cCbLMBPm0K|2iWlX5u|Ws;7~3{1H_lz#sR62s`nA@g*TD3G zV36DV&sYGYsYJN|_%t~Ia(%=FjKQE-DRb&bb6nphOZ3{(MG;s%W>QgdEuJCgZCQq> zyD{r+d9=$G2~N;fjcD7^6J7AXUB}WtepMC5pLNE+7aXexwX7UhIt&=};RGS}_T+JA4$i&{Fu&kMrrf3ZGFxJ=D*f|u_x{7(zC#MJ zlee@W@FPeiEU-)i>8aa4+hdd^s1lP7o-jb(m)0*tZs4Z27Es$5+hHIPa$?43UPkLo zZxHBaIMFn*t(R4hX5r%M_n(hPSOTV@?^O~UUN2nz_)BoeT_=Yi6Bh9V&j#iTihrOx z#I1391p)u~KzNATz#wL;#Td>3zsiqob6oX$6G={#$i1fNXAFa^=dE>QRk`IoS|GeJ zc%4_0iDRsj9D45YDt&|Y(&&vrypxV}8t?Vp1=fy9rn5o(xO6L{eHfQ*V=opV5tR*v z#%}<+`6%`5C;D=XIdcSzZ=s705U9VCvfm}S7SiciDjn5u*+HO#->iCGn+P(We4UaW zKtY-?D3YBo6aBy(u>q_3Sw&axjE%G=cAjwP|1%b6ds=_(siar>aumxg6UA29%}E`1 zt$gg&S~-+c{bb}TamWSdf@~;2kzys8F`Jc|=%`{FOUjx}qe4q_HZ*wKgPW~hqVaiV z5q-|=Do4@0@3^!JqR@fMw3+0=SK4>bW-%qz-Y*s9S2H!HzDAv62wbj^jo=2!;jtjq zzNx9*?yBZ@LX}mYJABr|hY^6x)-)^ARogY&f9b8IC2jRAQEmJ;v_!49x8J+%OZnTPQ>I@ zGvR}U$MjQskDJuEeLAx;{eA*~(hUb9jKH&h!+QdkT#M!RR{ z2e}s=)8Phk%+y)TO#H{$T{(nUpawAzYBL(qiW@1quNb`aQgrKR@ffuFHZ}2F;wtDj zDwp9;y@He~C1bc)_x>GPdl0l+#K=w{&HPc!v`A@UU&#mS(E*_wGx36B#8;KAMEM`r?6=ssQClGHu>s#t4qg z$Lj7iX+pN#cn8t~3L>L345PDQ?9#SV)7A(7&m&er9l9aAyIFsL1X8?7IbsHbSt)`I z0i#F4JIk@=OZTuUUfW@uJ&k16umr17L2dMGy1iMQa!YQsqj?aH^Xd3+X&y6L6zA$I z?~~Izh0hxtuRM%XJ?BAM4pj>%v2P+O9*Ghm{uSjuX-}r%fR-JhondTSE(>$I>rS*G zw?KX1y|#DmF8oaW!3{ku&&e38$0F_k&>=s?9j4hYtLZSzQ)X;i;cDEY0FG}A}BjsuR^6L-v+RlVbrdBpS+3pW6MR<-;CkS;rR({ zv-)qd_PfjgmgKZr`w-3Y*4o6M1a?fVkgp#t(YtCJflSQ4ocHG2-m>T?+Hn3K%e@V( z4$?|3#ZmqhF=dkeC~(Bn=OJO~v_7@^tUNxpZ_;yHqkIt=nOg;OQbWlJM5?PlDR?a} zF=<9Uqs}+TCppG9sKq9O)C25w%4A4bW08O`91W&%x@q(>%4nZwi~?h&tvFr-cris| z!=ny;?*1n1H1gZ`7h}6hSyJZeUYzge#ijXJ#v$`#R;;NLG=wevkRveDw7z1qy52OM z7g*HOIPN343EDyplU;&xeK%jj7q~_aAJ`NkatN=Vmg%rm=JkX%PG|emBc;J_gWmz;=<=Jd|5U z^mehDdhh%qQ1)sozFNxx%PJ_ZhR$ctuZR*Ol!a;%CoE^A?s+ASdM?JHahyHIZP25w z_8TX#MdUKTD~-{M<)HYj@VvHC7>`On(E+6U78#nfHkGu-wQ}?eRe~4jw#gdeaU_V7 z5p82kABXz|R)hJo9B#F8Y`&h$sq7kwwq15e8$LB*iDCst@2kHLiNezW@0H#^*hu26 z*y((ss+*vw@{>QR_FZrX=Gq=iV@S;qpGtZMcP)L(Ix<>s`wHw6CYt^7Zy9ZJ7XH$I zEGqne{2=?sn6xCVi(SxQb|{({(~QmQ3l7XXA|TQ1}zVyj<_8xK1Y`E z*aTvcGOTNmF}pT-=m4bQUphX!>;w+;xc?h+17r(8-w;Vx9*r8suZk0a3~_e(*h~wg zZ{z{v3O?ZQI)B$7BrZ88tix^jQk2z27z;U#UdMCQryz`v=QSDE4rCRxR8 z%g#FBd7C=2_m4`?{7+4SU*h&&@`b=IHu_I%h&dB1o+#y*IQnQ zbc+~5n@;i88?f@yKV=Cyl~Oi?d3FD(7A`S-yZVxZ#^bL(aPB|uOcTg<(zN|jdP3;) z3qVdeOvt~)Z*$_>rzw~QJcPurY+U;!+O8e;KDs5^W^yl-XiGKSfwy`IHh(PLv-7!mR z^Y571NB)&B_+g2n4lVACG1Ef)zx*En;y@k03q!JgWReI3D%=HAXUZ0|N%;3aTIOg1 z9{%|<@vO_uf2?!*A2Tdlg4h0N88I@66NNh>@SAyu3&8(2B(^O$G9VfG1&6)wb};Ue zn4>z`I-EV2f&ZVqHxF;)y6?R|SO{=ABqeGaK@@FAkRnsEO$K8}al9zYO&43dPTS<# zX`41_Z~?bBN&VXH)84ct>9>8m#BQ40cp0v8I#^o z6m(=tphO)m072mXaRv*u*iPcumOS6*!2@9S<;J$p z+Mal*v4cpdKsFd+sJZUlsK zvy$YT)WmCp&Ov*}%owRgoj*32mqf}1;vz~m5F%NS+}qFrW!OHQ0Uw&MRT(1X0{u;0 zI+v|$XKaOxYQo8(KnI6?A=0xM`omoeHM}-*Pu9CHcxu|8zun>G;XLQdT)G zA6g~5(zVq5X3C%hL?Q*sXfo)&dpo$qB`JK=c%1*dw}ZzVabA__O1shnsIp1Omp$V= zSxg`olGRdl>T)~%w;~Hkb~S9p2@CFCaR{eLmzB2srToUs6YOf(%E0U(cdr`f4mpO^ zVK6u`#$O-Z!?!!XjX9^VPJRq)nSt%Dn>;45mKj8f1@4;sS47xh`{9f(sD2m{9r%3E zcQQwOZIo>%bC`3Ac&8>}%~?gHsAZK-vmiOCEtQ=nL1I#}J)0pL4C!gjf_y&DdYNU} z{$+glsjm|bhXEh+HwMUVD6z=4_^*E*ezX~WbeVoiuKEczwQLEPgZnOr`>ukk{|i3$ z7x*a=qD&K1$=5Kj=FbNS;$!8tyIJYl88@N_aL(ES

    hbOaAV}w=h;&Jl3(e%x-@= zL&`9iy;B#fhbl5ejL`fWvNE^wKXe}1P!?l_ zg`7%|na~!t|Y=sMYt5+;<<%g*Wx z*zx4Onz(Io6}632y@J)HCgNF#_V+%_ye%lZIbWONQA*o#W-t@$hXB=r~l={@a}J%eqNXL zDyA-gjX}6+LMv(?3sI|}7vK>$Y21h{_;7Czv+*cj0z^7PLsD|{UP1gLQEW#L>rtdX zmEnpWMYux7+Jf>a*EHY=eCfr3`d~atAZ6fpmkrv2azauV9-(xG5$WCCn*hAgb{@`o zBu`3GtwvQTyXwG`q;nY(N>-Jy2_;F+NX$a*Sx8JTe%{lQ8Jv(HzQheK7u>wE6_R#Z zV%O!NHRtuVoS?vVbGlYY*@{{=nRov;8YJcJxHEsGO*sg<>jhJI<(we0N%L9(#; z_);z@o1V>(&SyvzB#C*6-B8>Axl(U*cWHjZ-d5L<}uS>m)k_Qb{jxkakMwSw% z&8v{Iav_QE+o#PJftvEs2-Q@ziQ|&59Q!J(!YPb!idBs%C~Gw>J~WBCM%Q!K`R)QA zHBxr6riuli3{IoKc0cusTF}Z_b51eXG=QAZ=U_Jp>?TpQMNTa>aGC`2WP+RL4l~#= zz)dS}#H!nmwcKELV5?q#^g6_2&4~7F?I0>j*sAs%_~U;>vxG%zs@XDp>~CPY1wJ+i zED)qjfGV#{h+3Z6H~jek7ykJGVQNa+Wv1eSq@>MMSSt-uD-G^yy?)Von@W*dWw0}L zd9^%Ss| zlZbh}pUk>6a(Qy`KBGyHASP|ib}pcq&ILWcDJf}oKY6r3y9oFkLD0S4K3fkaeaY{# zWf>Bp);4<6^T2U<=sO0#(^u;QRooK@+e+wNk`iqH%1EN4~IB9)PZsYYZH?!J$3pXq7d24~Gy7Ni=isbj-F8Rl=8a(0% zJ`hoiOof>Lt1(*oa^xMsFSixw{*j>Q2(r)XeRplkvD;K+ZNW@`7e&h;dpN|ziUQwl zfIZs{M%ESx_T>O5IRb_{XfU-sYB?Liw=IXyosWC0zHA7;OW6AQa$0d4(Tas&-T7AB z47~hq9?mtSpU)5}7H}FDKcC5I$pQ0felk1H`1nDchtH?;!B+Cd`hdRq97ByA)m*d5 z8Lf=X20|pJC4I9w`rEsz|L-_ChV80r6D}!RA!z}29@lwh?FOM$t#eZ6e{C{|EEKBy zwi>l{a->wyxn&y-5_zdf+pvKTxMNnUYMp>!aAu7D<}R$TUd~)lSYbVH+d>YrtcZuB z+K#!bxHs5=6A%>dThF^Vy#-*P(fdBKbZ^|KE4L>er;Rb1f4S z6W%lKLX}O%N_PMtd^WJd%IUiA~`I>=&D*3B{NQf~eW zo^}l;%Cu4=W5e#Jl22CsXe&#*o~_#1R-U*6{au*TiaQRC@zH4qHDgjJMi9*o*-!{` zTJZ-hEj;S?b7*=R`FsL3ZK9^#oU|>qd*%qi;Mf>X6|N*33Q;IT_@V!8TJdTu?vvb9 z{2o78`wT~0j$#%Rk%a<7tsPbOkCD-uGBy;__gzh!y1z3YA$n0Y+6>+0&hc$EK& zM>$$In)&K4JmxBB0XC;IbR{M2rb1c< zPsO9ix^;!ASe=xJ*kYAP-VvIxJq5G2;9xv@M$-0+#{^BLqN8p->)#B%(FNaXhu%$! z2ge1Q6-=cJCgM@@w&2T4pzUT!`Y&th)=Po^VGDL&rm%ibZ*R+oB>O)iX-Y~)f^gXb zg1LBvIS3j&rwgJo3JwfbGX*~|Iu;haNaN~>M#N!i4d z#LO#h-})ZDR17jceh{;uNGORVjHtW6-@VncstmCR#Rh%q!9p8De?G?%-Cg_uUD=Kw)rkT{){TXLbGi zrPbpYB84GRdRpBw_#nPEiqU3av}s~@*EOrrYS{%e0b3zx=isV6?*9rYTOnx6K#?}P znE+*cKfacBS20^5T`TI@2KRsNzO8(-z0Bxe4G?sn)s~y|HLzO*t5<&(05xkazRs%* zc3p50y^lVk&ttlFPR2^BI;}F@oK{>X?jjnEbK~lp^f|9PotU&+YWL1miqz8D{ge}R z%GjCMqWwiLjMKBJw>mBJe45PjX-39|tJl?NvygeMd{xET`3PzxvRslx%sUvf79;Cj zQg#l_um*H_Grp3-cq*kY;BmBXuxk$>p0N>6+q5Pmjiw@RDkgy0l)k2AQ&j_*zL$_= zHXKu2Fg(IXugX9P?1JDAuFdfH?bPn01q|rUx3K?6mux>pexGhx4dIq7{YteBLY5KP8Shf~lz~P96@CxxazSl9Ksjtwc)K z(iSPOaM++}LzZb*0WxzqL`$T=UN>+#n+XH2kXF_DU@jXX>nc^3nu^VXV>Ctz z$e|AAvLT*#=QTzOMBRB)Zthv-2y&<7uI=7AiZB(*U8WwzYzSd0)((yliWHc3)u^+M zVAc_wtlL(TsTlw59L=WUe_mW*<%R-Rb|^mer%~FsUzc^NPMguBxWZ20|p~v}Lg4 zlA$|Kj1q5+G8ESPNvjO^hB~V1*uG+pdqW-gfWhf8`dhjf3Uy!>72D=>SYd;qh7Qsy zL*IOk>sq@>7c%tC<*F*$^mL|5*aD>IGGzTBtOkQ^#T?0^B-LP?GiuqNrr(jz=Lv@! zPaD<#dU$tL&etQb&JRpvLyS6tRgnTKA_Ycl!LFeWzUH=jHkyhjY{95omw$gqzc;== z)bVqxWkD0N_Tz$~AH2FbsJpv2d#Mx7f>V{Ur$YJ?D4)5AJUbO5rQx$~E3>ejT@72Y zS`AtQ4v}(!zPTKBSa98%ZvJcGpQ_7th5K=u1>2@|-dOx_+ssamH5_HC@liJL0Lc@Q z{$*V_VZl&K2N#x~<=WzI_O4;#9;8~7?Jq`pI=epsl)%kzV>~j z4`pzg1lv@OK9%F%)((c+I!H`vYh-gq@x|Y|h-WVlXeDd`ZCkvcf8X^%c%T;^h{2Wj zyVDndIeg4hj?4nE@TO;&`P%{f_-K9WF2dAu%r>G)y9clTApmQy+Rd7)cQI!RK68s! zS2;p(tJ=xs)6?woZzZ}mPGUl`{kaS~doM>EJ<4rQJdR};+%)Z!d5{1AAOJ~3K~(=e zcFf$)-4`9IDp_}CMs*(9IJ7#ZXzOaU^{$1R0 zYz(JK=crXPnox~i7(Z)yP;(}^X`L(9Xip&;PcIiDXp;$SM`0p-4xz>@s?h{L6dEFg zf``d1?bFQV0vP!eTnH*?qUKEqKw+t?mYsJmXb{A>jX0!jm|K&QfSydj76g6Zk16c} zR2g{kB001hO~sroXxk|mD(Lr^&j;fN1)m;K*pq_3i*kJShh4O}q--;qs>i*@OQ=~@ z2hoIVBe2w+-*FOt|IebYd$nw(4dS&wJe*Hhv0~+E>cUg=)K)l;%JTKxhc{Tk!)p;< zp4nFq^@`cxE4ky!%c>GA*s|rystuXRUp%6Na#OJp$&c(P zleS>;6vfC=Q<1X;Cv0(=bwsQNDFm4%0cf_`O0VRqs)oJr*ZNVE{ zGW6+qlv!Ia?pkntalPV-RSI*1;_90uhm(?7TW~ZU<>)j#@mCpQn-unwg0QIwn~MEq zuoHsB2PDq0;M0E)r8Ob>rm1lLFbW^8DfEJ-qU;DtFQT3aCL{qfxM)9TwGmu>k3#8E${ud)PZOwr^TMw8#dkYTI~wlvr7jn3LFLZH;U-8w}5mkP5gtVJiw;H+QU6mpj%DibaH}9n`;L zMWqQ(YgeCN7_|ihc9i!fB=1Q|%D^`)gRfZz3uxQpdfaWje9yJ@ zRpT{LuDwA23q$&~64EGHXPD>a2PH|*LhtGG%dU#Dtd}!)6Y9*uXrlu)_j#PLV#E(c76;*o^|w zP*c+~B{Ao51yL(7HFG)Nv ztCq#`m_GKw;1O1lT6E15&r9&bF5k7N8Iu7_`lkm-tW<04i^oNFqty&yUnYzEeJS*#&m`PZnog~OUvha z!ZJt%C7HNl)tfTh_yu^R2mWBC;?XkL-xXL-8ML_00}bx>i@-@>v-@AT_q>H#?(Z^M z?90=5YFR4wm?yj!vWM3tPHm^OwY61qd2ZQq<)UT0HjRf@yPsScNZ{esMex)o-kQ$v<2w7}Nn7x}-k$2dV(AQ%w!n!;nX(1< z*UdW>?WSVfqH1^C>2~19Eray?Gg!L~?B@i^7Ch41L)%&GwWjOH(OFxtG9mdk;6EZL zuZ8ZDaMdCBD>vY9AR+0$0N$IBn4<#Q7F_UIgA2-F_9(9Yki@hF_D7>6ep~Y87I-uS zANWtfV~y}+I#ad!nuV_pecsTd* zwYUDtX{79_utTD1R}7k{bwWCDTAenpFy|HVwkU~dNpf1^goK{IpyyjH298Ut+J1qV zSHwjWJ1DAl!xanT>b`@5^ob01Q_XT1w3V^5Ah2E1wzs_pb3qZCS0wY2SXhxnlJXmx zm_?FU(7|kiVEPq_qE_#keuYz3*uL}sxjwc3QK>)9w;)MnV3>#V6Qho(jOSppsn`@# zRpspYipoGS5Uev?zp%Lr`!C=z>vXJEFh9n=K-G&I*q?Q;AKRW^eh_8r}DO{^}@`)SZman1Z zm=)FR0^D!Httq%G3AcXIonA)MZwpldw){r}RdwX@KN`UA2GAO)5wiiH_fH16@=pe; zxo3eYDQnKCs*^sVK()SIGGVIhoh$mR{@XD9#6V+U^9$q~JU+n|%RJ5-@R7Uc9`3XIoZ$Tq3 z@8-*gtSzdfY^SMM6;s5L5+`NQWhx%C4B#MdN=Wutx(=D!A7N6q6Oy`PywZG0!JGv}%b@7SAMMXBSzK%yv#EeMh`l6Y&hs<;KPnv5!eYX=1QAu%g;4%#N8YE5h|==qfod34ab zvz8SJva3K+HHL6Mx3x)SMP08EjMt5@U@%uaz=}VvBKg@GbZCiNlfV6z;=_Kzhm}Rn59a> zCMS<@XY=A*!)o3{&BrjBEuyV))V$6~tI9Dlr8I`m&21cV)v$mH$B=Ca&1%kpT454> zJdWy!A=f40e&7U%DI2=9BAapd;)OvxXESFDj>MysfDR-pOvO~npa>K!1I!G5Q^8qM zCp+cSua#9az;$l^<&~0Pn?A%X%N4&l79}0aU{4Cdx~W76XvI~-Qf)F3LfafS10C-F zR7W43o3_2mg?OBZhgSmLV47DS!Pm-xcq-c0!vkNlE%wxe z9?mD|MpT*g5EoNNdImId=hJyvB(Y?z`RJ2c!y-idN}+p#i2UF_Gx!Jp9366u5JE3uaTsBDHMgoxQTNful%@mVw_^6fJKwxQBBe?|kEW_MXzd zGz+Rmrk(|{d9}!X7$AKjgVk(cHS1@?YB5O8OVTQ%6|oJ1-sPG^F-zKln37hxCgvq( zK?j@dpkVmu2=R8kPCB2_k-;+92$E$+ zSyoy(3k=VX5D!MNdUzu;Tw+vU)1XhYIV#B~mMj*HnkWU9Hzu z2XRf$n%FJ7s;XOn{?Z`H;?1mI_Mt`h$8Oe&+vJ2Keqj{5MIf4On1SR`N$vL#)mER&izRx3<0 zD@=@*6uceS4Qh>vT4Ta50Y`zy-HW{%L{{&kE1jVTOaaqWF9#*}nlG4&mf?}A6VRgT zP!>9c#Mv+d-8TFN@MtHrCnVNa4eS$w7E7_*%-}=2GW+X36?JT|?$ZqTj)DD@N6c3G zkKX&*gNK)nQ=gZ!5w%`h$ipw9>{ZH}hgT25*J|N7lZw`R37xy}a&CG!UppR^K&Y2@ z^B02$EQ3y4G46J_FN&#Z$K0_DR@;ihb)E6vgyhoX2oI+W{{7DkqCb2SA$c)dwzSjy zd;i2rQ}Kg%lpn{V96O~Gf2EuI^_U|#W{WBT3$VmgT$GeLS8ZKfYswZ}n2=Qx)_zuy zyi(#E5ZDI=5BB!3q)r`czCrP2+kkf|rd$AoY zgTU(H5st;96l_r)Y%u=ugUoz8N-(BqOiKK48iDJ=t|(>e(Yxf#cIdWW5D!Kn2#I+KMYPhjL6Df2 zq?(QDwtAa-FpG)=QsC!Vxq7Y6gGn1NDsq@cCfE$FP-_{ z;yUicYBjLKg5kp>i|Vlc!XU|GlHN#dxxXLpDzo;ML4v>=ZW$m%)u4g^@bH}j0Q}co{rG?zzmwv!W0HHe zybZfa(CxmbQ{T|U<<^B=#HLkM;aX9=Qik!BcVkTI>Gv$Xhw&LV53ftkS}P2a$0S?J zwOq6nSSt;Z6SBIjJf2`zqeE)BA~7McPO(HbmRS1wuUp)9QS)^w?4}f|Y@$jrjDUsV z)AwJ7lBkf03?=EA?nQ;_);XC1zb0=9f%GMz3}UHW+x7^sj#{!_;oc(Ps5?M*c~TMv zBoHzcftb?ye{BKgPxt;Y%ZeBZ8ld|ibRUHqJ_k#XJmExH7LybmK@*y;pLGwbweAp` z-QR6)ISH2_;Dxv9;v?-$O?hz<4<3Hren@@H(X&7H@QZwBdw6vb_{c{-GT`_7$!4?M zci(-lse`MGVAnQd?bV=&C$&D89`ZKUt&0*4hZ!Dzn0!9(T@(-J1v)#|vToga4jjlZ zF)`s?kY7|ikPR{J)B+AyBqbtJV05U1tSva~2-cX2li83CruaZa3S@>lP}vZpu;i9TiMD0zYs`LxD)N zK*3a~NP&Dd#7XyjmzUw>ngZY5T;Q>p5RZS+ppXsm|FkLkuE^m$CCKJNoaiiY?8A~L zLonkAa+bmVe=vBm5gzz%2lM|+(%P3}&Jh%|A!dgX%8 zs4g2>C{+LNe0~%sEXW2zWCObVCuSr*V5qUSPGVMK78On%QJct1w$Em8f`V;@9Cyr& zk!=X+e0%{xGA}VvmgjDH{YjeDJwX8aM~M_EcM28!J|<^ahD}I1kHqd$nKiN+X}oFY1p>O`RYd zZUkW6y7koo^_6K}%-zFJQ?}aL+Q{egUb%UNam_W?ux8B~N~O|kQ!#rccq-a+uTfS% zdfy|`J)BSI?%o8zo;~+_7vmK`m#OWG?@Jl{OFT-asd!gH@=Q!H1H3sYc`#-0pk;8_ z796%~IBDZZFk(Akc_$n>@i!g%v2n+ z1;=f{`h+CsDry0qwG56sdR_&o`wgu7_4>!%^-eg8JL?@W#RW;pihmbae-Z@?T1~}C zcRT41W}po5o1?rjox#osF3y2%8N}BMHl#C5{gH%tlxbV=OS=W;rHb8A1yRM=6^iHH zrf7a#a5x^N(NxUY0&}Cn-m6L3rAbZ9&bhY61xFB_c{5W?k!gOA4pSkJG$^3)D-=X{gC+5Xw|mZ4hd4isQynM%V5qcdJWfp*v%PxD$IGU(ukE*HQ(!* z-~fiyjka(O;2Ztw?wgng2bFw%~~M?v#3bs zsE2tH*c0g1WMd@OuW?Nj6m}N!WAN2~t%g`UGpuSI1Kkt?9n{;D=JwTPM%dUYb;opAziM<7w$f7{`H}|u;*&)+J1rUuMH3) z2%=;&JgqH=D>>24qQdkm(kCWu0b$QZ)tZc;s#@^zkH)>AsQEp-7KOtmOuB)-5-)Nkqe7txPmqY@FH1 zhv$o)5N;?BJn~D-z(fU$xX*$Ed*#hTF2Ddzy;hVn+ z{X)_m0kQ`FJ6UOTAR7JJ0Ghx4zq(MEUoX0L3&!Wgp!&(#s1GeqLfg1OXXoW?*#cbs zeb&BDGT{iFYql4A7Cz z5Hi)GX&yYBE2xmN?Er~CQlE_Pv z1x>0tVS&|jdSK2D2vT*{!zP+Qt&p-#P}>&T4LZ1O2Ly?{tP-qdQIT|sS+lG#(ZTMR zYfbF90dag_`V@9qRp%|*r%&%EUCLnl1(ugv_GRspRBXoD+S*>xzDalYCT{@b>kN)9 zxZE8m^_xiEmz4ZXI>TkA;t^Z0*;M>-JoIRqhP(DjWNJ=zPofea7jF~LEFD3LlQeINHoD+C$DF3aqsEn z(=Twsg3DWfn8kiBe0uJ ze+KPFfzu=yA3vz=e5Y(S9MNjme;q%_)%oM3TaI$;hBvWg%ax?=`3$}#X$IOqKzjTO z#8*eL8wIf$UC-aydR^7}_txnh)q!Gmn;=$D*sJ1vBC`Z*nL+*CGG`ULf?L_qbRE4L zb$KwF>dMOuB#%i3muS+LW{VHau4hN+R*ZnfNNBjasPH)$vngb264hj)!X{$cMohRw z>?#xE=@iB@7Aj(*mYWa&b(yv}regNsGNEdn$(q;>ggfwL4rp}WXUZ~YO^&bt9Dj*} zQQF<@w3~_>#}zAtU|$rz_71S~g5GJjpO%GH3CXm3C?&U)i~-$f61GxQE4gP|fuB6) z^@}`s@bKE`lhns8>-#13%Xs$39!@PgI&FyOy!2`zc&-;9PeuFMLA^@W%O&gKd_%<| z#4Fpc4(_faH@i$lr>S_x?W8~WA{}#S3ocJcvX0=8Ef}#3WRH-2`A2X1{6 zGhcZl;UgEbF1Utpr?!gez3X9Cn2O!;D0|M3o3?@uQ;|v;WWH*UxLjhcQCL5LE7BP{ zOvOX-C^>iC6Sm+{m)u>KkR*RqQs@K+7_-3op-~MYd`dw069y+n1oqPcbDiRL2kfUH zj;pl&uw-=um|Y6{34s|^96Q5xN!?>`bgv=`jdTD2AOJ~3K~z2l5mShmqVSasbapmy z)K*Bh{#=sK#Bzm%J@wmzhjRt>q%5$Agf$C_CcGO;O4EJ%a95h)&B{107uGikSs_{zqUb679@61Xtiu!*3`Xj{#d73 zke=7uvi*X@g5FMVK$A7Y#Sv0|1KTI6YS|P9>0$;N!1U`NrB(LG*_R9Tqt`2KhDzV0 z5&(I*10fZgSFhjmI&K?T1~(=p-7YD6iK!^V&qc~sU_T;A{Ej63cNtP&FtGmV^!J6c zS72`x*n3~zwn44U?FETWg)w8DRViCtCU0TnUw9eWlE9cg^D@?qp)HRaV;FN5v7jQ^ zEMXSRuy&F7YVj)oT%W&_q5SO-275t3362C^b`ad zx6(hmi+FRCREw?)0S3b@)n$f`-%js}9_*md_2|3-CCOJ#`WS2+V3j|G9TLPlblsht zlkE8L3SbVdcnJ2r6&~7z&NI7!&Kz6$F5{z&|Dyx=(4=e#Xre~WR&tB_fvJbKvh0do z1l(y2?svuZxI*fF|C0lpXj)8+n{%pKzVCVDQ8H8a0`Qv)+qmuI4tm%1u=nH~;@DBH zo|t5?p})HBuE170ZzwS{zd+~I6i)^H#G3_1z+&U^U6`}ei=W>XfjO(NmclL3lo_rTu9c|X|g!H|7LFLx{;B_N;yhm6jM+JqoB!I z0At+J>}3TZkZ(+2JZX`6mrJTY53E6Z1?Sw`;RkWRX3aMxMc}9{n6Gmbs$Aoe+gEuh zM@1#;kyakg#|}m%_~`|RUVVHp zo#7cuh(|n2IZsl0&xOkV}S2TM#i7SzE9wrm78C zIbLG?pJ4sl4+3lG?%qsT&NBYx6Xf?BOifL(!c<(GkWAQuC*6QR&KCSzz16Qzt7R+m zDxXtvxl7u9{qus)e@Y+QQd2SMF5B)N+uJ`V8T*QX{j?y~srY0soLJD?IB5&ADTBk7 z0e_jn>{fic9X6yh98MYZ9RceegC~1?FxM-Ny8CW%t-yTuy@RojA7pAOO0%ixOlK&# z%Txj$$}(tl6zvJg3CkmMJe(Wo?%u?Pi7fX_OrCMR9THU%HdY~NTWgBi#Iz0&+jTi( z?FNCpB&yXv0f7}Xu-d7TwC228w0s5Tf_|2(3fDSV4F=|d!t^N;3v$u=PH?em&GPH# zFBLGb0CrWbBa*j`6`?NyV3K*Cu5=fk~7f5_1`zB`!g#0{x6py&_P{Fp| z9{x6+;c;8=s4ckrWvru}5kabKXj@}Ajhwaj3hcjr`7P2twd{*SgQ`p{9~Y>Xfcim+9Zxkl9Q4h zn=j`fc?3C=sGj#-;ySj@?;?@YmcmR*lE)?1MXvRf$q^EhlDow9sQK6;;`Of9>*0j{Z8V=*eeEZsJ)Pd+_jDglB*3;f2aZ zMP2Q2Ij;@^ANj~f2K;_M*=&~k?z`{2C{)@~Z1HFiuYmoc8eeVn_QtBDm6tHu!})~H z&b6#tx1IwBGE7WNco*a~fZo0w%OeG@?8|YHsd(BEOlCv0M+%JDg2#tCs>|M(&d?qy z@WfCDSx4}bx(@v13CTO|7z5y8%iu_z-SH|@vGvnWFf}!W^X*9{96|o6HEjNsW}4?a z>A1*G=lk|EVGEAdStu_z6~DZ56o6k3C`>~UX)5r&od!AQ%p^#5sDnvI@V#&8V_TPy zY<7=p($TqTPdI{iFE7yd-*Q-Y8*INh!-H$!@!1g1yXUJM!PCjWc?wWfMBpNMqe?f^UE$MA{5xRki!brh*%Sa6)?#9Le*_JKE2&- zz8rnN92N!%pX3hz828e_5FK72d4+=^6<421=Xc$@^|ZCM5e_&0RQ;67y2HZ{dl%OO z07gU)r~1;%Ja8&|B!u&bz`R7!_s$&7qk`;_&>5Fa^huI^lE|_G&iN4Um8Z& z>_jzc<)O$sr_Gllfoyg2eij@;3)$+t%+l@E-(4sBPg_?7O>*Hrz3rlnC^}?IA)J!H zDGH_vk5!k8&cx{pXCbm=10l?!BI^$k7g0T632+(&PJC{pa_8oI*LGuWysSzUG{^9!~eZm7~QX zrP&|oi|vCh(NEvW9NC5tPLsAeHs=(PVu5|_`!Ga}P~C7O%hp5B^2vFs^~uRVfYF{e z)82KVTSv5W({ua52ScKR@2l^jiYBUP(h(lg*ENu3D0e%D8$wJqKSn5^%g4yvFsft{ z@*QTw!u?niALC^BF`jL?kX)dTT`gPrjpI*n?es33)>cBLEGlGTFBRmP`t)UOf*PWW0V#{3*v&vLV4Ze*dwjg}-@8g>~L1*WggNN~NMM?BX zlD!gZ#NdYE5sun|ADtoJY|a+EHJ#z8E%>#7V)8J2x9)tF#S~xvCB@f2Wsta5VjmDZ zo;G;=fT*f#+f7ARQu357i2qF#J0oZ_72k;|oWF^p_6n3ONZA7Ul&IRfPOW;9Xum|J z45VfJU-sTUK8~xt|9$VSc2*BZlD&Q!uVuxFWyi5iV#VVS98wg@b0W2r^a3G;rc~Xf zEtK9Qy|=W#pDf+d+ZF=1Ep4?w87PI+n9)q~{_D0#3mpVw<&yE|ugW_ISxnRC9M^Z9%^o75S%W^&Umi90M!C}Q?> zYXjwmB;tzJ`U$^Ew*=MfBnksb)x&ERBu4#0&~r!wu{k+pi+K0hB#*d4p2ZPD{Eb z(n?JmoJoIe1q7|32DVO1;su9fP^T-ah-X5Oz@d{_?PI~WFn+a+QDCm+ak1>@S&D7k zxS8JG=lm1tql7QN#7-8;FY6=$^F>&88rMpasb79yb#<%#zW2|8j2JI^U466@;m%dW zZaLG4Qx(7DZ^V?zmUE3b<#F`Mg%!EQT(u^GMt2MGG6yR!Fv=u^z|0Bm3qA}hz#JAB z5s8@-BmxeJfKzl4rYF)wQ@#g4Ess#j!4BYr<2d02-P7%?$jvA_<2eU%>bdKL+SngX zAcF=Qcz_LeKZP_RUhlqWIgy9t$JEEfCn>6Ciz>(pVB((@iJE=7iK=b40V=0xQ8hH3 zWmKD8w5@R{THM{;iWewu1&X`7TXC1-8X!>IX&|_}I}H@K;#S;UZoYfY86$s^KN)W_ z_L4cDy%t*SR?@1_O^ zh9cIx&^efem$?@P*;SAZlllq{n=3^E-op(a zi<4ZM@?5%=z)zVGvK^s_lpS6cN->%Fg+t(B6d4(NfZ=J2u6-fqT6l`&5#5z`eEi`f zSJf4ofY1BAWx4&VZ0Du?N8PM%$5U_+4<#n zRT>}(0K>R;t2t0n#z9oPVclHHd`@BAUNSC)TKk_l zmK~W1tbkXko}>JF5W(Al`^C+I|*+6GuKU`CQtMI=Sr?>f5egC`XXHigVaffO5J_-5+`AAir5mP`#~!S{h3n z097VNRp{jVY$F1137ndK8E(>Ml&BDP{g5=+WL~Ra@L|{sV^WQ)`8=& z0gW9Zg8Fs2WmgpDusYo45@|Y)^Z}qF@3t!Qq!mg6XuQf(yR?gnV(CU@g1dk04~O}l zP-@3)$wdRuh2BQfN`l)&GXE^{xEdWed*b)1zNU*J)0@az3iiYue8-F*3HboGi=xJ~ z7hCl@;3bLharLg=)&R?j$;y&D$&o1f@7zGMxbwkLwx1%)G79fqb7g*rGFG2S(4$ae zi25^wgD2QMbk_B6&J%gIJIJl(AmvB_tQe}r9If23WJNMIB&_|Tz?W^{D5b+U)4wgK zGtx*33-nxNPT(v0v-kIiAkGrRM5yO?d4GDq6XS->J>F6rgKo`vQCV4}0I6zP9_z8{ z>i3MlBRx7@_;9d|AsD~Be+oRzj@@4{w#(?;;KE3wF&91JJ$(nzrmv=$LDx6`%5V~_ zLvYpt?>=_=zKAo4+$o?GYSyRMsf*6$D+89N!wd+D|BZ-($L{{V-vGIpbU zk?Jq3rOBY$woO`DZ`|7L(uc-POLN? zPGMQu9pC&r$NJQ@Q83IxwULfurMl+IQ)lm9!lM3bP${`(2@z)LChoy~d5Dse17cK1vF6DHHO0C$-qJKI{b2ydQGil?_5?uGSQV zLe36kDn~hrGQ`~i1ASq`7i{kLJ1thVlnGaxGzmRH1+ZmQZgB%xRZQ#N$9k1LCw z;BdGGosVt2@T>F_ehA`EmZDJ<2{Y~FGAAvp$FAgRb~( zN7&UyQg-IPw|}qZ80$JwLsqO-!U%?ktWJwxk6QM4rJbTqIQ5tyvi{Bax_v{V3h^Lf zksaN2`cfJ0WcvDfOxwY(96!*vwCb@>vc>@PV}y`qc~NcoT0Talg#;O0iO^6@OO7z< zb!q}v1td?aP{TvUNF|V1Xupq2o5NP5MFyP-ZxOMcGt~sf;BNn_d&SOZv>J_{&A>;%)k@2??tBmE zb#G4i@8TUGP53Ti_;rujuPobk>ii29{d~y~w*+{+w7fIM-%w`oug;nbA2z-O}_)-TvJ4#~+6K4nqfR zLdXUaVKfk!pwk)%=9A40u;Q9;)6yDcwwr!MvgbE}ZH)~7rDwpW-n#A+=sx0oQhpKD zF44zsw8}d0;?n3j2ttSS(@q(^jOH}gdTZfZ#8u$o?44WG*1zj9+Zqn*?hyiHp zE^?jsaw|t5UOE?-a~sQVAUipy1lk6a@$|@&HrC&YQdd3(T{I3h%j5!_;==-ALgT=A z_nTj)Nw3a#d3po6i-`^0Yt}EEJchG?t@!fM+$8!ucWnW>0pMnPn9|~@ojIu?&=HX1 zmthH_CYF~`5G5S?%)GS7_^^CG&%GjLpMAjIC!|z+9w%J4j~<6HhSeR2Cg&&cD5?A*7^_EF14pE% zAXk<@#s7*#OH2DQCNYh$>r)C@KIz4HIj>s4iRkCYBTzGjtVHaSif z(q|V|l~IV4U}s>0VwuJibNBzD$K*(jJQ4$%tyrX3$h4k4$m7E_+iXYX1A%kj!3DkO zsPUa8w2P`dVBCog`gAAo=1jVBYNl5$nxc?HL7IfN>wdQbG~>dDX>wI;Pr=F~YF4ix zV0OU&QLom6K?_X~FWh!V51N~w$BmJWmL6BS8wr{o7)g(4Z=XlUzslq)8bg1YIrh*@Ny^`?s<)2+?5IDVH;f`))n3;8y_f@+=C6kgW*vc~As zdLqX2g8;{(-1oXdgN&on)YcY-mer18YMQ*0@aH|mX<9mBKhLDnkjdRk-LJ%vF=}Wl zt~v$9;H0T%vhYZXp5DoEoSwcYmIyJ&Fb90hBjgudSV#>}73*KEY@ctBOT0Q>&9jlR z5>k>QwRO@}^if}qAyioYD#QCPD|eJ9+?Ic66>_>w-iJ!jy)VXt&pyfnZ)i($vNgJL zI=Y86<@iGM^oP!TiN+&gT#v1W+tq?wS0khW)^i4xN+oM9SV>QzCQigLJ1wUsDpV!c z2>H0p%qGjtbOz7TOAho_C+oP9%L{TAGl$J+PVrMuSBnRi$Y=zXEu~Eu$%?Y-^MHe- zcUb+8g|3&;<19ENOzBs0@p`>F^W9l$8X8j2vtRRP0wF)MOL}@h=MP7K2S2~_ty5f} z;h*s6{{jfh@&x)Z`WW)+Gcm=Se0JC|hC)jQ?O~N$)V-hO4ljs_k-bkZ*@} z5BIf1jx7?-wQpf*DaTAhDH7XY$CPEffc_UR9c}Y4@;0WzK^m+Q54lX87d6}(dV)I|*3D7W^;nxa+M2y_wmUdu6i@#Yz~ev~79 zm@RX;&R*qtsV(@E4Ex+U9DUybd%gw*cRY>kj&LxGfm99-@xI!_i7gP%zg;L&H0)cI z)`6YdwG*EhoC8Foh8dL_K4a(rprj37H`NCxDw?v3B*xw!#$PEBNh!_W0L;} z5)Kz03sKP#Gg5~@OsGFV*W9mf?otYFfF z3&SlIXJ~{Yr%f`dn6#EH2N90j8AYveq^yIU-E&Ej5*0 z^=Y7ewEnc(dXgGFGfzcFgWBF#Y`pLIGmT$uxFi8Rhrguuu!!KxLO)Pp<-hlsZm=Ub zpHNE{N;d-w(~@mEyj;sF6Z)#j*}C00`RclHgbe8HgIC(Z52_fRsu=nabk9>7hQQ6x zQxJUpTk}ueD|AZB{WqN!5{r3n-6GMb$lqg|qOFBQ&P``G+KF&kA zy#1D&aZ%@H*S(96>rWjp(`Alp6-1!-&V0_lFC9k+R`4HLscK!zE$m)1;5ANNa309apVf+ z_K6st3A4F*%L)aFf)xbuI)%T%&J7ttU`D<@T04AeULdLUL4_+e6=Mq^-O*zj)(CiL z#o5Ab;KaN>O^UMsnv-s=Qug@OIWD_XZ6-0AFgy&N&~H}S9w3E6TZDqLvIRzPfZ-p{ z&p0u)E*rc-<(oVMq*=V3h4fOx3qGp-W~tOakrH*ob|{v8CUKyp0%VmWcskwMZPF@V zZjK_eG~(6Pn=>0@OknkhxE7(yc=@+mREy^gujz*@1D>2ZJ_>~+w%9iMQYX*JQsI5~ z?+bS%JD5HD*aLERyV$cfk4x-JrT@nQh}ZbWM}ZT*B33TB&Z4>x@MWNvOli-m7#*8~ zlhI%0FI4lLsIC|k-cegwkcSfh*S-&DBL^$CUEQq87X%8|(P$m(W9!wz5cc({%L4=p z%E@o7T36*dRuB3usJ{^5xr7|@Q!*!_nFWtu%k8CrnoY$(ChU3*PMV%nEJ{v3=#cPF z8EL;2w~H}5DvRhU4_03FvY0@ua9@=8!?{b-eucu(^Ev$?;S}39jhuHmDYDATDCYkt zt@klQrmjB>n4>;Ua6Q~?^NfF40kUAKFl+H67>Qwy>I;b^*W`ptX1N9ft^q*F$iIb5 z+TYTEEy;bZ^xSFg{COT+R{-hWLfQ>go?jNb^wwXJ(JNkuUDMV1H#aIXSV>4*{Q447 zgd~!FuqDOu&c2#PB~4V4Z=4tq^}txm>v>>u8_<~#wZ@1AxK%IXJnEZGb1k)-wgrj# zj=kE?^7l7=)QdZmw(s+lhDh$RZBLNJv&8Um)DBzkS(t3Q`dC(v&oX6{3>PhFkSsLn z>)0dxys}=1$_s-V?B}SW#h{ZCUT7>R6&`3FWeWWQlOj+TPU5t4i%#%Kxc`-og}l8# zf0Ms1s!L#ghH&+`dWqZUe{Hgor#``6v^V>s z6pyyD;Q1Of3Q&+54j}qtxTrQZd|uE|Ul%U>vO>a0Db~07m_${(B<2|re5$}&Nvf<;kLx^BGdgJIrwlas=$%)xqQTB$p<^LMx9TxA#* z)b#w-sKR!DlRbVZs*GKVk@C|oc~lVm^K55X@zzm@=PAhYOUhWVYXD)7$RknWouB<8 zr!|PESom{%u1OLelIR}>2mxefda>eav^rh_A(GZ+dF|dakJ9I3N}a0=x{XE{r_p=I z%Y-<%8yD!L^v%Qyo?t7M}`JmyJ73YFbF+V@w-cOj|^#40lFqt}tPzo3Z0c z>5k;POrR(XEt7(>3^AMScp)8)R^kqor5KCQz1i4({@mkRs&H!a@P338%CEa>&p+Mm zwsxI{XtY9tfjaQWU>L(lSh5%|oZk;EBZ67sC7y#4_HH z7j`EK&AI4$>hll=D_A&K-9>kkfo&Rw{N%M z>l>}3f*@ITQx~<8>r`@y7eWx;d@HCpALPk#e(J3k0Q=@E2jAw&A?q)`6Hc`h#Naa|i0}XZn*z0E*UUPAx z`V>;3e$NTdNsBd|KqBw_u9GPiFx4{Z9OMa3_6nmj6!$@FXiuTcM$k$Z1iGE%p-QEjWS1=~dqli%5cU$FaWGGqqPN0TB3D_Yd#G5_I-$Ql zS&CMNaCp@+%s+K0b);nV@jJ!eejYoEVFFf;XR-1?B{VtJ!kD~oxZ#Ki&*SZNXe6M2 zOuKzd@+(qKH;9YV-cJ}82Tn}-PUr&sRbuBI#7GvKVCuEjjCxZ4{oRxV7^UXBk91#* z97NLVx&eynQrItQ)EK$EbFSRxzIXjmx9ujA>@Kx(%>YWgC} zvg{PZ@VqMq&%fdJaj(aG6f-xw1wxK@*28^15A^%Lnx-Uo&2;hj%!=W6~->;Pu^9-6d$^bA)g_j zv)ZAKN^}*6{(}3BRAT?8aVEbIt=E^rVte?Wm>dz`3>&m~mVy%6zVfCj@uRaz`~#C~ zIxqXxP^1}!Kx&Rkg2--3%k)kKH<51w4eKsqmQBbxtbz@{!(E*wnY0NT>*$=T*82Y3 z#BJy?Exy!O`vcMW_yliBsY4U{2neKq*h`A9s_RR3Tw-~Y%%zd)2dgRM!dnFdtdc#QGb0#D8k0!GoBf2b{kC?kqRfHDH0({un9^8lWr8(9(K0 z&GVW&tl@e41om%jvhirG=*OfX)-rwqn@NBb9|Hmp8g9uRCAx0{e6O27{&tzM=hD~`FZ?OGp!QIY=k?;_gn4rh?;s-vEh7M2hTaB_RKUmb6fp_x>6CDg z>K7AI#YZRby>twomO}4%V1)G#kW*TB=!(Os>6Q*6M3f4UP-bN|wV@R|OU`ta*FMy> z3IjSKL3{jxAvRp-8(rhS4M4d`f|glrJ(GI6vrJ9&bUZig ztJ{%ub`f|aSU$%O{-A|Sk=#N{i^OAoF=k5UAoG-zkh{-a9SWPGUU4Jc7Q?ozO%5LY{i!ZWBB4WgXTw0EtM3JD7v( z18Y)mN4NZPf~aQavB|*_E+KnDc$ul%b+P8q)5pn=_1M-|lLQ;I4M8T8oDPKe4ZtJ# zMoZoRuX&qRuP0{cIu)~Y_5hQB66=q&jE|Ft0t(t7v9^@-?>QQQ@lpLIGUi`kib6F( zotaA7`&vH@qA$B&o)13uK%G7<>iy(;n19nMPyG(bu<%_4qt7%F4pDsV#rG9!bs@l( zy7C1zqT}MA)&zg#_Q#{F9;Du?*vrK6cV$mkB9YF#?sNy+;91N;;y7CqRNwT_4kn~j z3Bf|@ykL^5$v%t`MT$Q~8+1>tPbLzd75^^i{sEY|dZ*DxmY@qRY4>bC#w7{T$&w*W zd_oE*0ZHQVa&nc?k^c-rk+N7O21q7Pc9s-*M`B53QXS*=|u7k-G*8 zUDD&m4oouoD|qp+a>{(J&Rlfo@ggr44)E{uplg$c(b0{2sQ6rk@#47yoVkMfmCnk7 zpO=I!2y+~rOndRxaJ)xhE78ZG{eNdmzEuYpW9+o#LW<{K{M-U1oN{4lXu%t{uI57-s( zq-Y=^;*nu?k#jlsu+{L@{#&Zq(j;f<+rM?zqu_C9^1Yfk?33#{-iZKdD~MHD7?jG5 z$e1d8pgiX5u@y3as4-cGbG@~be%Qb^2PCa7VNEULTL~dnYg>;0N}_?=D0`qE#K`Ii zu4Mw5k!HA1i~UQ^{BCR5_#@EfepU~Z3eK@(+)h;)8*j~I1j4ZR=@>E|PZKXdbuJ?d zyGfo<5OXQ(H}yLr-xwj*FRS_sA;cdC%jd)ZR>H%LY^NjWDDh$AyasfRJHAnajZzjq zXqR?!dPGs*@7kWZrQmoEH;OY@tyiwzDa`nSUy9E1e-oxZUR+j69(doH6u1~4FZK|A zU?h;!_AXq_J-jnS1UK-g`EAtKxNU84>Kq^1a8%{t@9a-DIHtoRT7?G$Q(cCQFw{4A zEM^TB$GR$8e+LW*3)|<*{-CQHq!t3Fem+=!QALSxxOzTVR3q%l#xGO>Ojb!*t8lq) zNi<(j<`b43}3cMBE_?Lo1dC4TrTxtvTv2U zEmsvWYuWqEjD*nT=k@za2w-%g!$*}IQ#jELAq`a; zH<*U?Q}~xHbtDjj}F-c`9qcGpVS`;P?l*PjT^xn@W#k5Pm>!F3Y%b^(tw8x zsHI;+)?lO=8#uU4B%6?APfXnA`bStSz_9wi?9DUEEz+w-XU92$R9Nlo$xIosQSjKR zu7>XVgo{=E`9;|Qp7b*f!RA!^j3XCa@ajr$@Fa~rR(4oq6#z-9>x~sOYbrlud|^3? zXXqmDyv!nGhFZ-}*Rz#k4yCC)dUX&ZymgS`l~b#}={I z+9@E3A-?Kg9N_<@hGDox{i22{^lBOaZp4GGj6do7In091UtmhaK^m0att?xv1x=x7 zWvVcbKEAHZ>I9uRwb(KdSrep(Br2=`4`8WVz$6;cR09+LK$vBl`V@&!5)8&v)nbf7 z6y(bHUMiV*W?o7Sdse>`F8ne_%0W7ip8H)nV8!B&`T6HRrze@jp7ZgsO!+D+|HcEM@$qtJZr#3gTu=zpEtYgJs%`I zbxg;3nEZ&kF<$Y6TjRymk3&mC9iP>h7GBmL^!EKb+L#(SEt}o%-~K=qtpQm0>R`B` zqP8C)w!AKAV(8wqDv=xXL~s40!0nU(%5;99bA|iRyi1CWh#NY#S(r3U zJg>m<$Bo7<$6cm7k3;48{+80hYw?d8v>6v~~qD&|2%+=?%<7>RS8`6=HSl_3(~ z9@OcVJJn0q*+9XB5AlW0vejsP*}Se_dVMh<#VE5V-w>Y`=YzIw$P>SI96sD#=6^X+~V4gUX)}jNW^E#PP#w>N-<+)B4T1@X8yp=m&^^F9JN0cZt<#f zZ%2>@`>8<2>ZpQh>z2!_Ss*U9eQC(B8qfTIP)jc!%&z@&dF|ZbXudfKuu)y zd`ea1J5H?^Gv@fua=ew|-yjk8R{Oc7h^{lE#}|i(@@sSd1ctHTs?(2u7{-X!PM9@K zc!3Rfa0K7i0YYOP*JhS_9ium;D0t>n)8y_v&6lTv;J^c}q%sp~1agvPCa4M#`6@Up zu}(=XYU(fJsbJQmrnZ$H| zxVTiG^AJyd-=>mP{@#JB=VVv{M4Zm0Yxl6D2L~}chAA%72pL2Ov2bys+=|gq!L(fW z$|x=@+kS5SfuS^iU}?Q|YxyG-yrh`%fRamyN4)CezW>wO8WBR11e4<&MfE-L=wsL} zVy;iAl)owR^YO|O_g_fwg${vOrucK1U(d6K>%B?gS9_y^FT`ATRx-fIP8~INVoALv zf)ERnHQ3(iH-@8@6L#$8mC53K?^k1yjYmn+^T)2cnY-%uA`M}5R=OqMfvATGoAp}P z_d=gH(S9vXIwk($=bYE^SBs!``bvhxbh_?_O@tjmC=nMQOk#2M)@GG=q=#pn1{#i7 z(RLpj8fl_g9c#{(`y+?(zxT#5y_Tgu3@6^q&%$TPA`|@Kas5#CA3@C{}SiUUT;8mso>W4H(l8#0$b%}2^KpTjoua7?c2KQb$s?yw&Ej(RCc1@un0DQX@)rSK(-k8#jWg4^Y=>^-Z)l z-pT0S`cJPqDSZWUhgQH~rj+`jhx?>{RsnqmHPBl@#`;W&l}+)Oo`L)%S(_zERgh)F z5yc#lZ~{6M5K4U86MoWPL)ZRUAe3!(V5`5Eh+#)m9nm>1;jl{&^@LGBv@^_lG$Zo1 zS^h4d(sot&QFMeKkHgxUDIrk+D0$u+esd(i-h z&`@rH$X4%pW^aC&{(25h-YhwWpSDDXt;ikB=tSC@o6kx<$V6{sA70m9|ON?0C};Yxiac@6DCk@TsRJQ6cwJ8btzS? z&AJMl;UdcTa8zUjbAymQn*Y2#^e(}hd=MlR*!C9X`bt5iMEr>JPg^!*EtH|cc}eLO zgI9Y9f4u|gFhMlpgR6BgE_-k=snz7t8iBY;umzTPP-`x!v*zlr_OZP*W*=+sG+ZE+ zZVyn(9miplmkg6)7_-~8i{Blv)Tng7Y@7~9&8VO?d83i@Er)jN^rXtxyz3bcHgh)E zJ?z8Umw4!B0Ui6R9?eFLT!{qgw!eg-9E+Iye8GyhSNv~W6Grh@nZd@Pdtg^j8lkSG zG793fJO4`K@5l?Jr}4#2?V;)Mxn`0)XBiIOht;IWmQf;~3A|nE=pj)`V=Rd)W$gX>sKX)a(71ZDb!hVnCYQ zENduCH%z9EuNKd&(2(6HojfW;R6LGY+Ef9{TJU7<^>bKJ6_ymG_x3{+4<2=o;689} zX6U6)t3gaIbleUl4~e1RnpJqLxP61k_uJz!ZP1xAWlfA&d(CiwXHjOk*PAYq_0?QO zb46!kchZlk9VlE$MBKKSUz|bI;4%3GZKR2oet|&j*o`%jA+k_1$YGKHV~q4t%Q^A8 z?6upF`OdJiG!1qlxzclZ#3D?jV}h|#8aNJifdnAXWa;x6fA8Aq7JZ6FvxbjO$(%!6 zMMmk-riBO)e1TWkl7Z!oI+8$X`IduUS+>)!MkN{ zr1u7(jZ};4;he8Fe}vx6mQ9;iYKcYqfVbE2$#IN34L*Hxc=dfr+x}nTybh8?3cQ@l z=s7n73y(E3D3=J6lXXj3V-J}=B;To}&urvNWV{ukJK_5frK@D!7oaK@&`IxN}@ z^D1sEa3K9VM!Asn+W575e7;~gtjst;c*><3@<4hCOR;W48oihNKvp@B&%Iu{wTwos z9a0{n+(B2l4``|DtVEeBny)JdvY$1`myyf@EOkdvnd=2gL8mw&z<=nVT2!JH*ruvw zA#)2vZ&`(7VFb9?uL)bw$nbq{rbJS0vY=o>d6p-ant0~lc$rq>GK?;4pXrx@F91~8 z*YWR&2mzbv-hY{q1R^6NIkLVVA@c>ic$*s1{(CqLVi~nvc%iD5U(8t>Stf}^OFLC@uouyr^^xp@3!}y?T(9N6c$?~RSt$!V zqCA_syzz9(9#Vb(m#I7yhtAKmP zP-fFuu2@Sn*m;4Q+THL|&A-!9h~w@2{qg!dA=?-_e0LYa{wqp~E9PR$iq?)vtX=mg z)3cz4Ci;P3dd~&S*3lKK(ue8p@gyEVuvgzPalR{;JK)`BOkw^VMdra$nV8$qE3r)J zj6y{(?CY-|(75n9;3;T@U~y_Wku;hb9!Uh!M9amQb;D2#%?d9$1OMc6X!llAtdJbs z1IbV+k-kiMAlZ2nwX{ zfS9a$6{T<_K;}|khVj_q+R}KX#us4t5K)rgc6zC~^6_;C-Xi8`poF#Yk-)=+Tj~95 zp!wZZZ$Ock>87ULi+YZaKH2O;s_MaioN!7Cc5u!;&HxmgVd&J?Y?P5~hI-%*X-F?| zJ3Fy~(O{$1-qBH%k;Ky1s4)i=DGKbTx7GoUB)S(r_3}kpj-!qvL5=yRvIG@vF zc^n<+?oSV(P#tuhc<}N{uaJR77d11Ci;^HTD!lKd_wZGtqOE=XX~rpv#Wq^alYOCTI)8r;KKsSkk<=&!m`qR;U9~xx=hVus#7HNcVzfg zKb~xOTZlgO{V4wRng7l4S@1`;|6z?_|MoeCn=M*=lFhLl2XonFLMExoR}yh>@&*Ci4qbOj54@k#?8dN^+` z{5>Can;2@PaeZhlL5)DgeKbjJ5N9jCF;!R9a^)oOjRa-NWXhFZRvWtk#>i&2@vEi0 zmTVWy!DRd21HW{*($5uXU?#-V6VF~+Lsn}BQeCq`V`}bVpeH$wP!tr0JxzTbgyR6Y z;)(piM)~Db(ytb8Co_x`rs!m_=Fh}7^M5RW*cTq~Y|aEUZ#3fZ5Xs{pMm2vEMXLAl zlm9C89r&+gyaTqBx1&7 zCmtk!qnh0gcXxAyaeIFE9pUPZyz-wM^y!h0fK+{^roP04r1K&D+>3pftG|;OtOE0o zvT5y^&viy;ruS1dNT<6bk(tr$U{_LbKZiOT`LMK5=)~30PD40eE9q2^iL?~ipGT+Z zyi}yLiODe6c}5^hc{5NZWaa7`#JCx9eQk^)d{9HjT}Qz)A;>fvCB^NOtmUICGmi>ix4UrVk-Mqgl2{M- zYg;fxIi@(03r`PT;Rn(;Ii?ic3d(%igtQPGLZ@B;MP*QQUp~G3jR|7l-%<-8jC-wp#|Akr+DHaPGmzAKc7B`rWxHy|9))B}$*=U`~=wH9T$Y zlMj7jn|Ds3rPX;=r;;d^JF-s+&&2XSGnqA6jI~nkT^{(9y6C%7*Gh}E`vzwUzO(I7 zzSYMW&z_{9qjxFi^{}OTva^{?;a^OpFZDwQ@lZty?DI_3Mqm7i!n^G(H+>YEuuQNR zgIn`(RU=_-e@>?5d=+MRvNLQf{iFs#HCap495GaZ8q^r}@yjGF=U+3b-7Z%+}{BS3P+brrv6Tm`HF>T-vz!;kf#f3$(q+ zp|^D&b5-r%DhF;hR$V%<6GKak@P@g(^F$Ft8~LDCk#TIL+6~qY(X)%f#Gs&@*m`JH zVF5ISdhTQ%zAkd&Q2fc7W!%?*mc&Eo02?5aexj=JM<{l=qJvJ$TR}zN9O52gu!Gsc zK$ZtZ2Wk=EfdvBi^xcrcVo-kUMw+3AcchJmnyizR|L68|BslyyVw7ynW=wS(dHwv< zlNG%wr=p|^4dQW!aXmNhNO~RQ){A0{M#u32{Nc89G>o;2e?bdPOy=4vEMK4@WH0f| z7)T1}*0a3aEg05I^2w{^(}rFua)<@&arct8&wy10(GB_;Z318VYsZJs6@;hqd}fE0 z14IZ5js~%_MtBL+y>pcz1VuX&j{vmhg@gEuo?T(%aRy^ORD-GwDVJ ztpCJT<4Qlsq^SsJOd{$CJ13PiK~0w0b{i;Ecd20IzouO{Ma!R;$8N!j=H5 zZuLiK)sD4t1QjLgnphu|crt`3rOnB#sY_xC`UMpp*aM|M(4iOcwtb_d*DvQAGN_@n zPk`RdEMffzR-{kH)pZF;I-J`rB1Fff?l43P1SgeK`5~s@l<#ZHs@wc7VG8-GknWE& zHLD*&T1|08c`cj_>1=N`6pEw>4JZiNEqO6b`V#YN2ZM+!1u&LVErL zOWzoxDxo@4`iJb=k+06z4kIqK_CoBU-Oyeg0fRhI(AVzr&x2oT9RGAzrbZ7NbW`*A z>ijR85*Gynz*oeR;7qB>VMz{cmB4f3m5CnY_2JMuZ1v@~DG>pn6p4_}p~Xc*w%PTL zbSB4MGCPaSM97wrNM=BF4B8Z5-HWGasV5v$X$jKF<0PT)4ez^RGR&g!hK9O2fs<>` zn~TW9awvlehEo*G+T)gU(7_ZvR?YHoUft)Zq{I{g5v36w@pb+KpVI=_ddYIeD~7?w z7@MP8emZ;&%2ator}kM+(%IpsuLCwNU!Wp_52x9 z5lPUZj@~nb7$fRWT6MbN$t6OO7I(15!RxHWr>|Wpn^{fZ@s1OtAinK>J;2`6R8vfM zQ&&DzDbE%w{L@YUyC;7^&+1pV?xi2W^<-pb9Zxm;7atNh!jRPIM-1}goDJFEE{jo- zkOwzeXiL(5hTEWnxi5miZW(Mywu-kHT=gGSmjvn=%v7EPK9=w7$*9SibdI@n`}*50 z*WAfgFrOAf^+Iv^?H$x0+sW!<@oUvl2cmpir%lhuT|JG9*{U!H3Sbj%Kv=r2BkmP_)R%P#U6&nZmkRh*zcpr%qxdxlsd|N0$nNbW^yQ0Nt{ays3S>>V<;9a!0K4@c+s5mG#?9T)S|f>e zUc~VGTpRP5D+9IO8*z5?G`8@&Nv_ezV#C&NfW-^RU9_yxU%SLpR36(E!S(L-Kk2dp zbb6bUU<)V@u$1PyG`rH9-10Jp2-$(^o}ADMg1C_*7o;PrZ7z!dy|lQ^N=u85o=20X zRk8F~Xvs?>FOSSi!^PKx@t<8ss`$9vY)x-q1d?C6h*#{)Tm?U5t0a}2wkMZeBg!vV z*L|{Q zG<)b+c-c$PgaM%Y6T|6!sGnMP*~ad1EKyog4vs-qo%B59Vf@iPjOeQUYiCh)N;I$4 zmFts&za?_MaexSoc@dUTz+|p^x&LF=4V%3r<(c%%6KwJ-H?B65)V`rB{b5R0o^nA8Lz>oL5roDW|Uxj+G3WB#uE(lZ^~!1N=iZ+9=@txko%2TK_}a6*$!zEsyG9eq8~?Jq_1tl;Je}h4_Dc zkDUitfC&c zw5^ZlraB;%KkPi;RG&@4ao&Rn3P+cj-viwch@^zf^WlyS1tD3KaUe@quK2zP6zuKs z;S*owZqBhOr@8+A@i5=t^NKTAn3zbG-=p&}B!^C>9_8{)(l2K<|Lkkk%OzP0c^+xD z`mqmc#kDz!N=MH&4`W11C;6XDpkP`eY~0}&QW_AR zXRmcS4G0nb8OFc{q_?NH4Nd{IMlw9dG$I)8fm}+IRy8^X{w4K7^e7c`G4elJ`Ol8a`Vf_lf=xk*BT}4u97*gH-}}k4~I89gEN+F0+B;@ z;40-l!k%~(UL%DxP{+7d#Q|d^&|+zAi|=G6OoA$D<_6p1&fl-dgB~B1(#|#a!r`B} za~}i8CtOyd_~>dQ3F^Emko^Pp^Y}E|J6-+--EsKCxb>l?wHLULk)Y9GjpRwA%3Q=y zdt#2sV1iJi7$eO;^LS#NZ6mlBhOWDqC&YbWN1N_Gl)#L>uXvT?iN^LsXY{48^Kso| zCd0PIEd%!Ap^0QrAjx!`=<`tM)xEK3w!>qJh*9A_8j;3)4`Jn@`PlnlZJ( zhlO}Dn*@)Z+W$n?JnoC<{?V|KsH_FGGNR2^Q=o{HhcfsveM_M738nlQlv zJc}wgvr*pIRo=+8wKu4YK|Ct+=3eNy)@2O-bK48`9fxno$hgVQPL~rIhj4sQ-=JQW zG{?95QP!j#4%JONHww{5G8;vt!|D|U)c|&NfsZ!q(!oeux+i3Z!$cI@4d;*Opt2Na6>r2iAAF zGKfu0|Bt3`4vwVz{(d$a+qP{R8*Oacwl><>*2dY`wmGqF+sVdy`}?bUtGcFU=D+T` z_w+d*T^*n>kTZ4O_;@;r=`NO5ZGr_y-XP!KN@doMc-Pj2Y8;hvBbkEhAdG(V_m^L1UUb+-ETZ*;lGrgE1zxAc9eZ~#*5jzfjU%qChiWurwldp~t&rE>an zvY8&R3pvR+`b_coE-<~7fHJ(ykUqRpTL^XJbgm`3UncDl4?&}5$zX@y?X=YK5>w;O znPIs6(DeCfr6?OJN51Vl&X*3_F4nPuVVmxMY+gtec^&oP1=uX)=V>%M=Y5cKksBC$ zkL{L$aI>O!^2&l>=-@{;?X>vwn8;4D$n;BD$(v}zDG6A`l&J@iBsWV3vAbHq9_Jr= zek|XdD6rpF-IIrM9k+H57TJr=ab^`c8O11<#_}pwqF0R?E&5GD@TQ{{HFAL9?k6b2 zvU~TLRr38x_%Izx?0%H#qz5lK6I2x5aAo0Zv{`!4ugDi`&S;lIS+7Qw8OB&igQ%>| zBO%J9!$8I&6~##z&dgC3Q#3WHljtzoGOp35FU#zMhXgwT6)r<=rNzD`1DZ^uu5f3Z zQowbSXW92lKKmC3wS$bA)kkRT%fAUWhWqcf(McY!)29L&U)%$$@q?@J{j2fDZ~oV< zmf4lFp?<1mL=Pqn=mqD=xQlI^A$~r7aXXc_f2zZ{7QMP==Jf~_5=$oMb#@T!q*O6Cmuad{bZHe zE5p_GlvgQniY z)o!#35*K*FLd!!S)?ZVL9ceZ4Iw)Up&{%9quoeO!r{>U|6GSMNrv#vgNK|MX%au>U zv`4%3Xv~Bjh9C)Fuk1NDZZp{oDji6a-^9VU#j9K8?C>C~Z+ix?%xQwhA+|RQRUT>( zfknoJYvXC7lM3)`4=y)Ixw+SCNy&(znMEw>Y&AWjbXkL|e$@IS-P>7ttulM2;6=Sv zG*sIQtw#{p9pVT$_fI150PwHqWyjc3w9jR4v*Ru*|z6W z81oyWvL?zg8F>3F9KaO213r5)dG&Dm-VzZFSl#~Yqk3eMyc9Ike=U~Z_u$&B>?GB3 zgdPMm(@U}jPEYWD)JY!i!FMWB%6MU-7MC;i3CFb0D88gj-8X-^G=sG(^opMW6@ow%V{bcS;Ei3%|WuaUQx3dmH>qW0cjp^#rq|P({me1%Nt*?$6W^&)ZMNZ*F zU@mp~!o-x*WxwBC__oJdK8CDc?9geAMQnbc)TEE$ zt}&WQ$M9%UfSHIwn$ih750a?RmS!rekEkaQbL_?6Vsx7?2*pYJD*?!K8w<@S{U08v z2GuYcGcR2(hVS_+f07$x%u_H76Y}a*FO$A(WTlmpVo7~J_7AFJMOLxDYodra&wX7D zaTx8li`H5%TB}!Se}rmD@pua+mAFc#@Fe?YLBoa?HBGKObIM4L3&k*~ISM z{lzun93Z$D+;ByLty$RJ(~7Vp<0(h2?v4H9OD3deA7yk@JFN0=W#~hDdPoh1Kh^U{ zS_A)ScD zg22_Rg-xe5Ormtymxo6x&5o1GaUR9Vja`68lbM%Hf6+Xu&*H*qhS_)r{gsn<|6z}8 zHe0iV+QxptBoAQCV`~OI&9iK1xr2I^QxD}}(klNKodXb*PBOJy@$XvR7KTCaGbS*< z-s@LWNAfKNt`fMnKhIdInFIzl{d2|MBM*WpxGikxg}x<)u|qEPhbqMlaxf-^aqNxr z=X`Rxz1LjNcuLB|s-zmuEY&jf?Yc$-W*`RXu&1l3xt9s_;clHs6Bv14Gdwzk(d@X3 z!}g9y?zeu*SbjF~Tng?ZgOUdX#&w?%+g$&cP`em$r?{3TGcBW$Jo|8DA=qf8(L_5w zPb=5d$-`3R9!d$_3uA2;i@mHrIzsp7(dGpk6;rYN5%S-E(|C?hPZfD8_v zvv_O|D|8O#%cOEaFPmt(^L?s(7HVbia;;($*`K)L2v&B*b}dM5#**wAV-jgROjVG>LeMyY}gFEqtP>;cIy|uUi`Mc$XuOL*>29^ zTafwEz34XkYm^UPIgQvn#yY}RUx15DxU;|DsWa49-()+tyK)2R%2jHSPg8)j)VoNm z74sG4eoh@^vFMJ&R$7M(H$J7+cb@;2(=wy*C)@>dZ6$iLwoWQh`}AgIcR5*&H6ifs zT|kP#<9T8C^S5V{kMa_A8oO$%CK(tB97A*vC(B=>nDW=PRy{{uZ{>p7DiXC_WTx9% zP;&d@X{3X3vh+jbPuVgP1uN_#;1qQK{saiVmw}|?{~YlciDOU$VcVJUogqkVl`ca(0nhdtlr2s2cC z%k}rcdP7`jcoG)iT9$MEmvVhu1_uY*-JyX$tQY?uF=v)}$udE-%3XXBBoh2}K|v=W zOU|y;wh*K`XlETwLGy%+(zw5WZlRSTx0{4J);v#c&AP`b<)|+bw!UuDbI8dJk<4n5 zkRNWh%sXAL3GcrTSvupvy+eYrIc*QwfBI-749()SC;H83HT1D9{PGVnatpaD1K!y| zuC~=B-jnjwkW83VoHq{0-xMlU;9DyC?qL2<2P%haDG*ntyIV6L+g2s|yxB%W*OFf; z;XH9?qhvLM%WO0707)5*;2m!Z*dvuQL8|C!{q0Odd6p_faUXr?K`N4MyVb^#|H`G~vPRO#9gB{}Ho-arb_+yeOrqy+jnrLx+32Kz4|Jtd?43J|f(cOg}!j zjJscYb-8?GI)0I7$2D6lKXaVDI1gV{2Lasz#Cz%6+uQMBepR{l)L05#ghT;}G{znR z3$%7mcW7N*o#Qvra3UB!_)!brqKks!sS3e>*2#EVPVyRa@EYwvKb`$wV$N$zC)bPI zb~dhsCJO+jXf>sT@pJ+V0Q@v?jygf(b}(r`ed#Du!FbZdd*8kKo_EFADv{eH0r!)~gA57KXanVI9Bqr@7qW)Q4c{q_P*{XnmHI1vFE*OspE7?`FRZB3=t zU#$50Q8>h>%2EbmGX#Z1T;~x>Fd4K)gOgyZqr)(SGX<%XC$%UguIhyr^)gb)`)`Ua z0rKQv=Bh~H8*ObSRj2_ti&jaiJD#H`VGE^VytoBk{F26VX2bcHAnNw z*~#@a((u&;y~HFG)1AoH+FBLXBpUYKSYVxg{cFbJM*S;uoPdi{0podaFE5GZ%8~IQ zZ0_o1&wSb00r>3@VHqEO#@r&d4S9qeBS?D`t!8i}3%St1%S7O7P^+T1|JgWR2B9$_ z>iF-+N_|%&lRq=D7Xq+k+-#?bhCz7Gi!l`_7Hr>e%;M0gPf`r>YCoheU65v zjTvVXDiAskojUj2!Znc4_#Vx!{Eo)yD|98M%bS>0!J|aJl<8i3KEy;aZLwV=x_3x# zv5c`3VTcKz{*;Fre9Fc3oGIG%>Q^^pgIVSc0YXQ&_p=)0X7<-!d z#=Bjk_pUA9bM}q1F;?K%?Yq{8{93}?L~q*stB#PST084S_tU<}#$jX}w;1777dTrt zHWT5Rzqyu}RJMM?2Vp_-Y;FT8lyOB5eBU#9U@Ft}_F&QxbPgnQ8Cl)cXJ}+aycJ{N z`>mdU$dS;#qw}HvLpq^_xH%Gn zL5wGwMk}wh>8H3Mhb;!2cBo4vIs*oKbQ?BWq7;g0WJ>=MEr!VN#Xs>t?=d%v?Zh80 z+|Di0&K{~pKZ0H{9sWZRb|n$}6t!qdPL7vf315Z05~<-wi5aV;@fw8+d2-cVVL_}8 z`T&4H7UO69EQbs1C1KoVnOs@XYz2D>17|XaVk|FD4YOXOL+3K+39OrC(cjn(t5Zt+ z6(&|wVbl>aT^?%3NMpd0**@U!{zhK)LckH*Fm3Z^da{#ColbelM}C;s=^>UcOHLZ# z=~BHM^)3(ivR1*Xlt^f{?v!$LKjY7AYEJh9#=2H=LMaxTCYCOX z$+V}p7LoFZxU6(CDU?nVOI@Xh@MGyaW2iLvf4tp=&3Mb=DlCE*R#vi)*x8Dx}6>b zuid^vuikoM*h7CylgcVXI+hY%uOfX{e7G{FwNWEn;jhyMmwl)y%0B}y;X5z$Hekb0 z6M%+|SoYXnmSsWN@-SedOM6ljJjYftoV+8{|Cn>yQdt#Hkuv`|r zVOE+Mn*EF1tG4Y>?`oko;iOv%=V-5;!2QKu^v){ot z_(RRMGzRiGCcXm+Swg)vDy>M=)vw& zIxQk7fkrxr_l<-FZ?7bPzlCjCfci^T4Rb{3YpBe~+us)jwLya#*i9>S1+i#UzgBv_ zFs5?c;8YupYDotdL)X?A0%-Yd*Gc?zFYcv5ykd7)3_SV`9IpyiE3u%kBt#-LYWVHAuudF7H zD{0>Mc7;&F+oz{j&imLm^*IlFrZ58@qJ@?@mP%K6lYl}qGemFQfhsk#ZB{o#0yKKR zp2EA2#BHxpv%kURf}V#qEPG~z<}I-;^CmHW>3f|&k3W9uq>i-?-wS$Wx9~v%A!(gm z6vGfY1#|=^HD&YnJ~X%9`g?2Zl+@ZTS&@;jQ(d(*C*JPl1Xq@$vop@@q82b7i3%tt zO-NWzkf@MK*|1DN@S3N`s*zgqPxsL;em~zmXf1%&B=SP#(5tjf&7^W(L5Xqw@sXS5EG5TR&Yus_ zW=2L$QKeOBBFVnzNnWg*5m_-1>XuF>G>aJYM@WB%RCQjzjauIaE!Y1Je2GQm%pS@l zNV#2G65_Ef-J&4{O_N8&I8){*xSo8`lV!C*(2_@^}bGc0o~6d8+k1x@=K%X&4P=>1LlK;aLfb~{#PR^iT-ft&^4&<>Xc ze!Q;f=_20SH)tCY?`H9vJwjZSNcO5Tqfze+8j8Tr9KCPp?a<<5ssE*@2~@7l^-W&e z6xWxBg-lSJaU`cWq15`?K;0g)y-3}Ut#>lq;ppt=JV{Cm0dY{(N)zGwKx4}8&7+Kl zI60n)jlXWd&6ttg7=73(^!QD%>vjAhM&LJg!we<*-yD3ELR;&F-GnjkQ3fj!i4XT( zE$iJi2q>3?SQf@p#_iFtY5uYQH7(JqmAmxPw250n#q?avAaVgSo0s0Yx7Cg_6CbB@ ztoQTvsH;E7;tBNvRpIxTU!L12q$KZ2zemRRj=GA`sc(Duh`;QYl>4Gz!EOwCK?m}iYmDqdEGA$`Sh)x38g{%PH(_0 z%>N7e@*ne7KnTB|xk&(o*~(MtimBS-o#S7va4vY!eA>Ztp6yYzrUqaHic;|>d>jTC zwQf35>eycb$UuGB$+P%)#RZBCoNADeJmVTNNp&MmW(^_gP+qISK zZ}{qUu?Y}a#EF*(q;Fg_2mjLhA(BC5((!@cSfO5Jep$>4L_I0YKdmV$<_r(7)kmxM z4Ja%cBEZG!1a_Tbb9A3I+eQs1whp%u#ylMJ>v!NR*(Cvbs6oP|=OMPlh#=hDw@%n- zHM~Tw5`5C$PuFOb)SXwzG;1;EIaJ-7o`ENe!+wO3wLXy?%gWtefBM4w{KO8zx|Po; zIPM#yCRJ6{`lq_Y+S!ojfZF`P1OhHP(VjO9RwXl?EJ^2?K5Uh5TNC(0HiB`spWLaG zBR`Ipza1UweK&)!#Ijh`E6G z76z$7mr8{e%w}(kH0C*3GAeBV5NfSTp)^L*nc3%L$;opUQfBuybL-)g>ERdnHYP2! zlDh4C{t@TxplZOLPXs06;uh<|n+mV2p&(R91zWGu8PoR!_`W@cV(n86UgQmJq#T~% zhQX;aQ30qJZ>zfd1W)JL;Kq=(dw(7KukwIyY;#cCjTtRlvK`SFNS|sK zLYY?=aazxlXGZ*|5+)>h-73Le?GxD=jeCLTLcO6)5_ zAeq%N<3hPq3Vk-6kJ$oHcCjRr2h+;JothF-z(SQAPCfi@*ypbWx&xPc@T zNMXzt;QF0(2C?1Goh!r%ASIj%&6sQ^7Wm=`&c1pN^!iI;5nui}$&=SfpJR;ez$|p4 zD8OZZMZNMRCE=*if9UY_((wMVrBHT{n_gompEhV|@JQ^PCiojohC~90hwG3USa974 zK^S2bZ}oebDDjF^iiVLMw~UR>9q*RZ!8@qHFu@77K>0QYXS_mz`-CJonM6f&goKp? z2NIo1B$uZT=@{8|SP+fYj7Ag^S5aU)4Phx{4%E2t!SxXT{%fl6scjoXtMfy_mZ3T) z&wEHd95}KJl`ruT55Y5P-?e5vf-`T9Zh?O-yprW66=c+?%91A|f^kvyX=K0t02oikiv5AWV`GItK?KZ-# zgw4H?E$iU4^%UFkC$~`UyVeSkWPuV;8N`eq-9)7(^o^3%9?rSm6$8(d+bjo&#lz|9 zCN+S8s47bAeZf#GFq%TD#6%H3rf1)AZOL<5pef++cK-4L^F_YzDZX4Q$KJ9e6=paUjoaC<1-E-%=?2 zFFXV$QpWU&vYVGqN7^U1m(e{YXBSUB8oqP8kI4hpVt0C9Kwtwn(T!S@7obp9Igam{ zo+=bOl*sJfpSPrYGc1iHJJnqI3jPyzzyoEX3i;A&ZPNk{E@M4Iqu3uh%cDTNLG;hTn?`J-s9SG@Q(7+e88Klca7HmID{DNJCD zfoR*lYYsv%u@^qT-A_#Yi!Udd(2@|&YuipP;j>1@Qik4a1w;=0h|jpOi;RK*B^Pq# zLmXH;_xJrt3<#;yDo>(86`9hkkUGq5A`RREV39Qn!LsCfr%vXU3yj|cd}k*Y{K$|l zeq-OFRxu45uu4Nerl+x9yk}Rvm{-hm7nzrS?nMb`_mm}Vc_f6eweS_%dq{N+^=UG( z@VQ1WCbloKmL>_7KH9A88CRxiQdx}Xc;B39=j9`;pXgB<_ln}>7|BogBHzu>2@r7FPJyd`|3|G>I%iUArB zswvP2JX|G7fB?qfMLGDkpr7o6-qrhUg|6{U-HED?iRL^QbkoEOZQ zlec24N5Cg5?b8N}BlA(QsWMF2@EhCNih|D`4x;;FLr+D{wx@@SqCWhIQyf-KXM~=@ zr@})v7B&zVk@NMms+NniCG@aX173~WCxF)=74tAlaz^9!1=}G72O>3BJuJ=5uHpPz zW}LOe_Ne;_;Z1w)_3QKl{@0rYNFhN=c027ZGA0Y69a$pH2{30t`z4Y!Rl za4qDn4(#qS{-RyptCkT4@1$_b%BDH64mz{QxWODwc%lz&U^)0DR%Rw6qVq~Rw*pQU zwJ;ejYP*dV?i=!S|Mb)a-|L1(C}yK-y*!{W=sCLp_@^q_$boTX#bYNfZh4}k+PzEy z9DpoPNox5&Z?5P8DP&lg3VHyAQ(Tc#9EpyJ*9P3k3K>oxhf^FxZ$675IyU$(;Do5* zoCVm|9G_YrMy1Sa|D7``>-%lC3mdUcC7^d8@zeivPU_0?wx8?%#m31AdVRnX)d*gO z0RXZgSxcL6iGqvumM2NVn_${CWQ|{$M1amht)9g1?4*e!k;tv~5%xkqhH9SWmt72~ zPz<13sZ@^3T%*(20`cHSw_m}}OESyhq_i+Lejhr;`E$9E_Ua)pLNWCHu9`K2$;njv zN_dn9`U=J#AI@qv@}7rbIvzgezNqQR6*gB6ZTb?b^qiJe8X z&~%1qx$HIz2k94sh^?J z?GZMF2rO7Ku)Nz#vAX8S>9Nc!Z?quMh&si&6Eu@64g`L$Nil9b<<91>x~LqT8v{~6(JwfH!A6%)Hfv8t=e?};J|@#kmh#u7^~LR z45>4}&t=kovI|0!BT%`8(KtmmG?6|6N%qF?6WWZf%MC2Ey229@0UBQ}STzLIP{hp_ z;F+9m;Oav|y|ZEuC*$&twG}xAUx()QYa1xY?L)o0(T3YOZnhlcQB*mH%N;oq(WZ=N zrhjueSSTrq?@Ky)1w3az-{e>Ox-1Aus)k@ej145?2*zS;%Va&8@H-XD{QUtG*FzCS zGkW41)@YosTJsuXw0DbobH58p9RHy|9T6Jsw_VqjoEvZpzQa#%l|mory=A_P=m-sO zO(NwXtS<0xLz@xTsFmwGh~pnGp&P%SFZk5s3?#WOUj!@1;~}Uy*a&6SC{wi~5B9SAu6q1;NZ((K5@uz_F9wGQW1)qSFYm#?&iD|nJa>P-}}-DhP{tfa*{ zO)WhaJjw&1rR@q+jQ_5;Bccs6Noa1b%Q(T{zx(#K{5>5hQW2k^u)hD8#_O9j0uWS@ zFFXM1u(Cyqr4rL+bje+P9DeycF0u00RZ{8$pthAG1E~MOr^vm)i~gU#VTs?~{{K~t zxn94ISA@SmIS0=nO~MKfr=15ieqFqdTLVP{4?$W*CbkQw&%eZk`?ERC*Ji(Djs;+W z4Pf^pN+S^vXwKElEC6yYRI+WZFx%*;sQK|3$?f!xjleKmtI4yY5x(W77$ z`}`B)<&)Y<0eXeAt*xQlgk?rylu80|$qb&9vLnCaIY0;eYSkz)^j8((N#?@vRX+v{M%Mt&TXsa3#h%35X-FrrJ91*(u_*Do$&%DGb8>c^fPj zbI;#b;(QSg0wNzbgcmf6*V<@-s_8)-B-s3Kv}7P;+Y91I()D-MV$1)&pHoK)`y3b0 zciV$PTfxQm^gGIepi!3W)&@4O*B~ZJjbs8m)sWUXJ#G>_xLg_(#-kH`#tWfg3hidr!`LhtiNNK&yNc%|FR;u9d3PW zzdNV5hdCDo=vw9J)s}gcqeP0RznP6+|2CF_&p8yl_gfQs$75DUOj4??5QYkFzu6Ne zVd1m1N&c^dEzkr9?P%NE;O=T=Luz( z!b~*Aq0f);<5ay}Iy0F7aTR17u+ZNoGp~WMi%fp`pB7j6C)VddNA0A+&`wQc>!lS>lVAnB1IcKf>1Taw+$h{-mNf-k!6B-DRpU4k4nmXs3QH z0fJ3#?=P*H8+k07+`Q!_OE$O1*Q8J21;73FbG665ym)$P#Yl?KT8VC^hb2tcx3Me9 zA}9RTp?IoK%gfZihG$p@mGR5|41NVy9L3CP<2otxB?LM<8*1f^K)Q;gtw7|k9D>`# zhTrH6qR`flulMQQr`c;`ZpYcC|Ins*D(aJ`c{9iCBYC(DqxR1GX7so`BJEe@Hi=Q1 zX%`9485GTb(U5622;xgQ4IJ{CfdYa`Z^GVGHVC71F5O?5Nr*kod@@t0S^r?PRx57d zCV6Q02}|CACovc5o}|H)c%0=mwzN9^Doo?OW%P7PZyq8T=hzg*5stiqof+i{ES69W zshp$H4FEyVQ|wuHWtRY#is3GlAovr!Y0;oqsM_kqCu|}*=S~vELSY5Ow;8Gw$bVb4 z#-eGmEB;|<{qx0I_9yDTeO_=Ewst4J-0WHUD_S*ax=iw3^U%1_5Aq0_G>|0%0ve-v zggg_jU4hmGsvLxCRPv$IxM?h)+W>gjb zcoa*EKeS@bTOhyvl_3Eu+&V*!^TM`4rx`~tG*JHtsMAjT)ew||wsPDg{9>K0`h#IU zzI~CzMHxAw^hp6f+9(@!kdFUC1mS#P@!oc#TMotY^;6w=7|z9I>@bwn45<;5+B{&# zU&~CfLGrM)sjxTkY>hqJ;fRvu$MP-X;P3KG9Oc9B$51mJ7_;6c(-u;Ly4r896Z6)# zr7Xd>QRKUnOH<_-oun9?0C{qylE|-rMoaRK@yONnY&kRGX`b-#2zgKc6NwNJ z*$;&OtYmSs9}Pjgj=|r-Ipz+!@-r@(Z)7@G-8RxSOqRN!iLro;Wpnc9Ga>R}RpjrN z-I`H0Jar=&^bq{H=tdy2wc1I_nM>t9S&YbOm!Z^eO?|w{AAyzqkda-{jL%(v4Qb!q z5OzrS<~gyjs-iXhIhtN)*RhO4-)(*C+-S`^S&@k>wnTB=)<7@q9;48SI9-!QW%kWD zs9dg4VxhlgnX&YZM8e#8<)_h1TifQ>H;EYli&fa%o`q9DdH7$vr5CUILWM6BgFB+T z%U4-RT|U^ZIr1@Es|^~E!b<<2fC;I*mSqs9b5MY;$xK}pp$zodv~R!_ALqafs@q?X z(%?nD^np%uUgj5i))z27Po?4mdyZ19p85(U##{A`b_pSrJPoDt104SZ3qpMe%e%Sp z-yy7O!!Rot0P+`*tez0Df&DWDr`yxdt7puGw1dU|#=m1Wf{&(Y;df^-I%NBFKRrs9 zU8>h)?bdoiKZpnWKXT+}*7r#YYo;ZrkGwX;KNgPM(|{TCgi7=~T=c-iLl ziV_z655W5I5PE6J{-qT=D8P6mG$p$dgGVvxpRiA~hAzE+g%+P{H||_O()N|J=2b}F z%PDr}$_omJ-qA=z?8$I`Hs_U)l3j?7|m@l zD+5Apa#D2M0bI1>Q66!!PWbBaer{^ZeUM5x4b-*c>k|;RTBPDJVzP=Gr@68Jfsz)a z)#srfj^a=F`GJ!S6woN|jX#cBs86-;*Iqy~1xUbU_6Ubr*-S5OD_N2S?50rZW4*H` zplSCA`BV@~SV@V^fx8bOzgz@Rh&gA)Y9(J$<0zR|!|39Y^6#WeycE^6 z%9z62LIuIuHWu`+4F7_T_?4UUI$iv_=MR2{E&L3t-q%}*yMlq%k%6^!DE3FQpuccJ z0D5M~C&RykkLHDfCJn9;P8i|hh{fC1+;;(cDqiR76jWbKr3<+Dc^Yj{!;~rf8relUUt=odeQ0zP~ z)r>QRR#((Jlkh8*{t|{h_MY4(!r-axQSTsjp~1`qO8k>0AF%u0e_g#-SrLoE)H-P) z4GC+F%DoQ}$tHMpCu1ppb^(uDqDrF8%#!z#j%ZLTp`|aOcV)-q4w;}d6IsQSF(MA>+w_fVa4&@F&{WC2 zUR9;v0M+lA{R?jb_+ZnNzJ?aRoJ>&Y39g{*MH58o#q9sr0hgh}g;-pQs38_p=VIvt;F+?!kKzjb07;qv~tZbSbz%pgL4b=#MUKg=2k zP#eaEMG9l)A9jaHipf;w1Uqjt&!UqGmmd7fznty;{^f>V9!xt&qs2%J82W~Dp^F-G z4yHsC4S#YQ2u-lPy^;WpLIaHLR{z67nTk+Dm``aw!tK5NlbYJN*!do^kPG?N8EVa4 ztv=?8FD?inkyk9Sb$Mu`YTm{M+buB^601XFppN5FE07@cKq1qmGTQs%9%i`2w_^V? z)YNNZAGn)gA7`~V@6M_|gu8ja(FLRDBQKuhH@g_I)SXpVdc_4WfJCidjpt8`#fY!X zgdfd)F5jxw8nhribaW9#QIMn$;2^FI;~2z@tB;fUdG+u4dXrafxZ)+KbRbh8!s?v8 z$-~*D|1e5!k>3t8k)MlFcWM=vpjck%M?%y8++sDwCbl+?R+gg>W2@IM4@~C%{CFhN z-fn%2v&>lM03F{=U8*=*cBJY0X3d+?t!en}|snZ0R=_wAJ9A}29G!(XP zUIr=qP~7*;!=P4jjsx&qCze7={EKi{*yfnh?eYNSZf)_v!NLmYb<{56uPin46@i=~ z`q@!*m^Dx`FQ*{iGt_$skvas{_AlEA4;yeD&*f z5*DvFJ)P&^38&CblO~3azZ;{C5YGxzxd&zV3H9zs{LJ>bYC+)rO;YOALkvlVh^O4= zNu~~Ka>39`t%in{hDVi**BCwF;4$2yXuaR0diSYA)0{*l=QbTPHjlNo zR!C;(K&^E7hPxH%w(kmJs+*wJFA6RG8O9LV?h9As$k13 zFkQ|achO|$sm-r=_|u5k6p{x1@!FTjy-woo6>8L84g4l7R%k3NPH0T#Dh)XZlhvHq z1d@R6+==TYb?F0hk%^O}h66w+zd1TcQLE#X3a#~l$fob#A7pMNw&0J`dNnaBZLmw*%8Fi6xktLd#x;ekA@pqKBf1a zgeKfs4W67u|2IPP*oJfA=g+d{&(_y&hP9p@iN5$zZy!%kTGP?e@^~*HV3EHkvt<5Z zfMFV*hQh$W=sUZ>()av4{>AuWX!R-SG0wmjWVbsOj$9+zL4=PF?~)k&+?IFShZ~JY zo~{8tio{bWcrf!?D!=bgfiWwQT{x*~`qQL7bb|iQC5&V>jV3G4pZoMCA$j1MYw0G6 zulc)U7s*SZLe6Jq+5N&kUfZo4o#uTpA>qf{U$5hZbd-%WS86cC=i#r&GM5ol{ET}q zz==YIYjcv(@L?&Tc)pGX0Gfyv;1aTT{#ZN*Ie}zMuoGGG&ShfzySUNfw5_*I>e-bP zrDZB#78V2^9tG``9ux#y8O|%4ngdQfKG`HePdqY?qy_r_wNMdkWjT9Rs~z(l#TB1q zZZ02O3Jr9h+y%3gul+2(fP$*P-RF3JZL(<<>PQpnVV6=kaiQ6zcbMpQ+(FR@ z+x0tnl1zoxva*zfjn1L6O*ofCVYuj*oJ{y{t!k5KnKKZ@5m>hDDEw#!uG@$#G;5S~ zpxqDRQy%83`PNd2mkkyZ?~PU|Uv~*K5u8%|dh=6RJ_iORSgqtz$O_GP8uftHb{LrX z8Em!O%q&Od;^ag~)sJ=>9BR`TtB45RP!@_ZF=Z|amZ*Pu^5Nr1Ufw-7ZElAUl;+!F zzjf?aM|XC-dft7oqu)^0KH{QeEPat6%V!d^sfj%WP6_HMf+;6<5t(6MjIL8m#6dL;1+O3LT}?E` z%G0RIvno$tU=0IhowaDcx#jrWi~aZhc!a*R%r)^ZjwP)7T)7keVlHzAsYcjCE}B)^ zTs8i7be*b#h?d*HMR6Dx%@hQCy~@}X@s*?}jm73$%~PCo?#uivG#3362)=TDTv>L9 zaGNqar`ehbfXtePb`?uJuSOcFc1K)y2*zD0lczv%Mv z#9s_}_^@H180}8I~p~ur{u48Tvj+_KX4vvQ?9F@F742T!Vum>{|gft(euc4nb zrA#toO`ph@=M#etrbxGK#OP1dL^OhN)zS|!TZ60DqxG^{ziTRFw7Vv1Y1g(J6^0DD zY@NFQS8%na=GJlTe8p2ji~yf!8*Kp5Aen{o5Pyax_i#>1BnSj?-p1|?y1%a;95`|g zXiRjEkE~#(rOLZO**)g4EFV=^`gYEL=frVqtx0@v;x&4(#Kw{lZNN|Ycvg)cgcNz6 z=iJ=Hy}-qTpF8{*Fa>kIqKjX^vaMN3#_M( zgm=f%Gf@q0dfchOcTh1R3mM%PcC8w({j;*DNO=);(cr~QX zdM!F~w1wYq-}%e^E_rep;ub+9|9rurtc@>|0dE_1aD%LrCJp;g>#%aM0_7vy#^{>X zXdtbfyqd!DLlp}2k{Ft+Zg|D_=FfJBZ$?&8aXD&7* z4#q*%g>v-wgItUA5HvS(?GHcy;ZBH%=t)P8m}XuXA$TA1;_q`0!7a1ge^iV}CfJAU zpg6wfbHYN$Bk6h%Tk!Wcu^%WxXK|Tu5w(}W#QaCpWraaun$nzJxf*hOc_bjS*4k1% zscdKfKypK`Z=bGQUIOT&>6 zDlBDBQ(nz%57ZS`>+Xp)t?P& z7ZqIJ7)n0g*{>>dDzu;Kl3C?f!X3;ae>PRY%C)}A=O}miOH#&8P9sB>j!f^-V9r+c z(+>L%>NiRr)HBDR2V|W@&Bk8P;4_uH?YZ`b>c1Ff2< zZ^Psu)=|0KYSkZhDTOaJ?X|Ws&q*Sc_6P;q%KmzhGw@*`|FI(+U#ir?YC-W0g5Rq< ziA}k&z#0-9ddla0V?bbVAZgj)4Qqq*A0Yb@n5fwk;p{j#au#FdJD4%CB2;?wK-jkk zn1;2NP|TxNyj9mOgN_3}Isc zjVgp*_^89lCW`3)5zl)~7Son4m$p>GZEJPG43V~2qStUK=`<}A}d z3cw9Pwy{uU)iQPKKHfopsg}e|pvdHhg$LV$Z&2{&)rLUI(xL;10VpYO>w2X|7^TiO z@KPCwZeBmC)JktRytl^pzGEU4{pvEwf~GULXEkNZoh02wDf?>_R!pWhNM+UnL)5^6 zAED)X=gh&0#i@^vZ^46)Q=1ZUi+yN!;fYF@H_Kgy-=L@{l)M+wPdsb9N#@LETBCJB zYyO>DW=~Y$IBS;#k4?c4UM3EJX(Y%KNQ$Z_HE}~F2$)nb^SoN4sP2LWH`8zwk0YT1 zgB^joLJsy*z$SVuOGKZ@LW1w>GG0Y+YC|L<;_eSEU0U|6deSu|@TJY|Vf~scqXVMK zqr?49FYxAP<`I&68T^&LUH`-?JlHo&KL@N?4cC08b8Hf6AD#G{BFfOdo*8P zS5Z0>Iqeg?eCYKbN&BOMvnKftk#{GJ!|6h;c=wu*`oR{f{FHEB% zf2Rao^3xJZZsR`KMvG-633%j+TWC;g6V4fZhVJGYY-5v9x={EflDh$2jwSc_Tzb{!0;pfv28bYnq*^hV;hZaCk-3hwr$(C*%*y&y!-plyq|VvXFoi%^W5h?=fb%x zV%DWSd@f*?yZ1L26#V&2f9BJ(yNmNn_cyTsz~e9d#J42JD|&h~*`lBy>eaCUC_XD>t4kjU1Vt*KYfjYFp zn=|I1d$Kco+e>2RggrnQynD09k_*8VVb-c73Qv$9(wC{k=q_X&y7!`ZLkoZmzJDbK zBhJj;JCz$7Amm1t+?puPg2@vKksPPw7BLea&0D%ao`U0|XD8=D3y2Z7u0fCi4~NPl zFF2R|UIWe~vfp>hYWv$Zzx~8n25(%Z`Du556K~}{Oq2MSC_FrznvU*?iZI6z6pGXF z`8}JWcpA`@Ta*8A<2vDET03ml`NpaI>tcnu1!k`Y4lVs+_Eix2#w>u%r-{Jnj}@sF zL)eElnpMOwx&V@4cQWB%I=W*mJ>mi(^K*?xe8!pb@4CEzt2S~A%{3h?eT~U1-xq2* z?kN#QP5AJ{4^R5Bs0SKAdH|8MQAL@l-S*1j5UUZ)OjYr(3a{*q0YHm{wa;Po6*J`7 zur)qoT^goi>zPy1Bpeq(BU@xy{1JsN!A8D=^`GIlmQw4rbvh-S9O;`;?yQSq5(~Ib z`ebAAQ3KFsW%WHF*VKTZ;DhEPMp}fi1;wl%$-|7w*WI;K!Xotxs?*g`r`Gm0$Eo<@;Yszj#^F%%_~x=JX@f|~^aWiU$x{g> zX1FN}c16;HXv8S)#hAj-W9T|?yj{{Hd>()m;HNeE)Qrz`sZkZ^{Vv6uj5_)U`VGu3 z$_)H#&_kr<8B>0jcb6~gXD^GZ{kt(-u~S)0Vi+~o(s#hzvC0R!AZq=xBE#`rpvx!= z;)0T9y}>}S4-jtuH}E6KG9ZdY!q7G61)_?cb=GqPz4Fn-AijlKtYDQRJ6Bd$BLo2# z#%gbKF8+}C*H)s{zpW}54Ws&d$>riZ{5U5Saho&46r3ycK(>%q3mQCEbrLgt^AUzg z{@gZUCyw5Q5{yvxm6_y0CTSl2QngMMrL>ftGDb&dhXC+WI``aQL)I5{@;Rj zCJ_v_afEoRS#C3+QEDfpnGXUxK3G*T+b!oQ$;qEWiQdG% z?vmE7Nq+j%SsuF}d|`?V7OfotSDCRH?LIP$XQ0s|T7G(8 zzZAGXpIkM9UdeNo0*4b@hH|+Dcx+Z1BEg)oa?pSNPXRY}ruR1Re#$ zCF8~SL{PjqL`=sNa4+>JuGmi`0lrK7f&4lmfUqz5>vfOQ_Xxx>Ly>y#$%jphW=(6! z?lpxzU%A{PUGvhuBC}zh_&O?5YB1Lh)@?URxvibyRsT>K??eZeQ3Sc?9xl7PH${5$ z)GY5K+zta}bnUA+wRGA*pEVxwdjL+Atc=~5=lq<{FdoTyvCYCkyxANMeM zn0J_x>u+HkkMOth_8V!H5HE~&?* zljRyluF->*>$eF3U&6frfc!%_ZoKSFb-tMy10RpooZr({ZMb4R?P{dS%`#z=^_Jqq zv8_t;=nIwg9h0q|P34E$o&b-GQ7f>C6)j#=xaphPjOvPIBtZyjDWihTjd?e%mt%O` zhyG*JLGmuRkk>ZUDOgtrBn?8KOk{_d(VfYFHz3X@;}lnQFq#}z=PiBRR31L8OR;>S zywtM}uY*3b>v#e291`_X2PLoHT981lRJ|rFvur%4i)^wS({_z>TW}kv=oEixRXwCm zAl94c@omZB(2GjwlY7;H0VKN`Qs4wc- zP@=h+^6lNamqw$rAEQ%J0+=pJlvm3kpk%%OAdN>*DE1Y~PpQ5xucyr0>C?3N>x~Y# z7>RBZD3W&}8e&kX_i_6*5d9nPY_6 zHbD2*psLd=RSz!xKo(nN+f)^rq!4G)QJN&o$rKtQi|F!-=)C*QXsv7`c}XN<%a5@H z8W}5fb^_k+>n+M`#72eblk=b=h#5ULrPq?0n?h0Xa?gV< z0N9o8YELUnY*1;4rg*W4n3gZ#Mokg@v|lydfW;d0=*`D7`Iamc@%Bakle{L&erl$D z<&~pBzM0Ie=0Yd z+xjjjt7XW!*4J{ai2tJsYH5-zPNW|%n%tEW7%|J|$SyJ(J(bH2b=c}%AWWPC#22(d z$8m}Z3J6wm*#b=x4Y;;6b77o}|FjDes4-5RNS?A6TL=GXMC^&?U5Dy})3P=f36_|O z&MT$zg|Lu?6(x}0Lc&({^XN%uUn0&2huCP{I^zUimwNF*wtfE-=0|dVG;jKN=kThi z23Yy(x`|_D&ZfbR<)Quz0XR@AKW+nY?#RO!|HU=+AfqMs!T`yFWu=8ncEiG1KeN|U zLh5Q10#iPfCIUB3dhmO6f`?JOYZ^1}pWD|0PSnWtABt%s$KsPwvod&krqd~&ezc=E zp0AXpkpl^4mMi!exy))pa~Jkd8+LI4b0XZ2L*c2~$_@fv#4ml%Ush>v0ybk^&DR*J z+w3OQH3dPUS_hyk$~^@&iwZYW`~iIZ#W{r$&gZ2Xj|o;j{Mf@L76S<2z+KOqTgqGd$QzeF{zeNB>9p`-jxOE&rK2OKI{8{8xwT` zX@v(z_Qw|kc?KRV21t+>U6u_)J$B)l*h~J{6sTr&mg991Cx)3L@N&0}PjTL!&BjnV zrrEMPaB;Gs#XKMXTyt5-trC=J(+k%UsrxIob5-!m27b>ap}ePTxSKz6)g-=?su*wz zcH~C#NEM4|n?^q>(pirx4j(o>>-3pHSiJKOD~m=@ckpP30}{F>7(P3J_sJn^aa#}s z$i2pNHt~x(2T#9yQM~l3Z}~_S@ffhPUTcD%zZdUx;w@EA;0v1U5J9)+Q8+xd)X0f1 znhsz5waq$^_j}kK2#Ilm#=RUN-u5-y0abcKW9tZM>5^=h=Ao|*@thp7Goy1bSxTot zWauY{;vdWi59&oEhZz_7i&WPvjor;+IPuG z$;r2eJvmc(AJES=$@|XQc;Zomr^~H_v6HY|&TdwEpDInHFD)AJ$jc?Gzu@d%pwE<4 zaOWqg2qWZ!F-aHpZQst^WA#V=;6TP}Sj0PHBK)iE(Y~XPwnNPG5P@G^eV0W+hZI zBajjVaCHdcr$}cAnG#>ULQ~`^hK%|}X;RnTvh{xe@=!wri3VSn2H{u*G9d989Bnc{ zdlOKBjgnMa`Ce=F;#xM?OwIzx6PebUbh)Sui!67TbykNK*@nw-=Goo`y!sc!xXn(t zCT9{#8s?%J#6fsoIcFTDN_b`n( zpQ>xv|I~wAX_Q`)&4(XbN1bc}g(+Z*(;^4Dm-C|PTqkeoBOeCc$>g0gPE0Xi4hYXZ za{pfoa4@U&2hTJox5bLpvtzt$N&^F*0?kUYs^`%hKShpvx>#B5bm$58ED z{TS;F{jXPz9AkWH$QK4H!^y?pNLQUK0bbpUoD+2C%QI15b~t}9t(*?M)$FLcWwW`~ zny_`Fv(?|C-gc8heYK?j+JX7s7HT|$!M@S{-56|yU++X%1AlV)d%vaQErJe@RcW+* zzhzFn$Bvvttc{?;WWCSI0Z`mu$4SXOk7fl74+&o618iY!OzR$*GxSe}*dXUhql3iR za*ZOTu!z0m^e3`H_3ol_p6bF@B%pNFGjTcM({)2QxqUhghAQHe5f4=UNW1!GygG-U zkP|XgUFMvqo~}$DBXTtUD8b)!s?B;Cacgk>m9l8D4vGdHuo z2l6Xguzt;u&xtn)^nQ~zN+YFl&9QjN9S8;naFK=t2<2jnP4dHsJ%BqsBTuA}FGz6P z?+D6eu{j;lV=?O7dmR?NxmNQ}t3I1-kF9*R(rIdIu zzS!lYie>z(e8XI6o0l9rqHbxadFnd$&b(p90$O58p=AX;-_cqnE1JJIkH<%DS{gl= z^WGT74%?NQ)Y*|+d`2)%Mg@Sd#hApY_eWx``s{6fCKg$tXL;*%br*y5fMrkt82ppi zX3V&QT8Av^BG002BH6vTDF*g@2rGI73MxsN(mf#!DH*PO1EB`BNM9fE(@%QyFD|^J zKGH^Qr2p#JKEJjAdA~zq_!P!=xl?`W2Go>M1keWY7IECw3MzYdhiC%6Cl3ofwfkT# zbv<2`Njt=mYA)p83n2ehaZy(@;Hya7`moPmg*K zTJY1lV*e103a?1I!%5GYxOVOVSc$hxdxDI0{V{#7Ehq53$zGiz6Y28 zFNzUxT}GcKLHc*|vb2eb)7Dtq)wxTC?w+sgcy<-an+&xIMCu8i{OFo`&{8|!{>qpK zlw-C3Di6ypM{?p+S%>KwP6EYQ@lrma@Jo`!?X$YjA$@8$pR{Ym4 z1(Pv~ks&ML$yX21F>JV^9Q#C#5*#H3$(?ee{w=sA#E@yjkH(jaQIo0VbZ`8yVm&x_ z#wbZ8HR|bc#iY}vJD7A$d!q58S)e37C^F)3ym$vpKC~S+xU_z!%dKP7kfv1$;pDw( zfI(iLWa#20TE*KT8$gZ>i6^ zi@l6pr4ALSYK8|f3-CEPldn@w7IykG#Zw-EraT(W#ZVc-NX0a@?Ma>hEGJdZYCP9J zG@Jql3hF8S&Z-UgGJQ`v@O#n-W3nzZ%NhO3V?IqRUVNa%qEtTs_~-%p-SLE_puN`J zr`c9MAp`2!bjO#;jMY{01~SPq9!U9bE|F+sJzJ^92NOt54>Zl`;h9^eaF%CE@7qg2 zZkay2eWB*G0PH=X(*Zz^&1L=q20=ZWQnI)Y82`fJ5IiGS1{)+$`Pz|JGKjRTt1aT! z=lW{G=RC7IQ5c)@~ z$wtm$Sq+8a%8IQJtvTl>qN1=n4k^JN{$ZHrk+2mewmke>OqZKT``4ry)yyuXYPfWqHGMB_-bDyzGAa#5LJl#UBK z_uap~YNgF%H1#+#$=FWamj~4ZfBZD`3bgvLA6FjL@>uHu^H(${x+KfSCTBZE!Iwds zTJdf=$DMoBcb=9VymvS~EkcJLqyzB`?3U{w;;C@K!q@MJFyJGb`Ed#LfLCnNQo?C$ z@xZ1c?r@y)QPdIOab|g-gXsqNyOe1OMN(rV81;;H9q3Z@K`%3AGbitE%PEO@-;K9yE_zh6M| zpk_Zi#NVB}ibf;pt@N-V!qpBWQlc)M=eK)hx8JcNJ zQi2cBvA@5;_YyE-NhBu6D*5l>q{As`+OfQkHE-h^%p-4HLHg1>R{o0UHu_kYuP-pC}26J%j?GCyhQ4 zx69)9+oExpP}7wtU@6fA$L%#WV%G8~Y{Wkvb|XmmwCh$2JUCe=TAvz-O`4L(@tn7S z!32}QaT~K7nv-TW5Yb*V)90;UO8)PW)fRqZ6RXa{QzSNjyZpD-9ipRYl+RcdYKFk8 z{}fh>egg7uT0;;$M-9(K(8MxE?`Mi%n3 zEf;)QAmOi{1u*ZowT3;zYbnKwEOc!c~ct#JO|#N%k(IE%T}P$ zP;IhQzf-OR_b2#%)4FMu_NF z0xP+DAyk^`rtVB1ZklAXyo{0r*oDco!k7Oph@o>0>;Ne%)v!NAq{PYy8(NvRq{z+D zW&Z`1tTn3r9eGTni*wR3Y~2_nKuP^xE|=K8+hyx<$gi670LceQFL>)+VUeLW(Ohj4 zN+d>!hZ(PsB+|)x5?62N8z5JaaA#KsieOU|R={!8=<&vsXtxBqEGbF)&2|E$dM6^L zpu4|zw7_n^*Vdm3-TEulpRTl-;pCPGtOVOG^^IzHj1etjOIQqi3?HIXumqp#ybZ_J#GIooUXf z9-F=Sdxv$#N>%7ZmEp<{f0zT2ml(XcoNzMN)b|7UZH2FypWn@f$r`(LIg=Vl6(D|m z8%&1i$kvWvAqkTQHGpWT3H3AYce1*RizTDbKKF%}vY!x#lx&A|_V*!p;yr`3i+^KN z5fQlpp$M~i35$4(Q9U`#u z3M&{Wv)L85O>Es~&f}epwpY%U3Ew&amR$@`Vwe0kDQW4l>S``3n~1NLC?0*Ww-D7& zY{tsmmX;N!FaBvMoCxwb|Nbt%(cyl9*za-8l zfW>kQCe&AkdKSb7W>uPRY7@)M@*<9kzig0JdqR_g z&q96=)rhyRENA>GDSK!lw-N5lA%h>u8R}juiWv_bkQW`0IY=9z@QV^1uYC|Mc;w*U zfN=@B<9`Wk-bP4)F8}k`fzxFqKt{kvvUmv12{WWeug?>2O?%9C_M>;{Nqtw|5K zxIFvSGAz(s{^jxHwejgLbkG z6B$5y_@F6LBXr=!H@xEc>3?B=mWL!fFwGgjUXUAw4b4ITJeQoG$V4P=fJNkqt+5Vf zg^R0u^CYj4PQ??6*U*o5H(>6VoC;&VYZ$Z~tn0Fw1UG@lVOWNZj4ha)vLnOc{|!saP6Y$WnMCEm=Zp+hBn{oDSge7@;j+Ix z{F?u24Sqs2Ni5$CwkRWf{}(%e-HkjWUtu!b=~CEk*>;J(q6ofk9RUxcfZ|7Sx2(w3 zGo?I_)xN=|vm*NK8)MHe!W8}4;os`Inh1sMDN5Y`Nc6vYw;-UtTWfbjjdb60hPnE; zjb#-AXkW~?v3x$;rOPifpFPaKV{u%1B?cb|%z0F@nr)r>lQX1;bEH!11HO9+r7lxE z-R&g~5q--bH9mCy?!dXraHWZM)TBwLxlvMYQlRYI=wqT!A5Br4A`#nwX#GQ&gjgIP z&@1`&-T2ePObRAkPz`65SP8=B+N1~~IVI$mJzO+VKP+QV{|{ycFtHyHIltrIe72-M z>J|fW>lTEOq!E(P-_Hr#TYTC`+j`m}K9Ywea%3D9I>$j~J0aADoY!1gudp5U8IQ9@H-}L?juh6~|=W?8|A|fL@J==%x?i$qCzKV>= zf^-2>po^M++U5E1Yq5{YbX!eGB~ZoUpNc-kGXT$}JN)rn48-7>PG=7N?ecoRz1r6e zVNq7%5D4C{7s#bE18~iQn_kGUHS&Vkd5k{3;gAWf;wmiXBMT${JN9OAq z(|Xf05yTFlbZ?nHsK=*fKrZ_*NRKn7kONGC8g^J8$JXgz&G1fLz4h$v3=eR=e~D5Q zmuxID1x83Q#!VNRGlaY3NF04}k>j^vFJOguF$>3I-&LKk!M0;gtpSi;_R1{vC9fP!A9%UjUz zdcr7hg-k?DLf4Q(Y?`A;En27`n1*I}o3_JTluc{vm(?kjZ^Cjb&(%!Xi7jqC;tPsW>nul=%#R*SC zlm?sVSvEX7zk{S}py|D~&`05L0(8!ojR;dA1KOR#kM?!BEHR8E=XqzvI+-QUH9#l= z?ZY`vJjb8cxWp8yvobyS`Y)%gP^BT$#M+zRMTLmSH0(Z&g6eB612kfIZ-eI+Hs8PT z)12+=)@1xFJQrP#zp@o@kE==cPKj+VMDp~jj${P41NY}IC#*!IXIy^an(%I2zRC4J| zXH6NmY|B%XVrMOmlx|{Bsz}~vdvB6@#VY*};N~Axt6D3S!!)p@CHO?&G8M;8c?!6W zzoyu?&EC$FR;9_#H$J{M`oKGkie5zulL%V+D@m_BHs0LdZfN?x@P&#{a-_%nygpUV zPH8BhgE#Vs^VcO7ijjD^71)v|A#Pr&RN=5PhC4tM*+s#0+lrcFBK0#f;l&~jTRkC# zMtq)3QThu=!%2CuLE=jm|2>}ZM11P0O#d8a+(!B$q;d?cm<7s?Z6Y0m{%p((;Q3L0 z?nqFS%2%q#(6h|q1sd1zSH3CZ5)ru)5>dK(j>?eTzRB}{&i?N#n>=$hlwcW!t$}~J zzWe-P0YN-`(#XVi$Z2n>xH_$S;YokJAFi&_R#BK9vXcZz_V=B8Q)$AMXe)NiLq6Xw zy!^@Q=vo@G++|U^#~wr1P9jcIcX@11LXvY%M1A)d-$JKC>@wx7Wf^9wH?kMzWUQz8 zY@d-bMhO9kzKS3UpRue%7`18cs(hbfz2PlTzz*F)VbIzT)Tl2?8qSf!D#yZ@nc3^B z{b*ygzN12HYiQpn+KCs4$3X^Kx=LGCR4~I~_&4>(g0Af-*s2<7H~ zYCb(ehsrIJg2nlylxF6mUp9o@ud&HYB@e95kuxMX=O@U0zQxwDLz$re^b8D#;dE;A8(#NQz8UgB{a@wV z5?Z-i_kd+gw^&a8w6|BSFv=K^b=gu%g$>HjTQjxzAKx#5%qlu) z2nGq~$;Mv;Sr;cYjk#2dZ39JsI3;|M1e|no`#WmB8g|r-1~}UpJ@tnz)ka^F?|j%2 z)I4lyqtOD#^&aJ(S>@%DlzB(iglozZ_iZ)@`>_0DZZQdpbNn~&wEUh+v_F-zenQxq z=A`J=6m?Z3_jG$=2KAD9(IEVx<}Xd%A=TL5l-Nk1+{gdV%y`Bn zF~c3zWIyH9&R6-!O@}Yh4fSqoH|3iXzHP=CYiwr$kt2fo_(R=_RV@Pf)eJA{ESH(h z*dKZ9ilVDF-lrmr(encQ|f73`x!%-ee|Wex#p6xo*bg@m|?w} z?d{75?)l~BT|BjGpSYjNUTt;ZZ?LJdxy{?qSI2zJXWVLuWwy}q?)fu#vj_kRn zBLTq|u6tIYuL}{=nxMfuU!NIgsm;+Vo=!gj;V(Go(suL}2`VY~=H>Q@-TP_}v{sgh zJBYeG_O&eC`3khT^@|SNF;m?7Ve;+sXRL?}LV5`#-f*CXpItY_*B>QFb0mPH4H{p$=GN)M#L!diz_CpUbMfadx zn8b-2gi2_{I9aoScZpO4BF3NY(SknvX9Rd`Z1SR`89t+~9mJR9)9Ta8a^xyIK_&xLM>GabGU4i#a3i=G}PD6!B1*3j^1DNO6^n#$5$S z6ZLZI4b=!d0{|OVCD~15FLnIjCpB=Qfjg`$LDT8x1A?(TXJT`lOQajA0A|_Dr_j-m zsi!{7szyhwyFEp>VdQz;DXQ>`TktRS zB>$DF*eRlLg_FSJJPbYL#}d}PdI32&SxFVC8P4e4B418uY7=&l(}ws^JCCAF(~o=O z34DG!Z!>4%3S%!Iju#NZf!Y5*(Y=(ygD5*O6Kz3rM^u-v*;FOodBjpfvJ)bx{ZCbN zKh-P$c}TyXo((<5W2Be1up&Cfy#82)%BdIZZ3WTMh#yXIU?s@H;d`bZN>EqUog02~ zzX{Maq90oh{Pou^@0f4ammNU|F_NZUHQ3l3%upXV&s-8Pn4y6yp#-3T%>l0R;w*X8 ziXCs%ks~*sRLa9tmpW|Nij*F6LY%8wY7*Na6$NT1a_r?LWOouSWat+G5N2R0c)dvM5g%og6$7+>KT%@(XYc%PK8hta}ZBn#gB zf?WiEbjz(-27Rp-zg#j-Rs{@#AVRze@;ptX8#7(6`H}`KovIk;Un;=KC{WNLXq<)d zU4NvH>9XPo(t6U&SlX5|Y=+;n3K-lMYL_3i&_zeC|BLban1dFbJ`O9gTH#Dh!ettn z>vt)m*c(oM%gB6dr3RYx>13rN*s3v{Cw&x8KR{nM>z?1t-V2nSATn=cK~T#kuc&Py zc?mKzH1iL|=m@*1jqdt&*nzq86CLEbxUSb`Pq>a40oSe-GnSy^Q-=)uCp8)*-P;<{ z9!wQowSO?w!LcDo9L3ff86ZeSk^(!aPrPlDb;pT3B5hc{@!l@uBrcXH4@Ue!U&qaW z3~=9d$M2jC6*<>XI-HLlD+szFx6{ElYU8D638t7M+v4f|S8g(e4znW&b}FG9D6aZw z+sNz&#%$zZ4artSiyH@`&w~@kK_X7FKoQ=Z4V;|mt6u-_(C@CXF|6G_+;eKTDoct< zNfYnZYi_9PsPJ_gqUS&7qBZtcx@_}nBIL|XDhZorb9jK_7m5?gV{(PbQ-bF}>L&VM zkFXD?*g9UNhz;^2$9TWbv0DrfEh`zNJr_P!WNS0WLCerOqG$O-sJQ>&5XbS>F-YE9WL*q_ zz%hg)y=Bqb%Bc(v)o`T=qAlf#>1g@y3jA(_m`)qiqFgsvts4|ii?^rQT40x7vu3lS zTDaKX&h%>zM>3XJJ|9mht20)Ht5>Q)5rMC6@C$Uf<&l4SjCXZ)eY*9IXhIq_4{~R3v^7VU&g@!Q@8Jie z@<2MUhSn*dMHmCM6b>pCNi|nka)1l8FE4iBdQ^=MR)jdx4^cky zq|q1>20!_M9}hI3^Znc)6lpS#-^juNwflJmq+z< z8Pp_#RTarotJv}`+v-UzaT0#=I!l8u%5GkP*5aBS_UpFY&MxRd5a#Wkn9v<5WN=7i zQabqi2Blk@!Fnh~YWgF}R#23k`YjK<1L?B9a*g)Wt-m$=?AMPzFV#M|ag}XC18!_W zm;Xj5R5vh1#?sb|bTh{nj81i8hoBKzWVGi-Z*M+(ch_B;26XI&eo($9Qycb#@ox8~ zp$VVM$7<=tWLAu>D14GI@xRQx{~nn6mXbIH+Oa;up$*jigk9&?5WG(M64vVm18+AR zX;QS*_lTQ~9q9WggT0z+caN<=7+Z`TV7``&m`-N-`17Tcb$}+~C{{qONX9JvxAThm zO)Z3}(E9Sz2Qml5RH@|T(;w8{nD{GFV3zTR*0b;<75d4dTp<~9`QV>T4F`k#EPo&U z-dFh-SGiA}k4oOIZ`A&qgWs9N39FMq z`*KkzGxlQZZ`lC(dG}@@SU5n=noM^<>l$OI0PbKtdw)(NELd_?V)IdI=epz{*^eoj z$t(DDvsO_%t=YxJp-nEN?Xc5I4oLQ3mGBKPkjC!4MY`LEF8Sck0}aUXTR(=ui>|(M zH>H8bcThWr!HbW4Yt1_fnm_7lrw~E*mMuFA=SWiXJ8*ju@9^kAveZXyJP;V6qn)!i zGABSVQHu`UD~}Ddx|go(SLP_ixNLe^?Dy!L7Z|Nb#*>MBAZLkyaEOy0AAZcy5rU`X z0f+>riv>Ivl7J*`?m)FIZr6-VZz_cet(SDACMb+BkY+tS#>K#L4>3&BNP*VH+JBvK z(`?~)CwzqmP}liZbCk!i z&9=p^s;Al>?CT0W#If%dI$#mGRoqlj!S+6cWF%0M)*kcnfN0UZ&JZr_G-Mp>IPgn_ zeIhl)#w$71W;iASI`Jqna9kLzIaJ>~UQjagC0Ec$l29g{fxT$I#60j>OD;|8JLJ1N z^n-I5zWwE?i3&hn?XjcL5+Wx1BH^69O_du!rekh_1N8j9y_z|7j<3n_Wz8zHL2r=` zrclck-zw5CxU(;5scfqG!SiB;aoO30&$ZB-h9OKa$v;soo&IgMg+{D;SMu~#IW>K! zX==OZPNQT6AlBfbY3 zC`FyiFVP1Aj@%{N91~euNf6$xtu*PwXvlh|wp23)FX-(Z4o>p9Pcl5j$dVy`I8Fri z2+ot|Akp?Ea!;8GGQ4u!9A}jm{ES9U^BkeF^v(oc|L1Mv203CuVsnsSLBI6@08*vf zF+bPa?~=KmOV)$B^Pb$SzVGlLOgl@+)KHi^>ru6y|1S%UGKJb}7Af{55j!=;HcR)N zZ8sycKK9~dO86>oxxpo>sBaZr(gnyLg?3+<;uvV@^E!!yM8GL{9sxXMl1KIB3jL44 zZWEmkLOaV1Zj;SoeOv(wA9MXRbE+U=8|dRM^$@jrSMMXJXc!%_5pGD@axhO8*+Qh5 zoTAD>wXKY0`x3(@-O9V6J50R@xGu4lQTM>NLqv=Er!jy>A9RAm-isLn%_7^E?jCzJ z7%xf&fK{&LCv~5v(8u3QJM4M(Jp@PJs zDk0pMGHQjy$Kv1|QoZqda1>%@{F`^QK@cA~P!>4_wKfg!dyU@CGVGp|A#q9}UU*JV zYkVakZG3TD7=Z&tSkS~$mF}M|4KCHk_0Fw2)~U)`%xD?&q$qW|P?-aB;xVkzjpv*3 zGcef`Pxky+<+G(zvG0$e^wv+7Vw%x5#$*y+j1ddJ)KEHw;ma`_Eqy6tfhEhw`*@>ztTB-7h=q>dO(d~=Ex|VbI zk|T*Li*I3!_3BMO9#yr-Dkvi!s-9+-JdvS^ylN}0U5t|DCto=6Yu?Cj#qsYXUN_ac z$SjKU;JBHz2N+sT5LWWKv}vaqYNGCPDu{1ngf4oXPs-xQ5-cmV?m>Pa?mA`uqn`A#{ZQ>WV7d8g!a85BKEdSK1#;za;0y>>9x#X#Dkq8@Dj;U` zU*(9pFG#@#f4#gNEWrRKtqQJAn??@-hO(a&J)PqdUx(;rzG-t`E4cr3D1DtC! zh!Sq6LpmcAdQ~JIQ#l1k8VDvXAK@vT{SRANm-%O}UK+k1e50xWl|SsRnaDPsG0FmO za3X08o6M~V^1if?1?hz|dfP}Y*BSUkh6CvOCIeCMYdke;HP_;!V&3w51bc17H`w~# zepD?z?(1S+dCJUZdjw8DxQf5${G+Cl*zaL_Ib-*3^yQc+2pM3iNc~XyDH}uAx@!u_ zA$08RO^!|(ZDgsQkGF#%X81^QO-A0F>MkL6O>tj;C(5e-;L*Z+o_U)c5D=#n4kM0>#QEGA-VkvK|l(+9`l2rhS_JBa}?<@INx31e3A|$&=uBE#P zwVa?WB6s^YJ@!GSxYZO%!;FH~ntl>apQPVw-sc$LC82R|va6alznJyQFRaE89tf7a`r3_k_m2hiRI(5@1|S6akf`Gnqo#8;@( zqQRou!To%ogH5R6q^xVL9w{`cAH&?7pGWAWm9Cq^w04DjqLKl41sth~Vb*%g-|(Lh z?^{KW4ZtQG^YwYX+kCxnQ<_O{l+9nQfHE!Bo2tUa@>>%qtM)X*&;fP94^GF+Ia_9z z%|+6!UfXI!xV)1MQJ)R2D)FfnSkVTE75&?`x`)lY1O|J!`LR?R-1)VR<+rZ`bM=#& zbS08RatSD=n#tC?trW}sRRwS@Y8ZE>C8IS_#3{<_lst&(_fy)qEzxB^4VUqhG1Kgd z4ukAFQv6+{;&_Xw3b_u6sqDOX72h|iXkQ2e4m8pSX&Pcp@OPRnupb_65oyVK&(IRa zmgiYiyQ9i0DvTb_x%!@;RfAvnpzB6N&YkHdi0&9HN@}?PzB@8ypruH!hd8J6%Vjfb z7nwKdixg_Rc6BxH?JCN3lfStY|1PsrpVuB3ajdt$OAOr}@NUgSJxFLiA<05*G(eqb zw1%Zd?jfZ#c0GhY_;oH1XFsvXmPdh8^|i~)xu|@7?F}O(`#2*m_*wTC&LyjSukL{I zyVSvNN<-Aa{8v0~SAXX^^m6nzG2?n2X0?o=(%=yQ`1UoZT%a9J!~N?)9B0iR22xpj3n>^Ww1HYNA@E5rT$ zD`(Xm{&{%?pZpSkUMj$9#_m$}b5TfoU&48j(dl(Q4|h8$O{HNqyU6IwCufG3g65e* z-sQ7f5$#`hzc%0Thv!l6{^m>ew+X4w%IB|SE zchok!7FK)o-G0Us%kE#I4lavLMDIGMwMwh_C(3?0;8~TCJ{Q1$6GcENyg*FMbSb=Wu|IA$woNKkHZFPyP0B5)2~hywBIGCs8_?cr$+2jB<*E|k-f9P}P{^SljLoGJC|66! z6r?x4v!w3U1dBW1QyrEkqtuRlvekLa^*exW+$@!#F;Oc~OqdO&_{9oz`_6dYESbXg zU=o(C#pI#hwBp#RIkGf70nid{%xUL_%1wUKCMj@pSPtw7sZez*6@#2alk)$g=__E` zV85?%cinJzch}*z;V#7;hP#d7KHP`96&Y4wxDG4s3>fZKzU@=u;7P1>|+(tDqC z&pr2C!=iW~ySP~}rB7;(pv2EYXlh-=M8(Tmt^gi0f^q02Slk`dQW@tzqoe*FL?twv z*IZKlDwM!q>=u5o$A3YLXc+->c#_2;`P38mq%1H09bV;P3Fe=qIvmdHp+2Itqr^c` zhJHm*U94fH9qWP5gb`ZPh}@~W21KM~O`1LDxdTwBaGcP&)g zZK1noQ&N?;R}!3m!Db&N-9v;5a3>0EYW*Wc+3embi1zQ?v;MZHNH9BQqa{jxy{It2 z)E{<##C(UrKjJdjPNiI*u%?`w@+bG7(i#MRp`4&sZ3mmfkgj8G0_tXE)PdserXT~% z!TNt}IIUi97bNe#{1sGu)ej~uKeb#Z!(Ops9vb^j2*sWt?U%ifO|2Eq?9X&B`fwhO zyYUx2A3UE{f_NWK!$p^aeH|t&J-T@5nbE2AhGF$FJzs$MOE{In=@&-EN+Pavbnbx4 zw2(kw{)?{Np6924q~JF$K2+8%JN#D%43fT=#E7RK!ASG(dKXJUUZfwK8%Zmli6&o( zg`R9GP0@4~J-0gIU)x)$*T*6DZ3O(5muVFJf0vk!%d>vOhkOE^m>94 zBLE(tOu8pV!|P#{NK*TnAW`dw#!36RI8I1&V-kNxP5WTX1tU!ufCEwkY%wVLS@0OZ zH+*6y{lyj4rIqY2UnuD3lhaCh{(Ftu^X*g`{)9*FojPJPkE{w)BuyY`vE9lZM6Yrj z!*#AJ{UVO%ST+#Q+Z?=mkyiWqqmaC7ab}H-D>_6 z%`}N>zM+Bs?Mn=KT50EiXW4*tDO>2N;L*&7Kt`R~EuD;?Lz?Srv)|apB1uL+M8>a% z#rGrcred$AGE!pRBwG@FwVPRLb8vHOG@sGQxkJvo4|w$a*lY^L?>K}GE2?#0md_{o zu8uvCoC>t3Ky3sQnGNRu%)cilXk-`=F(S`(&_l;O&dU7Ebk%Kpy^WVkJ#4YdT7$0W z(7RMy!-8Z|tCyadD<(1!FEOO6B~+{5ZVUfCx+_8P7fw?Fb)$x&vyl@4uf4eJAL<-5 zfx#lBm3{85*be12HlOHn8NZir3k_E>OK?hgdIyOts~!eHn|NQr6e+;8p{lzF(X!}d zT0*qFg)Cp4@WnlYT6Z}pbk<{!);^5Ro09}H>x`C6X_I;`Ag2cr(6b9GnG}zVY`AVR!dAq@@>?gTL$ypdJb@|(aXjD{ucx54Nmw${XzRR0q zOy%gpB3rDb3*T=oOs)HEyi8jrn;O&Ur2lbPvMbGPH_VTWUqPR>aw-UQ?(N8};XFUE z*&6Q107%riqg9XWT>pW2Fuq3o^eRmRK3lAY)_L!`8TT_*2Kt~(CA(rpEtZSM=rWgT7lp9PJRjem^nFLzlAE& zjby3}lT-IW9T;wc@Et2?_-O-&D-)r2u;Y87q{J$d9Y{QGvEG-D5bPpXV%Ls`h*A9U zRqL{nbXb%qxy6>(R$EW+!O?an2f8GPo9C&`9txJMiC(1x2)8qZ4 z!e{z9qi;kk1qzD|^z=r~H~#fezIjDc#oeEZ61LdRph_UantCjw)1MJrS&)f&9rU{e z#te3T-mwl5j<9hB^{sIN^RGg;i#N;Ipc5caWA4dnXV1+|1uGk@2951AT&u)KglQVN z{ctj7&iGdS*{1@DXKYd{EXP#v8hs-XD^CX3l#KEo~T)sm^L)BHpu{0zb5c}2R)8eG$_eRzwPPGXE6p?5b*RgV03g)sBv zJzQv(X_Ll?hHxe|yv<(IvTm*N)>IP1Ua*Z^#pP<4|Cje<&glw)Gd~K!xxjqtkSX1U zDLAM=f+mY2mk$(PYMM73talGxS}2-^E$QtnJsB*4bGy8gujte&BmU}j4#y`;~1 zhHoIo2a92zq%3ZKayThJ{PokY$0r%#)v*EQ=;V?hnm8@;<-7*0_ty6wQ`R_%qZ3uWK=u$%>unGNOW6-9o<9=s?_?$eoBfV z)X`TVFv;Bd{k=(GwYrl(*B?#@PH$o0_k{VHhoi3{(EZ=Ki$k$gBe=w;0g+-2_?<{A ztznUXuxYU`#L4(~`I~@C-crJs>&_fhl)qA#Q#QY)av5wK?*~2%g5}4^_}nxZs>m&P zqA(W3&}9iv7z;_wjxtr51lj`OsN*h70zUx~Si4DzTWmO8EKgFmV{R8gb!=YW4X?280Tvr&>`!mrSCGr%bnHKkTWI)@4HI>**fM{D@)Zdmr3;Nw%cC z{Y0+~Nin!WPTf2@bNw`gG02x?T+|U-7sAOZpNOt?oo$^YcFmW96V3$%s0D1trV^y? zJhM>X@uSsd{w!S01pf44J+UHb=nYIM_&D~37mM;ef@!H&}TH`$=_pMxwkH-4e z&|O)kg=tMdF~32v8dq+ggJwsN1gb|2&6|8om&W!>ADgl42~A|H{?55>N7ri*F>5NN z#$GvM6X&sXFQHC{eOQ-l@?%@fO=Uwtm$AhbvwJ)G`phFf9R8o1MYX{<0p*FcT#bOU zbE2@WA;~wi$deiel@^DI;|paSoB2imbd6}|h5Hd`$(;we^AbK$B@+)(xQ?^0t$FR# zDCjLPVjsE~p)Zk2Vm%U;m0$3v--gm@)J8n8PVO@x!eg+K+_hBB^3Y$u#=q#Xu|%m) zZ4P!vOfl$_XgX|CFO7pFxZkXLpoT)1X5G%IR94q+Nb{I(kl| zT9Gdck>AM?)h`bu;i$dFd8lN&ghMDW3=UwJ)DO>phne0q9l#1Po!{GvA`JVDKz3{GDS_$W?$uzURnSB>?-*k7?@bg4xx6 z^cB|Fr>u>08XB>E__^Ret-m7br^sK7L2Zjv=VaRc?b&_O^@Ax!Wm**2u{! zPVF|t66GHtAv4LHBKSnsf2+nR2ehiW`Of*zao+=Q6B3tcJXxnMSE$rB_~j-wIym#_ zeRw(8PL%TXf!@<>?t5nkoovUJ+@=++YxC3T5ANFd%_A}^;k*itraDoTfy5}RVQB6aIsrId!W2l;V_&)JG(6rX*Px}h+za8T1_5)!npHX$)WoY5#yHAcH9Rbgfalb>!6Pltw;(OYcp4`_fGrgN9D*3UcVgdJUoF&Ejs_JxB_P-{9O zrPG@)>%cz0g~4kN`;D{kL0X1s+98Nbk1=6z*BSztNA9{|j;_~YH?X8R*#9jct-g?d z7ETyF*|wCSCA=qV=zo0YKMHQ-dteAk&HwfR2EN>09Rv9?k7KPK#OfoUG3;n_@j+YNu|iLxnuS~N&jY0DE4%;c?rWPoly zVLz!POH)*7Z|3I|b9OO>lGRn;YoO~($6y^H;)%r)4&ov!V{7cf_`h1c&Ul{IGC;lotHA1#;q%ONIac(YgUc`}~bIV`2aF{cG zpnvLRf9@o`Np^UD_K^C4+dc8fyWucVt&{Q{Z++IsmD(%=)*NRU!5Dc`F3ny_VTxoq z;aq`LdWmI7f9$Eg>nkRsNk4`P;g4n{Xw+6BxbU}Dw~=Ip9UQAaTKlvg)f!wXt+*#g zWpMip3xJ*8kYJnv@K&$Ek02+SD@1%oXBs`i6OAdyzvq+B&E1cWS^JhX=d*V-CeR6Z zO?_&)H-?3E0C~fc5@V8T^-N-+ck@o)cbS8rp_X~PkyGZ7i$$@Z$+n=4Q)Ds=nuZul ziJAw;H)Hf`XbW?T_RRJ}oJ8idsOaZ7wmDwll>3btkjgdT_%N+Wu84?w%a8QZ zGHVl)4bjGup%*JO2+DIBtSmi=8$HAv2mJ(&5UTQhJ|YbuMPz@_IELhF3lZl*mrdmm z-bc~LG-L@qWV>thIWH85Ih33 z@b1%oeJ|k?5I`clQW-c|9T##nT3;4Qdxe-`oEpLtFyKy)u&w@`&?8{$jzCR?0V!L3 z$IKIFNXa3)AHs80OdiY653)Zf4Qu&5C`xza2Vq#{9NQ%)uu>;5D|Ax9&o1~)T1(~> zCDYh-z#uO#|F{vUfs>u`d*a81?UbHpZxuEJ)%|CJ8Acmk1&r0)7OTV$rTzo@=!9cQ zkKl>`#7!6JgT^qgDw@9zkmiM!-ux>(x$C4kDD=-N3-d(CQx~=!uI1W+_~Y7jlKsZ|I)7Fc-3i2@ zX%bP1Hf66@KZmamFuT)GtKCk5dr=-#5+T-)8C)NY1y! zKuh?EnesZc{`5LS;jR^Yj67TKVcTXvZhT4#uI?RZbZ~P+OjtzS#3aaIc$xn$23_tZ?k218Tv_4x&JNNI5N6V_5Y%e@1lb{K!XFHpj`BV$Zp*!qEzXY?C} zvz!=g)vDVcm=}_V6eMKih$flP8;YAl&P$I!A#Y7G{|0_`%f0W{g3K|#`j@^>&V+C5 z;JsOtl{FcYGrrn~6z2c6s_dps?EYQQ%=S8R0;Ffx-d`GTA53v=g&yvA9|uI}XdTK* zjh;sK7uI|KeU5n5Yz=g(d%xQJ#R?BAkKp$fjcsy#wv`*p42nloQSbA<&d;;GbSnD; zWNZi=;R3T$IrjO$rm)DboK6u60Rut-sxE<+M0?K{E!X4fL^B&w`loWAzAk(L($>Ro zuBsn5)b-LtXUl2I^p`Zs__F*uK+4UzJiNv6!YhMM z?NWbn@cmM~R)sLB(*i}7gg^{?Csu18?fjwSt#^Dfj3J-G&+c4cori;P4D{kWJ{x- zJG^sJrtXix)PXYosw%NPv6R3;Fnne0fFYgr}6C;ob4sFt2jE{R+={U*Z|dJ zR6f){e4}kK2Pk83BF^>K#=tIIUZfF z;`ohib1RUJlEU~(ZIhaA;iup8)x(^ z-S2E>*#*9%dh{-YgIkPETbwbkas)nct`(gIIPal@oigbw)LpqRH!o4|&jr{1UsalI z#r4eVG++7^=qluywI<iupy0?YH^08RC1ds)7|jA@B0+zvD|dT5AYVd{xKb zBlQOMrR1YMvf#(gAXHwKZc`bD8uhtPtlD%Ma zeg(r!X0NGX=EOS}iOIGh`TE?D5SgOLzFAyOL@B@Zx|<4ig_=;?<%Y&&X7nSVV8Q*t zHGpUI3RzV{&l?$EbMq*1rH?P7*WSd2_NB*Ahc;eK#Dp3_+odU$Jm^qA)ON!^;y}tT zX2DL7QabLb{hfBln!O``=S(re^UYS%2kvh%oy)r^8%fEMIYOW5z>8&dh!DWd2x=wL z4Qj<75PpF1f_2WMo*L1yA^Ku%9dPlE_t&1Ji>%3=X=j5O+Mq+jwO7E@Ch9o8?yh8tTDUF1QLuNsG>|g|gsS?J-1iJ{ZUV9lts}!gMntn~~ zdu|-qC?(ggtz^+R_aOU#h}8cP<=FyOeal9z?HGHt4hpvsm|myFo;%&O9(DG-Dzc_( ztZv5p%>M?2wwy)xQ0M@m8Q%QAmZdEedz07N$0|BwU35?Z_Ae7rd1#TU`nj$c##Seu zFB6ZQD}Gy*IZ;&g?1US7-<27x5?imh*-^J}7z`mg;D>Z9{5~P}^c2*ov_>CUCSu^- zXFVZ$G)RLWW>ZHzCZu{@sHFLGsE)Mfj*>B(Mzkwz_fWY#pzO9QfqN&+_}|0(*62sA zFn3*3eK}E}q(^st_<}|(>sZ}{wne}{0f>54`vucV@GqJt;$A@ex4g5bXNFqq*aa<% z?m9Tvnm)sNeF$<;#~Q-4tj*9j`2%`**SNk;&DlGt1_>KegEiXd_xiz35#eV})L@dk^| z9F*y@a=_?T!Z*AsNp(D&vW}X)Y)-pi#w`bdskAKr;JQ>ZwI_`+FE+dXO-lkCD{(gH z{$MuV8=)_t9$#oOS=o$r_LC9NX_&DsOa>;|r8|eTN<&@39gT6bM+p;M6IgVyZPCGF zk(LQnXl2faV-iqCUQ<3xHN98|Xlc;xAYDG*N1_F#+MI4*hsxz*7WNy}nPn=dwD|9M z*CjH_f{ZCE#53u&tO*p&9gSzbezvV}$K<2D$d>ghf^cJA; z#Q73}qb_52!z@7Ny2twN7t5Z@QmBPKG#%$k)#c>%5!NtP@;N%Hdzc}jU!2n$w}yF` zqLx7=(@QX@y;e?+4P!CMT@^&B9x*26n3sRky5Zn!TU`{3h@)B9u=h`0f?4qR%}6$D zv#T?CX?1;LZHUoqee{9h`#<0Aw2#PQ_ohG`uNc=tW9${3vr!}GNk+0kilob70zgtl zVT{P=R8n%6P`E=ARr|NmPxyd&bd0-t1ruI!8Nd4%6nPuTfi(jvYZbzllqX>*p$tx@ z0ZM^JP(yGlmuQc^`Zr~;ibzyI@~(cTdZ!Ql>Z8*V^`d0vH76KmubUt|Q)uom1Mjo_ zKBC&8HXnQsLg>-=ru#fmaQ5P0VzS{UnE69*0SgN&qt(cdIQk`v733OvW4n&SwvT}$ z6+$e-bkqfs>2@J(c^V^hmctbzgAESuHq{1}{Ti31@(DFl5JFZXqmnQJ%%lw7%e&u0 z;BQKPs5b0R^T6y0er zb%!8Mmw(-5=vCfz;&TrM=6 zOJ{KPL0^a3(B;zWYU4s=2pDygtbU0iG=Y+c7Mdf^))1RO2^q{buy|Tlb8Q@YT(Hwi zsu?T4#*zAeX zr}JMmUL89lvXh&eeVLi2?s$lEJWfqHA&DCD>^@{k8 z5g)1CS3ZgAb_0Gx<`XcAT7j;#qvGLsCqG=ZT5S`sfUEwx!BHDZIFtOeKF$;aV1C&Z zjxl0)tH=yV`nCA;5`SB7UQZ;KZ3+g~^um{&k+fp`X`&`IJRZbr*{s=C>(mp`&71h7 z_*Vju85d|ocC%LD7o_vI+&6!a!dT&Se#4W~DOZ!-QKCGFF=QU98EKlqhN1$e$q{lq zUbRzny7R_9a-zuw&T}6~L4f-MYAq=N(>9$arDKF#=SvI3wc>sHPG65n;sR8@sd*Zr z%qmd03GPo|JeSjt%_Qn$^8}y%o@s#H4m%XhLJFKS{Ed(!pNF;HC6~$A=4qZNGxEak zL}5Ivb0BE(L4>!nJD>y8qu+b*ZQNh+``r3h=hXAKHE2w}KtR*K(NT@JraNw)0pL1u z?xGVP<6Z4sI*l@=Z>ptbI#VnFYR#tWnMn_902swYK#83cDr^9~bFY&~%Vb5et%wP* z^?r2kljAq=6lk5h%2#*U+?cY3@D=AKI?4f`I&{@01V_GP8bp(G+>gR|ygTquv*ACz z30=brXv;o$IlF0*elTa~g%LwwlY#EUQ{aTTJVtDzjQLVo!FeoE2Kmt^lcXl5L6GN< zhn*WKL?k6T*=G;wgSmQ8uC+#+kwl_I1{W(Wlf2u))#XgVcA+Y+6xK8lu;pY|tBoi9 zx(-ha^ed_qmmJ3K4Q*?EE|lh3Ip0bK}q&wacd>f=~rEm{~~g|04q^ z-Vak2=o5ymG2JO3C{6sl?a*fn&zcAaz|qaw8B2$DFGW zGF9^AE_>*n?$C{>u^dNYBQUSk>X z-iyBCLhDU1QA-jj%AlC=-D~>vu7>qTC(JG)cGFU>raSAsZ?rhY!CnsVP99+z7vELC zedI#)>B9+eU{0GoDVMi(V+PYyc_JKV-#}1+0WT;m870N=-aaTEOxDHmM`kp;FTBt= zR{vMngpKR=aZRrVf1?}kzUtJNGpSPvQZggab(xV1vp%^X4DTPJ(MR zEDl+1@=w~7-@e$@91pK?EDOIPC6?6>=i*qYr^kyYLmOrJOSQ1uiG`aJl0A>?BGoyK ze;k(E;7L247u?sAx62scan~5Fd8y$Ut?=L&x*Lu}CORV5SDQOeA5bo8wZ)A}Vr$-y zKU6()k#ac8l3k)zo4EJU-`{TSOmh8u)hDhV+x1Nw8duxeX1vLux&I}X?vy0a7HeqL z;G!VM-sx($ml!3XvJ`b8fBH^Tg`Bb?jQ5aT+I#pw8Dazg$)>L2F!1WHhnR$roRre=TORi|wrb7> zJ7y%#@Y`n=VWOSPD@#%_&fX6(hLt>b$JnZBuDD$eg@Dg~PY$f>hhG00cnP$yUn3Nf z?tX))K-+MzhdA5a3MMAxH;00V=*(u+rh>66FUmflo11mgCB)l0{n{+6fe|k!_w>NP zC$vzhSKRHqP@Rg#3KcvBwc3BN`@4KGuq`wAkL}Fk_72(bt;73U4t8RZWPQQTh|(@u$Yqu%_NW>0HlEjnP58C z4OxSD$vf|!FibDK5}xLI$~&8Sow(ouyNk2;59bEMmKjxel*FZHk_2~L2nGSOv23eQ zDeWwy+sxSEQ|W++L6t}%W$Lnl(nKoYAWKy3&sV>j35t1V99wPFJgl)Wz8H&0-U&9K zNgPLavX6$K?{;JmS0vA|=SNeQ{Jy$4K!WyWE^mn#Cp3ng=cs9gk>}##cv|i; zOETJjWl7B4b6~zBg15!J0(z6q@k{=cpyZf7kk9my@*4p-%q2&1E4-Uw`puTIw9N3~ zYFCks09EzijZJzX2*FWi%l3r%Y#5f{M{BuY>#ex0~zk1qOe-q93e5;Cz2O)N#eo$DwDEalbcz5}ybn>aj{MRruV%N-NK@~s3vosT*Y?zJ27@z;TI zMDHA{W0zFd2Q?1t|Ec-NpC-?wq~GH9^5|`5bmCTE4uhi{n@vh}jb0qsRY*ul4SEBu zFa1#5)ceVC2TfxgngRMaYve=X5|NlkSmMjxNl#V^B{aXp)Bqp@=}D0;)%TmmqDJ3= zerTTo4La|6B8TSK_U4X^2qu#YjHJ7_LQPrbY&KUhxb(QRc9Z*WGx zCTVoDeeMX53;TiC$f2_gqIQ2kSr?xjXnU;lH#)s}Ym-B3A4C$q=cGrt1jspR+iMD1 z@1Ff>8`ag`DMy?xd27Ri>;+=g-C(AHt*g1l5Vs{b-3p2ICw@#92Q3e-vADek8n)|g zJ74L<7%4N9KxrDv+n6$BwOUrftF07$R>GJDUG<-Iy{BtBUE%+!mKErmB%^m-2=r?R z>I2RV-T(dYTPqzqW!hg3~p9**d20JMfSW*Y~*5 zqvqy&^w5&)zmg4J>4$lF^d}_YgBbX%72|ag>4Wz%E6fdDKNJZWOx2exYn%3Ovh;?Y zLHYl3PJtRq-Kc8SaDz7T6=J<*OEB46AK0{dQW?yt~qq? z;&n0e+-?CcLxn!dwG)I*)8o-Zj`}-Tg}vC$AeGcdSFI!+f5dKlwZVg1;n89xgV5jo zK5sLUGkj^q#Z)9G>1`%jxUFSpx_^i<{|nq3(!;#;rZ&S^O+7sYjhW%lZ0t+cGpE1K zDny*7nvHAzb%kS3H^f{4_j!GtLVdz9iq47q#%fu&*rcD=%}V}H3t+{-!Y;)t9HCm@ zARP!-O)6@)jur&U=#ksk7p~3b#}e9zS0?Hl@Q_rr4a!dbm`q z{1e~sk+S!CBd?9+uGQ>mXcUeSw`@*W3>u}?ow4`Qne2FFpS{SpmfA|eaB|n;&zsjz zEmx%URfhw<0f^ISas!OeY9UA`V-gqMHA%u|>HXj0(zDFpPlLyf&C9O$9y~ti&R#D> zW2@NrJ7;)S%}Cj@NMJlUh7+Sk3O+Xq?ik}AmS-0axWAYbj-%vQ8}{GTEJ0ekcW6Aw zm^_>x^(P3&u!69w&bg+Sroz*?rEL28)@T%8sh~mfD%c|S+`~2f3Ki<7*Fu~~TwDG? z?onhaif(3}M=?k`ND-^*xxg%PJUeTou3|n))v9&Un&mO^e=h?gt*zJ;AWdvl!(7>h z@F$;U!9oS;tDD}b`BzpamPL(b4hIu!4SsiUj-OJhxU-<@CUE1=-$AKAP+DFG-3%az zm*o=~a~oXvgauQ7pzb;uzb5@%(3X``s|3&t>WXw)(%SvL_eoGUeWlMBQGTaHOJ9Q+ z3d@~TvIL0R@jF2j+sv)=-nZ%qg}(n+bWkXrcxa55PZ^;<=zY{$#Q^O-bdC2_33?Ho z5h#AN(EQ$O=BSGMab|}vOUu+Kbg6!30V>6U$~B94;1HyYkTe*iW+JcjHg_NI97vhl z{0K{(ik-Ujq{lNd(hWakrk_;;xg>IV_C6zd^h7LIJ;cyLjq7Y@!qwJ2D$!l_xqxTF zgB;j3rYYH6M?&Clf*fcpD_v%%yJ0C6(b|9AMiARC3=?0Glw8CHUU#}+I$Y);C%eJ)$zeXi1=k9zui#5PE3A6+?f&e? zcyX5=If~Qf+j%_bcf~~dRt@@fsDFri1|bT z9eNPba&Bz-hqMqFCmQU_Ir7||T#dfBh^BdGF$mirh1MXEV!hGN7vdv}@r0CnZb!N+ zm$Z(EixTEe_j_us>*^Tc=L|c}1yoMq9RMw^dfpczp|5;DSxxqlL{4~5I1*Okn5!)# zUo5Kcigki?eF3KfU!gDzTdWx3qd9WnL>lWT*HOG*Y!#?0Ux1NUjqeZy=%1Oq zM>=qDhW9}Pni4|AUJz5-PiNZAXlZE|78i*D2-CJ}ZyuQciFRw_;SrdgTyiBtr2AyM z;eHr?EYuo2g$g{;1mqzP7ucI)Fd%_6gfe`DCozy-mu0$HDHjh9o)s&ykZsDxn;T^f zl+*qnEjp#6b6I}bz9SXuyQ?yKWP2cxO(HOpcMWsRnLplT7 zvI!phx<(q0Im!1Ts#ZZ`Dr;Dt5zKDbu$w#v%~V(Qd5WoBOac$vI=|TZhudAHo~bp? zMw-}3?ug0cu!o;icikbFg370YirvJmL)=m?3Jq{ z)ECSv*$h04Q4fJ*S2l-7FQ3dT0*;%wHa*_>jmy%L`~XDeceyRVcU>Z%66my2{Tfs* z*{YoKPjK2EKvZO6J+|-x5zuy1CLwYlumg3$jnK56P$&L0{I!<+bp98R{+Gdjn!wQa z-tJF-Cs3tXS|hLg#2iuf^cY90n&+i>@pT?sMke>%QoC zYe4Op_Za{F_}J`M3uQF0C(r-_eU4Et2>Q_L=YNTWQ~S{?-bQ%sO7Cqo>U&~_+SijA z$W!havV86= zCT$;rZ!k#YRkYJ(U`9Ol=%&0Da!Oc}BDmVivsgoA3KcXPn$O;DB*rcslF(Kn5*=vZ zMZf+%#6cFDEEKV-J`t+KB6^mAxgHj(RyxGmx|~zblTXXf+$?H`RonVk^q|o>+6IJg zED1sOaXs6$xRB%qoos)Ey9vlyp4zO9v2IA3|&+i@Nq#Q-EQDx$k z?!+B%PZnxE_nH|$wsQRBH@MPri16u5_%i!{L$iFx$H#U~c^`qe4KRns!%pT#WZTAl z`)r0iaIZ%-JUc1xst7CNu%_5f|_w=kfFoU&RY>&x_tlLJeDhEwzlumiv=Z3<9UwF3sJ)>Nwj%zII;s~Z~@by@X z{rta9#xkYW%+nd;kMO#iEkGBO-q32LH3!LQf_uj#x8{3)-rGoq{Ci`X#-3K)hAM;| zjY=C`(>gd&0AqIja4Q@1(XT25K1-!ellkGxTMF(zXsHi&a9rN51U|Wa8w}APwcWrj z-*bK2Tk9=Z$1)b1*NpbY6HNhd2_`qNKwKcfLX6LMX>*-2!U&VCJAbkoQnIF0# z<5gj+cwIMGYUlR0$@QI=>yH&8iqX|?`Gpz&X?akB=E~G!xYmgA$mthiyE?%tWxFX3 z<#l2E@U`v4I5U}W-&^P2>DD_<)6*9yhgtt?*P;61+~)1pZAZv2uA8|KzR>9}-Jp%! z#I@CiVe!QEOc)pIS1VWm@u#M*v5$>xYZ8Qbm?GFai%{nAh%Y1kG*}w41Qzr*w`r?8wi%@wJ zrs36>=7RzP%ICLi--B$*!kdRH|2DCV3yxKU-1onE8;+YgKrDgxiWmN;)77eG`4 zB3^T6Nn`95~wnt9fy3cfX~-o|2%#E}w>x`g9>n zhOuY91?h)afrF{;F7qfSGxpZMPVhNWqzWxn$f32M*W@?u_X&#-^~;J2^&4Rz8d2aJ zVMovyiHn#&r<#hkh0$hp2T|7D`%1vgrBJo##{0aXvT34qSAzTO@_@O8(+UEq4hlCN zN;6(^^9;En1NE3)Cy&bY1doR;k4FQW_!yg@#lfbP&CeVL*{pADXApr&GhZ;Pj;-%AW3yEul5BVl>yU>o7)oIGn2)|!+>d{3kXH?Kl}KdJg3jf z21Niox#a{|S!>3gniIP-=VI%Bx^m-*5ndW^H?GffHoB%a)Jzd2Qat4-4gvn&YaISg zgDESAzVmtld(KMJerLBMY|yi>3~#BaDaqW#Ctj;1!s#G&yMJRnWsx*>=rqu^it*rx zcyp(~=Cbb1n%{~!x;P{}z}oPHQ|R<8wzV}sHj8|Lp=5wkFN+m?>9hYZ`U2XD@Y~*a zYv@zIy*COKq)AXomS-Q(RhI+<^7rkNp1(jjd_C+K-Tng~C(WR5A~8KCL*@IQLArp= zquH0F>JUwBqeR6Ve2)j*(;gbvke87@$?9k#%QEc|$)66*_dT7@z4E@(paxviJomwD z=jF-3JG~mOkZ&lsroYZ)r^DC>Zbl{yxsB|M$X0;zzGbgcJvc0@*}9vvX@ID}T^|y_QN2MFS zl^I^mG%vYYQ*c?CzH~&7rAY)#A7)ZYH}m?_Nx=1?QXAVlx6J9attQxn!1IrowA4x$ zNl_PC7h`{b9C3FYiO?-fd7SpO6M$Fc5n(pPi^&UCB)W`8ee7d8Qn5*-q}#+6qovM@ zAFoY!D&%`KN-Wu^>1{5$zx8SDd#a)aH7OaXJn&V5)@$Vf*+~JKzfqB-HA7O0{~fbU zn|`^jy7ROpgZ>Ik%Ln|b+_>5OvNL0=);?$qy zKtT+THLxr-NHh64?!6TRtb(clreQmCx+C z$5VgkT5cUk$W1dfE2bOCOn-ePbcqzGDRGTQL_5G6bnv(6uEgw`6(3#LiFi4ES*0PI zlT^cMboB+6PPzL_i%q6X84yJkD&ZF!wjDu?WGq&XZ0)aG^l$DAZnSvt4e>BFb1|o@1rdC zetEP`4`-`Uyv%MDH_mPcoaw6`ZWmh7Jy=*WJ>`g|T6n*vi#(j+`QJBxIy^E<{~V~W z1|nG&>{rj6%bEhH?nPf#RvEcCk{cBXLHTKz#!xGI-KO;Kyx5KYa_ua!EmD{rgd|&! zr?44!BS!|LhyNJ?f#)xA3Az|y>E0*zx$CJiI}Ww1-5A%F?K~S z(Av-V>8k4e$dlf#DLaAyXhFHpZ|lA@b%7VWTku68jg%}@H@~Eqd$y!qcq(5ZHd5AT zwvtR1yPDP(#=;4KzimpdGPZT(Uh2(0uf4QC8G2}cKj&`3tW-=F0tR&|h}Rn8E`Ka> zicT<8a>eP_Jle;WW*~av`e3|8y^XOPfG}_Iax{ap)!~qa^&;POa&RLvq(Yh&^9H*7l zI!ogO%dWIA-m*58ZdW3P{*4!}Mas@650dM>D|eG)S~xW2AcVXKqj;>r`=K>8!*yx< zRBs-dC0s!yAO49~&0hWG$O~d|^=2^44d6Pan=W{HS$H4+ev>1!?V@t8Pr4FO+6|;!nm6SGv~iu>`MFwtnse_!x9w%h#?KYWK)o@{ z5493slR$5=_6RWw2vCfNShP8DKw8^1OYDVIps665Zpv#}1^2UhI+N0PMvhIq(j+g% z+Hkq=^@7xLBIeM{j`qeu3l`esWE6Cm@s_JhFs>VOsezza&8_&=O?~J%!(J}qcS10c zV}ZJ*x%H_w8p#Nua8A88WHhB&Dr+JGA}PE(E3jU2?TCJ_r}!-Jw33X0B)5Msx;^lB zUT1uBg?&j;6+%}YlvQrGfx;PF2&fOBk@>cCEMA=F;|)5NJW-t(U5D{8*%;P~Hz}pD zUc>FOP4k0BzAq)$m4x}vcST&+pA*vW#X6}!2m{ClC6H&WGxHP-;vXZVgO5Gkdw#wz zpuIC(b+BjjOK<;lFFGV0WC5IRv=TSX^h*IW&_y!5EI6)~LH_7I#=+ zn$9w)&2Edr1&UML-CEp=yA&-}+`SZcCrByo?(XjH?(QKt6et9j;BfQ(xXfgRNrpeX zlXLc7>)Cq^vq{7JD^vYG2jn8{o%y?hYM5_5_0NZ@#N8;5Ua4(`(UPBP*^9}DU zgQD-{!g+r+mg8YbEg<-c{(G!`3|Epvog<|3#;q!{QYHbzS?}2u2zrO=A>`7J+DQa zRx6~Xh((QCSYf?&v&U-)_SC^?jHhNFsBF*k z?qLKCoKDH|lkYC0czhou(ozPJXkY{McW^<(Y!G$=0AC?&`z7hg3C}eYM$xClFu6M} zYHXAvKZ>Hj#tInQaYgrfF4>`pkENXsNr9iuuj6G~!jX(Xv zVENWUEXi(7doE@r!FCsq7CtPZ6sHFkVqw>mC+0PG>Ii%RjqXD));r(t!hltWJw9br zRsWQJpVUwnu{8?8=Z|Fm>+lEk+-F-vDW<8iQzSy5cX_&3N78-l^05uSPp!3lg*^Cy zLtk@KYM0|)gp)sOCMkCgl%CxP6Q;`9Kl~t@K^MQq5Q>`onWpwEkxx^I0Lls;ewK5y zkbMxD8L;@Gii0B(jx4H{UDFkMTwFRKD0YliOpZJ&+Of%MY(gkZ>D~Ew zzdP>uBkzYCz(9i^5GoTnYwln2Q@WZ#*j8~$ZU-N$4kkUFc)IKqC`VzYYC1is_uL$P zyQ7YTofrU1^J4)5Jx_kJ(1Ux^gB{{mW&u&&E0*9m_%_COF+P!QW(d>c|5QRGhDFYP(7 zI_-vL7EZMOD--H`Tdds+1KdqptQ#j!`ksAp>eth`dn>!)F8tGWdo1#qr6C#85Vte6 zvoGT7nlPW91=d=g<0`n#gqw!FfkI8loQL%S>(kL5+Y>DYp+M(fqKd0O@d7kIsY?W| z$|*$7I~OD`yAE0ze*jUeTD{Hc*6=TlgW1Rm8XE#IjJ)k+$5IM$>xD~6Jn6^6xKo7s z4nJrAgW^4<8JkWO0WwP5mz8RtUT&UZRd`^`)qZ0bx(jcUJyAk#r3L7S%j$ZPYOzW_ zb}te`nsxvb?==(l-E%u5GkO;BtIo~h?k+gj5^&uv=)pJKU)ClwE^9dEDVi*^#+=t> z5#$%Iwu)r+KAbg8?!;$5UYx7k8Quc_Vdyp9cb3ID(7#&u3q4I%WJiAULViKzf#Y4g9FuFp*;nx0N8cHh{Z@B( z;V*WyoC=q?#Pja^<};0Rt7*CWEf69OL(FA2ZptNF1`9~dyAPVkRAj!XKc7!-Xi-<> zqi&y`o}#uOsU2H*QEndkJ+f-S!J0rDR2v47b2A`9K*;xPCGYqw|}#Z(iq_=H_L>5 zh^xBA-Q^%IV?}o6Ky=Mg325~ZW~!__J^>BW1)<*b3*c3CGHXMAIvojn*|Wcf#c&5U zHYlTJcr2MB7TH#a1lFtLA1svAj2T-MCt&;78gAL__2n(zIuZ1p2Vm_m zxEUzUb2{aAGJXUi-pA&w!?QQa3tbr~?>C-fI5e4Fym?2Ya-T-EsAL8ml}~A#35_jB z2OI;qP~DhUe8?;$2GV%JZPZUtR5@?vvn^-tr9L%+MFl>k*2*}%%LKV(oXL318CIKVfPwvk ze&em4gxuKRRDrvYAt0>@U)f_R)twg6SVa_YfO)&%O>JdR=wNyxP0{ee#E@dC*aN&| zgj;5AXY4!IJ0{G;mq!{;Ep$%|UByEwfW_v5D~+9GJ&EFCRp>4%5ro7x70%BY;63u<3TK`P>eH*wIXSWJ z=y2!c;gNn)$huAM!k!iy9VASA3tLaJ0m3v#>7o&a89yAm$p7XaXq+WLKiTHTS z6N>?L&ead!Lz2lG)ZwIoe}j#2RMa5JGZWvmav!I?vv>_A&f0%8CsW?>gk49K?Y*J3 z`y>qP{&U+SX1<<8RX;ZB1V4inAXs*7x!4KEw37XK$p?;jCD6MpMbQus?T=8=zANg2 z;2t4&!pN$*6RhegKdmD=eC~5nh*SR1Q?L^C`QlYD>qa8+im>;1R;gpJ_?scrmR)u^PCpBZ=Q}wVpZy?L61Zsaveh&K$4}ZnjW)uEsjrv-9cR;lh74o{k zLLvFrbb?PvJ-FJ9B`G~UJ!K&gnE4;v+(-&Th2?h+ti70xEGXSU{Wj4)O&F_Y$w5~-kGIKs{@F&pzj@mZROtMCi;PCC z&>+l44NQ&yvj81rJuUl2j@pv%$8S1d8#vazy1=(QJYAxrlZ>-MLC1-YfimvY-b-Cu zMBK3+cGzC|0bO%Q%k})pte6#M;>*_0tM=lg4f9IvVS!4QtI{=ULExU=jtJ#aQeDxG zfYL&DHN%KyQdschFa82Mi$(=+-j6z%R=7Bpg<)fN)EHW;t5HRg6_E7m0FfRl2Sw zS13o**^kDi{mvrzhuQ+5Av%@4P(aaf^!s3PHu~D!2;NSI)k65l`SyGLrGGnhgIzSH z2~R=R+EGkubh1;vos*=9lqXB!T+Gjd2@TsVTg=$e!e{CM8+@hy#p7;E+7ch~3SU$+ zGqV@-ci|?MlYXLEkA_6*u`uD{S!#2bh0;AL22|smqxiDx$kSLs9yb%_go!6lF5o#M zhQ*IK5&T^9fP*YtK00{F`0ov!9kZJIx@UN$UP_%KlNGNbj7r}&)j>Y31y7Td+eN1; zI@hc%<30u|j!zit8Y`n8MjjKE0Ljj?-dsPDdZ0Q44=;?R;X%CiY2p^%sBpE&x6xc^ z|3&G99yy2JKKI7QOPLV%%tfSg8u(|cN_rpMnE&d8KJHO*lhsJ#0)fWNExo7a-xq~s zF3XCNj;=AuzG{S&@R~Q$3Kj+8P29RIFsMUgfhY-$*vQo1uQh<^6Oc9pLm9}*kVBS2kIm< z4vEOEl6dBo0@H^1>N!iY(_LUX)f;$-0b026wdZ9_6Bq<}#0!jUQ1M0JRIAA`cw~s zs(5tAfV6#UO!n&GZwaktc{Z9cwhrmii$S1Vobq2r>Q(yf5%u-;vSgT00qD8lhXKy+ z+TFA>+&WwEK|Sy|sJ4CQ)ermPUeR2+OCGBRdQM#6OtiE>P^TMLuI@grwQ^JEFvfrD z?7Z!15+QgEji?iT8WeOgg@uz-W1jrQQ|~crh(`MiZn;cn>!B!AFdd>rNPx(Z*+|em zf03f}bGaWi))&r8)xHQssBYFf&e|3`DnMWr@=6ozO<&Ct*n}T`^_n{ofAE2Gag|3>;X9u-a3Bj`h58W{P(1#e;o|e;#y+tGE z%Po8A9QQo5z1UJLBE(k{#og`7d&}OTAY; zy)P(=-(Fn}mofCC5=c^E_DMTD*z|HlDq^_H$Z#Tkq4(W+E%%fLxqhta_-Ov)WHVvM zP}c}exA3+_x<=vQp5U*gAu|8v;A|{ti!JrWdMCF5PE0%cMoI`5@*@Q}ns?x-cv}d` z8nq?}?G1*y5@~Wvhq7x~NVL?}&|^R%Xd6F%_}*o7a$v#}dOqZLYu^^)Q%St_l+_qc zLCzjybZ3+*=R#!qh$SEGKZ0AEK&wWQr#Efl6^G%GHA@eR7My4SFw`@G>BDz8($rl2!pI4A+w9D z#f>sg_FW?_uQ%b*_hc1-gmG0It>C7&4jU0FKcz5 z&70wy3(=AMiPi*rse8#MXY_KtufR>%N;M1U%4sv%S0@Cs=plZ3bsk*frSDT<;nS$T zH{E_e)|832hir04fNoTC!jc7N)4RTw@*rZw+Rwt!MwznGzxN*(MRrX5`Ua70g@d@HV?8fau9s0T>(fijG4EZQ5odpmm zhmBp?3$u`(snW~*%?EVz{bE(O!iA=zBad0Tf^D#dJDZj&bY>DI zS2g@p<>g-YQgy5`aSoIyXaAnF4y*c=x9s(wVeGq7RdI*6(?67a(eBV^89E)n0*mfZ z)v6tW+=)60XnyeS?0bL#Lm5S?i~S;DDj`mQ288sP-fJ7W-LjNL(SUdHUN*)Xn0x|i zMjSeyI&0QC*4BtOg$&meQ#RN}V&DnKPWCGJ8PdAi z-^mdEW*|QdufRlNMj}3`tSeXgPTDCE-=dypox_nG0+$^YYkQb0(ka;-KMFtc8QVMH zU{19M@5vbanWgICm*9^LcL;MJ;s*W)d)X%E4g4w&TANSd2(~t>kB7gwdr7r_Ll^W9 zsbk-Dyh5G z%!y8|0=TOeV`k{ymD%?4qWyA%J-tUBedVz)s=sXMDf+#Gd8yFX(h|wt+xsehy#WUW9}|*Fp$=)k8QgO2k*j>`1|@$y5FwRFL(&a5aJ|${S^Z|{%6)*!8nVqTvXXqIDhe_ zaLudfb1c|L?&S5mUFTzECc7p+j@9&gJ_196!?pT|ZGWEZ$v#ok4egl+7>Ecz5}fc9 zsV=Sly!muWT1H8?vPIxi()=~ceiJWiQJ(f!qRg{_z_gM2v(js@K+hphGE|DFdl6%M z%Cw$@7GGTN7u%bC6Z%EWWl?L8gN}*R=v-kV_nQoCNgrsah9J($S28n&lnuHv1)zmI zLM`;l{2NYQ(t(knPsxrbl%chB*x3DNW4-HRv3m&P-BI{?!2JmJ zDOYv16 z>MknE{Vk3dYJAhhO62)NOFq&>3wgD=y=bO!7xb}zpJnG>mR`}4RZX?{mu3CCn;y10 zp=CHxPrOU}@BQ8^+9s7fjA zb`dYhHfVnr-DRf^WmhHiUGi`i?}1&GI3r0F7ze?RLfWryd;4>(I{((0|DNm#8DH4R zb+sa*97BGALWMLpR%3d892}h7>zsPlX0WZ2j7_3--DgmWz55A1-LpJ|cdR%E!Vt?A ziqQUo5vT?Isf+z^Azp5-3=6w^ItbNw43m3*Nkkll2Xk63*D zfpE6HV)Zt%W&<#jG);{_C7Q+QY)4dB`&1=uu#J4za34|dW)gI?@QeAEBRla=e-`LB zQs61revw)-?DE8xlUhi$%TjZMe|_)dWSCUgo3_CMTDgyObMW!;S&Uq-HCWPg{zj_R z{I5cTmih-f{b-{Ip^hp%n#ad{(Re!M=i@a97F}DC*feN&x@GN4lq0yxtuF@*+l!0X?Sq&P56G2j``qEB zB^E$)h1Zq+lv&zh!pmbl{kns-UaY|a2yHSiQ*`)Z>`qwSZ1Gg``BdZ`$BI_r4_tRQ@Bgg zu#Q77K8W}TGqc1}*ISRY^bbuZdoK1U~q4R(JH~z&SH_nSJ~|3ZQ`TJ$||<# zsCm$&IsIcN=gN`<=`?ndJBmYY^r}Y3ee6T%my$JJu8Gzsg!YmPOajdm4(GMx{N$CX z(#FJZTg-x{X8NX4@(VY6Qj1ma0!qbsZgrt0^QX+FD}<><2!Vin)gZ`dyIrx8IeTbw zLHk@n8+$3w%NAnGuzh-i$_xv^ZgKF$>;~SlG#2$#St+&61pz{^HK@Nopn$n|Lu}ch zQUF^SL8l-S&017&Jw@BFB#h_1OHy`#@pF~8)u_eKadMCOUc2Nh0(BG1(anVR7U#kM zk4EZ;z5DH8;DPZFZELbc-Q3!nsEE|j2*O|Kz=syDcc*J{kT02quCaPq77%sYKWv3X zkH6P83!zu7zJjJt)tI=(_lBo~pjz4$??R84mI-YfUPrsBh$LXoL7?=r{j zUR7MgtOXYMnns!b%*A|MBn~bzX~6N}^K%v^9`t$cL4iI@rp#>svm1JY{Wv&(n?xJQ zLc_i?GK9N&KhOHZm8)a-3gMD&V{Iz5see~JSUMNt3{%UuM&>O!`Fz$C>E|DJ2k__M zIPVq?*Eic?lcz)%fL~O6@r3=IanZVC`6uSy4}Bssxp(h3b-1r^zLIuv2Kjaga~x-D zNt_;9S(>!a6^XSjXvrJ0f5J(WifExuQ+icq^>|g~-F#*sObCs$AW{_m;4Mbqx!b1v zEG!Tuz6fGI{~fZ(>2bE?`9*#)-Bx9!s$O>ivPHhJs4F|eV>dRCumiwFeS-`dAnx&* zsn|h$)}za&!$3^~SEB^$6YmH7?j$-yGGXjE&<;D`gA3(Jps0M;Kh2T$($!dUVQlVm z=)-Q~byltu%^dMP!~w-e@C;PGZjG&((2fdEA;%t8=$3tGTnLo2q*$(>xc)2OFfmvb zr)~CVRX&{l!`vnt1!+u*d?qdLQI-Yb=oH%h+EydGmM;dwNPFl-9)k;1HD*qroxQI^ zgion7%SFMBs1&NA5m*r?0~`AR+R;D~OSv>0t6tgwx8fv&+NF=vy=B7?Sn!URPUd7m zGaUAcJN)>Qg-9qr>ffK;GS7wH91NLpK$(wcvH!GtQPiusv2UznA)#(nb^;^t(53!) z{CL__6xh2>5`>kX?`&uf1!3{_y9FR`JDmEYz>%#$RXW_hC${Xr03p?P&TluOOCc$v zAIjN2T7!D4ho5GTO8B@!K9|!FWoRwWsMeIABd&MnrTpaK+j`iD0B+-tFZPS1{3E2n z<^&!cf)-L%UCQ+=wn&1{0yr4UDU!A2f7ODs4mfEMyAmq2JFU@4b~wU0G<6lNSr(is zhN`?=?3h|N4Ea&6kz&n9ANO7GRWIaKwG8oEYDK3KhekBTd|0Y6!hPC22@Eol@ICY_%z#*6M?zg ztf?l&cuhdgc?0lIO&NV6Tgl>Y?dEH*0cgXElIJ9B7U0_ zF7p>brfKSQNy&76vJ+NG{sBNQ*=6ijBIdl|+ukgFVjZ>sFW28xBQ#P8EUU;56uP{2 z#hmjWD1J;fdsb^>R6?|QX%ED#JAz9+9QFez^>ps`-D`NeS%GIB*w57l zB88e{Ol&-t_G3(dJ9Jb=@%M6gvVgDd z*#TY5{?XkSbji9YV!?KARO}I3ek2`t6vq8AXR9ByK4?|U8egE>e0S+9?A9F>8ZGSB z8g&ZlXn`}nmGd-!c-XRa3F>%Vy#AqcQ`z^xW)naKW<3cLI+y|p6fkoz|Y^|WD! z`?Do^WiS?dX?KBJW~j9lIpdgUbrNCn@JfBV0_cg6D4}6|7@jDB&h?ZkfJ2lLPdNJ! zt{M21(q$&;2WQPSyOtN>@}uu(wo6&V9TT#-di0Ob0bJuufLjJdPP~7oen^q6bD+!# z2yLW2pxU{X(yLtNq#C9^t!CKS70tl(pYx1MdeuEUSeTHmNld9*@Y~5IQB)8VdHg}t zG`(Fu?5$1r_$78Jlrthsn6?fBIbqeaNTi}9c(hA5;mH$WB>&OKrv99TT*&H8mu1?h z^0QaB%!wLN6ll+kd;9nRaRO!T%`6*20R{q+;6V^U596v-i`T8cOC=E4fNrrLqN<>; zK;5?m?McuL{PfYPgwED4zAh!5*rZH;umz_wfV9>?wDKlXZD9s#$t4$cp^d{hKp-Qu zhj|1uoYH?eDg5I&Y|y=m8XnEKea0bMWJ|M6mN5*U&(@4t=DxwYUSEp)EdsjA48S&R z@qwwm;Y>4n95$N}_~Dcx&UZwq75u}&!=!4?*!;LDH!kkDG(9%{(|F>vXHb!ng>1Iw zvt0Ig9O+d7#Z~Hu_Ozt3S}dx8Qvgi|n<4RE^6&nq^+v&~c{TQCK#NJN)>(utx`dx^ zpNC^)T4~sLe@(CUnom<(cE`fwk5TXr-tTtl{qdsUls{*?QD*3h%@~`ET0m5fpRI2$ zanqQDIWrevd2df9>G5Y8zs?&8lT+12xPgrg$x&)~{ioYv4^8yxuV#;G$c85j4ORyI z6IF+FvlucRE|ZT}3PanNw!S!54DQR@A8>hLz}9qf^ApE3<($yx-ch}Wi7R|Au}lPj z#}5iLdR6zzZ3$cF3>wr4%lGyeHzOyzv`3!^viBCU_LkeDS)VV%F|`gBo1ek#ro}e& z7f-ZXcjNrER)@-Jo)=ld+pGjW7i!zXfY9*!m<4cTpu38lnHCbXI5y-GezAAe9&Qhq;$!-6*I^6Fpm_SwRsG-OlWCtw?^DDRiP$PKaM9 zZQ7-H*l6Cl>?dYUsQ0RpHFP6&8>bhfx*e{1rt9X$t!3CA3_V5XJ%0uv)$V58w=Xqg zp-j{eOib`uh?o1d#Y#IL{zptkbK9_%)YirZB0~2pz%ppjYG|?jf&z3$O+itZy9ZGc zdKc+|VfG3%2Jx*dZl&B=X_RDPh8@K#x+l;^V!N(45cf99S^{u#RnI1Dkz{qkME^~WU~cv+ zHlx5NtfW29lSY$ezN#mmx|kHMW}aAB-;e0(p4o2^o!TMAZY#Yxx^DS(r?-0Dov{a( zr8%+oBv0Gw%M;jWw3D;s2+iJFoO`M#KYfLT+B2^|ptMamK$XU8VQ|Vj|Fh$Dlg#=! zd6w6N058X`S=5+LO8<-mmM*Da@z=^(s|Tp7{sgdkz;4ygC*PWd zR@knZEWegVCI?#V?0WTz3bNa!+BgHBlj0l1?sgr3~LL z_Zf9C#&A%{DLkIMwiQ`1>lNiG{s-4!m#WU`)$FENX`?1bJ9jXWzozwmbknH$_Mcvo z?zTKEh0!79X~oXNqsdj4twy%IY=^eqvf=z0D>A-2ANh9%TT7Du&(Uw|Fqnc_1-;IV z;%B81EN(ZGz};ukzvc*Q9u>ZJ$Lq5@G1-lfzWQZ}crG-9rN3DAOL7jI8iPGRnzWs0wEBq65Wb$FbUt`Yk38uupSGcLInS8}* zHaIe)fqAi`{c%HcBK#`erBxLH3710;uj@1)ft;UCC8d1opwwL1Ih}2>(NNJ`x@kY~=|Qrke-E|< zidsMO_4zOOMDglA>Yi6KIA5ou*5@H8v8gs|JY;*yj%qWQU`L4~YyEj`qO2d#`grzX z!;LS76SqB0sJDft!6y3hbiEnslokM+q3tybaiWmTI{qdJ7Ihcn4-E||x4S+1mRp^I zxrql4r72AVyfbVLOB(EEC^D$qrd^ZZ^6q`uWifA-@45KCO$TK30 zOtZ-LWZ?H0F?O37Naw~fdlB}iX-toz_KJPglTSx#=?j$lOOd;Kj|*8OVD<X#eMfF<_>Sq|sBalDZmg9R*Re37>l7U@oPF5h+TdX1JZhB+B^GFwBN1T)^4oILmMIDTh-7@s+`yPNMUkUTe27~ylnLnnmOXx^aX6ois z0=>m#PK8qow2f4|ncr-Tl;_3f8v{5JL`%{iTlu9-!H5{xQ zp~4%^(a;Rpb-W3CJ_9_A*vWEr6rKM-y+x-Dp5h z;QM~Vs9Rz);IrJ)KrSG1>m|Tum*-*zN1#M@c(@CQq^)+Z-KkK%D7>qv=4!*Jdy?dx zc4vX=H`*tQkQH)hYyZ5mInM8ZXt$EDre;u~GAC?J{mX5leTuk8J&}Gp+nYe%L1Se(Xoy`;PeG zUvHXSC^H)mX8PX#^;YqiY5NN0n|8)qfS*0L{m=Je2gy@6OaL6UU+wf!?!P=2mq6;_ zN%5YU9bf-@{A1B|8o4!il(0;;XY;6vntQ7>rSo>s&-A0oXS z0M%b5Fx#y{=A8XM0ed^5{?7u8^8yG-KD$fLU1t+#mBQbJ6rF7fr=g%Zw5 zgvl77%G2IASeC@MFTr3*$AzXCa) zO>5O%78-Q8pQZAVnI3HRrT;{es99Qn!9ATic472dQtuiY1B&sK8tufCxv4qK%(;rE z+?q&@b*R#`_wToWzw-G~(;B<{^E4t*gsOnb@F*q*3s(WGq{`*Lvdv)kh2)?*pi(X6 zCLY};9=#2_dY4) z(LJ{0iCL*cTg3*7R)bfayq~!@Y{k;f2>71ikBx@qdL{?EwgR2&&KKk`M!%`@gi3s! zpYo>t;)9*|<{&jQL+dkmF<0>50tFNVygQ(7+h~KT1;fIhLQLUp54Y{V5eG23 zAn=2^>8>&q{~jP*#kkH36)HG`&nXs#3?l^%^vyOru6wOKD-wN`&-V$oEVUgRazQW$ zb92jbRjNAf8*l!iC231u^!zqx38{YJug!WN+8i(0KUoM^d3A-f*Z|mF<(?A-a^GkW z+voc>oU`<7{Gv>}J(+Nk1t}g9X+j^i%B%G`E?}f{PAvkdu==}DjMoCJCc>^#8k7jX zAq%;semVT&s?sBAWZdf}m$z=Ox$ zDL$3;I!ZW*wA`yDG|muNyXR#i>>>;^|05K}B!UinJsr%#_PUt5mvGy-LS+g19#Q9_ zMfv&PGK?T3w)O&%7jteL%`k26Vq*(>Zv zUbGWF3;Xbz{mBU}QZW1i_(H<9a;irkt%XDhamy08BA92=kmPjCdWN#+l2my}Fm5by zG(-*`$st4mYH^A-%qfJ+*p*Nxc|U&6r>fMgN`ZsnFiV|h6fzErw+l<*p*?ua2Ha}L z-q)Aw5EO|_`=rs_e>(zV4q=tEz^%8*qLbT<>*s?Sc3493_MU{u<+gDiOsXqJ8#F|ybH*J#AlW@X3 zl9gFRM}8j4JAe?MzRn8GCDgX~Qe0*cse(<@Q zuar>dj!syVyv3ni$uC9-`km&-1!2!hIs*&s%1UK5^gM0L7l|^Y8>L2Zc8kRgHW8kn zLtFjv|7lAUBs9&ZOqiV2RPs9H7rn7!DmTAk6e=u;6yMPJ(sXV;zQrN&OwfkI_fT74xH?Y`dKf?dk&Lbd zE;#Q{Zftl^aF}wriuQdHeL-OXSUZMtSJAme9VEEaU)AD%sdkr!Vm7Y(2YAR1})wh;dgAf_8Ri~St|ZB6D7nN zY8ZZ|RpOtmT+|T3$2SG99{i0fH*-ZrW_%FCWaOs?2lXTA$&QUCu!y~2;;s#WzS7G) z*VAnEA2YSd@NS-@;W1mqUEjH)r-fA~&jafxaRsw<^u%w)r6)(W zI$T}yDzBCMAv>8sKOn5QEsE~B8rYuK!}tQ*kqT;poe-x}w7L8A4Z(NI@kL{%mGzduo2w zCs9-oed+woU^C?M?ZGad#$Y22K@Im{zD4OSu8+v=H?L!Rv>7|v$0xvDEC=|8j1x@tUb7pO?U^S+u#7V<;4oCa|}A@Yh}gEwws zaoUH8+K2n3p6<$hf;Vu@V4naEW`8DU9%$`lnsfaNt13EBCu8QP6MoW{fW&}59$%aU zIhk59p&i1GrsYdRErmr-o)x|PB>#yJNnt|E+m4_IzG(~e9o?aNxC4iLU5_u18ES~U zpDg6qex$etYYvTblDB57>om=vHQTCsr+p(oe!OD$UnWd;`8D+gwJOd9OwyzNecg#a z64OqHYu}J%mdOw>$=wpIRPSNws!1oxag3vfjj`VLw=R_b6mJcC_Gv5W$5;u%S4R03 zeKq_!c*ro8A@Tnix=(~u1ElvdHHWd66VfK{cDA-rgRMUQz0laK5`g}{Z|J@Z@XXjK z?Y+i_-^+a2LpJwfCPlm&+PAd7sImhyNbT`^_+*q^Gp`iIU?t|m^4zdRwBfDW4Y`N@ zOb^vLpBE`NQ#}4z>oD}(HbF03_fA4v;Zv;53|EqO^=fn&z{};>2%tC%b&L9b7e^*G z*rP<;A=qxBOh$I`Z(w7`1 zgd;DA?5Xy}DB8)F<-D}Sj%RL0WiE6MJzMX*<17Yv|Z`e(Ly^s?#_ z!H3JOOxoweFMpq4hmXIZH0$@f z93<-vSV233Ip{R7pE%;D>Iu`YW$i+_96u>J%*f9cVUTr8atvEbB39)zy$KHzprB0^ zX8^oo@DLPD0GvChlDkVAh6@hs#bml4#EPo&jh_{LcMBaZt`_c`*bHUu>oRp zFX}9izBNSp1RJ5KwjqHu(V3;>2+FOO8^y<2j~H4vjgUhb>v~k&=5m{*hG~o?)B6MH zCW7ZSZ-;x7gxVW+wj0ZyR{TlynfWgmHla#4$~Gnxw84l3(7YZAgeVhaEpMneIW0=h zxB3m+EP3c5C`hKyo3<`Vn0`mmdX5#bQM3*H{@;=jZMhLk{afclMw-KYo~jP%`fNg0 zGaR0E1s$K(yC~p-oI=J8=esvoJI z__3koFO9tJW{&90sVr0VPdHZI*^8UC*y{Ei{>H|m>&)$o)+)bi0g)4GWk%D;0yXkl z6D!|wWSSU7L-e)Emj(sRkt;jd-Byqc(w+h9iULljZd{h{iERz=#d6;3XKq2gvZ9ri ztrqerW9?RqMI94-{hErRWQg>Q`I%gp9DkXywo#)Rx07JH))Uk=0{{Ij;cgKJ7oly3 z+o_6qLG)Sm?7O(W*ESA^?%UNU+tS+IbM8?g>MyfpXxVP3f7EB2z@{eIq4Yq0+oruZ zz32Ri{uCzIfFWW9-t+lM8@@Cc8oiO^C++vVzWovJiaao9=p44MDM8ZEXP#oz&BH@Q zr4@;Qy*FNxuaKyy!il@WskwD~WFAtp5&X>SC_b3I(e2x4e?R$^HdL_+EAgq4*zqDN z7UCu?sgm0+Ht~f~@D2ekj+853Sy03F>96ny=2Pq@5X5=@yl-{8G~n`1Zvhf~ z|0K5=Z&PKd@LK13_jEoeXdRF@r<?6T~w zID(#!yl;|+D4@(d>N7BqCF(V*_@6FdyW|}H7>LbZn&eymHV3VpHbmcktu>kDH{hG8#7wpB7hmTU$dgQA%CPtP19ED|`Z<+O`8{;~ zkij>8T5mxe3X0E#8oo59or;G&&-u0=Bz(&%3tdI-a84_T6~Ll>e-uu9>Ae`(1G#(G zrkrfpg7OZQ&wvC-4>XQ`yU`3WNN4W*ux@crp3>VzN?~^1zH7A&T2uhMXdC$PBgL$$ zJf|Ls84W0(c1>K|t48zm=1l)kjfAv7lobV?%#SsHmvm%}RZAcm0jRSa`(~2LqdBwY0L*U^-mU zIt@C0Uvdy3tCJIh6?hsZ-UTXdFZpEg!x+PJ zU7c}7^GNnSL@pQUIYnm;2Ch`gn2hY(xq_CrYNd=N*eqXGij(iVF~Az+IV3gnL%TMk zN4Mp-E04b91io>%<_tcdNh;zWKtEMhC{brT9%JmTJ~X$J-fGn0RA zQBC$%+iYLdL;m99fH`muzuipRjoskR1ekW3h4lNW#Jw4$Jy3Lvm2Dk1Vf`61_LJZ_ z1BU0SR;(Aa2 z2Rb%Im*i{|4V{7#pNJQ@3lEgFY~;6XgLj#XN7r#;r$ZIBg5|VA<0z?hT6cd(INgnY4Z3P1299Yo*GX-&WEo`KK`C>GP`9UZrn>F}oA6 zD*YnTki+uF#~_G%M$=YuJ~9eS4(c;E7uNTGUkyV$43Cy<{>1)gcJeW6^$|snRcBDm zs0&@Ev?=4Ntn~&-|6WVE-hWu5%FCQ-pkA&u)CnE=FRau_AW@8OS@`I=7w+%%w_8NC zd}L6EYz|Q$uX2@zp5G^Ps#=ZICGjGD;Rp-t97*gnAeuv=4@p-?WADQR674V z>do16$x{ZqZ?>f4CqgUT=p*sA<9B55kNgrrmi{lh38U<}brEkYCobqrA-q;nmB6Ei z2%yBwsdDT+m7%K-tUI&wg^~QBzx_}-u72CIPS*E;$8X&R`Ca9LZyAcYU5L%9)b4_R zr;#3mvFttnfj6!tec6R;4OFqQiN~_So*BA^NuPE{2eb_|T^veY$Kh z?W*>N{;0fp_dnLwo#_ROagb2?xr8JqUvi?WYRRFcwc1xhRyA*dQ z?ry~$3dMrEyA<~pcXumN+}+)wSVEBE#S6jp=KE)ECX<;kkV(k<9NDvb_V{QK&Jscq zngc;DCW$$OtiP}t=vM<9TH+PHQdIbRx>NT7W#_a7jo=s=TV}6VW!qfh=xa0O0U99T zad=SbclGr#4o^F0+hL(!_lX=H$sXy2`T#1MJr={96L&hF9C1y6qz;K5ScRt5H>ci# z7Hoz699n_dH#0h!kRb$i!VWHstl!1wWtJ=(RI74)?!oe?9{@o-Ag9iVXhyq!j&yM(+hJyYf8Bl zC<3~c%rXk0W%SdZI>a38t;v3eJoTinA9hr6=>CooT*)uiZ+$%F&$C?u`>ic(ZqA<2 z)^l%ohY%g*Njo{QE&e20&~#qF;Xl5(U;sE%A!!%I1R|9d7bmZ-8V#CqNQNk`W1j=@ zDkrz6Z8u*8AETTrB9?X&*Y396dB`c>U>FbQ7_N6=4}Vc)u=h%~|9r;MfUNk(f+0Ae zDe-46Jt=I}^#{}MFG9FxnF&(E!Jq~&h;>>TZ}OgjKZ}|I)uQ(}^&ir!e(S9vUs1<) zi^RA)tPD>I8OQd{opF;g)$;Cj>dscLKy$BSdI$}SBNRLp$<^YC)M zPNCOh+B^k}iQ2D1EH53c4^H++73u$eaW3CsH#uJ=HxA5*4@u_*^`5DBIzKRfrlnrh zb_@-g@G6`hR@eDAO+MT~nOLf$xco`gIN^uCN8U@A!lV~MRPWs~ovD5$U1PV-wAAsmetB9QjeU0_@5HJb z?d2P6Q-7sDO2ha!kscfZ+_o~UN+pF=6eXvV9H2x}g@b^!myyUE67}zZ!l+EyzWJvl~Ht#Ck-0#UbuWirSL-+J4 zr}bmB!zn})bwN`N6}+PS?Av#h145q~5>fXJWg#d0`-YLN?OAatkek~Ye`l_%boRL& zxAA*?4DSl6Hs7=~Rm1Xg>--w3AmC^=yMo~kZq;n+)*eoVSIqJ(iRzTN1q~51O}_7! zdaDK#LQA5Pjmn$526gAU*Wo;!-+n?ZbFfnOa^Djy5cT(#Q$>@d6942zWU(t5;c*S1Z5-6rXKD)57qQh-LXzFB=Q2v&uZtwipo|ZeUu%ULQnpqKimGr1t zvdlFC-wF-BKdyo4LyX@=rZ94zJY;=aB42<*13?ez9|R$U&n_m@u%nmiEH)QTNz13Q|$(5|hcx};_N{LW%-z%6Q z&{zyXHG_(=54al!yKNZVhBUh26c3=p@2*&u5uQws4Bm-oPGvs)r_{=_N@0sCZXJQSR z7(O+_z05m!jU_8mEy7vbt=Qe zON}PDGS-LC$BFD1uRBs&)!aQN;oQ3<)8XfJTVW1)?`Em}p`JD_9ov#NdWk`9;epdj z2Lzo)*ey1XjJ@b}X#K@BRl(NcWrGU)UnXAudwF@EM-*mb`6%bhP;N+@7OXi*0g|qIY1lcd=-}&;D=fJPTT!xCtYy zLKx;8;J~z2c=Codz6_0*L`RCC^Dv-K3Gf`QQz7|D=KDSm!=x&MT5nPEVhrp4@cNNI z$h!X~W1M>eLh#ZX3oT`RziJ)yJgt#Y^!9!Eq}^?hch`9SQEE8ywuKCsFk>B+k4L|f zP2EOyLRrzUtzG80)3Y~EE^(p8RB@(NCd@rTC>Ptt0i^h#ff()FK0)}{Qjq_7>`YPj zXkd=L&cmTgC^>>$gAUV$k)P!Rj8~E1@7oW#^%1Hw#GRsNo+&xgGv&2dC7#V{ji}-= zVTpyJyu@SziT$P88W}`iY*H$m`dbbav+HD-v zQd*QYHcb3UAI7X5yY(GT;4K^F)HCP|MyZbCT-&cd*ZF11G5MC&BhlOd>xpBlt-W7q z^YGoWUWlk$cOj|j{=OT$r84x!;IL=%bJH)&dwv%vXKF@6_Jg$VijP0=j$+0|Z$!GQ zFuBrG5i{F!jQ6?zQoB!0)M9w<6MMZ z_Elaj7C)Eksi)0Fi;nh_E~Dl^G`7qide28DqXi6{lq$PH!dzWOtgz`h9jt|5m-8LS=JzTU2J=W(qI_h%Ax*X+`2AppuM6NeWAO>3!o@C@R7D zCx_&toGJHuIVVD{rtl|@)|wpNZpd=+q;mnA7vo4zpk(_Y;~?hHUY$VXFEdNE5$+26 zaX{8tk`1Nd9t{h@se7#3)7ZhdcjV%BYWn|k0TiKwp)ECC;fgkSmv&!S7S$cH1YAo9 zqWgCmujGmpG3o%)y>IydOMgSjli%pk^z3SDf7{&KXjUo{lY?fpAjSp7rE8{608HO6 zJ1T4A>))&ppOZ}UwO%s1mzZ15-H>y(x8-E^6)BNZ#mthP6uzIqeW(WCq?cUDWyU-3 z2xx|#Szs0o3<2|35ly>Fj+o9Yx#AJ|J%bE0A@WpTA`m<1;z2@&ZK`$n0`ADwT*{c>#wVzp% zMNda0rQE9OXs3JWBz-ZhFb-YEE~KBq1Om6}Ell3%JE=|F^|lxGv~ItDGMn_Af5&r@ zwKob5R;P~jNpS4kNgY47+dR@-7@Vp=iCo(fAPC8M7xOw90S4LTN58uD-n+86IrqzS1xe6}UEv5vix+_M z<-MvlU-7FK0WC*=n9L%XJ#Dn2FmLR}`e`885=qLEZa$v8yTb>J1w1;li1tr9Y~pva zAqzW;3guxHOc4vK(G+dC;?Y2utchOXTGz38>yNKoF*xq@T5ngBF{;TF{e8{jwlPol z?JmW?qr;p9GKERApfiT3fv{0tKqC@B@qSN`o0WkCCX^X6khOCm+Gw_Hp36Rm`*~<4 zX7yyD+X#mC85+oY3o?Awz;n}}@togN#4SxaE$gx|poggG-dc$P6qF`n*0xpEzIS)U z2VHd)jhUEU%tI`;)w8WB=-Y4cSIQ3c*UFoDiZ^~|h_G#qU2ZH=)W2VaKQUMIIaQ(H&%;*32|2z>@uO!jPBVxrjs~w1MZv z>XyClZHS_&8Dq7#A?VcI)5^ePS+ zU3Lu`^=xa==&0t2Mqzcny+n{{@?w56@6|jjcC()xbeobI*2*kceovftZB)wwK5{)a z@)+d>g?d#!^fbmXP&n}=@QQO;ZwqIR(A007k3NIPBj2ww$?@n+xL+shAAE%qGwg|c zWs>tm{Nnb-@y46QDC%pR@=B8+_><=hs|mXh2Fz|cf0Z*X%gTHLAbElNb!m=eG6&Py zIh=n2)#Bfi_N^aOZ$X(Omz{J1ITPNIqE!tJ@Kxa3pvivTMs}X)dN;=X#i!egb4Ym~ zmQbe59KE+1{^tc?MU3{ZJKo}zrsChviC=&7=K)Mw0wANAX1cK{{e=kW)kbVgKZ~y6lwUSqyxDmw;oWwSjKG?|#)GoSsMJY|6YLU>H>YzjzK40(NRac+PXrrY6DnR zXLcr5RSnR-8G~ZMx}0{mgl+U*Ua@dT1u(GXlBQz5-b1PzQh~!rFa43tg#^Rp`Z|G_`<=#%_X|CdiNUI-@udDlSXW2(Wm;$Ao zjXc*X#JoX1(bGVCL^GoUzkPb8ds=x(<07C&Zvop_YYp?Z(&nXcN$+bU%DB#Le3a20 zX&2JrJ?qS+>e)|yYE|5};CHhUQPIaYi3ZLJjj3M*xK~4jxUcLOt+#L73-+5&m;7;C z@2kJp8pc3F<-pAjpKqT)#~Sx8CVQpQj15R#N%PL;vzPphZxEAxJf9J}Gc8XB=aD+x z%CT6W`z^9-olgs_X%@nyv<6nAiA=JYtmsL~h64?eUxGLXnrenH!*6Z9Zq>5}zs=j+ ziOvSHefLNY8B7%L_U1P8it&Qrj`{!=R%>WCUOVJ?yc1%<_>NIh-g;tnVKM8LR0l?<(- z318)shyBc{`F8b7G3|%gDcqBp%meWV@*4N{qBx}qlAW3ilCus{M4iq3W7f4tM1oeE zdFwPsj=DzHOL&2!Iz~F((MxO%%1qX^x}w*&WVMy8>d3o7M2|T`!brQZMz}{EBL(s1 zJ}6Kw`h#ZX$lLkINr~RGs=?d0ZuV)OpH7MSHIj3>Wp&fo{-2c27&Ui)7ztvb){SIX zn8W_ohSsTyZ>tgRRMjZj6>@{>RNmY%uQ?&^4Pf|HGrS752Y81wfaXW_PqoVx55;aU8-U07PKR06H_>)y?$8c>>{@yQ1C>Q&%w4Rjk$ z@iQ<6C7fxc;x+E|JD`i3gwI|7;>BIBaPw`PTzU>pkB^~AWUtx`ZTz*~@p24v|3k`Mt#t7`v^)u! zd^Q}MMzbMOIR(&XqWL3n#x>mLCDdr}X0X%*;Vt=L3j~4b#{CE0-`j&891Jwi>f;~m z4Fud6VTi=9jbKs^7$SHdZE0Qie6BiW;$~MR77GGY3+3K^Eq}LxOnD1)+d_Y zLyMiucFxN+vE7k$_QuW9Kp_ZhY_(5N{&cDrvdiwtScLKzp&<=HBE9O{xDn~YcHrrQ z`K{l?2WhDG6ZTbKLY?JnX8u`(Zo68C_kF6{hB||*L^jpa`v^7%eroPTt=k3|Hw%lA zi!xiGsH=U%%|+2vJZB`J{I_rZoza zhS3}iTZHu2V()_Y?~;NM%0A6vkCu{))-v4$Wa?e7GWMhw@okuTEq>VSAc2%;dZhmlkv z%YZ+5Do!i(CM)Aq#bxZ{<72w?k!rwhCVzQ_4K*)74Nq2QOkMoZV;xGd>2wQ$NmU7e zX0-R32KFG@{M;~dLa65leCmqLkw=LlX!CNtjm{~;t$dT_occUe>t zW4w)>;YHKp#Gg1@0LOxF3(oaOSBd2hbjwH@5yvEQ-i9ufJTBiBC{hEG8g3Ui7U7X! znjxE0l=2>+65qDk^Ciinc=c)9rgHA0Q_1wK0}AWRY48?q%awgne^MX@RZr;H`vWSb zo4v)#?m+>vEXfcE9ac`6&52bs#K<c5`?*ylZ7CGCl1k@ut+CT zr#O%#+oq{_k#hRdXdhcp{9C;?E%`@}v(2FJPJqa6V-%&A-G$?DHbcPl!51by{0doO zP`&M3>yCE(I&6hagx$#`4#|vq1NqjAy~83G%$u_TJxD2Bj2y `ovey@N9SnLcA$ zeDv^6XPe!3$V(gT_tLP-14s{?yEINBU&G+HL6iGuh~M3`#JufMCf8V8ZqT3sPfZ<- zh%MEZZ>J;DODA66Qu;-w$n=tbmC)h%H(CHv^bkMnoT2}2;7@{MkPpDTGy>meqVn^ZpbzI!^~ z+!==M!+x^K`7Ff#7L@aW$V7U6rc+cz6->`@EHbyW{lWm#F0Afe3*l{2ky4QN&_G-Z zJRow^_hM6}`Qb{|6kh7oZlBiTycJjT)$+Mo&;7b_@k3a4^@iI z$A68}K3AbJY%`8-9bL{6#ZtWef>8{1-Bi3}VbodRCF$ow6OS_ghKDYWqLUE_tt$WhIH7sElCIU5886-CXV| zn!*vIA%?#}oX3vPB2#LYCR0J5Vv6cZD&yS}6Nn|JH zYLFI~-el?5CSBot7c&NCZkGb2w;eQO8QOBs*e;kK^cXhq5U$^hRLE%HO*af`we8J&%yBIaZ<;QieloO^rsGwWY#cj$U9X-B)`ZM1M(B@}=prV%wT8dh#lH zsc_Hx#ObDqSw-SZ`m1R zW(E$=WKFpnTE`0oMG^9;jcle>j(OyYnk56I)_R+LYR+mJF#XO#O2Z*-V6hP-Cas zGR2pQwY2axv1Z|we&SvmN9#b8{tF4&o=|-Z~u(>1E2amUfVC|R{+ZK~_;$0>7kztk*>z8E%#=?H2oC&kQG2C$8Tx4JKIN}XWyyF`C5J!B zo$BD@WVJMYxp=;LPf=d%x7=HnL|U!GZyw~+lBqY5$VW-?^(w{)^N_ZS)jM(^eeF8S z#>g>nng-&+Ji<@f`05*IblDtr-@)3w|GCZBn_jV7@|xx1Z6!6}ZO6a2KM^MVt#hsC zLG*ZARNB!d?OS|oUTst>@-9(l*{UUPFgW(mm4zy(Px%B+*3kyvKQY9j;{Daz-g74U zwPYa%lvlJ#b321kiosK#I0axou|A9f`4arnWHLeQJo`6IQ~<4*Isqz zx*l7E(LiQyN;YOpHfDscOZ;Qsm-nYjqk5W^g24iYs1;eh9p4RlYq@#i#_W@YyYa?I z&5gg;DIfX-JU66CEcPfof)>u&_YF&nNHRGrl3Ta4g+j_s{$=@U|M19wV#4k;iw2BYPP+wsr(s+<=!$eNMfb@_;v zj-hEWQ++rv1t)!&S0bdo#bI~@ia>0AsEwoW>dOuF`cl7Ki^`0dm&9KFJM3xyg>j&$ zcvU)AhygQBH)DpX5i5?!t-DaAEty8Z1ra$+R6hS=e}d{67?WuOyyw_;N-=^-3fbo4 zLX&*N)<(Br(2^{$$}AYqV1a&A5u7`3(-4_U2bK2wtK04BaaF@2mXwc@Zo{Shf1bwg z!WcW$JUe+=>(&C_9k?|Rynj%&(JLvxdNY0SmxLmNKMxMh>1?v~n$_!FK1!UV2+q@! z@Hb-SjLdr}vbr_4Bkw;diLiDj1%O6=@rF}I6kQTf4FJNh0{;%Tv|SYZ!?okwLc=!2 zhr&cR#yVKv(!M+l5%ocjztPyAKccdNHr*R<+0?ntWtbB*Hz?4q zIiGq|(g#)O`P1lnCOG~KhgfW7rT;fJ&Z@m^>(&%h7ih zhq*5N34L4G*DCso{0xBCeU+=}F66vxt#T?N3pI~Sgi z9%=H3IBQ*=g8|e_m+geCsp&P0AG-nfd_8YxhdVkSyN!QdfpaH}zloawAMvX(`)7&| zbeHVde<(qhimv?(I?uOxjyU~~CPN0Dr34f!YYF~1$Z<5@oO)h$LHzt;VnwR=Q8-F6 z_w3?I0c7)i_20t33fOP|Mr@*HrcUEP;-=Vbb9%!W>wIK!tIZG7c(pN`^CNB&sgiu( zbcVrkx{8kiX*~!vF-P6y#c_B z%Ey!lzEV6x9qj9U=ESt(!nAq~gdQ@>iRN&Ra-$YzEB1K5ermcT5UV}i3cCuf#uZl$7I)sE(!Zte#V>9iqA~&s%wW-@OA2fj*Z zz78Q|BTuD+iGw7^!Lv8d4Y1I(K?XUTt!VXX=MW|#J<_3a2=APOu@Qli%fdSonK@Ud zI#??cU|`35l=v3$^@s|6TiW{#Zmi!4bPd0z%@Y0DjFi+g{-_fPl@zJtPDn)(a7Ra$ z$j0b90O^Dr%@hAxG1E%-4Bf7cV`O#|zqdi)L^uLOy7X+)^p5`0MR?87WyGs#%rGQo z0T~gh+R&l*>$0H>9Nr#{L`aO}YGuj!IUd||guJX};@$PwM5tR*XK_AthjdF4==|FBt+gM-Gc?hAF@0 zTm&95Hgdnsl|6SxtN-m&hy*O(d+xPAP%G^C+aJyfTZSN9OiJuK22b^DHJx|}Q z&YF37BYo(9CNTjO(0lVvNd#W7Z27*|Sb{4oKY#&2;iUa|`ah$rN=AsffaCCp*c^a) zzGAi>TeR;BpEst=>PUe@3NBF_Dz>H&_87!8aG-7|xj}8{$1jFIctoE!#8QhPi+TPR!U;apL}W6KejQXl?$!^Sn=PI-ji7D>l*6T2k9tUSD5fLHJYy%$zP;FOqDeFd?h6iW?*2ICIW% zXJ!%202V80Q_I-#CLfn~gt-PuV0VZAIER9E2b9}xqj&GbP5Mqj&mjlw#-6Jy3B(&_ zKROG@R*)?K7z3xq0_0L#2uwY@0%%ueaxzRH$CMH!`KF)nm9NKrAM_B`j6}ovM1o}7 zZm~VQ&zbF?VW8S-sWijcH|6?2t^V)fa>biQ_8gN-UVM)G$^kiy`q-0Nn1&N9X|TF= zIuTE1%Fx9w8Aj7N1-0v5?L>ko$sk{Y1jDJmxsQI7el3=-B+i5oShU4m(+-g0seZN9 zc}k4FSCx#>C$9c<)~cMZnF`DFDKBBjvHiw1>tBhK-Gdk4B_AdkW3-#iE5d=t|1zD} z4Bu<(_q36ltPoGWD4x>h!YbU7nJSJ;^|@^mHT+UV7l;M!G@LiTW8Bxl+qW`=ZAv62 zC$h?5dPB~nO)QSgMw92%;?7t${&6VQy=Ojm?wC+mkA?P%n!d7CU%qnzGEHQ}-EoQG z-3MGAff9Y6&HJYDtjvPrG?q;+cw7@u_&FRRaTrF*dnkBKHW3;6Jm%MZg~SdQc8$Ja z6c8itVJ9`)z$s@MOZq=o4|a%4hAa`+tMKbESI(hX^j%!ALo-RBe9>nx(TqRhxBAll z{%sdsIF%8-QAb$~a#%Qg8%xAbpmxGYff-bnWFxoHuTq5PB4p5F4ZR?JDa44nfdyVI zvLfbun(7DsUDCiW{@1hFF*Ag4Q(ZrByk)~R17T?@$z2hZH_eI7BL7EJyZ<=w=OBu4 zn~sT3kx+)?tCsqg5fgVaVR2s(iq+!XX#8ouMneUotVKdA@ZiVak0w6DlDrcNXtQEpbWOjPKqPX4pNSGyg&!t zN5hmX;P{vxg+Rvw)*PXf=&t#}*fL;tUI_b9n_caTpdIzX!L8Dxl4gJ8fhWo+acT!y%$4w5O zJxWN1QG}hCTF-`T2D4>$Npng5{vTUXBdGuM%zkM{G(hf|#5ln*0BGg0+YIB_#gag# zVY*o@7Re%60(4#5ta(2ZtJ!|wBc!7oqreuF4*Qm_ybE}jY+5TTUn?W;czb|27Ih){@R5RBZipOd~6_#i_)f9+uWMbZ9Qsm>p{$s;oJKKy4 zpiy!~T`ij1M~;{VSD7=uB;`m1_}!6a0uss7hO z5^JcSKHtZCMg6fiZ3%x;5gGJtZZw;rp(4L4IA_B$rP8z2VnNgu6FCbD9d`4HB9WX0 z;Tr@wsszdleBt4{>x9m^f3|ru{0Bc<^bhqzsl4rd?*@FN0qqrXMOhfwDz3|H*N_>w z^fU0b9g23#r6GP(=Dg1CpLi;#h`>lkc?Fv==vd#9N!>3e)4_njb;>g#Qzm(UJ~k8& zcVya-Kf}gV4!%vmm$2T|47o-;)w8gol1*1njNv-z)0Z?j!N9PV>ucM{Sl+a`uoJ#U zoDm!QgOhb>A^tWS*K)gbyOTWh!e3K`k5kk#t+Xey`L5326XBHv1kN4rQ-`Q$BK12%(+qj?F#oP6{- zUd^%$a&TKnfoNu6ObfEQM*mpiX&1-O7&cZGsAo@&*m0HnIJ5O@-o_G@)!z6f3hJ(6 z|1{qY3Mx>Nz~36&*Qm7KT=mK#$Vn!cgwlr%6-2;AcBB`%kQEh05!_vri0bEaJ#(cQ zCP2>v6MQskCQvfXWyE|xr_Sp1Wcu5qJou%LKE&1A%pmc}9@I)J#EacA1i}f&DD3?aUN17^3wo1UM}!G zA<07x^|#5J>36!Bw)M2+>aR*4Fc8a^os{EUM154q(v00r9Y9`3>&gqTM9isTw^?58 zK%{*}-SIqHew}JiZU%kdq-{vRzc;a}zqqtviA%xc-D|x1h0dg>+n3e4LpDp)YM0Pq zNW=`XLbM0*2#(eN`h|Kp1P3oT>o!fAkH*4ek3}hN$a|M7;1ZNv($?S<0&{7NPZkt* zc`Xz7bp~<7F{ByV(0JOV{rdIEz@QC5g7A_G%6~^o)rdTR-Re8Cg7Pp2(a>GsK-}Ri zIAdJ!t2euoF^&qU0EEx{8+^+|Vjy4GjY{A}`8pX$3Mz&&M5(C& zcBbjMP;uoInqdxy-LUwlC^2%`IbGiVdJO%a4MA2-ZPY*hYxa*%rwcfdXCuz45xrZf zdO1|?BBXi-N8QxL%(SRVc9vHM>um-QbJF4|eeA^7b!0M#=2ik^)HNo9^3g;xcoQgn z_^yOe>`t^%Y79J-zT9gk1#T(BRZv-ffV-=8cxG^T-< zArMBfS=<>;aCXWxA9HR1+0GfYi20v5VvX*HN=?sX z+x%8^Zb$wrMke(c(Kpjzg?lgS4nscosG~&8e}8TTXy@w9r7!gF?p60j_tv<21DMk# zd7oJ+^P96j6}iLLJge+0oeMS}{?%Fa;gyzPJr0ufh&FO9djFWvzdQsfTpKyFwAU9P zl;=~rPDYlKCv2?E3h=s&E7einChWi$I(^fJUhmF%o`I)6{Ch!iM*}hE^s5qGBwsnW zghgVI*Jq#-Gct=(R&T*5a?G8=1l(SPFN9Ptd%Vss%}gMLx4cMV^7Du#iLsV1S*zhs z#CP5iy&udj={`Cje%@#fM)Q8>6~B2k!OdPB9zPp^!yBEZ{W{RW=fh`k^QNW54A*P_1FdxyWHzF z2vKyi4*-@PmwlVM!(hQAl2E@9%Xod6xpKdjFRc7xF=B`3E)KvE5)BQZuHc&By!^AG zg+gknp7~K@x+JDCbqSEK)R`^52#3P0RYP^_fm_q`$O*TZ+SMJ@`D)&x5Fh9S2P%o; z@PNX2iWJ<6q7}6@#InFEUHuG>{A0&boV)W&8_E+w@uNvP2$$ml#Yznr>AUI zcGj&qBOIP?38*REDrA6x&ZLf!l~bRSr&yDdl#XS3IehTlS&>AF6ub66+^2OVs-R{1 zWRK_-*~SW#FZm>vg*0tczv_=wML8^jOKbF>UiK30bkRO$*ot&47tfTTu6@fCk>Vr0 zygo5K%x!jUw$9cYq}B<(OCRpJO|wgo^VQU2XQd;hDd1`cdYl42lEi0#=W z_8o=Fshi5_)vowBwB7KBK8H~`eeROLxqiZQ^JB)!mDJ{2BoX3ue9QCg&Urq91(3v%g~aeMOX_@)e2yTC;CN;@{D^1dZD>h3apw(#XOOlA{d?(&w=4 zjzVbP@Ba;B?igL->x?j0@4vrZw+UvErgr$ybM_0NbUxeUcz(se9lNd3?#;V?>+~6s zZzr|MCVQ$&p0V%D-i<)jd&Ej(qK zGZo9i0IPJLo4cx8(_P%bd%dRrR_+fSKrdn+nRB>$gWVK~JQz~Qo5#}{?`H4(-7+)! zOpEu9xgYDr4_o47$dIbKKa-8f`JR1(c1t7y*b5pItjd^Qi}Ebu#26p$e#B29Q+vO&sT36jiQ(0wshs zuKJpHb{0p3klu)pAt*r^@|*wnk0GevAjUK}YI#3edtcFquyAP-g>3$$qf^SIeNJCx zWG1ysSo*Ar={Vf1N$knsvt-*iRp3CggYiL15VMLF0P`^}jQ&sB#725As(%iZ(P_Fb zXFWlCh1sdd9kB&l665rnhnmz)dBqP#$31N{8fjk%jy44+aD9OPK8%h0^S!b5Z>XT8 zq`zMx%McnNcndQJh6D$`F?Hq{F7d&z8Ve|$bY3xVlS*KPxZc4od?`n%tBtSLbSH6W z6XMNmHA_U^#?_fjXX?b|c{GYxGVrWh*7y#-2u^x+=ZjX#l=pdyx^d0&8jf|te)*#u zJWKSpww=o40d2^4zblu~B+9s@`-hOIp#`do&d#+JEcU4x|Jg@SvLE7j8BxcX!xV4e zAEy8;d|RPDjG_(rEDAqhWlyPl>$o?-ves~$O+S;bh0^P4aZmI(Wc99Oi~RRT=O$w@ z<(oaEhRe&HambEYKhZpwM~WE`vY5QGeb<>gUbQ0{3_Brz2sb>@vpa0| z?S=B~qmxlj(kq5?4}}*AbWJuA(Q=7c`1C^DUy8f)n%#-wlga0iuQ6vu0&{{njEe_- z)aE*OpKvj9^4NgX(@M~Z@8>oo^Ki{3cr|vLra+;92Mx|uDA9oTpU!%70{MpoN~DCZ z%ZP!)Fqbm;_{}y-W^cxy{}-WU2D>_--&@0sKN0OjN#JP%G!(u2qPQM%7NjA#eu7W9 z&+wO@pd#f~(EWbQBruUdYKiedgiawd9@kBEzvZ@3Ae%4;QT3}3bTTnZ?xawxuxuN< z*SHUz1S^-ULnVKGn{JkV1?31rxZ{R@$J$Ahm%E?@l)Rp{XD@qrwZagyzr@^8Gt;RQ z=&7@$f?}omEwk37jVkzHz+oP?AS1kYyH9*CqN;~`4Y)nav7d|jlo#w^d+lvd-~}ea z%g(6ypM<##Jj6TqHR5x_P6|Kq>WRTZnd1b#&ale&G`xAB$&$r4-Cg9aQ&r?ie}32VR$ zgK_sIku1l79k;h>*se|jQwCqb^kTx^S!VU)iIE#kv1oEYfhSX3N;PzHw=mw|)3_EC zso+~M!b?Q*WrBNDRpN!DvwT}#P=u@LM@#}o9yu|&eq4fDoFn7(&s}vqb^=@R3ztV! z>LR}fIsxrhY!B#8yHy?YeyVS`m2|If>M6C^;~7HzIG4z>s1;dhJsmFfl|eU{Ezm5bPWxEsaZeQ&rwbaVgewe{ZJe&Xr= zMKOo<2SWtCELA>?(K3QQ83t8}CTA>c5vlO~qt2X``crV=U zTzKFizU{Kt+rPih2KZZ9Wwi%Rk;I@0i1B%UfaNdfCnnxKybQ`*VS{j$oH6}Fry(=F zY0FXM*gn_UaDTCeW3xMVC_}x=`80gYmJieuRI3=u{i)!hxFEbdas6E_&sbIK)pQU; z6|3d9URI^OFND?bTh93KH#2HMs=qeu;536|^~!o`k58-;Q#(IOGR`%Wx3(p(uKym4 z*ZGK6!kYEcGFXX1jAyQ~l6{VHFRm*ChhJpQFF5%;o-k7ahNROI1Y zsXyA3lX8kDy`w)nubG>9%E~jUiXho-t}7g-ki`v5@u3x=I=jWCu4Y%EnDAf%?mcDy z)zEbtVaq+*RC^DjZcg^j3+Q;xUSK(AewzFM*0ibfkyU5BEEJ19!yjxWC#QebelmW3 z^{;IGpq{aInK!=2Q}Vu9A^Sd#wXN1kkjxLSf-_E+D9DVMYb{Uh6g)?({)%3&gdlQAu_#A z!I902-0=41vedczMdprV&dx8?S{~xa^!Fr+tKTlEYf;mgtPg7WJcCL&duh73fvFZ- zZ?)(WH0l8Uq2Ksy*Tr8jcGc)KQ~go;=A2hk@7J%thHmsQXgY7wk?ty``Pzea!kT$2 zYN!W+DRTtV$%C~7m$DbD=;7l6uyTTIAc=#9Hz*aNkwwr$;C=HG|NADJ)hXj)LZll~ zz3p_PJX^*0vFpUHOml zk9YPt1bP6*0L(Llsq<+0muQ&i=rTh!$5@Av>o0AD(*UW!SNy}7YzMC_6d+l1hQ;@9 zqQ}CUATZ*AzxN1od%(s&if;Sk;{6d~m1lV167=jIb z&KWvhDkH`1@W7wrRRs@u4^<${g?x|v!=l)ry34L1$iq8mt;nghtFqQ$^CA+_9pTG| z`f@}MQiBMD^c$xHDkUZ4_0G9{yu4vjU-$UEKWJ2=Ady4W%caTnq0G`hD)maIREi2gS0nL=rcrm!6DeXWso;*)NVzm42bY}Dro?$=@re9UZXA*g zw2*5Zd~qTUjux>J??2n3kI0skp@0uzT+!-Pt_)42V-i0|l~%33d$39zg>M|al6>7N z52)ag9z3j%+bv~WIiBl5(Wf373mR^chgcQc5cv>fiXYE@TMvdI|QIo$J z_)<7`fg>20Q%)aFMGa<~xWM(iNu2*x?}xx$pYQ_*^9MXAKWtUEqW>z-@-qnbqC$ZqpaD3}>GEdbRi`-`-yEKw3sTolM|*<T!uT)b}#rU1acPvJO>B z$$rfDk|z5TSZnMj%7rk|W_Yj#BDSx;V?ZVQw;cGGk*~-5Hku=@a`wk`C=XzZgCz0b z46(&R(E^566Ap*U#S75km6Sre{JI7`tHfaXJcXt`%_ulRke$~ttCS&RgvNL7aKcYx zRgiH^iYhRosVDWuel0~us(O{Z?b@xGt|4QC3Uz~u64OLZQeUew$%IY?nHf2`&8YYm ziN?37!{N1&7d_^}{U2EWG+G?C<*8HLTQ_4sWCg2RN}lW7HVoq?3kH%c{(il6vfC@ z2ZuRdd=3gv{R%lQ3-Y+@o`7z(!? zH5(oh!FD)c*_pAe_+4zhdb4Ios1YjD&r_TvJib0LaB*;$2wM?M28eLul4B7}O1iba z;jeK*mScx?!9a(M1=lDS+}MWGV=Cz=6U#p^7h`_d=PWQL3%H;79MhNYnLY-->JIGW0!?$n%n0qy?gOhVAK}4jMg(il@Ud*B6xZn>KO<9 zZV#0WNshaC!RwB{Jb*mz`pl#K%fA7OM5s~JdVu#Rv3@eolSa9>{5%|#C*~NqlObV5 z_{+HWmntP6KRfGUB%<(;>N}ZMTC>jmTXwxSgykjVma?)7#>)G&yrc5Ic&KlO4^ zd|x{~B0_UZ({faPnchYETd`Wj2Dt4HiX8`g9MO787sg)*9Puk2$8O?!MBLbqe5j}5LsC|p4%eG@e}vR2$31*BL#fawExqJ;IF3vZV`YHl1?h96ClcOUd`uM)SOGMm0RV9Ck zgOx8vuUbmpQiyQ1i#ZBMdmk55Bm~i3d2(Z_Zp)T^1#n2 z0bJs33Q2Nc7ZTpT1~4GTE@r$uprrv78J6!fdG2cVAn_ty!m5e12EDM`RAC?u^wsn) ziUNVHgTG2rqf^e8xAt9|D1lZ_R9{!9P}pO^H5YM5r-ObP$O{odb?uSY9!jni+h+A$ z@9yU7RvG^0M8~mPqjNJ~(mXlm11lXci8m6_F04_pG%{N>zXuw7uiJ1$8r!$1Z=pbG zLBkOfm2!-$v|qwTs9n4y_0RsR`mkz)Q;f7s`$j2q1aVyzlmz*O91B0vLM=p6`F+{R za~fKWJ=(-@-&w1D#dPYuqDV!+H(_c^+#J=O%^#oG4$O9Gq}tFt7(p+T4pX5Gz0^7* zbpil#X|FC^tg_`?;>DIdrJ6To1>Mtq!>RTKgK7b`5$<0V>VXRSYKVJUrnI-MUW#*- z7eo5Pc#6x!njG~T6u3R=tW9Wb>z;8Q!Yes@`{`0i_7)Mw|49*?&t~Y zvR#on#hLkkUH~x^H0lA~xwWn1ZW6Fj5a>`U@Ik$DeyNIZwistpjKM0}1)MEE#)3?AxEvI%c*$gj-HicL4b3c9@kHRo~Urr${!F!$35T|@s` zU6trup;ZCn_XxN`1sgo9I&WR~N8NlCXO`=vKck1a2J?R(!$1|ODZ(bwQl&$-M$Y>| z0{WuE;9?)QlIvFk->RML$gw-hwH{~A@BI}OO1V1%7w>Nb+)QOe08-}&;tUtVfeQ)G zUv1nle;Cge;>YoeXt-J1oH~glClw-Bf_)2*D6vZ%i8lCDA-JY#?tJ>}D1|qZ3&}S6pjTax$+(->QY50n z_vvL`f>_J#y3|9Km(Xjrsy2fP<@lvuQsUR24*tIDy;N_;G!251kA9}@XcrQ~$dUpS z1cHKP@YWio`3uSK-HgugTsCw?Jl8RT+b>W$Pj^txvb)RUCCK3tsR5YSza*YLU9kh< z62BbkkIwyuuPT4jG+kfM+%#`GW}13|^1BNmeUv{b^#eOnf_I$_U{&rjjWT`x=R9B4 zR-Y`d$StnOp(qjyBsfCn0jJc%p4(*hdOcZjIuy_DO`pE&}k{+uCF;p_Veh@zu}beA{9r-e_`h+5{mCU6^Tv`HZjy9Y=i6MuQEGF^ zS-q^!a~qNVS(nnRBGIzL`z0}Qo~fbBUWX`(wPb1mwQM}`D3gAFI*N792=M~YwW##N zLek)mxksgjol5k3+5H1@-ix(5V=NF-UM6q9h@#OCF*Pqs<*8kO0T`9q720e+H0TGp zSGQzdms<6i360E?Rc`23RVw6d(=a)*^xabgrhqlVOPB6jPb2E3Dfdy zHVKZq!6AkqUC+b z-qGXBWN>3>Z~}BE1#I_($+lt+{cAy?%v@#6Ogo|(E4cDG+vpu?*Qg@(J3 zse7_&)XR7H^CWh10Be0b2d~T z;*hyIY34u?$d-rN3Jvb@HYaEYij19%vpO7%$o4$9U&@(fe12gwhEhbUSBy`M5u1Wy zT{}Cz>?&!0H&(#HK*{q_y2|-*_J>R_NaPFEYG@nSahMxaOk-$aJCiS*xh0C|0q$WficUc$E*%sCk{OXl0& z-OBWt>v#vkWJ$SkHqJ6o^@1zy0rVZ>65c$B|B&3zKHakg4xgnPz1>o8VOb~~tWAaE zlw-RgmTW^NeueR*a#L7BK?)ctmlY9T4yd? zw-v7#8P;+aWu5EzK=YPe^77!wxc2K-m_^!qS$g~Kh4C`9kLuhJdXmDIXU&cfOF|gk z=EyIuL=>;v%8aaW9jmxrq9TIFD3M06Rl{pKw!yU9O9Ci0eyZ&APkd3{QM~jjq^ZV% zQ+LQ+GppCZ7!5FUUFU^3N!l|n>ao1U;9IfEkUe2lFVWcx>X6m2tsNfH0ahk`wWaF_ z*;y{-^{ET8ejd4>GN}VyA$qh!9p*7b@;C`d1K7dB3fX=?rDir<#tu3>q?=v;I!*Rh zB^7Y9O;{ZsTy@gT2*oq3|Ff14*|ajDKf@M4Uu$#nL=M@UKk(jE$HRGwBSQ=B)y26W zu$bZ5eawSaf)e2VCWi#}LuxURe%hG@O2>ISem%uFzcW?a$8-w4sRfc{c?y z%DPY$^81?1KfeY-_vJ9a*TnX~4PuGWx+pJbu*SI!-S?+^1`=L=ffucF^y0LB*q%O7 zpV?1_$9NFgHU{|-zuJ7QIP>z}G-0<;+i!NR zO-`(9x@6~SuxRz*^U_p&8&nf;o9b2wk zIFeoRFOp6d&PXvEY2pn_x$*oc)bMEKA5ZM?wN>_G;0I%N0vRJNe|hFbipk#OryG?f zb6EVkfogEnK!iy%nS25PVNL#&i6B-Or|AGOrtM0pix1DPMliS40D0sB+*Z~&HvZzo z0F*ueLmPK)zCTFPT-wYWROHYgA;Mqar7rMw(~1jFnZyia+afr~UxV+FUzbbzi=>MP zLuznZ^|P_YIO8EdKX_@T=%x%}lR!LiF1@AJ=RpFv^Y%D&duJ9N2@AFD)@%s`Z)1@zNeogbOjomB*!+qt!btz{l;m2Mxtnjm5SiXK`M zF14gR=D@LQw4eL&WOI~uEYb^WBo%f_i+eN?H=X{gOD)Asc`rb})^JS6+!NnW6c zaBz)-0huk^njeLgaCW~N6;ioe1E=X13jUDw8kc*UkX5z!73hTq7inInTCNb=ji{z! zZ~Z~FVD(bhJ(5q<$Ov@GH6!+_VS~W1c(@A1{V@*tW*WaIiSa!6vOk{<`T=4XJ{b&{|fMhZ7$|Zo7sKz+BO(OTg}% zmn|5w%+F+VFN2y`0T^K?d8f7*iz?w)Mw76YM*WH3iH&@28!n&)>~cSsMiL&ElAym+|$Aeq)~Iqh1@b-AVa zVIK0e<=uHEAWL}E=`dE)*qjI9kGU!@lEz?zs7gb{rNnEPd;3lk12yWc#A%20SJ&x? z)LHY@5eA*^T&cODu)5@Nr^JKTcPo7vu^ z3z@?2=Ii#~@<1r+p_ggr+bMpC6Wz$kj=3&M{CJxx`v>Vg*ilmVwou>fK2CHJfDL1B zdyShOsGhKfCk!J%R`p}AE^+4pe+fJZ}zT6VoL^`DA?B8;t zVYF&Y_@?V~1OUU&b4Sdu6raANpCESKp6yt$>Q>ERFGz#HR9$Bwn8%bxJ1k{SewYy| z?n<%t1*wrKm6qvaT-4gqG6t_zi?C+W-$`Qa^E#kverYS6h=aci;+De2Kz$XH`_1ke ziNB>GCGY{MGmh$Hh-d3tcrOEr?FRFer+nAnpDv<*SCKbZV~XtkTsY4N;PgK@DekiJ zesS|r-}5NU_d7B%d)J8_=JJjtH8C*>A{TDyb!sz@9sa6!xpFjgEseG6O5KuT&zIQ_ zjolMB<|G})PU!eT6a5WJL&eA8FC>TZ*I#gZ#5^cfnN`v|6FTXsm0cn|J52`P0XZPn zg+NQp$fa;~TUTQ*W7-|kzFglSG;H@(1HF$apW1=nG;XjN=E!22QXsOTC4Uf+@`-vX z=!Rf=|14p9kY4BhQRZpFHS=oF*yEyk>U-ew_fwQ7-B97l<@V*`uG6IV^Rb=#iI>i0 z!Y}lMn0%xAu6vuC0;I-_?h6Ur8vSxFbH_Qo#@}YwQFddMyxHPg+G*F0PHdD^ZpDbm zef{w|yr3445Ti^D8ceKooe*1S2DFp=`|Tk@{y9@KWV>YIb{aD1QUC6{z&mCLqn!@o zIxHEj)!RCir2E`K^Nfn%yHc?1=#pUikEbbXF?V-h*e*FaxybWzX^SLFBtD=N{y#=r zOQ(S>0$+h&7<5+D*%|x%{4xAD89mEy{TE->nM;0v$92vC7bVvaR-dd*#q=n{n8M9D z#G6PZ662wk%jI!$>$I8`;nt2K{UC4V%rhjB?#m?*G>!al5i~%`k+5{D1JkOY1|Oz5 zAYh3IuUup0?av_I>N?ZGjjz-kDj>|eMIpsUe_R=#e2(38VF$-?1QWtGe!ZH%0g_HQ zqYxi8sXkl%c!6Y5k!224+RL?`P<&1ss#xZyrxlXt?SmBoO#r~L9#uA}>ryi#HyqpX zj5@P2BQFazns~z%($0$qDbp;~cS;Vy>jXlq0V$b)=EZHihvo%_>ycMOyxN?Q{7>0= z(S{=h)MSB&3-j7!zk(?Itbur11geELL`3Re2gDfM$wb z64}%8B`lVyLp!lnC$QU^8u89qq@F!BHl&5E35?Ribiqc6*Ha1>h15&+-E~et*vBuk z9$`Xmbz2;~!^@S}2~S47L}n)WjRq(A4MVTRV#a;}AFVka(;O0N!T-Wi+Y8Z3^JJyz z%+MJHk?048qFn?r5jo_Lzp=GopRQ26IZCb^GDEPz-H1`t1FU4rw^TXaSy&@a+Pro6 z-j|?q3(N$L_4_ZvN`s+1n&|W5aS8QATR{VbG|1(0LUs1DCdT8-Q+JsoTzwkniABL!w2)(n3vX9Ff4PpsffOuD*)E z->Re$O`#Gjg>O~ay|r&h#$C=em0bH42vcFaKmC;+(ed)}>`8GWj059Y5y`Sb8TTHw z!5uCS{hKNWi~xF0oeI_vow!Aj>@aWKm!JJzk)nqid}-f@uSXaQ&@`qjb`u=Om}1Lr zpXvp(S)B>;?U>xBCi)b+w6}y&3Q^aE8Sur9@|&^?$V}s@vS`#Ugw?jVzW0(4i-d4j zBik$a{-ApT>Q-WXu0Se%R@r#lESSXszRS(Ie}pB2;Zavl*Y+Mb#~LuiB04$*elmO4 zOw6AO!1?M0T-cs6RDOCpvgm_XGx^kcdoWk+$w5kgC@oAcolO}ykg9&&w>{a>l1xGe zqh0)PxfqVRT8*(}3>9V;vP1=^`6K+jTz|vb<+hwm^OX38Ze36JXe#%%Qh$6f0J5$$ z#A-jbyn>DTLIlhBu-34D$OWmm%9jMOay{D4J&3|%_sFuj!=5`9CX$S)SGsk~O^vQ- zRG59CzSnT!4=u4?B2K7gF#pw^8KJm*uRp=E;F>8Zdj=kzE%||!Q_Syh==3sH0cvC<-UnC$+hG7 zQX{OsJFWRxD;KgnGDwO@4&VrLzDAD7UM07{&GyIx!DgKVzP*2sV#o?w-Q7 zx38_#E}j@KVbVOIS;qtO>p(=7E|ogO`Z;92*BXyDjNt#?Qu+ z3kn#c8Yf8Vn;9L)x!x-Xi$ir^&5TO42?cKW(hEKiLdkxI zI75DZ$^ABp$ z12n#=Tx@a(hJ_0vO(#LVo?aWlIZtW6)pv;cH^3~GJxl%OTk0zuGBY(A#!JBkKg@T} zfvWCeayG)WCJkE}Rd*Ql%D2fDzFa0dtCV!IU`1ms`u&LB1%W4f*$qyeZoHh}g^F^o zCAY?xgURn?jyXJcFX_!49wO^~!xBra*)!jCBr$^Nw@lK+^EF^q30L8fCSteSKW( zX0`s3TTxPgca#a(5Gn|%RbxY@LiuwTJE?2479P31$2jO6PtIcIhn41?(uP4Gt^vj>`vI<&9geEMrl~)}j4L z%3GVZ;dI>coxbDp(sTnpSG%>U>2c$}X-!|D|N z9nH36TM^rWRFb;JRfoNr>V?2G&l)r}ZMJF*Sh7+42`7uK%_uno*{^Ng9gMH90s|Bi z+=Z?3|99`~Oa@})GfLb4xzrgnEm=AVru;KcshbI7o5Ub#t>&*ZArUAQoG*x4M1VIyi-^9D3kJB=@0b&vSvAJdWF4AV%Gd%n7dKi(T?%SjWgq5S zsRsy0AJE9UgwlB~dqa* z+9i|zudYO@0gtgAWyvU~pCLcvbufMhD+{W&1lTfF7b zc~Ugkp|FVb&SQZ)J4V+_ji*PKDfN3XLlLHW^a+*ez^`K7*GoqE=PKS7f=6y2jeN3 zEz&3&0*I`d70AzYf63_&T$##E;l8f(PK7I~V+3X%yxU6c##&3PFjq6$*PqF}xfcm{ z;7YCS`OJfUvdXOAn5(PkV0;kz6LwAZosuTBuFe1<@UyUz@22*1Z*7}MW;;fZGImcG8U=kdj(~((OblndvHFLd2=)>-zGNMg04+rcO`Ot6x7kR+h&wHF@l2M{^+L z$CsIIsn*(ZVZUECf&21&W-LVboh17S@TuwqisB&HT25ZPDGamwVj=mD7!Y7rSY&XA z{YSbu5vo;v1vV*91=xrG+mt$Sn;TO-htS>Ww*Lh*zqd063+jwC@GKvs0crf!Zk`+0 zBEpU1PuOo*ml2+=tPpBh8R~}y?r_~D#2FUc0)gYimf8g`b-aLzFecga-;e0HlDbqY zACb?_8+7iYB{)A;wy`w<$H&Gm;_SP|WU!?7%=c5b><8E++3ipyVU$VBDlAfu{6wc|ZZ>P;whtjopFs`p;F;6`cN1)8o zE_^_)iN4jwlA<{jkVrM^L<16>T(1>E43he!r{sR~_0`!h5{bVk9~XO{{(maP#4gKJ3Q#v<8T zAW*EMKEqAG!3^(j_oFp+ZUnprIGguR^<+zMu5vygGsr_Oz1*xK))Ml(2l9Sc6jBx3 zdsY~bHxhPy=Y=TzBk{lg4+`Hco4kAW}`hNMY9Ks@(P_Trx@N4x;f zX8I)q$76u2Rc7~&af2cpqzv=fJ1``4gqY81mC9}EWHI_!0}PpE9fxQhX59T!8<|=~ zuR0N%n2x6`J2}VfX9Pg-Go1_HnJ!PRuh7@(bta{NRn|TtxV1cOgonA5TddW1{8_`U zt`tVV3#_*FV&nXx(&X+lY_6CwxJ2eo&N_~nEL)p*@H(q_(t^KQk=#!n{(E?s@lt|r zS%=I{_xY1d*evJs74C-neO!rswYac%#TieWn;81vR#^Y8u~nN2imZXQP!Pj>hh^e3 zC=b{fGW&y3l^g#Fv&N~XBV$?jo0I_y6JRJXreRB5Y+ZuxB(*c#OkrS&$CEA#{t6*s z&Ge{)pcc|;i9!9JklQ9W(}M($W^C;RbmR?FDLaiMa^7DXNpKfQ1EdWZ8)iV&5bN^@t4YEQXy# zBbVG~%F`Qv1hQ9m-S~#-E6_IDFa#^-hamB5Jr>N)r6{T}btrGN;IvO|!z9T<+;!RX z!2wWUf2h9@G@_6Cg_EzBHrs(Lljc<$Rdd+@uve_ z@5QSj2dKX}W$t;1r3QsNO>hrk);I}lu$XRFZN)QXq zs#sCWbuLYOV7JC2YaX7_iv@o+CvVJ<5W+H*AOwuaOP?zbN|fl;)sAJEC-f3nuS-~h zxGfAC;zAZ`T@iS*^947YXjiOW;NIT!qMr?^m|I4{$A*&VKi(S|U$ezN^SeW|!I z09aufSv>`$?6Z!)=YN6>g`_Uc3^kJ_4DGwFV>Xa!q-lE(=+dcah1CN3A12PkNhJFdWP3QHL?*$A+jt`TFLarylYVjcE$KE# z77IPX68kKRb%0HutGUtLn2b*&p$wdBUGN8p{Y*6st2x(VQjN^ct7u?{n7?+98> zdjDo&B7vsI0xbRtZLQ|POU4uD^5J0_U2={C<;`?vW4sq{g2$8|#yFJZdvRmqAZx~3 zZIhz83G%;3w3E}*XrMV;fN-6)Ac5R0m)XyC`|BwLbvh(V`e)ee88WEgG&tGM;;hv< z?wq%S>FWhU+2#KpWCz3nTQ@Bk4xIly!LQ*4!fVI&!RCu`&+;2JhMe3?f{gX-nT$a& zaf2-*3u3HU=Gl9R`i(qU<7yVwLbiE2bQY#}Jh zxkbd&N0mg?y+P8|N ze)Vw62~k9Fwzk4GAJkV^`m}nq_b5<8#ofDcQb9UZoRls73EU;+V%R&SqSGpZuFGOZ z!DXW?gwsOxxsz~Lq3MG*KHSkYV)JE5V(ALv$y{`((T$X61znA*L z*Lev8p9*!B?$K^~o=6AO)V`gOMayQ@gkd}J7w0d~<6EZt!cTMp$|z0pdn?Lm?e|3w zy@{TfM({F7h(iO(RYbSV5^MyGMmV&eabQf~HXd^Y-{fwWHu!+;mYpc+8(-A5A1v+m zodemYLi$oQ_HdChALmZ=yy#{w26@(Y{quio-m6HzSP=Lg-ZHZ>+v6i5Mw`QEaY_rk z<-s`F2}SR;tMAHAPzOh&r<1_6V4DaMjAO!-S0o-4p@$6-FNP=iJg|#of(P?O=IYUZ z!oNoiopQ73Au6pf1I37PJUusWa*gc{!^v+R{}{oa6c?A3pb06=o_j&LBIcB>n= zWc%osA^sQQ04^}!>UPIkt%-86ANTp27~5Q+_4q}4)Ib@3vi;t?budRXXk5JW+W5kB zQjvBE0e%0R9w3|088ZU!XG?AjqsDqdkR}5mLLM+Qe&a~L{`64^FxcoJI-CD-ny$4f z7}vctQo!#cI@@T;ayM?v)zmhcJvrpo-Sng1ex7h<$_Q7^4?}XdoQ!vQxswamcc0dl zUU$l~c+->u`vpGvczVx0FEw~f=m+0kvg-5Ck>_GoRd3+Kw^n1v*D|hMK&ScYrZsvl zwuOaae>;%`z|jc$dici!wIU2!rbHM{MVo!Gk(I&YLHEfLl@*bT|2UfZG<5^^!&60$ z{l;N`MSW+jlhXAubnpLI{+$B}LPFtJpuB%i_GCDBG?Q?Zpz8Gx*qPOO&oGbPBWr>( zRZJ?#E_(hRUOk`tWOk$~J~WMiLIh>4xIc^+(EFh>rA?Eb$8AZ-iZufVNGOsthsmra zJq5D%r%IFk7o@ta)nJp7{C3$u)(L$*`UyL0wh3WaqA$<0X;BSa92k1%WX3ufB0ccd zs+lbM{{1uuIV@1whJt?7?U(GC#a-^n@2O){EKv=Med*g?QFYP)DrAmnnCM0VXJ_^t z85e6~1I?}&Y+sEPv}QU&XJdtrg}F~29E{^^djz~VRH$CyN1c_UfV+_XZbx4K`q|dwg1&WK>8Hx8dBik- z>{MVcPCv=Kobt_LGU*f644bJ|up#UeICdgcBnS%*kOUjEk1rv8;SoKLjCM5+<=!FprzyfGPUg{ofnN#3JWc@w2)h$IMtPh{ zZ8Aya8&6CP>`EXE^?D8K&iRVB457I4N$!p%to#0*E0*D*{I~mCMpUT-s z;`Q$f?B)zYtIn3de#sf>DTgkw=3HV`fs+~9NaY!kboU6;MP?n;(7Zd+frz{*ic@V2 zA=q*P^ka*;y$i6&`gIxR_kuz>KY(?Y(u?&^V3DC2!AG4Cg(Y@iWFg!I;rxx{_!q)_ z?x{7t{bbMp)jkD22s#~Ly;8)SDH{JoiWGfY$aDUa!ZK{bPAy8cWW&AGyf6~2pxR}L z8X%XGH)GsOBgEs(K`jx~$MJa$fwPhAuIob2c10f_Sn5G8KY6R(ZwEQx>=bE2WfT%v z1_*8C0-(?H8kVn9-fQo_W?Ui^(LJ?KoNi8HuaeRD^*H2@i76;FG+zq>7OL4F`3t{) zgwqY2d0pu2&;0oje!xXB55ebp#OIJ#xW2JDT4d}!8>biHDcX<%ghisLp|yRE;yB-r z1ddh5<^}9ntIu!0_+wvcTP{Sp>O*&cgmb;bp^F#OrJ7sIorqt&Bs4o(4>$>ec&?bh z{Y^S7FET(O080Y1(P6_n3Y4ix7o%}Hq)U>5cBeQ3rE4s)WR1I7-k#Dt)cde$PR%sJ z^eCsS8KrlELIe`EddW*}90hbQo%Li)-+Q6K=`ju7X`MvpQ}oFJc-R+tb=xF26j`1l zRKik4`QG7d(`soC%A_0a=t<5KW29BC{M?eLLr&)`q!$t=-N*pl{m-zM-B0Ps~^5D7m`Et zbPM&E(@Vg=|C5aeJSki!6|}67|7uR+ESXF%t|KaTOoR~|!jX&VeU>Qy-wWGkYumTy z=9a-Y0Kqt42sSvfP8Lfd0LF!L%gJVL((@_4LiNVU@KqD^2}cB~M$t&_qJPO@yL>=N zCDCq88(N{1`$N`G(+Tz52vsxi2{;6Z*u}Qm?fx-Ta6}(ja&L3qJ`K>Apb>Fg?rQa? zvh2Cybanf{)}HB2Jz;L3&qDJXedIi0(wVBQD+Z}yqa_3qTjFx=%#a}9nQ)UGy zUJb_4F4AT$np|M8dm*!cRr*7L+=J$YZ>i%JDL8f-|J+kbgC0|H#lCVU3rHgXtw<2g zfdFQW-C~D{_&oztL+WZA-|H#zspa(;Qa zLd?asdX_}5PkUu=5zUC2cEE-@3imfT4BwJfh8K`uR~o?h!e0Dx)~ic}8E-!_9by2Q zmOfJu^Y0PXs43C2FOgpCSw4AKSsSTrSH`#oC=z)7j2s_*g+2`^(ZJ+&nKtIX@1Kf(^2@d(-p* zvON~Ar>t;Yt9Ic_1MO*+?fB(6nS=C@{_NrJm*c&EzV5neVjHui`Kg>{Ke5xw3VZLd zO#oL`*e#`uFwXfR>_RYG3m3WoGLZ>iO#ULY|7Z5*8RkX!3bL#1J&R(}SO!7zs;4_( zp@+>@GkdH9Qq+6i^V;5J-xHod{q=GG1+`5QHSpw6TsRgCC92>YzW-keky&rNl_n|w z3)o$$m8?`Sdc|>gWb;gw0Bvb87h29*BU8wxhS6SdqL5DbuM^~C){kK|rYR$OHsy^~ z2ZI-Ac|V?(31mos~y!SGvIZ;xV{<^@igwGr!hr+f=xF->wnkl)4HV$#Up z<;MlOxS;D4-)^IGve~yw-LO%^5msRsAuyDbxMTmA zxPzeyA_P0~#EK9qOHq_~X@>?vw|iCiX5^C*#E;zFR-d_nhepmp!%GUI9Dweoc+c`5{HytlAlSr>OPm&Y zq`775yXq_|y|XUb|53jw-dK;nse4}8$0l8s0$0{U=M}+N>`fVwst)h`<{sermiLh1TENdYfkBDiW;!>m4 zg7?i(ALc!&2Ie8dG=9;NkNF{=g|W}OdVDq7Gf7+lTZH6u3-U{$JX@;tbFZ|8F$-$u z#@0OqKTM1Gwd0t=kRbieiwGVABIda;MygIMd1NU z4aD+`V4un6H-gFBQUSEbUA{+0!=?<{dMBp$^B%R3h=1Z^0RJ^phwMtGh5D)|*HXSH zg|(!!Tn#?1&aF=RwsWFdM{{0pz`y$9=*|3lMzM)IKF^&#`gS48#naSK;hGR$=3Fw( zmt;a8?laAs0F7Twoif5{Nz(A2wobf$mIbTp{gj1FWhr6zU`S!NXJX%c_IPy=GIExiE%okKJrJtpg9Av|S4+RB?DKlJ$^!#P#aB%WjmD#ouY9P!BHE=b<7VYNW5L}C`j>CSo!c)UC*OaC zMZ`#oZiYbxKlIzWFSML`G0Kg4Q2mOaU#r7gRf_N5*5gVXOpJBxx~O`Je{$GAv17-- zX~Vp5u|Ud*?_G7BRtc*dmYZyk3?LwM2LX%w6)YNn}fNHB; zAo7t=5^Jk3h!JOXWIUCD@U_qFS$*P(NBwJ_p$_9z2BUs_>D_erwmLe2%xTW#ntHre zzbP}4La+|YOpm`WF)3+kEN3jNMXJ+Ji9MV6VR}~|WWv~gcQtwMLDJUBzzP5PFiT@!{^YFn3v^%Cq~Iupu|r|sBL5JFJj zmZHGFJKNLlsOyVCdHmrm?f0`xcbI?TFut&Vo&DktOJP;D5fxp=9UsifFkHtSr4PFg@S>9sYl>|MouQ8prF89tQs|)Tbm^C47A(# zK{q!yciV(BUAnlNnP`*K`Mv-9waXp&6jUz1v09eIWTFcDJ!H4Op0lHqe<^S2wxzW@ z9-WkrLr^fA8G!~#lY?e{DWp-wX%B8UezQx8W__jA`LZOZda~2EB@nY|HT2a4;s8@-2?C zi0)i@YVK5(yKefOG7#rcE_-TFd!^7bMI+~`XYGII2iyXxTnAwUta$^f!msaPbZz>Y zc!S($He_^v?6;p&j$W&1oOx;=h%Wj+fj0s_o&`zsK!au_ z2G6uVJ(?G=I`86XtrZ7(&I8xR)SEY^&pw~v6^l|isU)zBgO#0N={bL`K-0YULRkl? z6RBJyag30BGEuTKRY5+4U-N${_&9k|@Bb1nNu!VYF$rEA>+sT7ZsTZRk1RH0WKPy1 zH%^WaDrG_^%k?WY9?H06KGl?2px)U>nlgf#I@RX|gZIKlz@j{ts=&G^8;Ik%{W>!D z_W=P%AyX?bWmdIq1@0f%rh*hqA?+=La>;zTdh?{%JG*NqF0E*V)LnCP6-on7o?ojLG+Ej-yk`G_;hA241 z-c6=B!a?9)jX@3=4fvy5;qKt!ih3l{89H6z6GD@_(namOUL!r{t=Nl@qTN10oPG-> z(P0=mb#3r)8f>}VYLK5aN^}`_YT-IAoH&++h~Bdg=OiK;1_r^&{?gC;4+*-(dl9TS ztMZI^IGNQ{Q!vS6THI7dCU+LwHdKIYuiu)!j<`v2MKzBxyLIl)Y%9;tErb2WpZt+LIwjeY9oA&=uK3 zJ0RO|JrFx^iiTH>X2M5I>x5(CX4Y3U?d37f(Z9R*Q)!i!HzrQ}+qTY+%&L~mo==8e ztopy?^?%T|_~jxhEOGN%G`r*acLzEEv%iVQ%${mZo@Am%dScut2j$7Xw5uE}O$w*Z zraRbkJ*;DKAcX~i;#50%M!vt?pQr2iP<(i6q(TaDDXzzx;8vfq6shq*>=3XDk3kOi zf4QGf%BAYs?N_O!&-)*mzB(%E@A;c82MkIm$TP`tRlkpz)zQAZ4FP^`Q*lW{@FY#dBC*@y8zwB5Ho=;j3|j>L?$G zK0g-^5#6Y`WcJ>4T{m3?07+%hI5KHMI{{E&CQ)dhkF8kR5uSU)* zpoJn?o@3vvr$a6>2b(v3YkeH5*u2~<6>q(-!aNBIaudi3D_|yTV$FrQfR}*mer9*T z#qD8%-2+5sR?6fz)8hOP--{m|oCNNg=wCzaw^X#&Lc31TcZJ@KkCInR4V)%u{J5J9 z3|+d+{ugWLHQVeNaY}dD2H0?>6IzA}wKUk{>#@oF444L&QDA@n=JF0^U3wP?n-xq-OztwabJ!3ZwMM!e?y#CfmH-Y>DwfURvX z=(o7-#@^rr5BQM?1qO4Mkq>;nlLrosHR0UAn{Ul>3WAo#AXVDig?6uKdm;;UQ(l~Z zU98HY%-#YX5mG<+)*79s{_#~=>i_Qh)avcehVx2gxWJ=b#8j(t3bb~1#Ov$)4m zd_V24k-GU-I>g0j&D#&azE4{jwG%eD&D#Z2=S**LGG^<0v-6XRu=`*`)+ZI;w^o zQhZHMwYA3J_t-~w8LJ~p`pvixd(Hn|beY2eu(|}v5r5Zv^P8?=Ry6{@b2r2iiz1?%z zqBR;pQR~Lddfhlc>TfEi8r(cd#Q5ars+D=k^t!pVQUnNhOO&60d2+h0?Us{>Y~Ah_ zqRZ)Y&5!Q10kOab2}m6hMV2TKTL0Lxt{dIQF7wv-GPMFSduaIR=z}&UtZjK<^x`No zp{A)(u-8nk{Gk0p zPnPRo@h#i1vbDJ!`%2awtyn7UQ1aqQ7Sw%R#qd#}u+}X_yC$ zB&X2F#kL6Ax(w@_It@A51iZ;ZKFpQx12Td^@i?iyZ(Fs9fg%)%n^ZcvO>O3+J_56K z@{r={amIgRd{?LM<%`?nOcLvyCUe1w3^r-#aVoez{&fBVh$Sm2W);%}Z-YRZ)F*as zmUv3gM?_MdPwN{Uayj-{BDjnFOhJ3$t1q;FXzA^3*)s|kGl0MWRAg5#Q*yadc{W(* zuwI;*x>;i_P2AS|6z6Q$ZIRnym#hKOSt^U+Am$E9;62a@Uq~UU3Y=nvL@~ zsk?{dIv4Wh4*Ub>m#qOh%gY}x&tmKKcMS(bK>FTa-j89{+Sr{*HX@`B(N5*93{5r0_tUFfP`Vd++ z^?ed959hx_eO|_Md5h8r9KEw%PNGj}mY3FPSg+LL3`iVUt46)Mc0W0B591DCB#0I8 z+8gDXV9QxF>o>g6B7q+mmgVoZg>@|6ehR?;z6qb;ZOk+v9uv2VA@AYxYm;Llx9BIP;?*$M@1Ijpm*V}+= z2Y-{1t}ScVN=D%D5yd*A6YA&_+PZvV7Rg$%{{&3L@jnO3jHT;sT3|J=%lFuZ;)}D* zvkXI4Zq5B$q*7qJZ3m&p%RIJhm74_mi_Z-4D~^#Jd5^+N&9Z}|V=mk2)iM#y759|ho+R@-eLm()O}tqPMDEWP zOG%GTpsVbc7yDVhp9*Su__534-K?(=9zfz%skzs+SxD?VRAg_qEY^GrTv(HA zP<5$o3!M}8db!>EVa{0<5F`pblQWCo8nh@Ue0j!s7pw~uIF$WpJ7+FhaNzSW7hor# z;+pSSe-=enRYZDE=k(;hLvKrq3BI-=E$%Bs{Nh{dnu9yiYKF$rqL`hN^uff*5XfDciHfDnF+0yIL(el6LDpjXeU?KLIskMOnG&QHOT?KKKN@g%xb zP?|G%>DQ;~R6MHZqIKnrvN|i9=}(KX z-U3moPmy!>I2`rwCR@c@9ge0-q`p=2X2bn0>dxN@fr8@QN3QTOIV@$Ef^&|4mJUpxnS7tz`2(&TO7oOPZY<;ZRTBi5$Sk&SCYN?l8madqvXaai9n3d$; zqW_`^_OU2qE(8j+Y1iji`2u6-ktF;kw=SLay}iHSiR#GKZdW{a<8votc8LO2P10GN zWh2*zdCQ6^!<(jl)Xy)ee-r=89%-|S+e3#0tX&-)1QVAGOLj!xBEe6NiGnX@rs38l zht6Xs!m*?LKk$de04s8YS799+G3fpJ-ydg`EnM^$9d( z1yiAqqTK9>V4!8aIBj5ZCZZ1od{c*B*qU zv-wVSpN!ya99;eL;BC=7_o6?u`21JoC2&UVnO2p}*of24!)j0qqte)p@I8&x-6rYy z(OVzO-FIU1I~d)s@z?JtJKS-?ht^y>`?XNAv2i6;Zr51cF*1jF=pGvsqgCcUm3OT0Ojw`0JTtO?k@T|Q8I?8mzsRB}Mb5D*FORUl&_}lv#T0&1>c_|*L@Yr( z$5uv3A;C0=)3bQNbA}Wr)y~v@d5yy~F*;QZkWYi+YMHwCv9nvY@ggd<>+qf+ALo zrP7yjOL)r=1REbx2RigIgClyY#!R9iGlh!)3iO>jF)EW!4an?%W_c6A!Z*v0yuFN# zdK6A@!dSC@he_x*&n$3LW50xx7nuZ>}yLnFcjbQw$$>>O>I-vPX@$ z>*eE`XuwYXXtIO(Rvd&(#3|>IE{{2h=As&*f!-t)MFvRJI@=SP38_rnbnM$&fGU7y zvr>oU+O}O<)A2qr*1%eR9oo?^b#si>Q;GL9w~+nC)JL)V_7y6rj73>$+6GsOs|E-? z?QhItk2{|zx&GltiPOexr^?X^ta>#xqC_-HS3=C&p68n%;{c+9=l|+?x>OBQd-8Qw z2w8GdottVG@fHnCrW-2NWwdgz7kPDyvbY)IJQF}ud;Ev0 z)syXq_awT_Z(EhoG@kucfSqb)LUou=C4bHr(YW%`WkY84aq1r#_+!&Jm!VKUv79?} z-;WnjSM%w)!o@n#BS|jkzCJcJGf;(ABkry@nbQL!tq&h`T-y{f(QDrHmv@?f^t{q* zr+}AxEr=3y8j#po5+n3{rZ}r95EsPoz3;S>M1{5NobwaXM;Ht_ElCW^Q69a^$)G$v z*4cBGu%%c8)E2sw8z2^;3SRtt7eIE*?f&rvTV`P*B&7BIx47SdFo%)NOQY7~elGUNO^@DFw~e6C4Rt?6^+W(U_>X7JG_-MdE)w5zH+uSPZAfxzF&MX|gEa;OiCQ zt?axKVWisHU2n~R`kS3O9V; zF65SYrkg`EmVeyAnqLBDs^tkJR0fHN8E9l7NhP{3n)Hhis|92Ny79L5Wm14O+P-Ql2OOUt2ZdHxc6h($XM)j z9&bQPo%CqUl@#uH3voAK&h z`FW+1cncZDL66G6L<;LPQf>j4?Uw+tQH##+-SD#zH+r}Kbl!(7s9_H zU;4^j`3k{)6!GVAeyj@yc7j(af}V3+z3mmifSkaqah(p28hmHBQ8X8yZHGR+j;|U> zS)6~C^P5K;<)jfgV8)H30%V%X(+=IO<{Z@L7K?Cds=gvmy$hVCt{)7rRR)k3Xu;N1 z%`5_PT6pTg{iJy4U%_LReVwJSYlV>3tGh%STry`H-9ooT&@n7|nI10b&>=YE!J_dV z!=flD7P6Rf&yn%*CJ&m&Uli^a#?;=V_7`Zs64d{9l|_E8t{N#6XlvxwW7Ws`ddf|d z_zTv%SSU6%(7ToekKSK_cK_9WJ*T6cjHwyAiR;9RAO z+P@zTsKgHEy(x+KYG^#bdh)608=s@N2Wfh#1QX%EI5+I4M?Hn}FP~BAK)Acz8f#Qg z^MdN0{q8|y(f^%bX0Qt=xzsGv_+iq&-e`8xNTef^vMuy*T9#Q}lm>^Ut^hRzag z(9FJ*+S)IkF4^X>ht>^lx-N()86RN^QhPS(l?RW7<>uj|NdS2!QvOnNkq{5DEf>Or zgY+}}AG^l={h9*DdumD|jvw~>cbsylR3i_T*PpH;{j&)LAe@;0669fwV$)XV!e)R* z=94(+At3lgY{R-D1-W2{ZcqzHyCidXTf)b;9Z{!!NWSU%?K6cn*;1tvdCoSa^|9Tq zEa`wP+Vj;0j{%1d782siY#xd7UmN1xPA{%cQ6=01Ueq9(Pk*seXs53Y93VlqT>87T z7Q165SrrNobKPcr-`}N|hN?lMhk}v59)+pbWTo-2hb8O>w$1`;B39|^U+vtt4Pmbz z2uT9V5YF0XU$KiJ3xRCY?xf~h>l9Ma|BULjdf(YC1~-!S+2)ccTCcFyl()WR2U2TE zZa*gqFq*>iu~xnv7g3ChayHUY+8S=)3-8K$a9-WG)M`y~a$p_0c#M;>1XC_}kW(U~ zlw>lfp^kK?zW<{1+)iz&fo&O*BQ}%uwomYoIC9R`{n*(uSd}nx?#R4E+23W@DTW^w zLpc75aO;^z!R%-#a7rmkL;iP4H(~0AuWFml143%!8rH>$$vLHUcj~$h%8+&kiUnQe zK>3UN@p~bzW0tNGO9Z+WNti{(+>l9qd#$|b7RD%Py5sRHSDS4LsNMEZ()n%%dp(^qeqzn>ZP{%b3_8@4 zjqY3~C|tCweN)Pbw%Bc^M0f-YP@@2pW;*CHgr_3KXMjAZ68FF)3{u5F4a;~x=3TL2 zG*MA9{z1q1npq~%W6T!*j^37}RN}X1ywfEqzdVU`#SigR_M!!Df8HsL|LS*Kn(_B! z-kyD?0`W4Q!eoYFy(eNZMHdF%`8cw!f54~puldc9h`gbFEySPJ(3z=H>YRc5?Pp!; z>`+BhN_u9COLfYEnQ{aB(p%xAX7wLFz_X-?<7VpGepD;Y*PgE^BHtb~cwC5l6{i>O zscWBI}FqyV43BiyYO7J!3oE)z@_K3 zY|n4ZwbbRFkBxVJMIQJ^E&I9qIsRGA1W=3qWD?(Cn_D2+Rr+i0(CJ1`zs~JDjUJpw zfdNZPA|bp#U*o?uUBPP302Dp7G<{}guA|=FJ+|sWmyO-;>#l9vTY%GMY%9@0Z`$RH zWJ76r&Q(}X>*5e3o-mtYag1n<3C$~0X~oq?sQx&TNV07Da9?-;mv=Oq;Wm7co*MZa&a47pF5 zgn79?L>Csh*4JpC?2@YM5ZWMHCFpEqp%>N)-1^gKo3*M;jG|p@kk6M{i{<{3(uK}| z&3NYzeC?5T0U0L&1CA5?RmnYw#An~sh|uh8(+SQwD}M30b-vL|6VK$xJ~#po8hkBb zoELsVps-EKk1YGE=yu8PMnqluR9YPMabW$ja>^(*Ti%bItLmi%pX`x$-92)+FK94` zZiqh9LjuwH_9E!O#LT4Rqj-7ywr79s_wV4D(>tz6!=WSK(Q(||#WziwZT(Z|&)Dhy z6U1-*%nOsYTO+#TptO`iH5&Yxj^&gh|lWrJ$uF+LiM zM*?(6TZw>J8Kc}&7~gzzSEKzc;?+Cw+Cvnn*BLK!D<&a14#YH6R*#hX%-croWY4o| zc9Zl|aWzF@ZJR=X6wRLp@YnNNB4DLWJNLj^PRx8&O+RK$mwVicpSnGXF+e7LEjPWTR$CvJ4%AnmyG~c8;?>L^1*x0esFckQ{@wu-0d&& zD%dTrD+meg`0^#YdexGHkzvHOU_(8|K?Nf<2QlC#eF?u)MaHes z)Kf#NoPQ_v)9?OL<1!(xo_!P+K1$^EaKcE5UF$d1M&CZP*xUVAlU!pJn?BmJaEHk^ z$5!HM6p@Lw)e!DD@RxnGp8JblU4K@d^^;`igyv)Tp)p^a8BOL5-62J9#unSnR=x2xwW|(<9a8Qd)UJcHgNMNy1W`=7-w* zNi>L^W$X4%Nits0rCwlGxo`CY#}maY^2X-g5H;A#jDsFo*`7fSmqhqF{e50m&e2~E z8d!RwM|tn!gn>LDN)T>g0zKv;ekztSa6Ds3Ok1>nDc#-PW&TscnuFBo$cfU4fvDxm z6!2i-BKw^7m?jODZ`3Ez^`7pv!peRDPgpb+wf0gq`-G5elqqmu&mFXWCzCGYUvZ0?v&7uhX! zv-<$+(?@UO%c*Ls?P9Q}Ifna{fpKYW97Z+r5Pg+@m3;g2gNokMXl!<~oTfvf<3vJu z0o4pXA~C=^ioZNpZCG^Cz_xuftfO%AHpg#z3{g_FRge=P0&RoS+GUL|^S6{h_USM7 z*CZy2c1jkcf6EeLV#+9dq<4RgwD8xC@40g!G(s4)v?bEIJ>27&mVhS7AEq8>js6*f zxYnDy!Fxl4#fE=0#={g_l%TvOcOQcWBDh6!_CWL3L%vf+qeQ`mxT#T3!ZM<9`P+6B7WE3}Tw=!Gw{mti*GJtE>6y z4cKm2K&FgWx5e$bU*sG7siaV;tx?3|eLmdV^1>XfPe@L!Dom&3(PYP&G2c=p*m#l% zO>!^Q{o)TF#rXBayQ*S@3!+&SGrmqxUObShpX&Z5vPPUS9L%caIG2PC-$<;UsD1fckLv+g}4LS0?Wge zY|S=Y^rGhM_Z{AQ;t!Uqdsn0=H%uoo<@grt>VV6_z86-Vnmq&n;Kk*zt=(iRbLkzX z^GD466H?IUEE!l_{|-tQ1p@qclhyDM5XX~FpAo}zIj$Jy=MOrB*z8t`c@NEVo3NEEHBCJ({JlUe7oQ$ZT-d5Z|I^G z3VJe|-&6e;*>V93nMdvmKYb!wKEaz<=Q0vDEH4rMWK8b199&m%Jqpag$o(Y0l6;Q$3yQ_hB-BWD3LB3m9v2})$5%l# zNHy#z_ZV?`-7&3QX9MMHPL+!t?Jf8|U)Jr0K0aFn<>^Q@w@)Q!D}gRJeCl=u97~IV zHnFdDMUNZx@$1){;-j2Cx4-LsPMTh;f1-_UmSL1xq4`AVjX&riz*p=6yf5M5$LfEqWF6EuB4Dq+r8PCHEO}fsg@tV3INh4W%`P8pkTfow?>7~ z>npb})HN{Kx!32}tapYbtE#$cmrZ=oO|MenSnZZSRk^okbYDID|7hY43RTTRw{o(8 z|LxO6itWlWBGRCmwccO$W%r4)A^IY$xV$A9;~10YxYSJ=v=JQPOEYiekZ763k84qk zQG1`fyEm`2=E=6E58C?<*nmUQYo6ZD1sr(_U%@^~yPnj~9hhs#u@A18dsfDSE@c<4 zUh)Ng5=#ptRDow04q;xucs}6oS_9oi;ycbMhp(O2e+ZHqaI~V`09PQ7dSbtn>n6n) zws@l&4QP_-+j3j$$X^{@jaB`)rw{~-kPM^dzapww|eGN(cOk~Us6~@k)V;E;w?lMkv2$}pr_>>*wyj5 zdLbK*9mp)+lRzTJ?0hE%hujLwwjlbYUQ#3#b2-6xH$5AygL`6wxw~#RB+mL+MfsDTf})yc`n^E8O0;l6hZ;qLB`P?Mrr zjd!%lMR+@=Em+VtOxC8>=F9-5W4dF&j2ErjGO zgK~~qx*BGk{pxw`b&vUxO?MQ12G&P?M?AwsM3NqvO=CSCf^Lk*K(kYZM~={3e_Dd( z7kDJNM8cLwHgjAF9K5{eHG6L##o<(ikY7gFYhD|TB8PS4blIVjM+9;ud$F(!DOx9G zuWY!p&mt@P2PIES^{}>9+FU;~Kq5IG{{m*h6-H&Zw@g*t-9cglE*`JvJ(*Y~&^sRc zmyy}EVbz~SPPLLo-Z1{J2Sd6#+#$MKp`LB`OJr~nhUF* z{*`0!(s(>d7ZqNOwPPl}E>W-PQA$ zf32TO`Xr#hfF4N+9yuyl9LJ9~PRTMAE8^UATHf6?Z-orb`;V<7nR;mZWL zPY}ZpeM(3^!cE}C^L*Q*=X?;;PRD=Z!yj~Mj{m$>e!u`xv9mL&C4}y`mW7%NzkKF` ze2mmR1NS>y&v9UlM)f}d;$HifA({cpjr(!SytIFHx_tJPAC;wQVQ%4quHO)D7bb)p z(NvhLa|mBB%_OQ5LWapq4&;UyMtk;$DRXz#zUwGkFE?oIatFHm<cSx==%%X#cpsyY-H&il+XUZ7htrxHC(*Ej9slOca7CJ zl#KyZY6xvaU2xPhJ_#b%CYLZ8`=0xoM1SDm#)QW^84R^SYoHce*7i2eDM!vpJdEj* zetd@lCfsVO2E4y4N-Z@UnKJV2nR#^N|3G1Nb*v#^sG^TBs5a98%*RSF25v~IQ$cRN zdMdi7)!w_P-#cPP`*SNecwch?H_eR0-ZU~*Pi)ioop^80&)s?5uSJgMLL^3cBC>vV zdv*50s$JLi$lGJ(DKXhXt!+E3-NN{Msu9iN-L3}7mz53+B0DjSlOIkwb&0@bMBK7M z8{U631@QAu<5P~A6Spv{te|#8zp`Wc@^aUx^AthlwQsg<;g_!gKS7Y;qkEcDUDLZ2 zm1_ZX$^~JFT%JxlV0XaR(lxk!F!_9y_O7(ZkC{i?Iy@G zd*nX;^?k|<_0Pz=VaX1&+Jxj*c%v`}RzxjuN%?h$f6M-nhgdOUsJ5*(%+A1D=kdV;*rrd(sxa8RIxw(e#a@Z1~!oeUKj8G zaNW~Qq@UN*Vk6WoaXn$Y!STShbpOrKbZQ_6EGqP~HS+JCsj7vTUIRJ=caTSG@AjqE z397-#OQ6wyZeNhW#R*TNJ`;b1V~}6p*dfpbQp#_<4r($#FkC^Mp$L> ze5rvY^(yp1MNH3Bn82*h{-Yf_N1ea$XG4*Q!!8p5d&-E0S)4X-oK(xSS%NeShd1fh z2MAtM%>SzS*Z6e>Y5d3Nbm|*}0ba~3rq++2RWae(i{F*UI5PMf3Q z-B_)MKLfW-?MxTUS4^JKV*sZ|3J6-7@LJF3cLmdhWdAPYk&GY|Spk41M{YvB(>ptf zKyEDL1TkPK$B$U;{z`}0dV3-r;N>sA{xSYq1ofw0b6Gn%LtL68M?lxrEBd3SNj3Px zjx9snidC3h?ew#jnP=w8wk^O+op79W2Jd&S?WwR zkJ*!GY5*mdh*=|k9lF5mYqF#}8Q?(P0YVr0f=pBsO&H$T9S_XxEl5of`MQt~Q-IfkKdyEbMang{DcI8W0oz?&Rtv z?iJOZH@1vZ{}-k!v(w|Xm!9-5u+IL>@}A4oy{95_h>8lACR?3NgE9T5NVQY^isq2y zw1X>)uBMOc04l&IyPFY?W@+|6>0eWTaVko{1qY6hww++O;~{qo@r{%gYqGpi8W%kP zo48@-Oo6Xg5i)$5Q}xysXvS;rKzJ1qqq;SFrcQGYX1I?(N!Jujl@1o{ozZfg75(PU zOpFr~59FNC`Gs`nI>*EHr$ZC^2#Y zk9_O*t7dFffOK*PW~tMl3ng?swSCuV+VEdFWh9`*?zz8gp50KVNY-zmgzF-olp$4j za& z6)uuW-Tk6Y#nu1bVHFS-l(+=NYq@YTT2uk3RVIl-j|I|zrtBTYgB(Ot7gev50ide} z*GHYs>zIKC7!!ovBX!LQ7COgy?Cfr~E?x>b*P^oV?|2&kLm%~itVlmA-8W=^{z$0V zVYHyEFpCK;O%%HH{H~{r@9gmL{nA2BGiMv0IePQws8cY8p9PRUBWv*STDg z$U1_3e6K~3E^AiXi2yR-S3M;oM6SG_ou@;b+AP(NQx)xH2bt8V#RD#s1#v$g7!HEq zMC(x!1%{nQ%UHu+bFa!xPp57&itjOkIx4A7y}`|s^ONZ%3D6lXrnu$JBLZLCI$1hP zNz-jx*Djg^^@ZCE0}~TFN-}-_Mx=9wOfg>sn8HC;WFe09lT&1p7Y~v8Fy}S?I)nr* z)-Ak-bihv1|9o7d=c5%2*4oEyN&Fhg2tIO@dR#_Ij%>vMej zM`%nB)g()LRID9p@cShW2a79q6^Z*14cjHrdRMdS1|fO*)B}m!zDD3(?1c}IQP2B0 zU`%#*GjUrq?Z6zQoSEy(5^)iuYSZ5CfxAoMBS6+&+VsNX%bU z&PN`q=3A&jP(;l+8a|?p!vQzAcB3gsX}kLLjs)6UP$d13^J6$kL>~*E{=la5a0)-rTzVt)XgG zV*|puroOS?%~e3-_9)Blgn%jeE-028~F74vXyV zU0t1H&6aFGxu`NMM{$u!`!4Mc9WN2#_@f(s` zf%ob3%pVjO6$+jKX;)0$0mr&pUSLVsnDe)$N?K9V1r3jXxbWqQ(RD)kci!rh2m5W( zP8c!z^$2;DUgyKY%DCz^%&EL0cTG3meI4v%e?awa8bKp55S%FTbCz9UzhQpOBz+-| zCeo{$)SWyyl^>-9Qm1I0_9D7+ie=pJA%6Q?ino2~GlZsoO#T*iJg{@NVoGuP;?Dmi zhYubzj@I#b(Ux`M7OZL=`o{E|FJK(k+N;Pd%s1v7#W+bM?&u{byBWDE@v!Rq?;^Kxa(PYW`nLPKBd*SK2c?t+LiE8wA^0R;np^v%ve>B_F z8>H#;^bSiJ-|&zP{oOQT7&35J@68i_*}ZzqX@3+g0B_~a2zQOQYK1de(7N87QdYVC zdadWvj&Y(oA-%!TOoY(WG)}zf?(4bhAZDCA?GGFH?mDNI zvSIJ@4ZtaPc#Dj|z2lQI83l_131 z-!nD-GEk6q-G|-Fbq;AGQyTv z*q;l!onrJ2${CsDISg|H4hWN++Nn2{LSR`6WM1=TI{=R0%DV~>th0L8G7P&xhe{!- zKcX0hT}`UUv;SlGlDvS?SFE1<^VTTA^da1aB$?Y+j0rb@XOcM9+4OwFcJ0D)7TwMH zVPJRfie2O(vBZwsl+d1WyTn^hufL*9BOtP{va#WS6qxm!^b?{gtW8+VQL6(}RBTN& z-WkcD>tjGFO>CPa6a^AaIQY@}Wi4|G=c&s4>BbHB;$7#Mj8et)PFyW0&=-K_CwVv? z#f8v~!>G$wH#~!f zbF}=pYmETBYgzNwv_8SBajkeYACN{-QZ?*>vg;Eg2cQwq-(kQ*e+GwB0!BRO!#;AW zTsXg$M-?pK>mnHF!LMLZ@a@;R4bu~xgFk5+<+XySecr5Tyzt-oskG*?=GuS#PA*W8 zLCSYy#0VT z6A8m|+kZpS)RdsvW|ZnDu;qjH8LV7K7hmYmfZeOdMG!C?K5q<@{^FIcNvJ7ob))1l zd0HCN$2N#If9k#WM-z44fg$Jj=-+R-X3$Hjm33)s8voIdk%mcSVPH>wNCInrIzj*x z3Ca4SNiq({N|#j?7FDpA71{*{l8&&^R5gf%B(B?xjw?zh2n(pDb8o$o*#Y}b%1k<~ zBZo|6=S2dzb_>SdAn;hQL70`KI_i{%KQrTR^dtf16tC( zDU-iuS2DNq$x{Q_wgg4D)rcsCTav%+3ND7s}WFiJEc?Z9`H5zcR3>nb2QrBqbO(_U6cNzH70 zEiF;zQ6e0B%OAWnoTyT*gHTKRJZzt%uKDSXQ+xwCRXH8y0k%}qT(y_so>%rE1mqR47WIe$g zO~S>6Hs8+RRGjraFQm;5YsgL6FRiCaQ*$#hh?q++36TM^OZY14Wv1d{F>8H80ms*LdJ8ndS9&LpJT?2r>5tbov3+$>qvN}_C_OWhq0Az#w2A@3S;zdifghiBH(^?}(J9#hX>=e}W z;Kk={;pMt@f4-|C+vL^_M)b!U9ryUFmeQbcR zaVgG81$E5jd~KR=ak|k3rYr%>OxJ#DL&y4S>3taLIPp~lWUv=;{xr4>Q&I7p@mZ#C zJba^}=5;o;7=PdpQEJEk8P=UR!V@Njh7~E!f(92GP-rmCMysF8c{kuUhVgl1V8~UJ zFMB~%?6oMj8Wu~1m%yh_7TuKbF5kZhG}+$lN;Wk(;Ly^FpJmOskd3?8py8eM!mOL1$>4h~Pa=-xS^7{*My`6$Gs zx%tqzcqA*%k0_;PwS3->*Xp!cyZOxs`jgk=^sILl$K%rN2nCC_0nC+C3p#@srFyf6 zAKdU}*W&a$CeAZ{NdCC@R~sCq7cYDs8{E`0hGudRQedbDdeN@uZD@ zxJL;^2f{@7k%!N{*Es4BzGorG8aNwy)K$D2h$80l$+d-C==@^#RZ0#%n$Ak@&r#sj z^(Y1k|a#YphVmRiF9AOM;rOy{0#@j?1Z*k zpuBk=uZQ{j(Is0HV}*uKh__nF2MhOyp8p&Y`k;bKp5#xylBNsMEx1X&jUCe&+;}Hg zM#&RNXk}zPbB8vgo1b7(C-<|sg}5+zoTZU4Vf=8jkj%>FHfz@or}k37jky^V+mM~K zAD;xG`S`6s9Q?{~)A*o{1FYdTx>dNxM{I-4`!0yLO@@AC?pOe}pLuY}J@F6}FM(ml zN%*ouG>+LWQLsk3m*NN~560$p)?#;J$=9ob8GYUL)4zoIQNC>+%Kjwlyy$bwk6(Rd zXX%`HGp6+ejc`|`m5pZW$5>v!4<8c6-#yuyO(9A<$GJT#GGd!B$WEuwwJY`tPcrr2 zo>OwIklxtZxXZEO4cHmHwS>CoVE^-c{SObjnlmA_yeETx6kG8xM?FmLzq9b*e#iBe zxkf%8e6~kVW?i{nHV|(H=6y{;BN-m=;T94WP$qFhm3dBg_q8D4rt%>u@OO$Xr2ayL zb$Etgs8}j-z5WdyF5|E1gb);KMBg~E@$SxgRk0jRvGz1tJ)x7DWYDV@Kcft-&GxOZ zTJ57+<})dZ_9zr8T!t6aYgL&Jwit-5zxMCH<(O!itF7)zz4-Dz2(r14NLpz0g$dcL zBL6l!^(etZT|i0Z6SBEBFF?XQ=IUOFL^-GieIR;bV77C!+IzGX4nZ{}`zf4luS1>Pkfz|X^E5UHu$atdVy zHX%dtCpf@S*A4dn5C6a`7Tx9G3TGdRbJl zde6jQS_13uiA}m0I_f>xI0RHc8^fpp9j?m+?fn;it=88gVWc76U!LmWEi5V0ZDV4u z;u9Aee!$yRJdCjzMJ0GHAPP>5e>kJQ6YdFEy!zgkN4VGh8Z?C{BwHVRRZ0+5zCJxm zYQDB>e1%!a<1@M)2d=gcdoOG@!+l-I9|C~+q%RScv)d%B zKk?~>X+81WuItto@}gQDGVdxZ&4kc3ptZ$e!1DWK2iu}R*-(!oFTC~h@ssz#$)_7Uzg?Z6Ns4AO;c&qD}@RzsO|x;jAn%5 zygzH4R$gz9F+_&cEZaH9FJiVq+|(n)hkmr8%x{>dKzr8AFl(zNRY1K>W&tz3qGK~qH*?!3OP2eKqm*mj>w*TZ&p@+g^)i)Ek?TWBNEMCKm#p&i zSrhB0SJ$STwIcynaf|g^m zyp3<52t?yLObO-6Io517fjg!q>3d>@m6@Pwt@wA`+OYNal0m)$qKuJ*$i3@-KfGRp z+DFQH@546`7Vj5an)y5@%w7N^UaATT4HLw6`8F~}EC8UZCFhk>CxMjE8MyM-Z!dLMuP&wInoTyV~L_E|gD z+WR;f^k1Fr=vn*dR;TVdfNLliiVuogdAeq6<@lqEm9I*+p+B6}fr-wHk zOKEoC_r7f1mvU~LUSEv9EzzlZcZdppN^Evpa=8>`X=gM?S)y`YPTi8AP8U|vb6DNR z7Af|=;t8b@1zxZPpU+oKO-qi!hv%-mF_>D*tvSbiiKrtjBf@Ixt*oq`4Ka47Vw-~+vUnU&u9m>qIdp)#S=r=k zTe{)Z^}@oAXuc}qauyNnO}fN{8uGH*YJ|Wt+9VMt*9~DTj$5V>m`wbWOm?vm*akmZ zaeiSb3R>_)+C7^;c^hl<@4Fp_%DRK!(1&lqk!_DMzNh>r+UubpBlH!qV}N)BRzjHd zt#NDdZNMqO9*a+LQ2VO6KS#ALBM7TUf3eknh%gTLv!nEyL7+?eEjbBWUi{zUKFA{yKL@opW=YG4Ov4&i$}bz`A`D+n^m>w^sN&c{xi zRS!Ci$GBSmXJ<22gMFi1EHYKUzEzZN{QGU05ZT}GnfA+Rtp>e|Q;?f8iP>IzG?@%@ z)RHvb#YKl>%fsYQ8*UAt6Ng+r1O3E@)HV%bG*OS4Y17^wske#?wCuq&*%$D~iS zec(J<(AhWBb|RbodtJA7(&3c*x#iARSW@c?e`|#(ZOgrrNoo*6rt1}mvxym~V14-5 zP1NAlFF2SQJ*Wyg{@V9V2&2CdHnTT*E&fkWqYVe-cKqH+7M$7qrnc zHNjSvDdpI|ticj|UVF|zv&jL%%v}ov#LdJ#n6fRmOe~@_=2ANGl7@UGL@;Hml-Q0M zR@wnGBwl17q>eCVeHbdHPbcJ6trwDINpE*UmmEJW@wda)+6ZqJ`Bv_mnckl&9e0N< zOI6se)D0UEwogo7Wnmddlur*!KEHg9RUG!s((jGMT4VpzVl}bzhJPhAb>O+ur~KS} zWQl_XV0chuMeE}iGVxjD$Rjt>klylTGm5{TAfFdSe5Yl5nOfp+-!t-V6OY`=eM2xt`p$hApmFo+DrnpWz*XSg5?&x;l{Cdwh6O~yfFC1!JM{q zP~A-vXP{9|;7YL7|JMSTbp(&1Qc1=h4cm|s4YSFtBps2$=0v~bB@4q{Oc^_?A=`vZ z@QEAEMVsH~c40=Wp-egTzZ*V?HO9a|%DYP1yJNNGKT9~@mc>vwR_7BI1U;;_{K3Qg z*(!y${Lp^YIH~;S!i~@3;m{u1;NdvnEt%pl^VET7-tzKSMZm_i|> z?FrZ@B!@nl0{p58)-&Cfms)o6nF5>-yMHz?X(BXR>-yrS?&p=2EwPuJUGxYR;#bMk z;M-XXNNMWVSi_=QBG&OcdfQC%GBkfU@-H22-(kug)5rkFqoG=RX$c4WmcDyZE!zORP)Vz;T=y7BBFusfF z5)+45Wpzs#^tDyP>Lf>pW95?aJ~Upm*)AjNsB6dvOl>NZmR8k2DajG1hi#eR@n|V+ z)xY2)$&N|2NY6z_|LjA!{m+P1i+|3L^=llQ4}yG61;kma%`W+plM>-V3_mNd`*=#V zGU>oeEw}D#gmBeQ*qSj!x#t&(iLr)G$?`?IMa1x6;kPH?0|-)i7PI-gJO7LfKS{3j z(ve0pwg@{zoI^6;k9-3!z))bbC) zw^p%(L(&rP*^{-s+A&mIYjnWgrtL|78fSW1A;a{MNn8NUf!{j| z7x;P$sLNfrv8omKwI3*an)_6UA%DmT%ud=fw$n)!+s%>mr%*eGS37yZd+wm`UZ9J& z^6jumUMa=iBOHmoyl4Q=pg?TFD04oYS64R8zbk{!{FVDzmvoN;|GLRjwy^Vdf~VZ5 z15b>bls8w>EAt;>oH9EeAI`XEUggY}@Mpdt3h#TZL-U;nvTfNOmL?|ui8hkE+T^Cg z)iiKVpz~=+&lkkLO5T3%TV*jTO=F;T)tW&gqAMeGrh?bhWM%jnInpX)aS=_(JdR?FOqghm zvRRJqUcdTP_~?ttb_0M|0r|3iVvoJgQs~wrlAuWg>~9?{}&{`gWGYajUm`s@XM5HV~&{2wshaw3Nv3~ zRd<}nz29-QJY<_c;h@_#1+~!tk!PEyjXnJu6qU?W^Z1F9(S)}QRc4uD6E_12MNB0|6uVek*8W1LrV@ zZ=h`$jb?~;jXYcVrNXyc51a${zjLT*#pL@#sX^J>6ZcN&-#*jpol6-AdH!647xMLh zW8d6>(ak}PNiGXXnP2QA{pyla&#@7;{g&3 zpW9c*n5S2@;t7oApgd#%&CeK!;hznY{l1w2tU1V#{k*V-OysMgom8~>i|MZktv22+ z*Hu&Fl56ntIc^TPfn9=>jR=L!X^H?$YTt~@Ft>5HW=<##erz`UhekdmTOoOY=**u+ z&+lDcX_4PBHTY-Gd8yAko`CMCV1CdO#um8O)^P{y)?YpgFZP3mvq|V^ zskSiHH%P=xoYg#0u=h9x|AF=Hm}$gAjh^JJS|}-5cF$jF_~{%iQFZXS+2uRO0qDCD zWfMC3KylfeHepBV*_}OYt4t!0D+5+DYy~~U(SrMoh!KHr=S`}4sFN-Wdnp&oj(V+X-iqbB^*UC=Bl(44V{|Ts1g>Mq^ z;@3D-vD6g=Ok5O()GE);e%Qi(R5kJ;F-^42Lmr2pr>VeK!p>XTH>ky{xH6TcNR#+Y z_tfuKGD(f@1e=Xj@<-S(Kbi_p(ppSt5MxiM{pFg=CF1=hS}jxu+W?B)M0JC)P#9~b zNzh2E5|sdZx)FwEhf$S@nN{>!4|!aR%;kM9H_a>Sr3;)wNk;0&EkF5O(UaCjZ@ix_ zHiX-gMi?R~Fg5x=YqLe}1!NM`$H(O5JSwP>!ft(Jb2&GZG^Z2OQC{ zaZ$vhHv}>6qcJruQ2^Nf!40R_o5%OcaW#APr$^7OiY}80{N3;6vr>*e>^g&vQc=g_ z^iNX~wxmqu!yn?@q`o22AoekkQ04YKqSUgYIm}S$u#9<*HjcI=K7pj)Ig1v?Wq{OJ z#n;Z~aus$APh&|r;kaD8=p+!JZ(56e(eJ53ye6rGND#AVdfta?G?>PUu`nfe(~ zzj%DLaK?V%mnY0{QJ9u|4tNOU7Bu^T&&FZ=P4W;)+UzYOUU@yPm-N8@A9{awPXSnd z^wKEXjwRz_e#9TeXt6?LMlwONn=a-()y2J98+hS*!)<7bK(~x{$1y*Q&!5h8xQA!Ec#`S5!OWNHm+5;qpPK&ATMf?>YCDA?=Gvu*0-{!M5-5L&pNHxAUaDGR%ZCgV)bGls z4_A+3d#*dDmkhCkL3?9{O392~K|PDX%%L#)3LpiUnpD5fu={xXw1tMx#^S}^TBB{4 z6mkKPg4{iIOkbNNKkDHHdH+FX*>?{S6o0N=c>F_D{vJtkd3c%`a_zT&BQQHuZMEg| zz;eq6+PrrP`tlcazMsbSz--GTRZj1jY;4!uaFXPh>X_V|XD3B0=0|7eupV!Ur*K!p zTi%pD$gv%>T+B-EhbqP~iCv#+eO~BtTRc52F&tK1>r?5mB}Ph4E-~)cdR|jueYDs- zFgTc4G?f&WDVV6_%1>bZFD#e>H5?%4`uY4Krk$Q8z527$>CQsq4OzW- z@fD&w$bvKC9pBRjprS9`tt9=k-IM{@8Td{ynCV>nB)%6o(TZ%p;NY(zeiOLXQN^L zKhB*Wl$Wsf!DJ$B@uPfKf9v!>V9wN_eKVHq9w~4?OxI?4nBydGv`UC&nMPGU_9mC0{Bj5N<3c zu2_a{(6DY2BD$S!@D@*AHFmPu{mDd}>&>lm?f{W2qA4>@^R9DUx>Es%Q79g~Ee$5E z(DG?AS@TUUmt1m4%KF<|BM@DQ^&U~P?aHT-5ODg*&7vDRD;k-WsmasBG5hFHlp*Qv z(!(zU$*$%{dO7-7&kXXEO9yw4ZJ(Z?;)QI2+;Lx2=;`qR&N37B!zbycL6l;Dh-%GW zmd(}aqX1`-eb+KQWifz>Ymm=xd*jf=na8&|{na)RYya-&mLX41`oJ{X%H#*qo+q7> zkXSSL=+Pqx%nDS>bd9r2SUHFGi?sY$PCbo15I{pT4CZy+D_{w?`%T9j-_6(m&|Vfe z1|o6AteJ+_){H+j_)}hIN($>s@Q|U2=+Lrp6hV}Hh5bm-R<5e9e7H2ext zkjwR9jl?4}3iK@Frwz>f-!m%hrzV;7Q|>{Vq3{uF`iZYh!R7H1cjuyvOQLvf6jJ27BQMBK!Wru1mV9zn3WRe4eONBNqU__|g>v)E z%XC6+kfO>YBM;BAeaWu97sxr>Ttr52<2qZ(nGm(ipWbOyb4FC3RbQoS@v^Sys{)XdVX`5qjD-v3!beb7h;6EfD&n&&KLGVP_t|6%Z%P-hQx zcZ)tub$&;@5S#s!BtdkOu0dAGXS>T8?>(OEF5UYBlQ>@*=kj5?mo#>vHkQ0xFAYH| zoR8o-tG>@U6KLMqn+b$ZJ3-+B;WM5X3Wd%e1^+4ViEqY(ia!go?qYqeD$)LV&DpTX zYr?WRn+MLLK#$TSFa>DPDuSLQsU=Lnn-Wo*^#!zCJ({#2fyj@GWBgWRv-Y1vo$0Uz zHl3I+5B~&VX}Cb0XMAjeeYxbc$5c7KR%JQiW{_ z-i#LZqoxdnCFXDM3<=>xJ?lClxP$g7irqg;Vsy2fR$ z*X|b+bN!lffbRRoOqwk($7NPMssKGJ}t4hReT% z<=tuVo?vN#n5hjV{~!*hd%19Dj|QPvqbDFi3);lj1?G(rcFo$Lz7(w(^IHcMbPUhP ze#xuf^@4nR^!|eM2i-88zhiVZts()G2lBPfrj`oyd&XMAiKBDnTJ_rOHzw?oUSx$1 zx#=WOC*PYn2w0pu=~oE%qiFcS3b}eR^$Fmy(AwRRu#FVO*!gP3=zdgpPnl?=OUHi4 zy2l#HOG-Nxc0}TA9tA@_|LbIPa)1X+afSj#1G1!EmFRex-&();V@l{Vj4sOPgGN(C zZI3B)ue~OhyT<`m8(q&?`d9`h&WI@HTB&feICZ?eBDj9op7!_5hr@^*?;zrwO7#Wn zx~T8(`P-~mgda3v)8TV2(=tCGofo0HAyXi_yWk?FDKJAI)4v`E+TiOBpdMJG{#$2`A?dZGd($E8%1nav2f%Dt`+(Xa zj*Z`)ii7HjJ84_e-0$z~zy^*PiJNtwPwKk_TM#A*t*-%W*# zxE+2v-fI%G2kFQQNS$yXVWC^5U6FxhOXSg~!=1B+tU_orwrwNv#OiaT*Zz-?%6dkpnktZ*Q8?;5L};>B3!Hxtp*v%P3F(gIQ^F6Uyhr(qalo zXtbjQhP0(4$wig<+~yJ69;B`4-&s`GEin71tWponuw#ySxTf#9YTL4z>p02dl$JV2 zlHqhEtRSQfX?Stcn(>e(i4cQ}D-4<XZE$-{`B5GK7o6D)d<906jft_|5TshS zD(h~c9B@Y_U^~#q4QTE^n|xi3Yjg#O_5eMv8y-}0w;tc7X_}MD!R)V~43qRl z;9_JlFn09KIQ7m|V>e!3+x274B34U#=bYMYd8ur-Lbn{uL;)Htw%AOa3H>x5-tZ43 z{JG$>t`t(L5(rU2`b(9tRpgwDMe?q3bPby+Q#l^C;<#EsGWT4au$-wK(se1g8%;LO z{0~tR&Wl=p8I$Do&J#Qh{GQn%pCxYw+l&8C{EWjSCwUK5-k=>>?3eRvn#yM^ zwgz>jBuuaiBSp#`2L!r$_J_HWmU1{GD2_vbBWZku zAM8FVF0RA*c`$iGCE7nB(IEj`R_wX(JSItewSg{C7=U;)Zeywv<$-3C9J%sgs<7#_ z6VT!=hLO*>NrXyFCiDed)$W0d_!sUDW8-P`mC|v*X#3s6MY)F>ZIFka5gi*5^u;j& z<~i`pLH#(s8vebpLrgW!H!$v>f;iR{%(Kw6)B}%xv)Jf!YuvR_b~XFqnQE%lG1hm& z*M`J3DaEn>BjxC3OUjk7Q}Jw+rjDB+cAON}tSt{KDPHCn6vsvQvO>_?!ZCY56Q-CA zEtnm>#vodA`HK*dQmiYsV@EL(VXF6a}H@NXk8M*qebl9t0yTbM)x^_G)orU5-PXF9|s_-)1pC?L0myf2l zBs!;Ru%fs^V@KqOqFM=`LcedMF9$8%`h-3hQY!DYp;glGrx_E*hWMmDteZnSPJYMZ zHt%tkF@gllDa543<<|GW^N9c|FKMMd#ViL#H(Hx-DV!wiseh2cqON1cGoob^#HqAW z!|y7(MdyEgoeBjAkvu6|(LKy_KbowS;HN1!$ci-M`z2e#)0npefilzEY!Af2uP` zBsMO>Zxy&XkzKMOO54%RbnIVX)F7>>)q)d{{FVt2E-;4JyG37jLXcQT++i1AA`o-O z1KyWgoyXyLWo;o>dX}Ke-kMqCC!NMaJ>wL#wT;1VkHk3*pgxo2xO4O_vwyb+W&jvi zWGr}`&2J1BbFk%OteIGKdRB)Vm%M;i(ztFoKCltN7nM|28xokxj(3<>EuY(QTbc}` z(lp62#NKjIOa0hDZAWm^RHn)WCdyREZ=g^t9Z8k*j{^r-ey*%QxX1H{ z`C-Hmm%I2-b-N>3c$+@ALiW(i&4u7~pdabq1(LiaKE>SQM7prE5(UcCXH>QsR;YKR zT!qWmr*7>Zjj}#QT_|DZ+HglmBTQnMT)5wFI=wdNu+xr+mJLeT@t@-hpKv%q7I(nu zx%$MV3ikEmA>vdTy{T1g^ulX&rm}p#rIapQ5ZF{oZCXD;>#)JZ4`*VFrxW=Hq!kyV z)(&&TqtRL{tn~aywcAnd4QR7XAB7^QKxc2DJX(nFft?q=Kc!vw1lv{v1$v5;qtE5= z5+LAae^7w0#EYQ`cI)r}s--D+$_qhw*XYbF=+Gj91uh`-v(*e+^Pu7?zHE!SVI>%S4^reE`*cNuY74vr5G4H<6$eH zuy^NInVD6JggV+Ma=SUIC(Y95Kw&RdwN&&vFJdO*Ge4069}^)^-K}}WDz2N6jP>K6 z(aTX-`{_i|vhMyfg_wBCC94gU+5Keg7H50sF`ePnKyIqd1{!3@s_Q3I63Xg(Ud#SN z)JT$W=FrTUbfnUgPVK0NLjfc-wYEV5Quqwpc#9^_ik`|m*pJ)_v-OT3$iREut_@pm z4q)o+re}lL_EdJFrKs2bL;$aZ4TwzT;??PQn#@YoEl*~}KnFM-B(3@E->b4@dEHtD zOu*l$0q@q4?EdDIjZHiD7?6sb3|p=N*!Qoc+6aicf=P0`{5Ohkd#%8;TV0s$i=xfI z^#W&C*Ft?>`$YqQ_b~Ii7fc`5J?NVt#|BIwh3$blVa=;i-xH?wJo7hsAVI}w%;yw` zBrtpT#WwUOIMBNfm37YZ{GIP0N#1hqTf0D6Plrt@4C?u3TCazi2CodRjVSn#c^T< zRN&@lhaolPRi_Qb(rq0=xO~ttOMu;4S6>OGO$w)1P>UIG9PU5HqN?92MoTN^mDc^a zd_VI!Io2CJ_p`i=0zJVAKwt((Pv=Bzb-iIDsL$q&ylAVFgHCF;O#xIT`{N(H zEyf%!hehgEH$6*H^E9#V$(b)emt;9KmV)iiMy1*w+`O+FA(@gRxTlP%dV#4p{whdW zRQGsU(|Enn$;B%{MCt7mGTq!HCsr!sNwlU1sihP?LgQeDTjj)f;KWug7T5A?@!0Gp z=6L|k55@uE0}?vObe0`Mvwik$2Aj*PKd|j#aS1iO%j^$omgk=M^8SIj$jSH zPNx3Gng&G2ggUm$Z2NFX!Z%1DAUb+=1Bm*po199e5&VMtogDoV3}o3;u5MgmhWfQ{ zCVXk~TE1}ey?2TusJAo9H{UfS)(N>au6YGF0SBI4Dy{{35d&82b}vZ4w#070wvmA! z#U0W5!m!5Ks7ELnA@#0u`hvRi^N+#L&zeAc9*^7CM>1L-EG@ZnRWx0>49Et`KCoZT zaW#<~dUuFJdb7N7{7LS(I9O8oi)tMnc%cdlxd)Mr^$_mZK6hdvy^xMPnwryHd-ead z0P0>%0dCQwnVKH)d*ciRA}x|%zzvaYGVj)|u9^nT;@4DRQ=EXr;&o=cE>)87Kokl# z4^_a*Q4w+^SV`jnIYJ3}*_(*6HQb1Cv*MbCd3p#Iv)+m$&EljMrOQkqC> z23r|Egkcz_Uwx-`uOQLMInd23^@R(|`zOa59_U8L&kKm@a8PYoT!Kr(4yk5dFs-)R z#H#TskC^8^Mlf-&@4LsWy?)sE^7T?vZRLSt`znBRf(`QB<1bYuhk7~b?1_;f-xSpM zv4T%r2{Wragf3Ss0|eWzVZM`;-(2dO8|7)`98J_fZT0ku*7_kxK&HsqQ$K6Ef)9Ia zy+tzl*JXAe7|U6l8kAv7Vamr7TS>hoC-EhZ2hzurIM*@dSuZ~vRk1_*)D;>8qoUcx zCD9=nydWI)h05<9sX|*C$XUXTcZ_F@V^ho3Q#A|8AE@6Hk7YFD&JOl=JVVU>1bl@6 z$6a(v!s%$J)~9+})#MYEnfKvEt*L(d(~t%V@EGc9`{Xqwh;vW$h~A|;Il{ztwyk#g zBy&)$W%aa#9CPMsK|x}Xh?d&N3}AIy%`PbAruu14ZqcLMCJ}aya)gaA2x0iN9PP>$ ztmE4SHoorC1I{py!iNMq{Cxeu@PC_n<6scR+w|K=rYSY41Fpg)C8Z z2EpeSibduzgEHTfV$UOLHO<*scM;|e&|HcdNKo15IovRIt%wn&Nw`gIXa3Y_K`zCDX83;dJF`I7cE)D(V$P6j3!ph9~B2eOnVnUNC+?rFFM|7sigIZ~|E~ zS3pBYtYh)JTc9hY8?zg1Lv=*n>X6M}E89`a8$M)K7(YeyB=B#Rctm+O*n(tvV_&5> z;Xx!}CVVWrd%Pv930=0ddD=*ZU&)Mgdq^kmVSc%)BN-?dCM1LR{`9ZFa1!;Amxyap z95nNA5VKFRPzi~+TuULQ*>V?O6GLiKgH%1llf;l*p}Iphc|GTbsAR650x(id(UA>8 zGf|}ZVSw!sjb*u|Fp!WveBoFEvGXFGs+a%P@n#CUn(~LUJeQ848Eg7CYVcYQrVk$U ze;UlL6ja}bszR%w+MkmOPeyP(J}u32jJSXRZfobv>Q*qKNc34>jQ^A0y(*2>&JIF+ z%5vxS0pkJ@buqr=UxFtD{*!yT+keESIv5*h8h<5w4%~kDaz|a8=akD{L)~;BF zxqr$)BW<`Oea{faVx(Fi?)~h`PuC4EB*_hkqNgGc2Sp9?K5*`>)yY>7sNQ~h zw!gN|`|=HenZ(0d>IWqIr3bm2KKeZ?etN4?D8u*?IKtH2=a6ZNjM_5DKv|nG&eAm~SR+Tv0_S0Dc zX;>CJ6YJzS>m~K)wX6o6)tQ)A>zvb0tWxI5LkfGIDw@gpdSpC3j zff8K7HKh=>Fu_V$_flD^1U;nbDAwr~^ zEiy`Y5LL&23V-_V8ykO4CC@;qFc7^k9eAc3gw%|e39plWze@Lh4>N$hRH~KRxF<=l zcyG{h>{yEx&@Z<8rvk%?l4ttiA+u)kAy%F?m?^jieRZ1|zlM=KJuXHNT;-PK{BR^5 zs%eM4@^z7^mdBHjQ~f@vg+t5wtrF+Li7fl~98l6uX1KZWNRjk+Ps98Q%02a*M)-QC zO&#=Mrpps7I!_t^@LwPcZn03xJRrieH0B*bVj;34iv3%3Z{?tU2%Nx?)zkdjE6{ybG4Y;MaG0eB75WDbe4>4E3ESu^2x<{3!qoc|NP+{!t;B7PFIst@ddvUm(8pb%SIM!@>9a zFM}^pt%LVhkPJnJFqs;hKn8(*lCIv27NX1toZp24HWXK{Mt;iZvt}N;kxE$KreB{K zMrS2V6)}*w?Iq?v>zpzb)1_DQGDCfP^g^xEqlCtq9aUnG(n0rqf#{AlpL%O*1-Hg2 zX~h;H5;>DO=z^-`*MMYt4&<3OO4tM~y03H38FF(VrhU0n;1uXr&Evu4jC*PqF#yxx z*Hlp-3^$qE@&^G!7pu1|YU&d|A(>?s|HmRz5$Z$%hr+;f*!eNmo4xc`ynGV4kODm; zKOr9B3(e#;o~Mn8p6OM%>Gzp#64*PHp4uYF?k*-Ct=Rf$t3It{c7M0F{{F&Lz|-W} zp)bjlywmXoQ{fCfr**vB$^J|4gInp^`@e+jqQ@E}W*-&)j%J~$VY9lB175@E%Fz=I zJ2owa2LW4d=s?liqvHGO-QFG#%pcYGpQ8` zPgYTwQAqM%$zLiJ$tcC~r<67-S3RIG@7vGit-HNIh^*|z$3B%y!C*b|ubv2S?AB1^ zBS;9F0_O);3=DVd1h{mtZc-`tA z185Tg#bK&I zNMG*iwFy;5&>B!U zc9ED>Y3pY?_MvBVSiNCpJyNp_lkUzD>1f;952OSHQIbz%@}a9`8>#NZ>kgyh?tff- zf`Fm)_7_p$qv9}qzt&w-q#zR`cpfoLb9lP0-~bGV@7h3pe+>bJ8`lemoYB?WfAZUA zuD9=wjL${G!cE}&WR3p+8A|L-yxh@=DB7}YVd-m1-GIoZMv)Uwe!@!oBIJ+NENH{xk_=I6$lJ% zVE6IMc?-3!A)N&lG+@#1R6UBNq^`sfJ%R=kGMZQyoBQe4^FZ|3pm-x=P+7NZ0<=xE zgnSvk?ZjhVwDH)+k*BqAXAEtbT=NXPWmzEaoT*ss-H)(pK{OL?4V7PR(f7@f8bp7u znXi&z)T43!_Sm+fA7e)QzJ$xeyEI>XhYtCH^c6~oz|(es(n_4ts3Z&dIJ^7e`g%GW zO2D{CP^qPjX?c#aIbgPE;m^$p3L>IS2TY*qrZ5NM_-Nd5SL*>aO1i2Yeg!0WpW3Y zix+7&3R1Z~O@Q_*zO@j~)6E1ZOt|^e7l8?Y;U=;KNZXEKi|wteI{A>2lL63N(~~bp z6>Hii7;c<%5|aG4u4+8DXDKhSr62v?*07_r?iYh+IPPo-1mH_I{Cz0{!;4TaE0s-H zS20-V)jUnkB==RKQLG^I8Xea6vaY?DrU|s)AH?Oin^kAmUlbG%syHvN`|RiK};YqsF&RRgEJmG*UHAv}`l#}dYd`ot4TOr(UMf5Z5ys{K9+fC!A50+LY8!q`pg>C#e*Jfe zud()a^5SQUfUE{m+=HiB3R+5lTHK-TUhB#cYU{^>a`Wf0X53pt;4FkFodJ* zGHVHIRC6)a@d2*af4$ia@@hl~u!>9HMtcnIthLU+_&W#-1ayJX&XOBD(mG2AaR-tE zA7%H^L@*85+MczD|GJx3SlInfFstpih?zU{pr$>WoOeXHvl77*$GQJ$2geScHM;%*+SV(0-#S$5ix`7MXL=OG( zl3)Jg<_o9Dvr5b`eBN{6nfyV-q;^T^->!<7lV5!|*GP8PNzzvw_mN2fK2P5nj$yw_ zi7~J8?c&V%?N8iKac5zcyz``ou*{^KP!Kd3{au$sw6V$em2Z z@@5w53h-~ulc-k=TAa%bs8Eydgmm9=bMBACuhRNsvmFn9M0}Uuo1iedK!e+PUsz;C zN>V!866&(3u{nhp8=b3fe<{<-Z<71xEonbjN<`lGA3R~VGBopc`XyXUfquhYcQWZA zkM$8`G%*)$oZxL*aZ-I%-gt;nXG>fjNE4k8xxd9Ee5StoLtszl-zTv$IG-EWmA$fJ zg~!Ue+mr<)PT&p913>o}i~j-Zr|!=4K89}95Xn8sE+Jv&5Qp(DeKJLKtQc6V8Y)7m`3dH$-C%TgwD9$Wh; zV$|7^yj|&tjlwP`>cvjg6RENDkJk@UJg`%O!csCB1J1LZvEVK<`jcCeFUT<@TO{9T z6}X10SC$a*y<4-XrI@Cm6=-(vjO^nUqYB9M?fEH|?8%B_SR1R14*V#-Tze{;hjXYp zWq766?VhWmZG}%a!TOM`~EnmD5#JjHm$)C}NabJywQE8h+bRrrAzi4n8jlX)w7jg2s z!M=5J3FT$dx*xr;N$0}ExC+Qn)N{SlSEC%p(*fHAn$8j5lTqO2))4f*(>EbL!>mEx z5mg**O)Vmw)_?0hxW*n;*pCL|8!3cAZxtU&C}_yLHS7S-T=LX``8w zdY|=v(4OYn*6D-5dB;7nOn{50>DrQ^@*Sx30l{X9ziPDf)8l`Jd5aG=+RcmCRW8mV z)@fB{18PG6INqls(jFX^Q_>v`U~ZE4P8)^G2kxmRu+idDqyb1+C1qrI1Zu3NPN zi135CRL-5{5igpT1>~;jB~Ko^E&D82Fjt38!A3T&8K5X$QoXU zxl=$h0<5a9!8I<}Bd}r@-N=qAHNIdtRE3VHDh}I}{^V0;NB(c^+9BVoIvMNj=H_I$ zQ#d!;9_I~xHapn82W%Z^NWb!o_v}78I9eMjZS8t>EjPUC)^lu8l39K98`EaE>GRaq zn|Qt!m^^Ug79>gjZdh?D$!(dz64@r0`R-{LREq21b-fMXDDTIYYLx@=d_`ELJgQ|M3;D6 z*g=H?f_T_W7GmUV|7H2${NVD@oDj~AeCJ{i{;9|`nrWF-=wS}VFeo}{hjh{um3d+5LN~%0+1@2pi~UMg3Hc+D^e<(egQeB#0aB64dB&wHsRo3s z%Fe6v)hV|h`_x!JwyfKkXMYPf(fKAZt@_9=-@ocLf?N5P+>N7;c$7}RP^E027K<Uob*oGYy$sc1|4L&KZSjS@dDIQdqInZg!LEXkDYnLvG~;e_d2^1m*49*3DY#N%+nj$QO zBa?&0*-1O3bQmChg@|8y*qo_ea-C$S|J;UJF}ft*e+cVKhG8X{ES*gyMgSIMP(%MO@R4=XR38%GJDoO`xYBcF5aXGhI03Z zr55Ef0qZmQ>&WT#B=M(pkdLv~31isL<3oMM!CNw)Jb%lne5dAq00E})r;6#XDbK#H zjXN~ROYEuG?FX8gVz~r1pdx9dGQgwI8NpzY89kpZ4lBdw<78gVc(dEh9DfN%={}kM zpUuRt?oB*IveA~|n<$oQ<{0zDMHtJOhH7s*$(tC=oo!XgV?Cu;=bzc4wmO(Ox*Y{W z(QhXC{E}{8r4Qk79K($30!V3nl#YbI6VZ|Xp$*V8?6hcnohUBwGZ#aU*K*w@hk*fW z;zg73qC_Tcarpl(ZZCyl-pC06D`MQ^7*W+?)>I@KCB*sPf+!QO54)?UOa)9eU5Mb) z2L^<2=_bLwQ~9Z_kj+&+;`=6sXv9R`!C5MU)v4+2L@vw(k$;QL&zPFbG zX$gH4_xlRNxUzkA%k};fb6@K319B+=NiYB)rYQI)>`qrY5Ny!$X$`@3bc=2F@~~PR;NrD zdd|Qzr~mVM2HWUkDX%wp`{g2&tFkU()-y4A#_k}Un4jW~pE?c9&G-o4QF`YO%3 zRpmPbY6lUELDMrTHieElHNJ8#vnJ#Ht@^?N{Ow|VBoyc9EJ0r;4o+DIjI{ zd*o32e~knkZXdnzX=2;K>%CSeLIn^18P)9l?}ziNZ~w2T_l~FXf8)n*n}}p@m2rA= zjARp$kTM#^krA24Asjo7NXiaL*?Vt}y^_7>v6Y#foq2vQpYQkk`2BzG`*odbKCkC> z-S^Fl*Gd>_a7z#;bRmSGKl!w}fXlS)XV0eFZH*U;W3aObQPTWwdBc|R#i_h`-{V4J zImLU|x(JWW3(L|FFC7`-5#geg(Vgx0YWVPJVVttK`WHJo>Wz!CMhWGS`|hTlF6QS? z*D5+YZ=e5~x=jW)` z;ay2mXyP?iP7`O4scG76&Q1*ed}H>VL(hd#^xrqGj1fsBf+>O#!lP>;V>saubdM7w zyx1)&>e(%>GR47ag$Q)LXK>2$+#THE@I-0)GRXF1FwGGWh?nk1}R91gx@p@|w zMGft$1Rwc?AJLQB5I{EZSFh%bKAA!?X$`Ar6!>Zqm%(Pty42>-6)4##$smI1e25RY z0^hpT^C1<=ea_0Wb0YuB{UjWZday~H{b}7PQAy0b?{yLw&%*UnpI0_dy5D7Zwo9~? z(O{G?wSyLU4jQaq_v6v$n?wI3(@V0_+sEJ}lH`^&&je!2mb01Oj8~xOQGXvo(m%Xm z8x^_{k?g5^;#8QPN!JX=UXJsBys;`a{HhBa+wNca`1s0ePNbr4Mx+G@T-s^*?63|! zGpIsY9`?^vlEt*xmWw(Lk0~DFh(6(3pJAx|)#k*8xAL1fn)9yR^4eXOsr_~qzoS3& zU>7r0$v?+q+Z6o&b^$66BGCJd>dhMOOV4X671e@U3LI8zhsP}=ul;ibMyn&xVbc}(Z{BFkzZ^aJ-88hFFo4`Ohh=jqD zlYr@P!y0QHEaF?EgQ-+qVJ>q+C#lP^(T9Z>X80t~?3L>FMYu3B* zo<}!6%I)E9-}@m+p8A{BS!S!KPF%=2Hr>2#+drR4W?S~!kXfaR5QYiT?(@9i9iD-8mf@%`O)aKqSSqendxBdsrqo5+!k^od{P0A}D#|!0$M=kmYfGQ~ie)v6UW6f@Z-- zx*L;THTNGYQoeTBxDN8lvk!Z>S5sAV+J!JJO@BvxWS*bnYLtfpCiG_mmEaftoHM0d z)C_M&BiqtX+7p(?<-HDdMlW=S)bm0ga-RmJ8}b^(>^txneVOjm@5Y(;edBQIH64?{ z8riG|-AIQYAtW`dW(lCuXJWA@ebY#_#x~DQ)5o}t>~$fao80jkhhk+#%0=f5!j86a z__KBnqjFdf$X+!T?{4ItqhUomm_3EThA$;YxX7^a0Lk_%7uoWP2R?irs2wgX$@W4D zx4LkiA`%nZxBW5cQ#|s?Jn84rCV}gMVU{j;=!E=f?gyY*KtT z@Hk^|x>BC`ifJ=70bC@Pk{8%S&vGNi<@W<7`0h)|y~-<8;YU#^XC~|Q8O8YEF!b|W z{LvO}WlsDnx;GOm6_%=2(Ma1>B)ePq9&y&oQ!anhua{1tj^jB`O#hnR>hNT5*$TP= zhoEtXnF!9i#|%xz9@1FEUjo{?K(xKFyfEVQ~xgQ;lZU@V{za- zRE@8?iBhZ47^+Hd=Qa9zwk>7%D*k?LKzUDZtI<*EEXl5{&pW{x=ZFzq**DuMZuMUR zoGsh`y-4oJ9c58pJDqR^%KAQ4n{dyYk50<~QW3DHuz2@&vfE(G!bl{e@Ft0*44XeUlbh;tyT=5N?m$?et zf0wP|b29o8z00eKI#-9So)`3KE703-8vdT7Ty#oYwzGb{o#>y#(Nj-Wwj_F>eDsgw zz@Gt3&XNNPw`F8}8bQFvwB&xELXi>Y(9B(n~Pr3Wds&? zh1^mHR-l}DutuF!Dq?9+o=Iv(zlDW!s;YXgI z=I+z3lYNSiz#xBJL7G5K+TRkSLX5?UJ=%Ubwh3OjRqs8Y%^$We?KHY(S4K(Dq)GWy z$$)zsXDTCqYN8z5N-IuGD(}-f$LaeU;jTP=Abr$a<#A{yyyD{mRy`X?aTkwZ+rqq7 zJ!6>B&$ToECg>s?xNS6?<~Rl1{lX?v$7nJ?h^*g!rmU?BLB8iB*T6X`>mOl3ucy9z zP88E<7rX)ztPZ`(H`!sKnfq~xKdW{~$}i#3!)&oC)*o-vgBkrfTk`T&JZ|~kaKt~3 zNB{Ksp>r-aV^nf5=Su(Fd{klL9I+`JV6@7rp>^$d(zB zNJf9qQ;k)jbs;_x{}7cXSw%|JQYymHeOfZhQBraA9&y5tL~)e#;%2$JytKv-zk75w z9yV*wo+=$T&Szi5h5kJV$ou71e>wKSJvT>{i`%NR=b_h*Y}CWmo8|3Z zJ?6O2j~cVJfuLP|)mX3V>QaWC7I0b>HaiQd4ZU@_3Gm!Fak(k&BN*kPQH4ym3-UGP z$L!<%+?-E6p)Y*+$F<~p=O{&9R&Y@))yqcX4O9>ME6B<#8n1Poe%21g+asD0ZXa3W zE9uWZjZ#?*o4fCrXypNobT=lxO{!(lDEhkppL!OL_p_mvr<)J5m-wTS{GD#4_x|`^ zb!QhvPXI~v$bZ_O92&Wizs-}iBWfwjjphMU=0c&V>*@^BX^u|7edwvYcvyd;_w$M*YdiC^+AzO` znC0z+;UP9$`eqwbgXR@Jc(p^wQiJH&**tqA`F=hxxlLgBfe4hGUGbnoX6gWOSlFVD z+kh3e6PI-`I49Z-+TY9|n%uwnk>py?2jD0Q&IR+VUn)pQjLOI7q?We{nF}Xtl{^&a zZFka!uO!;g7$Y(FCS2VwxLgA>D{$|f=Hl#Lu*=zqx4$VH-eQZK#qB(yQ7h$r5gjjl z3UVA%Sj=|nGsfDvI1w({b&9pdi=t2iI-+A^Olav8b%!$i6(@JUle}o|-YkXX=Quxc zgSQU@jLFd#4htXt3z7)COzvsjLM8{qKp-3TXC{PcWq&8D1Y*DNY^y4%KRu_B=}Y#G zN`KOcPYPRWob!YS-5m81j6PaO@k^>m=g*jQhiyB-@W`-fnxCC4Wo(hBW`gz4a`D&} zVTi0o;l7&e#{0PNAn4}$0(ESobgGit+V~9Cqz}^np2!xS* zf86IXm1{=jYGPAKgnx9Ws9$g)1HP_E=q-jz_x6usS%0toyCCeFoMPoDQJ6}*b(oM+ z=N7Q5u!0UK-CAE*#wSr*@bhQw?dS;BY?EAo;PQn#Emd~`8-0Ow(*ufRwc7S#<`1S`Px7# zIVjWfFQcNeSXkOU3UB{OwP4>nCH2fh1@79vcd9gphdt@8r*-oVt@JK7)s3vHlx#TC z*qmFh7ob2@Oq|P876mWWi;c`YhA(TxT()XkhYTKdZzfnPm#4Codhurk>DP)+MlzO zTw?cW2W|>eYAP8dGvgLhx%joQtu#jEOYH6FZbDhZduE+_0(Y;5>3>(4oc&$nj`o~W zs5~6gp8ckM!IV&_J?8Bqh~Mj6Su^?LzFFaD*ly=3NVd*I-(%p!^^xJs2WhyN(TyBB zU#8?msol5BxyVjCvHHhhUVQW)AAc68{i>=^%!cZZi<25(y#cy09F{z&VAheNawmJRdYjPXxL8gq~ z%=(Jb1gspQo(?oncFWewkVamOp zwns?8LR{I{l-Y&k#%ABTMPVlZ8TEx~MW~G54j$7EASRx_dKBUOm!yAjkzP`#S)X)3 zuk)EdsAZ49oAc(wEI5my4-UT@^tWi*uJ{ZO?Yet$*X&1yhK;M%)auuZrJO0eDL>=L zJJR>@Pd`#SX<6LcbL+KP-TlrO_R}dVstM<UzXbwZ$slAuQKcvXn_r<) z`bAXsCjnG!QeR^eMb;xgR^vviqEmLuE%vAc<9|Jdo<&J)P zs7GX89r7m?EU)x#Q!!uNhKIu63(H)2+H6;2h`q4(5;62b?#gfFnU6MZphK4?r=kiz zpDUot&mQlJA@!6<+66s|u4HU$oP;f6CI+h;D^q{*YBakE_TtN=eQtC-Mt$~ydeGHx z3IJC^mIEI;C@sg^Pr@ddPZ|?U8E@gPSa=|cxyY?W{{zUd1aRNn$~9P#JvpQDW43PK z`DrEl=E$M1JfXLxPsPtCy>N?w5O5kV3D`-xx>U~_jVDp<#!S}Mj(VwHpFRnfx{_G3 zXy3M5_+jY9?O5 zO?kVNsQ9!#814OeHpe{6i&=;M>iK0i8uI*q%^$f1*gM~vYDQxj!l12|&ddcmbLJ!SX1IHFIql3Fg zH7x@HUS^=fEI)gBglw+KIL6<_Im^kaCPv6IbSDIf+2KpKXD=p4Ey#Tnwn6?qeEXMDrWR`w7Fa6Juv-eOT%kO?&UzufVNY88ArL) z8@O8-i1_C^eNew*E07C+Z#W-J^KNpwZo58Y;SLVxGQju~^+#ym{qPx;sDQ>@Lps`a7`#%BS1Bv8@BK zWgS3}Eb`utA0K=f$xI#tF;!|GmdUf9)EB1&yOx`O2eN(j0&hQEiGoJ(AJTrAxiPQF zkC0pGvBNbV3ovUnWFEeO712%$`PkO1pI-d^ggVCe>zqrg?j7~y_~cfIJHGiDIV)5x zR^s;}@7Q7BeR^6XW^7fah_RzgF0dSg85A*dViwC$7B3o{lC5h+uksnlw9?!0C-sAv zbxBeyPl}*6`zl$M@BI;$<;iA)@)ow?y2_@%@Oqagk@PRipPQf*hAR#;wP*cP&K#t2 zlibqHb8z-FOU7CTvvXvUr6Ro}A5%ac2c=q@B*$ zm(^K(eOc#`(8a^`14R7Wt@S7?^xRI71|9+WT;z`X`dkIt;z{$t;!6W>tw`Qg+o6&? z*>q=xn$*_0gk`4Sr#M!F_4K9Rw*m7<+heAPn7VoW*P_P_b4JnCEDeJP(R9F;a{q?{ z7ReO7(@B@3V_5&nPh~CCe{`#Lk#Ji?mK%BYqF2+f-Vk**i z6mPEDd{l$ksy-^{xXdi)hq&qWlG%ML%|8W|fu8^Rgf;Nb5obliLykGFx1(!0G%&hO z819(FsQt~w(=*_+TqWfq--uf@6aWE^)ZErIN`7!8(WB~IWc&OE>avWDLQur$_gDJ0 zU7%^-mdY!1r@Kyos-^|;Tc_*X1C=5i)KY^FeHUcvy>I!RPiesf)G5E{&*mu~_sf7% zee105$!_DS^>M&f()#R|_gS-XO1=24ms7~#O09J<1g2e%wv?p;7>w08Q4*+10A$Rbdvgre~wX}?+zaY&l? zyP3+zD+!5n>$4o|!-Fi|ujjuWFyXbltYtAP@iE4=d~Ra8e>pUoonz2Xog6}6U{rRO zS*QNP&&S)A-IytD5)xOfxySih4LOBPwf2|fgk9T;B4}kB287+qGBVi)3d_Mt!lu#|^5F%#AMXR~Wv$oWqgeDVWzlS(prP2ehub7nw6x3@(bGLexEmo=UNx*LA zkHoo^S;orq6=Oqoe4ZQUaF&oPw&dfY&$ajNnO!+x+*&k&`b@yju0idZ{U{!2* zo>$g0++orC>fVsb6tIEmzv*Wsb*DA{xPV@LjjvYUj`bU8}gHZ9O$gP$_N)rKZG-$+j7Wwunf!kvnwNTdTWS$KUhL zglDT<08*m0-jeQh3d|+&SXRPC)c{G;CN9FNQDhiZm|b9qT@{a%;KeJs!3=8^qVWZb z&cWToMhb4f5A_Q<*5{Y~oqSd(s&UU|Di$J7l^vZ5^V3_mwfL<%6C>{O^(MtdVP-!I zNi>CNaC`BLH|KTW)JmTa_lLAsv$YtoRnO-RIyQVK23rUVu5Ap5g5lQw{ z&Cb#9b&>(OKveEh`Uf#FCfv~^C!5?iHhpT51W*&K=zuLWL5S216K~3RYBq%hz0P+P zSTP;pRV5ce^N@h(vb25#}sC*g2X3oZ(nBg_Hm>9Iw_$&Lu%&lr|CIQ`Y(l48< zFz4u+&(JN;!f(}Qyy1=#(A@-NZY4*(#ffqK-Z!iLrq;dhl~IL=ZChBq`jCGl-a_@@ zs_Ke;z8Ws$xIh{%U&VJMUgEbRIGSX4zA;Jk3de$lPLNpdaA0}Jx(ejgC0rgIZz#}wPu-8#8=_WN!nevgk1Q|s_7g{RUE^$v94Y) zycWl5c8&5xREb|z3GYtp*0xcN+Y=dH5-=qjX_ZCKWgt(cAFQu4W@Wx`R;mulkmW(C zU3^|Vm^4b6P78$xCza8^?H{VHW+0IitUlsP;*Tf!aEoIob3Gh3Iq>r*g*^Vuxeh#8 zy7;;PRk-92SQ>d7l)u^=e}64&8{+Z_MHnUh>0~c8Q}PAOm-QkmcsJurZ!h+laCG?|34ZDYMo%Z-(yCQRRiR`?~+h;zIbN98*^tiDMr; zi|T<@WIv9rd87Ip!>V*AW=QAUMz!$E`;z5bzWF0uV5BJ4i=wUmK-Ai-yQHYoerVeN z4dAIlsW@tX{bU}m3O#ab)t7RYps(IFYvm=>x|*60A3wCV=HZi~m<05AT)9teG_#{m zNmo+$ECp1iQQ-=V(I#lB3sTB&!|&m4xub}&ku`k@fK8cQ^g8Ef_dY4)ihk<+8QGdU z!`0O|KyEIKM$gZVk(+FPUb`G(l<+E`7iVdaJKe))PVYiSxR(DBI7i{oL)V80k1hLB zh_%a0IIf;ub{5nBud@KF5QP=JGz6P(E-PFs(Tk?urRw0ZGudiaqH{X-GJ5v1MdR(Q zJ4P~J(0QbKaJY#BjqZ$jNlX!9s35XI0A9zgp*lK!y;_%IX(HupVD-dU-O1t8lF4K6 zZXP}M7qa$eg43+s@(cnW1>ucD=5b4?PRz*QZcZ33Ok*pd#I}g~1tta+@-AQGNO4H~ z;{%W!6AEgFNz(9_VL#y&C2nVq(Y zg18t)VHdX~p@~rV2NT!D2IlT5s-?Mkn3Sc>YM8i<;6d55nbNHX`M+{AGEUj1_=|cw zv8V~xjAQK=n_JqmGwPL_yWP5bA(L4A1zFTKPBPtt*AP})SsEZ3(Rv~mB;h&6y=*?~ z2EKZp{PE~Yqx?*5QV^Y%2hc{HK52?3wL=c-i}Wpbm-$LLVDG&>z?s<2uX0jbF=lKrTnyZ*xg zCHe;ix=jYM*SlmB-=|)@P(4^Lz^#Qk+cLG89hamnA?2~ciPq?Hd;WydEx4m|NSyt@ zNmR<&%9Qe`^G?v&LfBe6$0*33Gjz5)J3Mza$;y^jY@+4_B35L6zU4_LflTkF!Xi<6 zq^_6i5Z|kQ`wI%Gkz1eo0}|&#e7YwNI?)S^4Nu!j%`jwSj?d6zHN2jLUi>enjTh6c z<6X-TRwHQ!4{63NE(Ephn^DhsW~0bI300}x~UQQIamv*hkYK*o)& z7$Z#=EQlrG08WzT-ky7|B&r3kDHqMv$=5NB3{|9nIxdhNAW#u&Z1 zyiid0sEjxpHrBjja4)R57VWn8KB*QEX-gWoSd(Qj+oO(c0q)wiI;m z;tY$eBMMP5rPN9NBAndn-JQ`}SQMQ#kI*CpF@92iaR2!bAv9p6Q+{I#OSW4^VW|<) zMCxJu{@TEuHUb`5Tcee{3^K-1GFQNjkVBzp^7vfw16+P)*tv9Y9cIU(}r}4Af(}e-s z7$XI*_Mr0HB!;?r0JP7dLY+}2PS5Am8X8@1*_~E5TWDywwK;9Znlg5LOs6$7PsVes z%DjtUgnTbVS9+)ko9#XYw=BvT5V9>Y5p4DWfZ_DAdt!&MwWfIZ7 zho_#JB8Ex@+A({tb*SnI0k;K1ajU~9qZbhN%L>p$zB&&_u2700W5)+mITs1LTlrri z!wig~-bxQKtWJMnIOYc(k%r&2v!TFlCC4#PhHE-<#{7&wtRXwl#OLWn=$7`FJZqk- zM((g{+AVZ~^;sM%p7V$~p%j`#M()3jqPFRN+erK;>%QwSK}XnPojZVGO8*yz>5K;i zRfjR(bPz7ndDxmGE1;o= zqi3&3ckFzT-@3V4xLw3SAujIv_{c{x1~a2`?&+3XgU$u1l5%)R|ETfRE4i_=0BHb6 zb`M+^*3)cAaBv@WMN-fT+qfLOwOqTt=K#jzaY>f}{%aYhz4yySfwm{+Jq5C=*}wF0 z?CK`57yMz6T;FA@BDTP;c(Hcf#=)pu?k&Nh^11c;OT;idFE6r|1$pr=K1Qe@C$rdN zCBtX>vzL5~BrW(}Y0_Z7&r*1LpR-Lnn^9>fJkq~63>VI?&@ao<#YV~S68l{C_VHJC z4}N7Z>@+XMN=UkVLQR!!Ub&={YndNdfoUB@?3>}IGv#?n$K+L2Zx&ZFJX(0_e&m1hCqOR}_3_!tP|c%; zepyzK8nYWlXVnd5IlE+MuXwtsTxk>ZP>ob{75%=P2piFD=CQiE3y_j-~f5PEYm$Ke~?e=zdyk zal6Vg$EWvmEd%oR13^4udozL{#3{kJv-c$aGS+_IjD;8L!n!?5eGRnf;mKeGSCvWB z;f6B1cS&WwBg=F-SbI@p`OYsp>G6*t#e&TM{5eM%qIT28(|w5!(677v@nhBHs_BSSM2Zl%vPm8$?*ZTM-j8ZIP^3LRLv@TE!XtTIeBTn2|wT{^eVKH zZ{Bh64W|;9FK<|1!gRZ-O_!k)k_42Ucime#7op7(>CwW# zA<-Py0@{xM9%E%WH5wXOx*j2|za%6I{C#MPvuYhnP@x*h*{xG$Zm+YA!?&o~ z87Y&)B@qg9ww0liN~v9}^6^yIT3nc|Ud!@f$L#0DIs@QmUXcYM!NY=s)!l)Yhzb_? zzae3xs9dq3-BY+(ANc;Z zQ}*$*OGajSW!+pIwr)hpz+M8Xv%*$(L$5>|^dT6SOk3iA`TP`1%^wRNAQYDN3e#qk z+L-^*VXLSClF`cKEYhA(yJyFzY_m(&!53`1(d(Tvsva1!S`CL)DovFC`tT)Qosv5$ zlC6?0@RJahTA^~>@`GH}I0T8r_|%8wr%PcLu!21TY_x6_ccF7rQe zPha(g6lqE2Y7N|=d<~+|@wl*4HlTd9p9qRjUA__Gb0fA_nr`UL0weQu>JMg@|HD^RbxQ%-#ua4&KH1QStLxw#g=eiwJ` zg1muhu@6}n_e580!sg-AJT){BZ`UG;`_iWD*toc5oBsQ*1EA?x zs%g`h4uQJvE|W>muBMWd2CU0!Q@^x2k`x|Nr-V9&U4p|VuFLeWJcmeYBVyy@*SyH! zDS}PnoQjU^XT^ov=t05>=Dm0hnrMHNURA?kim|9_)!^l&lP(Qhe`0$-*}6Q8ta?TH z+MRZ=|9^5nR!NW_i6CvV{w5Tm6XH>0{cbSCqi_c*ZuGQpIoMg2XQUgtJe)ZL7IXr@ zAV(RC)f6^&)Sxep$f?{{%I;DEZK354a8-I}iFGfnQ15a{=UsErYIPe?hzEP2rKmW4 zLOJAnlRLIoWRHh=rIYaZr5roYWrpZ-E3oPz0+$(h{kmgRre-?^=gS6_1#9$bMZi}y z{NAYG>h~bvt0F;2oyZA}ErgaxoK8X6GAQD8T4P>UtwH+VHCnHJ2SqzfTOGu!UmhLe z(MAJN721nBqfWBPIfYt^CtL#>rJ++Lk+{KD!|PqU?>V&7Ra$xpf#rOW^1k!or*$t^ zfW}WGx5`dLNPRCfu%ffSLYZ}D00CfEn`-NVJ@&9=qGH9EC?2=fq4cQFoyjf5+TM#z zXOjfgo2rqOFH^Bz=G`705~xdTd5?KuK!uXsewuCoT2jJITVG~uoy&~vUps5Ze)8DE zZ=#3Z0Vr~!CqbITRHR2A(=I!k@#zxrK zXq*#n$Q@3!F~gXqu+@x~1NJxIjbc#KMWKLt`^KwlJ(i{=G4Z0RAnMguzLl;D(K{32 z-U7EOJPtu7$D2218-5*Dq1=$$Vj)vJ<}n0Qf8Cf2T z)nOWgq|xeDu(*ecl=Mg6wN|LK`$|kc6m$dqdWL&LOOE4xEFld(pD(rH@oz*fdrIwEIXLcm&Jkivy@4Fm-} zYl#g{aCv;<63u4#jmU!IluQBW-}Pg#*c8?vnSd8P4$jtzptkNcJ`^PN-7r3-u=I5b z!xZ+`uQTs`7D9*|640a0oYCslYs{Y_7z>>F2%=FNs(~_At|66g{$6h5&9@0^5A7&? z{Dt;D_q*Jilio?X=e?{w#Si@vc21PT`6R!6EYi|jT|at6}d4cq2@&P{uL~ z@xhZ6DrS?hB&&m&Qz|Fdkur3-3Xu+tvtH}y`j@oy$s;*^ylvmK0`OL_HhJGGG!_II z?5F=Dg#8d7G!YPN;tVs8N#!>|z-R%oBmsr?(-v|IFE}w3*jOxIz=+OofNvl6LfRJbxCnfLqyiMH5N5B9YOHOHaf+wh{X54 zA|+K3sp;ika)xjd%_DcwgEwgw6oMq&Mc81sfkO+u!g*#o&!~ZtdCa837JBRIVI?(p z?B*@HjyKATup{<}48QNbjLg)|g>p2O1WT`#3<`_<F$Hkk;S$c3uj@Z}W1Pa4pVJX1{ee;+10xP(??(`9WYgt(y6)#OWv$LT~6Q+_*X zWu83xd1CDnh4s6O5yFIEYiOxiVtFDT$rI+#^ae?A(dT;yN64^6VaDwenj?<-zu5~U zjgA=qc(6X=^|AFUQ1E+#NBJDfZDX20x|;wtTmSC7r#)WO3j*^X9>-gZuwyyxa_0Dvi2fJI@Wma6HfK5{e>(NvB4m~YO05}%O9?6moi`Mp= zA)TCZ-@KyoJ-=-RoAMA%0k=eP##+3Dc&)(@Z{-8Y8KA1pKmtD z)HS?`pq3)CL;tV|`NopVTmUlhVi0Fn=HPwGeapVcG)^d%Y+OcY?%=98^@%7A1QV{Y z_)JnSV*`Lenyt$RRx;?rU79#&%cCH05230ax}E8_1YLQLQ|wqd$`!qyn6{DlI`xyF zJC_<8M7cmFgV=xi^hXhq!e`WxV};-|AU26A8lgncgkt-KP!H!hm@+>qA&J&EP@cFe zV}1Wg#0asVCBZV`^1JylDJ<&Qif=UpX@5Lv8usgyV6tu@f5L@l*k^FDSs^Z(h4WsfuiIh@$*I}~2 z=tWR<*)x9l5gPjS2B|hxxN*F`8oT*lt{r#;1MN$|9X(^EGiUH~uOS8Y_*%={-KLjK ztSRv>VFvubQFM)po0VB1-yb8=2?^yRGEgx_r@Ulk<}SIVETg_Oi;RVt|DbpAls0&`b^Jqmb$Uovx#HE?kFpkLjav;Cu zZ}8H&j08&A_#Ny)h@j7q;QmNpx=d7P{wE&@W0sN&+Xikuxib5k?O(dfiKwfE2xbOL4OG zoR89$34H4vP{xy{V^|bWn_MrI;`Nk`;w%5qib$cSbt@gLoRfr2Z+-oRf3Bv&cjbwv z3X6vsecR%-b?8O8lIw^BefbL3uVd9F79`wHS7HrlF^{(YKJb#2-@Fqd} z3Ncos?UgMjn8~FA`oB>U>h<7Ibn7)=vjXvLkw_D@v9nC$@I@$AoQcf77>XdbD0^C^ z0rsyRhANU1am(|+d7`8+pkf#={f?Eu_jQehr28#jPEd)p`8RyPzxOksYbrjt=DQ!S zs1uuzYIHNX75LL#s0oWwVx}tJN(q+0h!Zw)K{gvrWE=HcqPQWn8k-7R$So+KfW}qU z3QOOdUtOXE5jAl~_qsLxKRxE5o8Lmz?DcpeOH3k6~k1?Vp+rxVuv-uEYy9YtjEWJeR(nA4XO>k)R7W23G_<2&^ld3oKRO-+S zk{m0p8nea)t`-&kTTJS^&uS)YNKZJPG@~>rh*QYtfY5yuSflDyTnNJs#=S!3mil|Z zwJeh;O`I8;G!9S=YJwJI+WxxKc%4Xhs4j&16Qaz>bg+8TjvjnUbk#xAR6_-_LAMgL z6kvM3pYN}Vfvz_D9hjYPPDP-mWE+gL!wiOxmHrWOhiYTpdxj&?1M?z#ghr0g5Lo{S zJZaDOT21BPv?YO{hh7|-TnF5|Hwrx71hJAU>aG;V$@jd74Fj(IqM*;onNyKXX~Hbc zpOLIt`6cApONm8^33E#Zzpb$jl#~<^hSbaj%uUff-guC&Q6D%!@6xgSy?~gb3~Yq; z@7)#f(;wmV?IVKJZ(xc06sWIDxf0GQ4Y?tJeGw9EI`3vu_RE*@#m?rrfI2j0}x}t zK&&`aG$LFkyDTaOL9Q6HSZXc-X79g96eX8Q(Tt1e0j1Pi)J?rBq{$y;YOQ;TkR!^q zWt&%=iF`R$bfM#jt#ol9w@8n)byhW>TeBS~+)mC6icCrd(;G@^iiXC^N4?Wfva>xH zB}~}f*gNWb(mAt2woD38;tR^FchZ;0iJ|(H53?&h%m2lS(=CCDm#9rN0Jed>;6Ev> zyIbQ``oRsn-u;~RbsAFw^M7Mm5lMiCTulYclik5%S5*-)9t4Wp)i-R%XcC;9+dxcp zu?Rylv|aPbD()v#h&>PbK-5$`2Zd>S1xW=_cA(Ik3sz_Y>8+zf?`U!zhLC@K?i7Qv$o8QK literal 0 HcmV?d00001 diff --git a/ifm3d_ros_driver/doc/figures/rviz_ref_frame.png b/ifm3d_ros_driver/doc/figures/rviz_ref_frame.png new file mode 100644 index 0000000000000000000000000000000000000000..befe4de790dc333c02f9e0583f440f42e943ba35 GIT binary patch literal 57878 zcmafaWmKF^(v-4-} znbT5TeO1*})qRJ_$%w(j;J|=^fx(Oa6j1;J12+Z(`xFZW`SFjTkNN7y*B3`2aV4ma zj~A3t=*MqtrypuginbD%=?kg%u(**pDH-gIcm zFTi!sqVDgR%|Iku5vwu+T+Pxl1YszmH^-jd@3mZk?@+AEwv)c9s5T_d8mM^q85=_j zP(*=9@8T^WGMn7@5ocGp!KRbN3W;06CJYyJQq zEH}BHoW%x-o1Y~tYDJp5b43DUNO2pg9VhA7Dz*FOHumk^#_!u>4I~o;Yg5=Bs3Bb{ zqbe`pt%&o`s9{{w2LR=oK*JufJ;u=!zl~T#=gv>-;mye;CjW@}{gfg~8H?%E)1uYf zEioXa3HW=KD=M_ny|iRWAzNSb1Z_O5aozm@?k%YHsj<#l8yTmL(!VtUa-_b%rUPAz zCnhHHl;UaGp`g*O*UkaQnooPA-Iuqk1+vmZ7<;A!X?ZQZy0)P!kRz8^sL6Ntd*Oq% z{{0F53#!Q%nqn3Mh|R?Yv4BiTNA832gS}xD=TGdF%06;;vSDx}S0d$Biizlx=V*<-6k+{Z>gKcZ%5FltZG z>EckJx2v7pTEj*QCNO8_YDK=-JPACBY0h8Cn|v>v)A*7fBi$zfLq@m>Kj! zwYdDkmpr^4T__bP_8SO6;C~m5ZsUsRrpBJK`Yg69pjt#2ZrVtcHqceC%a^me7XGJ@ zR&;kQ;rOc$bf#;2KsbLM9eqK9JhBYZC|_wJaYk+SF|z`@Ii?Gv^JZ8kpx z*?`5R%e%}$*A&s}y1{NOL1pPGd!S!t!Cz-mIZkpY7Lmr9&W7%|YhehOn8TCFysaEqg6jFoAfi7+4v52Y3^-u8)&Z7!ls}Q)3sC8r*9Bw9qLhpXWp3(i$qQ%$Q zYK)bA$d5GO5{gqwpID=A{lB{1;lPWC&WC!KLV#PS=J+ICzj!mlwChAO?y*RAnEi+> ziNwZD#)e)VotyGpi;h6l5dT?5l)9_wa@7TuO>8<}0wjCzoZC`trt;wuh}@l7DA)2F zFB>T`5gOg(7BF?Q%Op*!k9Po=3=Zp6-H)9l{}T`TTBYo>J)&iys;2#L`tQ%ffsVdN z1v>lYD-9@|QgH>M7-*Ml$tIlR@)0@dI*cKtUxn?8*TOE~9Sjpn(c4qY@)vV8=@Gsl zyQcPUzKn#afhCY95zBviP0*%McT1>B6XXeF&`YZ1%iyC6Pn*beh%DLZ03lu&-(27b zKQh|hNmO8g>T3~y;JW6tNO}Rxy}Tk%p|xcUWvvZX z&rQ72g~QoQSxZ2)TO*|4X0Jsmyd9^xIIfA~nzrpMP(MW-TLPj7L0?n7cxImE8VBY(cHug|hEKR0DNZL&* zhUnNVHob{N3*Gp?vNR>y2)+t6Om>pPGHk3)X5mg2@U7$kbr~ zf|H%lR~=W5)?H+N%~(jYV7<8-&3F9W3OVmp=O;0@4R7Vy4=wrV(|PEW-M=u5VyR4e z38w>?EP_b~PA`qS!wPyZ!m9;$9sdu`lt`((}V>JUFs^i<@@a7@*x z7QF27mW3VdaxC3>o6gUX9ht!D>q=D;V@ihLbiM0j`Iok5nOGHi;zjoIU8TV_H0H$} z<#IC6;VXE3Nt`w;mhf_`4SDozZ3fH32Wr5%Q|l{!_(l59cfJf4Czm0J{}adB=vm0f z%!u%N=S#8jdfm|89Ekn4hZW(Dn;2ECMwqWcu379Bvx`IxdIF$*O1f7l-7yUNk~wk% z*@lrWuy0?Uy%MB6RHR9rHaGDiiUgE#9RVs8KT|x>?PmRO908rKYm#}MInbP%zCSh{ z9?a&j=;*P#1J5a)#3MY1@<*ZLTv%ne%OhPWQpIMqN%V>4!6tZboPTRnijWqjMfA`;Bph>z?OYtc!8px|Ub zDC_E2HYs!-Z8fOwK!D4AIrc11+ucr zp{F~-D5Vf1WX+f|h8J-A9A(c<Y>rwmc!CXo7tVa ztcz=ESI!?}L3sVk6>Xl1B{1?xW>&suI4u@G|5M-cT_Y}>KqlYLO~HIpl_~!E*VD;9TzrQYq)dE1j}- z+zJ8p0o2RhdCQDXm{EUr542cuP;ro1mY&h`fAaA@W}Vp8%kUXeB+;$)%8lTbi_3F) zErU1ch+Xc=-l)sxK}UxQ_oMZb_(ea}?@a%4#%ltFrZo~XKyqX=(u+U)TTh?+MiiG) zZ~J%FPMU)`7P1a1!p4Mo@OqeQmNG5tgB&Wg#p%zkhEw9_7Je|!fcol@L` z{}kRH=OkD)$tNLnXq2t5fyw1X)mohI*L^*9BY)(+&F9$Z{OdxC6?&JMEm6{7BeP}L z6whE;b5wK4ipOvVCQ?wB;%&b;*QOaHHDa9KE_l4PyrFc%`tA=U)Dcq5X01$2WOK3D z&2Fg}gT9|lW1o>SX&X;X@tv`g z`T8Q|s}z02CJ?!r9`n$tBp2kh28m3_J9Y>gpreKQ&jsG9_Fw{E6LfoJD-JTB+| zqZK#Lxe#t(ho$VmOGm~mJK-(Mf*%nZU@ALJi>D#2vmtAL*;S}ikQ-~goO_dgZDbg? zTcqz~dNAh%O$Lk??^xXKm_BS}B|{qd9Kkgn-@tWW!d)Ms z*>De6THQzd{+ae9D46JeGZrLF^pV~)OwJBZ;ru zi-#i1<#9Y6QqdJuw+*b}&AK`v#Vx^xC)a|ALmO{aTFFs`|7;ae_GZj!YLHROMfNv}1OoNUW-@>Ln@aYjeHTyp z3o9WbBJq)b^X2cb;tFK{KC4skQO4!`O%wx>zDxd;{GSf}gNu^N%IL~L$wycL91S9s(f0O2#-*g~C0)F>cbo>7b^Yu9Y&lxZbRUJ9x zUzxmq|9Q^+|H*e6TT@u5_Ovbl`RV}aod|Iqr9f!Ebyx}73{B8tH*#ipPmJMSEnuvB z=VKex1-srn#y-nv8quQ`xVEUfhCh{1J#tucuZ% zn-2b0k9^ULcGkB%2ej*>k;#ufrhnBlJil z?OF)cJszBVm-`yq_C@@CC4cDfJgPLDdjo=M=BX523m{RWcPD?~^Mve7g+?0P_|;~D zuIU+4uJ+W(WleemTY>a$?-K5{=rgFMbvKika9_i#duMjr+zD36-NA|P-BJs{v%F^K z{77b7ymF`Ml2L{S+lN$_#R;A&$0f_Qw(d=#l+U|a(JpmIoy6o|I&0R_SR`Kj(&5(9 zymgR}7VF%~WOD!G`ybyw{{RH&XQUvhZW6ZNlio1*?m(X^1aG!JhA;H&i zEgvp2ZN6_>MD{8u!%Bk_z?PJ|)MSj+kMblWNfA8Rl8otA>GPCoFom0NS7&UXp?0uY*rH8z|_<|NYk_{zK^kP zwud!R&FafgK5BnKyVM;Gul2LJe7bAhn_8`T7rD7)F~2?sjY=vkfrl2~&^X65z><`4}c(7FgVn$_4wsHi6df-vG+2;Jy4~&kkILXQ|h-51cIa zvtU%Or`|I27_iBV?^x#@v@tv4VSGULR^hSY+gXVNmRcWSF@gQzOm#SrSHEOf=Jv|5 z5v>CwUJ6@$(4xbXbN^;UxlzdHqIRkq@qU}K)Q2ia3Js{u8@sAB zJ5S-EoxZ&jhhjA0q>vwj*dOD)2rkyk9C0)S(C*`^^t*R|pU7wpsV+f0Nw_cLEgo!_ zHUwZ_I6f{TJSFA_?$Vd>c|<%9pt$8%ab=WJN2Ov#RlLR3vU1CJ9Z2(BnvlGVaUEod zpWl-N)b-(;&aYVhE~JO|CT@0RXW9-Dil?{gIq?qRyheMmn(1_oG=zXev>ush7*(sj zfdhyA(q<{${4XF{q*@N=WAhe0qS_3yqwBDnobMq$46#n16ZBpsD=qCj?>KHdW~Czc zX9fsCV$<2o^?eiLX>Ip>`?pcNpr#ttouTk*c6MfSpc#e@_h>*N0RKVQRYjxi(c9DX0C$5gm1sA#vkvcuRv`i&w7>`|PZPy_ zV^fbiGg)W;Ql%ECj;Ogw!?}?tpid15M3|{_xZ(}|lw8b0!^0ZnmvzN428I1|1dIj- zlep3bI)qM_6yx7u*XO&*?L1jZ0b{mi#$doicqp@RDc#NDnd2LCN2;5_O6$`)*7j71 zmCJuY61U=P)We^tboqp@n{?M5MUI!uo}MB$Qw?2?Q2x2vLg=ADUT$i8(}ib~^~S3> zJbQqPd_&_WXZ|BxSn)IPK8)7FP<&*`59KAeD95KhBI6^DdJ&X%4;n zoy$)0vQe@=TaWVlC|sBQ+irF|wKFmCq=n-Lkx2_f<5;Fta}^oWq9k2tjVR?<3b~}- zUug?;N8ic_I8&_4O%xx;c`cHdVCfy2%ozC;>?;-0Zc^^<9qm==?UgG@(_|mUB)k5W z!relQ=exYK=W~Vk&DGq5Gy%UH=egopqV+GMcb6Zo#u5Fq$TAS{sj6l3e)3hlo=!b2 z=Bm)q65$pyo!c!@2X`&z%>Keb7IgzKQ>yKo%iPwm6~!Pzj{q3=qyY+riC@=r2Kqpl zI-FlRWC|fz)2EVL$WlXxNNCON7uDGeAsUBe#PcY&MEF&9 zAF)GQWl=<15t&Pb2)s5x0Ws!O!wYiBB2{>2UR0sryB$><4nN&l*n6qy?WmE)CeGY2 zeYI{0#@JCT?^i_PuG*{V8mc*%i!#`6MQv^%0XHn?*P!?e{Hgw>JKMc9hLWL-{B z9t4j-r-N3ihC&z~Q6bk|G2>dcnVdC@dQfdLN%(?h(l^!}&O@5IU8MR6qN-q_it-Nb zDT@DXqd(#D303b{Fe(|pEVVt6oDqj6y`6FfNL}DHo786e+SNDP#BT6pq6&!28v51Q zPy-YoQR9js*5w4O@K|ap*;#S|uEii3^v@w5)(M0g6`<+O9p#E`Y=k~1UEc<%(eT2~ z7#-<#TnzLImsryCH~41WsjAyHILQxd)^Ts={Uph|DaH0A;$E7$aDLgg3IMb zds*n;E>J{#Kj}%0-`?K-PhzVhF%ltasM7Z@OGY9jaWDAa+*nRX!6d5LeF5_C@PSB# z-|>^M?}>z327u%Pkt^P~L`tXwpe@Y}gJtJi32Z*O+km-wHlg8HU0du`5)e9bz1 z>uY}hMqjVK{YI1MJ57pqoQ;jLqfHMF zmq92(ZJH`&YTfszi`Nei1wX@<;5^-eG9Bx8m zHZU+KQYpt_WMovw2Yf6*duB~9#Y9mhgh&LylC(2L13P)but7~TVUaBVAiMKL0 zho-8!*k^uy@u5~2X446ygRvB_yNmU-jdsu7!^5Qhm@wD=2yEse`3p3&-lDb|`4>V~ zb7@>b-pJ@^Su#r>KAMX{)5o?-r2>hm+W##47)s6$irpQ$6m*Y+Qg>E;1@SN=)r;|Oqo`n@0OI+@Bo)@U1 zC*%O1wcd4_B9Xg6F}XE5_Y9Mu1aHoP49|OSlM?3+gUCW(o0oQc25(|~B&D8r9GTiE zX3iVJlF@i5^temmsv&3CxaMsUeG;1xOq|obNOs!_uaoHL>?UCujTf)5y%4sCOPxKt zqP{);z=Er@Sx?R2cHKER z7|7)HL^%WjccY8ds=s?b-RUn?>C>R%VF6UgwvG7{^=5ft_8awGg0dP*k@sm~ih~@|ode2;_3D1X(%6S477HPrqTG_> z6#nx1;>pirQ`sE0qs5AaO+K$&v>J7KCv(L-J}=3T@HkaIuO8_c8ONKQ{G*Aq!j+4P zReIfMi#eakg7}TQ`wE)KGWj4BA79Ki^KUBo^cNT5L1s_NZ6~hVwZr*W4fCj8APP^q zAOk5?5YlX+^ufqHZe@L$u8i%|Jz?_I>a+adyJ~Tf6eB2dn5+|}r0;Wek^OX8M6$5V zC?5Tysw^U-;gyz+^2Kmq$6NCHMo(P~>d{nhg79g}Zn=CIH1tk&4xI2}M0SZf%{F4C zz1J#=&xKA3NOG|1Wsv}_&WjUccXp5mt~UGONZCt8Ld;4H>HSQzFTN7zdhz(j*;@`> zlx;P6eaUA4`28TAiNG}p`#S)Axt+DLY*exQmer^39b~)0?@4=`CsWip7iewz1i3+n zE>#d{z{Ckh%7Vi{Dl?B%Jp(hEj$vExRYIlb)m0!kj=fbAM2OQu-oRBHR`?9BwM!h$ zod3g66t6x{V^AjoHx@N*No=jzE4E84CONkHw(Ju%K&ec~CGMw9##+`%L3_mcI0mi3PG1;}R@3hwSWGgR_ovg!N&=9q_gEBkhPg&9 zUO&t}scc72eEDMJwWduwFwAz$1QP9LaC0+D>&Mq>-fdK15%nqdY&*2F1X`|Mm_;4_ z!`H*_C{b!-<`@W8Vy^&Fiez?r2+28sQE)|*6O-+U*tJZ!IrYPh0@y=#tvOuc3D9+<0*SpkQ`QE7R+2sS?P&u(zHhhBoG5)fAo z_I=}(H0K3pzB!}4)VoSqRhC}d7HE?}g|*-aHk`$54-`*z2E#&zgHaH>(oAa#1=l;_ z^c_E6lzn~J{SnX2m@Ei%U93bhH15r(ohjlv&3~B+(Wd4&!U@o@vqcto-+u=-amLa5 zDz`|jirLM`E_|Q79-P96zjo~%UIy>nDNpg_%jv@*Wax|`URYRATSYfG@^{U9{i&?{ z864bvrH=B0wB*X?iH1$Of3S1Ao ziEuWe!|4?q%};V=+wW?2JZC}7_>R`#d3+TjI z&9}0KmF-4Y{j{sWsPx4SXYxD*+tTsu9>%1H8~E)RgJhA2U3|nYv6CnnoOoL?qH|T# zMCVF3BM@FYO*h6W_GUlZf5lQPW$3VpTH^NjUDz`iu?cGH*YrIg=USwa_OWG8KRdU- zrjxm?^xY}6TE_sXrWZa%wWB7l%ahK&Li}{Y$m0hwBO28%lRNwvG$7>GC$L3YomrIKtNkep`iTZiaXvnS9Wj)5{8c62@$$ygSTO z)3(`Vps9Za4Wf#;D*koU@%`erjyG#GA|fIIni8VmV#E-I{u-$fShYmcy$!>%jH$Fl zXUo~5RSq(zYvO|;J{hv|85Ws6I_<=oeQL#0aq^DjYfR51r!IrjB&Q6obR}*Yih?Fg z3hCn+<6^a1M(qwzMwX|WjJ+c0C zh*tys-N=vWpXSo+IIcHnd+$380Ge+z;wN<QwnwKOp?2?O`zNmEfq_w;<8Q!Nv9I3E(MXnxe| zVb8B-ro!n9~<%w&T*F#k%TvbZPKKjUDCcT-;Lq7|n=Y9EtAIg1bLJGQt!md%x$oy_sV1r1KD~xIdb}#;oTlR!vvHCk(F!jrwyA23CYA-1NrG-CAVbfQ7*Q(e%xU`!y8$F<~kvuIA zI;Rkm(ZGz~!yVmp)zp1zV14Tgxke`kyF#nu{#9u>rBycaNR z8@A0joxL>E@$dqn8orD{w}a3w&orPuv&gVyR43--OA9de4iD~Gy2y@W^3ZHgea<490zE?|$ z0IiA&21PJM?#?%dcc|35^pKe|OB49X=!2|;i1!9~_+N?Do)Yj@6=V6XoyJEV(x%eP z{8B;{_JcfPFU}tx(T8U~TkO3}LHMKgY7t*|nsGM=`s)MrR1)Mh2joXTqm}b6OV8TF zOHLlUjZ&>qg|;dHNKY_Ubgn~`(BGs=;5VoW)j91;lCuxFcW7zqv#7;W1gGL*BX=__aGOovcJK5wXG znxR?VupAL?dQW57XN;OhXrxR}W1gR%+dDh|kVm7T-Cf0zmXf-mudSfLlaeNl!y7pHrO(7UVf}<6 zS~{~dnAz=sX;ez!0^z3BI7&1LcZppI2KAO?QeWkU4nE^*zVug9LzZCr^yoTbIuh&h zFUXz*U&0>J@MWoveV~-uwS}I_cIAUxsI|J#y12M})GUHOL%>Ycn#!i9r=uKFDi**+ z6Yv`J1JKjCU89EM$Wig|q&}Dl7N3_}j}{~W1pjAG)e$FLk=bVL<}5s3CPxXa1LQ zE|%Ot1d8%1+hwt{RYz>${$E%K6YkFG`Cw>cj>>;@=5LZsC=$!AZCmO2@~%(1?%Xj! zMqOYdhglzoS?9-dAj1=M7oo3x1OSJN#IRiw{A(3|~GS*o+de%V4MQadTWWSZlst`qfB7X8HK|F%SUD-H`koB} zaZ0UO^oWJ~n2NLm4Hfg#xx4dInT!tzxMa)w&Ns=c&%~VzY|>;rAODESl9H5XF!JmP zRsj@iOOz5#jRkI?2pfjh~DI$c3 z5Qz$+R>^6Lh8%ITb3a!x*{hU2B%5ahA6d>Y`7xe<##vry-oM2%8qEx*QIljY5DBv& z{!3hpM!iVhIvVcPYuR${IwmdUdeiUEo@X<{UEj7UP+l8C{wYf0`XXSbPm4MOe|y*8%c&1f~sq%o?vc3i2 zD^sZyTKVC_{Gdpw+Ne8yMZ4&ULgIl^Y@1shy zrOLdA8M3C$wA)g;&{zeXO5XnQi8@g(kwqU>w%TyWn7nfKG;2D)A5t6*LHPa`Kf% z+vxIgS^>c9D_Ocgzl@nkfFUyufKQk(4J4Wb3({T7rJ3Aw{ku!g8e zlz{t*^@V1%P)h&0!g0+5FQ7Ow$}WI&x|-^U-u_04MrVBF_b$Hmz)v3;)e5bYB_U3O zKB$Rw&fYfnTaFJ&J{aJat|lG`Y*p zET$_pZA!*oV!R1mcaQ3vlN;Xx*p}-*-Wv#Fj&`?_tM2rQN7a9bFURv!H^{R7N~J{m z%Vd{PCfLku^$#V8Y{Jl6kHp#HWVzY~GZ55+ zDC|O>A;IMbqZ}kPBS!YEbv#tImalz@U&nP7qwqL6JRfL~k&)LrywhGlx3wQ7A1`lj z)YG8^YSo?X?e2QZ#j5)H{SSV#*6jEd7ZmIHmd}N?9;0{PyO<(=?Dt~Py@Tk z_l2XezQ0I;Xt=tX=EuCk!HdTW2m5_Khcgh)!oRZkD7KBy-Dhl$WKy!t&PR%RcDJ^s z4o5vCHbi5lSP_$pg)Z3g#*-!wIZqzqhx`65p2ZTh4=yJlt1*2?!w${Fg)9)8CKSNd zVTUkpT5Y~Id{9BebVMXy0-(%pYTE8WB?!Tqk@rzb*C_#?!5n=)*_^*7=S0OA?mDL9eT1z-I*n74(9gEyL=p-9T4YDdeI`9C9BgtNeO~VNND3Upz^Ca^& z#Oo(yeY7X8>UDp(8)sy1??1&pmUxv6=2n}%fLTLn)%%3H)MK&|YyK`TlU+!f3|y?D z8@zHC=2Y`U^7f${$i<`Q69$%e;I^LB6`7BdpRzmD+7j02u5|@d>#(Hi;Kdm&lK$t# zt${;!i<-q;HZO^=Ndm^BOVT>u*ah#(m>z`arT1O-JJLe+*3pDzLD?cs=? zcJFpFi?>t1uZV2zXWJhBlNoWC>AF}JrCQZD2v`iG$xL2o?|>Z5MjNFvwd;K2TI11& z7fjX&@*KT$^B_okPzzl4McG>fp;Ppz>1Uvm4JnO$bwhpd6nS9j?>*k6v0KCZ@%4zr zA7l)M^90`|MQa?=Vk}TkcXGR|l_BD4;8s~8gB!##7xi{Q4)2htg!~Q^zV=UJ!V$&_ zHnhxIZ!vV|!kURlbOs;}Ov_t_pvK3?iMD7!N}F2nqA3i8UdI@Sj_hkioz zN)~`-<_!(E-*W7K?%0&w9yf}|)7Zc6j83O>I-0FDF(M!!C>6>1cXbJTWF=QuSJ@w# zM_@?E?&alVBCY1pbe>qrsZv>ue6|^5P3ILE14_z4kdpMzL5nn?;`5u~1 zErI4HPeb3*$P_ zvzUbu)AfSqcU*A#v>s58V(YOY&lkm>Mlj=Q`*yF7pr_C1JaF=|t3Kq&U$%dd(i%*6 zdHdtjFD~Rgc1^6x(2_u|YC-r+P9hi}p{{3g?q~X7wUkCWhMP9>l@f+T2Po}0YksX? z0#Tv&c9sHH%pWj(epqX7vA)=9LPf>_`YKnZCc%rRBOm4V%Jn|K_*QokICm+#8FEuR zhB#=^Wf)Ns!`yta-BOLDa>2&2o#|iS)_s!_sNT&t_GW{r+++YHq=}h?4Ij^E60&AYl6X;bXkd519|CRy4$FO6sC#W@#iib9@Y%cN}O_3 z+ZB?*AejlRSfIsI7P7pWoyxe}{4|4q0ZBY>lhe|2L<9SE%Qob{BH(?aql;23l#$O7 zg81gs#~v#Cad;xWpJQN1k)yAtZ;b70csl3jgDl|@#}6M0FK_ZHf!K*jRrR-BUgWG$oNQq;ACEUBh&MY%eLd*k>Dd~30R zfZZ|C8eU$VfV0|3Ht8>+o{KO66*B8Dh`6w%iQJS%UiCKmvdefDI|PeLDy<^AS?tNa}G*)jRIhfZsbTh zqc&xAAvX{9WO9kA5c8SG0dO=z-QH%@7}I7meQCCnBjHo^r~iC+u1ADJF~nuk*kGC{tW5Jf5!6u z9a%yQBtD%MN*Z@}{@6LDK5aRF9W-Q%K3ok;3wm1&jxEN|3M45q6M(T~9Tuw=;=;IG?}Zm; ze5nHyy|`E&CzTdlLHnszY#<&5bB-;a!;0@?_VXCIR{h`bZK{We&|lJ|9Vmym@0DO|QKD+y2nuWp}Q; z_llk_M)IjRa(!jwgkecg}u=o zN`B~!2k%P%QF58vxklrsxSGY|4yd*{t_QZ{13Ce^g4^eKViGbBpjv*09*H z94(}S)(fX^YdJhvX#pX_iWfng^35*#FE9uFM#nHFG-H#4?&uf%bvZ%-u^gSmlS!X= zJnll_aoMImkk&_3p9Mb^`{FsQlP!uukYiwO9%FYVMY&=~5+MArwO%VDM5qZNX-N%* zNIC|lw)jVP6U-v=RDwMO*@@D;KVy6rXi}cY#mp~$R9o7eCr*CivlywrS>oohDv%IZ zW24c)?L9)LztpwB!FMFR{#k}Xw!)r`%`bBt_Ik!sSv9mn5wa$K*lk6neVCkALxCuX zxn)VO0v~ZtCnpDPRMC%T1TsM-JOIT$?zK}|udq8@X8*NH>UPQ8 z&dEijy&(X7RbyLwH2T1Mm7)CJi0`6|smPntK~2Q|eMdVT$LUW=2;^)H?~$errS8KU zzvm-9!H;GLJ0SaNtd++l#8084A0Cx65D;IeslGh`AX;?rtv=!!IOpj!c%whft;zFJ{0v*q#eX%>7C%h ztr)-+bfiYkSTrp=*K*)(-j+|VWgDjnH{uvp&u`vG`^Bk;FC0Zi8N6c)_>cn~9~b_< zr~lM`WOP);!A9Ewn=Tw`i4WJo>BMQwk}wA^Ba}2$OfqcSMIuODiQOJmw|4#ST>!_+ zeYRE8WTtFv83=JaZvE`Z_-z))u)*p73LgZi1 z-LKk1-23kZA-`ZVo^$!UJvLD}zedr=K?fhd7yw~etADG;5p0EBd0J)`Gg!#C^;zBkj4o6z7A)xK^T!|7(E96@Tzvh9O+8&x;F}G$)^M$ z8WMJfxU-KROoUjwza^@eTB@ zq0qP~#hT^#_3c2`ySalj!vFjj%PlyobSa7@QyK5})CG#S5@Ya7n##F(H_gHOq2w=H zXfk>({C8Y2_LK8j1|ou9dNP!Gv{;>bqL;7>XUii8+pJUpo0MCwQjg8SlGyK=^_(`V zPTLc!#6YVFr(CD@6y_Xr^dAcmcbV68if?U^%XwcNoK{!{oZ!2aO?S>ZtCJ}SF64LJ zD-#{dQw`Os+TMcc3-a@0Qd0qqjjra5(W5_B?_6};pOEOsd^0?KKPQoayVcz4tpr9K zoZHs5y+0Isfo7;s99TF&Y^FzdL=nYQl)e7`%m+71mbTZgwXRI;V*PrT0MA*MFP!M` zUJe(ppLMcyTA_P0u;M`@d`5Z%Nip_Rj1*Gtaz_%<7SWCYr4{kRWqAQD@?EeKjOS zSzk_n|M5N1RP%lRMSl+Y1&`-7HB`9p_1UX06rG*iM8nwl*HpK9%PE_0Zwj-Udg^bi z+Siay9GZ-UW%e>Ejzlzo+-xdYoIcbyVAenjk66HL8A!^vF_RU7LO1SbL0L$7F7 zK~jXd@qp|kolomLXfl1z-h7NvMX!%6jlPM(9rK~UzoXCNT%}e!3p+>yWWD?l3X;st z%hPz3(^~h~C(16~KOW;0EWJG&-m%iT7=-)|s`8d}7Dg?tAP};7xV&FryfoG$lb>-b zr#NoFlhzUhz)kp$Pr?EZIPPs!efCF2fSo4&M0T+`%iAm7Ff(2o5`KE$aQl5WULr2) z)gb4QCEjV){RazSy!%n6_P|O$<}btcN~Hu|29`E*mSxl>E&83ah3PghXw z=!-SX7VE+EI30vinjNV7T@A<{Ca@DXl{-Z$1bu-MzEn+jylrs+~>|d4X@?m7}qY2XZvko^z%<-AZ%VZl?*R(kCIaF zZSFnO#dFo~^p`JL{4NA%`<6^CkmzcF)4ux3jf>rjdWy*4!Vx9f(l5JlDo=`_9hF#@_yltWCs@a>6gf%g$P) zzN`iwwO!8$;>N%y=)|C88zJsuC-myoxffm(vRU}e7c8Xe#}&OFO%+?@(A8)nnE7<< zBE~H;Ht;MdATP6rMP;JxxCsXs~DM6GCk zvCR_BawFO8Iw*;_D0y(NY(fK9)E_mSwsX^|-}2nGCr3ya^^H*lR`$YA4@_0P@K&)bkwQvTJc zMG^6;?sI)d2gnZGo~+=pu7@_l{2Lqv1Lh3Yc< z63gc$G?sL0mIXF7pz2$fHTUgE6e9n>n$7a^d9-L8H3o?6zp`}mHhcvG*Z;({O}9V( zU;i4)|A|J;zx|&R?QNVe$pXy(eY<>FY47+r0%Qnf=rn;E3J97NIN>0FAkazVe|p+t zv5G7uRRRVEhVSCym>3xTvSxFIAkkWNI_UdtFnD@0=O2mid(u*axzVpsf)HAlv_D>C zo}QVhSgLFKF+M)t)YSBmn0WpFbL7ow`QBK%R;$GSuH8~12kpPt=HGD1O|%-UEkge% zhXtqQTj5N>BM>AW*BQ$aN9V|837`g#roxh? zKg2q55n%DDYBcq`6cie&DlJ}(IL@cpnfB?ZTC4qSWiTQZ2}yK%Izev;TGh;x)qFXW zdlkZ9CAE|{QpCZ-8{%wSbM=J>L~U1Chkl@a&?=gN;%==A7Fc7I4hKIl_W9_Z^axKvsJhF*Af}Zv8xS{Oc?4dIYl5A{BmA_EQj6c%f z_6Ys6ySvM5y~w1jQZe(?8;oMq?GL9KB^g>K7nDDmGyH)a9|igZK~pMps|NJtB{7*Q zRKvUVzs(&twY=C>M%sYfKBXLmb?+{F;>pZ4 z6+cZ+{(fBdNzO@v`9ere`cFtlG2`FnBsWgt!z}5v{%kSj=y*%~u4}Q9BC~NdbYv3N z+}ei0oQ#X>z7|B+msl*lm*34??XioQC{gFkL*y9%+uq?Vm#SOEC^IbiQpV4pvmj?` ziRN=in-q~(4mp<*Sb8F5v?NTuvnE-^f`Q}Rc&|BY;qY%%5J+C7o{br}lN$QEA&epL zjN{~riq)A3x#MuW{T}CaOumk`s*{%THB9>(ZZ3zjh}Yd`Qd$xMGe5e*SxKttqnq70 z7N{s(w<-xr0K>m6?Y5udH&L153SxD9kTM<+?7{V8*cnh*OPODWNn(Av?_5OCs2xGX%8}KW)xGK1YYsLkQp`zQP==g}=z&Uuz-D1UL}z*O7|gfWz`GkZonZf0y!aBdp#b zSLKQA)~9}!t6DIkCh9S#zIzRO)nV~rBI|eVmyO&%6O5KuKl~2)?hC<99%$eaWEnUyUeoiEU=y2kI=2r-I~Bvc;X3McPaV+Jk&qU05u#o+cljjJ zV*i|S5kaz+zUd!Oo_dGj#95G=OIGeAu02P7d%_*m>@0wE5gSVm7E5>SHplSW?qu{H zw5vgN{=^)+LK%^7#>#7r5;e$9{`aA0Q>BndEiENy)QsY8r6xu4*!Iv4LFsZa_Y+?C zhK2t1y<=-doGNP0=#ROkEm^8nJ+ejm!;%yN-0?$qI$R1S{3h@Lnw4s!*^Ga_(t2er z6(}(U*MI);$T?tW_(N@FQ`Z6G>Z|K%s0d0&s+nHqcOZ?Rs`wQ_=H^8=s;EQ^_iw*- zzhI3{`kn3iwG{U0vf-V<+m=@M0_ib~n|_=&t{a~Qn^g(b4I!?E17Y!f_NN*f0*6Kp zQu(*V8icEU7{D3?q8^u&1{*WEBov)20BFYNgu$l%pHW+z(j>m@xE(<#$Uh$o!%tnJ z3v&i0i1o}*bJ;2hc$ZCXB&*K^oFD4BU5g>c1!gh( zpM;PE>GyWX6;-+#_@7%^4FoP2wI(#f3hB9eUV0&m4TsWJT9eH!;QSpYEiDdN;KE*3##P1@^&(7!`jV~SY|ZB(*U9kh>LhNt@fP= zpa7veY4C;`ZtZc9*CN(bJZYY-v2m8Yw$*zP2V{y-@!ket5w{gITFUOYHm1c6FUz+h zj(z}Rh+bL9EC81EUHVtaZfoYx2ipsenHUk=lmR{&n)X z?Rf-&ug(pQ2myINcuM48$BwG^AOHB2d7?~Z#EE9y&4laqsjYhy2`KeW5H37y;9kMl zW?2s^cgbzH zx=MIev+I2^atO{Wr%3^GVcUrv?S{J*=xbk-%a}Oucn@u(xi*iQSe#k;?424~N8Pyhe-Ppc%kO6Nn;sD928fd@& zGl^c(N{kZ1-*g*Y(wiSgVv!dmbm+xsC&V;w@S_h1`4}JMe#9;5M@@4*S$0@MVw^3x zfC9#O3jr9X2Ln|>NU4Ba*wPn;lvYXR+`2~eWq}BH*iL0yHO6{hPZP(p^>JsTeJl2XkO?+LCza|%p$O=sA8779OsO6g3ENoGm}iIaeK}e%zV+-Q zjO&Ren8z0@D&XO#kRDGvG|eQ_&^mW-q%y&Fw$890HFYQ9pO)KgwHMl zBxf^*Uk6E_S0%oXMaNoCZ_nN6X8N`1VGp6`|27#Ku>&qt&~FLI9v~`m*SNe@Fg1g( zLlHs(fdmnk1Yd=S7pEc{U|o0mjyKPA98v;ojW3J4av4M-sk(oO%^Dp+4s6sYH+X+V zowQCZ+fu#yaskx7v|{cVgwJR6Rg$wdC8CKs9QQY&cRxYaB)}(LPHu9I)8ylIyFQuf zX)+^8LQN||<4e!h53~e6@eOs(NrC_Pv?7&2x{RRypEIFCT#?03t5wH!P;jfji|a!> z(;a}IQE!Po5Jg1mV>1*-alFx)1vRQ*;NZ9_oZxA<+vQ57Gu^E~ zpq^kN?->*$KE{?d}k z-l(52WyOb^o%c1G+CubEIT17<#JvB2zL5hc?ajr*Gu`RuhqVhH&sJ91z1#4k;^if< zv$KO~fj)mE25%-i{a!t-v_cyvv*|iPBg& zv~-T=E3l?!>t;c(YC^qII_X`M4Fo`fW}NL}(c{wCK3ey|hKa*j`){*-RNdU(e)|n7 zu)^oUAg$D`C+?vB2kG|}#B7BNE6Ym$&vf|x?f->y;Kz`g2!~pl7#p)WzyIfF)aoUX ze30>2b{q$w-7g<*+aR7i-DJ6Up-A0-CKHdqwcE=j&M9tVPoO7qt@qruR@AO~ zfWDaB$IdsywH3UcvmguvSKd7J}Aq8aMa?8M^VKDqenSY!GEIM;g?fIp6|)`F>(B$2c^ujmB^^e1GN(d3>lho0KAusO$}u{`usjKqwF|)D3rK z^})v-Z-v9o=;VrshH>}5NYrB03y(VCqE`OuA@lo}TpMwv3)gxR!>pgv3oYVJGyLGE zN8ExJNZcKd`Mp`3z9>N<#ZJ_>BU7*^}4fW;j7DqBOu155qW<(#R{uC39!4%y*cC7u9-n65<^lNC z5Y zh~IB!6Nw1kC-2^c7{D;`4?U83UEX^|Gwmk<+U9e}Nfqr|E|5?en&CL%zERlBID6{7 zGO%VnCh@Au^vk`)@BH1?=?#WNe@&4r(8aRVo0lJYJD`c!`@Ip{Atmda0w9K?i zA5gK)c-*Xh+b-Fn5=#o7Y->FvZFk{$Lzdo$%}4#tL!zAaTSnu1xR%j=eRf}!T2?-` z;5~IHMB_-Xdgy_z!foy7GU#HZyU*u>X9u{Txf(B0A>AKO;2!WT2Cw?fpL>-O<#lL{ zEMQutSN`kMb}*Tw=0SlatsjPwOe8lwJw4sk?Mw(n*1w&me&N?nIKWOpTC%53ckw&h zO@LL5py${oLNsXvZI@&SX@16RC)J8-+@({zFctigKwo zCNnJ<4h1#pb`A|P1Mj3G&X@o_MPx}Yk(R2u9=;q2A3F}q3`;dku)qY1n!0;#Grh$edG@*_ui1$rE1WjY%9>hM&f{);Sjyt?#T z4kSPAak+3o@Gpj_Sw}1jX1F38`VZ4Mj_yaOrN@hktcx|fAA>YWG#k!~w^*^DMq5P0 zVGx`Vdzfm7Dr~rBhN!6cWvvD?@9W<`)_!C;Kme088e5Kx9pN zAv+rdCHLK(pKmUiWwq}FmVZySR|6|usn$_(?&TNtnIV0?cOAmir*b)=toQtc!6~Q4aeX_6$5*OU>)nlDx zYyN$qV|jqB63^{O4jWFIQus?$l>Zu@zZkN!zhDTbY2>3a{L`*+#bbA+;`@ni*O-8r zI%JjLDa~gJ<==d;sbce|w-Xz3uBVHjd85Y44bxk*+v(!z+B*snJgH#1mm0y}OHz53 zoX+SlC_-)m18XwavOdf~D;rCajwpa%JOG?oMb3Q<_qsA|1BBX#uJO*zNbU4RP;<<&q+X#M(R$|ixkCk6}NZOP@vD5 z0zVZl?`&QtVzo^SKb zB2U;V@5d>Wj?CwI-mLVvjHWv>GB~}A1n_GgUXDKU)p@cxksQhnup51vRNlQ0-Yw_X z{+51t#@a3dSuYwDTsQp_(7A0yN6zfXPwUJ3y>KGZ`(e+W59_n@r@ZC1;Sr>>e7lG5 z!S%O2szzV_RADKn0ixIH;pm^)pBfC|F*8*>-1gLk>y@*+&ypZ?zh#Y9N06H8PbAk5 zW|C2Vi8;!h8C>o8^zFA!Z9_!8J-t8(;$_Bk?cu6AzWU!MJ|chM)u?}xlU;J&ztM2p z)Z?q^Sosm`Nxze>Ve|=|Ka9h*giv6!o6Ksx@C?psbuV{8O~z4mUA&6h;`(3-Ll9w* ztL8UIYP#BDC7PHRg{}X;{CnD|Lu~4Imxhi%hRPfsMoMq_4dEk3R1` zUGR?S`2@Yv>+}>6bhUdh5cAU*nmC=|~035DHHxJ(oX#^;o14Q3bY~0Z)3F z9v24i@3732TU_~Ctv~D)>Fpn(WHEbL!1Cl_+Ug29<4pogDaa&m_}%y7ak*~$sH}Bc zqemA8R6Bl#(eh_$^=88AU7fC0-FsZw(XFS1tkZ|i_Y&`d#50W@JAXx9!T^rA#^d9-k~Xnsy!{>UGrnHNn&I5GJ1N2X>TkP)xm>EYKXykL zI}HY7NKuHAi_I*DaU-rnSN{e#244^UHIE6SH1ua5k(w z5I#qb@pAIA)nyjQW?3S~qocjGJ4*Qfp{Yqx{RY{bf{k4-etK85#=L&p;j#)SrR9 zJw4C^WutCLY!VX_HFmwk^7y&AUA*+m$y;zs*}fhz?Qe__g?!A7y<{qi$>(4B=S)pK z?Mp4bD}oN-dr_IQ-QBSy`qx<{w&bkV){wasXIIzCOMYlt&GE^Jm9!rF zm(Hry9_{YRD9=t!-?FQ|VkuDF+E%W*12}bv@Ohw%UShR<--2$z$#|_QCyMi2;=c75 zWGE!3_Gn#&f&Z+NWA7()e7pF&UT>rD`D?S~gyvARpRaVckO| zp#g_)#<;h-l9~nItawAMX{B^-MLc-r<9%T62Fft`Z50Vkm z#ib{6IGQxjT65DK<-Ity*oBZ%=G>|1e0@A0LB-n))(Xcy#$S%WMsqQCl@bZ?A;Cvb zgGZny&-!6tCiE6=D)ex5tr^&ka3aY_tXz{d7v`__6QMV4X}h33tig-4d~jssG51Um zb9acRjqUW57@UHIlZJ+EWV{UpKtqN)@Gt73T{;A(~z14O_-Qa(NCqa_YDm+nbPbR&uFa>yUGCy8@atVQjm2(k2l5@ z48e`RE=k#mnkH}X?fHJNzIcxg3fIwRUe*A}2-=lS93uW(9Ugd=f=Jp5Ks}b}e)Y+@ zhQM-K-vtYAOaFSRgwNaNuYJTM1cO84+Xu1gnd=FXe?-geqG3pgkGEt$e@v!-dC0E zD5U!|KNv;9o!joo^4h@CMwuq@qAs_#I=P_<2E*fB%$7juaG=GAgDKJQTQfA>PsHCC z-3YXAVv+$Pm1GWWcXAk1QkPPIx0ncUOnoaqV&aLZ0K&eu3@c=ES4$u0-|~7gf9?vc zLdh@42R==h3vgS|G_K9=rJN8SjMSmpI$tw`?Phb?aX(^u__zAXQ8aQm%nt=U;vF0; z*MEplTfzhzcCCp8%v2g6MQeCy(&_!GnZR3>%BWHj227gEZmjWQ;Ie*3hCQthET~`7Mh1 ztd#UH7C%7ik!g`NYi%HYF~LO0%Iq^U@L+&vA~z0@Fg&~+l)~n@9O%L1Di3v3dwJ~H zD|qvmnN^~>kiS~9Sjl0<6iv;vq!M5TH<K zTFDGEw|8OL+|m~xNP1b_)fw#U%rX&A1xi|-s)eopLSOKh=H?8S5uXWV{RPZRZL-G3 zdK(bZU}}o=7H?lsy}byA01X%3^+O&o>z9SpHkbB$YS&e69{&(Nq(z4Vx-u5!W5N@2 z(+2I?7^(f3j{-y|A~D>_6$&5vunx>I4#ect;A$=LfJ#d^DyaSW@$*yhs4orX<2y;2 zgS_{=m^sWq3LZ?%`qgABuD$HVNx@ZE9o08S+v7#Z@Qi}%BqY)Z6~EU8FqcwLWXBs) z#y|r~tSOGQOP`X3(=-D7vUvk|gD^@NH}`HtdsVRkMEqph7KwoFDunRDDJsTIO853;{$L(S@|G>cDzJtaHy&f-E)m#~h`z(pjxM@qgon_OAIllY4KYjAm}tL#Tef0_m|u_zM0TEsW}8wldx@sfhNihkZA?cY^oEC2 zByqp&W`u3upnyiorFMSvLT`}{2BWV}#29F%8N^|>#H1D+ymB#?L`YXJV4D0cp;zuG z8v9N?(E;5-GdwM^=XE|)Z{ZYu>xpYMvZf;9>3kvR4#hKsbGN-?+?Xf={M(OZS3uff zEKZl@C?+R7xw7^PiM>oxpPD(wpAjO!)9^EApO%ygC_qJt=XE8fOGBJdH*GPa#Mjh! zStpfETau7?>7AbACW}~0vqbJMXtDv6u7L{BxI`C zINdU}l$yiYPEX*LxAH1C?^!fKK$VSa`LKFq#Mmw^Y`puMi%RmCg@v`0+7!<+Sf>S) zvP2XgBr%1#qgZ#!R%wfTsrn;SmQqov4z-O4WwFSlmQk&HVF6aIWYT-A?BrItlqrC5 z;rqoOk|K2srEmI=d*1A$Z?oclm)Gdcg#|~A>0HPIAr4ZK4#KKfkH3f$P4n76BypLq$m^=L!!bjcuZ#+a<(0XewO(#&X4`dFT0wSv7Qs zoh#)o*i%0ua&PKp$fQAow32>W%9N;<_-KKBQOR^K8JpL=GEA661z=|UeSqbzm;gv- z{gullt{K#e4m-Jmp- zjTYm7I1&Rh^9D3>?uXl&Oy?ZEXx5}>y>G=SYDm;OjtJ8$?M7DTyH^QPd#t9CriICp z>-6S=bEyVJ5ek)~RJ~Qjd{M=xmEl_!(Tjg^DIt>BNf*w2V_a_=N%WE>zuc|_K6&$W z&bOOtifegeC#LLZL$`8c+&L?Db`${|5|kV5<_J3rR9@T5FSXWFFVziqlrQ3-=!`}% zayly<8IsHAVWg)hvAwIt@T5{JyhhsT|42sc38#!i3H0~(FAOH+05l$(>B}SEy}3Q~W8$5F6ty3``X|36+*gTx ze{Tu;9d(9mg>YH)1pLb)&uoW_y-4P6=fR21qE0y=S;0qO_aI99n*)V#2tDXma`=jN z&Z0je4GnWFmB*d=3!ErF9mL~@s5NZ;Y9@`!VA3Ggc*AXu&QGG{1M5+?RbLfV$b{-| z0sDlDnsH>iv)(?A4nC5--V=loH5CA{2Vzn7yRM5u*7GG1D% zPg-e6(awtN33RPTxB%(7Es{uMdeiI=#MytWs)t zvMmP0y?kxi@(vEX7pWpTOF&hd_(`_~5(h49M!5sSo%Gd6TbG8%J`309=ZE!{Mey1qY8XkTuS7*PB!8hX( z1e+5#Q9;%MDTTXR;$MR|iD^=ZYWlzcGZ-UQSHU1y`foR_^|_2;bA z06J98H5h=nR1$@|*87JCWaflt$Mg8=SrG;bN!zB@V706o7{8OLL7_Of?;;p=H*6nT z3-N48nCwu7#?zM7U4Ho?r!jUdD}8wM+e?yA?qoRUBbV3bGzk6jrE&7deq!#vTsEYY z#=dGE@`zX;Eg(5tBK-wq$I|)U{gcEx@z8NRPFK&14VA_$xxbcIy{W_xM8C|Df&4ji z4C8SBl64$1e##&n2*WkeV%pu45?6{zcP{hfSdF*EiIm~c-jU$=v|R*A{6J&T(Gc5h z5p+WMrev3>A{AZJQb;N!jHPtU@9}sFqdjhF&($8|9hv#j&y1(pLW0}XAFd$ziE+a> zk;o_PmDtr(HJqu#=|n274Ye5K`lo%Ntr9vz$5C_ZlY^-q zJiu4L$wmEfsl1cM)1$>hBog>GeR=BQJ5B2h^bqTV%@X?(6X~l7@@kr;^pY{{YU2ze z$Pf#PF1VxI!NsT=x9_CG{@_azVaGFB6f7r%)kc`Ng-CAuTOnNgRMO@sknd6sKON(3 zQ>P1c))M)Zn<6ZvR9OBeyIY@1%mR$_xOw#c(hA4akV?yWZfK{pdGlY7MirMn>B8H5s&_2)k+i)lIQ)DM8#W40c2*bz;nC<} zl`(;IL;+e4EVE+W8G7GFo8PU!>|@a~7@Cdny9Fb3j2J1p=>@;@U}9DdD9Dc4iIC<1 z8Qb3~2Ip$jYIHEh^CECz5TtfhBK8U#buiKf1~y|Brl?~jikbv{0m=L&_wq2eM znu_BWd!}Tpl}-g&RZ(tVjykjxS@zFQT9mGv=>tE!eTJN@sNYI$p*cWvT3L=_p`bFP z)@Ee`8V*8stlbz9G}6d&2CVY9{i!tOgh*QXfp`xquFe*PD7ZD2_6BMe$Jsk)4&! zI+D98x0~%8{WAPLIi2~S^<^|HO;?K{vxOyPrL`X>3nZSCffPfx{D;>aBU`?Zb?E)7x+<)IuSFL%AKdO<&P^($p^Tb zv>4dpLT3RjpM{4~_5(3=D+U z>7XU`N_(i|qGI8;AbIows-(Q(;^K1L8$G1iSZKdHZG}2!3^{P2`6=ropVIynDb16% z8_!dS;8u*7v#Dw^i8h)|5F;XuK~-*1B!aT;P00HHF<>}6S|Rysn^gd0l2iJ10wcoBdu-Go3WaFg#1yd4oa5XLa#e-C+uAcY2|$R5JE0ln}^ej>`$3S4yWzniCKb)o$t8KDu|D zs=6jr3`Lw%_H9Mfh`ZmtvEXxXXR#q}%8*D+-7XW{45&&&f0z!}HnMuIwcP0N0qm~< z&7!f%pjvr{ivM*Ly}9V)=0C-KjP22~W8Mzzf2J(!4r~DDmdn3>H45}TbxtTOPLk@* zjFO){Bqg5_eoz0#83E5P*7!~HF1_nIn!|yzGiMtUg~IKO7x{WJ_og{{gT@+RDa3cP z*#Ypup}x2OKz7C!)7=AfA?1Alr7k-N#j|At)*?4zRkqeVA<`q=oC)~>c6Vl^&wtgX&kzooaK9+d=3&$@EZd8I!lc~3k9`PCdWWLtezvLUZsWOw_L zm!;W@r~UqDJ|rE!Sy+?pv7yrNl#VlaeGd0E7*$Ezb#GBr8t;nEk6cT>jke7V%xZhe z8@Z7nyXv?hRo4)1w7rmZl~tn^s?ib@3T@pQ^%)0cD zmEPpjjV@ifj;fU8@yA#(Xxq*SjO|8Nreoc^Y^Oo$sM`+$k ze!b9Yc01Z;rO$Xg6rvmrE7%BVv_Hrz*xleD*$wCH+>h8;D_?#3+N*>0ZTHtpyanf; z)%vTUV7x9gV`mcTT~Uuj)~RD~bBorLDLS0WgU;s94h>&F(?XQ_L*_nx<vtdB-BTOlYf9N4aLX%ceX|o&L^D_ z>hQZo4R%KD9ausQ=q8Rf?M?N{Hul$!s`8H1@(KnU*oC)?f8w`$L@Sd`AW}CmT%t!c zKkl!kZnajgY1>$U*EuJ%rlIy6@;;X${xlOEW#HSiw35BB1SVXJWoAu6cj;EI5FWSn zO#b>zcJ5jY8fQ-#=WHKLn@I}8Oj4^(_F(juiD)2W^}Ww1F@ai4Bgtfhea5q#aWb~< zxRpLl_7EUw@oJ0ku)6kt`NC?&8Y4wv^yfYkiuV!bJd3ju|Tv2{zZh7QOpGXl& zyVn3<{8gQ>qi`H*xG*h;uc~!ipn{wxttlKv{8bE$&$X>rFX-CaA9j4l54p!o_fpM* zG9V{T`%&#$7QWmNNQ>5XJzU*MHDYU}RLTM!J&8Aoaa(sHfmq$)Wz5X!oK?1dR@G-b z7fRw)pL57QIka=Wo{~DOgbEw0fv|Cy2VaTz{n9iaYAxgN>o@DItA;&9KIn z>u}!34=TeXA<_g8;SICp`j^r3@qzkHIKvmL$w?PGk?)7`h zZb4LPjM=PiPe1VThi3u=m5v?@0uu-a#x3R?pqrD{g?AK`vD{+aCzOkY<9}7~w{vu# z;dx2P3KQ#OBMZlwH50%00UNsV>=tPPB=c)HFYXIb)@|`W`-ih0o$D0Q^WD(NjwPu$ zxLECqyr5DDzl^$BUu?WHt$0hoDZb#6W^9)eWh=LUh00787(1bsmBN?Y1SRx z)>=LjS#sKoy!~W%YOp|oX)6;JuYmBezxf%Vi3n>n^BFhvejOnkt^dvY{p+TAWNxj{ zsSwY&UdI9PhTmXjvPygVGj{*eHIs=$ea}6|2X~3QLwqORTT}70j$`6WB3Cm(Mi zW9m$*0arsXyV~+3HvljD(tbi#mf-lS?w5rSA=$s&xgOD4!&<9uW1k$c^t%m6^holU zLga*p^UbFtN>tN%7k-LmBzq#p_})M2zbHYE~`29u2Y`W-7vb4hd z$8~G((cp#!B`}Tmd!~8^*LYWM5MF~ZPP%wPQBJ^{;CSg{_V{p|g8SVr$`&(^)ClB# zJQX^GXTfHeG7RrqWHl6?TCCyd8QeXbr~Pj&jLj0I!BX5!)eOX%KR@!I(uock1ROHA zGOV=bKi{+e>X#Zl;D`u7hx^p#Mez1gtYf(UMao>g7!RoxrBDH)_ca|n#z5i)5PjqB zkP-{<+l}2I?4NTGxe_Wvfg$o}K`xl86{EAfA!2;N`?jD+sd|0T>wA|(N1zOE1yg=O zP!ng-Tp8D_&@9)H9E>z`z;a3G5kg#G<4NT0{EIehfQ?qN69hcx+mej*%zAH}($wCB z@a*O}Z8L$kQxD#b3}&;iU~a;6DwEAN8wz{k%*LG~a-Ht%wHz&-FqGCYJEW(9?tD4^ z3 zjf4+Gqo+`thS%(L#Ua+^>_S9~8U$7cqOA!M40hQYVcV2BZ^?x}JT>?t7ZB-XO5(}Z zI?lmK6G!6Bo~V2dzl{gSzDhR0X~>s)b#fZzZ7QFNx8SgDUu4lP;(tOITA@K;f1b|s zd0{MK5Kp?oW3)BB@*o?p_nc%HfmXEfwT>0NPZJaj;TAG!3Y zIa;Cu`^Sc}da~|%qQgho{CqTf5w=*hWcrf~pO4z<|GGGzz_=2(^s27d=E5u4rs8Fu zSx89a*;tT2K&2Ws$4hs@n?ZKi!kXg~JfWL~U2kOhL*?4b)1^|nMXr3cR7eW~DUw-i zz!%SY%F-fLt!8BZIdoE+yShGdU8zE?<41=;b~%}^^#Abn)=_me&6hBQKoT^;o#5{7 z3GVLh?(PuWCAbsZ-QAswy9Rf6ox}4!?{C(8-@`|U#PA5uC9V&9i?J;SI_XWKa5D=_XL}tsSS{Ra zBBGUJP41ALFHW_LGuoYWd;6QW4JN;|S%a9124i~QB=-$L+F@bl*-VX%Os`KFKXSEdAKXYA}~dAE#Fxv74XJrF8 z#C1tjcZSfWnG3i&%UznuK;?^QGIqgsiRB-Gl4YJX?SG8V-@E-`8b%A;n;sCqwaI$Y zm;}w`3Z!rjXUe2w=T_0Vu4v&wrXv$e^Jq%xcYbP>vZ4dNs{AHYc|{yztMi^o7gDf zDx{%kXl;X#MEO%_aeS34=}A7EhixP z^Q;TM@tJDz2-8j}Wpoqse+=@bky!GDU`Gc(?1_g(Z^g>nMfbAIh(T65MJ{|}ENPI; zO6zkqg4Z6Ed?5J=v>9XD*oqRfZba%!NrAY$U!O;?d>!N>b2rksNwt=kHJa`5kp3KN zHw1h#GE8pL#kG_Z%qPBiB}Bbe2bF+UmY8^QCovlx4z)A3MhalinH!%Z4Rq&c6fUtu zGu2K+YrJ{tR+)8nA`5b$dh%*Cn0~aQw-KtfGT!T0t#lPlBgn!ux6jJG(iBLq_ZcLI zg`3v;d};H;?Q;q8X%U(*=Vi14sF+!}dDIBeUU@|64km>4wQIP%6fToSE4;@Hy8585 z2k%4Ber$<7Iyl+fGm*YA%CTRix|Vbqv)yEZYtDsx6eotvkwUbqL7+*ek$luX)_Uvj z3_vn=`NI~?(^~;}Q+{vViJ+X_c*7CUVEgwYNB>jT! z36vqh+lEBrF-Ez30W+xd#_qgjp~|6K#IwAp!eFpapU9j&8aQ(X8`NLsRwC*RQ)1L zRT;DRe-=#pKBgIuE8h3cN-bS07AD*nducKLwiOnqr|UQ|E)SEdq-F81gZV%v=lrcK zb%*dMq1=FBT)3~AJh{mQe@oeU_s;D!W+c&!?e90)h)>W`C`WQi9Rbu^K{aJ_2E*)v zERQZ5yy2qmgf^vGnb7diIzsgx08;3PRigYVewS(2+Z+=x*T7MC37>toqzk(!8>%hl zUEI_qtP-E=euhYO+8p~6t~thNR>kb8-BX?c;#UKn?rBEoren$9dK+-Y!1C_-Mbfd6*y+K$GxA^3gxdUN(vFAQcp_)aIq2TC*t~mD;S+&J;usuH z+6v?KGnBYnkFwu{k@t?{Zbn|$a`3rcBq5aLz^KECpVJnn7j;IC&5T6YF!S( z)7EMdeb$mit{BcRtj~1sAPJi-OfN!T?kM;^Uq}KZn;v_6*9VNf2luj?7s17a8KuIC zGBPsZcXjnrzl3sJNf*QlB~^y#;@URO9(X66Gf`*Jho{|@+3T!HgDL`aGODZq$)!#%-A(AIdM?o#T=vNalW!B92<{(^&RE!WlYyHsiF}Nv?1{{BzZG^8MZ5z~dr<)GC%`YBLZBUz3 z*71E~!1hA#+Ds2iZXXIxjv%yJ>nl`hM$e#U8xoJ{;C=nXNbfW#kYK6ZJyZ9`q!hkdtq6p)s07o(I#hLYM_7>muv4)st-p zcW`16ONEOOopIhG?oAh+|B3bc(b12hjk$fad~CCU3EsKty8v^U9urA29uJ*b<4q%ZDyLj8r5A&Wt5i4pez5x(|oi_8=K!L)Jb^z_lq zn|H`&`kcI{V`g>b1RW~XeL6JC@4s-lu_?w+`^gQ+)2k#ly6(nJMgl}Bz_$5&a`Mu( z6`CDQsa%d8<$k$6gw7NcLIXkiX&3*^1WV|(B}(f6aRcx70g3!bZqCz*)$x-v6J+e9 zvNm9m*a7)DWGWT9wSHQ~VujX-7wVB1LNt8*uBmOpNOpGit-pUUc2G3fHAOyTSYwI! zX7LWe&+Yqy^N}MLK)=5s zO*zsZM9U=XGc`U&==iM%_htltUB``}3{bz#vH5^2XFDqRvPMsP^bUa|hDJnKwgNvL zQ*lzJ4lcW<1-%9MoA0MI5KtG~QLA>*0|r@UM1%ORDyxVQa3{aAv9k+5p@RMIKLQFZ zThD761ac0kz*PPf7yX^SpD-VCPyFX!K~w_)F|;jZ2_<~uxc{`=#Dq6C=Kh}Qb3u+( z95g^4me5GO#z77By{vkp5~IJ#C$A#K;HPj-Wa*mkf=(Cm%bwJ;vWzl+^iZ&15AGYl z(+xk34wMfsNy5E@mT$VKYo{W>E#%^E2$Z#?jNyzRoI_36U#*dQe9~U9T|V!c%NPEX zywv;=BTZh%aPMdN;miHjRG2_g!~2ZCSAT*0o);!6aoHlBtS2SZQLk`4+y2x@gTrpw zF}KWA;=k7M^GEa-?GBK_h+e=WLG;tSbhZ71ObSiL_+wLx$`ldx5^dy-+2D`z%$8w7 zYf*zu%WoQ*>}iwgwQ*$2NpiPPrx`25j}N>uI|6j>@NguVeIt_m(sadUkWkol-<9i( zYUkbtGAV`RJB}q2a5O}4?hLNeqk+N22mnqHxn{U94^R8#Y3t`9`Z(R6Yf2q-Re^np ztS^Tu(G{~Q{p~j^8JQT;b%<@MvscC`3feyumj%)??xB)mYtC@3UQ8lxN;+^4313Zq zN4QZYR9$X^U82l@lUUI{gwO}UZ9lmpv_NflL&rbOszq0T^d2KEh2y{URY{B%y!Y%8 z@zc;0H98#V=}B*;qQ+v`jVRBa(b-z>xp2%qMp_i5i|FbG2CStYYqDG-(`jl-q-H0d zS2lF7j3T;MXegZ2#o1d2=x!}OI26kIt{kk|R@QfpazWB0k4zeNfk&32OVr4z+RUr# zWe}jKQaBke229-TW+A$G(5x13_x6AgDce3RQaT#G4iyyAy9muKE>Ac8#yQOKJLZ0> zZXLBrDRR7w1t~`5C9}^-nUc#mf5oZ@@UHZ}&v=UwdaCY~*B9QZ)4gDjzCfY(ri=zB zb82i^&dTDy<0xD;z6wp}l9c^LgJZ9U(u7Z=*gVCQ(_P1_WV7EBmHNItHe-PBm=`NG zsmzC{C%$@|-p=rnYV&f%3yuIRErK5Owt#Q z^oSmJPz`6R+oRew7z|e=riZjynx~20as;nCXVbd-45;5TU(^k|nyHWn_5DoyM5R_3 zWaW5Bfh7^}jhX7Z2aMR*!8B=3n>GWip>A5zdZO0TT6?otkaPr(1DO%hLkGxlU)X`kKI^l;uWj&|g5f_4AMvKQubDrXj0ASj0{;YnC3KDj$4 zg4#w7%(rNohckYUN`Em%7x@(g8@>lfXuy&lV^v-c5*#)Q1{UEJJCkVlC5OM?KV8TZ7wS@V$6TG>B^e38_0mTQY`8MSeA{%PLY zQ^qM2Ekp8tFwoHw6|gxRzE>6C^AJ3wvzGi#Q)i8_KjSiyvaPtS^+p+PAMC6dkp5hA zo-gxDfvmvFmQnB?zuJmriQ zdHp$^;zM2+`ryxA5?Ng-D}wg=^tMRg&fy*h`nusaTz$&YvA-#LP`6xON%rn4^wy?y z707P=d7Y&5vuk`YF~tg@Lz{?E&t7UOD{H}S=xO=#CKTVV1u}ZeANbjzp&|DE3foH< z!%*r7C0?BiVJuGp52yKab1aNC`|tM8()N4F-Ng2$PpikzeJ?s z>9dUeQKz40wZ6Top?WDo>+xD23JCgxKB;GDC`1MwNOld10%pb937xs=cuo#qdmz>_ zT(eH@)7eO(!Se7q_vIeb{$#BMSF3xEqDYon1nn0+(reETi#x#lD~z&&Vkq}&+6^72nZ5sa4#f{#Bp9`BIZ zMz>!I_qsQnx-?iN>&J!-bu@R4Fec0oFA*JXDcPU3hKN!C!{MMVq~&vYZITl#!@@0B z3s01`;UMw?MnXcuml4?7vN-|+0ww?Q4o1!F4zQUA3x$b4O6WdaRLTdjNp45rDd1Y9 zbZ5g*tkoULPCOI#yb})+XaOknb4`7H^OFwLn7L3$7L>y9u5TVm zxcC!p&L$S?r^%h{f!^}c5|)f_c{NpI6$AmTH(xzcYrKz4b~}7Xq$Zo-h5g+9Y=O*Z z`fZpyW38boNy4CH9mSeNGDjq4p0!+s0~Gey-@YOw|F#-)Gm872-1T2OwY0{1^UhZO z>s+EbA&XR}=<|RHg4i&uHb{Fkf={%l>o) zN`U5?+d8%Vw6h;?J@2*d<Yc$7cwa7aZO7xLjQv$up^b$PFrQk+E z5h&LnY{{lpIp;*7PzY|pfW~h(13Er?mX|pJa||?NQtq9dNdugcTb9pqd18Ib3)+l$ znS-I_lmLLUo$Rr!_rx(WKl|?T0yt}qhK8KzcX2Qlmimv7kbN%RU;ZVa@$dtpl_u{u zEj?*M)nLh3g#VcS_ixefZf|2B(G&ga(_X*<4z2&6`6K-{0`mWQzSiM!G+vtjeFR?s zwy%EZlL*w#Bgh5K^j>f{^HV{FSN=}uBNlKgS~NBjWkeC6mHxT<D~a#5Mc@#oK<+n{vL{-;bfTLO4vLSU&r$20;mbgr+@uB8K_LOWsqr7^?yVsz+m%AZLSL9R>$L38m6UBaa`AEQykIOVGD zf?SWFD=JBeJQ6zERNuYkpfE>zMBj&4n+ENdOfve;}+bpd89%xx|!VO#HqoKrW<0kpbGULM6Ij$Hc4X zg2VzH5694`K{S#644!X(;NjC z7j*u&r^)dMRXT%9^!VWY-3|o;aavmGN^qgAt!Q7KIGR2;s3GRNp6F3rW+aRfW1$aw zgYxTO(#s#~7bW8JdyQtrp^%_-VkI|(YURV>=U8diw$2=(uiyUYwLZfHjG-V4{*)aZ z;(VqO0*vFKWRZmyTRz>uXg6vD)y_WM75cA=PoMQ2`LURk>Qrx!%lK2R=$iZ?o0&8h zaV`Q#b(=>@FHvcu%5*ZUKkkLodkPY;EpT#kTy;O&J)HdPZftjiT~7r0mXtvnp|Y^$ zfyBObpoTBK`Z%Muh9@Skw}SD2$mv)c`l!_*n?byN(|5{!n+|IPMM=EgJb?6G=h#>T zi{%p0tpl*8!3I4`OKQLiRf;at zD+=Z7k+pNWT=&kO%p0hH?qP&$n%Lj-mfSOYAF;Ua%bjGgXO^*-8h;g)QP>P@ejLGS zZhK()zP3k=xKyIZ;M4B;1b8m-gN*MD=ZLit+W)Nu`27j6Zz{I4+Ym%?ZGv4i+W6J` zO7_p|-mW?nzk=K{OjieNy4%6Uqo}gWQ=w!Y{;0f0@)wXgvtU$4QJRFEY*`(S*X{rTT;gZo1 z%nQ6Oos~x0a2!rl`zzM7bzpYN%F3$5@3svwI*x{k zwJ}g}0IpHFl;3O1^23J@pFcMWR$9|TvlnUbzPq+2*qz8?8-77t_EaLe+Bn}DAR4jK zUyve(k={`5Kc&c)4typxl_Tw5#siQv-WXY2l zmgnTVZ)_jm8tUbdA?b8PvVZmI(D~{GCe!5CC1BPr4PHtss%>~9rLb5I1Hz&2(tasujvZkJkr;CGRO;fe+RH$-?($2vxu1Jf!d5!XlQg@x9|EsxNbqsaC<)U7txx z>Y_T5@_@WtgLn#ox48xig!+oTPDb}bnuX5ml=>J1EJhpMDY|EE+F0^^oNKav&W|h1 zzC3O_zl?T`vI3ECakWi_{Zb3CFt_MInl7O!>-177vAu7tf*w;QOcKcq0f4Y+rB2s} zTD6lS#cF^fllb-;IQc}3K#ERwjip>FH}-cU?B~sq&Fc4S6Qc8cgN~7dMQ?u+;9Nz> zk+u~FtHpRZA7S#>Jrbhd)xiivofGB^H*w@Zp6$Fc)-7D{((`7l-Wds)tyorRyVP!e zi}RCSt5z-G4;rq?DnJLbN48j9sgn0)x4&e7>L|T9&o{H7RsW^2+wx#OtPnYmDWU}w zdL(uCgvfL;Ea{W<0%IRZq{S;!tJ4FT$VbyT(R}c{?td!1vq})LAs~#CS*P-N2C{Kl zX{09&1n&Fyph*kXqx z)0OrQq=NB2CddMYSu(4m@kbDGVSNYY1D9MD^U7ug7-3`EB8_1g4HHg%e6pXo{Dujf zSbmK#mQ(7>9^4rbZXZ6QDi@Q5=6uwnry>b#MTGSq3I&Jcfipt04d*h7#j*^WS3Kip zD_rph={({d_Jr%B?x8zSdRvEMzkNqQjQeVE{ z)&h2M*Dxp}uH2PemW%P0)>-))C26ArHV99s(q&IC-f>-jqa*6DA7QMlO=x^>a14kC$ahfQfq?vt1>)Yljm;%&@2)%a+1j(rs7S4)_#&kFA0n8lGIerU%#Y* zyjytedGWoqT0tO%5kTH~el{d;Fc=*GjY8q!DveL~jjjM%bvZLX=FR(AZ8ughag!1_ zjm)iWZQu*-o}7S`ddP)J)v7iiDKI|*D8~Cj!t^iS=ZSf4i|-h0C=O-Uc1x=OzxH?H z4}>jCM!Dvm6tL;_b_7$x+4mFi#na$u+VO!ZCe!6GoF%44fbn3CYj5qL&0^)6RqXGi z!=uy(RlALijZQ#ALBFo!AK)$WKlz`eh3T(V*Ub&S2M>}UyjIu~bK+eO0XajrNc?B= zw`0xj$K_xCW^&O}oSc0vV|xSbl7mJG3rNUc@TD`7G`QcnI)m@ei-}|~?TD!G@YdN* zT0c*D$_m7*N-fbYi9Ypa1ik+|e=vfIs^3^bq>+tQ9G9;z(SY54_rSEl0g%UzT9u%( zsw(1&{=W$JMSRFnDq2|Kdmwp5NA+KSzd}M|y;X&X=6}KmLjX0m?VX3t^RISJYJAv3 zZ?3}_&HrR}?HtwEl@Sn&(eTLC-CefMQl!DRf;E4qo%2fsUvng z^ga&0UKJ0AHzZjkZOS-pLo%2zFuGUC)GO|8yph5zm+SdO5}J)+C4VLn49(8rg&I!! zgW=x#M1$r0;A?E2spir=e0qZy80^f?PLx{j+ryv-(*T7D11#uQBw%wt_AmOOzO& zr)6~aBE3k94yWk2w6fN=pHrH6DO_W0u>i3ZnC#~ZOCXx+)z{Y-2eQLyQ6)z=9dF;v zCUo|G2S#^d*?Rdj*1m2-HPfDn)}<+;%R4K?-7!Ly?s?CqTpoq!P_5X>w#s>~jQKX% zzc3iHNE-S}s;VVO`U!G@xZ9JgsPkMe@=IG&KdkE+7AY@cSc-rdBfRykIOZKJ7Jby& zoQ(Hw`nE3`o)d~Wcw?{Zx}DC1sM;I9Q(G~Y;%cm|6Ppi4T!K0v>N=X|*OD~9p4oSW z$)LZ*m10OIeO&Ypw_h&?;LmBy&COld)mUl%A`lD?rqf}*-^&|ry%2X$P>Xz86O!jg8S_|nZRqBfEZ${W8S-RG3Py;A7HK?& zV-Fp*Fn-&@`h>9eJ*n)L|zM;Jq`1@a1XM9%5~6Xu52vomWs5rM!)SB~N6 zr6JbRY&vLT@-ZO0Dhnva1MJ3(=z-p5@c8mqlYGg{vG8Ph^cQ@cEw>t>}Kev=VAf9jy&HxOv#lhg3?rBpbKPV`9v5tYA`в9_)V;LQkc z=R!Ckqx)6$M-cR)O-)^=*qLZK#cHxM!+E+Q#q?}nEqTfp1b52OF{-M&VZm7~adxz_ zyT!p1A5L^;@*#D$t<)b-St@_`@3k<$XiD;9LB8{V;+VFa5q{|WzaafKz31F-gb}wp z=$M?C6>t#UDytJv5sH=xZJM~I&0X7wsQXh6hR(euXnW8{P%|Xnn4hS|s47L16IM`y zs_tC3uh@Cp7&30xW-{D&kme_gR#Z9sMGFYdO&G$6J=dWPz?R~W58C_}sau2D7~{J- zK6yO4aox}_w-^qH?MaQf+S=n}y&DSwkM})`l-YnkakAD12MB;Deh%ZaT?Pa;FaUNs zK(zgFn?*`W>iTFN!Pt0DMcU@H-4#}aGgzV=14Bb!=GsXqbECrnCJNcQ*|EaU9acGF zhIDyfwU{Foq#83;fqODl{M_KlJiQdJcb6A&jH`**cIjrG@zNGK)fd6>zPe#%~;^wIm7V8Ib= zm-fZ*P1qWXDL?4F%+B);bU>4U-D8&&wMd0zAyN^&A zs?|^)S}9x^sJLL%*v-7s)rn2yTjY7Um^CC9;A!iAfO)f-1hYD$3dH=PG8=i==Jdz9 z+Mn4kOy{o3hV%2!(b0h5z`MLK&sJGZ@yBq#<&#YJaVUe!;#S-02C zU@LIVBj=KYu9%pkJ`^uQ2l0fDNQ(R}nAzD29GmA=SI*4Q@>rfXXhxF(Tb7rp1U*#JS^oe7ouiMZUq8g zyo-$xzSHccD!Mh24XLyhTk7Ba7_4ZF;mU6Y7q?(MRFNOAn0EFjTBwP+dA>EyeD%#N zGC9Tuitg;G%5a4_A>~Er@XuP`~~{#avaw)=H_AuHUm(bXC@_a`c1#)K@zi!*%|QDR7zIcPJH zuRrldQ1equu@+L!T4=YA3sBwp-nKR+35`_kVouunNW)5-220;7Vt2+HW|Y&0l7=89 z?;Xom!qY_V>mp!_(?20#iCd&=*wowS4qH3Z>Gqp%u!NOUD4x2ok&&zI4lMYi}OvG+m^XXUa|(gyqp%+KED}tKTPVP&76;OOH(PveEP0qv3#2pQt{s008Lz5 zwy5AvieME{TuCAX-3KG1_W&F9buH|_*_#%Gkwmxx``9Ig3fZV#6vj5R;ZZtP2xhLd zyC5*g|5lo6YpG2y80Ol|4_Q3i5qRHF`&`@;J&rg1h(p~$CLNxq2q?Sw5SDNCU~(ru zLu!#;A8jv$B{o+kQQV-d(D!Q-f~Dppks%2WOY$YZrU^Ygp5xs&4Hf_@DAwzV9GNA5 zW_~cZ8ie|x6jiD)bZ}<}Ns`Z$YjsOV?TKs!vX+d!2y(p+VDwIxf;p7`klD_)%sL{O zzJwuDPHS*~3}Zcv%sG~-brx$Ex{xxxuL!?_PPAPPwM%P@vFjQp(<=ViSG`1_RKY8!~Nh=yY z*V~GDj$==cV%Wvy7pb7uH}QYKf%v~nKw0P0gB-}&$v#h@=Fng&xzYO$oaFoSqxR^% zAxn#u=OG4VBQtvMn_bGc%0f6e;j_K2n?qeV`}!jQcnJiERW>^JqU z;nT&>ODhq9{88T<{%JZDkR#3u3mNb4Psqy3a>3#qas+>CH-R}WyACgBL{x4wFCCCS z9%gXcVY5;=>dRm26JgDvBZe{V9)sdL&Cp*bhS=A(EbC!aC!vD#rq6R!KOT7DDaovi+`)H=zH_{xacmKuYBr!W{=uxPi4t*(mA`->F3>0Wp%{v zt7*>QuArHQ@?Dd-*a&Yl%XN(G+l-IcqDJM6zpd%IzJka4=<5Fm6_9LhNL4S4Qkl=8 z8+)xLm9FA55I^zHqmMTCKGPW(ayMag$P&g;Mn<-~SL}8_7Vxsv$RMqQ**HIj9w-_} zQJpPR>Psb;ACS$tmOP9H`Q)&-vN>+9+T@8!LUyEGb5^F^?noRzf+EgSNxx9hr}p7^ zivHiqDl4qBjJO796;rFH%ZMI4(&!Lc28!Uq?w6B(_Y>Fr*XL7gP*=~<2W~dqG zN?c_o-KcwuaR{GgT~SC>DcrHyyU;GzpY7b=eCD!C=&O*Uv5Th?4y-ImZE`5w1|+tpCv`1w$#fKLhAb+C_{bD`Rh5R2t?D3TxTvlF>k*f)C&^>r+9 zK|ecdypp>B*<49!%w4B@1NMSBdaT)$S^Nr~xKGMbwkB`jk?AddUCem1oRNC3E8ub7 z1%5dpJ{|e=XO+x`oSxF(gyHrz$Ygp$SMAYi9(}}`5)3b%FFku>(>ptV0PLzr?wEjo z)NTjpDdJ^hWL&Vk0TZnko0}JZlvEyOP~{ zk<1^yRvekn7miI%Czxw%Ya!fl?`Q%$AYKBEN`-E{l}MpTvDPmo!NU`ys9?vfx@l`? z*Wc3<3n-TMFVp{?Vg5G*`8g);Kb7!XH|YOUcbA=eq<8uKzo-L|NHYxy98jgTS$9S7 z-|QlRC;;+G9+L+rZr1!Cf32@inCcS%l9!`bdl%lq>i@+mi0FZgJrj|@|ITp={00(~ zLt*~a)+u7=O=F`NyndDqk|Ep}?>7JQH^KMk7Zw)!-QT}*D~hj+Z^2U&;4XbOFyxY7 za#gsq^CLep)wQ&LC|Xu$`!E#mV8WQg9q-=}-eUrp_$l4@TF8IkXJMRnJO4mNteT@| ztJ2Z3_R6{t^Vs$tK3N%_+e|_7{52+BH=AEI&VG%yr@R>?Dr8}yUlV3(AMaOCAZv~x z*iA)_*+YpA77baV&LnPp4@3-&1M(sm*IX$kjke7|Ug!AU4`%}Z6oZ|;QXFGx6DKt;D|d^ypjTJB8!gA zFGH>QrZF9S?}K9`CEfd|{_prU%48C{mBNAqFS(zT{(ndUyDy}x`b&2&CTiw=8*zqf z=qAQ;NI#k;$st1e4|6o)Dr17*%@aAWWvjlfdpB`d?E!*qVSg_VX+ti+KlL-`fTF}r zm0961;3Kjo3Q$vLg^%~;ewXdJDcuZ9hWfj~149x(%$q;TbD+l%YbQVEuK1uD zkL^YO*+4s=CnG8|52_#`^)m$D?JZGB0DP1XWz${r6lI*g-=&UWLc&}s?$x30R$H5d zm3jhIIg5%Kdo+nP_2Y|e%*0*fHz!9Vek`=E`5{agbK@x#%h3hys9?vsT+H6d#nmEh z4m4BwB|TH4UzWuZOj-^|NE8SxH~9)IwAk`V`bN58>IrrZNv`3Y4e%CRoSE>1M;yV+aSsEv9G<=BSrz=4(e2pmnoSq>2yWRNRD{;+$RI^a|1H@KY=)5Q!$JVIjq5kM9)AysE!vJ+0!p z{RXX z;zb2Bm-8zVOX-_4TeTPSv>LKuN`GK&ABB9Lt7>Ca>MR!NWNSXVX=GG>rQtR*A3S`v z#>3yVDq4v)mbMG%x1gJ_{K?{DLxM=FTuHSDFZ`c{Q47s(pSqS{9S$`x3Zfv%`+h;= zq{f(b**KN0jJC~L+Pb@QGAHTlAIVz|e#6EbHNL7fYaCgAkHt2&w_)GQbp`kmVo083 z>aU(@`YkZRlIOy|!1ZtCJBR%h`JZCMe2M=QBi>fY7>I{-$(yzmAu_hWW&QjUnRd(+ z+JS>rWhbGS7C%Uj5OLanJhJ9+$vc=kbsO`uOx+Z7+oJcf3I;=_4DFz9e3Ab7lhUe~ z=*dHn$`aGf2$lre zE{@{I)2;g_kVO5E1QdgAcRP_q^-z1GkH|07nb2$$vDpGa*|6E>+Rdq*qEMKn(9qD@ zxf5ArWdWE_RKXt~RTVz|8f-Vje_|Q&d==^Zia5wHG)j~?&z`{_= zR){1Wf#;2P7WsB@)Hz0&v|tV;uBAFWNm*W638AMy;V8{;R-9n?({dLgjd4SYCBikW z?o3nj6`VI}X#U2q+gI7u@uV#r9Ru>UjO*bkXklU#T1)kbAhE6rjKur?K?3US8Uxqs zQ2cf8kM5(c6>K|>M@`*FY(Mn1g2%JQvUwY*7T9{Lr@%AMiQW70@I>k>8pBP}l8}yT z)dU{acpBMR8bShssnSBnss}TcOnu4e?W^>Xq>JvGYl~GsRx6iue)gb7>mdufu&ev! zKJT4T_?N?rk9i(`ky^&U~DF? z`YRFaSBy0%wY}a~?HW~Cx~X5U)%(1;yY=U|_Cue6@vgokc7Lz})(FD!mJAqTnIfLm z5laF+`CX;g8N%_E-!jz3b{ai@NctPivh%i1qy)kFi#pZgu<&vT31hFfkLS}cnh1B$ z-_rtD%M&&DkAai2E!1%1qofs`y}u_Am6^{d!IaQK<{R|T{#y(11?pECz>Rf(LHRco zrR4lmHhYg%-o1lOILGVEA=hKnSTXA#l$C^6I*OAbr^4pU^BeSrNg^$goehFKrTU{e-n`jls-;J)fxNJl( zqrl6*N2Gsxx%YC3o=nH%dbr-FVzB?vY30RsJit z0ZpSn4UCjl|E?%0r4OH~J{>mO7TgDn#qIlFhfYl&*s;f$tJu=mq+GPIH6HJeu04-f zpKk(6*v~q36Ixv<{jlM*n}dTz*f?3dG|R%qX?Qswq>U`tjXnQ%g$$nPpfD z0Spxa0&BIx%QuMD(s{}OGpq(nQ>xCKuuK0)EHi`tJoComqAV&5O7W%R>v{sMN}@g@ zb0xwmC61mXPgKjAy5RVccYplbGak3iAoDm1#{X49uN?ANlYDOQA$wD#s@^-n$nqozeX#>Ikq$p2(&yG;0>=w z-LVBEDZ;9^+b|w`&UClcUx<`vTg;CJ^Tw$La5*EzGh35G-ll&`1HJjA0p{PnndWn4 z7yu;+D2EKWX{%PoSGy4rw;lsINtETT9+;R33~@Xsk6;rmn$|RI_5^|7LRD8tRL|aG zu(XE_1~sKGp1#aq_8w;3d%PVcJ{o=_=RravBzP?)|I&|!936=O}Nevls4lN)c z&@Cw@MiCGY@P~$Gqns z_Vxru!_}i?TgV3v%@^lWSJSTzTrP~`8n5`QPIdOLt5FP=2MSt^j%=Q5?LM{;%SdM< zM&t9Trk+pGyHdfBdgxvQTcgh#dblm-M4mj2!6E#dUzJn(=5~0$X30aeeTKM83S*mZ zigPxO+{_-Q)w5}FDQ$o8XdFjy#4%7!F5_)@-g0iWpUheD_QK-KL{JVcwVU*P1i^wQPikyA+F7mQNv; za_H;_1c9!Y`Mk4Ju28fzG~1ExyEWT=!Y&;Pd>VW(YIV51h4$lFf-*dsShZ|#y01^B z+NW>JNK}v8#2KR(NT~}kjDgy}md$;6`dN#CS>Nxa{E|qy`z+mYi(j&)DsA;WW4oL` z`8LtK=_G&X+IIGw+cslNJ2SO!VDCBkVSat6PkT(?LUJ4hH~=4Jn$flRY&|nC`cGa) ziNd=2uMtP(@VE=OyY4Txq`mWlnP6I+PO|OyK){9qjQ$FMGGMS+sQ8ufx?S%>skh+g z<>qeMuwmUi60_IE#VLSIO*yeF*{l7gb8!}=$=r=+S&9t}20kJfbu@u!K|P{C;wgux z;N($I6*&of)UUF-(SNUi`S2?2{V67OGfh}tr6l;@`P4b>)h6i6#viCfq{vph}fDZmqw2tA1tNrR?qh?ABVBwedE95Gg^rySp433F(yXRyu^CLy#Q0yHg42&Y@H3K|&-{8ithm4&wWM_x|qu1t)f_ zz3O@PIcK^2oX8%_5==C3>PQy#Ih*myo;q>c_cVY0qCFry_M9M5kF1;WNnEN<-~1}& zTDpfv9a|F$y51hf_FJgAgeC;}Pm`v20iU=)X6389j?;b$f7eM|f`FFu3k#qhjk#7L zoB0HORID&wrq>)h1;)7v){{Bo6?%1Y3LgW+tz?Rei^tM=!|++PxqxTzYU}D+wleI9 zUO1AySn;FG<_{l^l{xFUay@j&w+ib;8p${q3K#lFNR>++_b#ujA}Ru0L_M6) zO>2BSw~_+~V_C-0k)zIf{KtB%_||^gfi>{jDjp#re8uO08@#IznD%mywoUg*@ILi+r@_Uv4?9EAWOXg{;)!-4@4-uHgE{o^^v;)-_)|1Vt_y- z<_k(SbVUP7>x#KE!SQSP3)vX-$k3w7z)Z4Q7>g(NgAE-PPw-OW64RW0U+hUU_{{BZ z6+;n~pj0&$JkzMc;iHr5*^^jx+-?Vza=}7zTHQfbtK4?S5(O+6a8RS-oI;x=pmvOE zJLVUzEru`KYTS*G_eQS9#*_%ybi2ttmefn(jH)?fKz-sg;MsJKB^Okuj#GkfjSd!z z^){evl^pMF=FaP5#S-Pr0ifov&2$Ooi&bAZ^E{v84PKIy5iyvQoh5|j;LJ!#FF_d% z#b|Q7Co8{(@!HQdGHeue@D_yGf1-UvXRPfwUfPFD+xocankPgtTcTUOCxzCYO%uJ4 zPZV+5ayu(_Au&gFCk0$ZzKUMft~jUocj)*avWYnV!_-6kdbKTZTe_H^clMdcTBe1*&=N*XS<;=M;9NY6ao5Y(kS|D9pKh}&6 zn}4V*&}Z`08kCLV;ozXLg4?pkGhc+ZVw4B{0};EI!LCTuP2b4t%_wyYT^>US*b8K1 zDX!PB1MZ9cZSFO#0%ly5Z!s9tezs`G4?GMZ-JhT@)+iR2J4zTv;yFJ;nHSl?7tdfb z70!VnCtvWnZxHI_C}NgsKcL#6$N;#Gczr^sNf`sDT3*ko#h-Ms6h z=sAM(wDJpXv)&Jj?3NKfuXAdy;c_^)64acWuu0V_Th#;8nA)bkFXhGWXgTKhl$t z3d6GcJyo1m5@9w&|BL8Ev`y5ab8({9cj(Ftd-^thym`n*=j*>< z?C%Y|z1}I936)I0&voSD%H6rIL#8d2luhiP z`WjE25q{p2qn4q-P85Q1k#sys>}@v(ld%+lYUrhwqfOrPwY%@k&3?j!Zn|=N9)73N zrlX<3&G|2ep_BaJ&ctg?h-f+yiS9z5oF+Es*B<>%oV9zU@cBDVRfbuTR#)Gv^LIDb zNV{l6C%JJ${nSsaiVZw?{)EtOWDrcW*>g!PBia zFTPK1o+b;Du^@H|4qg59YOYacpX2hgzi<^lD8fGup6{LB;IN%QfD^w(Z@BMAUuxa-4c6{uQ8tROO+3QG!y~7l z@Kl?f5p4iV&mW9~ijH(K+J%Mu2#+A?b79^G^0qqNdZBo6<%1rpN?V+d6<`$i`lA&v zt5iBo3O9;VvfRx$`Ai2#BRZdKl*APuxwuL2v1c<-09~r*TQViN;*1iQDZr8 zGrn>Do-D#KB57s;^!G4-PNuxl+m9|s)JFga)=w3rS%a&);O1Y;#VTX*>)R&utPr80c$ckQ@F-3fn$ zvS0urUJ=Y`tYJtezVvNq``~|rE6)d_06`(iF~i(_#9p4y4P1}%Qru#hH>b5wFX(tB zj(VVMORyY&(R#=fo|hkDj^Qz8SS|W6GaIJ6AP_5~8R+S?Dj_&jOZrMX_#-^Lyul=6 zwuNViMH% z)+&QpK&)4Q1k$BIab@_v$`NibOrXY95Q$e-X!w7Ai%YzoIQ+n=YNeN{{ z-t>|##ic6S*}Yk#iE`V?a;3){qY+0kQHE*q@xRx*)hQXiww_g>>DRMFBk4W%G;}fK zuC*&01x(6D6978_YjfuM2U|6!kLzCV#c7E#5V5(a)4>op(^e$((9QBboEu+-3cpDG zE;{G>lXdHpvJb48J(DzG8L}g!`Qj^-&dx)qIv_i?y0@^i*IXc=BR2Ca<#=JNDyqE4 zUGsfA+lngO;t|0c+<^A)eG(|9(a{B)HiRE1cgkaiJ5N`6_r}?HkT$WsAV4W3P7(~# z;0Yy>wWYD8soH~BGg?@&8I|(a8Y7;-9sjw^g|cTVJ@*5*v^7da53=;bg5S{-;!Zo5}-kBdi<#0Ys}{- z)imOQk2JN_K=9;1}riJ{E%&yv< z1+_9#_|0i+$=J#9VwW~te{&F%^bMwy3}IoCj0rjYATl(iJGyIoAUOghP2P=Vv0It6 z!xOs%zVaS?-MMU&1Jq{x6dNW_j&YrhWPd&AC~%2nzibj7OH{y0K}tTFzO3(T9Wwr5 z3RnE`W|&j?c1FpB2RvF`!4K&a-GT9FDK1|lj9tuzHx zp0n)8$XjGN62U86h@yWDhQr^_x(=Ii6oC zrp}OK2TJHbVA4hHiEYZEl=WU?N(H;Qjlr!E2m7&lVm#`rq-2Yly1Z@!hcAM~DBhx% zvWg(vN1-oc&yE;T#%%E@Ktl(&mq@Ix%AfmP*EV>Y*<~sr@nhyhOP()H5VkmOGiU{^ z?i^Y76O@Tz>`C+hW56dA%a~qYpAGO1Dzrfk>JW7f^~jmRUiH1O*X^-@MtSK6n=Qw|2l@Os zuK@k7$y}IpipTR}JbLNwli8rhu=Ta(eTqHRUQ|@%x-qn-mP*b4%uz~=>WQ#b4~At! zhe`!l*p9&a%x=(W!U3ApBOkS^$sDKm<5z~IDZ={-!#Q$xY_gKr>ZzwAVXyn9`pG}s zkV7Tyy~qS0?UtGuHck$(pm(C14I9PqF9~c|+BrUyhw*;)OJ*Snk%~xG#1$#kgTy*w z5!`AcE4$m!6k6^SX>?PRg%iIsv~wz9`MmJdm4*ID-{)*!qcUe8KKMf!7!TPhH-@K$ z7Kuk!``Q0bR&mP9z4wwH`-JVLZ3pRfR51&a(?-Hk8#lg^r(0gRdR-UqZD1=?35W*& z6!1YqP#<<2Xux{K1SzQd7HXB6DxprG$|)%KGBP@djFSASX>Au-I5k#bV>Tq+G7S;z z-;#{(LFcSZD4g?_X^7Q)v`Rz)@o*S>GyM!PxI5A4k8?d zflAY(Q&u)bTWxY|Bb&~}`vYZIjsuOLK8PMedgfFbj@H-)$Jfu*7e#YpQ%0y>{;DuM z`8R{wS(FAtk?i7*_@p&17(2MK?SF`9wO1z`ImAm@(Z#>@?68h5@>@sEa{zf5pLj+q zksuisk_|KNrhEg&1GD_h$C;=q(0`L#vSXPQr0>A6CrqUY^p zDv`LqZ`sZxl4c`yXSB?K44jC@3zt{sC6 z#5F^IpWn~ufv_$Esa8bv?_okw%U8@oT1DW{f3Sd%`c45d{dX>z^ z;iFk*_Y8>AI1xgLF4A$?_h_E&)F7}P^H6KDemu%|6B}&*9~V76g-4VmfM*&+M2woZXVi5 z^!KbY!Nl|HB5!b;sC}5PL`eLFpbyrwPNS5+1Iyn8Ga{}D_o#j(*arZ#Boq9n<=axF zzp^CZNL9R_*ix8p;6Ex@gBFlWsH;el-j6+9DZP7UH(V|a0A?Fc&jBb*oz&mps2GGZ zqH*7VbZ??QA+1g`_GRFDK3n7p)Z1L=L85{YgNYSBiSofU2+db2R#S%?YV&`GgA1lH z^Ul>|*Vt!$a|O+%EcR)#EVvQF+O$XX4ryh0m@N+4^c7t#4CUN5Y~DcnPmHP;e6#GVm*U%FJ92cur*CB=DF0 zYA3s86Hl2kk=8%Wd_{*55qGGWDPd#NEp&f}G);;l5jhOlNbEq#;$!#+h!toyOQ0H} zZOatg^FJO4`Ea?!A7DnAnbW|hR)0mGT;|SQ+hSN1-b$hNulGj{910e%AG(TXpic<( z4SX=9AvC~RFKKLsQ2(*?WTk)x>SSgLgrPrliDScK$f48s*zVs5TmijNQ+sIYWhF#e zrU>&tCW>PtN#pR}mJomozo`GcFy2}fxH9-#wzQdZCGpu@n}s(A*(D??PF(_e!X`yG--iGMY{&;^u*13PBWg47Q~ z)Xcuf<^it{>vR#1{M7J~Vus5|ubySNeSG;9(3ALkXCYeWSP z^d7zUtv%b@*l{}NzPnVvakzrt)fCXTb;`l-gNEfs#E}l&DaVsEmB+g6YsT40p8Ck_Qhw9y*w)q`x=;qAT HH0b{Uiy6aG literal 0 HcmV?d00001 diff --git a/ifm3d_ros_driver/doc/noetic.md b/ifm3d_ros_driver/doc/noetic.md new file mode 100644 index 0000000..8c4a341 --- /dev/null +++ b/ifm3d_ros_driver/doc/noetic.md @@ -0,0 +1,64 @@ +# ifm3d_ros on Ubuntu 20.04 and ROS Noetic + + +Our package `ìfm3d-ros`, more precisely the `ifm3d_ros_driver`, depends on the underling C++ API `ifm3d`. This needs to be installed first. + +>NOTE: The instructions below apply if you plan to build and install `ifm3d` from source. +>NOTE: For older versions of the `ifm3d` (`0.12.0 TODO: add link to installation instructions for ifm3d on ifm3d.com once available + +You are now in position to install the `ifm3d-ros` wrapper. Please switch to the instructions [here](building.md). diff --git a/ifm3d_ros_driver/doc/rpc_error_codes.md b/ifm3d_ros_driver/doc/rpc_error_codes.md new file mode 100644 index 0000000..41615b8 --- /dev/null +++ b/ifm3d_ros_driver/doc/rpc_error_codes.md @@ -0,0 +1,9 @@ +# XML-RPC error codes + +The underlying C++ API `ifm3d` supports these error codes. They are only sent asynchronously, e.g. when configuring the camera. + +| error code | description | typical solutions | +| ----- | ------- | ----- | +| 104010 | JSON syntax validation failed | Internally the sent JSON string gets checked against a JSON schema. This error happens when the parses fails to complete. | +| 104011 | JSON does not match current schema | Internally the sent JSON string gets checked against a JSON schema. If the JSON string does not match, it will be discarded. No changes will be applied. The configuration state will be the same before trying to reconfigure. | +| 104014 | Invalid configuration | add | \ No newline at end of file diff --git a/ifm3d_ros_driver/doc/troubleshooting.md b/ifm3d_ros_driver/doc/troubleshooting.md new file mode 100644 index 0000000..0399b45 --- /dev/null +++ b/ifm3d_ros_driver/doc/troubleshooting.md @@ -0,0 +1,50 @@ +# ifm3d-ros Troubleshooting Guide + +You can use this guide to help you identify and resolve problems you may experience in using the ifm3d-ros package. + +# List of contents: + +- [ifm3d-ros services provide no response.](#ifm3d-ros-services-provide-no-response) + +## ifm3d-ros services provide no response +On systems utilizing a single core processor, you may find that the Dump, Config and Trigger services of ifm3d-ros package do not provide any response when invoked. + +This issue can be resolved by setting the "num_worker_threads" parameter for your ROS nodelet manager to use a value > 1. You can read more about this parameter [here](http://wiki.ros.org/nodelet). + +The snippet below show's how to set this parameter using the [nodelet.launch](https://github.com/ifm/ifm3d-ros/blob/master/launch/nodelet.launch) file of the ifm3d-ros package. + +``` + + + +``` + +Alternatively if a virtual machine is being used, configuring it to utilize more than one core should resolve this issue without any changes to the launch file. + +## ifm3d-ros nodelet can not connect to O3R camera head +If the user forgets to set the PCIC port (our standard communication port for data broadcasting) the default PCIC port argument will be used `default_pcic_port = 50010`. This TCP-IP port (`50010`) corresponds with the physical `port 0` on the VPU. The 2D RGB imager or 3D ToF imager of choice therefore needs to be connected to exactly this port. + +When these two port arguments don't match you will likely see something along these lines, being repeatedly posted to your shell: +``` +[ INFO] [1628860557.703261704]: Running dtors... +[ INFO] [1628860557.704592043]: Initializing camera... +[ INFO] [1628860558.705489893]: Initializing framegrabber... +[ INFO] [1628860558.706352595]: Initializing image buffer... +[ WARN] [1628860559.207288723]: Timeout waiting for camera! +[ WARN] [1628860559.708197339]: Timeout waiting for camera! +[ WARN] [1628860560.209029697]: Timeout waiting for camera! +[ WARN] [1628860560.709553855]: Timeout waiting for camera! +[ WARN] [1628860561.210310005]: Timeout waiting for camera! +[ WARN] [1628860561.710739497]: Timeout waiting for camera! +[ WARN] [1628860562.211714793]: Timeout waiting for camera! +[ WARN] [1628860562.712752207]: Timeout waiting for camera! +[ WARN] [1628860563.213765790]: Timeout waiting for camera! +[ WARN] [1628860563.714424040]: Timeout waiting for camera! +[ WARN] [1628860563.714658175]: Attempting to restart framegrabber... +``` + +The fix for this is easy: just remember the first 4 digits of the PCIC port argument will stay the same, the last one corresponds to the physical port as marked on the VPU. diff --git a/ifm3d_ros_driver/doc/visualization.md b/ifm3d_ros_driver/doc/visualization.md new file mode 100644 index 0000000..23a70b0 --- /dev/null +++ b/ifm3d_ros_driver/doc/visualization.md @@ -0,0 +1,28 @@ +## HOW to visualize the point cloud with RVIZ +The included launch file `camera.launch` will publish and remap all topics and services to `/ifm3d_ros_driver/xxx`, for example the point cloud topic will be remapped to `/ifm3d_ros_driver/camera/cloud`. + +When you open RVIZ for the first time and subscribe the point cloud topic to it, it will not be displayed as the transformation chain between the different reference frames is not complete. + +The first option is to use a "dummy" a static transform publisher to fix the missing link in the pose transformation chain: + +Open a new shell and run this simple `static_transform_publisher` to map the `ifm3d/camera_link` to the `map` frame. +``` +rosrun tf2_ros static_transform_publisher 1 0 0 0 0 0 map ifm3d/camera_link +``` + +The second option is to pick a different reference frame in the Rviz options: + +![Choose reference frame in the global options of Rviz](figures/rviz_ref_frame.png) + +### Change axis directions to suit your interpretation of a robot coordinate reference system +We have removed the rotation parameter which have been part of the `nodelet.launch` launch file which move the axis directions around. This decision was reached because we believe there should be only one place to change the extrinsic parameters to keep things unambiguous. +We suggest changing the extrinsic parameters via our JSON interface (see ifm3d) and the mapped dump and config ROS services for this. The extrinsic parameters are applied to every measurement (distance image, and point cloud). + +If you would still like to add a `tf publisher` which switches the X-, and Z-axis please see the example below. Afterwards the Z-axis will measure positive values in the direction of the center optical ray of each camera. +``` + +``` diff --git a/ifm3d_ros_driver/include/ifm3d_ros_driver/camera_nodelet.h b/ifm3d_ros_driver/include/ifm3d_ros_driver/camera_nodelet.h new file mode 100644 index 0000000..d048909 --- /dev/null +++ b/ifm3d_ros_driver/include/ifm3d_ros_driver/camera_nodelet.h @@ -0,0 +1,122 @@ +// -*- c++ -*- + +// SPDX-License-Identifier: Apache-2.0 +// Copyright (C) 2021 ifm electronic, gmbh + +#ifndef __IFM3D_ROS_CAMERA_NODELET_H__ +#define __IFM3D_ROS_CAMERA_NODELET_H__ + +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace ifm3d_ros +{ +/** + * This class implements the ROS nodelet interface to allow for running + * in-process data transport between ifm3d image data and ROS consumers. This + * class is used to manage, configure, and acquire data from a single ifm3d + * camera. + */ +class CameraNodelet : public nodelet::Nodelet +{ +private: + // + // Nodelet lifecycle functions + // + virtual void onInit() override; + + // + // ROS services + // + bool Dump(ifm3d_ros_msgs::Dump::Request& req, ifm3d_ros_msgs::Dump::Response& res); + bool Config(ifm3d_ros_msgs::Config::Request& req, ifm3d_ros_msgs::Config::Response& res); + bool Trigger(ifm3d_ros_msgs::Trigger::Request& req, ifm3d_ros_msgs::Trigger::Response& res); + bool SoftOff(ifm3d_ros_msgs::SoftOff::Request& req, ifm3d_ros_msgs::SoftOff::Response& res); + bool SoftOn(ifm3d_ros_msgs::SoftOn::Request& req, ifm3d_ros_msgs::SoftOn::Response& res); + + // + // This is our main publishing loop and its helper functions + // + void Run(); + bool InitStructures(std::uint16_t mask, std::uint16_t pcic_port); + bool AcquireFrame(); + + // + // state + // + std::string camera_ip_; + std::uint16_t xmlrpc_port_; + std::uint16_t pcic_port_; + std::string password_; + std::uint16_t schema_mask_; + int timeout_millis_; + double timeout_tolerance_secs_; + bool assume_sw_triggered_; + int soft_on_timeout_millis_; + double soft_on_timeout_tolerance_secs_; + int soft_off_timeout_millis_; + double soft_off_timeout_tolerance_secs_; + float frame_latency_thresh_; + + std::string frame_id_; + std::string optical_frame_id_; + + ifm3d::CameraBase::Ptr cam_; + ifm3d::FrameGrabber::Ptr fg_; + ifm3d::ImageBuffer::Ptr im_; + std::mutex mutex_; + + ros::NodeHandle np_; + std::unique_ptr it_; + + // + // Topics we publish + // + ros::Publisher cloud_pub_; + ros::Publisher uvec_pub_; + ros::Publisher extrinsics_pub_; + image_transport::Publisher distance_pub_; + // image_transport::Publisher distance_noise_pub_; + image_transport::Publisher amplitude_pub_; + image_transport::Publisher raw_amplitude_pub_; + image_transport::Publisher conf_pub_; + image_transport::Publisher good_bad_pub_; + image_transport::Publisher xyz_image_pub_; + image_transport::Publisher gray_image_pub_; + image_transport::Publisher rgb_image_pub_; + + // + // Services we advertise + // + ros::ServiceServer dump_srv_; + ros::ServiceServer config_srv_; + ros::ServiceServer trigger_srv_; + ros::ServiceServer soft_off_srv_; + ros::ServiceServer soft_on_srv_; + + // + // We use a ROS one-shot timer to kick off our publishing loop. + // + ros::Timer publoop_timer_; + +}; // end: class CameraNodelet + +} // namespace ifm3d_ros + +#endif // __IFM3D_ROS_CAMERA_NODELET_H__ diff --git a/ifm3d_ros_driver/launch/camera.launch b/ifm3d_ros_driver/launch/camera.launch new file mode 100644 index 0000000..a64cff0 --- /dev/null +++ b/ifm3d_ros_driver/launch/camera.launch @@ -0,0 +1,31 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/launch/nodelet.launch b/ifm3d_ros_driver/launch/nodelet.launch similarity index 65% rename from launch/nodelet.launch rename to ifm3d_ros_driver/launch/nodelet.launch index 646f23a..c48f03f 100644 --- a/launch/nodelet.launch +++ b/ifm3d_ros_driver/launch/nodelet.launch @@ -3,15 +3,15 @@ - - - - - - - - - + + + + + + + + + diff --git a/nodelets.xml b/ifm3d_ros_driver/nodelets.xml similarity index 100% rename from nodelets.xml rename to ifm3d_ros_driver/nodelets.xml diff --git a/package.xml b/ifm3d_ros_driver/package.xml similarity index 54% rename from package.xml rename to ifm3d_ros_driver/package.xml index 5a01f46..f2e8d8e 100644 --- a/package.xml +++ b/ifm3d_ros_driver/package.xml @@ -1,20 +1,18 @@ - ifm3d - 0.6.2 - ifm pmd-based 3D ToF Camera ROS package - Sean Kelly + ifm3d_ros_driver + 0.7.0 + ifm 3D ToF Camera ROS main driver package + ifm CSR group Apache 2 - Tom Panzarella - - https://github.com/lovepark/ifm3d-ros + CSR ifm sytron + https://github.com/ifm/ifm3d-ros/ catkin rostest - ifm3d_core rospy image_transport pcl_ros @@ -23,8 +21,8 @@ roscpp sensor_msgs std_msgs - tf - message_generation + ifm3d_ros_msgs + diff --git a/pylib/ifm3d/_ConfigClient.py b/ifm3d_ros_driver/pylib/ifm3d/_ConfigClient.py similarity index 52% rename from pylib/ifm3d/_ConfigClient.py rename to ifm3d_ros_driver/pylib/ifm3d/_ConfigClient.py index 807d15b..f4cf455 100644 --- a/pylib/ifm3d/_ConfigClient.py +++ b/ifm3d_ros_driver/pylib/ifm3d/_ConfigClient.py @@ -1,18 +1,6 @@ -# -# Copyright (C) 2018 ifm electronic, gmbh -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distribted on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# +# SPDX-License-Identifier: Apache-2.0 +# Copyright (C) 2021 ifm electronic, gmbh + """ Mimics (mostly) the `ifm3d config` command but communicates through the ROS graph diff --git a/pylib/ifm3d/_DumpClient.py b/ifm3d_ros_driver/pylib/ifm3d/_DumpClient.py similarity index 59% rename from pylib/ifm3d/_DumpClient.py rename to ifm3d_ros_driver/pylib/ifm3d/_DumpClient.py index c8ed2f5..b16941a 100644 --- a/pylib/ifm3d/_DumpClient.py +++ b/ifm3d_ros_driver/pylib/ifm3d/_DumpClient.py @@ -1,18 +1,6 @@ -# -# Copyright (C) 2018 ifm electronic, gmbh -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distribted on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# +# SPDX-License-Identifier: Apache-2.0 +# Copyright (C) 2021 ifm electronic, gmbh + """ Mimics the `ifm3d dump` command but communicates through the ROS graph """ diff --git a/ifm3d_ros_driver/pylib/ifm3d/__init__.py b/ifm3d_ros_driver/pylib/ifm3d/__init__.py new file mode 100644 index 0000000..c928a3e --- /dev/null +++ b/ifm3d_ros_driver/pylib/ifm3d/__init__.py @@ -0,0 +1,5 @@ +# SPDX-License-Identifier: Apache-2.0 +# Copyright (C) 2021 ifm electronic, gmbh + +from ._DumpClient import DumpClient +from ._ConfigClient import ConfigClient diff --git a/ifm3d_ros_driver/pylib/ifm3d/__pycache__/_ConfigClient.cpython-38.pyc b/ifm3d_ros_driver/pylib/ifm3d/__pycache__/_ConfigClient.cpython-38.pyc new file mode 100644 index 0000000000000000000000000000000000000000..5630c5070252046801c534f7d1bc8a4c49d4c51f GIT binary patch literal 1114 zcmY*YOK%e~5VpOKY_>@#DpW{t$OVZ#Kn{otLa3-jh(lAc7#$_=|$0xAoc~r3OX(f$a6=@vFL_jPrtMSC#IoKciV;;>W z{%>dx4Fas(U6Wv}&#-nD4|*nXFOKqrN4?q|*WOzV*lV0mz(^3_Lp8Qb1lTNQ!)`MN z`gc{U&as=NNg-o=n*?dw0@(!-9Z(Wo0aMo)I6-ii48kqb4Xt6)*yIR^a(F3bbJa|X zRMMhk2|%$$l8t^K-hf1Z`@Kn-Cp`$OM8bRHR01M-mKHbg1dng5**r^6Z*02W>I*2~ zQEE!iE#0CWVZEZNrQ6$afIk!`dBmh>0k$<{B~kZGQjmE@Y$MW@es z$zOM$itckz!98V9MOi32DPJy@ZgvZ-tG0( zhPDnr?)CSN4pnPd`#stU#pWHtA#e~l`e_Q7QA(9hXn2N9YAk9d~(68Ne?DJx@2`GyYDUfu=;IzzJ#p)qOZwhy5L=J@{OtGP_xt(HtF5h^z&QK&=kjAj$UnH*95HMj z!*owTNKz0|rfJGn@}ti8de`cz^a?$#>1Ojj;^m72KC|U=o_~Ux z$o`my_z8s1a0lb@>h`2hI;qM=*>Zx$YHj-}8G6EW--1vC0FgDA_XNO1GKMvl2^5@$ z95d|JTD88S;QnQx4y2J?m~I<{Cl^4>B?SryM6&(jR$qxgc%tevj9Eymam&*%)UEcS zHBuo2r|Rk7#10_M=iSNNG-?8Fol|x)(;l$+W8Gc@bGEwHmZ!Boy4JP zowvyD;U{dsG5bt^Sh0tE9EG7X){A3x>O!hp2~QGork~(Xg}x5 zT4Nvb?;ZaUM83MeJ6F~5M(^F{wV63SHJ0Pm&| z;N_oU|JS{z;Rb4lzwJGJ@#-*)4%YTRtoiHIBHtl(zVw|7$z!?mG~KZqpG> zX-;=2Bk*12QARV$uGm!?ueLWD0K)di2{uX#e~J(x7ost;t5F{b@un;5wZ#r0vE?YR zIW`0qV6ka-U^-+hV_DRnjPo!MLYhhldl%i%YVUz4hW&5xz}dGwQ5IX&-U1O)bF@&E f?-OiX)8E>I%^s~w`~|c1e_b3SzKo7oOk?&R46iz? literal 0 HcmV?d00001 diff --git a/setup.py b/ifm3d_ros_driver/setup.py similarity index 100% rename from setup.py rename to ifm3d_ros_driver/setup.py diff --git a/ifm3d_ros_driver/src/camera_nodelet.cpp b/ifm3d_ros_driver/src/camera_nodelet.cpp new file mode 100644 index 0000000..a7bc321 --- /dev/null +++ b/ifm3d_ros_driver/src/camera_nodelet.cpp @@ -0,0 +1,628 @@ +/* + * SPDX-License-Identifier: Apache-2.0 + * Copyright (C) 2021 ifm electronic, gmbh + */ + +#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 +#include +#include +#include + +#include + +using json = nlohmann::json; +namespace enc = sensor_msgs::image_encodings; + +void ifm3d_ros::CameraNodelet::onInit() +{ + std::string nn = this->getName(); + NODELET_DEBUG_STREAM("onInit(): " << nn); + + this->np_ = getMTPrivateNodeHandle(); + this->it_.reset(new image_transport::ImageTransport(this->np_)); + + // + // parse data out of the parameter server + // + // NOTE: AFAIK, there is no way to get an unsigned int type out of the ROS + // parameter server. + // + int schema_mask; + int xmlrpc_port; + int pcic_port; + std::string frame_id_base; + + if ((nn.size() > 0) && (nn.at(0) == '/')) + { + frame_id_base = nn.substr(1); + } + else + { + frame_id_base = nn; + } + + this->np_.param("ip", this->camera_ip_, ifm3d::DEFAULT_IP); + NODELET_INFO("IP default: %s, current %s", ifm3d::DEFAULT_IP.c_str(), this->camera_ip_.c_str()); + + this->np_.param("xmlrpc_port", xmlrpc_port, (int)ifm3d::DEFAULT_XMLRPC_PORT); + this->np_.param("pcic_port", pcic_port, (int)ifm3d::DEFAULT_PCIC_PORT); + NODELET_INFO("pcic port check: current %d, default %d", pcic_port, ifm3d::DEFAULT_PCIC_PORT); + + this->np_.param("password", this->password_, ifm3d::DEFAULT_PASSWORD); + this->np_.param("schema_mask", schema_mask, (int)ifm3d::DEFAULT_SCHEMA_MASK); + this->np_.param("timeout_millis", this->timeout_millis_, 500); + this->np_.param("timeout_tolerance_secs", this->timeout_tolerance_secs_, 5.0); + this->np_.param("assume_sw_triggered", this->assume_sw_triggered_, false); + this->np_.param("soft_on_timeout_millis", this->soft_on_timeout_millis_, 500); + this->np_.param("soft_on_timeout_tolerance_secs", this->soft_on_timeout_tolerance_secs_, 5.0); + this->np_.param("soft_off_timeout_millis", this->soft_off_timeout_millis_, 500); + this->np_.param("soft_off_timeout_tolerance_secs", this->soft_off_timeout_tolerance_secs_, 600.0); + this->np_.param("frame_latency_thresh", this->frame_latency_thresh_, 60.0f); + this->np_.param("frame_id_base", frame_id_base, frame_id_base); + + this->xmlrpc_port_ = static_cast(xmlrpc_port); + this->schema_mask_ = static_cast(schema_mask); + this->pcic_port_ = static_cast(pcic_port); + + NODELET_DEBUG_STREAM("setup ros node parameters finished"); + + this->frame_id_ = frame_id_base + "_link"; + this->optical_frame_id_ = frame_id_base + "_optical_link"; + + //------------------- + // Published topics + //------------------- + this->cloud_pub_ = this->np_.advertise>("cloud", 1); + this->distance_pub_ = this->it_->advertise("distance", 1); + // this->distance_noise_pub_ = this->it_->advertise("distance_noise", 1); + this->amplitude_pub_ = this->it_->advertise("amplitude", 1); + this->raw_amplitude_pub_ = this->it_->advertise("raw_amplitude", 1); + this->conf_pub_ = this->it_->advertise("confidence", 1); + this->good_bad_pub_ = this->it_->advertise("good_bad_pixels", 1); + this->xyz_image_pub_ = this->it_->advertise("xyz_image", 1); + this->gray_image_pub_ = this->it_->advertise("gray_image", 1); + this->rgb_image_pub_ = this->it_->advertise("rgb_image", 1); + + // we latch the unit vectors + this->uvec_pub_ = this->np_.advertise("unit_vectors", 1, true); + + this->extrinsics_pub_ = this->np_.advertise("extrinsics", 1); + NODELET_DEBUG_STREAM("after advertising the publishers"); + //--------------------- + // Advertised Services + //--------------------- + this->dump_srv_ = this->np_.advertiseService( + "Dump", std::bind(&CameraNodelet::Dump, this, std::placeholders::_1, std::placeholders::_2)); + + this->config_srv_ = this->np_.advertiseService( + "Config", std::bind(&CameraNodelet::Config, this, std::placeholders::_1, std::placeholders::_2)); + + this->trigger_srv_ = this->np_.advertiseService( + "Trigger", std::bind(&CameraNodelet::Trigger, this, std::placeholders::_1, std::placeholders::_2)); + + this->soft_off_srv_ = this->np_.advertiseService( + "SoftOff", std::bind(&CameraNodelet::SoftOff, this, std::placeholders::_1, std::placeholders::_2)); + + this->soft_on_srv_ = this->np_.advertiseService( + "SoftOn", std::bind(&CameraNodelet::SoftOn, this, std::placeholders::_1, std::placeholders::_2)); + + NODELET_DEBUG_STREAM("after advertise service"); + //---------------------------------- + // Fire off our main publishing loop + //---------------------------------- + this->publoop_timer_ = this->np_.createTimer( + ros::Duration(.001), [this](const ros::TimerEvent& t) { this->Run(); }, + true); // oneshot timer +} + +bool ifm3d_ros::CameraNodelet::Dump(ifm3d_ros_msgs::Dump::Request& req, ifm3d_ros_msgs::Dump::Response& res) +{ + std::lock_guard lock(this->mutex_); + res.status = 0; + + try + { + json j = this->cam_->ToJSON(); + res.config = j.dump(); + } + catch (const ifm3d::error_t& ex) + { + res.status = ex.code(); + NODELET_WARN_STREAM(ex.what()); + } + catch (const std::exception& std_ex) + { + res.status = -1; + NODELET_WARN_STREAM(std_ex.what()); + } + catch (...) + { + res.status = -2; + } + + if (res.status != 0) + { + NODELET_WARN_STREAM("Dump: " << res.status); + } + + return true; +} + +bool ifm3d_ros::CameraNodelet::Config(ifm3d_ros_msgs::Config::Request& req, ifm3d_ros_msgs::Config::Response& res) +{ + std::lock_guard lock(this->mutex_); + res.status = 0; + res.msg = "OK"; + + try + { + this->cam_->FromJSON(req.json); + } + catch (const ifm3d::error_t& ex) + { + res.status = ex.code(); + res.msg = ex.what(); + } + catch (const std::exception& std_ex) + { + res.status = -1; + res.msg = std_ex.what(); + } + catch (...) + { + res.status = -2; + res.msg = "Unknown error in `Config'"; + } + + if (res.status != 0) + { + NODELET_WARN_STREAM("Config: " << res.status << " - " << res.msg); + } + + return true; +} + +bool ifm3d_ros::CameraNodelet::Trigger(ifm3d_ros_msgs::Trigger::Request& req, ifm3d_ros_msgs::Trigger::Response& res) +{ + std::lock_guard lock(this->mutex_); + res.status = 0; + res.msg = "Software trigger is currently not implemented"; + + try + { + this->fg_->SWTrigger(); + } + catch (const ifm3d::error_t& ex) + { + res.status = ex.code(); + } + + NODELET_WARN_STREAM("Triggering a camera head is currently not implemented - will follow"); + return true; +} + +// this is a dummy method for the moment: the idea of applications is not supported for the O3RCamera +// we keep this in to possibly keep it comparable / interoperable with the ROS wrappers for other ifm cameras +bool ifm3d_ros::CameraNodelet::SoftOff(ifm3d_ros_msgs::SoftOff::Request& req, ifm3d_ros_msgs::SoftOff::Response& res) +{ + std::lock_guard lock(this->mutex_); + res.status = 0; + + int port_arg = -1; + + try + { + port_arg = static_cast(this->pcic_port_) % 50010; + + // Configure the device from a json string + this->cam_->FromJSONStr("{\"ports\":{\"port" + std::to_string(port_arg) + "\": {\"state\": \"IDLE\"}}}"); + + this->assume_sw_triggered_ = false; + this->timeout_millis_ = this->soft_on_timeout_millis_; + this->timeout_tolerance_secs_ = this->soft_on_timeout_tolerance_secs_; + } + catch (const ifm3d::error_t& ex) + { + res.status = ex.code(); + res.msg = ex.what(); + return false; + } + + NODELET_WARN_STREAM("The concept of applications is not available for the O3R - we use IDLE and RUN states instead"); + res.msg = "{\"ports\":{\"port" + std::to_string(port_arg) + "\": {\"state\": \"IDLE\"}}}"; + + return true; +} + +// this is a dummy method for the moment: the idea of applications is not supported for the O3RCamera +// we keep this in to possibly keep it comparable / interoperable with the ROS wrappers for other ifm cameras +bool ifm3d_ros::CameraNodelet::SoftOn(ifm3d_ros_msgs::SoftOn::Request& req, ifm3d_ros_msgs::SoftOn::Response& res) +{ + std::lock_guard lock(this->mutex_); + res.status = 0; + int port_arg = -1; + + try + { + port_arg = static_cast(this->pcic_port_) % 50010; + + // try getting a current configuration as an ifm3d dump + // this way a a-priori test before setting the state can be tested + // try + // { + // json j = this->cam_->ToJSON(); + // } + // catch (const ifm3d::error_t& ex) + // { + // NODELET_WARN_STREAM(ex.code()); + // NODELET_WARN_STREAM(ex.what()); + // } + // catch (const std::exception& std_ex) + // { + // NODELET_WARN_STREAM(std_ex.what()); + // } + + // Configure the device from a json string + this->cam_->FromJSONStr("{\"ports\":{\"port" + std::to_string(port_arg) + "\": {\"state\": \"RUN\"}}}"); + + this->assume_sw_triggered_ = false; + this->timeout_millis_ = this->soft_on_timeout_millis_; + this->timeout_tolerance_secs_ = this->soft_on_timeout_tolerance_secs_; + } + catch (const ifm3d::error_t& ex) + { + res.status = ex.code(); + res.msg = ex.what(); + return false; + } + + NODELET_WARN_STREAM("The concept of applications is not available for the O3R - we use IDLE and RUN states instead"); + res.msg = "{\"ports\":{\"port" + std::to_string(port_arg) + "\": {\"state\": \"RUN\"}}}"; + + return true; +} + +bool ifm3d_ros::CameraNodelet::InitStructures(std::uint16_t mask, std::uint16_t pcic_port) +{ + std::lock_guard lock(this->mutex_); + bool retval = false; + + try + { + NODELET_INFO_STREAM("Running dtors..."); + this->im_.reset(); + this->fg_.reset(); + this->cam_.reset(); + + NODELET_INFO_STREAM("Initializing camera..."); + this->cam_ = ifm3d::CameraBase::MakeShared(); + // this->cam_ = ifm3d::CameraBase::MakeShared(this->camera_ip_, this->xmlrpc_port_); + // this->cam_ = std::make_shared(this->camera_ip_, this->xmlrpc_port_); + ros::Duration(1.0).sleep(); + + NODELET_INFO_STREAM("Initializing framegrabber..."); + this->fg_ = std::make_shared(this->cam_, mask, this->pcic_port_); + NODELET_INFO("Nodelet arguments: %d, %d", (int)mask, (int)this->pcic_port_); + + NODELET_INFO_STREAM("Initializing image buffer..."); + this->im_ = std::make_shared(); + + retval = true; + } + catch (const ifm3d::error_t& ex) + { + NODELET_WARN_STREAM(ex.code() << ": " << ex.what()); + this->im_.reset(); + this->fg_.reset(); + this->cam_.reset(); + retval = false; + } + + return retval; +} + +// this is the helper function for retrieving complete pcic frames +bool ifm3d_ros::CameraNodelet::AcquireFrame() +{ + std::lock_guard lock(this->mutex_); + bool retval = false; + NODELET_DEBUG_STREAM("try receiving data via fg WaitForFrame"); + try + { + retval = this->fg_->WaitForFrame(this->im_.get(), this->timeout_millis_); + } + catch (const ifm3d::error_t& ex) + { + NODELET_WARN_STREAM(ex.code() << ": " << ex.what()); + retval = false; + } + + return retval; +} + +void ifm3d_ros::CameraNodelet::Run() +{ + std::unique_lock lock(this->mutex_, std::defer_lock); + + NODELET_DEBUG_STREAM("in Run"); + + // We need to account for the case of when the nodelet is being started prior + // to the camera being plugged in. + + while (ros::ok() && (!this->InitStructures(ifm3d::IMG_UVEC, this->pcic_port_))) + { + NODELET_WARN_STREAM("Could not initialize pixel stream!"); + ros::Duration(1.0).sleep(); + } + + pcl::PointCloud::Ptr cloud(new pcl::PointCloud()); + + cv::Mat confidence_img; + cv::Mat distance_img; + // cv::Mat distance_noise_img; + cv::Mat amplitude_img; + cv::Mat xyz_img; + cv::Mat raw_amplitude_img; + cv::Mat good_bad_pixels_img; + cv::Mat gray_img; + cv::Mat rgb_img; + + NODELET_DEBUG_STREAM("after initializing the opencv buffers"); + std::vector extrinsics(6); + + // XXX: need to implement a nice strategy for getting the actual times + // from the camera which are registered to the frame data in the image + // buffer. + ros::Time last_frame = ros::Time::now(); + bool got_uvec = false; + + while (ros::ok()) + { + if (!this->AcquireFrame()) + { + if (!this->assume_sw_triggered_) + { + NODELET_WARN_STREAM("Timeout waiting for camera!"); + } + else + { + ros::Duration(.001).sleep(); + } + + if ((ros::Time::now() - last_frame).toSec() > this->timeout_tolerance_secs_) + { + NODELET_WARN_STREAM("Attempting to restart framegrabber..."); + while (!this->InitStructures(got_uvec ? this->schema_mask_ : ifm3d::IMG_UVEC, this->pcic_port_)) + { + NODELET_WARN_STREAM("Could not re-initialize pixel stream!"); + ros::Duration(1.0).sleep(); + } + + last_frame = ros::Time::now(); + } + + continue; + } + + last_frame = ros::Time::now(); + + NODELET_DEBUG_STREAM("prepare header"); + std_msgs::Header head = std_msgs::Header(); + head.frame_id = this->frame_id_; + head.stamp = ros::Time(std::chrono::duration_cast>>( + this->im_->TimeStamp().time_since_epoch()) + .count()); + if ((ros::Time::now() - head.stamp) > ros::Duration(this->frame_latency_thresh_)) + { + NODELET_INFO_ONCE("Camera's time and client's time are not synced"); + head.stamp = ros::Time::now(); + } + NODELET_DEBUG_STREAM("in header, before setting header to msgs"); + std_msgs::Header optical_head = std_msgs::Header(); + optical_head.stamp = head.stamp; + optical_head.frame_id = this->optical_frame_id_; + + // currently the unit vector calculation seems to be missing in the ifm3d state: therefore we don't publish anything + // to the uvec pubisher publish unit vectors once on a latched topic, then re-initialize the framegrabber with the + // user's requested schema mask + if (!got_uvec) + { + lock.lock(); + sensor_msgs::ImagePtr uvec_msg = + cv_bridge::CvImage(optical_head, enc::TYPE_32FC3, this->im_->UnitVectors()).toImageMsg(); + NODELET_INFO_STREAM("uvec image size: " << this->im_->UnitVectors().size()); + lock.unlock(); + this->uvec_pub_.publish(uvec_msg); + got_uvec = true; + NODELET_INFO("Got unit vectors, restarting framegrabber with mask: %d", (int)this->schema_mask_); + + while (!this->InitStructures(this->schema_mask_, this->pcic_port_)) + { + NODELET_WARN("Could not re-initialize pixel stream!"); + ros::Duration(1.0).sleep(); + } + + NODELET_INFO_STREAM("Start streaming data"); + continue; + } + + // + // Pull out all the wrapped images so that we can release the "GIL" + // while publishing + // + lock.lock(); + + NODELET_DEBUG_STREAM("start getting data"); + try + { + // boost::shared_ptr vs std::shared_ptr forces this copy + pcl::copyPointCloud(*(this->im_->Cloud().get()), *cloud); + xyz_img = this->im_->XYZImage(); + confidence_img = this->im_->ConfidenceImage(); + distance_img = this->im_->DistanceImage(); + amplitude_img = this->im_->AmplitudeImage(); + raw_amplitude_img = this->im_->RawAmplitudeImage(); + gray_img = this->im_->GrayImage(); + extrinsics = this->im_->Extrinsics(); + rgb_img = this->im_->JPEGImage(); + } + catch (const ifm3d::error_t& ex) + { + NODELET_WARN_STREAM(ex.what()); + } + catch (const std::exception& std_ex) + { + NODELET_WARN_STREAM(std_ex.what()); + } + NODELET_DEBUG_STREAM("finished getting data"); + + lock.unlock(); + + // + // Now, do the publishing + // + + NODELET_DEBUG_STREAM("start publishing"); + // Confidence image is invariant - no need to check the mask + sensor_msgs::ImagePtr confidence_msg = cv_bridge::CvImage(optical_head, "mono16", confidence_img).toImageMsg(); + this->conf_pub_.publish(confidence_msg); + NODELET_DEBUG_STREAM("after publishing confidence image"); + + if ((this->schema_mask_ & ifm3d::IMG_CART) == ifm3d::IMG_CART) + { + cloud->header = pcl_conversions::toPCL(head); + this->cloud_pub_.publish(cloud); + + sensor_msgs::ImagePtr xyz_image_msg = + cv_bridge::CvImage(head, xyz_img.type() == CV_32FC3 ? enc::TYPE_32FC3 : enc::TYPE_16SC3, xyz_img) + .toImageMsg(); + this->xyz_image_pub_.publish(xyz_image_msg); + NODELET_DEBUG_STREAM("after publishing xyz image"); + } + + if ((this->schema_mask_ & ifm3d::IMG_RDIS) == ifm3d::IMG_RDIS) + { + sensor_msgs::ImagePtr distance_msg = + cv_bridge::CvImage(optical_head, distance_img.type() == CV_32FC1 ? enc::TYPE_32FC1 : enc::TYPE_16UC1, + distance_img) + .toImageMsg(); + this->distance_pub_.publish(distance_msg); + NODELET_DEBUG_STREAM("after publishing distance image"); + } + + // this image is currently not available via the ifm3d + // if ((this->schema_mask_ & ifm3d::IMG_DIS_NOISE) == ifm3d::IMG_DIS_NOISE) + // { + // sensor_msgs::ImagePtr distance_noise_msg = + // cv_bridge::CvImage(optical_head, + // distance_noise_img.type() == CV_32FC1 ? + // enc::TYPE_32FC1 : enc::TYPE_16UC1, + // distance_noise_img).toImageMsg(); + // this->distance_noise_pub_.publish(distance_noise_msg); + // } + + if ((this->schema_mask_ & ifm3d::IMG_AMP) == ifm3d::IMG_AMP) + { + sensor_msgs::ImagePtr amplitude_msg = + cv_bridge::CvImage(optical_head, amplitude_img.type() == CV_32FC1 ? enc::TYPE_32FC1 : enc::TYPE_16UC1, + amplitude_img) + .toImageMsg(); + this->amplitude_pub_.publish(amplitude_msg); + NODELET_DEBUG_STREAM("after publishing amplitude image"); + } + + if ((this->schema_mask_ & ifm3d::IMG_RAMP) == ifm3d::IMG_RAMP) + { + sensor_msgs::ImagePtr raw_amplitude_msg = + cv_bridge::CvImage(optical_head, raw_amplitude_img.type() == CV_32FC1 ? enc::TYPE_32FC1 : enc::TYPE_16UC1, + raw_amplitude_img) + .toImageMsg(); + this->raw_amplitude_pub_.publish(raw_amplitude_msg); + NODELET_DEBUG_STREAM("Raw amplitude image publisher is a dummy publisher - data will be added soon"); + NODELET_DEBUG_STREAM("after publishing raw amplitude image"); + } + + if ((this->schema_mask_ & ifm3d::IMG_GRAY) == ifm3d::IMG_GRAY) + { + sensor_msgs::ImagePtr gray_image_msg = + cv_bridge::CvImage(optical_head, gray_img.type() == CV_32FC1 ? enc::TYPE_32FC1 : enc::TYPE_16UC1, gray_img) + .toImageMsg(); + this->gray_image_pub_.publish(gray_image_msg); + NODELET_DEBUG_STREAM("Gray image publisher is a dummy publisher - data will be added soon"); + NODELET_DEBUG_STREAM("after publishing gray image"); + } + + // TODO: this casting of the confidence image to a boolean value image needs to be tested: + // inv cast might be reqiured depending on the interpretation of the binary image + + int const min_binary_value = 0; + int const max_binary_value = 100; + cv::threshold(confidence_img, good_bad_pixels_img, min_binary_value, max_binary_value, cv::THRESH_BINARY); + good_bad_pixels_img.convertTo(good_bad_pixels_img, CV_8U); + + sensor_msgs::ImagePtr good_bad_msg = cv_bridge::CvImage(optical_head, "mono8", good_bad_pixels_img).toImageMsg(); + this->good_bad_pub_.publish(good_bad_msg); + NODELET_DEBUG_STREAM("after publishing good/bad pixel image image"); + + // The 2D is not yet settable in the schema mask: publish all the time + + if (!rgb_img.empty()) + { + cv::Mat im_decode = cv::imdecode(rgb_img, cv::IMREAD_UNCHANGED); + sensor_msgs::ImagePtr rgb_image_msg = cv_bridge::CvImage(optical_head, "bgr8", im_decode).toImageMsg(); + this->rgb_image_pub_.publish(rgb_image_msg); + NODELET_DEBUG_STREAM("after publishing rgb image"); + } + + // + // publish extrinsics + // + NODELET_DEBUG_STREAM("start publishing extrinsics"); + ifm3d_ros_msgs::Extrinsics extrinsics_msg; + extrinsics_msg.header = optical_head; + try + { + extrinsics_msg.tx = extrinsics.at(0); + extrinsics_msg.ty = extrinsics.at(1); + extrinsics_msg.tz = extrinsics.at(2); + extrinsics_msg.rot_x = extrinsics.at(3); + extrinsics_msg.rot_y = extrinsics.at(4); + extrinsics_msg.rot_z = extrinsics.at(5); + } + catch (const std::out_of_range& ex) + { + NODELET_WARN("out-of-range error fetching extrinsics"); + } + this->extrinsics_pub_.publish(extrinsics_msg); + + } // end: while (ros::ok()) { ... } +} // end: Run() + +PLUGINLIB_EXPORT_CLASS(ifm3d_ros::CameraNodelet, nodelet::Nodelet) diff --git a/ifm3d_ros_driver/test/gradient.jpg b/ifm3d_ros_driver/test/gradient.jpg new file mode 100644 index 0000000000000000000000000000000000000000..e2d788b633a7ea0e3fe6450e3d191f13ccb3067e GIT binary patch literal 1363 zcmeH`K}_0E7{^~*XrWpGL55(kxS}{1nUjc1x(udsbjBEW8aER-NaEb$smm@9)R{#V zEQtpX#uzTUO%6*;c0jif$u5Qyn`Xg`-FE19*l7vtdrgX-mfiQ-{L*}V?|uL8egD_0 zw;I6wU`m(*7zO~QJfL+7R)CSD3>4X8pbRu^)H94;ufW78pSB*my~kp;I{JL9!|8Qd zt)3B&ci0~c2Cwvwj*kYyzUx6hM$@#irb~JKz1Cj;KaW-!SPbAbc8$OW0B*qu3)cDo z9Ewb3fc7ACxPems*v*&Y$_yN?uw9ys*1@Rd;vQ=BGw38RB^6--cYyqR=~1O=^ll1C z<6yp8?0{f~(n5ow($R(qf%fpeH1AuH_pnJfMy2Oq)D~@+MdDCHw0I*$RFe!Nzr$YHx~PD=RP{lG8|0H)p|pjBt%g*^4P8>?|gD- z)l8vE+Vb&r9yb9|!$N3{VV?zFPP1_Y?v=oP8LNzSxhvl`mLd{NE2TQOBPEEMsM`T2 znml>WdbCcUO3>*e`D#me*cXJ5bArtCTlc*A0D^R%%Rg}?T$CxXTnV!ROe=)eX4p7H zipOWcf+kO#GoDXks1kJgs(jQEH|z_7lksF@?&$&P*p47vm15!CelGiB{~+PYb1*Hp zJu#RMK!kR%p>#--hin8;B^TtQmZ)Zf-eSo7VbKIl*@3`qRykLtUO9YUKikh8cf+*Z zGoC`s4&j^yg|btVr`iZrazQ?7iE1|JEixOMuTjvHdKIyz#C%;$%%6Y%e +``` +Please replace the tag `` with the name of the package you want to compile: ++ `ifm3d_ros_driver` ++ `ifm3d_ros_msgs` ++ `ifm3d_ros_examples` + +Some of our subpackages have dependencies to other packages and therefore will trigger a compiling of more subpackages, namely the packages `ifm3d_ros_examples` and `ifm3d_ros_driver`. These subpackges can not be used standalone. + +Don't forget to switch back to building all packages afterwards: +``` +catkin_make -DCATKIN_WHITELIST_PACKAGES="" +``` + +# LICENSE +Please see the file called [LICENSE](LICENSE). \ No newline at end of file diff --git a/ifm3d_ros_msgs/bin/config b/ifm3d_ros_msgs/bin/config new file mode 100755 index 0000000..ac5c29c --- /dev/null +++ b/ifm3d_ros_msgs/bin/config @@ -0,0 +1,12 @@ +#!/usr/bin/env python +# -*- python -*- + +# SPDX-License-Identifier: Apache-2.0 +# Copyright (C) 2021 ifm electronic, gmbh + + +import sys +from ifm3d import ConfigClient + +if __name__ == '__main__': + sys.exit(ConfigClient().run()) diff --git a/ifm3d_ros_msgs/bin/dump b/ifm3d_ros_msgs/bin/dump new file mode 100755 index 0000000..2fd1789 --- /dev/null +++ b/ifm3d_ros_msgs/bin/dump @@ -0,0 +1,12 @@ +#!/usr/bin/env python +# -*- python -*- + +# SPDX-License-Identifier: Apache-2.0 +# Copyright (C) 2021 ifm electronic, gmbh + + +import sys +from ifm3d import DumpClient + +if __name__ == '__main__': + sys.exit(DumpClient().run()) diff --git a/ifm3d_ros_msgs/msg/Extrinsics.msg b/ifm3d_ros_msgs/msg/Extrinsics.msg new file mode 100644 index 0000000..7fe7168 --- /dev/null +++ b/ifm3d_ros_msgs/msg/Extrinsics.msg @@ -0,0 +1,11 @@ +# +# Extrinsic parameters are SI units: please be aware of scaling between any extrinsic messages returned by older versions of the native C++ API - ifm3d +# Translation uints are NOW m, rotation units are radian +# +std_msgs/Header header +float32 tx +float32 ty +float32 tz +float32 rot_x +float32 rot_y +float32 rot_z diff --git a/ifm3d_ros_msgs/package.xml b/ifm3d_ros_msgs/package.xml new file mode 100644 index 0000000..39f5fce --- /dev/null +++ b/ifm3d_ros_msgs/package.xml @@ -0,0 +1,26 @@ + + + + ifm3d_ros_msgs + 0.1.0 + ifm3d_ros messages subpackage + ifm CSR group + Apache 2 + CSR ifm sytron + https://github.com/ifm/ifm3d-ros/ + + + catkin + message_generation + std_msgs + std_msgs + message_generation + std_msgs + message_runtime + tf2_ros + + + + + + diff --git a/srv/Config.srv b/ifm3d_ros_msgs/srv/Config.srv similarity index 100% rename from srv/Config.srv rename to ifm3d_ros_msgs/srv/Config.srv diff --git a/srv/Dump.srv b/ifm3d_ros_msgs/srv/Dump.srv similarity index 100% rename from srv/Dump.srv rename to ifm3d_ros_msgs/srv/Dump.srv diff --git a/srv/SoftOff.srv b/ifm3d_ros_msgs/srv/SoftOff.srv similarity index 100% rename from srv/SoftOff.srv rename to ifm3d_ros_msgs/srv/SoftOff.srv diff --git a/srv/SoftOn.srv b/ifm3d_ros_msgs/srv/SoftOn.srv similarity index 100% rename from srv/SoftOn.srv rename to ifm3d_ros_msgs/srv/SoftOn.srv diff --git a/srv/SyncClocks.srv b/ifm3d_ros_msgs/srv/SyncClocks.srv similarity index 100% rename from srv/SyncClocks.srv rename to ifm3d_ros_msgs/srv/SyncClocks.srv diff --git a/srv/Trigger.srv b/ifm3d_ros_msgs/srv/Trigger.srv similarity index 62% rename from srv/Trigger.srv rename to ifm3d_ros_msgs/srv/Trigger.srv index a39d323..f8f830e 100644 --- a/srv/Trigger.srv +++ b/ifm3d_ros_msgs/srv/Trigger.srv @@ -1,2 +1,3 @@ --- int32 status +string msg \ No newline at end of file diff --git a/include/ifm3d/camera_nodelet.h b/include/ifm3d/camera_nodelet.h deleted file mode 100644 index 1a224ac..0000000 --- a/include/ifm3d/camera_nodelet.h +++ /dev/null @@ -1,135 +0,0 @@ -// -*- c++ -*- -/* - * Copyright (C) 2018 ifm electronic, gmbh - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distribted on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#ifndef __IFM3D_ROS_CAMERA_NODELET_H__ -#define __IFM3D_ROS_CAMERA_NODELET_H__ - -#include -#include -#include -#include - -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -namespace ifm3d_ros -{ - /** - * This class implements the ROS nodelet interface to allow for running - * in-process data transport between ifm3d image data and ROS consumers. This - * class is used to manage, configure, and acquire data from a single ifm3d - * camera. - */ - class CameraNodelet : public nodelet::Nodelet - { - private: - // - // Nodelet lifecycle functions - // - virtual void onInit() override; - - // - // ROS services - // - bool Dump(ifm3d::Dump::Request& req, ifm3d::Dump::Response& res); - bool Config(ifm3d::Config::Request& req, ifm3d::Config::Response& res); - bool Trigger(ifm3d::Trigger::Request& req, ifm3d::Trigger::Response& res); - bool SoftOff(ifm3d::SoftOff::Request& req, ifm3d::SoftOff::Response& res); - bool SoftOn(ifm3d::SoftOn::Request& req, ifm3d::SoftOn::Response& res); - bool SyncClocks(ifm3d::SyncClocks::Request& req, - ifm3d::SyncClocks::Response& res); - - // - // This is our main publishing loop and its helper functions - // - void Run(); - bool InitStructures(std::uint16_t mask); - bool AcquireFrame(); - - // - // state - // - std::string camera_ip_; - std::uint16_t xmlrpc_port_; - std::string password_; - std::uint16_t schema_mask_; - int timeout_millis_; - double timeout_tolerance_secs_; - bool assume_sw_triggered_; - int soft_on_timeout_millis_; - double soft_on_timeout_tolerance_secs_; - int soft_off_timeout_millis_; - double soft_off_timeout_tolerance_secs_; - float frame_latency_thresh_; - bool sync_clocks_; - - std::string frame_id_; - std::string optical_frame_id_; - - ifm3d::Camera::Ptr cam_; - ifm3d::FrameGrabber::Ptr fg_; - ifm3d::ImageBuffer::Ptr im_; - std::mutex mutex_; - - ros::NodeHandle np_; - std::unique_ptr it_; - - // - // Topics we publish - // - ros::Publisher cloud_pub_; - ros::Publisher uvec_pub_; - ros::Publisher extrinsics_pub_; - image_transport::Publisher distance_pub_; - image_transport::Publisher amplitude_pub_; - image_transport::Publisher raw_amplitude_pub_; - image_transport::Publisher conf_pub_; - image_transport::Publisher good_bad_pub_; - image_transport::Publisher xyz_image_pub_; - - // - // Services we advertise - // - ros::ServiceServer dump_srv_; - ros::ServiceServer config_srv_; - ros::ServiceServer trigger_srv_; - ros::ServiceServer soft_off_srv_; - ros::ServiceServer soft_on_srv_; - ros::ServiceServer sync_clocks_srv_; - - // - // We use a ROS one-shot timer to kick off our publishing loop. - // - ros::Timer publoop_timer_; - - }; // end: class CameraNodelet - -} // end: namespace ifm3d_ros - -#endif // __IFM3D_ROS_CAMERA_NODELET_H__ diff --git a/launch/camera.launch b/launch/camera.launch deleted file mode 100644 index 21f8bf7..0000000 --- a/launch/camera.launch +++ /dev/null @@ -1,31 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/launch/ifm3d.rviz b/launch/ifm3d.rviz deleted file mode 100644 index 4a8d949..0000000 --- a/launch/ifm3d.rviz +++ /dev/null @@ -1,225 +0,0 @@ -Panels: - - Class: rviz/Displays - Help Height: 78 - Name: Displays - Property Tree Widget: - Expanded: ~ - Splitter Ratio: 0.747222245 - Tree Height: 900 - - Class: rviz/Selection - Name: Selection - - Class: rviz/Tool Properties - Expanded: - - /2D Pose Estimate1 - - /2D Nav Goal1 - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.588679016 - - Class: rviz/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 - - Class: rviz/Time - Experimental: false - Name: Time - SyncMode: 0 - SyncSource: "PointCloud2: cloud" -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 0.100000001 - Class: rviz/Grid - Color: 160; 160; 164 - Enabled: false - Line Style: - Line Width: 0.0299999993 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 100 - Reference Frame: - Value: false - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 1761 - Min Color: 0; 0; 0 - Min Intensity: 12 - Name: "PointCloud2: cloud" - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 2 - Size (m): 0.00999999978 - Style: Points - Topic: /ifm3d/camera/cloud - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Class: rviz/Image - Enabled: true - Image Topic: /ifm3d/camera/distance - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: "Image: distance" - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Class: rviz/Image - Enabled: true - Image Topic: /ifm3d/camera/amplitude - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: "Image: amplitude" - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Class: rviz/Image - Enabled: false - Image Topic: /ifm3d/camera/raw_amplitude - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: "Image: raw amplitude" - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: false - - Class: rviz/Image - Enabled: true - Image Topic: /ifm3d/camera/confidence - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: "Image: confidence" - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Class: rviz/Image - Enabled: true - Image Topic: /ifm3d/camera/good_bad_pixels - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: "Image: good vs bad pixels" - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Class: rviz/TF - Enabled: false - Frame Timeout: 15 - Frames: - All Enabled: true - Marker Scale: 1 - Name: TF - Show Arrows: true - Show Axes: true - Show Names: false - Tree: - {} - Update Interval: 0 - Value: false - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Default Light: true - Fixed Frame: ifm3d/camera_link - Frame Rate: 30 - Name: root - Tools: - - Class: rviz/Interact - Hide Inactive Objects: true - - Class: rviz/MoveCamera - - Class: rviz/Select - - Class: rviz/FocusCamera - - Class: rviz/Measure - - Class: rviz/SetInitialPose - Topic: /initialpose - - Class: rviz/SetGoal - Topic: /move_base_simple/goal - - Class: rviz/PublishPoint - Single click: true - Topic: /clicked_point - Value: true - Views: - Current: - Class: rviz/Orbit - Distance: 1.30729866 - Enable Stereo Rendering: - Stereo Eye Separation: 0.0599999987 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: 0.549218595 - Y: -0.0461745411 - Z: 0.0779014677 - Focal Shape Fixed Size: true - Focal Shape Size: 0.0500000007 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.00999999978 - Pitch: 0.0347976089 - Target Frame: - Value: Orbit (rviz) - Yaw: 3.16620064 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - Height: 1211 - Hide Left Dock: false - Hide Right Dock: false - "Image: amplitude": - collapsed: false - "Image: confidence": - collapsed: false - "Image: distance": - collapsed: false - "Image: good vs bad pixels": - collapsed: false - "Image: raw amplitude": - collapsed: false - QMainWindow State: 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 - Selection: - collapsed: false - Time: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: false - Width: 1939 - X: 271 - Y: 72 diff --git a/launch/rviz.launch b/launch/rviz.launch deleted file mode 100644 index f82427a..0000000 --- a/launch/rviz.launch +++ /dev/null @@ -1,12 +0,0 @@ - - - - - - - - - diff --git a/msg/Extrinsics.msg b/msg/Extrinsics.msg deleted file mode 100644 index ca278e2..0000000 --- a/msg/Extrinsics.msg +++ /dev/null @@ -1,10 +0,0 @@ -# -# Translation uints are mm, rotation units are degrees -# -std_msgs/Header header -float32 tx -float32 ty -float32 tz -float32 rot_x -float32 rot_y -float32 rot_z diff --git a/pylib/ifm3d/__init__.py b/pylib/ifm3d/__init__.py deleted file mode 100644 index f31ccf5..0000000 --- a/pylib/ifm3d/__init__.py +++ /dev/null @@ -1,18 +0,0 @@ -# -# Copyright (C) 2018 ifm electronic, gmbh -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distribted on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# - -from ._DumpClient import DumpClient -from ._ConfigClient import ConfigClient diff --git a/src/camera_nodelet.cpp b/src/camera_nodelet.cpp deleted file mode 100644 index 1c1a7d8..0000000 --- a/src/camera_nodelet.cpp +++ /dev/null @@ -1,680 +0,0 @@ -/* - * Copyright (C) 2018 ifm electronic, gmbh - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distribted on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#include - -#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 -#include -#include - -namespace enc = sensor_msgs::image_encodings; - -void -ifm3d_ros::CameraNodelet::onInit() -{ - std::string nn = this->getName(); - NODELET_INFO_STREAM("onInit(): " << nn); - - this->np_ = getMTPrivateNodeHandle(); - this->it_.reset(new image_transport::ImageTransport(this->np_)); - - // - // parse data out of the parameter server - // - // NOTE: AFAIK, there is no way to get an unsigned int type out of the ROS - // parameter server. - // - int schema_mask; - int xmlrpc_port; - std::string frame_id_base; - - if ((nn.size() > 0) && (nn.at(0) == '/')) - { - frame_id_base = nn.substr(1); - } - else - { - frame_id_base = nn; - } - - this->np_.param("ip", this->camera_ip_, ifm3d::DEFAULT_IP); - this->np_.param("xmlrpc_port", xmlrpc_port, (int) ifm3d::DEFAULT_XMLRPC_PORT); - this->np_.param("password", this->password_, ifm3d::DEFAULT_PASSWORD); - this->np_.param("schema_mask", schema_mask, (int) ifm3d::DEFAULT_SCHEMA_MASK); - this->np_.param("timeout_millis", this->timeout_millis_, 500); - this->np_.param("timeout_tolerance_secs", this->timeout_tolerance_secs_, 5.0); - this->np_.param("assume_sw_triggered", this->assume_sw_triggered_, false); - this->np_.param("soft_on_timeout_millis", this->soft_on_timeout_millis_, 500); - this->np_.param("soft_on_timeout_tolerance_secs", - this->soft_on_timeout_tolerance_secs_, 5.0); - this->np_.param("soft_off_timeout_millis", - this->soft_off_timeout_millis_, 500); - this->np_.param("soft_off_timeout_tolerance_secs", - this->soft_off_timeout_tolerance_secs_, 600.0); - this->np_.param("sync_clocks", this->sync_clocks_, false); - this->np_.param("frame_latency_thresh", this->frame_latency_thresh_, 60.0f); - this->np_.param("frame_id_base", frame_id_base, frame_id_base); - - this->xmlrpc_port_ = static_cast(xmlrpc_port); - this->schema_mask_ = static_cast(schema_mask); - - this->frame_id_ = frame_id_base + "_link"; - this->optical_frame_id_ = frame_id_base + "_optical_link"; - - //------------------- - // Published topics - //------------------- - this->cloud_pub_ = - this->np_.advertise >("cloud", 1); - this->distance_pub_ = this->it_->advertise("distance", 1); - this->amplitude_pub_ = this->it_->advertise("amplitude", 1); - this->raw_amplitude_pub_ = this->it_->advertise("raw_amplitude", 1); - this->conf_pub_ = this->it_->advertise("confidence", 1); - this->good_bad_pub_ = this->it_->advertise("good_bad_pixels", 1); - this->xyz_image_pub_ = this->it_->advertise("xyz_image", 1); - - // we latch the unit vectors - this->uvec_pub_ = - this->np_.advertise("unit_vectors", 1, true); - - this->extrinsics_pub_ = - this->np_.advertise("extrinsics", 1); - - //--------------------- - // Advertised Services - //--------------------- - this->dump_srv_ = - this->np_.advertiseService - ("Dump", std::bind(&CameraNodelet::Dump, this, - std::placeholders::_1, - std::placeholders::_2)); - - this->config_srv_ = - this->np_.advertiseService - ("Config", std::bind(&CameraNodelet::Config, this, - std::placeholders::_1, - std::placeholders::_2)); - - this->trigger_srv_ = - this->np_.advertiseService - ("Trigger", std::bind(&CameraNodelet::Trigger, this, - std::placeholders::_1, - std::placeholders::_2)); - - this->soft_off_srv_ = - this->np_.advertiseService - ("SoftOff", std::bind(&CameraNodelet::SoftOff, this, - std::placeholders::_1, - std::placeholders::_2)); - - this->soft_on_srv_ = - this->np_.advertiseService - ("SoftOn", std::bind(&CameraNodelet::SoftOn, this, - std::placeholders::_1, - std::placeholders::_2)); - - this->sync_clocks_srv_ = - this->np_.advertiseService - ("SyncClocks", std::bind(&CameraNodelet::SyncClocks, this, - std::placeholders::_1, - std::placeholders::_2)); - - //---------------------------------- - // Fire off our main publishing loop - //---------------------------------- - this->publoop_timer_ = - this->np_.createTimer(ros::Duration(.001), - [this](const ros::TimerEvent& t) - { this->Run(); }, - true); // oneshot timer -} - -bool -ifm3d_ros::CameraNodelet::Dump(ifm3d::Dump::Request& req, - ifm3d::Dump::Response& res) -{ - std::lock_guard lock(this->mutex_); - res.status = 0; - - try - { - res.config = this->cam_->ToJSONStr(); - } - catch (const ifm3d::error_t& ex) - { - res.status = ex.code(); - NODELET_WARN_STREAM(ex.what()); - } - catch (const std::exception& std_ex) - { - res.status = -1; - NODELET_WARN_STREAM(std_ex.what()); - } - catch (...) - { - res.status = -2; - } - - if (res.status != 0) - { - NODELET_WARN_STREAM("Dump: " << res.status); - } - - return true; -} - -bool -ifm3d_ros::CameraNodelet::Config(ifm3d::Config::Request& req, - ifm3d::Config::Response& res) -{ - std::lock_guard lock(this->mutex_); - res.status = 0; - res.msg = "OK"; - - try - { - this->cam_->FromJSONStr(req.json); - } - catch (const ifm3d::error_t& ex) - { - res.status = ex.code(); - res.msg = ex.what(); - } - catch (const std::exception& std_ex) - { - res.status = -1; - res.msg = std_ex.what(); - } - catch (...) - { - res.status = -2; - res.msg = "Unknown error in `Config'"; - } - - if (res.status != 0) - { - NODELET_WARN_STREAM("Config: " << res.status << " - " << res.msg); - } - - return true; -} - -bool -ifm3d_ros::CameraNodelet::Trigger(ifm3d::Trigger::Request& req, - ifm3d::Trigger::Response& res) -{ - std::lock_guard lock(this->mutex_); - res.status = 0; - - try - { - this->fg_->SWTrigger(); - } - catch (const ifm3d::error_t& ex) - { - res.status = ex.code(); - } - - return true; -} - -bool -ifm3d_ros::CameraNodelet::SyncClocks(ifm3d::SyncClocks::Request& req, - ifm3d::SyncClocks::Response& res) -{ - std::lock_guard lock(this->mutex_); - res.status = 0; - res.msg = "OK"; - - NODELET_INFO_STREAM("Syncing camera clock to system..."); - try - { - this->cam_->SetCurrentTime(-1); - } - catch (const ifm3d::error_t& ex) - { - res.status = ex.code(); - res.msg = ex.what(); - NODELET_WARN_STREAM(res.status << ": " << res.msg); - return false; - } - - return true; -} - -bool -ifm3d_ros::CameraNodelet::SoftOff(ifm3d::SoftOff::Request& req, - ifm3d::SoftOff::Response& res) -{ - std::lock_guard lock(this->mutex_); - res.status = 0; - res.msg = "OK"; - - int active_application = 0; - - try - { - active_application = this->cam_->ActiveApplication(); - if (active_application > 0) - { - json dict = - { - {"Apps", - {{{"Index", std::to_string(active_application)}, - {"TriggerMode", - std::to_string( - static_cast(ifm3d::Camera::trigger_mode::SW))}}} - } - }; - - this->cam_->FromJSON(dict); - - this->assume_sw_triggered_ = true; - this->timeout_millis_ = this->soft_off_timeout_millis_; - this->timeout_tolerance_secs_ = - this->soft_off_timeout_tolerance_secs_; - } - } - catch (const ifm3d::error_t& ex) - { - res.status = ex.code(); - res.msg = ex.what(); - return false; - } - - return true; -} - -bool -ifm3d_ros::CameraNodelet::SoftOn(ifm3d::SoftOn::Request& req, - ifm3d::SoftOn::Response& res) -{ - std::lock_guard lock(this->mutex_); - res.status = 0; - res.msg = "OK"; - - int active_application = 0; - - try - { - active_application = this->cam_->ActiveApplication(); - if (active_application > 0) - { - json dict = - { - {"Apps", - {{{"Index", std::to_string(active_application)}, - {"TriggerMode", - std::to_string( - static_cast(ifm3d::Camera::trigger_mode::FREE_RUN))}}} - } - }; - - this->cam_->FromJSON(dict); - - this->assume_sw_triggered_ = false; - this->timeout_millis_ = this->soft_on_timeout_millis_; - this->timeout_tolerance_secs_ = - this->soft_on_timeout_tolerance_secs_; - } - } - catch (const ifm3d::error_t& ex) - { - res.status = ex.code(); - res.msg = ex.what(); - return false; - } - - return true; -} - -bool -ifm3d_ros::CameraNodelet::InitStructures(std::uint16_t mask) -{ - std::lock_guard lock(this->mutex_); - bool retval = false; - - try - { - NODELET_INFO_STREAM("Running dtors..."); - this->im_.reset(); - this->fg_.reset(); - this->cam_.reset(); - - NODELET_INFO_STREAM("Initializing camera..."); - this->cam_ = ifm3d::Camera::MakeShared(this->camera_ip_, - this->xmlrpc_port_, - this->password_); - ros::Duration(1.0).sleep(); - - NODELET_INFO_STREAM("Initializing framegrabber..."); - this->fg_ = std::make_shared(this->cam_, mask); - - NODELET_INFO_STREAM("Initializing image buffer..."); - this->im_ = std::make_shared(); - - retval = true; - } - catch (const ifm3d::error_t& ex) - { - NODELET_WARN_STREAM(ex.code() << ": " << ex.what()); - this->im_.reset(); - this->fg_.reset(); - this->cam_.reset(); - retval = false; - } - - return retval; -} - -bool -ifm3d_ros::CameraNodelet::AcquireFrame() -{ - std::lock_guard lock(this->mutex_); - bool retval = false; - - try - { - retval = this->fg_->WaitForFrame(this->im_.get(), this->timeout_millis_); - } - catch (const ifm3d::error_t& ex) - { - NODELET_WARN_STREAM(ex.code() << ": " << ex.what()); - retval = false; - } - - return retval; -} - -void -ifm3d_ros::CameraNodelet::Run() -{ - std::unique_lock lock(this->mutex_, std::defer_lock); - - // - // Sync camera clock with system clock if necessary - // - if (this->sync_clocks_) - { - NODELET_INFO_STREAM("Syncing camera clock to system..."); - try - { - this->cam_ = ifm3d::Camera::MakeShared(this->camera_ip_, - this->xmlrpc_port_, - this->password_); - this->cam_->SetCurrentTime(-1); - } - catch (const ifm3d::error_t& ex) - { - NODELET_WARN_STREAM("Failed to sync clocks!"); - NODELET_WARN_STREAM(ex.code() << ": " << ex.what()); - } - } - else - { - NODELET_INFO_STREAM("Camera clock will not be sync'd to system clock"); - } - - // - // We need to account for the case of when the nodelet is being started prior - // to the camera being plugged in. - // - while (ros::ok() && (! this->InitStructures(ifm3d::IMG_UVEC))) - { - NODELET_WARN_STREAM("Could not initialize pixel stream!"); - ros::Duration(1.0).sleep(); - } - - pcl::PointCloud::Ptr - cloud(new pcl::PointCloud()); - - cv::Mat confidence_img; - cv::Mat distance_img; - cv::Mat amplitude_img; - cv::Mat xyz_img; - cv::Mat raw_amplitude_img; - cv::Mat good_bad_pixels_img; - - std::vector extrinsics(6); - - // XXX: need to implement a nice strategy for getting the actual times - // from the camera which are registered to the frame data in the image - // buffer. - ros::Time last_frame = ros::Time::now(); - bool got_uvec = false; - - while (ros::ok()) - { - if (! this->AcquireFrame()) - { - if (! this->assume_sw_triggered_) - { - NODELET_WARN_STREAM("Timeout waiting for camera!"); - } - else - { - ros::Duration(.001).sleep(); - } - - if ((ros::Time::now() - last_frame).toSec() > - this->timeout_tolerance_secs_) - { - NODELET_WARN_STREAM("Attempting to restart framegrabber..."); - while (! this->InitStructures(got_uvec - ? this->schema_mask_ - : ifm3d::IMG_UVEC)) - { - NODELET_WARN_STREAM("Could not re-initialize pixel stream!"); - ros::Duration(1.0).sleep(); - } - - last_frame = ros::Time::now(); - } - - continue; - } - - last_frame = ros::Time::now(); - - std_msgs::Header head = std_msgs::Header(); - head.frame_id = this->frame_id_; - head.stamp = ros::Time( - std::chrono::duration_cast>> - (this->im_->TimeStamp().time_since_epoch()).count()); - if ((ros::Time::now() - head.stamp) > - ros::Duration(this->frame_latency_thresh_)) - { - ROS_WARN_ONCE("Camera's time is not up to date, therefore header's " - "timestamps will be the reception time and not capture time. " - "Please update the camera's time if you need the capture time."); - head.stamp = ros::Time::now(); - } - - std_msgs::Header optical_head = std_msgs::Header(); - optical_head.stamp = head.stamp; - optical_head.frame_id = this->optical_frame_id_; - - // publish unit vectors once on a latched topic, then re-initialize the - // framegrabber with the user's requested schema mask - if (! got_uvec) - { - lock.lock(); - sensor_msgs::ImagePtr uvec_msg = - cv_bridge::CvImage(optical_head, - enc::TYPE_32FC3, - this->im_->UnitVectors()).toImageMsg(); - lock.unlock(); - this->uvec_pub_.publish(uvec_msg); - got_uvec = true; - ROS_INFO("Got unit vectors, restarting framegrabber with mask: %d", - (int) this->schema_mask_); - - while (! this->InitStructures(this->schema_mask_)) - { - ROS_WARN("Could not re-initialize pixel stream!"); - ros::Duration(1.0).sleep(); - } - - // should solve the problem of first image being (0,0) - // see: https://github.com/lovepark/ifm3d/issues/12 - continue; - } - - // - // Pull out all the wrapped images so that we can release the "GIL" - // while publishing - // - lock.lock(); - - // boost::shared_ptr vs std::shared_ptr forces this copy - pcl::copyPointCloud(*(this->im_->Cloud().get()), *cloud); - xyz_img = this->im_->XYZImage(); - confidence_img = this->im_->ConfidenceImage(); - distance_img = this->im_->DistanceImage(); - amplitude_img = this->im_->AmplitudeImage(); - raw_amplitude_img = this->im_->RawAmplitudeImage(); - extrinsics = this->im_->Extrinsics(); - - lock.unlock(); - - // - // Now, do the publishing - // - - // Confidence image is invariant - no need to check the mask - sensor_msgs::ImagePtr confidence_msg = - cv_bridge::CvImage(optical_head, - "mono8", - confidence_img).toImageMsg(); - this->conf_pub_.publish(confidence_msg); - - if ((this->schema_mask_ & ifm3d::IMG_CART) == ifm3d::IMG_CART) - { - cloud->header = pcl_conversions::toPCL(head); - this->cloud_pub_.publish(cloud); - - sensor_msgs::ImagePtr xyz_image_msg = - cv_bridge::CvImage(head, - xyz_img.type() == CV_32FC3 ? - enc::TYPE_32FC3 : enc::TYPE_16SC3, - xyz_img).toImageMsg(); - this->xyz_image_pub_.publish(xyz_image_msg); - } - - if ((this->schema_mask_ & ifm3d::IMG_RDIS) == ifm3d::IMG_RDIS) - { - sensor_msgs::ImagePtr distance_msg = - cv_bridge::CvImage(optical_head, - distance_img.type() == CV_32FC1 ? - enc::TYPE_32FC1 : enc::TYPE_16UC1, - distance_img).toImageMsg(); - this->distance_pub_.publish(distance_msg); - } - - if ((this->schema_mask_ & ifm3d::IMG_AMP) == ifm3d::IMG_AMP) - { - sensor_msgs::ImagePtr amplitude_msg = - cv_bridge::CvImage(optical_head, - amplitude_img.type() == CV_32FC1 ? - enc::TYPE_32FC1 : enc::TYPE_16UC1, - amplitude_img).toImageMsg(); - this->amplitude_pub_.publish(amplitude_msg); - } - - if ((this->schema_mask_ & ifm3d::IMG_RAMP) == ifm3d::IMG_RAMP) - { - sensor_msgs::ImagePtr raw_amplitude_msg = - cv_bridge::CvImage(optical_head, - raw_amplitude_img.type() == CV_32FC1 ? - enc::TYPE_32FC1 : enc::TYPE_16UC1, - raw_amplitude_img).toImageMsg(); - this->raw_amplitude_pub_.publish(raw_amplitude_msg); - } - - // - // XXX: Need to publish ambient light / gray image - // ... however, as of now (3/26/2017) there is no - // imager mode on the O3X that actually supports it - // - // Update: as of 5/10/2018 still not supported. - // - - good_bad_pixels_img = cv::Mat::ones(confidence_img.rows, - confidence_img.cols, - CV_8UC1); - cv::bitwise_and(confidence_img, good_bad_pixels_img, - good_bad_pixels_img); - sensor_msgs::ImagePtr good_bad_msg = - cv_bridge::CvImage(optical_head, - "mono8", - (good_bad_pixels_img == 0)).toImageMsg(); - this->good_bad_pub_.publish(good_bad_msg); - - // - // publish extrinsics - // - ifm3d::Extrinsics extrinsics_msg; - extrinsics_msg.header = optical_head; - try - { - extrinsics_msg.tx = extrinsics.at(0); - extrinsics_msg.ty = extrinsics.at(1); - extrinsics_msg.tz = extrinsics.at(2); - extrinsics_msg.rot_x = extrinsics.at(3); - extrinsics_msg.rot_y = extrinsics.at(4); - extrinsics_msg.rot_z = extrinsics.at(5); - } - catch (const std::out_of_range& ex) - { - ROS_WARN("out-of-range error fetching extrinsics"); - } - this->extrinsics_pub_.publish(extrinsics_msg); - - } // end: while (ros::ok()) { ... } -} // end: Run() - - -PLUGINLIB_EXPORT_CLASS(ifm3d_ros::CameraNodelet, nodelet::Nodelet) From 1e44a9444b539a90bfa32e71d5047fdc719e8a91 Mon Sep 17 00:00:00 2001 From: ifm-csr Date: Wed, 10 Nov 2021 10:25:52 +0000 Subject: [PATCH 2/6] add latest dev changes and fixes --- CHANGELOG.rst | 6 +++--- README.md | 25 +++++++++++++------------ ifm3d-ros/package.xml | 2 +- 3 files changed, 17 insertions(+), 16 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 009df7a..cd57f27 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,16 +2,16 @@ Changelog for package ifm3d-ros ^^^^^^^^^^^^^^^^^^^^^^^^^ -0.7 +1.0 === -0.7.0 +1.0.0 ------ Braking changes: + Restructure the ifm3d-ros package into independent subpackages. Please check your path declarations again, especially for the launch files and messages and services. -Changes between ifm3d_ros 0.6.x and 0.7.0: +Changes between ifm3d_ros 0.6.x and 1.0.0: + Order of axis changed in 3D (cloud topic and extrinsic calibration parameters): This wrapper keeps the axis orientation as defined by the underlying API, ifm3d. Therefore, you may see a different axis order for the cloud message compared to older versions of the ifm3d and ifm cameras. + Extrinsic calibration parameters: now conistent with SI units, e.g. translation are scaled in `m` and rotation parameters are scaled in `rad`. + Added publisher for 2D RGB data diff --git a/README.md b/README.md index 1e76efb..9dfbc46 100644 --- a/README.md +++ b/README.md @@ -1,5 +1,10 @@ # ifm3d-ros wrapper around the ifm3d library +# Release versions + +:warning: Note that the `v1.0.x` branch is generally in a work in progress state, and you probably want to use a tagged [release version](https://github.com/ifm/ifm3d-ros/releases) for production. + +## ifm3d-ros for the O3R **NOTE: The ifm3d-ros package has had major changes recently. Please be aware that this might cause problems on your system for building pipelines based on our old build instructions.** We tried to ensure backward compatibility where ever possible. If you find any major breaks, please let us know. @@ -12,19 +17,15 @@ ifm3d-ros is a wrapper around [ifm3d](https://github.com/ifm/ifm3d/) enabling th ## Software Compatibility Matrix |**ifm3d-ros version**|**ifm3d version**|**ROS distribution(s)**| -|---|---|---| -| 0.1.0 | 0.1.0 | Kinetic | -| 0.2.0 | 0.2.0 | Kinetic, Indigo | -| 0.3.0 | 0.2.0 | Kinetic, Indigo | -| 0.4.0 | 0.3.0, 0.3.1, 0.3.2 | Kinetic, Indigo | -| 0.4.1 | 0.3.3, 0.4.0, 0.5.0, 0.6.0, 0.7.0, 0.8.1 | Kinetic, Indigo | -| 0.4.2 | 0.9.0 | Kinetic | -| 0.5.0 | 0.9.0, 0.9.1 | Kinetic | -| 0.5.1 | 0.9.2 | Kinetic, Melodic | -| 0.6.0 | 0.9.2, 0.9.3, 0.10.0, 0.11.0, 0.11.2 | Kinetic, Melodic | -| 0.6.1, 0.6.2 | 0.11.2, 0.12.0, 0.17.0 | Kinetic, Melodic | -| 0.7.0 | NN - in dev - placeholder 0.91.0 | Noetic | +| ------------ | ------------ | ------------ | +| 1.0.0 | in development - latest version checked 0.91.0 | Noetic | + +### Internal ifm3d-ros subpackage version structure +Please see the internal subpackage version structure for a known `ifm3d-ros version`. +|**ifm3d-ros version**|**ifm3d_ros_driver**|**ifm3d_ros_msgs**|**ifm3d_ros_examples**| +| ------------ | ------------ | ------------ | ------------ | +| 1.0.0 | 0.7.0 | 0.1.0 | 0.1.0 | ## Organization of the software diff --git a/ifm3d-ros/package.xml b/ifm3d-ros/package.xml index ce68491..49527c2 100644 --- a/ifm3d-ros/package.xml +++ b/ifm3d-ros/package.xml @@ -2,7 +2,7 @@ ifm3d-ros - 0.1.0 + 1.0.0 metapackage for the ifm3d-ros package group which interacts with the ifm 3D ToF Camera ROS package ifm CSR group Apache 2 From 32543efc2161797369756af6d223d15695e24eb2 Mon Sep 17 00:00:00 2001 From: ifm-csr Date: Wed, 10 Nov 2021 14:58:14 +0000 Subject: [PATCH 3/6] add latest dev changes and fixes --- ifm3d_ros_examples/CMakeLists.txt | 19 + ifm3d_ros_examples/LICENSE | 202 +++++++++++ ifm3d_ros_examples/README.md | 41 +++ ifm3d_ros_examples/config/rviz_config.rviz | 184 ++++++++++ .../examples/README_pointcloud_merge.md | 6 + ifm3d_ros_examples/examples/dump.json | 338 ++++++++++++++++++ ifm3d_ros_examples/launch/camera.launch | 31 ++ ifm3d_ros_examples/launch/dump_merge_pc.json | 338 ++++++++++++++++++ ifm3d_ros_examples/launch/four_cameras.launch | 110 ++++++ ifm3d_ros_examples/launch/head.launch | 60 ++++ ifm3d_ros_examples/launch/merge_pc.launch | 147 ++++++++ ifm3d_ros_examples/launch/nodelet.launch | 117 ++++++ ifm3d_ros_examples/launch/rviz.launch | 12 + ifm3d_ros_examples/launch/six_cameras.launch | 154 ++++++++ ifm3d_ros_examples/package.xml | 21 ++ 15 files changed, 1780 insertions(+) create mode 100644 ifm3d_ros_examples/CMakeLists.txt create mode 100644 ifm3d_ros_examples/LICENSE create mode 100644 ifm3d_ros_examples/README.md create mode 100644 ifm3d_ros_examples/config/rviz_config.rviz create mode 100644 ifm3d_ros_examples/examples/README_pointcloud_merge.md create mode 100644 ifm3d_ros_examples/examples/dump.json create mode 100644 ifm3d_ros_examples/launch/camera.launch create mode 100644 ifm3d_ros_examples/launch/dump_merge_pc.json create mode 100644 ifm3d_ros_examples/launch/four_cameras.launch create mode 100644 ifm3d_ros_examples/launch/head.launch create mode 100644 ifm3d_ros_examples/launch/merge_pc.launch create mode 100644 ifm3d_ros_examples/launch/nodelet.launch create mode 100644 ifm3d_ros_examples/launch/rviz.launch create mode 100644 ifm3d_ros_examples/launch/six_cameras.launch create mode 100644 ifm3d_ros_examples/package.xml diff --git a/ifm3d_ros_examples/CMakeLists.txt b/ifm3d_ros_examples/CMakeLists.txt new file mode 100644 index 0000000..bfd7203 --- /dev/null +++ b/ifm3d_ros_examples/CMakeLists.txt @@ -0,0 +1,19 @@ +cmake_minimum_required(VERSION 3.0.2) +project(ifm3d_ros_examples) + +find_package(catkin REQUIRED COMPONENTS + tf2_ros + nodelet + ifm3d_ros_driver + ifm3d_ros_msgs +) + + +catkin_package() + +########### +## Build ## +########### +include_directories( + ${catkin_INCLUDE_DIRS} +) diff --git a/ifm3d_ros_examples/LICENSE b/ifm3d_ros_examples/LICENSE new file mode 100644 index 0000000..7a4a3ea --- /dev/null +++ b/ifm3d_ros_examples/LICENSE @@ -0,0 +1,202 @@ + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. \ No newline at end of file diff --git a/ifm3d_ros_examples/README.md b/ifm3d_ros_examples/README.md new file mode 100644 index 0000000..7a455dd --- /dev/null +++ b/ifm3d_ros_examples/README.md @@ -0,0 +1,41 @@ +# The `ifm3d_ros_examples` package +This package provides examples and helper scripts for using the ifm O3R camera platform. + + +## Launchfiles + +Please see the list below for launch files shipped with the examples package: + +| Name | Description | +| ---- | ----------- | +| `six_cameras.launch` | Launches six nodes, reading data streams on ports 0, 1, 2, 3, 4 and 5. Provide coordinate frame transforms for each node. Note: you can use this example for less than six heads, but you will get a `timeout` error where no heads are connected. This does not disrupt the proper functioning of the connected heads.| +| `nodelet.launch` | This is handling the nodelet manager which makes it possible to launch a nodelet similarly as you would a simple node.| +| `head.launch` | Launches two data streams for both the 2D RGB imager and 3D TOF imager on a camera head. Default ports are 0 (pcic_port:=50010) and 2 (pcic_port:=50012). For different port numbers input port as a parameter when launching. | +| `camera.launch` | Launches a single camera stream - so only 3D data or 2D RGB data. This launch file is comparable to a single camera setup (O3Ds and O3Xs) | + +### Nodelet launch structure + +>Note: The O3R platform can handle multiple data streams.* +The `camera.launch` file only launches a node for one data stream, on the default pcic port 50010. To launch a node for a different port, use: +``` +$ roslaunch ifm3d_ros_driver camera.launch pcic_port:= +``` + + +The launch file(s) encapsulate several features: +1. It (partially) exposes the `camera_nodelet` parameters as command-line arguments for ease of runtime configuration. +2. It instantiates a nodelet manager which the `camera_nodelet` will be loaded into. +3. It launches the camera nodelet itself. +4. It publishes the static transform from the camera's optical frame to a traditional ROS sensor frame as a tf2 `static_transform_publisher`. + +You can either use [this launch file](launch/camera.launch) directly, or, use it as a basis for integrating `ifm3d_ros` into your own robot software system. + +> Note: the O3R camera heads carry two imagers, a 3D time-of-flight and a RGB imager. + +We provide the `head.launch` launchfile to handle a whole O3R camera head, that starts two nodes, one for the RGB image (we assume it is plugged in port 0), and one for the 3D imager (we assume it is plugged in port 2). + +## Building launch files distributed systems +>Note: This is WIR. We are currently working on Docker images which will allow you an easy deployment of our ROS node to the VPU. + +# LICENSE +Please see the file called [LICENSE](LICENSE). \ No newline at end of file diff --git a/ifm3d_ros_examples/config/rviz_config.rviz b/ifm3d_ros_examples/config/rviz_config.rviz new file mode 100644 index 0000000..e4054c7 --- /dev/null +++ b/ifm3d_ros_examples/config/rviz_config.rviz @@ -0,0 +1,184 @@ +Panels: + - Class: rviz/Displays + Help Height: 70 + Name: Displays + Property Tree Widget: + Expanded: ~ + Splitter Ratio: 0.747222245 + Tree Height: 900 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: PointCloud2 +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: /ifm3d/camera1/cloud + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /ifm3d/camera1/amplitude + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /ifm3d/camera1/distance + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /ifm3d/camera2/rgb_image + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 10 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.7853981852531433 + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.45539799332618713 + Target Frame: + Yaw: 0.6153985261917114 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1016 + Hide Left Dock: false + Hide Right Dock: true + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd0000000400000000000002670000035afc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000003d000000c9000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d006100670065010000003d000000e20000001600fffffffb0000000a0049006d00610067006503000000000000013800000267000000a3fb0000000a0049006d0061006700650100000125000002720000001600ffffff000000010000010f0000035afc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d0000035a000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000003efc0100000002fb0000000800540069006d0065010000000000000780000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000005130000035a00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1920 + X: 0 + Y: 27 diff --git a/ifm3d_ros_examples/examples/README_pointcloud_merge.md b/ifm3d_ros_examples/examples/README_pointcloud_merge.md new file mode 100644 index 0000000..cf5623a --- /dev/null +++ b/ifm3d_ros_examples/examples/README_pointcloud_merge.md @@ -0,0 +1,6 @@ +# merging point clouds with `merge_pc.launch` + +Three parts: +1. one node per imager publishing data under it's own namespace +2. set all 3D imagers to run mode using a rosservice call to `SoftOn` +3. link ifm3d optical frame to map frame via a dummy transform publisher: `tf2_ros` with pose parameters = 0 \ No newline at end of file diff --git a/ifm3d_ros_examples/examples/dump.json b/ifm3d_ros_examples/examples/dump.json new file mode 100644 index 0000000..6ab7a91 --- /dev/null +++ b/ifm3d_ros_examples/examples/dump.json @@ -0,0 +1,338 @@ +{ + "device": { + "clock": { + "currentTime": 1581092244602229792 + }, + "diagnostic": { + "temperatures": [], + "upTime": 1599000000000 + }, + "info": { + "device": "0301", + "deviceTreeBinaryBlob": "tegra186-quill-p3310-1000-c03-00-base.dtb", + "features": {}, + "name": "", + "partNumber": "M03903", + "productionState": "AA", + "serialNumber": "000201233338", + "vendor": "0001" + }, + "network": { + "authorized_keys": "", + "ipAddressConfig": 0, + "macEth0": "00:04:4B:E4:DA:9E", + "macEth1": "00:02:01:23:33:38", + "networkSpeed": 1000, + "staticIPv4Address": "192.168.0.69", + "staticIPv4Gateway": "192.168.0.201", + "staticIPv4SubNetMask": "255.255.255.0", + "useDHCP": false + }, + "state": { + "errorMessage": "", + "errorNumber": "" + }, + "swVersion": { + "kernel": "4.9.140-l4t-r32.4+g231628d3fa15", + "l4t": "r32.4.3", + "os": "0.13.3-188", + "schema": "feature/O3R-4949", + "swu": "0.15.3" + } + }, + "ports": { + "port0": { + "acquisition": { + "exposureLong": 5000, + "exposureShort": 400, + "framerate": 10.0, + "offset": 0.0, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "data": { + "algoDebugConfig": {}, + "availablePCICOutput": [ + "AMPLITUDE_COMPRESSED", + "CONFIDENCE", + "RADIAL_DISTANCE_COMPRESSED", + "RADIAL_DISTANCE_NOISE", + "REFLECTIVITY", + "TOF_INFO" + ], + "pcicTCPPort": 50010 + }, + "info": { + "device": "3101", + "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", + "features": { + "fov": { + "horizontal": 78, + "vertical": 105 + }, + "resolution": { + "height": 172, + "width": 224 + }, + "type": "3D" + }, + "name": "", + "partNumber": "M03957", + "productionState": "AA", + "sensor": "IRS2381C", + "sensorID": "IRS2381C_105x78_4x2W_110x90_Csample", + "serialNumber": "000000000186", + "vendor": "0001" + }, + "mode": "experimental_high_4m", + "processing": { + "diParam": { + "anfFilterSizeDiv2": 2, + "enableDynamicSymmetry": true, + "enableStraylight": true, + "enableTemporalFilter": true, + "excessiveCorrectionThreshAmp": 0.3, + "excessiveCorrectionThreshDist": 0.08, + "maxDistNoise": 0.02, + "maxSymmetry": 0.4, + "medianSizeDiv2": 0, + "minAmplitude": 20.0, + "minReflectivity": 0.0, + "mixedPixelFilterMode": 1, + "mixedPixelThresholdRad": 0.15 + }, + "extrinsicHeadToUser": { + "rotX": 0.0, + "rotY": 0.0, + "rotZ": 0.0, + "transX": 0.0, + "transY": 0.0, + "transZ": 0.0 + }, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "state": "RUN" + }, + "port1": { + "acquisition": { + "exposureLong": 5000, + "exposureShort": 400, + "framerate": 10.0, + "offset": 0.0, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "data": { + "algoDebugConfig": {}, + "availablePCICOutput": [ + "AMPLITUDE_COMPRESSED", + "CONFIDENCE", + "RADIAL_DISTANCE_COMPRESSED", + "RADIAL_DISTANCE_NOISE", + "REFLECTIVITY", + "TOF_INFO" + ], + "pcicTCPPort": 50011 + }, + "info": { + "device": "3101", + "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", + "features": { + "fov": { + "horizontal": 78, + "vertical": 105 + }, + "resolution": { + "height": 172, + "width": 224 + }, + "type": "3D" + }, + "name": "", + "partNumber": "M03957", + "productionState": "AA", + "sensor": "IRS2381C", + "sensorID": "IRS2381C_105x78_4x2W_110x90_Csample", + "serialNumber": "000000000192", + "vendor": "0001" + }, + "mode": "experimental_high_4m", + "processing": { + "diParam": { + "anfFilterSizeDiv2": 2, + "enableDynamicSymmetry": true, + "enableStraylight": true, + "enableTemporalFilter": true, + "excessiveCorrectionThreshAmp": 0.3, + "excessiveCorrectionThreshDist": 0.08, + "maxDistNoise": 0.02, + "maxSymmetry": 0.4, + "medianSizeDiv2": 0, + "minAmplitude": 20.0, + "minReflectivity": 0.0, + "mixedPixelFilterMode": 1, + "mixedPixelThresholdRad": 0.15 + }, + "extrinsicHeadToUser": { + "rotX": 0.0, + "rotY": 0.0, + "rotZ": 0.0, + "transX": 0.0, + "transY": 0.0, + "transZ": 0.0 + }, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "state": "RUN" + }, + "port2": { + "acquisition": { + "exposureLong": 5000, + "exposureShort": 400, + "framerate": 10.0, + "offset": 0.0, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "data": { + "algoDebugConfig": {}, + "availablePCICOutput": [ + "AMPLITUDE_COMPRESSED", + "CONFIDENCE", + "RADIAL_DISTANCE_COMPRESSED", + "RADIAL_DISTANCE_NOISE", + "REFLECTIVITY", + "TOF_INFO" + ], + "pcicTCPPort": 50012 + }, + "info": { + "device": "2301", + "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", + "features": { + "fov": { + "horizontal": 80, + "vertical": 127 + }, + "resolution": { + "height": 800, + "width": 1280 + }, + "type": "2D" + }, + "name": "", + "partNumber": "M03934", + "productionState": "AA", + "sensor": "OV9782", + "sensorID": "OV9782_127x80_noIllu_Csample", + "serialNumber": "000000000094", + "vendor": "0001" + }, + "mode": "experimental_high_4m", + "processing": { + "diParam": { + "anfFilterSizeDiv2": 2, + "enableDynamicSymmetry": true, + "enableStraylight": true, + "enableTemporalFilter": true, + "excessiveCorrectionThreshAmp": 0.3, + "excessiveCorrectionThreshDist": 0.08, + "maxDistNoise": 0.02, + "maxSymmetry": 0.4, + "medianSizeDiv2": 0, + "minAmplitude": 20.0, + "minReflectivity": 0.0, + "mixedPixelFilterMode": 1, + "mixedPixelThresholdRad": 0.15 + }, + "extrinsicHeadToUser": { + "rotX": 0.0, + "rotY": 0.0, + "rotZ": 0.0, + "transX": 0.0, + "transY": 0.0, + "transZ": 0.0 + }, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "state": "CONF" + }, + "port5": { + "acquisition": { + "framerate": 10.0, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "data": { + "algoDebugConfig": {}, + "availablePCICOutput": [ + "RGB_INFO" + ], + "pcicTCPPort": 50015 + }, + "info": { + "device": "2301", + "deviceTreeBinaryBlobOverlay": "001-ov9782.dtbo", + "features": { + "fov": { + "horizontal": 80, + "vertical": 127 + }, + "resolution": { + "height": 800, + "width": 1280 + }, + "type": "2D" + }, + "name": "", + "partNumber": "M03934", + "productionState": "AA", + "sensor": "OV9782", + "sensorID": "OV9782_127x80_noIllu_Csample", + "serialNumber": "000000000094", + "vendor": "0001" + }, + "mode": "experimental_autoexposure2D", + "processing": { + "extrinsicHeadToUser": { + "rotX": 0.0, + "rotY": 0.0, + "rotZ": 0.0, + "transX": 0.0, + "transY": 0.0, + "transZ": 0.0 + }, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "state": "CONF" + } + } + } \ No newline at end of file diff --git a/ifm3d_ros_examples/launch/camera.launch b/ifm3d_ros_examples/launch/camera.launch new file mode 100644 index 0000000..78ae71e --- /dev/null +++ b/ifm3d_ros_examples/launch/camera.launch @@ -0,0 +1,31 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ifm3d_ros_examples/launch/dump_merge_pc.json b/ifm3d_ros_examples/launch/dump_merge_pc.json new file mode 100644 index 0000000..2e8fa74 --- /dev/null +++ b/ifm3d_ros_examples/launch/dump_merge_pc.json @@ -0,0 +1,338 @@ +{ + "device": { + "clock": { + "currentTime": 1581090835576664320 + }, + "diagnostic": { + "temperatures": [], + "upTime": 190000000000 + }, + "info": { + "device": "0301", + "deviceTreeBinaryBlob": "tegra186-quill-p3310-1000-c03-00-base.dtb", + "features": {}, + "name": "", + "partNumber": "M03903", + "productionState": "AA", + "serialNumber": "000201233338", + "vendor": "0001" + }, + "network": { + "authorized_keys": "", + "ipAddressConfig": 0, + "macEth0": "00:04:4B:E4:DA:9E", + "macEth1": "00:02:01:23:33:38", + "networkSpeed": 1000, + "staticIPv4Address": "192.168.0.69", + "staticIPv4Gateway": "192.168.0.201", + "staticIPv4SubNetMask": "255.255.255.0", + "useDHCP": false + }, + "state": { + "errorMessage": "", + "errorNumber": "" + }, + "swVersion": { + "kernel": "4.9.140-l4t-r32.4+g231628d3fa15", + "l4t": "r32.4.3", + "os": "0.13.3-188", + "schema": "feature/O3R-4949", + "swu": "0.15.3" + } + }, + "ports": { + "port0": { + "acquisition": { + "exposureLong": 5000, + "exposureShort": 400, + "framerate": 10.0, + "offset": 0.0, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "data": { + "algoDebugConfig": {}, + "availablePCICOutput": [ + "AMPLITUDE_COMPRESSED", + "CONFIDENCE", + "RADIAL_DISTANCE_COMPRESSED", + "RADIAL_DISTANCE_NOISE", + "REFLECTIVITY", + "TOF_INFO" + ], + "pcicTCPPort": 50010 + }, + "info": { + "device": "3101", + "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", + "features": { + "fov": { + "horizontal": 78, + "vertical": 105 + }, + "resolution": { + "height": 172, + "width": 224 + }, + "type": "3D" + }, + "name": "", + "partNumber": "M03957", + "productionState": "AA", + "sensor": "IRS2381C", + "sensorID": "IRS2381C_105x78_4x2W_110x90_Csample", + "serialNumber": "000000000186", + "vendor": "0001" + }, + "mode": "experimental_high_4m", + "processing": { + "diParam": { + "anfFilterSizeDiv2": 2, + "enableDynamicSymmetry": true, + "enableStraylight": true, + "enableTemporalFilter": true, + "excessiveCorrectionThreshAmp": 0.3, + "excessiveCorrectionThreshDist": 0.08, + "maxDistNoise": 0.02, + "maxSymmetry": 0.4, + "medianSizeDiv2": 0, + "minAmplitude": 20.0, + "minReflectivity": 0.0, + "mixedPixelFilterMode": 1, + "mixedPixelThresholdRad": 0.15 + }, + "extrinsicHeadToUser": { + "rotX": 0.0, + "rotY": -1.5708, + "rotZ": 0.0, + "transX": 0.015, + "transY": -0.18, + "transZ": -0.055 + }, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "state": "RUN" + }, + "port1": { + "acquisition": { + "exposureLong": 5000, + "exposureShort": 400, + "framerate": 10.0, + "offset": 0.0, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "data": { + "algoDebugConfig": {}, + "availablePCICOutput": [ + "AMPLITUDE_COMPRESSED", + "CONFIDENCE", + "RADIAL_DISTANCE_COMPRESSED", + "RADIAL_DISTANCE_NOISE", + "REFLECTIVITY", + "TOF_INFO" + ], + "pcicTCPPort": 50011 + }, + "info": { + "device": "3101", + "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", + "features": { + "fov": { + "horizontal": 78, + "vertical": 105 + }, + "resolution": { + "height": 172, + "width": 224 + }, + "type": "3D" + }, + "name": "", + "partNumber": "M03957", + "productionState": "AA", + "sensor": "IRS2381C", + "sensorID": "IRS2381C_105x78_4x2W_110x90_Csample", + "serialNumber": "000000000192", + "vendor": "0001" + }, + "mode": "experimental_high_4m", + "processing": { + "diParam": { + "anfFilterSizeDiv2": 2, + "enableDynamicSymmetry": true, + "enableStraylight": true, + "enableTemporalFilter": true, + "excessiveCorrectionThreshAmp": 0.3, + "excessiveCorrectionThreshDist": 0.08, + "maxDistNoise": 0.02, + "maxSymmetry": 0.4, + "medianSizeDiv2": 0, + "minAmplitude": 20.0, + "minReflectivity": 0.0, + "mixedPixelFilterMode": 1, + "mixedPixelThresholdRad": 0.15 + }, + "extrinsicHeadToUser": { + "rotX": 0.0, + "rotY": 0.0, + "rotZ": 0.0, + "transX": -0.13, + "transY": -0.1, + "transZ": 0.2 + }, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "state": "RUN" + }, + "port2": { + "acquisition": { + "exposureLong": 5000, + "exposureShort": 400, + "framerate": 10.0, + "offset": 0.0, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "data": { + "algoDebugConfig": {}, + "availablePCICOutput": [ + "AMPLITUDE_COMPRESSED", + "CONFIDENCE", + "RADIAL_DISTANCE_COMPRESSED", + "RADIAL_DISTANCE_NOISE", + "REFLECTIVITY", + "TOF_INFO" + ], + "pcicTCPPort": 50012 + }, + "info": { + "device": "2301", + "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", + "features": { + "fov": { + "horizontal": 80, + "vertical": 127 + }, + "resolution": { + "height": 800, + "width": 1280 + }, + "type": "2D" + }, + "name": "", + "partNumber": "M03934", + "productionState": "AA", + "sensor": "OV9782", + "sensorID": "OV9782_127x80_noIllu_Csample", + "serialNumber": "000000000094", + "vendor": "0001" + }, + "mode": "experimental_high_4m", + "processing": { + "diParam": { + "anfFilterSizeDiv2": 2, + "enableDynamicSymmetry": true, + "enableStraylight": true, + "enableTemporalFilter": true, + "excessiveCorrectionThreshAmp": 0.3, + "excessiveCorrectionThreshDist": 0.08, + "maxDistNoise": 0.02, + "maxSymmetry": 0.4, + "medianSizeDiv2": 0, + "minAmplitude": 20.0, + "minReflectivity": 0.0, + "mixedPixelFilterMode": 1, + "mixedPixelThresholdRad": 0.15 + }, + "extrinsicHeadToUser": { + "rotX": 0.0, + "rotY": 3.1416, + "rotZ": 0.0, + "transX": -0.015, + "transY": -0.3, + "transZ": 0.05 + }, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "state": "RUN" + }, + "port5": { + "acquisition": { + "framerate": 10.0, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "data": { + "algoDebugConfig": {}, + "availablePCICOutput": [ + "RGB_INFO" + ], + "pcicTCPPort": 50015 + }, + "info": { + "device": "2301", + "deviceTreeBinaryBlobOverlay": "001-ov9782.dtbo", + "features": { + "fov": { + "horizontal": 80, + "vertical": 127 + }, + "resolution": { + "height": 800, + "width": 1280 + }, + "type": "2D" + }, + "name": "", + "partNumber": "M03934", + "productionState": "AA", + "sensor": "OV9782", + "sensorID": "OV9782_127x80_noIllu_Csample", + "serialNumber": "000000000094", + "vendor": "0001" + }, + "mode": "experimental_autoexposure2D", + "processing": { + "extrinsicHeadToUser": { + "rotX": 0.0, + "rotY": 0.0, + "rotZ": 0.0, + "transX": 0.0, + "transY": 0.0, + "transZ": 0.0 + }, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "state": "CONF" + } + } +} diff --git a/ifm3d_ros_examples/launch/four_cameras.launch b/ifm3d_ros_examples/launch/four_cameras.launch new file mode 100644 index 0000000..3a82ca4 --- /dev/null +++ b/ifm3d_ros_examples/launch/four_cameras.launch @@ -0,0 +1,110 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ifm3d_ros_examples/launch/head.launch b/ifm3d_ros_examples/launch/head.launch new file mode 100644 index 0000000..fc45542 --- /dev/null +++ b/ifm3d_ros_examples/launch/head.launch @@ -0,0 +1,60 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ifm3d_ros_examples/launch/merge_pc.launch b/ifm3d_ros_examples/launch/merge_pc.launch new file mode 100644 index 0000000..13bf287 --- /dev/null +++ b/ifm3d_ros_examples/launch/merge_pc.launch @@ -0,0 +1,147 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ifm3d_ros_examples/launch/nodelet.launch b/ifm3d_ros_examples/launch/nodelet.launch new file mode 100644 index 0000000..8259ed6 --- /dev/null +++ b/ifm3d_ros_examples/launch/nodelet.launch @@ -0,0 +1,117 @@ + + + + + + + + + + + + + + + + + + + + + + + + # + # The IP address of the camera to connect to + # + ip: "$(arg ip)" + + # + # The on-camera TCP port that the XMLRPC server is listening to + # + xmlrpc_port: $(arg xmlrpc_port) + + # + # The on-camera TCP port that the PCIC server is listening to + # + pcic_port: $(arg pcic_port) + + # + # The password needed to establish an edit session with the camera + # + password: "$(arg password)" + + # + # The PCIC schema mask to apply to the framegrabber + # + schema_mask: $(arg schema_mask) + + # + # The number of milliseconds to wait for a frame before declaring a + # framegrabber timeout + # + timeout_millis: $(arg timeout_millis) + + # + # The number of seconds to endure timeouts before restarting the framegrabber + # + timeout_tolerance_secs: $(arg timeout_tolerance_secs) + + # + # Flag indicating whether or not the nodelet should assume the camera is + # being software triggered + # + assume_sw_triggered: $(arg assume_sw_triggered) + + # + # If using the `SoftOff`/`SoftOn` functionality, these parameters + # control the `timeout_millis` and `timeout_tolerance_secs` + # + soft_on_timeout_millis: $(arg timeout_millis) + soft_on_timeout_tolerance_secs: $(arg timeout_tolerance_secs) + soft_off_timeout_millis: 500 + soft_off_timeout_tolerance_secs: 600.0 + + # + # Time (seconds) used to determine that timestamps from the camera + # cannot be trusted. When this threshold is exceeded, when compared to + # system time, we use the reception time of the frame and not the capture + # time of the frame. + # + frame_latency_thresh: 60.0 + + # + # Get rid of the errors when running `rosbag -a' + # + distance/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] + amplitude/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] + raw_amplitude/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] + confidence/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] + good_bad_pixels/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] + xyz_image/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] + + + + + + + + + + + + + diff --git a/ifm3d_ros_examples/launch/rviz.launch b/ifm3d_ros_examples/launch/rviz.launch new file mode 100644 index 0000000..fcf2c23 --- /dev/null +++ b/ifm3d_ros_examples/launch/rviz.launch @@ -0,0 +1,12 @@ + + + + + + + + + diff --git a/ifm3d_ros_examples/launch/six_cameras.launch b/ifm3d_ros_examples/launch/six_cameras.launch new file mode 100644 index 0000000..ca81835 --- /dev/null +++ b/ifm3d_ros_examples/launch/six_cameras.launch @@ -0,0 +1,154 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ifm3d_ros_examples/package.xml b/ifm3d_ros_examples/package.xml new file mode 100644 index 0000000..f8db7eb --- /dev/null +++ b/ifm3d_ros_examples/package.xml @@ -0,0 +1,21 @@ + + + + ifm3d_ros_examples + 0.1.0 + ifm3d_ros examples subpackage + ifm CSR group + Apache 2 + CSR ifm sytron + + https://github.com/ifm/ifm3d_ros/ + + catkin + tf + ifm3d_ros_driver + ifm3d_ros_msgs + + + + + From 660c3fc4b5363b57d6ede0e6f2636bd4e1265c8a Mon Sep 17 00:00:00 2001 From: ifm-csr Date: Thu, 11 Nov 2021 12:06:20 +0000 Subject: [PATCH 4/6] add latest dev changes and fixes --- ifm3d_ros_driver/CMakeLists.txt | 2 +- ifm3d_ros_driver/doc/dump_and_config.md | 227 ++++-------------- .../__pycache__/_ConfigClient.cpython-38.pyc | Bin 1114 -> 0 bytes .../__pycache__/_DumpClient.cpython-38.pyc | Bin 1235 -> 0 bytes ifm3d_ros_driver/src/camera_nodelet.cpp | 2 +- ifm3d_ros_examples/launch/four_cameras.launch | 2 +- ifm3d_ros_examples/launch/six_cameras.launch | 30 +-- ifm3d_ros_msgs/CMakeLists.txt | 1 + ifm3d_ros_msgs/bin/config | 2 +- ifm3d_ros_msgs/bin/dump | 2 +- {ifm3d_ros_driver => ifm3d_ros_msgs}/setup.py | 4 +- .../utils/ifm3d_ros_utils}/_ConfigClient.py | 4 +- .../utils/ifm3d_ros_utils}/_DumpClient.py | 4 +- .../utils/ifm3d_ros_utils}/__init__.py | 0 14 files changed, 81 insertions(+), 199 deletions(-) delete mode 100644 ifm3d_ros_driver/pylib/ifm3d/__pycache__/_ConfigClient.cpython-38.pyc delete mode 100644 ifm3d_ros_driver/pylib/ifm3d/__pycache__/_DumpClient.cpython-38.pyc rename {ifm3d_ros_driver => ifm3d_ros_msgs}/setup.py (73%) rename {ifm3d_ros_driver/pylib/ifm3d => ifm3d_ros_msgs/utils/ifm3d_ros_utils}/_ConfigClient.py (88%) rename {ifm3d_ros_driver/pylib/ifm3d => ifm3d_ros_msgs/utils/ifm3d_ros_utils}/_DumpClient.py (91%) rename {ifm3d_ros_driver/pylib/ifm3d => ifm3d_ros_msgs/utils/ifm3d_ros_utils}/__init__.py (100%) diff --git a/ifm3d_ros_driver/CMakeLists.txt b/ifm3d_ros_driver/CMakeLists.txt index 78ccdb0..634c40c 100644 --- a/ifm3d_ros_driver/CMakeLists.txt +++ b/ifm3d_ros_driver/CMakeLists.txt @@ -21,7 +21,7 @@ find_package(catkin REQUIRED COMPONENTS ifm3d_ros_msgs ) -catkin_python_setup() +# catkin_python_setup() option(CATKIN_ENABLE_TESTING "Build tests" OFF) diff --git a/ifm3d_ros_driver/doc/dump_and_config.md b/ifm3d_ros_driver/doc/dump_and_config.md index 9439bcf..5ca1094 100644 --- a/ifm3d_ros_driver/doc/dump_and_config.md +++ b/ifm3d_ros_driver/doc/dump_and_config.md @@ -18,187 +18,63 @@ Per camera head connected to the visual processing unit (VPU) of the O3R platfor As you can see the two services `Dump` and `Config` are also part of this list. ### Dump -Call this service via, e.g. for camera1: +Calling the native rosservice `/ifm3d_ros_examples/camera/Dump` for a certain `camera` will return a string containing with the camera configuration as a JSON string. Please notice the use of backslashes (`\` before each `"`) to esacpe each upper quotation mark. This is necessary to allow us to keep the JSON syntax native to the underlying API (ifm3d). + +>Note: We have mapped some camera configurations to native rosservice calls to make their handling easier, e.g. `rosservice call /ifm3d_ros_examples/camera/SoftOn`. If you think you will benefit from similar rosservices, please let us know so we can add more comfort handling. + +Call this service via, e.g. for camera: ``` -$ rosservice call /ifm3d_ros_examples/camera1/Dump +$ rosservice call /ifm3d_ros_examples/camera/Dump status: 0 -{ - "device": { - "clock": { - "currentTime": 1581193835185485800 - }, - "diagnostic": { - "temperatures": [], - "upTime": 103190000000000 - }, - "info": { - "device": "0301", - "deviceTreeBinaryBlob": "tegra186-quill-p3310-1000-c03-00-base.dtb", - "features": {}, - "name": "", - " partNumber": "M03975", - "productionState": "AA", - "serialNumber": "000201234160", - "vendor": "0001" - }, - "network": { - "authorized_keys": "", - "ipAddressConfig": 0, - "macEth0": "00:04:4B:EA:9F:0E", - "macEth1": "00:02:01:23:41:60", - "networkSpeed": 1000, - "staticIPv4Address": "192.168.0.69", - "staticIPv4Gateway": "192.168.0.201", - "staticIPv4SubNetMask": "255.255.255.0", - "useDHCP": false - }, - "state": { - "errorMessage": "", - "errorNumber": "" - }, - "swVersion": { - "kernel": "4.9.140-l4t-r32.4+gc35f5eb9d1d9", - "l4t": "r32.4.3", - "os": "0.13.13-221", - "schema": "v0.1.0", - "swu": "0.15.12" - } - }, - "ports": { - "port0": { - "acquisition": { - "framerate": 10, - "version": { - "major": 0, - "minor": 0, - "patch": 0 - } - }, - "data": { - "algoDebugConfig": {}, - "availablePCICOutput": [], - "pcicTCPPort": 50010 - }, - "info": { - "device": "2301", - "deviceTreeBinaryBlobOverlay": "001-ov9782.dtbo", - "features": { - "fov": { - "horizontal": 127, - "vertical": 80 - }, - " resolution": { - "height": 800, - "width": 1280 - }, - "type": "2D" - }, - "name": "", - "partNumber": "M03969", - "productionState": "AA", - "sensor": "OV9782", - "sensorID": "OV9782_127x80_noIllu_Csample", - "serialNumber": "000000000382", - "vendor": "0001" - }, - "mode": "experimental_autoexposure2D", - "processing": { - "extrinsicHeadToUser": { - "rotX": 0, - "rotY": 0, - "rotZ": 0, - " transX": 0, - "transY": 0, - "transZ": 0 - }, - "version": { - "major": 0, - "minor": 0, - " patch": 0 - } - }, - "state": "RUN" - }, - "port2": { - "acquisition": { - "exposureLong": 5000, - " exposureShort": 400, - "framerate": 10, - "offset": 0, - "version": { - "major": 0, - " minor": 0, - "patch": 0 - } - }, - "data": { - "algoDebugConfig": {}, - "availablePCICOutput": [], - "pcicTCPPort": 50012 - }, - "info": { - "device": "3101", - "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", - "features": { - "fov": { - "horizontal": 105, - "vertical": 78 - }, - " resolution": { - "height": 172, - "width": 224 - }, - "type": "3D" - }, - "name": "", - "partNumber": "M03969", - "productionState": "AA", - "sensor": "IRS2381C", - "sensorID": "IRS2381C_105x78_4x2W_110x90_C7", - "serialNumber": "000000000382", - "vendor": "0001" - }, - "mode": "standard_range4m", - "processing": { - "diParam": { - "anfFilterSizeDiv2": 2, - "enableDynamicSymmetry": true, - "enableStraylight": true, - "enableTemporalFilter": true, - "excessiveCorrectionThreshAmp": 0.3, - "excessiveCorrectionThreshDist": 0.08, - "maxDistNoise": 0.02, - "maxSymmetry": 0.4, - "medianSizeDiv2": 0, - "minAmplitude": 20, - "minReflectivity": 0, - "mixedPixelFilterMode": 1, - "mixedPixelThresholdRad": 0.15 - }, - "extrinsicHeadToUser": { - "rotX": 1, - "rotY": 0, - "rotZ": 0, - "transX": 100, - "transY": 0, - "transZ": 0 - }, - "version": { - " major": 0, - "minor": 0, - "patch": 0 - } - }, - "state": "RUN" - } - } -} +config: "{\"device\":{\"clock\":{\"currentTime\":1581287336449588512},\"diagnostic\":{\"temperatures\"\ + :[],\"upTime\":196692000000000},\"info\":{\"device\":\"0301\",\"deviceTreeBinaryBlob\"\ + :\"tegra186-quill-p3310-1000-c03-00-base.dtb\",\"features\":{},\"name\":\"test\"\ + ,\"partNumber\":\"M03975\",\"productionState\":\"AA\",\"serialNumber\":\"000201234160\"\ + ,\"vendor\":\"0001\"},\"network\":{\"authorized_keys\":\"\",\"ipAddressConfig\"\ + :0,\"macEth0\":\"00:04:4B:EA:9F:0E\",\"macEth1\":\"00:02:01:23:41:60\",\"networkSpeed\"\ + :1000,\"staticIPv4Address\":\"192.168.0.69\",\"staticIPv4Gateway\":\"192.168.0.201\"\ + ,\"staticIPv4SubNetMask\":\"255.255.255.0\",\"useDHCP\":false},\"state\":{\"errorMessage\"\ + :\"\",\"errorNumber\":\"\"},\"swVersion\":{\"kernel\":\"4.9.140-l4t-r32.4+gc35f5eb9d1d9\"\ + ,\"l4t\":\"r32.4.3\",\"os\":\"0.13.13-221\",\"schema\":\"v0.1.0\",\"swu\":\"0.15.12\"\ + }},\"ports\":{\"port0\":{\"acquisition\":{\"framerate\":10.0,\"version\":{\"major\"\ + :0,\"minor\":0,\"patch\":0}},\"data\":{\"algoDebugConfig\":{},\"availablePCICOutput\"\ + :[],\"pcicTCPPort\":50010},\"info\":{\"device\":\"2301\",\"deviceTreeBinaryBlobOverlay\"\ + :\"001-ov9782.dtbo\",\"features\":{\"fov\":{\"horizontal\":127,\"vertical\":80},\"\ + resolution\":{\"height\":800,\"width\":1280},\"type\":\"2D\"},\"name\":\"\",\"partNumber\"\ + :\"M03969\",\"productionState\":\"AA\",\"sensor\":\"OV9782\",\"sensorID\":\"OV9782_127x80_noIllu_Csample\"\ + ,\"serialNumber\":\"000000000382\",\"vendor\":\"0001\"},\"mode\":\"experimental_autoexposure2D\"\ + ,\"processing\":{\"extrinsicHeadToUser\":{\"rotX\":0.0,\"rotY\":0.0,\"rotZ\":0.0,\"\ + transX\":0.0,\"transY\":0.0,\"transZ\":0.0},\"version\":{\"major\":0,\"minor\":0,\"\ + patch\":0}},\"state\":\"RUN\"},\"port2\":{\"acquisition\":{\"exposureLong\":5000,\"\ + exposureShort\":400,\"framerate\":10.0,\"offset\":0.0,\"version\":{\"major\":0,\"\ + minor\":0,\"patch\":0}},\"data\":{\"algoDebugConfig\":{},\"availablePCICOutput\"\ + :[],\"pcicTCPPort\":50012},\"info\":{\"device\":\"3101\",\"deviceTreeBinaryBlobOverlay\"\ + :\"001-irs2381c.dtbo\",\"features\":{\"fov\":{\"horizontal\":105,\"vertical\":78},\"\ + resolution\":{\"height\":172,\"width\":224},\"type\":\"3D\"},\"name\":\"\",\"partNumber\"\ + :\"M03969\",\"productionState\":\"AA\",\"sensor\":\"IRS2381C\",\"sensorID\":\"IRS2381C_105x78_4x2W_110x90_C7\"\ + ,\"serialNumber\":\"000000000382\",\"vendor\":\"0001\"},\"mode\":\"standard_range2m\"\ + ,\"processing\":{\"diParam\":{\"anfFilterSizeDiv2\":2,\"enableDynamicSymmetry\"\ + :true,\"enableStraylight\":true,\"enableTemporalFilter\":true,\"excessiveCorrectionThreshAmp\"\ + :0.3,\"excessiveCorrectionThreshDist\":0.08,\"maxDistNoise\":0.02,\"maxSymmetry\"\ + :0.4,\"medianSizeDiv2\":0,\"minAmplitude\":20.0,\"minReflectivity\":0.0,\"mixedPixelFilterMode\"\ + :1,\"mixedPixelThresholdRad\":0.15},\"extrinsicHeadToUser\":{\"rotX\":0.0,\"rotY\"\ + :0.0,\"rotZ\":0.0,\"transX\":0.0,\"transY\":0.0,\"transZ\":0.0},\"version\":{\"\ + major\":0,\"minor\":0,\"patch\":0}},\"state\":\"RUN\"}}}" ``` ## Config Below you can see an example on how to configure your camera via a rosservice call. The JSON string can be a partial JSON string. It only needs to follow basic JSON syntax. ``` -rosservice call /ifm3d_ros_examples/camera2/Config "json: '{"ports": {"port2": {"state": "RUN"}}}'" +$ rosservice call /ifm3d_ros_examples/camera/Config "json: '{\"ports\":{\"port2\":{\"mode\":\"standard_range2m\"}}}'" +status: 0 +msg: "OK" +``` + +This is equivalent to: +``` +$ rosservice call /ifm3d_ros_examples/camera/Config '"{\"ports\":{\"port2\":{\"mode\":\"standard_range2m\"}}}"' +status: 0 +msg: "OK" ``` @@ -211,7 +87,10 @@ They are part of the `ifm3d_ros_msgs` subpackage, so if you can't access them pl For example, to dump the state of the camera: (exemplary output from an O3R perception platform with one camera head connected is shown) +>Note: The service proxying only works on the `/ifm3d_ros_examples/camera/` namespace at the moment. + ``` +$ roslaunch ifm3d_ros_examples camera.launch & $ rosrun ifm3d_ros_msgs dump { "device": { diff --git a/ifm3d_ros_driver/pylib/ifm3d/__pycache__/_ConfigClient.cpython-38.pyc b/ifm3d_ros_driver/pylib/ifm3d/__pycache__/_ConfigClient.cpython-38.pyc deleted file mode 100644 index 5630c5070252046801c534f7d1bc8a4c49d4c51f..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1114 zcmY*YOK%e~5VpOKY_>@#DpW{t$OVZ#Kn{otLa3-jh(lAc7#$_=|$0xAoc~r3OX(f$a6=@vFL_jPrtMSC#IoKciV;;>W z{%>dx4Fas(U6Wv}&#-nD4|*nXFOKqrN4?q|*WOzV*lV0mz(^3_Lp8Qb1lTNQ!)`MN z`gc{U&as=NNg-o=n*?dw0@(!-9Z(Wo0aMo)I6-ii48kqb4Xt6)*yIR^a(F3bbJa|X zRMMhk2|%$$l8t^K-hf1Z`@Kn-Cp`$OM8bRHR01M-mKHbg1dng5**r^6Z*02W>I*2~ zQEE!iE#0CWVZEZNrQ6$afIk!`dBmh>0k$<{B~kZGQjmE@Y$MW@es z$zOM$itckz!98V9MOi32DPJy@ZgvZ-tG0( zhPDnr?)CSN4pnPd`#stU#pWHtA#e~l`e_Q7QA(9hXn2N9YAk9d~(68Ne?DJx@2`GyYDUfu=;IzzJ#p)qOZwhy5L=J@{OtGP_xt(HtF5h^z&QK&=kjAj$UnH*95HMj z!*owTNKz0|rfJGn@}ti8de`cz^a?$#>1Ojj;^m72KC|U=o_~Ux z$o`my_z8s1a0lb@>h`2hI;qM=*>Zx$YHj-}8G6EW--1vC0FgDA_XNO1GKMvl2^5@$ z95d|JTD88S;QnQx4y2J?m~I<{Cl^4>B?SryM6&(jR$qxgc%tevj9Eymam&*%)UEcS zHBuo2r|Rk7#10_M=iSNNG-?8Fol|x)(;l$+W8Gc@bGEwHmZ!Boy4JP zowvyD;U{dsG5bt^Sh0tE9EG7X){A3x>O!hp2~QGork~(Xg}x5 zT4Nvb?;ZaUM83MeJ6F~5M(^F{wV63SHJ0Pm&| z;N_oU|JS{z;Rb4lzwJGJ@#-*)4%YTRtoiHIBHtl(zVw|7$z!?mG~KZqpG> zX-;=2Bk*12QARV$uGm!?ueLWD0K)di2{uX#e~J(x7ost;t5F{b@un;5wZ#r0vE?YR zIW`0qV6ka-U^-+hV_DRnjPo!MLYhhldl%i%YVUz4hW&5xz}dGwQ5IX&-U1O)bF@&E f?-OiX)8E>I%^s~w`~|c1e_b3SzKo7oOk?&R46iz? diff --git a/ifm3d_ros_driver/src/camera_nodelet.cpp b/ifm3d_ros_driver/src/camera_nodelet.cpp index a7bc321..bd4d7e6 100644 --- a/ifm3d_ros_driver/src/camera_nodelet.cpp +++ b/ifm3d_ros_driver/src/camera_nodelet.cpp @@ -183,7 +183,7 @@ bool ifm3d_ros::CameraNodelet::Config(ifm3d_ros_msgs::Config::Request& req, ifm3 try { - this->cam_->FromJSON(req.json); + this->cam_->FromJSON(json::parse(req.json)); } catch (const ifm3d::error_t& ex) { diff --git a/ifm3d_ros_examples/launch/four_cameras.launch b/ifm3d_ros_examples/launch/four_cameras.launch index 3a82ca4..6ee2d6f 100644 --- a/ifm3d_ros_examples/launch/four_cameras.launch +++ b/ifm3d_ros_examples/launch/four_cameras.launch @@ -1,6 +1,6 @@ - + diff --git a/ifm3d_ros_examples/launch/six_cameras.launch b/ifm3d_ros_examples/launch/six_cameras.launch index ca81835..b8a2807 100644 --- a/ifm3d_ros_examples/launch/six_cameras.launch +++ b/ifm3d_ros_examples/launch/six_cameras.launch @@ -8,6 +8,8 @@ + + @@ -86,7 +88,7 @@ - + @@ -101,7 +103,7 @@ - + @@ -117,38 +119,38 @@ diff --git a/ifm3d_ros_msgs/CMakeLists.txt b/ifm3d_ros_msgs/CMakeLists.txt index 0091b92..df3e3f0 100644 --- a/ifm3d_ros_msgs/CMakeLists.txt +++ b/ifm3d_ros_msgs/CMakeLists.txt @@ -10,6 +10,7 @@ find_package(catkin REQUIRED COMPONENTS ####################################### ## Declare ROS messages and services ## ####################################### +catkin_python_setup() add_message_files( DIRECTORY msg diff --git a/ifm3d_ros_msgs/bin/config b/ifm3d_ros_msgs/bin/config index ac5c29c..470fb17 100755 --- a/ifm3d_ros_msgs/bin/config +++ b/ifm3d_ros_msgs/bin/config @@ -6,7 +6,7 @@ import sys -from ifm3d import ConfigClient +from ifm3d_ros_utils import ConfigClient if __name__ == '__main__': sys.exit(ConfigClient().run()) diff --git a/ifm3d_ros_msgs/bin/dump b/ifm3d_ros_msgs/bin/dump index 2fd1789..396285c 100755 --- a/ifm3d_ros_msgs/bin/dump +++ b/ifm3d_ros_msgs/bin/dump @@ -6,7 +6,7 @@ import sys -from ifm3d import DumpClient +from ifm3d_ros_utils import DumpClient if __name__ == '__main__': sys.exit(DumpClient().run()) diff --git a/ifm3d_ros_driver/setup.py b/ifm3d_ros_msgs/setup.py similarity index 73% rename from ifm3d_ros_driver/setup.py rename to ifm3d_ros_msgs/setup.py index 3a020c2..412b54b 100644 --- a/ifm3d_ros_driver/setup.py +++ b/ifm3d_ros_msgs/setup.py @@ -3,8 +3,8 @@ # reads package.xml setup_args = generate_distutils_setup( - packages=['ifm3d'], - package_dir={'': 'pylib'}, + packages=['ifm3d_ros_utils'], + package_dir={'': 'utils'}, ) setup(**setup_args) diff --git a/ifm3d_ros_driver/pylib/ifm3d/_ConfigClient.py b/ifm3d_ros_msgs/utils/ifm3d_ros_utils/_ConfigClient.py similarity index 88% rename from ifm3d_ros_driver/pylib/ifm3d/_ConfigClient.py rename to ifm3d_ros_msgs/utils/ifm3d_ros_utils/_ConfigClient.py index f4cf455..1f5fbe1 100644 --- a/ifm3d_ros_driver/pylib/ifm3d/_ConfigClient.py +++ b/ifm3d_ros_msgs/utils/ifm3d_ros_utils/_ConfigClient.py @@ -9,10 +9,10 @@ import json import rospy import sys -from ifm3d.srv import Config +from ifm3d_ros_msgs.srv import Config SRV_TIMEOUT = 2.0 # seconds -SRV_NAME = "/ifm3d/camera/Config" +SRV_NAME = "/ifm3d_ros_examples/camera/Config" class ConfigClient(object): diff --git a/ifm3d_ros_driver/pylib/ifm3d/_DumpClient.py b/ifm3d_ros_msgs/utils/ifm3d_ros_utils/_DumpClient.py similarity index 91% rename from ifm3d_ros_driver/pylib/ifm3d/_DumpClient.py rename to ifm3d_ros_msgs/utils/ifm3d_ros_utils/_DumpClient.py index b16941a..3b45a8f 100644 --- a/ifm3d_ros_driver/pylib/ifm3d/_DumpClient.py +++ b/ifm3d_ros_msgs/utils/ifm3d_ros_utils/_DumpClient.py @@ -8,10 +8,10 @@ import json import rospy import sys -from ifm3d.srv import Dump +from ifm3d_ros_msgs.srv import Dump SRV_TIMEOUT = 2.0 # seconds -SRV_NAME = "/ifm3d/camera/Dump" +SRV_NAME = "/ifm3d_ros_examples/camera/Dump" class DumpClient(object): diff --git a/ifm3d_ros_driver/pylib/ifm3d/__init__.py b/ifm3d_ros_msgs/utils/ifm3d_ros_utils/__init__.py similarity index 100% rename from ifm3d_ros_driver/pylib/ifm3d/__init__.py rename to ifm3d_ros_msgs/utils/ifm3d_ros_utils/__init__.py From 4af2e6cdfcbb6638254e231a05f4b3bedcb55ae3 Mon Sep 17 00:00:00 2001 From: ifm-csr Date: Tue, 23 Nov 2021 16:30:14 +0000 Subject: [PATCH 5/6] add latest dev changes and fixes --- CHANGELOG.rst | 106 --- README.md | 46 -- ifm3d-ros/CMakeLists.txt | 5 - ifm3d-ros/LICENSE | 202 ------ ifm3d-ros/package.xml | 22 - ifm3d_ros_driver/.clang-format | 65 -- ifm3d_ros_driver/CMakeLists.txt | 84 --- ifm3d_ros_driver/LICENSE | 202 ------ ifm3d_ros_driver/README.md | 72 -- ifm3d_ros_driver/doc/building.md | 93 --- ifm3d_ros_driver/doc/distributed_build.md | 47 -- ifm3d_ros_driver/doc/dump_and_config.md | 286 -------- .../doc/figures/O3R_merged_point_cloud.png | Bin 763340 -> 0 bytes .../doc/figures/rviz_ref_frame.png | Bin 57878 -> 0 bytes ifm3d_ros_driver/doc/noetic.md | 64 -- ifm3d_ros_driver/doc/rpc_error_codes.md | 9 - ifm3d_ros_driver/doc/troubleshooting.md | 50 -- ifm3d_ros_driver/doc/visualization.md | 28 - .../include/ifm3d_ros_driver/camera_nodelet.h | 122 ---- ifm3d_ros_driver/launch/camera.launch | 31 - ifm3d_ros_driver/launch/nodelet.launch | 117 ---- ifm3d_ros_driver/nodelets.xml | 10 - ifm3d_ros_driver/package.xml | 31 - ifm3d_ros_driver/src/camera_nodelet.cpp | 628 ------------------ ifm3d_ros_driver/test/gradient.jpg | Bin 1363 -> 0 bytes ifm3d_ros_driver/test/ifm3d.test | 6 - ifm3d_ros_driver/test/test_camera.py | 240 ------- ifm3d_ros_driver/test/test_threshold.py | 41 -- ifm3d_ros_examples/CMakeLists.txt | 19 - ifm3d_ros_examples/LICENSE | 202 ------ ifm3d_ros_examples/README.md | 41 -- ifm3d_ros_examples/config/rviz_config.rviz | 184 ----- .../examples/README_pointcloud_merge.md | 6 - ifm3d_ros_examples/examples/dump.json | 338 ---------- ifm3d_ros_examples/launch/camera.launch | 31 - ifm3d_ros_examples/launch/dump_merge_pc.json | 338 ---------- ifm3d_ros_examples/launch/four_cameras.launch | 110 --- ifm3d_ros_examples/launch/head.launch | 60 -- ifm3d_ros_examples/launch/merge_pc.launch | 147 ---- ifm3d_ros_examples/launch/nodelet.launch | 117 ---- ifm3d_ros_examples/launch/rviz.launch | 12 - ifm3d_ros_examples/launch/six_cameras.launch | 156 ----- ifm3d_ros_examples/package.xml | 21 - ifm3d_ros_msgs/CMakeLists.txt | 55 -- ifm3d_ros_msgs/README.md | 24 - ifm3d_ros_msgs/bin/config | 12 - ifm3d_ros_msgs/bin/dump | 12 - ifm3d_ros_msgs/msg/Extrinsics.msg | 11 - ifm3d_ros_msgs/package.xml | 26 - ifm3d_ros_msgs/setup.py | 10 - ifm3d_ros_msgs/srv/Config.srv | 4 - ifm3d_ros_msgs/srv/Dump.srv | 3 - ifm3d_ros_msgs/srv/SoftOff.srv | 3 - ifm3d_ros_msgs/srv/SoftOn.srv | 3 - ifm3d_ros_msgs/srv/SyncClocks.srv | 3 - ifm3d_ros_msgs/srv/Trigger.srv | 3 - .../utils/ifm3d_ros_utils/_ConfigClient.py | 30 - .../utils/ifm3d_ros_utils/_DumpClient.py | 33 - .../utils/ifm3d_ros_utils/__init__.py | 5 - 59 files changed, 4626 deletions(-) delete mode 100644 CHANGELOG.rst delete mode 100644 README.md delete mode 100644 ifm3d-ros/CMakeLists.txt delete mode 100644 ifm3d-ros/LICENSE delete mode 100644 ifm3d-ros/package.xml delete mode 100644 ifm3d_ros_driver/.clang-format delete mode 100644 ifm3d_ros_driver/CMakeLists.txt delete mode 100644 ifm3d_ros_driver/LICENSE delete mode 100644 ifm3d_ros_driver/README.md delete mode 100644 ifm3d_ros_driver/doc/building.md delete mode 100644 ifm3d_ros_driver/doc/distributed_build.md delete mode 100644 ifm3d_ros_driver/doc/dump_and_config.md delete mode 100644 ifm3d_ros_driver/doc/figures/O3R_merged_point_cloud.png delete mode 100644 ifm3d_ros_driver/doc/figures/rviz_ref_frame.png delete mode 100644 ifm3d_ros_driver/doc/noetic.md delete mode 100644 ifm3d_ros_driver/doc/rpc_error_codes.md delete mode 100644 ifm3d_ros_driver/doc/troubleshooting.md delete mode 100644 ifm3d_ros_driver/doc/visualization.md delete mode 100644 ifm3d_ros_driver/include/ifm3d_ros_driver/camera_nodelet.h delete mode 100644 ifm3d_ros_driver/launch/camera.launch delete mode 100644 ifm3d_ros_driver/launch/nodelet.launch delete mode 100644 ifm3d_ros_driver/nodelets.xml delete mode 100644 ifm3d_ros_driver/package.xml delete mode 100644 ifm3d_ros_driver/src/camera_nodelet.cpp delete mode 100644 ifm3d_ros_driver/test/gradient.jpg delete mode 100644 ifm3d_ros_driver/test/ifm3d.test delete mode 100755 ifm3d_ros_driver/test/test_camera.py delete mode 100644 ifm3d_ros_driver/test/test_threshold.py delete mode 100644 ifm3d_ros_examples/CMakeLists.txt delete mode 100644 ifm3d_ros_examples/LICENSE delete mode 100644 ifm3d_ros_examples/README.md delete mode 100644 ifm3d_ros_examples/config/rviz_config.rviz delete mode 100644 ifm3d_ros_examples/examples/README_pointcloud_merge.md delete mode 100644 ifm3d_ros_examples/examples/dump.json delete mode 100644 ifm3d_ros_examples/launch/camera.launch delete mode 100644 ifm3d_ros_examples/launch/dump_merge_pc.json delete mode 100644 ifm3d_ros_examples/launch/four_cameras.launch delete mode 100644 ifm3d_ros_examples/launch/head.launch delete mode 100644 ifm3d_ros_examples/launch/merge_pc.launch delete mode 100644 ifm3d_ros_examples/launch/nodelet.launch delete mode 100644 ifm3d_ros_examples/launch/rviz.launch delete mode 100644 ifm3d_ros_examples/launch/six_cameras.launch delete mode 100644 ifm3d_ros_examples/package.xml delete mode 100644 ifm3d_ros_msgs/CMakeLists.txt delete mode 100644 ifm3d_ros_msgs/README.md delete mode 100755 ifm3d_ros_msgs/bin/config delete mode 100755 ifm3d_ros_msgs/bin/dump delete mode 100644 ifm3d_ros_msgs/msg/Extrinsics.msg delete mode 100644 ifm3d_ros_msgs/package.xml delete mode 100644 ifm3d_ros_msgs/setup.py delete mode 100644 ifm3d_ros_msgs/srv/Config.srv delete mode 100644 ifm3d_ros_msgs/srv/Dump.srv delete mode 100644 ifm3d_ros_msgs/srv/SoftOff.srv delete mode 100644 ifm3d_ros_msgs/srv/SoftOn.srv delete mode 100644 ifm3d_ros_msgs/srv/SyncClocks.srv delete mode 100644 ifm3d_ros_msgs/srv/Trigger.srv delete mode 100644 ifm3d_ros_msgs/utils/ifm3d_ros_utils/_ConfigClient.py delete mode 100644 ifm3d_ros_msgs/utils/ifm3d_ros_utils/_DumpClient.py delete mode 100644 ifm3d_ros_msgs/utils/ifm3d_ros_utils/__init__.py diff --git a/CHANGELOG.rst b/CHANGELOG.rst deleted file mode 100644 index cd57f27..0000000 --- a/CHANGELOG.rst +++ /dev/null @@ -1,106 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package ifm3d-ros -^^^^^^^^^^^^^^^^^^^^^^^^^ - -1.0 -=== - -1.0.0 ------- - -Braking changes: -+ Restructure the ifm3d-ros package into independent subpackages. Please check your path declarations again, especially for the launch files and messages and services. - -Changes between ifm3d_ros 0.6.x and 1.0.0: -+ Order of axis changed in 3D (cloud topic and extrinsic calibration parameters): This wrapper keeps the axis orientation as defined by the underlying API, ifm3d. Therefore, you may see a different axis order for the cloud message compared to older versions of the ifm3d and ifm cameras. -+ Extrinsic calibration parameters: now conistent with SI units, e.g. translation are scaled in `m` and rotation parameters are scaled in `rad`. -+ Added publisher for 2D RGB data -+ Use CameraBase for compatibility with other O3 devices -+ Comment out methods / publisher which are not available for the O3RCamera (at the moment) -+ Comment out the unit vector publishing -+ Changed services trigger and softon, softoff to be compatible with new JSON methods and schema. -+ Changed service trigger to a dummy method until triggers are implemented for the O3R platform. It only has a status message at the moment. -+ Changed service dump: coverts from json to str for displaying the message - -added: -+ Added pcic_port to the list of framegrabber arguments - -known limitations: -+ This version of the ifm3d-ros package only works with the O3R camera platform. - - -0.6 -=== - -0.6.2 ------ -Changes between ifm3d_ros 0.6.1 and 0.6.2 - -* Updated maintainer email address -* Added ifm3d-core dependency in preparation for submission to the ROS index - -0.6.1 ------ - -* Added support syncing the system and camera clocks at startup. Side-effect, - is we can now stamp the images with the camera-side capture time and not the - host-side reception time. -* Added the `SyncClocks` Service - -0.6.0. ------- - -* Added a image transport plugin _blacklist_ to the nodlet launch file. This - prevents many of the errors seen in the terminal when running `rosbag -a` to - capture camera data -* Added the `SoftOn` and `SoftOff` service calls - -0.5 -=== - - -0.5.1 ------ - -* Added support for Ubuntu 18.04 and ROS Melodic - -0.5.0 ------ - -* Converted primary data publisher to a nodelet architecture -* Provide the `dump` and `config` scripts to call into the exposed ROS services - of the nodelet. Removed the older "config node". -* Added unit tests - -0.4 -=== - -0.4.2 ------ - -* Now requires ifm3d 0.9.0 and by association the more modernized tooling - (C++14, cmake 3.5, dropped support for 14.04/Indigo, etc.) - -0.4.1 ------ - -* Now publishing extrinsics on a topic - -0.3 -=== - -* Added `Dump` Service -* Added `Config` Service -* Added `Trigger` Service - -0.2 -=== - -* Updates to CMakeLists.txt to support Ubuntu 14.04 and ROS Indigo - -0.1 -=== - -This file has started tracking ifm3d_ros at 0.1.0 - -* Initial (alpha) release diff --git a/README.md b/README.md deleted file mode 100644 index 9dfbc46..0000000 --- a/README.md +++ /dev/null @@ -1,46 +0,0 @@ -# ifm3d-ros wrapper around the ifm3d library - -# Release versions - -:warning: Note that the `v1.0.x` branch is generally in a work in progress state, and you probably want to use a tagged [release version](https://github.com/ifm/ifm3d-ros/releases) for production. - -## ifm3d-ros for the O3R - -**NOTE: The ifm3d-ros package has had major changes recently. Please be aware that this might cause problems on your system for building pipelines based on our old build instructions.** -We tried to ensure backward compatibility where ever possible. If you find any major breaks, please let us know. - - -ifm3d-ros is a wrapper around [ifm3d](https://github.com/ifm/ifm3d/) enabling the usage of the O3R camera platform (ifm ToF cameras) from within [ROS](http://ros.org) software systems. - -![rviz1](ifm3d_ros_driver/doc/figures/O3R_merged_point_cloud.png) - -## Software Compatibility Matrix - -|**ifm3d-ros version**|**ifm3d version**|**ROS distribution(s)**| -| ------------ | ------------ | ------------ | -| 1.0.0 | in development - latest version checked 0.91.0 | Noetic | - -### Internal ifm3d-ros subpackage version structure -Please see the internal subpackage version structure for a known `ifm3d-ros version`. - -|**ifm3d-ros version**|**ifm3d_ros_driver**|**ifm3d_ros_msgs**|**ifm3d_ros_examples**| -| ------------ | ------------ | ------------ | ------------ | -| 1.0.0 | 0.7.0 | 0.1.0 | 0.1.0 | - -## Organization of the software - -The `ifm3d-ros` meta package provides three subpackages: -- `ifm3d_ros_driver` provides the core interface for receiving data for ifm 3d (O3R) cameras. -- `ifm3d_ros_msgs` gathers the ifm-specific messages types and the services for configuring and triggering the camera. -- `ifm3d_ros_examples` provides additional helper scripts and examples. - -The name `ifm3d-ros` was kept even tough this is not consistent with ROS package naming conventions. -This ROS package has been split into three sub packages in an effort to facilitate dependency handling on distributed systems and simplify deployment on embedded platforms. For instance, the package `ifm3d_ros_msgs` can be installed independently of the other packages to control the camera from a separate computing platform. The `ifm3d_ros_examples` holds our launch files and examples. - -## Building and installing the software - -1. Preparing your system: [Noetic](ifm3d_ros_driver/doc/noetic.md) -2. [Installing the ifm3d-ros node](ifm3d_ros_driver/doc/building.md) - -# LICENSE -Please see the file called [LICENSE](LICENSE). \ No newline at end of file diff --git a/ifm3d-ros/CMakeLists.txt b/ifm3d-ros/CMakeLists.txt deleted file mode 100644 index 5a82652..0000000 --- a/ifm3d-ros/CMakeLists.txt +++ /dev/null @@ -1,5 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(ifm3d-ros) -find_package(catkin REQUIRED) -catkin_metapackage() - diff --git a/ifm3d-ros/LICENSE b/ifm3d-ros/LICENSE deleted file mode 100644 index 7a4a3ea..0000000 --- a/ifm3d-ros/LICENSE +++ /dev/null @@ -1,202 +0,0 @@ - - Apache License - Version 2.0, January 2004 - http://www.apache.org/licenses/ - - TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION - - 1. Definitions. - - "License" shall mean the terms and conditions for use, reproduction, - and distribution as defined by Sections 1 through 9 of this document. - - "Licensor" shall mean the copyright owner or entity authorized by - the copyright owner that is granting the License. - - "Legal Entity" shall mean the union of the acting entity and all - other entities that control, are controlled by, or are under common - control with that entity. For the purposes of this definition, - "control" means (i) the power, direct or indirect, to cause the - direction or management of such entity, whether by contract or - otherwise, or (ii) ownership of fifty percent (50%) or more of the - outstanding shares, or (iii) beneficial ownership of such entity. - - "You" (or "Your") shall mean an individual or Legal Entity - exercising permissions granted by this License. - - "Source" form shall mean the preferred form for making modifications, - including but not limited to software source code, documentation - source, and configuration files. - - "Object" form shall mean any form resulting from mechanical - transformation or translation of a Source form, including but - not limited to compiled object code, generated documentation, - and conversions to other media types. - - "Work" shall mean the work of authorship, whether in Source or - Object form, made available under the License, as indicated by a - copyright notice that is included in or attached to the work - (an example is provided in the Appendix below). - - "Derivative Works" shall mean any work, whether in Source or Object - form, that is based on (or derived from) the Work and for which the - editorial revisions, annotations, elaborations, or other modifications - represent, as a whole, an original work of authorship. For the purposes - of this License, Derivative Works shall not include works that remain - separable from, or merely link (or bind by name) to the interfaces of, - the Work and Derivative Works thereof. - - "Contribution" shall mean any work of authorship, including - the original version of the Work and any modifications or additions - to that Work or Derivative Works thereof, that is intentionally - submitted to Licensor for inclusion in the Work by the copyright owner - or by an individual or Legal Entity authorized to submit on behalf of - the copyright owner. For the purposes of this definition, "submitted" - means any form of electronic, verbal, or written communication sent - to the Licensor or its representatives, including but not limited to - communication on electronic mailing lists, source code control systems, - and issue tracking systems that are managed by, or on behalf of, the - Licensor for the purpose of discussing and improving the Work, but - excluding communication that is conspicuously marked or otherwise - designated in writing by the copyright owner as "Not a Contribution." - - "Contributor" shall mean Licensor and any individual or Legal Entity - on behalf of whom a Contribution has been received by Licensor and - subsequently incorporated within the Work. - - 2. Grant of Copyright License. Subject to the terms and conditions of - this License, each Contributor hereby grants to You a perpetual, - worldwide, non-exclusive, no-charge, royalty-free, irrevocable - copyright license to reproduce, prepare Derivative Works of, - publicly display, publicly perform, sublicense, and distribute the - Work and such Derivative Works in Source or Object form. - - 3. Grant of Patent License. Subject to the terms and conditions of - this License, each Contributor hereby grants to You a perpetual, - worldwide, non-exclusive, no-charge, royalty-free, irrevocable - (except as stated in this section) patent license to make, have made, - use, offer to sell, sell, import, and otherwise transfer the Work, - where such license applies only to those patent claims licensable - by such Contributor that are necessarily infringed by their - Contribution(s) alone or by combination of their Contribution(s) - with the Work to which such Contribution(s) was submitted. If You - institute patent litigation against any entity (including a - cross-claim or counterclaim in a lawsuit) alleging that the Work - or a Contribution incorporated within the Work constitutes direct - or contributory patent infringement, then any patent licenses - granted to You under this License for that Work shall terminate - as of the date such litigation is filed. - - 4. Redistribution. You may reproduce and distribute copies of the - Work or Derivative Works thereof in any medium, with or without - modifications, and in Source or Object form, provided that You - meet the following conditions: - - (a) You must give any other recipients of the Work or - Derivative Works a copy of this License; and - - (b) You must cause any modified files to carry prominent notices - stating that You changed the files; and - - (c) You must retain, in the Source form of any Derivative Works - that You distribute, all copyright, patent, trademark, and - attribution notices from the Source form of the Work, - excluding those notices that do not pertain to any part of - the Derivative Works; and - - (d) If the Work includes a "NOTICE" text file as part of its - distribution, then any Derivative Works that You distribute must - include a readable copy of the attribution notices contained - within such NOTICE file, excluding those notices that do not - pertain to any part of the Derivative Works, in at least one - of the following places: within a NOTICE text file distributed - as part of the Derivative Works; within the Source form or - documentation, if provided along with the Derivative Works; or, - within a display generated by the Derivative Works, if and - wherever such third-party notices normally appear. The contents - of the NOTICE file are for informational purposes only and - do not modify the License. You may add Your own attribution - notices within Derivative Works that You distribute, alongside - or as an addendum to the NOTICE text from the Work, provided - that such additional attribution notices cannot be construed - as modifying the License. - - You may add Your own copyright statement to Your modifications and - may provide additional or different license terms and conditions - for use, reproduction, or distribution of Your modifications, or - for any such Derivative Works as a whole, provided Your use, - reproduction, and distribution of the Work otherwise complies with - the conditions stated in this License. - - 5. Submission of Contributions. Unless You explicitly state otherwise, - any Contribution intentionally submitted for inclusion in the Work - by You to the Licensor shall be under the terms and conditions of - this License, without any additional terms or conditions. - Notwithstanding the above, nothing herein shall supersede or modify - the terms of any separate license agreement you may have executed - with Licensor regarding such Contributions. - - 6. Trademarks. This License does not grant permission to use the trade - names, trademarks, service marks, or product names of the Licensor, - except as required for reasonable and customary use in describing the - origin of the Work and reproducing the content of the NOTICE file. - - 7. Disclaimer of Warranty. Unless required by applicable law or - agreed to in writing, Licensor provides the Work (and each - Contributor provides its Contributions) on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or - implied, including, without limitation, any warranties or conditions - of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A - PARTICULAR PURPOSE. You are solely responsible for determining the - appropriateness of using or redistributing the Work and assume any - risks associated with Your exercise of permissions under this License. - - 8. Limitation of Liability. In no event and under no legal theory, - whether in tort (including negligence), contract, or otherwise, - unless required by applicable law (such as deliberate and grossly - negligent acts) or agreed to in writing, shall any Contributor be - liable to You for damages, including any direct, indirect, special, - incidental, or consequential damages of any character arising as a - result of this License or out of the use or inability to use the - Work (including but not limited to damages for loss of goodwill, - work stoppage, computer failure or malfunction, or any and all - other commercial damages or losses), even if such Contributor - has been advised of the possibility of such damages. - - 9. Accepting Warranty or Additional Liability. While redistributing - the Work or Derivative Works thereof, You may choose to offer, - and charge a fee for, acceptance of support, warranty, indemnity, - or other liability obligations and/or rights consistent with this - License. However, in accepting such obligations, You may act only - on Your own behalf and on Your sole responsibility, not on behalf - of any other Contributor, and only if You agree to indemnify, - defend, and hold each Contributor harmless for any liability - incurred by, or claims asserted against, such Contributor by reason - of your accepting any such warranty or additional liability. - - END OF TERMS AND CONDITIONS - - APPENDIX: How to apply the Apache License to your work. - - To apply the Apache License to your work, attach the following - boilerplate notice, with the fields enclosed by brackets "[]" - replaced with your own identifying information. (Don't include - the brackets!) The text should be enclosed in the appropriate - comment syntax for the file format. We also recommend that a - file or class name and description of purpose be included on the - same "printed page" as the copyright notice for easier - identification within third-party archives. - - Copyright [yyyy] [name of copyright owner] - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - http://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. \ No newline at end of file diff --git a/ifm3d-ros/package.xml b/ifm3d-ros/package.xml deleted file mode 100644 index 49527c2..0000000 --- a/ifm3d-ros/package.xml +++ /dev/null @@ -1,22 +0,0 @@ - - - - ifm3d-ros - 1.0.0 - metapackage for the ifm3d-ros package group which interacts with the ifm 3D ToF Camera ROS package - ifm CSR group - Apache 2 - CSR ifm sytron - - https://github.com/ifm/ifm3d-ros/ - - catkin - ifm3d_ros_driver - ifm3d_ros_examples - ifm3d_ros_msgs - - - - - - diff --git a/ifm3d_ros_driver/.clang-format b/ifm3d_ros_driver/.clang-format deleted file mode 100644 index 817fd6d..0000000 --- a/ifm3d_ros_driver/.clang-format +++ /dev/null @@ -1,65 +0,0 @@ ---- -BasedOnStyle: Google -AccessModifierOffset: -2 -ConstructorInitializerIndentWidth: 2 -AlignEscapedNewlinesLeft: false -AlignTrailingComments: true -AllowAllParametersOfDeclarationOnNextLine: false -AllowShortIfStatementsOnASingleLine: false -AllowShortLoopsOnASingleLine: false -AllowShortFunctionsOnASingleLine: None -AlwaysBreakTemplateDeclarations: true -AlwaysBreakBeforeMultilineStrings: true -BreakBeforeBinaryOperators: false -BreakBeforeTernaryOperators: false -BreakConstructorInitializersBeforeComma: true -BinPackParameters: true -ColumnLimit: 120 -ConstructorInitializerAllOnOneLineOrOnePerLine: true -DerivePointerBinding: false -PointerBindsToType: true -ExperimentalAutoDetectBinPacking: false -IndentCaseLabels: true -MaxEmptyLinesToKeep: 1 -NamespaceIndentation: None -ObjCSpaceBeforeProtocolList: true -PenaltyBreakBeforeFirstCallParameter: 19 -PenaltyBreakComment: 60 -PenaltyBreakString: 1 -PenaltyBreakFirstLessLess: 1000 -PenaltyExcessCharacter: 1000 -PenaltyReturnTypeOnItsOwnLine: 90 -SpacesBeforeTrailingComments: 2 -Cpp11BracedListStyle: false -Standard: Auto -IndentWidth: 2 -TabWidth: 2 -UseTab: Never -IndentFunctionDeclarationAfterType: false -SpacesInParentheses: false -SpacesInAngles: false -SpaceInEmptyParentheses: false -SpacesInCStyleCastParentheses: false -SpaceAfterControlStatementKeyword: true -SpaceBeforeAssignmentOperators: true -ContinuationIndentWidth: 4 -SortIncludes: false -SpaceAfterCStyleCast: false - -# Configure each individual brace in BraceWrapping -BreakBeforeBraces: Custom - -# Control of individual brace wrapping cases -BraceWrapping: { - AfterClass: 'true' - AfterControlStatement: 'true' - AfterEnum : 'true' - AfterFunction : 'true' - AfterNamespace : 'true' - AfterStruct : 'true' - AfterUnion : 'true' - BeforeCatch : 'true' - BeforeElse : 'true' - IndentBraces : 'false' -} -... diff --git a/ifm3d_ros_driver/CMakeLists.txt b/ifm3d_ros_driver/CMakeLists.txt deleted file mode 100644 index 634c40c..0000000 --- a/ifm3d_ros_driver/CMakeLists.txt +++ /dev/null @@ -1,84 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(ifm3d_ros_driver) - -find_package(ifm3d REQUIRED COMPONENTS - camera - framegrabber - image - ) - -find_package(catkin REQUIRED COMPONENTS - rospy - image_transport - pcl_ros - cv_bridge - nodelet - roscpp - sensor_msgs - std_msgs - message_runtime - rostest - ifm3d_ros_msgs - ) - -# catkin_python_setup() - -option(CATKIN_ENABLE_TESTING "Build tests" OFF) - -################################### -## catkin specific configuration ## -################################### -catkin_package( - INCLUDE_DIRS include - LIBRARIES ifm3d_ros - CATKIN_DEPENDS roscpp nodelet - ) - -############# -## Build ## -############# -set(CMAKE_CXX_EXTENSIONS OFF) -set(CMAKE_CXX_STANDARD 14) -set(CMAKE_CXX_STANDARD_REQUIRED true) - -include_directories( - include - ${catkin_INCLUDE_DIRS} - ) - -add_library(ifm3d_ros src/camera_nodelet.cpp) -target_link_libraries(ifm3d_ros - ${catkin_LIBRARIES} - ifm3d::camera - ifm3d::framegrabber - ifm3d::image - ) - -############# -## Install ## -############# - -install(TARGETS - ifm3d_ros - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} - ) - -install(DIRECTORY - include/${PROJECT_NAME}/ - DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} - ) - -install(FILES nodelets.xml - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} - ) - -###################### -## Node-level tests ## -###################### - -if (CATKIN_ENABLE_TESTING) - add_rostest(test/ifm3d.test) - catkin_add_nosetests(test) -endif() diff --git a/ifm3d_ros_driver/LICENSE b/ifm3d_ros_driver/LICENSE deleted file mode 100644 index 7a4a3ea..0000000 --- a/ifm3d_ros_driver/LICENSE +++ /dev/null @@ -1,202 +0,0 @@ - - Apache License - Version 2.0, January 2004 - http://www.apache.org/licenses/ - - TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION - - 1. Definitions. - - "License" shall mean the terms and conditions for use, reproduction, - and distribution as defined by Sections 1 through 9 of this document. - - "Licensor" shall mean the copyright owner or entity authorized by - the copyright owner that is granting the License. - - "Legal Entity" shall mean the union of the acting entity and all - other entities that control, are controlled by, or are under common - control with that entity. For the purposes of this definition, - "control" means (i) the power, direct or indirect, to cause the - direction or management of such entity, whether by contract or - otherwise, or (ii) ownership of fifty percent (50%) or more of the - outstanding shares, or (iii) beneficial ownership of such entity. - - "You" (or "Your") shall mean an individual or Legal Entity - exercising permissions granted by this License. - - "Source" form shall mean the preferred form for making modifications, - including but not limited to software source code, documentation - source, and configuration files. - - "Object" form shall mean any form resulting from mechanical - transformation or translation of a Source form, including but - not limited to compiled object code, generated documentation, - and conversions to other media types. - - "Work" shall mean the work of authorship, whether in Source or - Object form, made available under the License, as indicated by a - copyright notice that is included in or attached to the work - (an example is provided in the Appendix below). - - "Derivative Works" shall mean any work, whether in Source or Object - form, that is based on (or derived from) the Work and for which the - editorial revisions, annotations, elaborations, or other modifications - represent, as a whole, an original work of authorship. For the purposes - of this License, Derivative Works shall not include works that remain - separable from, or merely link (or bind by name) to the interfaces of, - the Work and Derivative Works thereof. - - "Contribution" shall mean any work of authorship, including - the original version of the Work and any modifications or additions - to that Work or Derivative Works thereof, that is intentionally - submitted to Licensor for inclusion in the Work by the copyright owner - or by an individual or Legal Entity authorized to submit on behalf of - the copyright owner. For the purposes of this definition, "submitted" - means any form of electronic, verbal, or written communication sent - to the Licensor or its representatives, including but not limited to - communication on electronic mailing lists, source code control systems, - and issue tracking systems that are managed by, or on behalf of, the - Licensor for the purpose of discussing and improving the Work, but - excluding communication that is conspicuously marked or otherwise - designated in writing by the copyright owner as "Not a Contribution." - - "Contributor" shall mean Licensor and any individual or Legal Entity - on behalf of whom a Contribution has been received by Licensor and - subsequently incorporated within the Work. - - 2. Grant of Copyright License. Subject to the terms and conditions of - this License, each Contributor hereby grants to You a perpetual, - worldwide, non-exclusive, no-charge, royalty-free, irrevocable - copyright license to reproduce, prepare Derivative Works of, - publicly display, publicly perform, sublicense, and distribute the - Work and such Derivative Works in Source or Object form. - - 3. Grant of Patent License. Subject to the terms and conditions of - this License, each Contributor hereby grants to You a perpetual, - worldwide, non-exclusive, no-charge, royalty-free, irrevocable - (except as stated in this section) patent license to make, have made, - use, offer to sell, sell, import, and otherwise transfer the Work, - where such license applies only to those patent claims licensable - by such Contributor that are necessarily infringed by their - Contribution(s) alone or by combination of their Contribution(s) - with the Work to which such Contribution(s) was submitted. If You - institute patent litigation against any entity (including a - cross-claim or counterclaim in a lawsuit) alleging that the Work - or a Contribution incorporated within the Work constitutes direct - or contributory patent infringement, then any patent licenses - granted to You under this License for that Work shall terminate - as of the date such litigation is filed. - - 4. Redistribution. You may reproduce and distribute copies of the - Work or Derivative Works thereof in any medium, with or without - modifications, and in Source or Object form, provided that You - meet the following conditions: - - (a) You must give any other recipients of the Work or - Derivative Works a copy of this License; and - - (b) You must cause any modified files to carry prominent notices - stating that You changed the files; and - - (c) You must retain, in the Source form of any Derivative Works - that You distribute, all copyright, patent, trademark, and - attribution notices from the Source form of the Work, - excluding those notices that do not pertain to any part of - the Derivative Works; and - - (d) If the Work includes a "NOTICE" text file as part of its - distribution, then any Derivative Works that You distribute must - include a readable copy of the attribution notices contained - within such NOTICE file, excluding those notices that do not - pertain to any part of the Derivative Works, in at least one - of the following places: within a NOTICE text file distributed - as part of the Derivative Works; within the Source form or - documentation, if provided along with the Derivative Works; or, - within a display generated by the Derivative Works, if and - wherever such third-party notices normally appear. The contents - of the NOTICE file are for informational purposes only and - do not modify the License. You may add Your own attribution - notices within Derivative Works that You distribute, alongside - or as an addendum to the NOTICE text from the Work, provided - that such additional attribution notices cannot be construed - as modifying the License. - - You may add Your own copyright statement to Your modifications and - may provide additional or different license terms and conditions - for use, reproduction, or distribution of Your modifications, or - for any such Derivative Works as a whole, provided Your use, - reproduction, and distribution of the Work otherwise complies with - the conditions stated in this License. - - 5. Submission of Contributions. Unless You explicitly state otherwise, - any Contribution intentionally submitted for inclusion in the Work - by You to the Licensor shall be under the terms and conditions of - this License, without any additional terms or conditions. - Notwithstanding the above, nothing herein shall supersede or modify - the terms of any separate license agreement you may have executed - with Licensor regarding such Contributions. - - 6. Trademarks. This License does not grant permission to use the trade - names, trademarks, service marks, or product names of the Licensor, - except as required for reasonable and customary use in describing the - origin of the Work and reproducing the content of the NOTICE file. - - 7. Disclaimer of Warranty. Unless required by applicable law or - agreed to in writing, Licensor provides the Work (and each - Contributor provides its Contributions) on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or - implied, including, without limitation, any warranties or conditions - of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A - PARTICULAR PURPOSE. You are solely responsible for determining the - appropriateness of using or redistributing the Work and assume any - risks associated with Your exercise of permissions under this License. - - 8. Limitation of Liability. In no event and under no legal theory, - whether in tort (including negligence), contract, or otherwise, - unless required by applicable law (such as deliberate and grossly - negligent acts) or agreed to in writing, shall any Contributor be - liable to You for damages, including any direct, indirect, special, - incidental, or consequential damages of any character arising as a - result of this License or out of the use or inability to use the - Work (including but not limited to damages for loss of goodwill, - work stoppage, computer failure or malfunction, or any and all - other commercial damages or losses), even if such Contributor - has been advised of the possibility of such damages. - - 9. Accepting Warranty or Additional Liability. While redistributing - the Work or Derivative Works thereof, You may choose to offer, - and charge a fee for, acceptance of support, warranty, indemnity, - or other liability obligations and/or rights consistent with this - License. However, in accepting such obligations, You may act only - on Your own behalf and on Your sole responsibility, not on behalf - of any other Contributor, and only if You agree to indemnify, - defend, and hold each Contributor harmless for any liability - incurred by, or claims asserted against, such Contributor by reason - of your accepting any such warranty or additional liability. - - END OF TERMS AND CONDITIONS - - APPENDIX: How to apply the Apache License to your work. - - To apply the Apache License to your work, attach the following - boilerplate notice, with the fields enclosed by brackets "[]" - replaced with your own identifying information. (Don't include - the brackets!) The text should be enclosed in the appropriate - comment syntax for the file format. We also recommend that a - file or class name and description of purpose be included on the - same "printed page" as the copyright notice for easier - identification within third-party archives. - - Copyright [yyyy] [name of copyright owner] - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - http://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. \ No newline at end of file diff --git a/ifm3d_ros_driver/README.md b/ifm3d_ros_driver/README.md deleted file mode 100644 index bf05705..0000000 --- a/ifm3d_ros_driver/README.md +++ /dev/null @@ -1,72 +0,0 @@ -# The `ifm3d_ros_driver` package - -## ROS Interface - -The core `ifm3d-ros` sensor interface is implemented as a ROS nodelet. This allows for lower-latency data processing vs. the traditional out-of-process node-based ROS interface for applications that require it. However, we ship a launch file with this package that allows for using the core `ifm3d-ros` driver as a standard node. To launch the node, the following command can be used: - -``` -$ roslaunch ifm3d_ros_examples camera.launch -``` ->Note: Please notice the use of the subpackage `ifm3d_ros_examples`. - -For further information about the internal ROS nodelet infrastructure and how to apply this to your application, please see our exemplary launch files and a short run down on the nodelet structure in the [ifm3d_ros_examples/README](../ifm3d_ros_examples/README.md). - -### Nodelet - parameters - -| Name | Data Type | Default Value | Description | -| ---- | ---- | ---- | ---- | -| ~assume_sw_triggered | bool | false | This provides a hint to the driver that the camera is configured for software triggering (as opposed to free running). In this mode, certain default values are applied to lessen the noise in terms of timeouts from the frame grabber.| -| ~frame_id_base |string |ifm3d/camera | This string provides a prefix into the `tf` tree for `ifm3d_ros` coordinate frames. | -| ~frame_latency_thresh | float | 60.0 | Time (seconds) used to determine that timestamps from the camera cannot be trusted. When this threshold is exceeded, when compared to system time, we use the reception time of the frame and not the capture time of the frame. | -| ~ip | string | 192.168.0.69 | The IP address of the VPU. | -| ~password | string | "" | The password required to establish an edit session on the VPU | -| ~schema_mask | uint16 | 0xf | The pcic schema mask to apply to the active session with the frame grabber. This determines which images are available for publication from the camera. More about pcic schemas can be gleaned from the [ifm3d projects documentation](https://www.ifm3d.com). | -| ~timeout_millis | int | 500 | The number of milliseconds to wait for the framegrabber to return new frame data before declaring a "timeout" and to stop blocking on new data. | -| ~timeout_tolerance_secs |float | 5.0 | The wall time to wait with no new data from the camera before trying to establish a new connection to the camera. This helps to providerobustness against camera cables becoming unplugged or other in-field pathologies which would cause the connection between the ROS node and the camera to be broken. | -| ~sync_clocks DEPRECATED | bool | false | Attempt to sync the camera clock to the system clock at start-up. The side-effect is that timestamps on the image should reflect the capture time as opposed to the receipt time. | -| ~xmlrpc_port | unint16 | 80 | The TCP port the camera's xmlrpc server is listening on for requests. | -| ~pcic_port | unint16 | 50010 | The TCP (data) port the camera's pcic server is listening on for requests. | - - -### Nodelet - published Topics - -| Name | Data Type | Description | -| --- | --- | --- | -| amplitude | sensor_msgs/Image | The normalized amplitude image. | -| confidence | sensor_msgs/Image | The confidence image. | -| cloud | sensor_msgs/PointCloud2 | The point cloud data, i.e. X-, Y-, Z-coordinates. | -| distance | sensor_msgs/Image | The radial distance image. | -| raw_amplitude | sensor_msgs/Image | The raw (non normalized) amplitude image. | -| good_bad_pixels | sensor_msgs/Image | The binary image representation of the confidence image. | -| xyz_imaege | sensor_msgs/Image | A 3-channel image encoding of the point cloud. Each of the three image channels represents a spatial data plane encoding the x, y, z Cartesian values respectively. | -| unit_vectors | sensor_msgs/Image | The rotated unit vectors. | -| extrinsics | ifm3d/Extrinsics | The extrinsic calibration of the camera with respect to the camera optical frame. This 3D pose is encoded in mm and rad. | - ->Note: Some topics may have empty data fields. We are working on publishing data on all available topics, but have kept all previous topics active for the moment for legacy reasons. - -### Nodelet - subscribed Topics -None. - -### Nodelet - advertised Services -> Note: the services are provided by the `ifm3d_ros_msgs` package. - -| Name | Service Definition | Description | -| ---- | ---- | ---- | -| Dump | ifm3d/Dump | Dumps the state of the camera system as a JSON (formatted as a string) | -| Config | ifm3d/Config | Provides a means to configure the VPU and Heads (imager settings), declaratively from a JSON (string) encoding of the desired settings. | -| SoftOff | ifm3d/SoftOff | Sets the active application of the camera into software triggered mode which will turn off the active illumination reducing both power and heat. | -| SoftOn | ifm3d/SoftOn | Sets the active application of the camera into free-running mode. Its intention is to act as the inverse of `SoftOff`. | -| Trigger | ifm3d/Trigger | Requests the driver to software trigger the imager for data acquisition. | - -### Known limitations -[![O3R](https://img.shields.io/badge/O3R-lightgrey.svg)]() -[![O3D](https://img.shields.io/badge/O3D-green.svg)]() -[![O3X](https://img.shields.io/badge/O3X-green.svg)]() - - -# Additional Documentation -* [Inspecting and configuring the camera / imager settings](doc/dump_and_config.md) -* [Troubleshooting](doc/troubleshooting.md) - -# LICENSE -Please see the file called [LICENSE](LICENSE). diff --git a/ifm3d_ros_driver/doc/building.md b/ifm3d_ros_driver/doc/building.md deleted file mode 100644 index 4421c9a..0000000 --- a/ifm3d_ros_driver/doc/building.md +++ /dev/null @@ -1,93 +0,0 @@ -# Building and Installing the ifm3d-ros package - -## TOC -* [Prerequisites](#prerequisites) -* [Step-by-Step build instructions for the ROS node `ifm3d-ros`](#step-by-step-build-instructions-for-the-ros-node--ifm3d-ros-) - + [1. Installation directory of ROS node](#1-installation-directory-of-ros-node) - + [2. create and initialize your catkin workspace](#2-create-and-initialize-your-catkin-workspace) - + [3. Get the `ìfm3d-ros` wrapper code from GitHub](#3-get-the---fm3d-ros--wrapper-code-from-github) - + [4. build the ROS node code](#4-build-the-ros-node-code) -* [Building subpackages for distributed systems](#building-subpackages) - - -## Prerequisites - -We suggest to build the `ifm3d-ros` node on top of Ubuntu 20.04 and ROS noetic. -If you have reached this document via the [noetic ifm3d building instructions](noetic.md) and followed all the major steps in there you can skip the three steps listed below. They are just a short repetition. -1. [Ubuntu 20.04 LTS](http://www.ubuntu.com) -2. [ROS Noetic](http://wiki.ros.org/noetic/Installation/) - we recommend `ros-noetic-desktop-full`. -3. [ifm3d](https://github.com/ifm/ifm3d/tree/o3r/dev) - - -> Note: Some users may require older ROS distributions for legacy reasons. The supplied ROS package may very well work with limited changes on older ROS distributions. At least previous version could be run as far back as Indigo and Kinetic. However, we didn't test this ourselves. Please be aware that if you chose to go this route no guarantee is given. - -## Step-by-Step build instructions for the ROS node `ifm3d-ros` - -Building and installing ifm3d-ros is accomplished by utilizing the ROS [catkin](http://wiki.ros.org/catkin) tool. There are many tutorials and other pieces of advice available online advising how to most effectively utilize catkin. The instructions that now follow represent how we choose to use catkin to build and _permanently install_ a ROS package from source. - -**Alternatively: If you are looking for indenpendent subpackage build - please see [distributed build instructions](distributed_build.md)** - -### 1. Installation directory of ROS node -First, we need to decide where we want our software to be installed. For purposes of this document, we will assume that we will install our ROS packages at `~/catkin_ws/src`. - ->NOTE: Below we assume `noetic`. Adapting to other ROS distributions is left as an exercise for the reader. - -### 2. create and initialize your catkin workspace -Next, we want to create a _catkin workspace_ that we can use to build and install that code from. -For further information about setting up you _catkin workspace_ please see this documentation: [create a catkin workspace](http://wiki.ros.org/catkin/Tutorials/create_a_workspace). -``` -$ mkdir -p ~/catkin_ws/src && cd ~/catkin_ws/src -$ catkin_init_workspace -``` - -### 3. Get the `ifm3d-ros` wrapper code from GitHub -Next, we need to get the code from GitHub. Please adapt the commands when not following the suggested directory structure: `~/catkin_ws/src/` - -``` -$ cd ~/catkin_ws/src -$ git clone --branch o3r/dev https://github.com/ifm/ifm3d-ros.git -``` - -So, you should have a catkin workspace set up to build the ifm3d-ros code that looks similar to this: -``` -[ ~/catkin_ws/src ] -rosuser@tuna: $ pwd -/home/rosuser/catkin_ws/src - -[ ~/catkin_ws/src/ifm3d-ros ] -rosuser@tuna: $ ls -l -total 0 -lrwxrwxrwx 1 rosuser rosuser 50 Mar 26 15:16 CMakeLists.txt -> /opt/ros/noetic/share/catkin_ws/cmake/toplevel.cmake -lrwxrwxrwx 1 rosuser rosuser 31 Mar 26 15:16 ifm3d-ros -``` - -### 4. build the ROS node code -Now we are ready to build the code. The following code block shows you how to simply run catkin_make without anything else happening further. -``` -$ cd ~/catkin_ws/ -$ catkin_make -``` -This will create a `devel` and `build` folder in your catkin workspace, which contains the required code for running the ROS node. To test this you can easily set-up your current shell and run: `source ~/catkin_ws/devel/setup.bash && roslaunch ifm3d_ros_examples camera.launch`. - - -The ROS package should now be installed in `~/ros/ifm3d-ros`. To test everything out you should open a fresh bash shell, and start up a ROS core: -(Please don't forget to source the ifm3d-ros package first if you haven't done it yet.) -``` -$ roscore & -$ roslaunch ifm3d_ros_examples camera.launch -``` - -Open another shell and start the rviz node to visualize the data coming from the camera: -``` -$ roslaunch ifm3d_ros_examples rviz.launch -``` -> Note: `rviz.launch` does not include the camera node itself, but subscribes to published topics (distance, amplitude, etc). A camera node need to be running in parallel to rviz (you can use `camera.launch`). - -At this point, you should see an rviz window that looks something like the image below (note that this is the view from 3 camera heads): -![rviz1](figures/O3R_merged_point_cloud.png) - -Congratulations! You can now have complete control over the O3R perception platform from inside ROS. - - -## Building subpackages -Please see [this documentation](distributed_build.md) for how to build some of the subpackages for distributed systems. \ No newline at end of file diff --git a/ifm3d_ros_driver/doc/distributed_build.md b/ifm3d_ros_driver/doc/distributed_build.md deleted file mode 100644 index 007f38b..0000000 --- a/ifm3d_ros_driver/doc/distributed_build.md +++ /dev/null @@ -1,47 +0,0 @@ -# Building and installing for distributed systems - -We have structured the ROS node into separate subpackages. This allows us to build only a subset of packages from the metapackage `ifm3d-ros`. - -## Building only one package from your catkin workspace -The command below allows you to selectively build only one of the existing packages in your joined catkin workspace. All the following commands can only be called on a device which already has ROS installed. - - -``` -$ catkin_make --only-pkg-with-deps -``` -To apply this to one of the ifm3d-ros subpackages, please replace `` with either one item of the following list: -- `ifm3d_ros_driver` provides the core interface for receiving data for ifm 3d (O3R) cameras. -- `ifm3d_ros_msgs` gathers the ifm-specific messages types and the services for configuring and triggering the camera. -- `ifm3d_ros_examples` provides additional helper scripts and examples. - -### Building the driver package -Let's say you want to run the `ìfm3d_ros_driver` on an embedded system like the VPU itself. To make it as lightweight as possible we suggest to only build the subpackage `ifm3d_ros_driver` and its dependencies on / for the desired architecture. This will look something like the following: -``` -$ catkin_make --only-pkg-with-deps ifm3d_ros_driver - -traversing 2 packages in topological order: --- ~~ - ifm3d_ros_msgs --- ~~ - ifm3d_ros_driver -``` - -### Building the messages package -Typically a secondary ROS client would only subscribe to topics of a shared ROS master for receiving data and configure the main driver. Both jobs can be achieved without having the main driver package `ifm3d_ros_driver` installed on the client system. Therefor only compile the package `ifm3d_ros_msgs`. - -``` -$ catkin_make --only-pkg-with-deps ifm3d_ros_msgs - -traversing 1 packages in topological order: --- ~~ - ifm3d_ros_msgs -``` - -### Building the examples package -Building the examples package by itself (with dependencies) will result in having all packages build as it requires all three. -``` -$ catkin_make --only-pkg-with-deps ifm3d_ros_examples - -traversing 3 packages in topological order: --- ~~ - ifm3d_ros_msgs --- ~~ - ifm3d_ros_driver --- ~~ - ifm3d_ros_examples - -``` \ No newline at end of file diff --git a/ifm3d_ros_driver/doc/dump_and_config.md b/ifm3d_ros_driver/doc/dump_and_config.md deleted file mode 100644 index 5ca1094..0000000 --- a/ifm3d_ros_driver/doc/dump_and_config.md +++ /dev/null @@ -1,286 +0,0 @@ -# ifm3d_ros_msgs: Dump and Config - -The ifm3d_ros_msgs package allows us to configure the O3R camera platform via two separate ways: -1. Use ROS native service calls -2. Use dump and config service proxies - - -## 1. ROS native service calls -Per camera head connected to the visual processing unit (VPU) of the O3R platform these services are available: - -| Name | Service Definition | Description | -| ---- | ---- | ---- | -| Dump | ifm3d/Dump | Dumps the state of the camera system as a JSON (formatted as a string) | -| Config | ifm3d/Config | Provides a means to configure the VPU and Heads (imager settings), declaratively from a JSON (string) encoding of the desired settings. | -| SoftOff | ifm3d/SoftOff | Sets the active application of the camera into software triggered mode which will turn off the active illumination reducing both power and heat. | -| SoftOn | ifm3d/SoftOn | Sets the active application of the camera into free-running mode. Its intention is to act as the inverse of `SoftOff`. | -| Trigger | ifm3d/Trigger | Requests the driver to software trigger the imager for data acquisition. | - -As you can see the two services `Dump` and `Config` are also part of this list. -### Dump -Calling the native rosservice `/ifm3d_ros_examples/camera/Dump` for a certain `camera` will return a string containing with the camera configuration as a JSON string. Please notice the use of backslashes (`\` before each `"`) to esacpe each upper quotation mark. This is necessary to allow us to keep the JSON syntax native to the underlying API (ifm3d). - ->Note: We have mapped some camera configurations to native rosservice calls to make their handling easier, e.g. `rosservice call /ifm3d_ros_examples/camera/SoftOn`. If you think you will benefit from similar rosservices, please let us know so we can add more comfort handling. - -Call this service via, e.g. for camera: -``` -$ rosservice call /ifm3d_ros_examples/camera/Dump -status: 0 -config: "{\"device\":{\"clock\":{\"currentTime\":1581287336449588512},\"diagnostic\":{\"temperatures\"\ - :[],\"upTime\":196692000000000},\"info\":{\"device\":\"0301\",\"deviceTreeBinaryBlob\"\ - :\"tegra186-quill-p3310-1000-c03-00-base.dtb\",\"features\":{},\"name\":\"test\"\ - ,\"partNumber\":\"M03975\",\"productionState\":\"AA\",\"serialNumber\":\"000201234160\"\ - ,\"vendor\":\"0001\"},\"network\":{\"authorized_keys\":\"\",\"ipAddressConfig\"\ - :0,\"macEth0\":\"00:04:4B:EA:9F:0E\",\"macEth1\":\"00:02:01:23:41:60\",\"networkSpeed\"\ - :1000,\"staticIPv4Address\":\"192.168.0.69\",\"staticIPv4Gateway\":\"192.168.0.201\"\ - ,\"staticIPv4SubNetMask\":\"255.255.255.0\",\"useDHCP\":false},\"state\":{\"errorMessage\"\ - :\"\",\"errorNumber\":\"\"},\"swVersion\":{\"kernel\":\"4.9.140-l4t-r32.4+gc35f5eb9d1d9\"\ - ,\"l4t\":\"r32.4.3\",\"os\":\"0.13.13-221\",\"schema\":\"v0.1.0\",\"swu\":\"0.15.12\"\ - }},\"ports\":{\"port0\":{\"acquisition\":{\"framerate\":10.0,\"version\":{\"major\"\ - :0,\"minor\":0,\"patch\":0}},\"data\":{\"algoDebugConfig\":{},\"availablePCICOutput\"\ - :[],\"pcicTCPPort\":50010},\"info\":{\"device\":\"2301\",\"deviceTreeBinaryBlobOverlay\"\ - :\"001-ov9782.dtbo\",\"features\":{\"fov\":{\"horizontal\":127,\"vertical\":80},\"\ - resolution\":{\"height\":800,\"width\":1280},\"type\":\"2D\"},\"name\":\"\",\"partNumber\"\ - :\"M03969\",\"productionState\":\"AA\",\"sensor\":\"OV9782\",\"sensorID\":\"OV9782_127x80_noIllu_Csample\"\ - ,\"serialNumber\":\"000000000382\",\"vendor\":\"0001\"},\"mode\":\"experimental_autoexposure2D\"\ - ,\"processing\":{\"extrinsicHeadToUser\":{\"rotX\":0.0,\"rotY\":0.0,\"rotZ\":0.0,\"\ - transX\":0.0,\"transY\":0.0,\"transZ\":0.0},\"version\":{\"major\":0,\"minor\":0,\"\ - patch\":0}},\"state\":\"RUN\"},\"port2\":{\"acquisition\":{\"exposureLong\":5000,\"\ - exposureShort\":400,\"framerate\":10.0,\"offset\":0.0,\"version\":{\"major\":0,\"\ - minor\":0,\"patch\":0}},\"data\":{\"algoDebugConfig\":{},\"availablePCICOutput\"\ - :[],\"pcicTCPPort\":50012},\"info\":{\"device\":\"3101\",\"deviceTreeBinaryBlobOverlay\"\ - :\"001-irs2381c.dtbo\",\"features\":{\"fov\":{\"horizontal\":105,\"vertical\":78},\"\ - resolution\":{\"height\":172,\"width\":224},\"type\":\"3D\"},\"name\":\"\",\"partNumber\"\ - :\"M03969\",\"productionState\":\"AA\",\"sensor\":\"IRS2381C\",\"sensorID\":\"IRS2381C_105x78_4x2W_110x90_C7\"\ - ,\"serialNumber\":\"000000000382\",\"vendor\":\"0001\"},\"mode\":\"standard_range2m\"\ - ,\"processing\":{\"diParam\":{\"anfFilterSizeDiv2\":2,\"enableDynamicSymmetry\"\ - :true,\"enableStraylight\":true,\"enableTemporalFilter\":true,\"excessiveCorrectionThreshAmp\"\ - :0.3,\"excessiveCorrectionThreshDist\":0.08,\"maxDistNoise\":0.02,\"maxSymmetry\"\ - :0.4,\"medianSizeDiv2\":0,\"minAmplitude\":20.0,\"minReflectivity\":0.0,\"mixedPixelFilterMode\"\ - :1,\"mixedPixelThresholdRad\":0.15},\"extrinsicHeadToUser\":{\"rotX\":0.0,\"rotY\"\ - :0.0,\"rotZ\":0.0,\"transX\":0.0,\"transY\":0.0,\"transZ\":0.0},\"version\":{\"\ - major\":0,\"minor\":0,\"patch\":0}},\"state\":\"RUN\"}}}" -``` -## Config -Below you can see an example on how to configure your camera via a rosservice call. The JSON string can be a partial JSON string. It only needs to follow basic JSON syntax. - -``` -$ rosservice call /ifm3d_ros_examples/camera/Config "json: '{\"ports\":{\"port2\":{\"mode\":\"standard_range2m\"}}}'" -status: 0 -msg: "OK" -``` - -This is equivalent to: -``` -$ rosservice call /ifm3d_ros_examples/camera/Config '"{\"ports\":{\"port2\":{\"mode\":\"standard_range2m\"}}}"' -status: 0 -msg: "OK" - -``` - -## 2. dump and config service proxies -`ifm3d-ros` provides access to each camera parameter via the `Dump` and `Config` services exposed by the `camera_nodelet`. - -Additionally, command-line scripts called `dump` and `config` are provided as wrapper interfaces to the native API `ifm3d`. This gives a feel similar to using the underlying C++ API's command-line tool, from the ROS-independent driver except proxying the calls through the ROS network. -They are part of the `ifm3d_ros_msgs` subpackage, so if you can't access them please make sure it is installed on your client. - -For example, to dump the state of the camera: -(exemplary output from an O3R perception platform with one camera head connected is shown) - ->Note: The service proxying only works on the `/ifm3d_ros_examples/camera/` namespace at the moment. - -``` -$ roslaunch ifm3d_ros_examples camera.launch & -$ rosrun ifm3d_ros_msgs dump -{ - "device": { - "clock": { - "currentTime": 1581193835185485800 - }, - "diagnostic": { - "temperatures": [], - "upTime": 103190000000000 - }, - "info": { - "device": "0301", - "deviceTreeBinaryBlob": "tegra186-quill-p3310-1000-c03-00-base.dtb", - "features": {}, - "name": "", - " partNumber": "M03975", - "productionState": "AA", - "serialNumber": "000201234160", - "vendor": "0001" - }, - "network": { - "authorized_keys": "", - "ipAddressConfig": 0, - "macEth0": "00:04:4B:EA:9F:0E", - "macEth1": "00:02:01:23:41:60", - "networkSpeed": 1000, - "staticIPv4Address": "192.168.0.69", - "staticIPv4Gateway": "192.168.0.201", - "staticIPv4SubNetMask": "255.255.255.0", - "useDHCP": false - }, - "state": { - "errorMessage": "", - "errorNumber": "" - }, - "swVersion": { - "kernel": "4.9.140-l4t-r32.4+gc35f5eb9d1d9", - "l4t": "r32.4.3", - "os": "0.13.13-221", - "schema": "v0.1.0", - "swu": "0.15.12" - } - }, - "ports": { - "port0": { - "acquisition": { - "framerate": 10, - "version": { - "major": 0, - "minor": 0, - "patch": 0 - } - }, - "data": { - "algoDebugConfig": {}, - "availablePCICOutput": [], - "pcicTCPPort": 50010 - }, - "info": { - "device": "2301", - "deviceTreeBinaryBlobOverlay": "001-ov9782.dtbo", - "features": { - "fov": { - "horizontal": 127, - "vertical": 80 - }, - " resolution": { - "height": 800, - "width": 1280 - }, - "type": "2D" - }, - "name": "", - "partNumber": "M03969", - "productionState": "AA", - "sensor": "OV9782", - "sensorID": "OV9782_127x80_noIllu_Csample", - "serialNumber": "000000000382", - "vendor": "0001" - }, - "mode": "experimental_autoexposure2D", - "processing": { - "extrinsicHeadToUser": { - "rotX": 0, - "rotY": 0, - "rotZ": 0, - " transX": 0, - "transY": 0, - "transZ": 0 - }, - "version": { - "major": 0, - "minor": 0, - " patch": 0 - } - }, - "state": "RUN" - }, - "port2": { - "acquisition": { - "exposureLong": 5000, - " exposureShort": 400, - "framerate": 10, - "offset": 0, - "version": { - "major": 0, - " minor": 0, - "patch": 0 - } - }, - "data": { - "algoDebugConfig": {}, - "availablePCICOutput": [], - "pcicTCPPort": 50012 - }, - "info": { - "device": "3101", - "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", - "features": { - "fov": { - "horizontal": 105, - "vertical": 78 - }, - " resolution": { - "height": 172, - "width": 224 - }, - "type": "3D" - }, - "name": "", - "partNumber": "M03969", - "productionState": "AA", - "sensor": "IRS2381C", - "sensorID": "IRS2381C_105x78_4x2W_110x90_C7", - "serialNumber": "000000000382", - "vendor": "0001" - }, - "mode": "standard_range4m", - "processing": { - "diParam": { - "anfFilterSizeDiv2": 2, - "enableDynamicSymmetry": true, - "enableStraylight": true, - "enableTemporalFilter": true, - "excessiveCorrectionThreshAmp": 0.3, - "excessiveCorrectionThreshDist": 0.08, - "maxDistNoise": 0.02, - "maxSymmetry": 0.4, - "medianSizeDiv2": 0, - "minAmplitude": 20, - "minReflectivity": 0, - "mixedPixelFilterMode": 1, - "mixedPixelThresholdRad": 0.15 - }, - "extrinsicHeadToUser": { - "rotX": 1, - "rotY": 0, - "rotZ": 0, - "transX": 100, - "transY": 0, - "transZ": 0 - }, - "version": { - " major": 0, - "minor": 0, - "patch": 0 - } - }, - "state": "RUN" - } - } -} -``` - -Chaining together Linux pipelines works just as it does in `ifm3d`. For example, using a combination of `dump` and `config` to set a new name on the camera would look like: - -``` -$ rosrun ifm3d dump | jq '.ports.port0.mode="standard_range2m"' | rosrun ifm3d config -$ rosrun ifm3d dump | jq .ports.port0.mode -"experimental_high_2m" -``` - ->**NOTE:** If you do not have `jq` on your system, it can be installed with: `$ sudo apt-get install jq` - -For the `config` command, one difference between our ROS implementation and the `ifm3d` implementation is that we only accept input on `stdin`. So, if you had a file with JSON you wish to configure your camera with, you would simply use the file I/O redirection facilities of your shell (or something like `cat`) to feed the data to `stdin`. For example, in `bash`: - -``` -$ rosrun ifm3d dump > dump.json -$ cat dump.json | jq '.ports.port0.mode="experimental_high_2m"' > config.json -$ rosrun ifm3d config < config.json -``` - -Beyond the requirement of prefacing your command-line with `rosrun` to invoke the ROS version of these tools, they operate the same. To learn more about the functionality and concepts, you can read the docs [here](https://github.com/ifm/ifm3d/blob/master/doc/configuring.md). diff --git a/ifm3d_ros_driver/doc/figures/O3R_merged_point_cloud.png b/ifm3d_ros_driver/doc/figures/O3R_merged_point_cloud.png deleted file mode 100644 index a0c2163bc2b46405cf049c3e20fc3f75e98ab3b0..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 763340 zcmeFYXIPWl)-_BK(WtNi14z{%9YH{PQITGP3P>@4^j<y%!0+_aen_vCrP;Jl~J^$MfU;@m|;Q@)DDK-77aMbImp87-NP$hO1nIFhNL2 zNUo`=Dn2D4p|mC;A^&>mB6w%Y%u^oxc>hw@z~iZz_f1zf7i&95tD7Fau2wg#eC)tT zpHaPtiEBZ3FTI^gY@j*hk45(PH(g^f9c4mIk+ZyIp@0(kk%)ex_FIdd#LANy(T;F= z(_aVAnU74SFP<{pdF(Y>E=fWHxnu{P%0Np~+QP+2(9F`s+)B{L$rU^<35o1|A6GLA z2P==8=2kX#&T_Dg>N?m>J4-p3zL?fsE!Rg@wsxv7-K=z8!gVcPI#@_q!tTpMWPPN; z1Wr~SW;cDD9G%^zedJ(&%_|N5fBv=*?B-uXJRIa;23n7AK5}uhx_M9Vp5Wa(N~cg@nAly#>8R1zp^1goLG}q=fE@2#JW?0VD3X z`#O7=`P^}K=Qy9@Uvns0xm&o|xq8^SINv;<)6Cq((?bph1J`fKG?+X3T;U0F@|A*n{SN=2n{ATILc0N{)28wo0R?hC=5#(UPl2Z5nn(aTA z4gbewDKW{vuAWaNt>$EAW2J9r>0$dn?)%RbRVzCiTkyO5|L)Otv$F!LaQ^#(n_xoc zYbo^iVuJ5R=-*$?`3n8t|MTAu`CqN^f0ygO%k{rnf&bOu|3=q;m+ODE0{^SQ|BbHy zx0Va?A9!cw3^1KH0B<_aP{jcFU2s=W)4c@#_+PRNAtAX*qNeyz*JpG!#W$HnuXevK z=55OyUQAk*t04A+&0*yn5!2ku3OPm-?>hz7DS@n zaw$6~yO3G0^MhqER4~0_;q8N!fppcRxzqGOz5de6%YKE0Aq&Sxo!rL8dYCRLJ>zSq z{W~Y4UwB4^%^EJS`K=1a3mU&~HpdwV(1$f|7pkI>q>K6wf0|&BN1C%cc!*?$0eq@X zWP60FlvL^kziXiNY5Qn;9>0GN)~&d}HCJa&80wb1k1sWt|Ji24e76xlKBGGV@qeIy zXp7S{^mC+4C5@L7yQo*6PJSwT#gWpBgh)!B=bFn}$5n#dV6-kCnB`yQRuM7ub;|x*=zGJTVa zX#(69qdcuij)-~t$T;{NxihKgZob4f?JZWtyqU-45iZ3@DTJTD^1Q_dq!jn|k#^$7 z;9d-hK=mR9l3?3|KaAu?Jm}iuTDk}`d$Pde>4X#Ps^2y_zsmf7Qhf+ z*6klw=@9R(AuVv74@b%C#RSs?;-zG^ed!PVtsQL?<#UtysHMfggzg@}D;XO$%JNCN z^%tSrea5>Zf5*-FkN6biRx^WpJt<|8=gPB|k)@))LdqOhGwkE@DJ_>H%@9_;{vJ+r z`*=yb)h?1ayXQFK@_>S6c%-?qSp;JzG~uO6k@t)gM8)__zrlL{VNhP!!4<5O9{mzT zh?I-OL8-G+dV7h1W`_WeE90}wVkzv4UDPM-LlJzYOQN;4XLnSl#W5XD@VIMyFH#`* z41+8JzGeguLZfB?@5n(PZ^Mk9$P{|S_aYy{s7uNz)%9#z8Po9%9>?0$ur?M>u;EBs zfu)&2Hw9cj7DSOxS|XlZ+wHqxLZRysyjAZBkHftFGyJhwgn|F5=By|cegvEKt50|g ze}dV^YbzQCiHR^ozUR5JsXkp+PiY13=8HdaRX)5pta0}3eX)+ng5P_j)KmQgOZ6o` zr=|wZdR?N3seVF~oqG;ahm;;X^Dx!*OjPA4alFmOZC%4JoA zM7Do*8DP5tOS{H*VH(XhYX{u~VWSM))PTCayMzjLJ$afqg(~jec#Yyy4Ibc7%$Cz^ z8NTRWWdM(4zk;)%=w3D8y5ZgF&-z(zRD>v{;Fsr?v$U-Y&G@oP5#6lS z&;&Jh;>5F~zOc9yht$M`YgFt@3T^iVYKyO@ecLe`C6=}=cqSfvD9>V)NU3;BWp|*w zH043uzLHp>Ry@_O`CKN*Aatu3EFA zW3j_i_~dLkdb>z|j<_&*(v~@EOp6h8^BHkQMz8Bm{1G*c&`@@i11ya>h3~7* zTo@d+lFW3=%5*8d5zsDH~T>P#!jQ;5S08j&5u9zr4)VQ_t%^)OGzN(M)F@U3M| zuYQ3e%|R(7<$-|hy<`=b)!<=x=&-rts3D$_OKXiQ` z{OlRrzW-RoP6+C?;1C(9B)>plyh%^V9m@FAi0Ib*;68ht{MpmsRf=S^Amz!^V2_m! z#)obN1sR1BIYD2;NfIRl38L=zs6uq>C1z_mlvD!??zn_+);yuW$}oOe{j_`NzE2%rKTTJ ziSJlR$S@rQOBNd?d5ntu1dQ##>StoOgQs=g5R`C2b7+a{{4r_~1Ci8FJpF={65UR; zSJ#XZo)lU*J!xA|HU6>MW|La58El@ImJ<|!BK&#h)bDfg)Xt@L_tMrIi4K+#`z@Wv zH)fc$d5oTn{wE!ssc07Iy!a=oa8Z)ll+Cw3T9rZYMa`a4pUA#W*QK_Qv^CpmZ@baG^**~fg#6Mj9c?f#QnXcc)YcShpG-y(F!ml^;S+i86J|J<8n^|H_ zrm3f6MTFpT;mlV3M13*|HfF9nPn>jz7}IgcJ7e9O#ApgPP27t4#cz zM&|$u1mM|{LAKobZ^C9-$W}?BJk1dcF6?7^uJ;pWH~tK`x{u&T?>~^0uAfpxRqlGfpO&4#citn#Fc6Y6GBX}Z&wPHwF9z?9aHbrtezg^81kMz?j75m6*e4iTeni8C6iUL=)(R0|AOxtnc_3ykbR^F^( z$T8KX`NLDk&MjS?FV`0Da#|RP zddm|@w{>r6K@SFtw;nN)ZnF#?04@&{R?6mHYhYbUJsDBm{dLpQhfq-qRdq!~` zMQ}6>EGgLJz;s+Ex`h{Ps+b=fN+k2e%+?l4>s4_M`jCCnyXh2+W%hjo8G+L-8PAw3 z2wka=$;BL3MD?q$yW3ya3QfaC0l>$PyK;u+n_g|xW=8<{iu9V@3DU8O8PDyyZnNsy zEOMMkyP(RtDk@rF9<&l>HUD12_tE@WxhOo+9|p~c*fH18#s4Q(Px#G)4gZc^!hNV{ zI6=YK3?&I;u#3Er)8vL}v4^fcjjc7Bk?tm3@(e3&1(zRFSWIdg@Q`(B5=FH2@vT@S z&e6MOzm2pcoZzUV-uyjpOq}ou;^Sh&z-=G-A;jl0IiG4u841Q-d%V1RZ;9j1>5kIs z;yuBN(vbTgtUe(7s`4DXd(+P7pUll@9;-PGiO$vbm9`c^4nIQ-z^;#zu9OKOqK@_2 z#IgF-kM)NkhwwNMjklni7ik9Jv7XiK2^D0K*eC)l?OW5#yd#~8pbJ+4a;#865c;HK zpjMsWCLZte5qU(1+pIKc>H^{IaO0iDOtDgVk~L!eTS#q6i`GQ8T2koUYRPRovIA+H z&P%mfcRO5X5sSkgNZ*Ti?!HNJbN$WA=x(-pcB@meH5@2v-s~$OFxra3%0*A}iLe^=(4ooTZHk1tK5V&UzEdY8-u zilB(WI9*MDDc90VxjLEjo41L@Zw&CVM*4?zuCWEbVS^?@DfTZn6)fgAIj=0anMB4@ z(t4p!Bij%{V?OH-Be$B&EoVwiFbZ6ugk5Ghinac>j(I`BCiu0h%2X;OgNDLZyw59< z3&+>^W-o)o1<#TtHyFCIHwH(69kuji)ivNd7OAx*HM9$E)oV#Kj__Z1&yk(&A0EQ% z!qR>{B^?U&`}KfkHSO^&O1sE(%Nn)3g8(>UM`B$Y5#ud`dvo{@qs)veO2da!$E>)R z61OYOrBdFkG;s!GD{4%+P$2%DiMNFwJio3a!=;%}ZxJci(wnKV7XA;^G}#nD`NzwM z4Tji$lr*zpLTf9^vpZmgF5`kAuF3no0XB^28(B^E&~@D!fBBiV0a{Z(HkEM>^3!A; z0Sx^6+w;n0U($hr=2J@V(Cd`lB_o;y@A3^h*kY=lKuI04wTYQ~4|%Nj0FA5^+?Faa z$TDTYVeBH4Qkck#UySOaO=$2i2)0%|Rqfe6js~74 zs!^gxFroP<=@OPZ#Pz&5fkN?sATUeTu`ID_1=6||mAroN@E4(Sj0wAr0B)n9&VeqEjJ>MGQ zpZa1AKJnkPiZD@M{p3XUNW`X3WMMR}yOB9uBTdKZbBKNSZ$tVicIqs=3bRF}5{CP} z3KX3~(D>^F%@}u4!wc(8PQKxisY9x|J5)2606LpJ@x;hAH>wI68SRRWDPwrtNbyu4 z?5)ewTPhBbQ@;&SO=``&;l6=RoZ(90I|Ue38d{_!zp>I3_dM1jGDd3hBFks~RVu_S zn%=(KT}RvIiNw;@tCe1@?F$w%MV;7QI|I$uIv-|kBy^Z`CAxD($OvY20gZAMXE*DsF&d2neBnH^Gk zUO*4Ay$f+o-rd*($JY|~_T=r*2Z8liWXL|FP#XDcGN{99o^%<)e&68V`K5(vNsR6W zxjiOx(Dex$-ys&lTOLxSG{QyW$z9eYR3Z5MZ@3{qPq_bkn9$b*aw^H7{O1)SXPu(m z2wCTG$>lxispH9m)zyFRfV&=y=sT4!f4+E3!j>V!a%a|n93gE z4RXh>ff0dYu9dXT0mJl$UB=5G#XB|TGV0z+dOpaxIwG*yr7WR6r|fIbFxJ${s#K9T zR4Gk8d+b#i*)@b)yV+dZR1)C?Svudv>IkQspdNa5^d?_XT|?jiIX{p@`s6XKvx z1@F~l8BRx^sI#>nkU9zULie5N@qO5>e1B8ESrdVopLZH_dv^{zoMU%XUXDBzVA8gy z2j_H6Mb9^{Y0qzD3=zA<*Ag)NHMGMRLx3&7uTumyz$m143?vGEnRG72N$D@hp(<if$J(@~8gJn2PS!Q&*D(GvHr zfZ6V5keQ4LxCZTlN@F-VcW2c4^?`U*OVvwFsAPIihQ$jDCe)=CmZX;uAI|(o;lYoyWZ*5 zv%*mpp264nrd#&e;4DjXfyjqb#QxzAxjQ=0VtBB>#8j*IcEAajM8`dyna}?0_uCGT z6PtWrlT6!d0d)5W2Ekd^HqcI}*`p`Sex#WEE)c~*FO)_am_v3ZqrWh;?ORuDU|kdL zkPbO~>PL-2q+EXRX#S||8yVf~PAqvK7j=TBn4q89aVUpRr1fjCq?3b-Sv)HT&h)mk z%Qg8u-y~-!H3QMPJM+pCDvOY7l`88!0(VF7CwJ>Uq~%1#sKghkl+VDMh5&m2x+92j7r{0Y%&Z`=m#Xww{CpvqelRb+Ur(2KYCr1+qKdKr& zS1DvDFjY!}3d1nEJF9a$ltbfiYiHc=&cA94u;=GC{;Zzd6WkxMVJ~-?a!wEb=aSG> zBZp?Lt)d;#o~AI4G>Q~syMU3m{IE2uncpcSANnB-#w#^)Jf{YU3ag4IfNlN0Bbg5( zP5XMAc!z3iP~16?ZD9jDN-orB3e4H^S5pPsC9X?141O*{R4 zH^ad^6ZGi^X{=00^Ufpb>Zj;kknKJBEK!#wAKJg|0t5M$2qjHj?SeWpmTQ?bC50E9 z>1~KwGjC56XLqi;z7u$rXJDPfD-6CTO^U18K{A~0%PkRrTAqNT&>fyK*<|85cRgt* zf9M+KDooN>+D%MyHjAW%`@^Gn*8Gy0!tQ~T;q0ArHRrcXi|94M#DyCznG)NTjo585 zOiOQ@%}3;oXI226B!A)0gC5Lw>qfO)1(9oz{ey()7TV7YAO57!LSCX7N`<`Zr5ezi zYMwZf)daXBFPdlCz0h)+EBW5mKg+oCDOifDBMwq-b#$zZWy4R@C^)$6Z5Ucr758dstz@fcnRuoT;vFP2hILq~cUIFyp{Y<3$v!;d#!)hw z24&5NrUEq!`%S2=(ZQ+Z><$#u0m>fDBhtV<(=84^hutl1j2-%07qx` z+f4S#z|0@XoTqOk<@a;iZ1|BEwpig%eftP;E8k$mBebG?>-rayEmMsZG50vd)bT~X>{OrTBY5Uh)+F`n8@3p52pnJh--SD= z;WU|%vEua~%oCSdGP$=6VNb@cl(zbhc)x)d+;lH~RPZE(7@S5buO}dC`t~~^bIsRI zYl81UU26gh8!pf>GjjLFh97}yC?(_<8s_F=L6SHNh36+)Slsw^(_8<|byZUl`r zs7uJ1-F+peTB9IKaYjk(OiOd8DCa?JkXT~dBxjFSUfkjjD&n@u2!Im4sx!PXAv13Q zoX}{@1q^X$cYrh1jOy@Rs5!Uz6-`HaP+i0O*|?V>Qy&7l;&`TSK}867mhl8a)b5(% z8uF?2SS~CLeE3wyL0QwSicCVNZIbbshqdpHsc(cl^HHar$IgSVLY|{ktG9n20gz-^ z)rGIfDU>r?tbE!RId~70t@8lcqbihMDP18c29C~0nWxN(v2xW0^T<%)NdSa? zk2c}@ElkMN!`@$RN~KPbtFYr>>kw{%{^eD?Ba&=aviCAjatduCk>u`K-ey|7A%baX zq}4cH^JkX{s!nE_YDYW*!cY3I#EiL^dV_9w!D$5;I@;T*K)`j@t1xUEh0Ct?yLgRZ%07kfZx5 z@vatr)QzzHbpZOGQRt5O8PHBNK``pz*u(~HxlPFO^t4sC%TDrtS@zH|2Q|X^Ljo-A zEjC{apsxw0rLVF__qT$wgS!*4o60W@F=X-dgw+9o&8;>Yje;(Yqqq}si4OWubC($5 z4c?)-m(cHR1IXDu3pX|ZYP1QapABEgB4f7>IMrXiOi!|#iJeqOyxF(mn@x}Irrzcs z$yV66r$4myprZ?VKI)h7A=D65NI3lxAUBG9%-wk#QaVx9U|Z0oy&Z7RE#3b`2HL-b zqzTuh6Ha)}Jn)&a633z%m)AU#++$*(jWS`s!Z{f zUvKjs`~=}>6E5(hURfe?_Bg=|(Zyoe(0C-zC4Plve38w4RTLmerR5r~JrfKw8sp|E zFMH}bm>mVEpRkbojeMG{*sm`m{_z5ofr@Mid46wy0%1AjQcx&KIjfK2TP#29{+fyx z+sx^hkBGiaJW>YFeXSq=zx#%m(C(Z5b z$xGGga2D^IU^?azDHfSsE1^}e2CsT44vpS-3`XqcAXn|%(n|(pNCX(bj=#4mto1NY zG%?Zm03eUY8^9?htzh+Q69VUf?V#Ic1l`Uaf0Wue;0yLjwUS~T0h?)lGTK=#>?Hef zBOOQsVclg1=SSRGH0SDNEa7Yu)Uxx-c~Iot<4-MbtzYXM$y#N1R+qusc(Z5m|E-absBn4@KT%I zsoZD#8ncnEGxN&DcH>8nKfBbZ0Z-ScU&b%AavhvH0|Z#H38Oh%9FG#=L$pFkBoT z$qR-$e;J%?)K6iW>OR;4HQ|bG8v}@LP*DOxE(KMoDIus&Psnq#ulZs)&5Cjc^^?sT zAb#K4DQo@Jez2uma9$vy#(6NPT{2w#SQ~14Us-}bQ+YGGs-dq^IslHEnpKv%zl~j3 z*1YFzG=*1NT}-h<1jcR<(}AF^#yW?r2ipsLg6ti!H&bA>N)ZK>(XmME>ydiJ%{HU?_!Qd4X*YM)21!+=h#X#-45_{48fP&T1mg z*jC@#mOAxao-#VKDQ$7sSlz*kb6me>Rj@Ud!q>VC@s<<=WM#aLMU}tvhwh;$$c=b| zskf0(Lg#n3jWB;U`=eC_0o#@`BXWBC$a91>TV={4{Ac&xUZqzBDc}k-n?-7ygNUUP z^LVtSybNm#s}7ySj|*!!^2kUH*}J{-M$n>X<`I#?f;+cA?x(&ET=&QspX*<|D~MK- zN2}g*rFE&HM53kuR=nKOEPQK2oReNvYt$0qklC_^93>ir-e!At>)`5c$s7DvXRnDF z^F)g>m3RH$jWG%laoz5{LyogMWTBoW>12X2VUWo7`r^7 z_@m$^xKMxGJumz<$)_zf4=FUoI9Z5p%Cp;8^F+Wq)U?^eKq`&K^K>*rbDw|ND*WIy zq;YM5H>)WM;+xL9rEYkZ(z!xrZ1%qYw@BUkC!-e3MQXvC;(|%KZQZ){(X>`Iz1ZS7 z$#|)!x7=^{-k8SlO*>YyJOB31cmHGgKYW@%d>#G2b-$A^oN_RN<|wZnKb0Cez;`Ih zZ4VRK4SDd=PFbLH&`0a6*vYEWz}|}M_?w7e?ziE957J+_9RS0=$4-aiqSwtG2gFLk zu30>?(r7tEkekL=&N}hwXqr`5TBI-yPO$CL<9C+J*Ql^TSB#nlk%_{bWU8ybU+eR= zB`=8oSqVHXsuZ2#oJT`e<-EvTope!-2(DvKCiHV(IO6La4ijV6qj7+Vyg<1e1OZ+I zHjb*vW!)RPq!NnqrnE?2EJaey*{6cKXAbC8; z)Ruo-^7HN}E3Q$xRNII}g-ZRgaACyw4!0~;A$2@h^e+FWuHRk@(J+v%d)U9?$|-n8 z$^b$(Y9-(gq>{kZKIuZ45cW+2o*C;&nJC{(ZxUrvs3+OIw#9-l{Sq zNCf?n2cty3pI>Fa_t!o^{0fKz)@)_YJvH1L*J<_+d4qmyM`Xk+SVwDxc_Yft_MKz3 zK}+rJ?U5n8z_6Ouz)^H}p>BO-Q|1Z%bVc#H?HaPQz*Xrlg12;EQr*7Fgm>pvT@el%|b& zsry!`WM}$)6bp`~$nG<|J}{i_Z(Dc=k4wvq>f=bOSi;9|T*uz`dxYz}u4A4v-st_n zXoq1YVHU{QQ=~%VUzhraEjK*>!vy`JVYYJo+qeg_DMw1ZvQ%TrKL#|N8)jc$89u7B^Sg)g)XLg zn-upHtKHkF*a-lVM%sISfaLHK*mFXa1*>-KgiVvVO*JU>RKs00Sb*K6S(B)4Jkle) zXY1*F4jQF$c-BOyrZp|guRWyZ2wgDV@%}9=FfDiIxNc_LdgUkAp0oF! z;VA5sLej$Wa^$T3c1SZ|?!3&Vg_k{N?QqKGD%#)K*!eGxulJuhjw#Wq_&S6gJC{L@43?eW#N3`| zd=bx!I-;IH-XXS0yJ>eS-ZmBZLV&HU^*>>0aea7Fo*Qm@X z*MlIy4T#M7<9V{tazem6$%U^xf{iI=tT-XW;7LqsQr?Oe3L+^@oIdd(R7EnpF^&j$ zOd;@{O~W$jw)v4HvXV=|(PcI=RO{^d&vNC_v*ic(y+d@o{=g&A6^g>#3l=Cz&zQCu zDjg=e+(3+u#pnIr#f3cLAuY1mMDPg#9TFyq94XKvZ4G%-wxc2BIg(gePf59%&mzL;Ps6+hFW|M;iMO*<-e4?|uKVo^JAcoR@ehC6dK)PlT zz%;o;Al5x|P9h}drnR1&)b@YouX#E-){4K7m`yaz3A#pGxyppb+%9H(K}{4H!25s0 zZUwGwsVp4_z~iRKxfdY-Jp%8Pv+0%h5p zZ1(^gsNs~MMGu2d=zSvhefqJuC&Akcu34RwOwIzMeqa7=U^p6Mw87N>U5zz2dYlup z?4548IvN!9j#`66rA-ZkPjd97HR!u}Wb4uFJ9QsuHlF1MHA+{5V zoPxV15fn(pO|>errY~#cwA42l z>+8IuL?$~K-}_ijndd(#k+R#oRSjye(o`J*_uS++fl$}5@O;w?IS-+(ANOrJ=-AEYZAxd4)8Jj?qQLHz< zeUN4$T@6GuBobJmw|`1jdLw#8CLJ?8v}YqLTf2wAX)I@JK(TbtDhH1PpmN7*48#^+ zZ&x4m>#VL}A=&&2go3!Ohv~Qo{cfgya#0dn61K-Td#7bCu3lfM$vGy_@i8fN7}4kB zrGh%jh#qKG=p(N;kf%dyeSA?o$FxF}^1wy+FqkEszm(K${`k&Q(mGwz11UXuPV+qq zk(P`>;7m=MY^+v_N-;+$>(whG+XTNut(nm6Sxw4zzktG8r$fZ>y~siG%6EJIyPz-- zkZFXJ{C!*s!TxAQ#-41-H{y4d< zu~BE(43*WWs(mGwe=`>O`~K6w*s1KYin_N`c@Bu#K6snlX~o(#IQL z=*c?-ss+{hDw7Vo_>IQ)QKGJ~+C*uI=#G1sj)u~}NXr}(&6S%4dmqC;_r>-ym87)H z>8=T9D727bth)3?DoB8v=5)@p4j57&8tLzcnG4e22ECRDD3CYcyCk--{7=gE0W-6E-8dQ$Vd;+Wv1X?}z5 zbrjlrLV2ZXpm#_>?N_{1SwE)?0gqrk!jkyw&ARJ_xeDt9D&BwMhq%)<4z~0|oUC%2 zoZ%>A?BaBj@5?Y9E7fGTH?-8rtV4O>bY3+qE{|c+h2j37L_M&&FiveNgyLnp{^Z47 zoehy6jQbgPp1RlF}q&g%#@Vl>U0LQuB} zshQww4CZec)|pU@3*g!S2~h+Yc18rkEYbvp2~PF?#y=QC&Ce8ZorSs~90#4AeAD`T z)6hh}MQ^?O1Eovy>iRxOz)g1~m~4%ZXFAdp78D{C1k&Nh&HxXYyDIv_-Btgv2*4UK z^?&pOozUHVexdoTM)Qvn#bn*074`!eT81^jx36!sXdR^3jW0l-0OB1mJzra_fbk_1 zb^&p6|2nCS>YX9QdnUJOJ~0pu3qt%sW6BL`V59t4uhc9u#jG&-S z2S|mZW|5NHB8N4a_iaKS?NuI5zvw)cAtsTZjssBk4U7D+FRAuds|+*pwp(4u*OKP; za-(1mb;T{v6fyK(GP(a_faRw&_xDy8b?dz^{*-!d!d+(O-QrF8vvLIMR)V)HMEQ4p zI290LF)5S_jHa14aY6*{$S&AEo87sBX?gYQm1LwJBO0@|x2^pRH>%+LOlz6B3 z^cBH-`jy(ZZ2;cc6g~=J$;LuC5@YtW)F(z`WU3{NA`X~{BGGv3L-}pv&8Mk!UNIrS z?|I%-a|(JO_DgnZI(yiZh;EPOkIQ+Y`~E3{2z3w!Q-5Jf7FUwz70zW5e;XU)Ux`~Y zqqUU+`F>Y8d9>w7RIhCqhWgpfV)jTkm=|q6*T84)m3&$43@2jB&Q`X-s^qPQ!->UD zX9CbNWx`bB{2af!mxsAn3gzT0!@OiN<5$8p>qbRRHS8O@#5tu!XSP6>37|#>_+D&w zFL$0*(upDQT_VoQ1#9;>;oo+B7YjWudEY=I6W4}9c&^~cyf%paD=`mRMJ?z|NZvvQ6{Qf1e_FBW3yUb#` zepIJ0@h5}7_RD+)i;#-!AkfI5ofE`+yKCULR{XA_JlN9CJn@D%8*FoVWbzcY>t$vq z56GdL@@qXDRAcD(A<2q-60@m(p&>;QQhHfQv}qCkf!To8q4W;C0(6EODko9hm+q3~ zfnFRfUX-3QIgobhcRYfDFLFxN?cu&ljpNX*DV$U9pl@_{or*l=`ix8$EgjZ1{E}bD z{&08fuztZePy_dI-1lVTR&ahktr=`zFbo%y*BOC$3_D!x&C~SC)|0U*LzMo~JN5ScX61)1(;wRw)v70&-Jq*EQ2E58AhqjH z@*{a^VC3LPBZYo(_Y`C_Y)Dr29)-sbS`n_q)H1n`)EZ8EyVagO3zkii^8PhZd{U=z za;aW)-^lmLPAeh>I9R-A*{V79wT;W#S6X)hPJ|^oN`OCX1)RMLqkhBHhA#li&1$!> z8_iks)v$hc+0lvKCk#1KXb4)Xe1Psmwzfq%O<0pFr5P$aP0W)4wXY&^Tba1+4lVL7 z335QNeJh*=#5gB$TQv0feDTXq1dE<6?7z*(mv_ZJXSzt6`VK zm3wZUR0FB_&__VLQUZ+zxhIwwwe{=4fC{seY4~JwPy)s{~{8PY<>V&S?dbq4c{y< zLyet_f_?0L+Wk=Rh2^|>_BV7ro8Wy1Mcw3Kfp8l5EqeV5a$o{$4XJ3gj|4_5nG_}v zI1xi}y2-!|BG3;7n*e9@Gv;m|{#;0+8huK-Z$`tP)``l3Ic-bxzi(-9OgV?JFQlK3 zXPZWU1unqN{P0UDbIWZDr@+w_w?VWFWq>R8YOBZt`SlOoHnpk-5b4<5{pCe2@Kk_E zWc=;5HxQVbfV8W4=`226l*Xejaih_W9!Lw)5*>gOztcOp{X@?}aa4TfCk{Lye1HvH z_ym#E()YQ^(ckr#jvT3IsoFIBI@~AeQq8lsrwc!zEpyiZr(sm^c?x?MYDE`|w3F|a z3TQSpsN*-WKtNEHC*ZKqEO1sDdG(~2dhT{%+P4AVg6ngn?|nx~E9|`y%_*B|+D>eD zE2#%AvpiS()p+K)J1tg7U@LGEi12rI+%SvNu?Q=b%2W75kLL-26nM=NdC43>8-~%_ z?>e5r%wv9xT_`ut*>hnhScg~*wv%RPEg&`kUnB=dQH(auE??Cs-NaRWQ0A#11z~&A zswxyYe|#SKbt@1*AnVTQ`re4*E=U0h)nsZh>jh%c86iJ4+34~b=;Zcma_3gcTALkd&^ut%6W2hF)Nzc3h0~u zCH2pl-A8t{`9|R)g1`dT*i4ZUPRv{63QWm$KT#EmhDcduptbm-+Ge7F=BdT^;sf#s zsGh3($DYoypo>rbjz^_Zi4S6V$zr*{8QdG-+<>Bi4Z!O1yy=(`dZPE+@8h=~JK~W{U zhJ2^POsD2=V8cKVL1Oc94cw|8uHtNX&{2C=kdVTp;^}p2Xgum!Tw@e$VgD_HBcd+_ z7sgZ?<`GO4`ojsOY?4oAt(v#-m{5gmD!Y6u;sX53AMZqPO`taS#}YrfYH^KL67Y8Y z8=oM3Yk)<{r>#tuGilIIwy$z3cX1M#97tsEjR{Q2J9j5otJPSQ*BUtb2+nL@Ke|mhEMW>eQ3j|5uKGy@tYf_3InTC5D%EY&3&@NeO$;1pw)Tscsc z*EWlQ1PK}!MPX@nS+VcynROpf`9P6tBTjDGQ=iDhvx8JAfSu8cBjP^%tg5UP@ZaEk z2D%?&4e31V?lmi_#!^AzZW@GZQ=8(tfp(v*348|2FJxY%oEB{s0UnsWW|3%!!JO_$ zh61>*w*5jcLjgn*RUg|syGYgGWL~27mk8>(t*MQEpYPbLJwNIgqo&_fShYnsa{vv~ zwomCmE#!X6mREa^PwGQ#^c$zy(!Wc!If~z*{~&o25(Ml%50E~_MDPF3O;gJXgq(f> z*2fR|W(xw?kb*Q1=>!Gh4dZFpiTiJKA5h?7+kG!ffD{T&bxj&mblI*$J|rP=M1qEY z475DF3cm=b>CC<7KPpFyLm$-Gf4ZOlD5>943oo*rSVl)9fxRrl&mo?|)35+QIHk82 zX(;1!i}GDST_+2SUCW7be;$F(do%0{>b|QvFFL*6@L76=Z6@um5pMjbxYiQVpvF3q zLACm6btko}K-fGFiufgUgn}GtDc8Juv%lDhIH=Pht@BHDmmwYgP#HLxEoYK)=FEr7r;z?R%9%aGBC}qP_OOO(|V#%@4A&9x2&e_6h4Zz zAC_IGUW_HlMU&XAScFC0vs->l5~uR^L(p=|g1RBwNEypYs&VdLWV?XX8m@j8JbqKm zc}P8A914$v!coo9+VA!clP?v3&=V(u{)AG}E2S#$c##$38dHhy%gg%9t{_v!CNeHM zzvC5tEy?;t#eUg@`^zdP&>4Ys1DNtFyX$o4orQcK+k3wNjhu?0V`r5^%vK^h>i%y- zpIKE9NnXGETYHncHJRHyt?MVig-1iuc9=!JHL`FBP7ccJ`&IRoo9&M_-{QrkRM z!jT5r>~BPCKWQ2kJzDafJf=7Td;qN0LHUT0uM)hq5< z)@qIQiQ4r!ehV1&b9trN>hy@r@S|yYy5!{+#s)S<3X3G7lVj(Fd(!*3nt(r*FCL!> zvtLdL)lwC_{C4qFHjwd~>c%`|E>j7^uxv0Zwu9 zedb%OcFnui>~Gxs!{IC~K!1N_dDQse|6}U98?>>0)&f!>x zW79E?y`ng_>`f}lcI;!7nPX-hnH?lKb{V05@9w?ddw=KQ59d6Nk25~c_v`f>ulGkX zg-fQ%e0&zxDGKEz1E{j`h9-MBw@qU zr*NTFKdOJgMeP0k95H?6)FcQO8&1VNf~$z7h$+(at27ghC_0l1r($1Qb9(6F7NX`H zA?LZ?@=$b0JBPG2p3!BUd$PYFdpp>gdOD7BsgC%nF>(W$*v+eG}J#Pkk^7Is<3cuoE0#q|@qz9fGtZyTg-f}s6OmQmKE8ax=e2*t zLo8_qLR~dup#D5tQ7UZ+6FHCa+hloL#t`;sAO&5Chkw{4?H~fkmV*F-Mv;`!`9U{dj!)zS|32VAzf+@myo>1#Hdn`;e5n@k&|z%)&|EY1OMgT&>p+BC|CXs zqavT-JrobO;TI^}P|AJBa=}zhw$|n?e1&fh$}aNZSDzz!4Qq*<@KzO@qn2C42u;$<*Q-7w4$`V8IPWtW3 zH_E!K&52bX=^?L++R@gJk%eCKtpCNC$dBxjZyDnM1=_P4e5l~F1Hbi(dK$Z|=lHC8 za4%&-M$1OZSq@-oQ<^+%y%GtT$lo4F6!ngmsxC9qA{n5Gp0t4wN2G7ct0X; z-whjZ3?U&XboSyW?b3$hl6nignk8Zb8u@lj(Jy}T?EtzFa;-^t}OH`r!fQ10n( z(n}EPkubA^3*EJgpAey}6VkLRND&Ws)LVPmwBJpZegD_y!dU#^RCAA0_t`-;G@5kq zf|OvtOr859Ba=NGt8q$mgymHA^OJ7uH&N{L{RupqCWvCX@*=vI9~zu49^ z-3t~?H(dW*+HhANLTo#=!h$+B5qv0!xI|oeaNCuNL4eSY2AR?wvYIjN?&Itf^%>q0 zm##xZeJCf4C>V5Z;>!>p7Z&Ve69dYFwL_=Mwz+ZIE)h_5*CwcSx!0(^E|+}Ypf)&B zVAvsOHJ-7SyME6mT~)J>)(U)c1rx)%<-RvNHqiV6X`T@~m`>et2(9@=T#o1}J;0vq znJS($Y9nP*YA9a-AZZk6TN*9v|D+mZCfrDSNbyET$W83Yk6WerrB@ToaQ=Rl*bnmj z%QbyV;34pgs!@7^)g&g4)v#;O-;Go=N^k090`BrUjuRZHUF6nDGO*e4k{u0P|8$M` zJ@T12)-8AA!?!`Qmg#N_o{03}!RDt)P5g(!_|-s;1x;Bi3zA2kuH|LFfp~bH{Q8OM z;%QD}q&PBEFw{30y2^-OEhDUC!&}9$rE*>8Ps=MT9+PAwPz1Ny?Jn^g^ule-U5dV$ z+=g~~w_=CxH|aaL$+JP{SpEUxsdWh%7Sz3e->GfI$Ks1SkSfHRk(E#^-8!(_dO|QvG(+{ z2cFI0*Gp#kO66|Xte%JS<0OPN$s-&7`VK}5)A_6#PnTI~SKA2Lw0^cC>rmVHcDmPt zW2rYgb>MBY6q;Pde*Gz7&>ZVy8ocj2LQ6F?gb#J5OEbyzrjBDhN8~ZiBp1{Utc5Zj znhpQXemXw>MaiM|(AG`NPsjzs@_iOV*+)g7K@rA z)yWDF8#hwUKPM+VSe`Wac0uQ!b9WLZIc&6LpMy^$EuXx4-&1@)i+q^(>($f4l7Wam zL^_vc@=KW|&oO1?NgrL(ORAIGGaHAxn~)s#RP35-n)*QZXT{tpPtA;5(9k*L2)VHi zSJCQ9o@lkQ&t9*atd)t|uUCEeoVI5cP!0@b2ewAC$Duoze_4^=Hi1LRSd@f(W?!>Z zAxFPS85`42+BiJ*Ao7qgJhXAbCMXWlDR;dOYB4U+6wl@XYdR+23^9$6PWk(x4UWTh zu}*Z?S7~*hCmF(#!ClOxed)&$S%QCl-XA{M5$)8%nTT>j09ZmvF+^MbdX+Q;tyg9GK zpRl3X$A)7Y6Ti6+P@+YAKIaypV)fHA%a|)05=#+?>rZ5?>7=E~ngr#_|LO&uj!l56 zGJ>7JMuq4?g@@g8wSm85$n_9DE1^f8*56Si2NzlI1NC1-B{crpD&I zpYd9lvj2ThON zM*Qy#6~#Z`Len>3w~M0b*;2CLGE4ur^NjVe?*S_FYtmj z^roUcmv|=eRCU90PP+ZwWPj|iA0oQGfQBV|^h4Uz^D}vE3cKv-;gw)5Taa^dk%hT1 zXEecVo=3*AV(V<4HR_s}s^zi`L6L~&|%G*|+=-ePM zzR!)U*CcM&u3%MZ_CcFVjg;gt^*41mcImb6e^83#CDWjAp;_*EC64T1&s?2B-|!sR z_m)Ivj}qZYy`j)m)Y`d_9@;f+F71v{OgK4M{|8?Do`{p#6up|T#1#1)y84o^avmnF zh%yyQ90%JGm?0D>8)fTk!lA3=s5uMn)TXKL_B9Zt{GuT2m=adMyfodf8ovhH2_mls z>-nQ&B&&jGSvo3~Y+hvaqvO^F0KwhE`A-vg`tolLrDY0~pqP!gn@mfziwZ8@!mln7 z{i)a`Q9~DCYVI*An^mP;5%izq$s}S_dag0-WwSJQHyziG5O#2^UJB3DUiU@(sb|dErz;q_pY+Ocm+|q6#JDJ@TCf{;0hFlqY zTeMG)xo^Sl=ORz3rdIX%Why1>T|4a*f-N=alF+6wOj>fY(5%h#S#tfq37g2{Z$C>Z z2L90QfQCLJ zHo~v76|`Stb5<9wNS{D<9KYJSA#+4KMDP+d{dYqoI;5bSEtO)j#*r|j|z0S=iJhJSp zvg>!|tA4guPp1!t)EetLj^7V$MRttBP-VvL=lL z*iZ|=e4b4V1BT6wBfaL%SD_&2%%nDrmSHF94`(#vT$#jkKFnT_7d;uNsDbA+xTj~w zq-nQrD9K(7<=j=p^?MJ}QExYGc7r3cYVw@!4|1H*ol-TJ3<1^XmK#@g21NHh7ejy3 zr#t113*T2i5LUuw)%0<;3z7&kcj|#p(J_ehfU@9u9zPYUg#nGUVJ{Tn_lL4Q2GlDz zDN1mTjb33OF!f$z;9PlAlOX5hrPEH5!9=SGiO6Qv<9tEka(n!BBdJ$Yw!nIlBO9W^ zw|W6*%lT#mofB9=aM%IFiwrL)2+HJ&HQqjkVDaK6_?|Npkl_|jS7oU7c&WL z>8zuPF!_|c=&akqz-`6+tZS=2Z%35)5k`*en%JzzFa-Kn<+X&bS8?Z((3BxlxfHt zsb%@5ay-#kmNu~>0dDt_V3+#i07 zaLB=ODpCjj*qFE!-fq`Ej@wReR@u{zeUgFjPT-)YY@iW7AHy^6cEr{9Gh|bmQd3Z0 zevTulWo|c8)gIIg3ub=XbdD!L5izmas61z9c+ch6At6WEx1F&@L1AA%ZcyCp+k~>( zy>q%Z_!C;whL=kQ8VTL8@cL;ZE|eqheXhK^z&8p`DNK=UU4^u+z1UlrvCB8E;`(Kg z9m|dOro&I{E1y_6c1hP3k~rcnE3Y&u+_8%vi>6G;xOiaYnCdO=&eFRffVzCGo#^W? z;uDxK7A=j@5L;I&H9)vm;N&No;yz2UxvB9q877#vdHwj1tQnJRJ0FtcO{HEJ2t4bKV{G_!KJ(olq0U6vNvhZsM7iN&^Gn%LY=7{K3na7BCN1!_W71WE*}C7 zB+Zyhe6A8Si>3StTm1_Gl?MW4sA?g@T63_z!5!lZ#f zb~O~0n`79bx+_yG-r+B6mCLc6*SCbi4(XHU3i_QUWV5t6n!LrU-Op{Lxe^efu>1V| z?2O>^!=OPr&Vf*a-9QWz5Mx4S%c9onRO1ag=#E;1&W``KFp=aO3{9>j?joO6dPyRS zpsNDq*A<-P217wNxZ1VxD}uE87B>2t#pnJo30kdVTg!gd%elKV?LoRRN&C3Dj;P^L z(fE;`U>)HiL#aPBh}8-W{MBepeP-7$ea48V`ov{=5ZRG!lden>3G4W+hwMNq7Q-(2 zfoIQ8lbC&vUv}1uN%srq0FWu(EhV+G-my~~HaJe# z(%ZcKy--dVbyz&xT$#`^5SCq`9CvSX7VTMUbE_g?Uj|iGA+tU(5v@gGO0M>~%*uZ3 zHT_|Q3?-_$-st*{kcP9z{J@F>=3O zg&y|4qC7ODNOrF-4ZQm`Ay&$Bf>q>)w)21vS^p6GbTw?}Iar`QT;fNg&l)Jk$n%u4 z6w`~{%_f&*=VN{;!^|%k-g(cl+q7K9_g72D*uot!Ev1ir(Y?q6v_nqZv}sSDj}-SG zPR_crQm-=OoKGb?13IBIx7&lb%UR$CnWvaePh{?$oTz(F-31d5t}4)xY6J5ILxW@3 zm?D!fo$_H-_Z+%CHDd_7)2@>oNstz+TJ~IsqSVaq>@@xS&n4V4HU2;t9it~?o|ZfL zjBLuR=dk;Mp5`OqX@jBFn9f)vuK;WZ=iw}N3k2*+*%Os56^ zKmiHM6dCAN)bmh+$1iqZ>MhVT?BiIELr3VpeTrV^ype^>Z zYrUwb#?v1CY4*>|fV9Z&9x9N(1OVH4sXv1*{o=lPcF3h4rULLzBO%>M>#JpG4!K#Dw7<@lMOu*>Q$w) z&PVhd;+udjz3|&gr(N*TW(V>)u)O}C#v7bP#Bp+K2T=ezJH>`VUH;JWPWEgMQ($bh6PFj=L4 z7Klh0Z&()UO3P9++5(ns2=}#5jIb}lrU4BT{Df~dGOyV~D8w*IkWbySm?T$*a>pqrmd2I`X1TNglm)0*wfP0KG2ctm`X4Ii{g0+g-^wlf@e znZ`k5Nm9;f_R45yxMs{sT0$vg;n-8uL5g?0I>*<0(td%Y1pW0l^5Z7h0jCltIjPF3Uxt~Xgj8lO^}A!jUC6a4)<-n z59YTmg%3{N;1iMMo60r&mYU9zitYRI7{e%Id!&LmqOj}M5+5RIaED_UUu4{pSMNxI z?K~YNLZ{n%Zyfth(m(&n;*LFu&--HhHBVJq#M5TkuAp9aACfzdJi3!MtS`IBfgMug zxAh`!-!YNocTm2zK@fcLbHH`nSAs3+ldE!SWNq=s^UBHt|H85ck4$*k*gpMQ zto~dr&_Ks(i8-K7;aB^>>5Bbu8P_ktzpO=WI}@7-*Nk~{=Q{-uJAQydQ5#s{Jns9M z_Gopp8yHG}c>&Eb*a_f`FXVICwjp$wvDTSMO`y6F;1KkfUmd$8V-t%UrbNIqrur1| zqnJ)0$?&HQ7jxc_NKmP#r9H92Cj7a?-ZDwwIJK*&j?R3`a?p>~gExd+g_91TY5>+8 zutG=(h6zi*Ari#_L)j9ydkEce@X2!yL58H7yB*); z$|3rqOp4S2R}&B`NU6}*=u{M@llLxg1Fce_*Sj|2eT>nSd&X=&)D#8`Z z&1AdEo(i?8oH`lrCZyOlW*Z|F9J*PqZ|Mt?^lD&Wuo`=K0t11Gg#VcxI~>^UX!BFFUg6M|iRqw!bzlEXDCoc_(+MH_nMEh6XxmDEt zwDF#mi|~3BRZSkDQk!k&DPct#x*C_1-pw7N)$!!B&~aNI;&teRjvaRcVZu6o3JAMJ zUW0EIAul%k1Mb;+6yC0^{rqI_?#1J>QJYtJy}?KE3A$YIeR@9c#;lty-PC+< z$2S6}Z?~UMt#Ko?Ft7=$)=&467p16D$cv;K1>h*c|DQ31d#|wW`poFMPO(0jw}J zWrn>|JPr|JeblMsTC5YfVTkN-<6q`j^PLmf`*8rV_$LcM>KDi1X(RO%2CrnRNuYcm zy}{KI2l|$Hk?{BOs5PfWArDHz0uc5GX^#M{1iTHb*)YF$&@_^-6`sb!S9tKN+ymKu}Yz|eTKAtD{X_-9h@ z!OGS_(4)O4D3XjC%2cx8Fgfn>ziqq(Mi1N_?gyav);5vEc5|N_VfM3%c#LDC6x1Jy z=I&4`%?FJ!$6`)jkzlB|7xBq0(r)Ekj4Z*wsbgB5DRK)1W6UD|BUP2+2pj#EkfQ+J z#u)8UHQWwZgu8u9hh5fL#w~Xzr=Mqd|9)^_vzA#tmI{e|wb7x6csdr;JWX$kG!gvJ zICKpoGLML0YBzsrCMuuhZ46aA_fm%cx-@(k(FC_UvvEj_Lw10L;Q;54Em`K|1QU7j z`An_~t}YQ=ukJJ%6qzmVvC7^ARr;!wUoj(-soEUS79c4J54d^+88kFway6r(15DZd zbSI*d>ud@;*7P1tR5uzdos}(+NCNX$lm};J`_#5hN(R89^8kChDC*&VO?stQ|Ld9k z2SvSoEBrD?os*e_!rzT-D&@Xm;bmo8r^EA3o;FX=9yP;Pz!K4Lmj^71g`-5da?|To zo+V2k9{H2+JuewB#;{P=#Jrxd{Uw*FZ~2ENEY;DT6hbdHm{T|My#Mb(3ngF6KiObh z{M>I7HRk%n5c|PNc2OVo{!L{unS8DSJopi@3T8zL=;pwQDa7Ae%hpT%Fspw(TglDP z2k#{N*MtI;)kx+Kpr62S)@^oM5ZeBM#t#>W)hhetc70(*tw}JayM52nJGP?nT#xdQ z?h}sHyS ztj0abP~Q927|G8R85DWwl8a~cU-{X>$io!bT328RRsvi3Tuf zC6VM7`pCUt*~L&uvt=6{;t9;XJ3Jb1nay(A5eOf`4%G(3iZmu%FvLEurZhGt z0CFEQ2Q=E65p>|{T&?Hj8~ZEfEpOw;zT4g9*WeuAl)sJUfZ>Q)%Z!-br> zH)orbiVauzT))=_F%r{icqSyuGuUw_cet8(Q=*8$YuTp{u^&{4Wx0tEF5R4g)8nJf zZgcUSPn?7PlQaR9D|-rYmw^PyVywPrXEt={einKlxVbvwcv@@USL-xDJSf9D z+3xZroO`S;iOyuk33O0ZS464IbK%TIF7D+JRk{83+x8=Hun#;}YF{ej-mB?7Jlv zzJFgiD{F;?+81`Q7e7QtGBU*=d@M-23-DICfza>{71ZJz*u_-nMZZkELJ)&?=M}dv zjsF<*t$F{i29{PR!gi{Wmei+8VJlr-Un;X$7`AOxws1u?i|4yn z2BsL+5#2D=bkv)Zip^!yA46=PqZUGFOk@SlW-9H*5*9PfsnMkfvP3D!bm?$`%==PwDAAim0 z`r;_Nc&9vr<6!%T_2kT2?V!3_7P%fr12s6;(HwlvgQ51e&37>8Y|<$)oeje`8O%7ZdpxD$`OPcXp)yKA(2;)RY6966;Cle)n{tp&y|0^2{Yu3wusTAy0#?s< zQDs~^t+ibH4mK@g&xb${NQYftBAL8Z;7age3|y=uX{w%6eEt$nK(kM*{BXF!0{lKJ z_^?q32+|QM4nGlOtNr^q6)bG`>8qG=F0$*hB4oP)ep>)7YcP}s_9=)P*|rFNmLSYf zWl;RZtIRquA%NJNSJd?ub>UvW+JY@`kNd@#N`gUKN(ai-xaY#hXH6AT+#V_}NlUiT zIa3n&AffsUax;%Tch)P}5?HO-%A+X+|G?tbB~&L+V^#PHre9dhaTELX(pA+^8R;?F z`n|S-3_g7s`lHc43Zk7#-o*~jrb_JgUhTEMDA@m0qPui(a?ti4x8uk0|1&!*yk8r9 z7^8A{}3~dM)?Qn_#HZX&tf{ey2!ON5ffTmUwb7MYD&v4 zN@ae)lQ+@+97R4$>S)*yp>edFot4;m@ALZ;)f!Xr%FXrY__isWfcD|za>6yno@Azf z1!p!V*7+}(nOFP3fR3aJr6KK_Z#i2CKg=y>`7>T(Cndj8+$zqNt8zVlcF21$EyKn( zKs**+5vO8|L7)vtHbM*ypN%&A!e(yq+ZI9`KV2stXj)8i;;x_-4V4fyajeOn+?D5E z%kDGa?K4-f+P{#zvg?60)4j+1k}q1BuJI+Z?0j=F{88KAMs5 zZp3;PxPP}R^Kt+$5Zb96=H$C~muL7Z(elqluUE#g+Bs7{?0HflT->;C3rm|bqp&Y> zPNW-@AZQaG7eL59=G^wMJ`OW+R2KvhoN)%ITEOzP=S6ik`yG!odnAsRn+jblQ+?l+ zrt{&!mTF=i?^YRhegVoD$x&rEbdJ;*xm4Gm(_kNkm%rd!+^Y)2kWQ#c)eP-S?hx^1 z5NtMMV>H!NbY1ZpDuV?#{bM5TazLyxwb$Orep$%?25{ZT7!7Kfj#`jL1A1z%ay)qN zWmTmou86Z|w;LImGQEFSR7VU0>GEb8C~4;0eiWAL91);I0U5!#MZvAWcBgOtk2q+9NokM8$QMx34fvay)50EVpfu2Qr*!Qu#zSaak;X4 z_!hcK#lPI&x76P3uV|9f+y=J`ByRskQUPf(Ugb~3sEynPyX``Sj3(J{K=C;E5=>9K zH2bKV7>CI;Z?ZN77KU0{TKxpJ@&-DU_p=d@aYRb<*{*~qgd=l3ZPGysCsHh*KlIFD z)5I{a3Q-sh+lU-a+`ve5Yt2?e2DyE&s;iX<Smosi+F6m`Ba(hMej&P569)dUi~z^%)xg*gUmOf3&0+skP_M~^o!aX z=BBVyF7{#P6LRj(zv0xPNE5QBKjnwIplquy7OldQw0H1KCeJHYaPddZipbt3@)?kF-BTPkshBcP*y03RZi&wG{ZX%4v+J1DDUwOQ%cH*5h$;H75$W^# z{|Q8>LB_+TUxGG>2V>E|DIti&51w{(e_C(89lG+W>*JMWy0ApBo&wdzo4kDL9*<`& zQ64Aa_L&J-`WXOFz%q5^u9&*y_9m!w9b8uh7>r}P*ckLpYLh+fW1C7$f6ldS_RkFS z(@ksO_>BT+s>OO`qp@!bKNcou@6PDkOVCGFgM*p!>l2us0kBVa?dzv(sl?5%7fns!PT`l8wW9E<;rpXL<@EQ_JWTqDtJ z44x;Knbv%_y}d{PX6&gDDDS4T!7%5Sts5zN>YWy{R{7A?sID&=1iORM!%R)5?vlnx z%F2%52eFB1a2AFACk^Yt7+PLo#@1c{s-$}-qH4#|FzMIR>E833>))`0y?hD!IWE5- zAupRp&D!>)#*C~K+11~ z)7J;}R_rF;oOvKR*`ybt*NW8xFA>6Jwj=DP)c zxI@&Vf?7)dmjket|Eljyk)Ss7`uvp95Vg_f5`9Z?V5WAVZ_vVQP>IG7XXM(Hxjska z3VKn$gqGXjT$^7g1LoV&!dy&d1q%p&u@|v0hk|98Bw`{b+M-pzN-b*@Ykczfg~4RD zH;_!-maFIKYb0iYK+}G664XPVdowp%PSYreYAc$q}{;^i(ur@ z$-pi^H9OzT5@VCSPu8-{-32xx$>2+J(JWcij99mQh)E9&X9O##dy61Famtj_1B)@h;7GNB{g(&f?B=Gf?aC*YG$&T^65B z@D73>znL|Cp_sx+@lJi*^n+Y^V+E9h+6iYj4LLXsQk0mvt4QPdU-R`%0 z*6=a+V9%4Rf!SAL>q*nR@D)fU=xAjrGz=lf3BWZY{30&No43A&e$nNaaawzvUCJ^O z%WAp#eQ>tatUE6I`@^BxagOYG_c)FxgU48VB#O_S(X%eeg#_v?iY0c_EnMfWT=Q)sl%OKb z$@Gsc!B#3QOE==gdE{W`mvLn&-oT*=aT`B;2e*qSgFAH2+qJKfy&hRN0j5S0>cTMo zpmj{Jd13d$IlClF=0$HR~ex(T^X0jq1b4Z!uyz zO9(4RCQrDIGQJ{S$_!`T`g)0n69;5|E?yj|{?}-Yda=BdfTpPDrz}_!JKsIJ*w3dj z`vGd7d>_qre(SPMS5YW7SYqd2K3fW|F*Iyjp22!B;?J=@7(Suza9qn_Tgl6h&@29T zHB`Q=Ba^-fHOORoO;5}FZbAN84H;JO`=Nc)L0eO4dVpAdsh|jCqLoQD&~f35-R_3u1Q9jl~$R`(8Y}uvU=!mSufFNw$`F$Ewd^Ck#m?i=qughasf>gXs|;uaDce0P?Pon&t_u~odLl#`f>-;Qx%7!#-v_ZV(kR6V~%P7 zC{tM=^fV4^8A0e*a(wS(v>|^&5=D%?Lw8d(9(b1FQ2SCJTSYhnf9 ze|HTO!{graBn8=P<;b*rIh$j%rqrC(?>dHC%~EaZ z&h$Yx@H*>=w0%7wSJwoVxL0?06$ENv-4YLgH2X2Yjg_qBZeBQA45b?WaU)}OiOJrS z-s5{-(D<%jgG)GL2RAxZNPwbQBDAhmHwJ5y{+#0p2y;WNel&J{VZ;yj$UH?yx`~Z` z1pntPY^Q2sn6vJKvzX&T7oki_0#&nhw-}H9!be5|%Ia$-=&AomnZ|4Z>_5(?zuo_b z<{QI08yhe#kW(10*$46(ya%)?Vkp1`VOFbjnA4zyMm-R86BWx(kUy@u{u$_%K)8k1 zINsTsOmBQRvgv+aMk-Upd#%EkgALQbVf{5&Pf}Y~m+P9KK6RQ&AE7c%rHyY1Cx?b2 zkBIu>fVtY4mPxdHi=a9z>zKbZ@EcK-*5p&T;RYAipFXO_|7=>z&I;;OL$n>&-I>{G zR+>^c*B9()xAS3*@M)F$H4bEd=ACL~7PD?o|Cuh?DdE_z%fatUW3q#FXJtSc4@&9< zj3NfkJ^APJnlD@+J`Uu)%|OTnz0vjYm-W~xPrz9=G|*Y8;(&Y^3(q?~Z#{mCKM;Ov zdVwZR8%U)?>l6dOjT1IX258G6z8M={9rO@~+M1<<0>-wN59#e*o){XD)N*n$gMV$s6Y~XBXUOI}NBtwbLBu}pWkP`LRce;kZ z2U=tyhB2G;xZP<<_wfQ3i9oR(ewsCZ)ntalCp z=;ia29SLT?r8;Wm4-U(#@v3RVAha+e_|-QzbgU@U8`%MbPmUaJ8E|2n85I4K{Mo+! z`o5)O^o{k5R!N_{-J*(l($SBelv*EjE5{Q|;Vc_B;2lu1Duo)m?&)5*I;?{#n6Im9kCak3b^d`a)Qgxy>=X% zte)unB|jCHpRzj5HkDB-*L3o?syUv*n!Ut5_DU zi5o-gS>uJ$^5&eop?N+d`l)JPyfT4JsqQQWN}yz1|A`;sY}_onMNG4j$X+4x86cd) z|IQVRxZnL>jHlHmD+3bv#$d^-yoxyzWXde%j!iG(0^v#zO|r=ovc2`0qkwiIj5+oK zV-_HotryB$Tlj5Ga__??NdG>-JhX6~1j?aT;1)(@lIz-LgW*i<6GAT0xvMVQ1oMbm zXX}!XGo4Ta-H#Uj2Ho!wdi;@w1e_692Z$b|N6&m&N2iW?R*VCANRg>iC4>C?q|~;(nJ|m(`R!f=9LK%@C0!(4-|Qo8GA-wtll#BM7* zuX$#{t(qV1`^-XHkm0hpFJ|G(!ipXh&2?*eQIZ1X3-gxh`asQx{Yu_@tyl~rj|}k; zIC{59$kw{}JJH2>ZgGj3mLb=D@~Zb0H3kJ@q4FQ-`)|+eWIhF3lwC-!>$gzn7qL%7 z*BH0dO)I!ertITgz2R>i+e4UGR9#jH4iGCcsZE`{f zBj0g)0F(;}hKb4(y1HGzbv%t``mce&BU)VRw&LaIQ$M@`t>iGJb&g}Gvd;Q6|1wGkd^T&^0Ztn zh0re!eY3UM14{S}5$9L85k*k@xD`+?TW+9_lHlFiTtg$#LW4@`^`%{(G)}mWk+)Ge zH4yX{*ljela=aXq6KvV48F!990a0g@yRx?y_8Qpq#a$9OAfi$A=NGVicF>aB2D=>` z5RBxtTz03yDefj_ZCIgxByNzITuXdAyCY{%ulFul;MZ|=?X{(g`eS;?#9PzCOnfb3 z4e^7>n;O4!c~hYR@$+7)fb_|!Cb*T$96V{B*XX8OU2T#Q+0!gQ<54`zfh%3dLJ3Q+fIjQ{*>V>9E(w}Yp{~Lft(*^zDZ3ui=@;62hM7Mv z{499#Pw2E=aOFKI%Et4bDZ*gpQ(#mEyp#cG`duG@q9!A6vo<-hJ+LX*c*!MPHKk4;j?ADB4Kvv5i0KJ|5 zdrfL0_LU(O21}kY7NH%E=)-GcNVBmIkdYQRf>(LUVU*7b|GuC&%R zHsP~Tu)r3=xtpV@J@=+OZwHOBTE8uHi^Cuj?}^AbaXzt7Ni|zFMCRsuLlz(RD!%{n z1CHy5K}`lLK1n9*G0fB^pi7~{FJs8tBnv$KAAenVo$U3-IB>W^#zM5mxqG#l&0gw< zXHA@T$0;(m)HZf~P|4&jkI7v-zjwK7@-P4?HlpNcjtlDPmjjwxihkm(J;W@L~F7#y~xG=gg8?$J5u&K!ghvA z1|Do=3*Vw9Z+Bl90Gf*)GFO?Dtw`rri(tO!hL(6p;?8;6LBV72DA z?v&Rwl72L~f_!h&l4G-ZMdi%6sDE(gPpci@Rs(CM206r7S15=V~`?+wdns#bQ zs#DZuh8AC?gM%M`^`A~(+gJK?vG)g+L1w$z(KkNC^N_%(KR#rK<7@U+=3oC*2YF5w z=6sKcm;T*VvFqNnkTkRLz3Kqh*_H_+??UL*BZJJpFYH-UHTY-6EzgIjsH69O{M%&z z=HuD=KX6s%>EpX++QvOACrx*qG$sV0fm?#r_&b=xIb_6a+Ir9+PT$>W9~HEW%7)vO zjuMCB?-OUbjE=Ko4>||iG%B#=OnaWF_eU!d@d2j%L-XrhdNc8S&kycLY{~Q6w$0wi zS2B={hgZb3l=apNxJ|4?ev97VdZ46gCMtmm0GbP!shBOpTN3qu$zAoUFrF2eQQ8uK zU&OU2?3&t9&pMfafO{qx4V8N$ft|OtoYjexpCUt#b9@J*#J;5NK;XygG zT?l?_fG0jT6x!I3*8ZL;mc$_i6_s!w zj~XCzjmTk41=k9$@e^`RZSql`m=0NY=)OBhSIAMdI(2yJ*F%dPRym-KsNz61Ck2(0l%v^1OhjUoe$Uoxg1hgQIP9fvbMFR z*XQ2J{!jsAP1CWv6`ktbovB#D0<;#(t?$74+nwxNqAx!TgRhvQF0>c0c;otk%SY_B)?4=138A5qd0D3IH_ z@Ns|6idsbg)qGxdF}iOF2>Pv=8kh?P9s{W4U(M;ak(gh4#bGXUz(4<+$rc$Jd)%HFZ|2Z@{=#KGvjL?9 zGqn)asuW?^PHTll7P3QfK*_L{25FQ?j3Y)2m@;l63Awo#+kn}YuR zhP#n0|FUV8>+0jZ*Ro3OdJmGKzK1}MzB#KgHT_4^^m1S^==o0<>3nl5zTcb+H#;#J z`D@yIc|-KIVV(a+(|2RFMBdAFmeI$98oJl*uCVrjLJ_Y&U5|9`7Qo0`NJzPro&+?3 z>w@b|DO+}Y1?asj+eb{=`|K1k>v%LU8J&G*5e(wig}nyCg*(A$^TkwUvMF)pQ*r$u zt)Kauy{aD)VQ=?d+l%q$=6oPb!*-4|R%@Y44kytvS-^I8WhL$gKbZ zZb$Fn-TGW^oThY%-7F!G7D>iU5dXybV{ZeJ2NVoEt=NyPEy?|EWbOfJ)yR_5v=HCx z=TZg=LTf;EqvMwPV11?DkYAv=-7|0Q)2(x^2c+t1JQ(LHGbSm(BF|tYUw6@J#U}2+ zq@&SO8`YRj=Com8Ah-~vv`XpCn<;f<9RgsFk?7@9ZHII8;kAAa*=layUCg`;pDjjB zUyv_4qAtW6yCfbgAR@*$zE@J&S!%Dp3cqC48alS6Lqnp;X5p!G{~C-M2AdVW3QsG; z?FW{#OD=l%IY`T*4yQJ|Q$qKyCWKd?)9mwRayNfDxATkAZ}@_oDAW?n!=^YOAaoh8 zSyp=`0P;3LHn$4;u>f`XZOg0D^oF}UpUXUPUc`!I2$9)Wno04@P|{x6v3Ne{Cz*}a z4|EbXLMMhnGz(h;pTe8c3@U*%HZUB(6a*+rj#=IoWWf$5)0Edyx|?sh>;~y5jnz4+ zzMmQu^=Oi#su^XBMZrABW{o?tzT^F^MS9c<&zZkoIgg**vS*3|rH&{H7;ZV-xD;?y zXLesz<-hX_u?2TrA_fwEO9pK5T)PJ?J`GU{qxe91J5t~-r9ra(?Y=O~UPZg6$c)RAy& znVqfrz<4FILCrn7`31tuz*H;#bk$fqrDpJ8&$lg&wobz!<{G`JvQjO?>Uy=aV#8Im}D_}oerpS&WP z(o46(`*8CBZorlvQ{?q*m!S_9$1!#N$=pq!7vXfIz3S=Qb%Ccy{hq^?l9&*7 zbxC2q*~-8+1g^{_fL5;4p-ot^UgxeZx0d1T?D(~weNo9HbynvE{-GJhtU=MW@F({=tQTRR)x1 zAhIBPrQg0f3Y*XU4Ovau%lXpt~fE4> z*bl_#_aaxYa5eQYw?_`miV8vpkDF}gO^f_|9=f7F^UPeQ7af126@!RmaveKr2>*LD zOQD%p>grlePFpO6$*=7Dyd)U4+TFo`y8dAKS5l- zqWK4y`?!hA%Nqt~FH`BqY3GP;5=;wDG0SavoT-f_U0~c<`h_az!2!2NCHhfO$32?n zBh>HU9yz)eot*O0J6`eJ&C<>(!!t!pX5~r`zB=EGSLgVKjN4UI7D4Gheu>0s<>w7d z`99-h5W%8-qT3_Kj>?;S8-Pw3sdA>S8Fs`{=glcj7oqvOIRX{i(O zopYHc)v+)T{cYR+J;e}4`;KvL>+<1tN1$eLji0Q{ziz<+wjW$H|K57slbmUqnH5%x zG*qttA5U)q)%5@UkJ}(92qGPdbV@fU!j$gr&e4npQ4tXa(p`=Q>6DaaqY;S_3XBdJ z5+nalKkx7Fzq7-6ZLsaI^St*y?&I;e&!>_5gNE()uZI28kWhyDCg*t_LW5Mpz2%$p z5nBS6A^DPWpXO^O;H%@6oe0f1;a6Jvkzqr&GHI4`>KDq*4k8BLr->t`uiq~RV?3uG zq^det;<=n%25Y>>yu#MqR3ve&zT;Q;vB^l2Xik4Hy08MDbMS$kvoVJ#{bKlmQ2C?K zV;;1PL)*`#qp$+XvuwuR-kHh`=rsI>nMy>d1E28amF)o4*|$amt5~llYzhz04_dL^ zN|ROO&F@1$ADhw1@VeI@ac0vtk^e@!kTt%b{n~)$31W8_BL9*+0CQ_m~ z+fUj*Xw;(ZZivcGuC)>&n6qu3Yju1ALv(zFF8Qy180x3|FdF(JK!K-77S;;V*la)5 zeO)?~y(;DUsywDft>9neNqzj))K|j#h3oUj>VPtFM3ilyx=ra^UpM2<^R`~yrd~4! z@9Scwl$JCOxrctG!?p&jmlEXAMGje4uGuylbLsX3X%&jX1t${d(3793RN~J5iLygX z>=mb-rRO9+X3Ju91Y9+v(kXES1k4!xZG!NyJ4`!nIemFE)a4D6(Z9HR zSC3*s#Pj!o^0F#D>XqGlBj-BUHjE}=#0Wt;5w(i9v`Tk95TUOsH>bczzD9F<_(7p9 z*IyGVt`5}V$QXYCZybV58yCBS%@FE`IeoUGzFmH|MEO~ojYn|1n3u0v>Og)z2-zyvat&NyTF|=*QkH5xi_znd5voZVOPl}S}$8Mh*!>#Px zttZ(93C{g0ACm! zN;YjfIrF&Byjf?B`Ip7aqSs=@J@P-UJ^T_Y{%3dt%dOTq>96G77N49oK4m^H*P~x# zOA4iBxL*PywuPCaY8vK;81wq{{9^6;{q(_PT7@A@njaL%Nx2_XpKzQ{8De z6G!e%3`li-EVZJ!E&U|5F#YR`)5N|$<_Rd~i6Wm`a>itUCazlKwob3&#$^=i zXCvrpITQO5bGwuW0_L43ad8RK!P<(fGW^y@&hg>$Q5OjbG|VrBcr+v>IQT$e zw%$fasF=pxW{qF}LKR|6jk3-b z8MxVIgIwMm{e2qh;_~qOasA7WTU1n3>`^X{Y-z%hHlm`U%)SdHoeoM^noGZuW2UZ0 z(PIv(@l9F#FJ2>dP6JHV-DLHD9*R;(x;5X!euq-{fyV2F_#I}Kodvo z5mb|Gv`O}<0@@(~w-h5tfMwOpQ2*-Ur_KrcRHb6PVaO>LD6LdEPwC_5;y! zlx=$eVucU+N_o5V? z??gM0oxH)Xa=l-|Rd4dIOe*?0-{B#n*lw*yopmZQc4ToL7a39C9=0bVrPu>CwyCI_ z)cyE|b9@lxBHJJRHVC`d$#SU6Zi7iVA^EeP_S==6YS3hmJD|FmcW=(Gglcq*?~#_Nn!A9!{j6XM}@?Ay`rZ>{}fcdAu! zKfbDy5@EK-QMD|osNti8jp?x6CZQz*C@AfRzL&VVJZ`fkc(^nY2ww^Rd zs&M}>b}#SNPg*hEH7C4;AHhd&4ur!OVdXB`!Hmc(3UNWrgWL_;`JBM4noVc2efM|R zeXJ1q4A00%P9bs@hLI^>$dO$u))4t5o0n+!aiXi!z|jr&>F6))OTA516%-a1i}G{P zGwc^1(f+U2{|r}l#(Zd++KoS28t=ZgNGB6RxAgP2Z^g%hc5P{z6$U|*equCFFaWkg znHm(=o`!}yCm*t}9j7CBco^2DbC|sU7o?Ehis;&B5{xv_VBvw=BG&~J^L9d6APx5- z(SfnIM_DATov@@#+jJ=qzGg-(9*Bk+oZHS-_N)~uV?}}`?BVB37)gG| zksPLqJ;mg9sk{(s3Z20-PTgE4!0=7jm*dmz*3Vm)flPrZhRw$GJhEV(IU>Ng=PNHV zLkC|g(gn;p9KRkgCrx(z)+(_>Umkb3R|!g_m6y)CTlh}3GHzf?rSNN?kOi}QwW%Ig zL+x2&4iY2>4~H{HgCk+IO)6Ftd`?_YGl!S{+!SF46h@4aw{M+?#YfG6h}Ye?TEx?F z=v&)+$6-f3uQ}^G^I~`sd{IyA1Fq1?QojcKPbMt{pT2d}%1|+}dPOz#8sU&9T~q%E zwN1Tr8lZr4R-E6XorE#O+4_{U+I_OAR|vq3{-#9CDAXuF>qr2nRBTEkN-L7b#*gd~ z@$JODwwNmZ$+cGi6ZZe5Y#LD%&|U4p#7-Rar$G2T6 zm*_cH9nd!6WeqR=Bn`M&C-z$eS@TX8@aCRYROr$l&q^r^XSQ^Cc{rKzf^X6hvmewP zUJUX4Ha4ftRb%MaVwO>J?F!mlrb(|h(4P8S#lu;KK|3PhRi5P00F0r=BukTivBpF< z^4;H{+^%D2ve43|$ydprY`pBP88_<(q>iZFvE}t9^fdvZ;D~zMll%mw+^(B2VmlfY z`{PP^KLyw>M{~Fuk9wm-pCYqytHeeskpQ&GcDURXO zMLy{xgWLM+D-6S9P&k37UcN;539oV_Z9jfAQ~oN!;a%p@f&U9SKJ1Ut5KI$MG)tbA zQjYV^)}?=_wIf+7IczUc!CG&^s;Zt(sx4-)IzmKeTR2>IARB(rNg&f;63jD&yoE^R z?mWrW&ql&C+4@+x^UAd^uM?}N38l%`qvJ%-!#P;obA1P@hTN0b9S`)gsU>2q9X#Z+ z*(VzS*Mo~CSKkvwLX&&yQHx%KOJf$N{H$Jvy?-sxHt)bdS(&am5*m zNG)FTJE(#H%Wgne%coO(UYQuPP*o0*HoxooCTAtGAp`Q))1@yhd`0!vjlpbQC+hmY z!^eB)*Dk6ee$Xk*U(g>SP{RG z;=N|MQ z_@{4^)bQ@!X zT%-1DBuS=e^PKGL7ITVR7UFRa^j?1kK%J=BvcS!QRGP%Nz!{La4XWoysaI-1Hn&e= zSg@XKvdA&Iq|fVGw+`m&uV3r^zxG_!d~&8R@bz84voi4jfZZ{g5i5<>@jx%t*(n$KC_m)nyJ(=&uW1i!gpw<@rZEgB=X!2Sf@5qXiWc=y&T*0|q zcLp=&Qv-YUKyKGcWhcY{R{eKJo#zKPQf;pKf!%a{(yM5?n)Jl%mHB9)v<4zC)*E|Q zA4Fc8nK^H5-Gz9bJ{M`19E9dgg^ZQdJgqb1HT3TMAzCnBKRWm!lkvv3aOv=|O?tCD z8=US#0QGHQju?hQtV;+P!x|*lfK-eg0SVoU$?jWw%dtnyImZbVUy=({Jf)DZvRd1H zYncjqT7VtfcxB#1o{2&ff0pY?J0&a*_T{rrXWeqH*_`7|ZK%no#TLE;JCrhC*67=& z>)2I~opYHjhpe=@fd>*|3l9?YGuyN4kZapTkv0FCW1biV-5qg^K()rNTTN;v_RTF% zHZ7~i0`;(pYK~;SHDhI3^doH9HF?|aHz^(NdsygOWMajHINT-O1poN9^@<|=T=gwl zSK1*S#;Syzb4FYOZ)q6_ONPcLk!l{cQ=Hkvw+QX^y(OuRJ!Qiqy9j7BFSpDpwyI*SQkW4Ku8- zirNo+y^tv-ukPRdeN{j7PSvh(yRnqXhRF`MEYw-c82wF!5qMQz zwFBDNFrsDnYHIy4A_C%>nvw2c=Q^>|95N%8+m%t-*`S4Mye45CnAJZ;x_{{4zJCX~ z26ivR4QLDVbR3qF^MlR$aGiD_25EJDAD>+}{14|^#EaSf*OUeil_}bMs~4DDU!gd^ z#(+=P_Sr+cdn-uP>!k90DIg4cvSpe22nt=WYTmwHfaD$4W2>-9{TJFlE}zV0`pigi zi&b(GBUV=D>(k2wo?_&77;NXM3gW3CHL`wxBfAcIe_X1Hr19RK%**zfWeoZf&NbHyL#DFp))xm2?dFM6MDHW?<0Jb|a0dRI$FsFi z(uG&mU}2<9($QhuO=&GI0hGNosW_Jw{nR6r!p4%V-_nK4v|4^}es+_U0Dth|won>m zQ_9k3y;9(iJ}%b1=ztXge)fVx;n1A z?K=4~h>wB(wzH}ErQhGyJ9xXlKf}2Ok}qu}u@kC|#6PO3S4Z@@zfzIx%oTW2`;b-(o-beY+-rAnOy$^DC3 zQMPZ-TOocc34PQKd#&R?FP1t?5R#5CwWYL7XRoD{+oZ3y$uU*PT?JDopFvgOG=+lr z#ClZ2Cye!_A{uk+m+Z#KyXpn2@oa@^)Ak)wwit$Ksar@Z@PAsx84y+~_?0DJ;H?wT z4L?gmuh5IA(@(($m!33-t1M+nnH>o^dk(_hKiaJfi1YYHm)m8V#`Du1A|T;)qG-nZ z4r!N5n>?L*4s)3J*Ij0|uzRiF<5d29B$79riqKk9wObz*>-Ii;zvBVUp=__u?7RBG z7im^|H%6u*fG7p;j~R5UpgksttBAj%BH8K8Urgup3(v?Y>C@4-@u}+TO(&_zg38wzBw-PJ-<2A`?MYf?h>-$?YmpdpREFJ z{h@&FkxW{qeo64ZQwd*Pc+zHM^FNZ+nwCD*O8Du&+wxQgdFe25IL;de_ys%4%yZ3< zNTGhMxKN=X`%BOj$s|NgKPr}-*?=^NDl@Ea*?br~Uq10WH*?sEjGOo-OAiUMG!Kpw zYnH`Hj{hvYtmm4}J(cRR?-e45*g6EP>{F(*Lr|wuA;3-HlCt`H)e$i`WO^l>JuJ=SLSSz@9bBSst5NdRNXv>^!W!h5 zV5yb|+EfcqYKQ?P5t=ZO~^;87LY33I#HEyBJQZy`Xqm*a8U2=dCqb(`2B#jr!01NjS0V%;RZrUr^6I~9 zd7KEXk6qUGgXYequf6eJ^2oFnq=?`YCiU6n#nv%}9LWx(z{`NS=v!W`yQgG1?Ye3~ zA>|NYgaD}@tFvbHA~6v08NV%7sQ=+oOW*?a3bzKkd(CC6^;U1WGTL64Ek+$@TcoD@c=vfP#+a@+0^VO_!Gm5Ft=nJV2zyqGTnc1^E@_>Hzire=edM+ZP z3@2V`bjy*TLZ>u@KMKxj&%Ta{btS`381V&sxqhx87wgu@eL5bRbz5SUaObosnxPoy z)7hIfyRmM&Jyqjg7IQY?TS_#xRCbW1%8#6{7?|@4bxr%^#KsHTI!fPB<9KaN?=^8Y2==l zK!L_DV??o$x2iMQwDWy_K<(5*LTjQ{?+s*aYSE{E73b7E3z+XXXVN17^}TIDZZOk9 zu;JEZ-jBa8anud@^d*C_?)q~uXIttamQtS1<3LdTk_xeAA_H9wG4CHGv1g;5lbt#V zJQ12oXa8Wk!4XI*DZ-s4g>nXz4wC{J!dCjG!f7NP!BLf)scdJ|R1Si#?hmfnP_@TG z1iomPXX~uJMucJg+=cTH;x)`u&xOiV|2(hcy3qv+uM@d z**&b3L9f4)6OlouW?drfn^kZv=95%VK|8$3?yvxuI;OTL;bZ;UEge|oYmr%d)yQv# zv-8kNvpTl3*?}r0oS^lU4|{fU*>~&Hgvz&*Y_<4R`ySUG=H2s>402q5#==pBc`yZO zc54=>Yv(oazU+g=+X!=H$A`*1eDe1;B9(^Ae&9^%h2<+)KQViD9{afLgg4rCa)ymL zibL^i@BeuL7D*CGMJjG2P4ln{5e$A(biU@C#)HmYaVpc02J#Cae6uvALl}=soaFw_ zO|hBFGebCHH1%_Bn_GnRJCu+J+hzb>y}}-4Rc&&`YxW}GEDX9GB?1H|er>%5xm}OJ1;5VEOgchh1Dd*WLOErF-S9XqdJgmZJ@aF5ar%xFFwxK))nnR5aH7%<)uk#i; z^VXJ%WEIWwfMy-LvN7e4-_)zO?_ee#_uVNS9?^t4t4sG(b^-=y4TD$NcP*?)j*o+6 z#c7a;4g_)Z=o86q@81|FPSuk#V?aHAV9#rGLoCWu!%_~8tc8vyQObW zFt?T1*HwHz4=`=Z$2tkQmP|(G(&Zh|7m4xKssCegqM~jNC{o$|Ct*fEoAknduk6Ho z87@OWr^^vT3>#GBx4q&i@^DyZ%8#;py@5_G(5lu*XPm$JKia0L4~FY}kYBr7Z?a3j z6nP?uz^NN4Q~)5VKG%4mx#aVStAUX{WG+78_w5tsl6!6dlt^im~+9;I`52_y4d&i-4=HE04YpT~*MLt|~Z05#9{41mf`ZL5& z`Au)~(!d9h##hMc^wTmr3vsF^%z%lX&zsxV$n7F24*2wxNK@QDdB>w=Oc}oSv_W6>{d6HTnH5uW0@#E{+F~zegI}&c=3XfGW+pG+ApPI( z>pl8`CP`Jy-*=71IeBvFujITJDSOOW-h20G+kqve6;mO+sN3Y;gO*>h@zvd-3H;G0 zs)~620lqcLp^-=%MiQTjyCqRXoMkt8ROj)`m_jPF=&$s-YF^5jya{1Tx@#|9L!oeW zP1TX6kM^1Du$X;P|Ga`$%WYAaGPkzvtK#P`lhW-4L6J(@RQq;sPxM!d*S$AbQ2`xD zK*o7%H_RYTT&DNFdqxO{P2vO>N76=(iETJhO&3AEb$7uAKApH`(8mVAuol!o*OqdS z;cq#J6&zOMF^8Zt6q(#z6SsALAEl%$fY-pj(CadDh^rejF#{JZpT!vLVhKG!Q*jD(8JEH(})XnylAuNC^fo`jwJziM|T#z^z_ zzo=QH2TYh`exNkdmu*2rs*5|xarX!z!$4FZLVu(6e$g>tvDnb#m@o72`} zRiLub2uAfH%lo4A4tk9JG9HV;`83q!XIx-BbUcuE*lEry%cFaq?WBZNyqqylqgJPL zkOw{d;5rsNyHH;xb7xwgYeL<0X_xksD1~=8)>qKmcq0Fe)mS|^Iy@Xp`n_IH`fBlk zcm(CNs(2yH$cSNr5qhxqQ+R+45dizh~8gK1Cgs!pO<8HfT(STTKqV*sGVnx`z zzlWl!rbb*0wb`YZx=G}6fo1BXrvFi^#qDi+UCtN~8SD_x8d}5zb2hAQzKh7N$E+*LE;ZogcaoYyRTP5aOXDa7y^&AV=~R>_Cx;<7xmBt(v^zh4QOX)-qi}d zI@%ByTVtVAVJ@of-c{&5*dG0zQ5n|=rq#o+6hf1Z)?j6R7(AK;Fd%#=idIYjk z!XIjjk^1)UD#-nw$?dv@FnYh}dl|PK4*g&FToK16@(=%~^F2EFJ^H)LBA*%Wu>I6O z)z&L+@$_=^cg5S=fg`YZ<0&2F+A;uzKH5v@`bcgn9Un9gr`($sMz0TKa_9psE6b@J zj71n#F=-#4QJMH+tn?fkN@)ITFk{CJ$+QaQ&b8leT9t29#*cl|%?L`I>+i&u%~s?o zGVwxDQqV<;W)1Ur9lH++WNj0$8Rz>q{yAJYz&6P2{Cfxk z7M!)gRRSbbX{3>jJ@b6zMdBzmQ|;y)Aex&r%o)VW8P;u$5ucs6zz3n39v)4^$pkd- zREwG+y6lq_dbgo3t@ifRNpKc^66FwEPMBU zAnKzYI;d{pPm6ewxTY241p4DP;WBXuE`m*hy~slw@g`PS)dlrkYS{iLRW&MsyG_lw ze3ZR_rOTH;Iu<>2YR*kd3Flt*ay<_Uo)TU~7sBZd&*GKF*Ml(j`&4 z&vNIiJJ&aRhedU^ad1Bc657X91EO7i)dyQ&l#uXJx>(~E6f}*T*{`4??$@ul%#^Af zT>;q)XvRVz0#xeJjH#NhCBOArR2Xp z=n#qxfD>+=T3Ef@-rgR(%PEN`SsHjLsQ)=ZaUmy=g>onYF016Qcvmw^M9TG@^|W+s z#eT{THu?M8JTr$`)OBJa_seqB6s4UYYnrMmUz$i*qFf8S&sBBZ?cSed?Es+Km*RbE zGQt`+7WnO~17L_Vm{qo=q{I9(K|Dw3%z_{}D8 zS#nO4^%w+s;J_B#(_@M~o1))c_eT%TBCO^MX{ZqCjF1vD!-gk3XUh?X@ZWAcss4iqB5uKliuwgP@cUjMf;q6r1_3$tz8RzLHItZg;M8B>WHi;NC= zU?y0JQ^@hh8RE}-(U)ZQ`5C`RR(Mas9#Ti&l`Gh4=sOKu)0@dPTOg|=n9 zPN5zy5SEi}0I3l*v(jiw`dE#!Y1WH85QYr}bL)3_48#s~PXqN73NbvCOMn-GK5*HM zGO?oWV`UOnK;y_wBe?W|)8Ffz&cpT)Ig@RgRe$BR;R1OyN!&pbYo>vdc!YEET0);Y zlvml>^&7LhptY-2~0 zpQ`z~c3w75r)7m0s@tUh4M-S^A}-n14X!??clu0M%>Z0I<0WB|+5SOgA7iT?1eD=N z?t68W9JFAKXlq^`3P}YeSkDT_1+1)^cyRrQj{as?pawv;05u{I809h{KvCS!eD*AR zl5zA>?r1FtFg}b+ZSuQYIUCe~Hsv*V=iEOv%^oDf?d6*}Ch5}bT({XWY~KrE7GBv? zd%qYj7ezP0_UEXmn>cYKA=HKCdJM+tT+r+(UdxlRKZIzTuh=F~Y8g4)KaEA*tT*sJ zq8!RA>Q==tZ)La$0#}YONi1MufcNJE?bIEepX}KY8Wf44F5sdcc$enhc|-xGC*x6~ zFLT*vyAZN|aSSUn+$z?k6}w+14t^yH65b#GI8oa@3KD*puS>&bL`w2au#LPg(R4}R zc_4fqeuEV>sMRJ(vpizvB_HcTBu9rpuumY>_&r?p>mJyDs+y1u_W`k07MP_&kNztD zFsk4|qA$PMvfs?ef!uRr7QY5Q0om}O;^Rd9qM)miFlSBrpn6memQOdcl!DB*#L zVA}m9?dXU#zv|svh%pVl$p2?+4S)WBw$^h%@vYyKYjc1QvzPUX6)0($(HBw;>AM%J z3ZxN-KN2=N)WeY7p0>P?E&5oQO}lPeqqBxyQoMblzV7Cr|C@KXu?RN`5-;zaZ=mx1 zlG3g+f#qqM7Prlcl@mVtn?O!M;kGR$E8&m$6i zk;oKWR#Ae-pVbr#LE^~ARL52pX1qW|1V|DX1C$X4X%$spRLt7|SQ((U2Fy{SMOctv z*f<8c)@2dK2fyKi-o5^I&$d)GeC)k$CNMfmQ|tP&g@i0sUc9&rCdWAaWzTkp-=KpW z&86uetY4sm18~{u;gAZ${sH)nHf($p8VyZu?a;9Z zBSJK3MqjWvRWhd^DaL-nA|%Fe9lMM%%F^LGB)LbR z`sRzP)}N)t^alq^6=4rWlU4izTl80T z(HIySBSlwpqPqk+Y#f3W&w^e^{1VX23~xEENVRc#4tAo_I$Q_E^+CIz=VlsZt}KrK zFw~>?2lC+~b%4b++M#zzyqse}1#%Z*g=TgqbGuRt;%$&l?wAE0)IW&sQZ40GRJb5x z3IIA$oJ?vg9~m#@P!0E*1}kr^jihah|Iq;Dt`>d3@`xLPibOkoi3_0eZmDa60(NHg z0ivX$9NzH48l|mzB@^i_ANH8ZV&@4j9_SMRb&Uiyday_N2R82Y1aTT8CXQt*iBT&<4y2(JarqV!rwOmK9&(KCK@9 z7&H&~nudD#r@RI&c}Ek!*)ik?iiaAV`N!|!OQ28BqvpHbha|3yjgjr~Y?f`oc zmMsjN$~+{FsauIQrPS@e9vby(`_~}N&}o7jO*{G8{OV)(kLAhdGt(Mk5?-RxLU-KB zpb_0(aV--%px$>u*_7b zamEmX{IQwRV~cUOGIJfzPC3x*^Nq*qFVxSgAeZaww^y59Bnm9=i7iF77F19e%@QT_ z)zQ_g1O7-h{1CbP1dWNOtI@Y^Ru)VXv&hGU?xo9y0}vhVEHcn~n=M6^rOxK`hF3l2 z=1n~7;oe)w<%e`Nq*bt1EO5eC^37s$P%G&``@f~*@mW-!LSf_U2pI}AwZ@Ocjk$?$o+k7)fVcU4 zZziRkxWwyqyGxx(xe6VM_*0`aZNn^25Old2&-V+|l#3i>QJK4RE_X}LYb%mN9Gsff z{Ctti0Jke6aBAp$y;;ZA;ayi?YsD}7X9^&4`InZ6UvXwX)S7Z>&LIy|jr^4aBB_rp zCU7>)x|udH(L<8!h<>FF+O3{lid;^#q*@x;@-^%~JY@O84SBi#rv*E$&Q*hkz3`(A zN%`Vu_(LhOwmD&>rnrrcmDwYgeY{t8#~l(manylX+UUa6j#|u?2J(JVA|+-W-o3nk z>9)O+gB&Xk&Y%>}NTE(ggl{bWTpVppq_#cV@HAIJ`vxt-{1kD4EJge?_Pccf)2|Nj zG8PphYC)+2zEez&E-4?%>WdP!t>{x+k>YtF8ROT6qcXgZ>y2 zwirC;2F&;0vH;S4Y}`55s>=A-$QJ{6nkQ2~@qfwAml`X=V~ zq+DR>Juq3K`+f+J+gNCy`Iimr;`y#SGe2)l4ESm4`ilZ(F@!hCs2i>CHh*3DE}d}y zagP4;sIb|H;^VLb*|j%Np*1nQ`OB9*9!ohU*2fRnVt{%6&$IHnn7@Zu$v+#>2Irnt z%Adsx);>JC%&ka%JUJW#O|BqAaTCqP+|uzfYL|E!K0KQ1ma-=j>8w}JJ2R|VE;`ir zmctX>%P8GO^I>|5WR&r-tGaaLPS#C1%zwS$B3^X=hsXcZ?1{r_-Hw?_grz%?HKDHKFkzXL4HuO&S zsDQhDovD0=3L-EeD8Jt9hErVXhnC0Rv_%R_to$AnoEXR-hk&Y5FyHlPiEB4rT55U< zl?hXetT}R9*Q3v-mc7?5+xvXrFQH%$+BJU`C_Y6(C>?XBAt?nicT7bP%ectNt|{8-iG=Y;LlC z@L_R4ogI4NWwc1zH|MK_(cfa2DkUsbjkqM@SHP#a=I$*9J1-Or#*v*_p}D>IRWeHq z%ruLt5|p&$Ny6@Xn!ysrxR450`JxWFz1O544LZPE_1k zIZ?f2#IESNAHiQW=o`pTWg7IrmpSo5h(ubi59}h5gfj-S17#1B6{J~;Jhb|_T(-6_ zaibR1V^P;!bfx2!?IOF}>aa~}!!>nF-{1zNk_9Ql)(d1!(JZJ|UtrO89J8w4P(Bql zkejZHIQcolINMupxDr6LJ%W$|BMf|L4AVTJSOAyY4Ae2ZmZ?4L6fRt|y=PV3yB3!E z-?gM!$H}ls(^6bjCO4YH4;^0FuIF?Sn3l8#Dn1U3$*_8A@BPa~-8AwU<=Wg48A_SB zq%8L66QoAq{Znn$fIQ_t6UB!~vo1=in?FV^9QA(}Ylo=Dxi6#{y2fKgpL*%rG)I^_ zCX8f^I=E*X^(@ZIhCjmkG{2!CM5xX3jDX&O{kJHrjHn>#>L3UC`j?sJqS~sW!OG+t zi9sLaOOku;D$>@+wfKF&(#8xM`8-n{32m@hT1`c4Y$Op}`er0TJN8y41x~%3P0rUY`$25&OvRz`Zt6^`&AK% zk$VqcyGRsu<|U?cAxa}AEKja#Hm>&L-ArMY-MSQ>AX=ef)CcoMDA{l##D<6p>y9#@ zcab9nKO>b+do3}qtmk8tveTf#Jv)tM9_?5*@Mrc(MbXC>W&meB*`3r^j&|642_o!+ z^O;rkj{fUt*Cf->n{(wrxdWYCO%H#z!$bXK_UzP|cYmXz?i~?2Pt=5mQH6I8p(#xQ^3>M)%cKtVj;&oxUjXp13XVzPc`@&;*dcl&?$3QL*!ZFBn5LIwNY z6E#PziedKS0(T1q)PUof<}F7%*^`63QHKE?DMW>c-;Q}+&ktL%72PT5mJ{ZtoawJ? zW8}Y@rhIu?$@R8*&?@hBnUB*TyI-UE)8gN97)9Cu8ya|{lpG{^Dt+`0^tc+0mP6;t z&A`4NPxY{%Z5~$4r_vC90YFPnJ`cLq`=csE(a(62kJEi)!Rfft5ZCe+b@noR1W)G@ zPxO&KBJk+?6rRp*O+ces?~XKkMaF`(pgdatwMi-Pi4hlm04LoqpDa{%8e%+462yX^ z&o+yeRnh|TWIKVs&%`1O_@d==yYSO2cWez$&q9}1M6k2>i_2jum+lb5teo+ zW2wm^Obw`wko8gCtt+Fd!M=Bnk)OYr;sT#yf-`Bvl@l^%ySz(z6irI2l#X)ix0>t) zL$O4qL*RAcnm2r+(l34q{jb0rVG&*f9r|Z7T%GjIeEd({?iHJ`7dAMY zYPlqL`mBSrQ!0TET}2)h&N<* zL5eObc_%_Z^D7>O*ho0i7kEeNJUZ0tfyL;3K^_$eAwu^3c zj0dXJ|D21-$5E$$J-xmRhMs^Y4QPa59v4gqio71)Bz3SVvXXk)JK#cANpqVVRUL^H zYO`r}uHWQJ47z?2ZhqZIF~aH%;TO{MGI3O*n*C%dJF(!Mui^lRX#J!0rL^RZf-$T? zsX!7Be*}zE^a;?u3xfhl+gB!Y&qh_u95Ywj?o~6H(TtM-hO>srOu{^*;vQWaDc9@M zEHL;S9%C~pri;_RiX173l2MKt8}PG;V!#->mQNV^yvyM(cU^Os|evAfbh=PKdFgOFm`O+^?Uxyt0^>mD;OROn4p|bG zL6hhkqHj@$^)u3DjGI~@_x@)$v+^iU>LdV;?W{_ZQ=0_>r_aC&`mMG}x7uaVLGVf_ zn0}PZQP0r(^gswOljW72!llE-@Ea06cbj!_VD>JulfWCZUxxK_(q6j#i^}PbJcu0;!pKn&?XVNQdD;xuJ1M@9Rkx=3Cc2Ru#e(_l~D!N+)7Z_@wD z&+&imvI9fgH1BvYxmoHfDDHHAuTh!66&Mj=5oOZ~G|eu3ug|Px!>0;8gkH6N3Rs1) ze)YS*w4wnaZVE{nqxDV+;;T<@w29|)*+M(H*JV*^iwS$vM$;|PU(G}tbR}tBzQnL& z+$**ZTI)GoW^GwE&zK{RID7byXQUJgcC-=k8M7w=Nam%FnU;byJM>vv^vqPtK-_=~ zq{AaJE8MA8*rEBg43z=C9WVg>p3T_vBwevaXnBPHb!Sqs+o4Qj{Ke$J3v(zqP>;mU zY64;)(q@4FFn((7L*h-^l&hpu`ke57=^cl&tY;F54dN1BDN=*S!}kGqvExyOO%YIz z-T`#N?2of^J8@fu=(0ur=xaUNGruR^WTRc;G>nvY&TKJ!;ANaw^#8~zE3#(wE6w^Q z1;4@jbZrY$D1S_q0$3i(LNQ-x(+Oq6sdBqSXG|Y|@t=Jmar~gE)dASth-ak+E-(Dl zF>mYnGVKLDKZwFcy=H?E%oGjr2VDdqi&N=b2etV1G}QqW|Ld0)HTe7fZ(%1+t27Q! z)BaQtlh{LDCt(&=Z=i9&-8C#zqf!t5?B~>_G)kV0k{!g#OU7tx{A9uoAJ-}I} zg2{5d_khy(CSeTPB`sv{_~+9cnIamr`!H6fF1<{B8x*gImnZaSmD8#L>TdEisN~-F zHd9;5Opj4v6pa~`ZsP>Zp!{4eYTkM>T(aOF!-fLG{LDKmz9HI6Ek)g&f?=rRk6J!q z*oTE!U?FQ6uqR)0dS48)V=7;{%5D`Qjz@gkYn71_;DGksq5k}dMc4TU=?$nr>H$kt zrtkH4-Td$!5s`X*<=xheLh&m2{X0=r59K{NxP;wXn6w)HuBPeynmbM_;{M$69P8hz znrK&RsB{+{pI6AF9*N1x&rkKcTGz_oOrw8ty?0tHd+oPH$>tBSLRFoH;SJZIkaiaL z;91^b!(o@5%?s5w#hAGBhN8|5_zfxXtDiae>$-92A9Sk~P9m0t+b*Z~shizv-fk9t z(5-wu(0xB+w@Z%a&$NQmGs@r^bw$m^sqoi9$%XTu@4O^Ol{}IA{GNyYSa~P;efyuH zQc_F9H$nrFN)M~-whUP!->8=MK4GSEAX`TU9uaX4J77MXFe zXVq^B5;e<@EI=H5)Uo;$H+Zj=iDFaXVWZM@)o5CxO{gRSEeAG9cuB~N z?hIBDTC?>S0;L3?4)_{mSPT1n#hRgS4;wvN+Q^$@>=N72n@&FuVdI#!v( zt%SA4T?YP{%WI_(U4L(68VSJ&U6m&flV_#S9OtWsbLGozYVsZQLEN4REAqeo`royg z^c4^b&Zyvjd}Fxexa!rd!Lb`I+c%=mGF-`K>opo2-_KS_7=@QhOOOP;V>;fc>aAGl zjcDP-<|Ae|F%zuQB+$2() zS5NMdaDj0QA7O%Z=qBa`I$y1Qqgh?Sg|O9qc-ZK$EuGaZK-#`pG6gwPqrS#7&veej zyDc|I>hDY*tVA^RwbRaqZwI1s+-|UYy;wmOqvZ}>njHOt6g_U~m-$nX zU2h1>YWrY|-uH%boqBD_U$VLBty_$F$(iMEf#1ICv{OHM&Abuy>)~meO-25ET^-@8 zz{%AFb=oZXga!r1MXIbKYK^rNcd9^BB zOXyThkAA7hZ*W4Z+e)j;pBgTd&@CSA=PW=0?OFyjQ2#9nJ7%4HjQ|kZn{hj|gc-Ud!KKtyw z?|trbpXa{Q*7~dij7ff*LT(h{;V^9Tv<8 zvzl<%Ie|)bycY`Smx?ytGY?Iv+~;?|9?M6}V9PrYWKnL#Yv#c_qS{@*49{>&x%?TZ4+m8tI9lc$H&Pdcs??+F|BWd1yMi z7G^c(J4GlB@yFzbRV$>LE&YokZ7xE>gV4#QMpRsGxpkH4Dv$!#Qs>oKikO_-c>|8Rk4}ui$ zWEQWVdxla^+Jm^V+iU_#d7baz`7=G|j*ho1hJxir|gaJt`->$~-{i0HF_ zSp#P9#&3(En_9@`JCed7{(N%{o}m~^u2=tj8WHQ4&+{Qx%i8~jb6X`5(m78EIY;{Y zzEj4;jVO|XBBQ5d{^lWR+ZZp^*qKO%+MJOg`bkZ3y94=y!Q+3l2x*|5qm^y>=Pl$> z_NKAPU4AZLs&LcrXWcIoaJMe^-{=bM z5nO2Do8&W)p1S_c&OKMyQ(D=zz?dTm;(thI5HovlAH)}9pYg~+&N397C3-WxV?c8} zCx9NG_STCvW--~Xiv`Lqzw)a>s^tskDR(uO3ZUdT(N*0?-w7U+*(8&TDyi{1O{(-Q zswhVzCbp=ag;fa8P+eWs^&Bc`mfO>hnGI$!(S^%|sZ%7H+QuQ_#nYVD?i(QlBFTMc z7&cxQ?u#NCLj``x1LUS_lKg8o2B`>-(U4HpcT*C!qwm4w5v|Ax3A$CwB!c&Ti>mZ` zT_9aGrInPUX)Hzym+Z)Ja)b$8Z_pi*&h~4w+h{K~<7mI2=o|epXTai z<2%MSP->G5A3oG!>eE6xuJ=cLd7PX@SCu13xIr!z2|S;`LlTqeFgl)Rh-}v8 zDeFV9KknK_D<)5}l`0z#i-zO6e0vK_HArMbj*+RYFEL8CMIRPiV~Zn%NV)W={fv!y zE4|Y|P|KS?hefNhc0McUXnle6d$)2&R2N?VJo1xP_|stR8O4ay0Y>~DdvemU9g9sp zAN7ou=FF-3W__MrcdSvX6v;c2MP7Zlvlw<$O40}=dqaWW(uz5K)7j*4+`3my@shu0 zMym5cYCe zbQx`;KB>{5bxJuaOr+Fw>AK`u=WUzEOIxVCDU6saRtz5v4%VWli@amCoXEA?Y{BK& z#i0+8Os%ky$XoYHLLQ8q{f=4?-A^&O4p=nFLcGv}ySLj4EL2at+qR@1sU4}L$h*SV zh{u}8!q6&nmv@{CRDLaMq>k{cBxlAUfCNU{?DB_>gah(alS z!@Lehkq{?u*%OI0ry4qmi2J3{upIW~L{YSDYg-FS}klrHDKP-ArxiDo>0GOfa;zWY7&I-7{5Pl=0(OOfhb$(c-- z*gj1p9e{zzhu*-ufyT#Q$y|-SsNQt8)|e;3WZf4{&ZDaUQIfOMHP3td+{>FQ{cQ?j z=`v}PpD_mi&~;8e&l2l|S^AMH^Xx>z4h6rQ%yHYoNW6QtvTHqkg$?MJc0VplFD4BxB&X~P2W`Im`1?^FzBgm^ z#=P=CIS-w$2%?4Z@Skf0vQSa6WhVN6VCL2&o>r=L3tr$L*ks%#5h_Hnc< z_gRu2d3do(xThlxil2+OV`^3dr3LA}r-=rw)XAMp<;&G@0^bk-TVz3^eaKI;_xtwz zH=RqS`x`^as;H$-eF4^+7AFC}VBe0uCkJ5|l4g3_Igj~t)BBk?I8A+lFXB004t0j+ z*G7SZ_Xf>Bz2z3)X==>pk3>@5s0pO6SrwKtBPw)Qm}62! z3(4*|{{k=j#f&|XOk8U5P+RbQpg)02Q{NmiymxD7g-H53Z>CLF?AJeBx; zy7IKIB;48HmNrsjG4+VH0!#fh(NH;Et0vyl%iLD|*Xuu^U#V~$KfJZqsyaKZp6*8& z_CvUuj3`BuilDEHrKwHWP zcg}}`liw{+=Y}?tg8GNm-|~pkeylC+Dj9aRA%D-mwaSyG&#(-fg%$b=9*kQYS8!E1 zS}(r)fJ{yndqUq|c@ts1$kaC;>(}NgvRZfpRoq+UEpebjBf9WMD)zDd9my>ks1=E$ z*`w)RgN49<32(;AZlQoaK{`|z5$?s{d0H4;I_ZPeoy5Ku+gM*#j0^UWk zkwli^=gnFf?90tTqHNmNqH-S=5R=?t&{AvB?frlF#m&Dt7o`d@O5&!{32MWm`stAe#-1M3x5v%C_3GFOMzu;@XS6=`Hv&V zi)CQZIG()d@=?OZgin_n-<1>wy=t@J43`>*`;AlfCP0mP{h8g?gif7`cjw64a5;>~&g*Fp=oi&{uKV@Eqx4uelPCb7Xr(RGT0PFIQh%{@XqGM4zZO^1*I) zPZc*+cy=Yb<(+1^N@Yg|T(M2xj@QzAuU?lkFFFWN6?HQ)d$_FZ%9Nd#_f2wI4!r(`rS2gN=u|MM4tXD3UgVU6JY7=}S(xOv#x4tN1z^ttQ=@au&ka%*OJ-uVST>dfg%OhCVVyEAOcw;OSqM=)OGshi(EW)FK4xl?EN z?jeZAaer@#bWv)zw1yiaYi7)B02v2|X);y#yzf8N%i= z($Pb~peT6Fb)G$4uIyCrwnh5czr-TBhyh(^Q6c)aS@@^eDo27rl~d!ye)HrDiPQqa zO1{M6W(EqJiIYGMO z&DqC>U%@at@9L)ZCjJAR1kZ)5rGQbexRUrkPFeE*-Jp`;af+;F-2B`qc`#W|50+@K zoADD%%B)`1X6369?0NWDwK44_t0qs zk>an;!Bt7$Q|q8FH+AVWANh({vXIO*&`lOXXFru&_nR6U5DpJ3e;Nj^q7!Dz?VRYA zwbpAsNlSJa0OM}S-O&%wYvYNtPw*mfEFqJcEkBFiq-(`OFTMa$2r^fZ4i2Xb20yrn zYSUoOo4g23LI67Gby*KxJHPD#_RyQzquH0GPm8}xo0c$5v8wjH)8ad84Qr=&9TDhN zy^Rz+gC8z+TcppzUW#iU^B_#Fw?Ssyjo&{bprEF#aFZNxH8qO&P?^p1JdH-LGDckLuEueVX&hSUfD&-WM;G&=oV!DX&vKG2i7a3H}+yC+#4@^Iq# z>n6W(c)wG<>S1*+32jXo{AB8wa3;t&mq}Yz1=)EtoadX9Qr-;Wy_Iv?|sEiT_MU+M$HxGFiJF+bojnVMf430{Yaew4_aj+3GfDA^>jMV%swEZ zSIpD<)Is_!89hxf&Dmy|XH5^;?*C%hAiaK98Jl8QVpx1^eY|U*jwY8>cUWwnRHG%D za9`h-x2qM6Im7zWrHb^LGOubW2XD$SpGN5fbtuBU_!WtiW#(nC^mit8 z*E-L|cdBqgPkPs<@NB}gPwo8b{wi-gSDapApKPi+w@Tz#=WIl2q>fcuVPc%e=t-p1 z8H2f*J=AKXg`7p+q=DOZDvWKgI&Ow_Zs?#!APTK`>Z%ux(~=wHIN|~Q=4yd;Vg~l|cp6dC&x}2?$=`$)-PY zoRxb{S$4RP{-n z1!X=>@DN1<`tojxKnmKxrPtWa)m61%^kmDu+4jXR@Wk0jA<_S90q&BOtHPy3D?hRV zI$5Xc*M|g)NKLbJB%mC<3iZmjA7PZMudLtsCx8*TDOC+iQ{Vv_QuJ1RZHjC@)H{ZC zZ?w8o#gV+0KfhG}*z3o?v>xpVPF&}Kp}5-f<+xS-dOO6%-;0_6dO-3>B$SkQ(m3P^ z==&MW(%XvERj&tW?KF9YZZ8%*&*1sB_`23Wwe2^Z>H^u zE7b5d`VNjida{esGwA0sfy)4G+IVn5D7R(@s9u*tLC5X+{S@yQ@#j3&j1aB{zy~qt zMUBMKrL`;UF>~FzT#RJ4FU~-%VpX*2$cg_z#=K!xNZo&2Hh)WBZ zb=dSPoYn;Z@wNel`j|x{j54&*tB}U{k3{fwO0!WVhMQ&jk4~Hy6CHc#q_lNa|NP1# zUG=$C>G!%ZWpp7;bcC78X|}hJW-+^)(x^+Qv7KSJ2FU=kw{tkIVXLJ^Sow|UnqqSe zyf3;!V&9n1Y`od)YpVRGXD=-r`16k=^@Jc{4@vAFb&`XoWZQ z&Ayk#b7k*3NT(1yfaWT8W%h+yg^>A;b;#b>TUN7`NF%n5ne!(iE#ioCNjWjwp#;|;HWbpU6IQlGSWhF*l@Chgh2=imjj zmI-F*TaoQ)AK+~Iv_UZndJ25%B}Cj2kI#9VgXmyyatK89;cHsqbg;S2L#Y`xp0dF$ zOP8iUW8N_-u7k1YFH<%p#duU`}Aa3Q1)Effnp(sQ+xyaoG%l`j566 z?2T_m3+Ts7|ItnuWE;Tgu^}grdunLxGMx_?9WttI(iGvPw0+z6YTNoWqJMIw-u910i*M%pd;2hMiuYew&@T2Kj!6?wFy5LF4o^M6R*49-jJx}o&^{7`_}O6 zU5McHPpxpjDnp2#(B^02_nl)^p!Lzu9I^P+xSzMmJ7!kB(IE3I7Qtd!LiTW$O|{16 zTxS;hqv^?})pC*>t3)b`0|z&4@Y`bjwyq{3#$f4t+EpaxNymrjJ(G?Rl(7{{R}Y=v zYirB{E2=TU{&wYm?F7kfPc%wozej+Yj!x)*(7n>KiSn#E1W~Nz(c_(+=98dmTCjQP zWb!e6b-73EoiP_kDcu=_KGTwTtqiQ=Rg8#3i?i~7cr#rY~QQhX$B7fo3LmL29sHQ2{kMV`}VeMZHYdG@#xhL!myY{2aIwn zne_Lxxc7yW>n^7FTQBBoL>$bXxqsS;PHq6Wic^dKPC|p)$PIxQ*agzjE(fx(hg$=3o7billr#=avrID|}}nt1`J=avED^Xg15WVe&FOc^bsB`Wg0|5C#N**pHqBDPFnn0IuHVYS! zbs9ySqJH9xOAkZD|*jhJfJq(C_)bxiYM!V_R4fjCrxm z=l)kjX%0(##_+LBnbnT@FBRNn{SUQUb$149l|F^14ms9!r298Z*q(M1=75C>k}NChyAt|tH%|$b z35xX29?&aXrVoRPS^#dgEXdO@yuvhQVR@JD4#@3*b_&(Tx8SLfz}tAxae&~ANAS$Whu_r z$Z*(PnRm>zRya=(J=K`vUH!HxN>6Xuu#8A-L605ziW)M!6}#rb1BX^4GQK7=xM(hx zW*YqstB8$ejBDs^(hx_O{X9~f&(BPy4bplSg;<%1CN=wzxpko9#?d7Y3(h(ur5aT% z?AH!0q$&81)UWMC)L{_n7k|oL!V%#0X3Nu@R7|dmaAuv9D#}i?F&yjU@*uKD5_2YQ zcg@`5vCA>vjgSG-`}c=$au&R(?8I@_(F$)1$Cc@)b(e>rG6+2+$%1HT!$=F;F;iOkZX<3vtZEFVmF5tZK`SF*vBXPzYpW3;**76&< znu=59x@db9lQn%A|62yf4)g4tI;b za|pT9xUwFcD*{zvBTMiOz-0pH%sJUQ*QJ$*&x}aOo0Vw;=V9Z*+ z#rT3f(0n9rO>QrtOO;Q~O~9y-c>z*szklZp%LU(l5PB8SNdMMOD0ut#T}lR%W65!u z0L0i~^f!*JeOyW__IRCHW}eldUsc?BT`OF^@+npD{Y&Zk9*k?>$hZ&S>_JWv2pGymb+O*i;rDaSr1dCcPH^ce3V z9f!P%T&B}6-6ubCTO;>vI}W{C{RHF&V5*&)XL4^jhYn^b2er#tmcJB)Te z0CT;Q1K65CTboKIl4r#y%+*+!FpVQap`4CKVVgj5i$GF}RFt!CsvEF>zNoab*N&u) zN^+PgjvS&N44V8FGrkbE=??I>+Vb@E< zkruf{AV1r<3~U=;>rbJ!pN| z>zNg@D%D;SgAuc^%wE1TEcexpgL#6&lTFe%6vlcgE)}sO`sR3;-J6q{TC(rdX7Z6& zE{e4)MvUd-;x>eN^<~u)cF=HwFeiMoDahz;5M`*n`N7)hQnFkH&@@0b{dwl zLm5m@w-vSXOH)YgYw&==*kc^{*0|{e<%XJaTfx>0w!6(%tX<>Q??Knz4v4=0t04NU z+}5o6v^ZG^Ahws++}aI%9D3TL+6+d;x9~^C2X#k%dOw$1lT@s7ZekC5#=Q$s!6g*k z5+f?R&g&NF0aj`_2Jxh`;zJ!Nao3+q~%ChFmu9@B}dn6 z0R42n`&2ECccad76RZ7lSDk220dqF%nj6F2qGfU^v2YfM~ zkv+t~1hi@5-Oh=C#gH@;~rsNFG7eRCw8FRWc&eX`^xpE{dreBz@IB71vi-Y*w zRsL|eCLFfN_Yx07tS31AU2eq7F0KGTx6sFWrHA?flf(&Lvv)10W?|Kk&;BIS5MGsm z={Jy^Grs0EqOqcv2@YFSN%B^HIK3i7TD+r^NNzp35;_>OeR7Kd*TYdJ>A>8oS zNY$|FVY@hi&*s_LGSrbTAdKwut{Wn^az&<`&X4CuB=~(eXM!?d_MCl)7m$>^Qysm^ zO;u!Zk3o?MN>Jr#p(Ipvg8};H?MK_Sb7m1oP|Pka5Hz2^Ua1PHz>j=HO6yw(rIhN= z{#6H8h#)h41!<%#Lkw};AM?wX#%K6V;8+&oo-y6uoK?MGh6(Hk_NXUPM}u4R2*R}P z9}2L!EpjQ_1*+Q*?^xdLHK=xp$>bS5Vg!;xODtPn8_O{Z=AA}J1DkVv0TaOM2TE73 zBB6bwbs2-}jf!pwX+#Vhnuu&l?qOU@_r)DzR2rM6gSAGwcs|ptnH+QUz#o{v(dtfT z*?@;V%hZk-X2~|;T^ob_zVjbXjJ*?Hr-Tj4o4MlZhp@~xcv20>AUlF=$L>sA;b^9rFpZQRGg&E?87<&pBM*PcQ#naiyz%(#!h4Qd5BD762Xaabx#& zJpfZAVoJ*8@Zc+p@qkmD@nq1SJU$pu)`V4O>`qX6m z&+qx5^cXQarx;=}jXhIlk2mX+iw%dTHn8tA8FW?PfR`8l5{rl2+F{!c1+f7%$hnf16!v?ELRbF)Fakdo1wQi;{e;2#V&dXB0DVQo;LjU4upt)txziF>hsx z%#vZe{?{q95l=umD2$j#jGe8hBBQkVEZ4|!=wMb(&DGGPhn3i-fsA3AY?qG<{f#}l zZ3@*;uSW+fR_ZfDXoM^ra<}O1=PsPnpf@A=d^W^20n;;%D6aH~eSNgE4jz|zxzcN7 z-eFVhJ}2|(v&LU9Fy_DV`CfG~74F`~nCBtArJI8Qq`9}|V@D-rd*I@vm(jv7qS$pL zzQ*kP)wu26o@OzTc3FS^ZW~jNQz*j{nkhYkq0A5v9q~E)qeedh$4*YHf#O1laHGlw zP)^#!MI+qWlB@$)#sapYJfZ$=dF!dgO#S2B!9_Ib1Sfo@ui!9}ch4FluN5|%uWM`? z6yeJjGAw>92DcQ-RRG;TPBsDJZRee4gU-HjQsO601T>pM1Fn6sd(-=*og z9)MBlAz=zEkAf;5g{*7Y8~pxjS7)~AXf*t;{AwXxews!_hU2CL7p{suxri}*>wzBp zAue~`@or#xjBIPC1GzsmN|RBcDBXQsXdP50P-c%B&=Uai;kgs8$E&u&>4yu?IYdf~ zOv4D`2ie~FHb(L}pI?ks8R+ov0qy~wLPRkc2K2NNQ6(&`PU^`;bPJQfG3)}&IvF1w z!foBQ##kfvgNsi*wJ;7t%S%yhAmqu?g%RiAWRe5Z@`QVC8T6mz6!!AIJvhrtkGXbn zK#K6@6f0sY)J{Mp!NC{|iV08{u>ROc`4_%SGUvqg(vQiR6lctV97v9q{jVdBP!bS8 zpyD{x>j})L(?!KF4T;($VN2k@Mw$ohi_zH1Zn#$*WdIsmz&R*$aC>t+a5N8N|4MZAUa->@g2+Mo?-ecH=RJH-rz~#wgv8YB*bYRMEF?oM5F*J#6Pg^GoY$!+ zmbMvB&=Fd_yQ@a>g~~i8fUGB4Bk%j#@ptWIM$3qZyW?Uhk3rze-q{y4x3X6j zfPRQaE++HbgxN#tAU^i-tO>CIJ0rwBtE0FrpIYsRxMQVT!ZKK{#l+`TjvRzFus|)_#V(DG};1D(KiopN-p& zl6G!pO`4pAY_d2^KoUJn@97J1kM*HbU~l{Y_~*fek(3&r^bE>uG>Qe=MnFLk5}BQP ztoVcQ6FbQX0BqZ%ir%YJimGCf8#gOr$v*q1d&f}8J*`<=GMj(g#EQGTCX`gPpI;0{ zsE0uNAlkb*o<6aZZvdoP2eSyNu-3$KElp(SzM*mxKad8QoljCSp7iab`f0KU*mhjz zo~s2uJyF8tE{>~Zj+sR~En#%m7rHIi0!sKK+FL;Z{a)+LKzAWI#@nwW)K?OB0?L}m zHE21ADc`0)+$1{yRzCG5zINT~2wegi?vHjj+yA6=;UpHsluKI*L|tc7w^y4 z2Nv4Yvf3xWfna57cndQ7QZXeFWbT;I9Nnk`8m?a*_7Y~q`x;Gu0Ne^qrvT!&U5dsV zUIU0|=c`gTE&MbE>yWHMtv&KsTSp!ePW_t-&lY=GP>o&9}>sTIok1}MQnz@LEG z^VE6)%3)PALO-CB0u{e66*z6ecX3sgG?} zs17LuhoU(YjFE1gL;xM~5x9v6{VLf-zzzjH5&I#)%l)#A!<4NCH_U{wujz$szvg{) z++P~aa^Hxrrk^Vjm$Hnio-ynDRa2g6q_`ZlydM;nk5DVwv3c->>09!0f4 z=$k6)PX|(pcsekvJVq~x&D70G8>K(rwkvxq=bwaEzQd4PM-o=;?#A(RW8%z`xX(&` zI{;FVo^XKuO3h#b^0tWr8A7ai_K(4~@9o)wRxskT z|7(qTT2IL%cCL{QnXN3fKu|f$pFTzh6aXv+z`V(Y{ky{f1?QGX*V8b@;8y_!<9R8C zAiubL%XApAP*7pz6T)1BGTAXC7d}-XcQuLmo zWKZNH)C+0aCM9W!a-FseMAmS@)q>uJ@xCTtb0-w`{6>LlENMV8Da&D0#}dUQ>RB?t z^Dr3p-C{I%xnS}4u0X+ytHLD-WXayWe~C>rp2>r3ydc?taL6_KOIzI?xvx1k!3_`; z=qw7vytT<_S<~%4WyLIgrOX&^P{t+zssR7+!gIzOpZXfP3BkB}5DD|w8ns#I^7@ng znub<`B>jN?=ZGtjXU-o$PeSV6BsW9E19v-4_5LTUCxck6lm%CHr@xm%&+$?4)bZZd zS9^8E)rMLN)%FWO+#=T_G1)vLtE7SjLt|ZrJHY=?fHCk&)OWpN=&778#I7`%N43c? zPvm35T;@C63ah7`M6Jz+&Zr)DQAD*}RD(9J^WV>nkMm2_@TP20Q%N@N8GQ^WK9{Qn z?=nD!hNXAjo?lNcm+v<$%|A@zo@U>4k3t&coHgjcw+I`59nu7| zZ)qV>*2^)Cm@P|HhJGBN5(OF^zaQ;$DEqjd8VuL>0ZkDoJ8;e&_D)q4?o?=ZyW^cw zkH8*HWR9e-M7vkIiMr3ohh+mbg0v?@X(}WGS)S47`S^^% zB+LoLSQ&iAoFXp)*7Mk}Eh%~YDbbb0MErQjXv(P9jD%9Rt7 zv)-C0ORHt!d(-|g#i%wQw^>c_j=qtT{M2x)yJxk$lQm@yy7LvOB)s2&PJyIUxC$QL zUHmOM$EgIt*BLRu~?e zp@7O7F7-fDL>pdBkS49{16j_SVXCw@xPtg>skz&^oF#72|HH?BfD;Q8W24h;K&(ua z;~d`yU#bhQ6F$(fJ!U=o+fe0XgaO@5FsTGUmzR$%Ia|2rYZki=X+#%A60Z5nOwMBJuJ;1;B5+I%U>QJBZJ|;Us!iVQEqEXTs9_3E zV5tDzLc|@0Cx<>q0`vO;)BPl1_EumTVH%_GNRRuM|M~#yb>FCQ0fIW|o!?LI1Z2@> z%-+{cmews9X5H_Gl?vCa8Aq-W&o-onJaupA$egEeQxn z^zcUG!MyeJkE_ox_Ny*EHkhU5o=62{{H+tQA)l`5iv-hz{1#`SzfCsh zo^}h((s)i4Uxn#rGKFb4mX}VkojbMKCLWZ@DU>_B^9P)&wwwy=_Y7v4{#SZ9PBBL; zEBT8g+~T*NcCM#1%j#MY)?wX`zhqO zinfpAmegJ)#fd&_SPMZy6+*clABgRXslmWh3h4?Mm^S5z1!D z0Al+%Z>EC>gZsOD%+&B+=18N((B6`43^!}q_js?T@U=X*pE%5-U+cGSl70Cp3)Mhk z)eq@jBPA1Ty@U_m&ubR@-7QH??sG|2oL)#qa$#;5MtvIHI`yV5{QXm`@9g|lb@yhT ze^ z-zmdG5?k@>QJ7im3y2)E{$#}Qt=1g*!#$%-i_851v!^HL&)n}_y+Lt?LXAdjkJWs( z&NWa#9HE=Dje*SX*G~5@*pIaXtFbM5^y5 z)s=N0HwmL@(Ii9-+OiOBIf|{SGhKTW=j&^+*4W{yX@c^p`W+OtH?rVUsN?2;yrz3h)+AB~$Y~5{KBwqE}^c5zMCUKUIA$6kqk0%2ZD3|HR z_Z>368h!ZfnEvT%%%5i0P=xu5CzwsP8E_6&{r|X@x=%LoIo#+MpL#PV5PXt@n&)?5h z>d++2`fKpvsEIVhn2JJG44E%%CEKv3B$mvrg#I_dgELq#d#h!Bv8C~%zjF5xd!EP1 zyA`L;oBT@;HZ7*hED=fDlg76)sGr#?oj|!`$vW)-++hrkQmSLDRty$Hg#69>bQ20@ zo%m3!2W%#|FsK}6u#eDBOUVcG_oX%)o}6pod5huEld}E47U1B7aT8ZkM!@EN3%;Ax zER-o?vg==Sez9NiS{4~;lp|^$eH{dnV=$;r^(N0UoAK?>e3AZ={h7RcCdA zhcE&`x|*z9Btb>mh|H$EdRmmCYrMI?wOFvd9-dJ?<^j(i;go7X0-Jo1E?(z(+yxyK z@5901aAC?Gp!yJ}k%En*dyP*r%K4K4m?_^?k>3kct@Kd~d$*>zsDQo4-@S5?S@%DmMGV zdkwFfgL=@9V#=Y81Pd-2Jfd^WvJe0=q%A0E{HQ%$aWd+Qg84gv=*&1c74hRXSY@F% zsDpP6rgAEzu-tp(aZj=zGJ)PwS-t zz)2f438rH8F!vF@lXj;5D5&HMR5;YA{!qy7w}|Pmsoe(K4BI(V&&UNCCyZ*feyb}0 z^|?-gsH3dyh%qXojjXeH%%XPQ;$$JC)t0jo?9m3{ZB^~g``fugTBX;hdX{{HZ$BgD z=gtcmIzRxuC!aOw@O1%0;J?Ig)P$6;eZ}MI$q$m%DRTM7*h18=m<|2#T>aw$VM-Fj znv;m@RgdR0{u~!P(|dAjS=9Z~mOd{cZKVAbPsiPB9#(dC}>(XaVd- z81zVvqR)mgWLdzRC}CYCtP=RAzK!@Kz<`QN7$vED!eX~e8}IsHfp6aB?MEtWv!A2a zB3KtQ2e?4PVM!qxu6edlW%@hG!jczHN?Rt%G;!I0O)Y;otwJgg1MVH4$H@ zP_BMbs2r{yf5$ADIHAG##IEveB0e8$$|bl>`b^PkNoT`{N%Lw#p8GC6yiGlo2Tw>QQPEvL)94lb#~aj8ZW8vy45$VM|@fHbCK{j*hO1N1%ssdqKq zQgAkEERlPgQo_Ulv@-!5GgD((v`m{f4a6%y9*-(61WW|#72=(2V~vKK`{)Zgo>zC< zV3hmLMg|lR`a(?-wxVDOdli}hl2zgj>OaL#J|J`6=xV@=!SslQ22XbDeh2dLqR#IV z+S0mTjHN3{!5O@O6KZ~`|N3Xev3a0<7qqp^2;zZU_@rjwJykT*6h@V^p8lN07}YOd9UL|$y@>mlWUGkM6Ixo z#`Lv+yx?W9E1#&&v^O%s zaZ_ONrQR4ZSL5ur#rF9G@i1JLMj*Z((J%yZB1eT@&5BNAb}zVUs__UcnJ>JLc?| zbAO0U8iGAQf2T%rpUgvS5Dc7$R@o(^*h% z=FEZ%Ke5%u+s-okmAKr~X_{<@QP(CPJVE)TW9D@j{X%h79d7%%ns*OI*k-R|qg z*SzLVv3p~fK)*!v;Go)n&9Jr-hHD`M8DT})cPas6IAHVvHX&N`fsfC}h)HZ-l^asp zbgrwPJ_h{GC9|=4iI5Vcqs}~?JwFwYFEP5^U~tO5Y}2H0vu&beLR0EBo1$S-aos8a zqBjOqkqO8Zr1Sh7tsUrVlOz{xfP37ZwelT}@zvRyPpHU0pk*7T4UD5GdlKruo$31k zM66!*f{*nFQAE3Mu}%kY8;)+aFF7y%#yMW)^EQYa7Vxy&u9;?H-GEJRD~r9|-~4w8 z>hgDKn|tq@CXuv=8lj$r)5m~uL3*;Y@9Q)rh7?-Ij-1tk3ilaN(SU2Ck+bO2O_gm-EErM6R@&noiyMz!RVWwOUSSMg;*39WFCL(=FE+f^h7evd!CE%J=des^w<$@(;|1}zl? z{XLiQ)DbpS;LEzNxwEf%v?_IJfG0uGeBX>%pvK6QlotfYk5ePQ>vU7lLU1kM-??qk zgly0zirjqPk-yuo_q4a1)A?j^K%scd5etUb><40Bc|B@F`%I3HlxiG z-hJiSJ3!bsd{)t8MP6%wt%QgD(4~AU`&UqTo;0;b+XFPhfS>`SA&@opMnU*+esnV3 z1~TS_-}Atk3z>_4&T)#-?be^X?wN5^k{yblKHdh+jomxYj#(P$n-53{TjGkRht+N? z)u^LacZ=q_ykkJd6QI3y1oR|NDv>f7Ew3dzz{;iqYaS#UH9RgDw&%qMpaZH7$ptc_ zInZ+h(E_+b=-iJfkNqMyoreb$#(<6`ViKhcp$B&{jojAmfob zxhPbNbUltOfSviy^Lyfyg5Tb1+lYULenS#W2NznQ^ur2wn55z7HUVH%EfF|TQXhlOvKx;>qRT*vhyd>+2-yo);@^0@-EpgeWHAvUNyG3_P zfh$-mqow_jG)b;yd;PZ#riuWij+dOl1R8AT{kq+COwR8u8-Ga^#D&5v6JN6tA$%(1AhkP78hpp;pEK?7ZXRs?C$#WA$8bv*ALmNkL6K^xjPd z8a+7vPOomahu+Eg@xX$pZ9Mk%#kKtxv&Q`5163i-)voP7{twqR#>|7vzzK)|^g38N z{yvXt3;sd4@1`=SFB5so)5*0Md2YVqR6NrpbWp2_qD*H;MBoNn)eF{qe%K}MCCl@) z!*ya*Y^wj2s|vc1;NNu(oV6#z6$Tx%dL+7(hl6CcXZ?bgjR4m*9sk+fC}T&w4~i1f|_3M@?P(?O9YyQnH;%1$5sm`B-VD(6f$gL#&As!xxr4qX&=v$|FY%xhim(VvF9 za*o%RQHCvrhl`Lx-NsGJ8oYDwL|RESWwUd0EO1AZX#V=>|F@jq^qIHsTBz@Vte@EI z+&*SdUT1~U@OdesN-a&B{)`{}=M0v{H+&Qy zyNX3juJ`q2L5f^H27bJc1uH9)H&k|{-kCnpP?o%{=dYt>21gFLNOHeKk z8N3E%#hGH})KkeORS$z)3Fnpo58++2Gkvo%9nM&fUoU#}I4QdeLS$Q{=ElakK2~P0 zezy3)5dW>AIpcBiDCaw;j9*}qQfsEr%=*a0`iLlc#Qv0l<4N{lRr8=ur=y^P9e3<- z?l{xo&<^Kc(#hd_o$TLS2Kd_FMaE9?HH6c14JQ^3i2gY0vG~xf8E8V1$sT;1=-S;? zX&m8Q%pXesW~fg@&b3ut++^N~)w#u;5b7 z(P+Ze2`%BT31^#}&BV6;c8C=VMb+)@ITt<|Iv9Ep`s)8^`s%PK*Y0aU6b`63r1T*M zsR8MRgS3=145f5;w+hlAHApKUIKa@|DxJ~{E#2Mu-S~dLzwqJ$f#+V&zV}{h?Y&8R zrbpu*3Krp~?vcg&dlqwdKh%^EbYr(msL4^~LMCl8<@Lh}-(J7=|5sgjY%Ho$hm9nn z?ZBELWDVEJnTqZ$_h6~9M5xXuq~H{lc@E0d8q>eD_etaBrUeg`_#j)3YW2Wp*R}|$&cp6SFHQLlQ3pg~?`gw9H2J&D z&`&#yHHN9M2TndCo28vqv{DmXnVVzqkB8^)5P!_*Y{L)_eq%>xkn7rX?d|ae;jHoo zmwiigf_c#%=zbC`dcw@1^y{&!qDk5{JETN@X*&U-$oGnh-rA*jpQ+8Q+aw+GX}i+o zwjG60iy*J=iWmtnTe6E2s+CpvDBXgs8SFHF1OTy&?dg%-D&SPHMt_ctCYq6G(w!%2 zu_KwFea}-?Wu(AvpK#{yABbOos~&jI{u#QrnE#c27R$8N(4*Vcb|HUV1t89)gq2-? z$j46I+fv*o-2$O$&H|Qn*xxosY^eqYN%Nm-jg}|Kymz zn@Q$r58$d1MM89d3Zy+#Zf!+t90{?^r^{M8NK3i(Ug-nMR%vU41J?crg!%y zB&bB%E@a6t6Q|0fh8WWK#Pa$}aJ-TbM^;?|C6ZV$w>PJP+4@6F-^%#BUbw-_TS{t? zzotug(p2lhq-U&Qwf?5+EX-5#QkHqH&GJOB)*)UeBs~V-CHEUQ@FBPxf ziy?tuoni+wik=0H(Sn&1H;#GSGS_^xM!QJ{Qby})?7+_ zD5qlG4&uI-5fwAZ^2}+S6T2zP7+XYdBXat3x!qHPH8$G$7ym>a*L!$U*q67!Vd%w? zbB)qoCHho>0^RuyJh4EoV=wp6z#eiab+>q@$H9Hy=kzA1PXN-0 zx-iSh5f74{o~ZbOJT)yP?=|MI&SaiC^|I`eU@NPF=M00inTf{q#=4=YF~xf23vOXJ z!#Mrd`7fgdP&>ojCe8VdWwi+5@5_bjZd2dvewJPRXD%?#b@M>e3Tfo?UDepiKadmV zr#mqi6_C%%(v<<43AId#sW^El0X_zT+6u6o2aR zxcl^}y3Ul4U;{c^`H(c14cBF(OkOl0neYpRTag)eF(@*I@I=^+nwU0VeaurMNQC|6 zj!tc?taN8K-TZ)(RyH-^amq;Zwc(8fW1r|gfOxaJO(EZMbb|V-0sKH6vWI_;!ET%I zyJbMS#or=fIQ0R74-drAo7L_p5xXJUB#q!(j@y65iQlG_=I@N?VqU$teRDNsX1LPC zsxEsHKS;#}g$$NxDS)*FpveeX*w{M~aGiAZ0r|aA!|O^wyu~lMid~bsI@;F!HI`K_ zlFIyoL)xR{siz_qQQt{=HgrJXxWaI|o_zDnVUP-$pmYaf=9fhgzSR1)vETYI9R}kv z!va0{UNy{*sPZM2wi%b|7-DMujpZW4*-#5|jER00Zg#!7qwH=Ibyw_q=?OZ?Q=x1b ze`Rq+O9z)si2Z2|FSVo1mEY9kEr4-e#%{ha8NW&7VH$TzuJU`G*%^DO`CsQ4TA%Am zeIj|bE2wsPD;>%!O&p?pi+E!5<)bFpv{_<@B4_J^anv(& zWsy=xjMtwk;-hN%!Z!hC>l(J4wQahz6@}+|@PFG#t)OBD9@D4RPDu3?X(uAq#)_rI ze9{IrLW{=YC?d~-bPB6ve}ix?Y9B@1hq;-U)I9+{0#th(-uLx3RlhhlRzKy1G}`pm z%?Ok+qiB7S^ipZfE-RMeWWtJ3({h=}^268ufguO?tzIo)f2=O;Kpu`JQjihR&UNAI zklBC>u;V|DI4O&>(9#!(@>FHZuek`O*FIXvU0ZBF+18k2r*95yG?&fTUs@O6Pd^FCM)Cl9;HqCVZ&&9|g|Hi{%FCy=- z&OY3k4yn%S8FKMn{5t^qf2Nr~9HiRf)=kd67qBd&>_8%5q;T^SwV$cTuuj&8na7XE z_7JxZla%k3{sdEL_ed##sg7Sgf(;rya@}!tFMzKhYPk>dIWL~?%6t40$sm0sO9DBR zTsd84#qdnKV(ERa-(J0D@a_uDQmA@f1Z9!cYC8PjIU{b>cc^xZZSJ2DbydBQxWvAf z7y2fR`L9RfPQT+`!w+r?r#r3sFq=o2oB{=eP8?=fZsTaaG?zv{m+ri!n)&g|KJmF! zr*!vXvy8_cH{>8veRZZgyI6HWH?JS7^m~Ra$(lWh=LiZNsv7~2-@s7#`7VBWtu#it z`5K#Yw>(1XQp~m|_hH6Vgmwvt+8-dS2*{>b@c#J1EE*)Hl%Ma{D+Em^dEGy9z^*>L zkqPse8ba?7(R$QZ@+`Q?1tELwz(g~?{aKkX_W6t0K4gP!jP3T(zig>-0)H0iQ-`+y-6q-^{~_jdv%NEs5>~5^eD81-{CviB6oP9KOr6f%fXxA zB$+(JrqZ-PFFkhXGyvaW5fgUKA+sjxoj?(I$}_fqNuR2RCM-mO%1+^6unL) z^ZTqMkrp~}$~X2+wJx153dDVO>jZPQ>PCOtvS_1lUv{em_yrRhzd*@g)KFcPuV_)I zTdNw8t3SIKc~FAn5T2>dUT?0sv1tJz+yT7vqKx6k?XgNAlL8@J#CAm~%eLGqBA!1g z{-_;|gZBBjm|zcHL5;JWrxJ|s`IPO_Kkz{JvGzdF9v?ei3sQu>=W=-+c z`1N<-_LLubrpJaLl)dRZ;te4a4WEzZyROtT0`WaC%n4l7mNk^I$ z%ac3yM=^?E`&iejTjppuE?0hk%Fw~Bs;=-ixo$m=i$P{onO{*UJ5{C>n(-wF-p$hU z`LRkaui_u=Mds(YIj)9#Pi`_99e+KWY#Oe)lE07CcOw~tDEu7z^X;un)5_2vsY&w= zVZ2S*#Ilx1OL$Mg2m8EPH5-6ol2vT@5Op=)mm*sMK6jt?s-jy`_pZ$yu`cYCwvbI8^h8 z9m$#aIrgy6o{>Z0qCV{01G48AeL__)`X$uW3ww7cO=rbnr$I1ng*$ zkIQr$}3G(%Uhb4u+O6POftE{ElJMg{R6@8C21eU>o)exiS_&wF7mv+> zHGWN{?za`q?)&oyGU^;3ws0w_~W?XwaE ztZDtN2LIDkIJe8&YMiyfI6X!0uO`QRr1Y7zki9^P(_a=-D|#q1_%I0A`d?X&*1mk> z@Cf@iYDH;feK-#6o?ds|_7gW9Bb@J%+3>H@F;BvQTmSZNi=2XDew6+sQ_naDz5F^* zFo?Gxu&b#+nd%$ucx=iYEt1Wa=ZOF7ltssNuA-h zG}})x0N+dwt4&RbEx!ie0HSkc{?9zlipj%14lAyY~wc3_kje$1up1*|geQsa0Lu`LK25NDx`iU|e=6 zm?EbeXl%dY_DP3wK0{ZU?Fmx`wm`llINf&`jk}y?X-2UerI1(8 zv=~2F4fXeD!Sq*BD0)p?_YP&Bc-hxhp%f|I; z!KwHhcJ0D_i#szA-;&%Saj3tD^IDDg$^F$0f6y5ay|YRQJAZEN89VTHq1W`@lf6%R z%l|+eu`Hj;{&Sm~|NDMqXrOxK63v!q*~3b!??2cU3cHx^ya7MN0wbQra5c2 zkHP{kXILZ|%^c#YypnLv^g}380aB;zFbU_amrG?7cCvZ%Ju9D>+s=_jSsL6!{x@T$ z#tHSU`c<~;VMBGv68n`O>`W_wYO}`p%#fefjB2bInv5OWSGVWII3HFSdL3DJMYSC~ z8uUp;f3z=uEYGktPM@hl+=C2lY^TICcw@?{Z-Z$5mBT%oeD41t-%+wO?bV6|Wbbi# zAOxpyC0&Mc?giufBNZ%9u`;p3#QL7idrP zBDo6NW2PdJra6w|_aQ^X;dzM=o4o&tE2f0d-koNWj{ngy<>XLFpH%@SHZdEnN#=@ z_B6S0xS6-BxFnrv)Xu5_W8wiCREbp0kyn&o-r+OF*x5%ZXa*CvynT~hdpg#_-7+B6 z5}-xQ7#4iMHP5x|RD=+DZ0k~R^)jfz;Pg-nRx8)G9+^o%s{$%GW_%<|T0Ru}o!^NV z8bFfmFcOp?5pB+C`b8q_+Qeeh)d*S$rMg-_iNQsn-hFG|Q7Qd)E9d(=P6gaqmV^Yg z$)RXkNXcmDfV(?YN8c~otny(Y@s?7D25qY@mYK|^$9Th#f{vaCa4vL}0l$Z(O=azm zRAZsw1HTbP)XbP$^e|b+Hf2;!qZHGrIhF%KY+7QKuym)l=2vZOkS&3*Hp6ZuWlLvZ zf+p|%RHl1TVH%;QlqWwq@rGejMXE)^e6s$#QxbX%NPO5IrpS08m0eeUb(xzQ!4i-c zI%&~W>D?6$cVy$DB;_MDW?|8*gPYt9`!Hvb@Q}hsRSleSIc$LfabcdL!>j*QOv^@M z*M!&{QQ0Pn82`i(qqmFSuhXMrgbx_`z5Yq}x(|0pir53~I-}uNA|6H8hpWZ!@>pLa z@6Zd)+^xli=Qsmrb94)s?AL$5uBf0F`fV#dc3>)Ec@a@gHD0UqJ$I_U;iC>wRp&U{ zpuc!x73^08=Fw*<{!8^R;Y~4*yh~NKCxr=q4+KV0xoTB}=~Ae0Uu7p7wyIO|Vv3ug ztvT7LlXatK5N};;ZWQu5;qpdvlDgjNpH~>b`Ar(Ev7eV zFtn_@1mR_B3QZOWw_HSI=wiV6>>WZ7wZ?6QAbe3im!w;AHa@TM$zUHVRwZ^%#_8~h zIcVQsH4i)S<@D|9>_XYw^$)ogO?lTIDBiXXmT5EXN~2bj=rfrY68h^WhbSzPi>N4E z6_e6BcMC%syN|r`wr`x5%G(>h`Gk4t)$q)oqmG#jfNgoRE3GZU2&ncm0C&W}}$+Gce}pWJ{zp0VhceYtwJt zP{!D@d&XQ}JO$`o;yWk9?#;jkXRd2lZKUvgTU{`$E8YtTr$PQCj~R-}2+f*Eqr-c9 z5Ep@1*4$V{TnDVNRj<6tai`7b1nilGDZCX4wolhtU87BVU!mQ*QWDG7_p;FA%oNPR zHb!vf%d%l=GT|gSbQ_)Ax2?A@3!KScD{bRjry-T5il;7RHoNME5h7z%G0kdh17}a> z>AM#_dht3|Q&}f8&>d@YQ)Y5(jNXMuVK$+5GCTl`Q9?a!CYsF1Y7m zpBO+$3oZ&84dNT^m8LUNx;M>hs|1>VzBW~g&|=;g1U1NdrG16Qk9Z~>blP+YI7TC` zT4WpmIT^8x_2%!+Ex1r2d@n$Uty~Yw*OQu~e+~%^`SX1+ z-sP*Tg7;*W1}#aaXk8}uG(62+usm%PUY0l+5pHU?n#~w@re~jMzu@{(UTKmVR{QeD zYD7nKnj!3bp7TN&iCu4l==|fOgqjF)_o}yZ6c&`*Jff!c_u;QsDI4tFjM7oE?q@_s z=7r8JDPe8pDQ&zB9sb8d0?q-Z>Nj3FNQpJV8KHwZ*_TnFiAU@HRW+3wE3;tYtmM>1 z$58d0RBs9nocs3SGAGl|nvaD~A|wCaP`+773KeS|R8avY*&Y`)*}ScI9GL=^F$X?M zCnkFNIuXmCJFZPb#iZK>IWa1ye+6swGk*U@z4K#|%}!Be%Hz!nuf{~|rl zNLiea4r9?`!)3}iS;#t=qPNl;dd7hp&0=L?FyIuXV;R6F<+|d|KVl`wf`L_`JR9NVp1jzA?@z(>qv-f;}bBnN0S(Vi5+Uh zBetNmj#;EZOmfeoRkU=t8griHL+vt39qSks!-{S zxnAC9lD%>mf0%hwsnQFh0+ElAp?yQt`zazkQ?!_3nvaIatDfem)s3T^JVzZ+hDV38&_U~VxLsf_K z))G)@m6U*gp;PsWS>RYmDQ(N+j{U5nViaMPZBhQ+j5>>quKk1Sgy@SyAvHxTrzKlu zx?D_+q>%cY@;6a!1@cx6407MtS_dogAu5E|bnG^&BK4GcFU3a03o7h%lLT?}?|DeO zeQeRZ6q)8;IWf+lj{i<75?&rUgvQFx_!PSHX6!BR${%*`eGY7yfy){NYhPUIut4~9{ZbBMBil<%a6Mrz@2Mjo$qCWML%;W zCvo1JmJy6=uy1u`;cCQslR;QJ+0C;B)u$k|bU6c$Si4eNDu*lVxD|-piG!HVFKn(S zgE*46In3-seO$%0E9B=)>$R-9N^oj<56~N0wat>I_QlAk)WmEj9|>~l)T2QbSnVXv z(xpKS+-rKXUo@Xz-YPA0ax|A@tLVvKT|uQOt)oZk)4rhsXk%TbPw!bX(3zFv+Xaw< zsW~kDaZ-JN0^W`lHzBjBSlWyoFtB%%!P?^Q6`NQXn}~}omB+FrIQB+`Wi?KXJXaoK zaCl7&hB*&>p1b?ApFiAx`J2upzEih{Cv4h!y}IZg?;i|aDQ(A>-wJ<9t}?VS>xG>1 z1~gIOJ`K5u5j3dynOBn+`3%oI3NeZY^?u8^a709N`X4N@%3JZLsqa<(KCZPxa8tRW z=wxnMWv(^fH>drrbrW{hx5r=okKV=?oqduLT~uXj9nSw4qC-H<&Fd^|KXqIv#%wM0OY)!`Ts-JWXMbK%eQYU@z>H5)*nZ&(J^Oo*F!F*NW8gRneeiY?A!Mt@%~AC2 z*F|U!6Bn-;=|k9H>5iIS^rG4IHD6`85BF&ZcEwU)hFH}JQ_OuJ(4xMnPGVQ2CGkum z_(_^U-RZ)8I+ldQjfn^Zyf7?wpn8U7)w1i^zT`HjN=RUW|D`Q&M8pnU+egJ<^t{sx zH)GeL248Q`0yJa?@Uz8fF=z9kc%jhU<{I9cHq;-Mm}(@h3VLz;@1qUfi3zw`3>X<5 zm2Na#l@-5;-G%^Bv~JaUd4D~&Zz=V`iIAIf3;x0V^|Lwagqr^pfFN_3cELHN_YHb$ z<4I9(k=!J!(Dd{?4b8SEXD(>Lho@h}vgNj66||;6i}Xq@$M1%wrKmw0Dp(R61~@4=lyX_z;w%5-Yk?A{S)a zCz5mFymZ(k6LvXGUN6;oCpqw!8xeR{n#QQFs?(=>24uG?Lk^N-l?p9MUMr_J_A^z> zih=*Y-l#S>bYr`5V|Huw0(EW0Fu z&}5Y`G;ohU%68%F)x9LXu~G@mXGF9XymmvW|Dh?wn-tVG)jE*E&U}nF8 ze!xCUQ1w4HTvZOw((eXD#Yy(vu61nvKZW{#p81qAFf{wVxww3gy)JO92u+va70J4w zLXIfqz*+}u`sjmQo7R|VEdIC(gKs!jf4H(rDOU2h^xxL?lv;!H;QQ;R%Gy*Os&?&; z@2$1qlY_FRJ&spi6=s6QZ!PgJw4Zh$2SOv=(uAV9!%cR0otK`{*~XTMb91D!3-|lX z_;m~Kc(E08oLKC<9T<-5kZKWM#y+dkyYCG2K4lw{PJX`fB=-cg6=p}+N-A{c z3(eojN(Va20F9RWiPP96%_{cUJH5r{=NRv=?mf0hI3$P8W%-1;|${tPBH>_l5+_AM>t{0*m3a?z*!uY7w@2hUmgs{lbmvx0r5P|f$88Lwmj zS>D|+n2ht28g_mit0WQ^n-Ej+PmiBW=Z)V@n<$$u3VMf5fD7)F2Yj+(+TU@t3vjiO zxPaU(R#zF`eaU9iY-|51Pue0ng8Z9?@e?yFJH(d9_7Gn!*}#+g)8yy+BTS_OWXpi) z^&PO?yd;MbN>FgHT5$+Bj3YtRZpx$q`uvbk5xD8^$Y3X#T79pEYE|RvHsWa3g? zEAWK?<6XYu-J{(mm5@|Y{#Qu0M%aOFX835$_AdF`x^bk7NogAH0MHxOSEX8Zh~8e@ zQqw!Rm`^HzU#gc;jgP|V5{PV~{Y(I|woW!ReVF6P6^eS(l)Aq2$af z^f>L{D;f)5B8zF9zG2bUA7?3p$uCwHjJx(yt7)Hv2*_@%wGph!t(r(gTA03O4{>oM zVtli#bM;1yRqs#%8xAU0J2!QZ^*bd|#O8|zx!86kbZP`%9lXbNa(Cce2A!1Zn9;NeFqtClB+g*eGW|W>cvBkbV7@9Zkk9DKFdML48W?T&T3& z=3cTrjJVJzp<^IR7>>1TNNARtSb|+?>T1euQNu?!NpPrgjzK*@Nv|U81~lm#PVpAw zg+eu8s+RA=lnoSe^e%6CwwG)E?(U4cZ(iK~>o82vxepXCQLySQw&b2{;5YaIBMi-o znL&s#fKI{!Wk4I3ifNlIdw3S|0UpU-@$E(NwD%^e$^$%AiuZ?=OM`@;5sYDR*B^|% z42OuGGw?ckgav}oxZG(Gf+V|CT?U!m(T2Zwg{cnK78fM7ypl7M0U0l@&6a03XU*V9 zT3XQ{$h~7Z_1ShVi7xX&>#;TmFS1+Ek{|I)1B7 zvFh$m>)Adta2E3bc?EZK>sD}c+r2Q^xno|(GUQ*@cU@Pl>Z z+HZ5s_D#1MdKBP#r!c1h#ldirJo>1wb5*&zn*^u{(*6D8d6#I~pBn9d#jHf>OghMb z@-3sRpIDnjDqppUky~59ZtK!kz^|j6ib``>hZq9!s`ba0MaQ1iHUcMs8_M)$`X>)+ z2F89zKnHcj{KWNyO@sp1KH{A3*xrt{+T zcu0=tx`y!^DuoLf=CWUs5f?fgG1q@`F2e#_ zi<)%FK)wOWn@JQ9oTlGo&|jhSmN_8@$W9B)Gra0e$n z)m6^Ym&gr-Ai+)G$`161b`9#=|`hZctlXhZD3Mz7d(5nfr$}ykaj6Ar$`Y*zBW;GIXZ%)a3!9*Sn()wc{d1`b! zwQhZw-W(gU12!^wc18 z+zl|2GFJYw4rIAZ56=ZJng&St)D{T}=O@H>Xg*lXD;Cc3WxV~V-_#lmN%<}P&h zYg^YeGrla3Gl4$UG;`6Y1f>`X?m|F!R-e_Vbd0|OB2xqPf0R##cjM*YfqxRGo`&Rx zEUxvdrYK|ZYDv(1vf@FC(Fx}s+v#TR2%SUkuUq8#xC#*;xG)lz5oT3{3?;fw+9qt< zTE)f$Q^!Awv6p0f;zZKxcZ05ySMmy-?scj9QFrFsUdXZ1hR40#Il`Di^tASAR1Rk) zJ5^pDgA(rgc~Kq%y?ScrDqKCS9?yE62k5P9xTplboI|1ntWUa%l9uCyw_(a=^iZ7j%y8RghoOq-qQ)A@WqiQY1)9v=(sN(XEXw zkmWlxB8T2sFUw>Q(M}@E^%Z#b3ULH1?=bW?cF>#G->EYQe)5>`z-HHiN11_mTQMv# zeX#>9Fuj~DZMw{YK8nw}-W5x)4zF2Y=k(kTFA1npM%YAEdJs5Wpfpf0Kr0`aPWo`_ z{}l@>(r4&C)21~)JJ&C2AX_+owd|A#d|oB#I(8Rdv=uHUb1(HvdmHWTWJVnFsz4wC z!ikpV8m8FqYQFRx*4WIOANAuXr%XMwB%HO;>q2c}@2QLLqCzKt{3f5lZ&f=v>9lA( zxHFrH}wd!K{U2wVnQG@BkTD}+oJ2u47+Vlskg?sYaq;i~FA_DAVIIZLDAHIh1 z>U%^4Mzx`76z{MBSS|$_YWJ)>C5C{(qtVp}Gs5dB7L)qb-=w1OvQboN;$)#(m9|3B zi}j%RgtknpDVngFnT@d_q7L*40E+d@fS-L7CG`io`KBuWrg7A}aPeYJF84f~+748* zP}y*7A;_B~>E56q`K9{Xt8h*EY{OmW0;|3$o2bafA2}R`sj&^hN(p;UAOIIY8GPKm zXp;Z)%ejAqLY+Ne8Qi)TmHGXLNsT3hnJ~qY*GXB;?%tE3f86pz1c)j^bG3zy>7*1V zurm?0i}~xD|H6!s&kb>2KfrI)SMwEVGJiGvj04P^zpnAISuYXzeNNexA-wSVUi?$k z-a3VDgw9h?)v@6)vGX#AJC zG%!3|09%jAhR~cIvFxm`h@|Bmbt3rLyL$E<#^WSgUM_r}@L-M!aI@JW#*nm6bg5k8 zm}Z%|6X(9QFzgx8XUa~qs9=V?dyk03VATxHd-q*uB~Yo{?(VH24Ei5=AQ6K&s+N{E z{E|oW#g>om0N?0+PGd`GLvRZaK9wOQ!*au!p@Dc6io=x8ZQX1XF=jf~jPdsPH9S1)`N+XrB6g~P09@i^$K#IU|^P5?Z8k)7*7q8!@PHxn{qFBx1Ge zxs+KN&Vw$Rr{7cW;GJiWhkJTwd;)uOBPe=COlQW)|733E@z!PX+Htu@=+Spncv2Bz z_+@2oCUktk0qEEy(g%#wPUP$AO4B^89-Pnc-Z=u3PL-#RdTPErv|7RBtxqfs3q9BWnF^DDiAgSp9gRX;Tl)`UEqOP6ZN z?O631?#L5k3X|~-XYE0z0rIM~>~}Z3Ck;(>&eK;O_guO~cg64q+3RF9#96HwoHss!}M7`tNwyJW95luw~c*%mlb;$dBt3s;iuO*f51t zcWOjM9m_=Jw`Z8k#l2&OivOwayMRK<8_fg!VF!Ax_B%{|(*?kUKCkz~R%)rA|MLP!vHzz6b<>FP??Xf-L_OH)Wtx(js8c5PP<_n1 zLQ4{a{N9JF5B^p6O9PkYu_*iCA_1boH4It5RA{WJ2!7P)48aVHmfk$VWO#h0PLKN7 zEV6UoDQ0BIY&}hCHP{<I^KYMAFlm3=X zUY(P^YFO5XL0aFt#|cnODCPf*38cXY1yu$Y5*p$5KYc+*8Rw2hMvN1$QjnclPPLVr zu-EKnO56JPpa!$^)c>iL_3}qc1^V+5B5Mab2Rfwwi$RF6U;;lWQopZE59{g=8*@mA zv>ZQb{ar}pr|m(IgYq^JoF7>y=eGMHk3JK1%S+ikA54*IL~vEYEvg9fAj%9!#NFA? z;}HVmeAk-!KkW%iy<_xvv(6{*;og;45BN#%+xHjR5NxLu&h;CA%8gQPhtheV!mj#W z4S;gurlQFvs#vD9BqQ20D%$|8?*c|o;0@hL{HMI7+)CEN%EGJXR9^dDT zn1Eo`o`HptTpm&Bq-HD*8fP|r7@lHh)T6g))A(;+4h&v_pDec#k1it0KB(B`dA9G5 z^1Ba|T#j;iF!pk%y+@=KK(Rx)qpl}V&P4}jO52C4RNaDp!y*c230_S@53W!+XS^`4 zjG8BQ)rhMco!lPx@;hQl`QQH?{^M1fE?DdUFinp|Vi|mc((p1{`)hk`ZTu@&%=3~H zl6YGE&o97_X}g8C>zf7Hf`*S>EekpH$s}sKkdN+sC2~(`B1JbOHDWniW~=J(+(fFP zJ+@3%#RaUNNg`fI_@Rw_6_M67lmnTCzAWPO^Ni7hV#6Rc_cD75hXEsz^tmx(np|C* z4}Fq4S+!aq6F#>%rc>OY@&7AJWr(8*Cvuk}Pux&0&G;iJB zemaUdtRid9PS2`h!8R2ex>7oz&Ix%fl7@^CMhl5dmBEVl&drC+SnZ7y9t*(}4iyUHaDN?9@1la#9HK{{BzB)NeWl zTIG(YOx93R{F8eWqU2e_K*&HXy(6ldox-kV9uEzWT$Okd$jh&Gk|c@&&yf zuhEH?o0Q5a8oP#FBT)3hrfS3vAnhRdQMlQl9zI-Lto7zCnmWKugIP57GjO<(dz8H1^-WXd^czzKb0LWO=&=2`_z%oK3Ly z5QORViU7)U-(IO-H(GO(JO{jF<9X14m9ZhY$)(IYEVCU3Kf`0%VQyxx`X->Y^DNz> zbnWV>(vD9}ON1gvO)HabFz*@U!uNByj$fQqrif@jMYn7wgD^)PTBYK5$geL+-8|v- zi?tS}1)UF$+)#GsVq|%_4Ln0yN?ua&!{hbV))(F)kQytB@{tTT(or>4R+0)_{d=O! zDpyU841-9q$*`nv2(RyE$#%LERWQ53iVpAnm$3cU3S8T;PbXNOkLNQqY$%GTHM=)B z>y2P8tMuI_7<)B1XAXWg=i<3dwh{`;!`DoZvR$TA^sW{);fml7!4|TXkjkap&Q+)C z?q@p8cUE=;q4H^m_|3lf#>PgLVew%$&2{HVC`jo04#YoJ4?egv7?RRu-dSI}@Ev8! zTOPm@SKIs<`@EyP+4!2t>PyjN1DUgQJEcx@ki|z@^JoRHVffd+A zSoQ?8sB|pd{;x?U43P2Te?Vs!tHy(B-TBLN3{Wx>(x*;rjMWUFDy8ZeuMtvxv#Vp~ zGYCVNSAYo>xR8LK+T3r!YMeEO7tSRetrBg^h^_DO1N+P{cUO$JEDTVpOM!qLI05CX zlg-vsTEM?k=h@S}WnBsk>1)`GlAGBaskJiY20Vg+c~gDw<8gA>dG2~%F`)KIsy}jV zx@(oUfQ}bO@TYd;?*VpF0`euTF1D1o3HWmF0rP*(;kDC}i*9ynx_wk7<14=8fxqP; zVKDdpoi;-1;ins=xN;DZMP; zU>eK6bt~>-VO@^OQzJJ%^zFZRjQJoH#v)Q2k>Biuw&cho#%bGsxlV5FCc>@zZ}&@< zMMxHD`%S4D|096$Z}GV%@=up2I^9$(ztEV4?>`#DYgBCLxfy_a+-cQxKah-GAQJv{g zDlxVT3o>C~@M*r?ltaYM7Zrsj8>x%$>JC<$?u1U>ps$jeUY({NzoY}{GTh1dSAza5 zQ^mOWVyYDIKL+*tW$3s;hwKPG$h<)jSf0w)KBa3 zW^pw<@ehay@wN%R%E0h>+RxqpRVWKWM=pbv!6=Li-?t6*9K&f*hxY&J?|A3wf8puU zE&~}zT^r-~;hEKV&u*EfyYPPPzKnj#J|3%pdbWVNTb8u{g|3JEM^Zb52RnsRu?2Z? zV_l=_AcMu>R;@}Tc}JmiZbiOqIn?o%homOA->xd%_p~JqDB=Va!{=EDFQ>YN{eC;M z<@{&(!|Q2XLObu^Len}8?CB5RoE_Qi3tF$JWZ9JWKxA_V-ddDJ`_!0!+v+(M9^>J7 z;OZvOoc0tr4D&9}{Egg(w-zHmyOE4IspRW2+az-XQk-3#_}&xDfF@`9kk0)E^;K7x z*BEm6DTYbEr7Y)Vq57&g5*Ku;1kt@I)V=pce2=mOc=`DOy~XTs`|-{bW9Hu#uB&GP zuI&cv^O6IgGd2Mu4CjF$nP)xX%0`CHU&`w$I)5+NI5{&s5cC2_YkGPZ*-+)=7;gTi zRPQh>0&aKWn=d+yvie5HV%6;oC4vWN80Jlhz^TSNQTR~yW$j$f(6#rHOOl=vJzukF z7O%KR0-rTT6{4p!5YRC^KU`jB{|G zQY=?Qog3kL^*r3nhv2Vmh*+BP5d?d#hCnis#;7Y$!b7-C#!LB_E2eIG^(R8;JHl(W zn2fn#_K)f`4Zdvi2K@tufG?z9Bw+Z8I0T;?y|e?ObG5b=jHuxofdB#FIAHgdyW*!qU5I<;Xnz1xxFnvGT*4QC&eJO>>}+odDlcy9RxoY4(O{TL=HatcZm2o&*1FYP z*Cb~fjDq-pyq|is&QF&KELK1`0W;7jxDFYuBAOxR)34d8M?PJfFC8iorl*c1DMjby zeBAni1BR)tC|Ap5B77CSe0y^gZlp@n#_sw)fiEOchVs$tJg;J;+gOBAE&RhFtr=~R zo3$5N^zJoATR=urJL`>$U}D)t#rop+-Fh3yz_WMfiUp>Trn&u_Q=&&m#;o1idox?I z%OVwP&%Hy$vkk55sN>T&bHls7NO#Lb1;fKOwVIkY-bc<9w`k@tx=; zpXvflnYHQZ0VpT+@9Kc%M_F-ury7J>)$hW-L0ih#XNFwG;QJUkgA-UC71QL7<)qFn-&X z_F6&zhPlBRQ#1uFF0$%*H?{@ zKLIORdRfM|t)Y`DL_Jr@e%XJErDC<#AL9rH5$aOzUBA(^=B6QsIH~5%sr!x@gBEf} zWG*!)H;9%|n*YYeVsQr`xta zNz7kO21!lyPc&uYOuNhb@VqOi6VW)mlIunH%Qi}7B~?VbWFm7R<*Gk2Id3et^VQ+w z+K~^4P7x536X_6bOx|UPQhP_%=14S)_3(A`cZ5uj47T6M1n1IrY;s44&=TiauY3J{ zw(1`QTOV2wO_f`ldm?6G2$9tD8_|{E^VN6!_f;@Hw4!T)x3BOipF!Q< z5?Q3G{SGo{IqUM1FO&q*>fV05nsy}vwoTRg}5AXNu#h9&AjAQ{JB#a2VssRsd_KZ$3ow1cdT_t=QK zAAgnMr&a4tzWYFhsNIJjy{;MGy;fbP%sJnzMCI~)h_Y*N zYd(|_?0Qx{x#Q(BE8HI&^>p4acgj9qB9WwfB1o4YG@M1A`5yzju%KBQCweX}*7E#{ zcR{n{6ABu{VaX8^~*?=+&mhMUg`O zmxcT?rL!+iv1Q{nd@jDHZ_x3be-Dm}RVixsVs8qGX5askec#3+bYhF%HOz$9$QZ3lwKkPfNIJxm`rhh(OZZrBw{tdCyN!#jdnhoodvk3<(eKBL6 z4#_P$B8HK!xE2_l`z2wKsEtu*W405Gv5MdIq#}QMv2yI=P1!>c7Ch|*TUgE|vVW&T zD{87|WgLF_>z@t_ffUz&g?tO6Nyy5dpM?@K?ndb3jE<}KNp2@S-u&(t_ePuTim?YH zl+dp=%)iH0?*qpChf)8PQGI{%_yLtX}36CGOY!1SLT znsE^Y*S!oRZWi}RG1*H{lLO1Iob4(zGs*t9P&gWs@osJ|rBfYO^e-umdL8*2lh;c` zZ%9h;JS7rpHIjS{_`}|KhV`2&y?XfE>)YkKiY`W8% zSyCdenl1yc_cy8GkF$EyYn>Iwx4XY|UM4PKfmZ2z_`(Hiw%sDv8$4Wc!ilEI8)oTy zwM^x$t0F+@b_P|UQkKwDH&at&Z?Wz6 zp0#hHt-gumEVv->&rK{lmq<+IgD?ie_8wsN^8diIs@TbA?bKbGP0Z(_x3)#y(q&}ygv4JdG7A1s~jRjh{6498BCemRUBDb z5!oQHDs^9u0&SR%QtPKiV2&R8_1kWf5QznkI%E2QMZ;QjRhV)T(!GT4Rr(Ej^>*t? zlVOATZvTqc2q-rS9kh_p`$Fdf&I`z>&|}z?P0CNMj+L0}7*2kW7rT83yht>DdH6>} z&De>qguWx?t} zh1R@DlmFX9sJLilGKdA`(rKpMExLfpWuAK&E-a8};BxNPD9x4XuQL=8z&tP1-%>w? zq|CzWDj9a0tzaWvH>-#9z00Ak4wDhAeB1og%U7y41L-cseDg0aR?L zcE7N?(D{0mJ{!ynPcZC5O+D_ISA*&Y@A+9wZ;ra^5IlB1 z4%=m7EapL^0e_APNj3+*OwDT8JT+y-IJ|Z8Al@7pcB39Zh1A>+&IyT76_?Cigi%IP(HB&UsZE#a&u;}5FNntazS=!FccL$d9Z-ePZti9rEB{t9Q%n^oPntp+p zXsm_~a?p)p21Jb+oGPgBmQRV*txoiU8&0FU~*uHaSOmj??e+Z zBAHzH{9xTo`Z=y&)Z_1B$*EWGVJ%#|)a`rwBoK0Rdu0dTe{3yr^W$a$fB%rd4gDsj zBaY0t%DO|>_O+0|I_OF+tA@{Pjl0}r>a*3VT^f(ituuK~qPL31cR@e!&zj)j_F4V! zK|_7^%|d!5%=x!)fdP1+`wsYBa!E<8k{YWU-Ag<{j3O+mLH|Xr6`1@BiZ!`C**^rM zC~I}xph27aLj~&5Al0XO$kLzrTO_CVPEo~uT^4B})WLHjX~0u3G>A8ECM+7ml8#mz zXwM9qh&<1kJ(-Yp;OX&h%9_eZ4{%8xpy`E0S+m-V;NSmu1pQi0Qq5D#5f6?Y?*;Yl z@d2nXSm;5(H_WN__M%ZauJQcLq4=>&Zu$*G>$9O{Um2yOjy7(61Q);vcSwZ(&|?si zzhn4u+cItNtKT1xH7{EI(2Nvox0tT#Vi{Z6Vaw-$c3=rB`AHvHl4qcZp2$7oSx`&k zN%;XsZfn-hs>^GmvYCNTykk_!NN)ANibDspVR(D4AmE7h=9k?{zPzgBxF{HKBla<+ zwBrPNH#w5jkFr|_(N<+8z^%_YSfuA3I@euSyks~aiKj+gt8?(({&e4swQ1@NATz#`kZK%q0%>7N2o?E*to)0Bocf)DmmIi;$z7^XlC?51zQ-qSywcPd=tbe zh!gghOhBoF^jPhWm#<%A1ve`r)%G8(PDjJV4woQT*HvjXw}x*Mxfi86ZR2ApmVRtd zjDI!aX87Re`=Lq|eg7p*pPSKHNIO%d_~^s! z8ML$Fl8QDLpP!^rUVHSR^+Sz!MMns?2~mCmNK}9IlWsS^piJ_N!jfg#-}t&pe98fo zpYaUjk_P@*4l&PV^q19fjYVPRo?7;$N?O4`bqUju4z?Q=rQT z!`F@JJ2bSIm7u!6)-7F2*it&)a7;URcxmx6T7Xz>yhb=$Ic^yhgS>GfAjA?K^R<`O zN*(}oBY~qZ|#Hl^#Js{91OKXU=8 zCl0Qwrj~vBd)OSO$0N48Y8A+{df--U9Kyf(FEOX>FM)fMY#J)!(DNSZnL?$JdJJTS zbS^0V=iNHSnRbcLCchUm$h}S(=kzsVrxiH~IvW`CDco0d`*G6#e$Yd`3?laFHqZZ6!kQoYh8t*ke`5w4ivgp3x>c6~S$>v%FZ4~bDR2U~Bf(1_S;vOv; zPOc2!vcyxrqb^+B%4;?T3^k7xLK}9QQ*Uz%kK{>m#i!9Wwr_K%Al-IgB;|||-Omg+P zJ=q-(TKtY(vcDi?3CfpYJW^ZnRbAyt$x%&CoP5zMzFJ}`A91Lfm!eF;ilS{*9lj;B z;iXu&R>FqKHRq_8S}sw-vatMUAtf_Nc#VIi_FkoP>OMa>A~T&A2-sZmJ3g3a&J80S zKE_G&rX`A7_EJzk4#}2wYYNr3=*?~_#+@zEwGGIjo}!qAYlJi7tj&F7^J_rX>>rX0 zozA4DwBX(v@QqXBP|n_>&SO`n5CVt>ccb4Zq;i*8Z(o2IjF$z9F3?JxHDX2~*S*W* ziOUlnO1@_nZuk|RIP6<)U$`l2NAA;G$oA+bb>Fx$!_e`2R^*ae8duorlTqZAbb_3N zK&hJO*=eFSILPFna=EQi#d=XhH8(6JUp*Ez3wpEceV5XrTB^a?2R`7lHvFfMTvJ0( z)Ow@x&&Ky2To&$4G%=V^;k(8aRde3WTa8tyRiJVZV+w+;!4*2RgO#IWC5fn{4vY;{ zZ4DaaxXxxf^!zOQ-$>AC-~U?m^Q+4R=THxcY7$Bz2%qOlZzz|YB(SM(lq`OdyJMIG z7dJCOh?ka(V6&dnvuW-}7Lyp|ohL2XV)PILmFE*ddUc@l|v68TY* zi(svA=c(=Sw>iWOtd3Hdd~ZkX!X}2Vn+(!8!YI6!jqMuqyH^+gEMRryo9Lp{Il3)6 zb=|9F8%=k3o>02y$u{N%j}ci}&b5%eJh~IOr0!d4|I|9e$}gHKZI^g}`o(FAxT!+Y znt6BAPseBKJzv5o*8J>8-lA{w_)SL{ewa&`(0VD9=jsr<1?HZ|SBo)>Q`llB9oPpZ zBezLKVdW>BHs}wu)n+w>yLV=9`Ipy- z7%0xVX(!45Z+;5t`6ck|I`Ex~469}CZ!KhglG*Mcu799 z`XozwrE&?%D+`r-XM}6Gr&b9YFUW&QMTt@=$D5lB*eCUP10$6h%jEB1y{MCcsvpdOo{_3mI1`NBX zBv?soz4}B3DP2-QFytsX}TRbse2)Xfz45S1)M7Kv~x@#NL%J`rX{8)y%;JE-x3k zzQ=m|;n9eu>qb!-&87mP{R4=V$;8q)ZLN=A$yK&4?(OaTcOQ?;iiO9kIWC^N#BLk0bj-HX z8w~3ibG0_}Ivb#8pTZ>IL;ITTE`!DQN}7_krnmh$nxl@oGVViH6lQCl?}yA)G=6+U z-J$2>%ATgS3WQy<8SWCXqd0TQ_rzdP8xRIBlX=s{OLXmX26-iX!1GO=4Sf_e^jMmIJIqt0`dsc#M@ zJwETjw4lh;+tDJy zqvt6SC*}=6{WHYO$S6b{+Jf{NjT6b$QY$7&kb0r+iBMljlwgmWppc*#h{SVCbYT#crJ%N2k_H!5Zxth5w8~lD2i=;@mFDRI760^Q*=**-v{a zOpT8;ussRUbJbUvV?TMU7a^+jsX?Dx`L;+I#&C-*7H7Yess#t@^L;GftDCb-4YOCu z=WyP;%1KZ$RA^kJKN1|BMEZ-Me-}fNeYR*U(X^b#JnBw;YHNuVvpl`=cdw3di?UVr zb;ir2hVNCBSF1VGQn>NBJmPzrNTNk7wHW-22cUPcqo>rVS}JMPus}?n`DwaKpS7g{ zo~42BtfJy_2+X~=?O4Z2!})EY$#3Z|5?hd`o>#pqKW7ib96Fj~;unO6-{AFHnUQP2*{J^hGhwOEFG_ z_!%YGLXHj|#E8MfF;>Uta6W&77sKXydrv*9pJd*7UUps%)$tF{_(IJar5Ch71aamB z;@7s&K(Q%bXF=yZ*_T>a%QfnHLN!dzvKLg?j3@K32|{4-~iGqXdV zoIv8SBdVMXS*nqsgY!~qP=Y@h>7gm9`G8-SH8m9Svc_Q%N?RjOjaE0T4Evev4y#_8 z{oQ>`g*~Vh=+y$=^I1ym=M13xkpg1CW%A$DT+;*S)AymVF-eCgd`O7~Bj@rU08HuN zs3;`IKjM<`E~i2Jt_>Y`l9qgczs{tE>w%GMq5JPwaw?tfhKKuE(TI;?bJZaeD>XMw zxs`TLZBNn z9IJn%{oy$+OiLqWlf+2yjeUAV)51jaePWDXN41#(mxi)=Uv>5D11(njBWd+S@e`QG z_d?+m@iH+Bv8S1!2rh{%<@*%@21-cidr2Ebo?)*$vM0CH3Igu3g=&UYCv&6rg)+CR zihmGuN!R zn{5+fjD30&fEXCkJS@Uf-!cuxT_d5xcaS*-v6n=rKNZl?bia6txpcdREid{DnQRlm zPHZht75V&9-%I2YffZ#-k89th!fzp{KnN;_c31S*SD@g=fJNJI=icWpnev(GOHQ=z zc#u4T(+VW|2_y=Y{G`?H2IaRJ*f*Prz^9O=EX1wr0*M;))|}=kvWxxhNcZ!Va2u&ZTL*nQ&wc{xjs{utAYB?` zUDx9!`F)pug1XX5K61QR_xiYH4v7o~6bW(ACJ-F&vDTZGEVewxS(dig-^v9dz6p2?J@8Jca=oqe<8 zo{xh3tAVK4oT`1#Z;YS*0@>4BBr{5t@{Xs2y-KOceHD9J8Wg4qC0ed^c~k1>@-#%g}xWYL~+ zB;3efpF-riIPu++LH4{w2PY3+?xe@0%1jYPlBTCeoky$U!14STNO5n%-CZ8WBL54f zpYtP(gS+k&>t1vKOd<9on&)Td*?lH&gJCZ^Q(M1`;krl^uv}rK*Fk|rC`$T#3JV3v zs(O<6u-C%}#PgcxBAq1GN@OGM zNf+#a89^735o~{;=J-Q==kIM}#y|FClIpfFn3iH$!AUM??D!8BLv_mC8b8+jT3wKH zFiMX>$40|tn_=!XQm-_E?~hA0?M6~rmyd?v9!CbdD6;ET&xKd$nVP0dbN zF=9rP=tqf#7a{}Ls?~utxz3(_vt8V1~^sX4iGRBXCed5ezRAQXAkkfas z&k^kFoT4R3+s#xHoK*Z7S9Htqn_F-K$2MtQ(H)$ zym2>{8dSblV#I*Z+K>|Mwn!5-VIcoRs(~&F{(wEzF!~$aR5$u!;$Zr$=OFo_?_p#14kXU}sZDjR>)hhXm`JAqX)QIlXuO zWSVov+hjuI)??y|;PqZNF9CH;iEPkf9B4<%^35lDy`IPh+7tuj=7)qQG7J-`@vGX%q?G*M8_m-vfce(+9z8vzqKse zZX2Q`czw3vqPxe%vF06RXsm!<)K*jd-91_@^MRMl=am_#D>vXUd(|k%glyVS@*MweYJNE@&4|H1-%31H@=3pmsbwk_a4`sMC znrZ$txU#MZ-Q93L_-uih(f@pvZhWGA;k(qY8+||Z_DoSCorFce8rhk`%ub^Fsgvt6 zFSBnfJy5-8-3uJTo=H}XSN}fyL=2|ScWSZjW}4x_0#>S09Qdr|Nes?`Zok3vT0(J> zL?bfV>}-RgwRoY4?7 zx|zF$w z5IYIA;?Uh?9ahDT*{=OeuCPjP>JG!e1v#1J>Q#f)sppSx0kP*d#AK6%TligHj{&;# zb3SzI_6eRr>c?AKwijildheHSvm_DO-Mgl%mA<*LoM+1FSIp{{61|6-_>a9Sn)W-L zG4x)~-NMui30n|`cs>HCMF4%ZbbGmu@(6SPW2t)v%*;Gn83$EHi>%zeM;<&ev|J^1q%@rw5sjn!1be?6klI)A=4~LGB|(SPP3f2+ zxjS}GCDqqGhN@jP)oP6-o$k|4|3)HXsVKMXt$P;uGRD;~2yQGAc_E8B0TzF+4ZZpV zOIgVYKYAIeN`u<`J~toNR6nI&1GRp*R9oeoDka9{TaVCvv=_<33ADL8MUM|^js6tY zP16uo)ULXe50*AnPep6FQjK7uOEml)5}!{afUj%M!DN}Wn7I9#AzrpxxtRDGe(N#O z)$N7yb^<0;fkI#hErwwKTYw6r@{J7DQpw?ff9dy$#r(cTqw}hPTn*O#40^G;%3P>z ze(f7%j!44E*>ahvfP$rt!>NWVbNuNO(`dveR_~iz=%``uhtp3!zqDqbdFUs(nxAEN zq(QW=l!9BJqLrn8*6L+(z!N-XYHf&^JoyrxBRJGKg`Rl1vE}{59!U zh&WT(xF_TYN_jltP%v#V3^z)_^vPQK$YLLVj*eg4Ldp4Q)pvA0X#t3hf&9|JXd}b` zI0jxe^`)-aS_B#Y^TVLA*ZV(q4bax@GH%2h65lF7k7Bk>5C%HapoihQh3_iR7&(Y8rIx16n{Lymy=V;=@?!$}+}!*rB;I^S za-ZO$W=Df92$9@pVM(4{CoYzDn?G*(F3aTHhlks7$$je=4Ny`%gSd0Qffew)`@B0Y z|GRwLzof`^%o{YXSo`bHHYZ=WilS1xj4wCaL5t z4Ee=7YN~8WO}`$UD5e(A5riLc^hBqA6kjCMjNx{!s?O5dZK2f)s}z!@o9m}p%5-sj zziiBXBv7+p$)vt(`+}T@K5e;H5aOa-v&F}9Zuq*DkA;=|U;ArF?`8LNMUfWKa}aCK zBT_Er;ZT7oeree7&VV~sI2W%BP;;E*orjSMI**i%gC=r@r0Bh-pAr7e1;&a4 z@h!5mCgP)dx2W>F`_IB`CWJ?`vjQ8E7C^Q;N z$zv0P&+uRBRU>7%%XR}e^6lykb@OmHJ4u(ql*(DgyF@tm0}1Fn&&K!%x4KYo_1*6) z-%>XE3S6h6LuKRcIbGKU9uC2@#C46oleX^juXrJ}&|bNJU#X26CSB8CpS{0&Rv*6J z_z*W%rVGnf0dm9Jm&}dbLJ~#o$F?p+SCxet=$t-3|x>Zlrf2H>o4ObT+1fW3z>{Vn8@>_BrzQ!t2 z?Q08M*{o>XLpwwj_?5)C~@Qd!!GCEAGriWfcO zZ7e&WANdb)D19OJan-Ka{omssT)q0)*ZjV7Y4I5er6`NdcCn{aeOj#C{s1-L4ALh% z^~zbN%u#=pY|WhAf5k{ zpxm}91!17L1C)O*Uq(*5?w_=9`Ey$%QC!4@4Em=rsPe5tlz6kgUeC}rNw#+P9o6%H z;fGEo+2%yr&rIYPv|mq+;1zqb2#n{h)_y2omwBvyZLGV!DRbr@;nzg8K%_y{c*pkj z9|ELiehGOL(^U@S^7hWq-0=InV%TiqHfd)*0ppA zwlvSu%@9^Bl{nrv+kQxl+3+fXHHZ!B5!P=~l?{u~*_7F>YYwaqPNgUp$_Q@Os?tT! zu8e{=zXw-il3X5FIcLaIdO6oE4)|j>`I_(raqBMVvZt^f1-mlrEfg_NETq~rc5c2* zHMM5jxVXcjg<(kBZa>oO#HvZCA1eE(@pb#N&u3YgA?w<*`91}D2M`el!Vsq}nh&H1%U)tN^h& zX`)>!!=}(O-W-{i_2ip!Lvr>LA37}Eh{_TV_s?gB{LIMAG@-fsV+ zj+Oe{OGE|K>c=cT55fZg6%P1TtVLJR=`mw372dlB(_krQT5Jo#U&4*xhBnafI^n49 z_ZOnN%bES^Uh1P8V%bSZW$3rV8v&8;=~B(9Z%mcXA>dxM1a+?hjMkwyE2Qk!jIEEp zWLY`JryDnLmE)h0oA6FH_ew-WM)fL#+G?h#BX74NG;G=u8h#!^5 zwvLZHJs0QkpBo}f4eCscr>?PUDnp5n3hGD%YACTQg}avUC=7G4AT5*Ya+Ryo*gAB+ zUC!kuF2iXiLUmiJfn7ncwrz}Y@>R%2mffXr5=9CECCESL<$rMK?r&gqE(#V_8Xqp> ztJ8Uo8K0~ofGLaBVSNDdV(ogM&Cfy-dX5N@5(oVisr+cl>p>4&a>s`Sc{qaRs%dgc znfb$L;SGU@*?4s8fscq%jUy-V${|RbnTjTfypGC=t#+w6(Zi-c)-%kR|Hynev zwGz66bz2)GlXWTV)7V@MKtuL*;sKi_i;n!bZUQew5sdB++otkDC2}FSaU2o5x*$7o zV~HG9GT2@T#XQ7{!x_GAB60pi6z*&EC?;Cu-cE8(DLfZK?+V0ZT}~oHlc~kYhF980SX5IcO#bFC4}shQo=# zy}Fi)N;H<8Qz?wm_tW0WOqxRaC<4@L77~G8ATGGpZhv6-%|;xc)4Ej6d+e?`^5tEe z>ZB=9UTNU;mSb01Ao7{51+qtwOuoT8^^MusO!K_PTr4r!4d%Oh(BjdM zK>!hUXjyBg8xGC)EN3%5)(|n8JvLPQ$&)oW5N9ZP_(B`{`ncVQBEcXbq{vCjRUPyy*4fB(q+JN2bzeuETHYo3wW@ z%U@VYrvnmtp!SIVC2xOD4UZ)DR1!J^TgEUg8FA*eo4)?~DHKZlCHO zzs0yKl_VDE0|SF{lgRs zqP#Ky%mKmd)#Q)v>FL-XHh)|6b2~M(etvCrvd#isf#uP*U@U+#)tQ^&O3GE#wgMRvGWzK>S@mnJjaj@I*dvjW2r5?9MXXAd|7k zk*f|?X|%3MSY1tA$UTqw;-|t+!0RYd_Yk}83VXz?8x7nBCJQ|8|8?QNv0q(m_e7WZ zB8T!Or;$QkESmDYh~i$NTz$*4IV9`1(!(#AZD}-Lk_hwzQ~S0`P-Cr z-#tV&Z8+j^6TQU0nXW3UhYfz)z9d5@<;r4eAVLS9k*mJ}Ne=yPfE>D{meZsyF;t%u znw@{9fyY+MQ15B(R!Z=dap)u!dLvjiB*RZZ7kBn28tA{bLvkM-_A1kj#{)D z<_G>F=eb$`-EEuI&!fr$`mbkY*=fc(fSQgpPqs0Zd;nfxmZZi~SIXB70GdDxE1`eO zM=egzHt|a@$XO2&9q>u-VXNc!A;{k3>&PDij`!spe&9cYzinB>7D?(WOC6v9@Ed$Ji0cUq+@t=v=4r1y*vDvA3H-(QL#EAZMM2KcUP{g^yKg` z@36&r}Xaw&LqZvRwEC5*0U2RIpKDSFc`oNP7EctcR?&v@V5YdfXX$OiLy&5 zKDx~Dbxwp%YfyC*)&V0Lot?}0H6V2bEFgevV7kHlUV9SXfagbifQ1-Z@(4q2lX&Xj z*ELi^Gcdq0qe+!rFBSfo5~A5A6~TMjTO<0nN}L`qlxMg|@V<7Z2_%m)4bG13r7Bpju}-gINy~`NduoefL+5$!`1MXvRreEqj9_jfm+SZ? zRcfe#c!QNzgWi0p{V=p0&Ceu6TW9#z_SDKi#~6BNN-a)xr>Df8;pC#dp$1VM0--d> z(6Kj3m9hQkK4_t4`cZ~M=do!MZ#W`bb#{juwHZ2PmpEld$-A*s!uh#y3D>N6Immi} z!rS^3UlEYYZ&b{{Xl2)KJ~j2+;=<%LxtYR_e&ktGG(v#6{tr{V=`BojP5xl){vqX) z&rLL%5)Jg0GI;y-(fTh8jPIa#UJZznf27wKyP6r6-X^2eI5yMSzISJ$yc0*&?C?M% zl3x?E((uwu;5@^90zkQ#kuKR$J9luLHDlXpzNGl$ z90I#IkzEF=zrZ-9<*Ute_e??fIMNPufhP+d6hi(2Vt6#|hl+#0xKU43$tf2a$5htzaF)0OZ(YnQH9fw!`FCdOiQ4Yog}-7LfqE z(MZVk5z3>DPc`%)Fm`{kd&#!#imR;7jXg}u6;+9lav^y9P--A@`*+Yify96cWfX}y zDX9EpY1Ht)8%1I37kOUPq=ktf=d*Hzawu0Xpt2!S&_)$91MI|+gIbK?llCVPKOdOoJ_B+VHEk(jQ zaRl1YQ{DAXHLNLv2!O(FFgIdk=By8$D}UIr7}_5G4zRo#WvGj%CJ8hJ5CQNb3wYL5{8 z*GcIzJyYb2f;fdSUfUK!(X1>xm+9ESIsVSeZH6qDGbEX1oJWpnk*IQBbn)(P_QhBK ztxt&~2aPA?$`dW@2y!rW^_9Z0eKDLlezWR#g9P&hL}9?g`5K(H#JX_|S-y3$8`a{& zfeT2i5DYCiRVv|jrXHiHU0*7Bhxwa96@%6@c$eQ9At`{7Yh247jJ6wb5~C)!mO}h?o>0r`zeuC_NDs@U!8Z6;{0gsf4l~!I zbRD8^_4hNC0?X-&aR{hz8fd!Xo*Lu}`P=5#kE*#F5Wr)v0%hu4^p{?H&Gb0HrN7%J zOHOQ4MTwh+W)Q$^s&ia+dPgMy$x&PIDU-*UE~3ldDeLxID&9UPbFXM>zLn;fdZ&9cEhedu|8qk5(hrsiXuWn2=R!1a2L%Z$|1Br8vyxH^eM^}gQg3HCkXvA!Fi z(;fFtBi2}z!X6OjM#QELZ z(+X+djH|El7@S*;|DkqZI#+Gy+s7lQhjS0Y0h3lIpyUxUA9)Fy98$OgfHEIvB&O5* zP=z@lTbkY7E(*Wtv8s$MHz+%9#V}oJXJRa zb(R4+aNIy9c+rqK%Jn=_38lrF!(R{ysvlW}SH=?i0tSay`~J3PS~8_W&TR`=vZ7O( znUeN-xZJ4TzGN!$(em}nW+a7l()5kHQ?A~a9*KLxV7WxGP`WY64fYN0n5HFgiN59Z zgGNiJce&*5snR!0M8T=xiGf?G!d~u$CB3^p&fgu~WzXRM>1B-)b|9Vg;SL+rhf)2A zmx)aGF#=8|G1l;mFuUEWc0-Fg&%`6M(xYCSPO(CiFfgfY?S5m ziB~KSp>MC1|fK7|JzPpch$mbqVl!(FV0- zq@i|;Q2RV(#b#EnE5*9O%Zbqe(KXlK22+_~EOWey{4%K3ad-_vukMuyfFh-0LdU03bn%jRWK>ucQ^Q5}!jbS5cj{*J4Mek1hBoXVI1S)o|5g zmuXMh>4LIXmrr*m{Mjy1H3Fk2Oo>t%9V_h6L?c+59t-H(y+uG^O$U zHun^zC2J|hjw?SCO5|}^iHdA2hTxaU#|1ritalPX!3t$y zUz461x=Ib!-?oX#@pdo_abK<0LN=#H|nx; zT4eds`%ARKrJ$svt#U#B5^iGQM)LbvY4lYw2|7We#0DbziNv=MatMFhL|h#>Ncn9S`Px;OG%s|Mq%E!6EdibRR@?yJ2*UeY ziuS{Yw4Zg9BZs~^Pdv|CW{N>hDpfv$1aef6Pk?XYp0G?36aKaV9VV2_zZn3_qfWUj zwY3i@_O|};&Gdp<_m-`}At&{z4v7<%i4(Pcfm4!{&f!$i|JC`6U;ius8WsRvLdpHt ze)NxtApemI_ry!_1ZN$G%D3|0hj^-<#Sc7FUA+l1vSIIi%auG!MhGLyi1S&@JtT#e!KS-pflQ( zqf$tG5YCs>qBgMNr&I}yHLQT*ffl`8qYF$C#H^qRpw9=?a?cw^0r)*mLahUn!W3Pu ztxclG5D?!dv^)feg4-M70bShYvAu3K!=hdbFf_mC3)TAaL24&&RaDpHyOFmzxe4BP zsZ?TXsZb;RAb|_ftVWHY00(^})8(95q(dj@su%DY+}`@_rV>_ZlbPdDBxbFs3G2x} zfJtxt-uKt}fs=K)MSNaxuW8+N@Esn|O6(<>8jg5ExzHO>$s)^BGaaQj_Yr!aLH=MS zj$T16v6);Tg20S-KVGJxrtq@o1wv#eXA?uc`OSW1O1dcRYJ!^YTXzz4qtg#EUiJP& zn#a#q92&=q|6F!T))!I4uo&zew$vLLWG!#Mmut!~f4krjvp`?&#jNnDE_V!<9{l#o zyKlvAf^Y(@nCh`#s{YUZ>Si@CrO^YrCyK7yW%@4)8v|aE+hJBFZWD@BS%;aodS(87 z4@y)7%NhMfkMX8AL#O$UTG=;WkApBF3`v-q`%&VH0 ze$qeFTy`@1d`evBQJ(&<$iZP2l>51-fR36T!R+kFnW)X!pNF?g-Zujl39W+N0wSVGAgF1@zd-WPziyCZM6doUdT7hXR@M`>L@o@C?riqdDr zft7DIQhgrpPSW-BJc_7d|J?vzsAuQ?NtbAhDi<+bFHLq^Z1b^QihLSyJ=o-rVL}vH zAxIO7LKK{gGCQ<)czL~I+&r-Pw9(;v@FMjG;HLFyMh(~wxTwEhR*sMN6-ab+s;pkL zm5%8vz9Q@sD2I1}03pP+_yI7bPX2U8Rht3~yWRp^ZRk@Gb7#!hKh8aSPvq+a!WXFD zo%KXJ-7A1Z#L8U2Xi9YoDBU0N^>kfD-rNWDn_q>8Jf{hO{c5iNLAm-A3*CTl0kWim zfl?3?03b);l&uMbN7(Tc`}U||SIJL6kLO&aeDbiV6qHtq8(`slUOkf;jgSHI!W%k* zE^6!JnMc&dy9oeUDB#VzGNhN#Z*6)RyOd(ybF$%;?d|uw4g7C&-L|eduPQpH(8NU~2z}nx^vBN&Sd)SUoyQ zBTM~ptHBEn$&Ibre&_Ailq*W#0{o=<1E+iw*Rty9c$l|z_dW!4@We)Z+@fKE zr>Yx9cr|)YER$$T7?w{LZNky}5*6v7*De-0u_|OiF%&2OVW-%f>Nz(CPEy0h1Jc#zlj&vm(1{rNi}i)M2P1DRZs=C`7_zqd#JQSVz< zQ;4I1%m33Tb5vC8vl6SZVvxVcEqWKKUpjY3*^ZlQE}nj-g#!qTUfI1G^Q(Osr)lGK z_93yci%&%*<{EjW7{oc?>j0`cYprz(;O_&Va-d~8{N<7Ovd`luWX~Ccw8v=)hP!Zh z0Nck?JqEy+G5!HpE8pNQ!)-HocMz~EqIZS?K@|K?)iwi2?y?k+5z=`OkQ!DhiYx;1 zB;lo;ZB0IM)3jvFJk*HCw;5r64^ZJHo+|-IdH~M+*jj*_EO?v;hKx_-;v@Iw2#K5# z9&NJ?=5j%(vBElEL?x7t#jBNl9&P9y|L?4i?{n{~&zu1v^#7)w1*5QyctVE>H}5XB zk~Q)YC;pgI$_F=IvR-%G0tG~sfMFG}Yhwfzws{JMn{IV)(7*V{P=2|X16>($^m2GH z2zW|r*NV)B-ZaiCG#SFk9on9k0zH-qBP}h=sp@ckcP@@8tX^X4_xCGJcJdEnraj%3 zI!oeWyl6(^x-9UW4?J7Zr%g<$qrBs4uQVTRf}_WL6^|R6@ilZ-n8!{}8E#9ZIea|O zPV=(L8m+>t(}aoUQ$BHfI{jWYjT1H=uMbM(4l9{uVvT!OT^+hdAxlpaNcH|46+f}5 zJTcU%X0jRilf_o&#Xp`hS`gCuFpSNI&CkDM%Dgb=KqqKIJ+a^tCvEe{umhrgWJx!i zLHPNmi9%j$xH@RcSBTsK!(hBeO~;BFW|aUgnjlV;q~IA-UVq70n){ZET$9vcYu1Cg zZA?y=_vH>|DowCfZFQ1u7ed?oEEnhcW7}h#oda#TX1(PZpBJ*D^h|>a4!TY zUV=k$clZDH`QCqq8FEP`lN-)HXYIAt-dm@e2iJT`WL_iCF!tW2*!A!;ulr=YpNl)w zEKi!`Xf)I|I5zulmBKSc%TmMV%zY@?HsCHinWGvN?VGW?Smg`lb+(ZX+{hm-Q>OeZ zn#=f8pF2`m&DOi(Cns&g)MBB}BXLH*bWBpePCk$Otb^my$`pW+FblR4a1ALg(0TjVTpRDU17y{(xC$6soCNnQ{O;*ppQV{m` zSc$4od(_Y=&F$A`UZ4sTLiJ<;PImG`?|8Syd`*kk&7ubJhI4C*WpCvOT8ka$(aiBq z`3!gZcGAHr(2M}EDv;0fld`|Qo-#Fn^6ReqY44TiMoM#$o84drTp%r!^vrtcCKgY&@H(d2ncIqhuOok`Jm&7$v z6KbyaEv|h_J9944Ji-39JFmOzIDwz5bv{+IA1Jp!_u1XdK2P`Fnmaw{xIVvS%WH6# zx2hviTZm^-&a?#Z<=m&Y3umE~yk&$_zM2t3gHW?jyx| zaGt|ndeWrtIfHt^wHA!Px98VQZWg8U!}l;Rp~yR7YwDb8C&S$E?T6AOpKZ7De3l>{ z^FmCG@o?}3DtcsaS2nM4KBm@qxcwhB*`I<5r%Pn>6oMhOMPnP(GW%`ZapzEsJ9fmA zMu~#M8km7uyEbS#q?K=TW{B)^KPP;hT|`s-ri_tv^`=ty#01;~{+mr&7Q|Z5uP;-Ho@O1`6)d$Y$iwt+#*AB(MN@K*-~rn=#6Qd8na zKjuYejbA){i)H1YV&t(NeffPX)0&lMfg32kWhxj$JIb6oKpvu#OJPtgNc;TqyJE_Y zq#BXfgFUqtzBHLuNz&ryQI{3mkENq;4X@0^kR9ynofmJ3J!j$YpZ1!=sj++6PkKn> zi!$dz$)2zv2Q=1_S1}P>nF-%~L+qK8kJe2aV`4%@njG;!0aiH74YYt|2E?^D8uC1QoG* zkx&B5@eRQa(=Nn20MSg#`pt6zF$4XBrfG1)7C^04`Y`=0bl5oXMu>_biWw5j~%| ze`!c`;fb-N{HWcIw*QW+H6*zMk2a9qss2cseGw^E@{JwznJ|GrN5N;65I04`<$Vr6 z`iKVvKEZT9e&Em0jMHd`-{Zs5JP<|q+5Ok)AA<(CB-+@V35!M_X4=x4uO%Krx9guqbXvIw)zj*TRf1$n9!I#^j@a;<8nI< zzUa)oesQ#27fOkXTyVT=UO$H4?b6!MAQP!R@3tQ!MrC z$;a>TX#cGV`4Z&cbaEF|wlUS;x6>2t>IkluK95ckchv_>JVYct&&&)9@b*<(o=fre zMS~dN0=#L={A}^pW}7U`#o8rT0`w!WAz_gEin#qu)>SN$gDi+1T&wlVBKG@U=Ul`PlOVh7FGquM1Jm z;F3>pTsMCkBdEv&IrIPhML^To=Uzv*>2@c6RZjCO3$ zm=Gp!14;XMn*PCx^G|OV({Yj*;N#j(3$4`XIO=g5DG?7yEkI>|ImAqoo~xE0Fc(nL zmnM)L%j-VO7r*{#2zC}e5g;A_h8QCnj|4TDO*%5u6mt-|K3bM`zjvw|)HHOTtUPp9P;6TFWLp-WOJjVO^*$)Nz?9ttQ zaO(76(+22Zm}w%jMi-C%QMsIY%Y#yE$6K~0F&3Bh>z@mWpH}7;w|VS;Riaz;TDXfY z=%+|!GvX$o!0J@skEb7-5}3y4jUtO1aDB;AP*%7p;Hs4sHCa1-sWrlcVmjRNYtRx7 zXo5juaEx8o;To6iH;JYWYN+9XGg+6d@&Zx9HXcJ}sf{q^Z!MrhBXz+*wUrAIA4@cu z!?C5MFE3{t*|^%~cYJLHt)wZT*O;?A>Ayi+zI2bAG~3xAtwXtY#rXU`wv*zO{_Xe@ z>_721G8raf$}@*`zA+Ow^Q@ChGO5xyR($I6a&3-iC24vuPPoGxr@s`r?DKxmB-V-g zYm<=ETF1m;bnpTJ+sie}gkLtKQcS$jxH&TU@;v3V3!;M}Jx}3#+N(Y-aM|+-7i=H_ z*9sNrO13HJ@MEl(l7%z;TeVfN#RmVL0xj)D0?<@k@aro@u}4ik$VmWwFB2^_jv&#m zSNG%fVb}sT!0U?~qJ1wADP1Oo@->&HYO6ZbYt?SGl! zi8h<&x};=3E(NZ~$&B_oSNLW5EHo6D5?4I!B72+QXRY@n!xPQtQ7KpWP4*W7dV|86 z;h(TsHPpBE!2Ug3%1MLt+=OuK{rZ@T6Y=Xr4Ou<)4HK9d5qgxw)}}r(pt0Y^6xuOD zc|GdAOEepI2zfCZe!}fn!ANQ$v)K2O;YHg+3)lc=e&iC6U3mR*LCS1Ka3r=1%%56O=1&#@jWXQ0UR39~tK6%3gWCAFR}ZwR>%LS! zB0)_r_eZA6W3sJ(&$QgJl|?FsYG%5+4`(A|Em#(6Z12(Q;Dd5|6V+1EK5DPqRDgmEGNXy$3w^FL+C=% zvTVu@!%ntR1|%C}h3DvRt9mS`qhdq);l^Frh$N^%U-pT~`g)3dKLM>6esp|ZB$O$c zs3!pDZ8s=Maw}^{O!lfh&)vH_70D?Nd=}VAQ0|Klv;YP2c0|r>qKmcWX63DDqQDR& z9N?A>a)V{|4rps(xhNeDi`}T%7@$A^Phj)gz?o#1n?kRV&mE7nDeXH2N-6IfjAKP- zXGkkvQ!MPw)+`$ioolSeTR;B07a!W64GpPKC<^FcxjiN^aqDeS5(ELK&oJu(6GYTp zr8X4!g8G_Tq9#r4$&tfl<>MP(DSQ6i#=H%P_W5aNaYF-lnV#SWm$$aQ=74-VS5gRP z>l=8KUb>RM9h<0mg3n&W5jD5s_Ng5ZjlD7yj?itzp}y{FdgR-kG2IAA$M~`$_R|~h z{mq)teG1#K8Tj|REUM8VuKs>%Un!MhiCM{&k?WlaLCtMNn?I(qu$3xNpL;)PlJ~~% zpm5RA4))91J*nr8e1hSD=DE+JS?`<;bBouX;i87_#Xl~(g&-oWEvKgyO4Lkdr>#}r zom=#&c(f=1lV8k)T?3f4-}B);{F<`e?P2%Mn*Za9mGAp53MfrQiH z#T2r>J+~;Yf=B^_wXC$_^-j3-`vLOjO(W9nHm-h0SB-t;T|dm*kjg{>aVhQyNaZuB zABc$}^R8q16S2M4zii@(Y^|mM+j%9|YC89JeYBb5a7HL64|6+&tAEVJZ2c~Ti+n{} zxqxuBos&1HTwIzb=dQ(P_h!@Q*Yd3It|IXHY{5Ahw2*KARx*0ZMuu9BRgiEOM>VNR zmsuBQ!N5BJe|P2Nn0#|a?cbTL>y=f?;GyqT_=psb8ep^7eM<6R%hg+U3rSY`zkL{{ zko$OG#edv(&gXaIvkq8zwI=Pep8PhIE+2&Q2%Gw4UG;XAzA+E_`vmhMJ4~Tw zx@mg6z*?}>&uUCPQ~m8&cONf}6pF1Z9s!<(cXB(e@)QEiLu(fB`w*|u?c{K~LHmnr zm6&^z%iJ&9_CF^r$aw?rc6hjy40Vl52F8SBUnt|nkTJ!^EYq;O;Lhx1+-w%%gZdgu zG#=0+mN?BiEU`0j3EpLv**4zhC3jya@I+HJHh7+^{B3gQ%8b@rMfC~B?7j_H8qg41 z(i_sL#IPL?zqb!Ar8~5xy;Wlz1Hd;#Dqh6I`TD&Z3H?7vmB`>W0BvaC6cYM9nq5@9 z2+1Fs8$&?8G&89RqR{zgu6yGT9|KU|cvdUDDe|FV>V!sI8F}2B zflmgOoHk=>fqa%Pt@zY3BT|}vB~3uD;4u4Fc5Cma1wAp>gk^q65uRgw)U56^k>ubf zS9`g@?=Ww5x(tUKu&0Fps3{;$$A9X^s$!CI#jlmb2>v-Og1lNqmptOb29i=h~bhJ^}C&cmgO02A1 z+pN(07PkBxwF@Q55*zvK7|u^H?dx=~GS1HoW{wuqERi1~yp}Nb_<8R22Cw?X3H>%qrHjDaFl6mBqcFm;{Sxj-CM+z1a9p#C`Cd`RR1&VUlM6Nf0m-H>#8z}`)1I8?W01YwT=jxtjMg*u}3t=lg{2yZ&2;^%S( z1sY@6p`LYWvK=NHB#2W{Z$eh914(R>t8W&rj;L+dWj3twnKDMOFA-CT4j%pKM{-kq zzaOVRsIY(Tp1Fa>Tb^6;h81cw>9I?k_UC6pmESZAeoy<8s`xMWRQ#8F)?2>^fHwvP z*k+yT>Eh+%t&K8$$j$J_|F1t zYGLTWpd+$`a(OT~4vB1*uj|1#AntjJNaYNy6u9L@z^eQEfIfHi!YbYj#(KP#WhDHn ztKP^#tj^%eC0dUU&FnSGIAVr>-X7mlj)orhlG~NUR%hl)a)y?89lCsV0ZhVD~iue!pl^@&3%raJUVv$ot{YCj^I2rvD*QN^k$jC7UEn50~anl)M7wZt!t z%L9{p?U&0_Q#71dX6#5ldp9q8^Hs^Ox3PtGG=p?wu;b0TMl($)I61Z+0!X&6Ijudy zCJE1pp7#L5TK7mx-Q_ok)h3k6p*Bt^RyFdx=`l zvZ#*s!Mj>iaBS{&znG43Pm}R>Etjd4N`zbDFX1YPt?t6ijW8air?U*{;eFBtdi1H% z1>%vcxF)hix99j?LVR3Nhn;Vsz#3?@mdmzM0t5AQ!FNBlkSJ(6rxv$TgK(Kn?lVMP zIQg}3a!jqM-7cwhtSe?& zQm1GumzEFd5So~r5S@tCua=xFN%u+x|ACF&l%P3@sEqMyOU@b2(5e_?`Ga6qH@neu zg{OKm;b)4VUzSVX8%QR>0-*ylK3`9vYB>O}bEEl}s$H3#3x$0hcCX&vrF@CVD&}jl zG)G9HNA_tXz(mrX3(}l3*q{`?Db_x7vPdUT#rLvZnuOiTuf7o5gk}S)x zm?qG02ypqW@VG1%680lZc?#Gp@0t_AnJ}}b|Mt$>h4B3q)(ulmsl%{MwGL!XHRmYB zzc*zBQ~%MW^_F?Fi%*c6;h|?8Wjpm$Ek-E_5I)%$b}6wSwi{enW7=7{W>OV#^N(UM zaKDDmw)XZGmwOGMgT-Az&62WU%;)&(yK!)dZATKbUs}1aHn%8pQO};5d)Vg8D^8c)X64 z!Hf3BQ`hu!UxaD_?NdA1`EQ+_K9@FWKb*!CO|?hz&Qw11^*{pyB7F)G`vTEkr?w$)!oaJ)T#NOA#fsI0EYNbgFOImGJn z^WCG+T`}UC^NRC6+ws}89t9+AK0x{UJ*j8G%qPfa9Dm7QQp|`o^Le7!UEW3{y1L_J zq&0I@(hyA2JsP+i7}K!eh?Wk8VE4(BwEsnGFh8F_V-4 z#+Qp#KdwXl3@O$m%>2Wq-8z~|g?v3RgJt;;JN$BW!R#H$fH6#+_2TvSFx89G>aYxE z*i!HQi2U9NovmhCS{;i@lK4&K4DN$&4XR|~>sYc-)E1Qpn*KI2-4RbB)2a;#+H{mG zP*x>P0wwmd!>40n$p9(^D6wZX#9ml0Rv*#ge}_!vKaS_m7r=A<=o5T@`3c!#Oe0A+ z__doijx$-pqW`=2sr!ph;sahanWl!IsQZ$e6E8c)F>a;sg@xAUUx#aEn-o0gF(U}v|7(w{cjjh0L=BF zK@h(N%}Rj0D(Haav()s*M}-HgFl)vfr&AT)wNd%a zL?eNp7ir6jku6h0QrT?gi7R9raFyb1&jDXrKJU!0W~R_t+k8yk;~xL_8Yrgn1O;5T z=hIykq#Q?siX<}!BU}@{=&A}e40?&lYO~*tUkQ7GSDtZW9Xf`|V8(x2>)?Cp9NTE=kwU_&mRWSmPj#drU zB#gycg!SdqvFCY_)>kJn*=Aiv3sz=}$q>YvRe^W)_=2qU{!r2EL9K@T!@7wpjRG?@ zt3k9$c&3uu#g8pz3S}d7oxW=PW{V}xR=;a7#uiqaHfi&;sNBaVaI5(Z<2&)t7 z*xVNs*iY`4$8}?h-KB#s&+T&r$-ij%V+$XcTVE<*AqiTFFTAr3q%d^F$#HlTq0dbb zpGoqS{qGbJ@Q~{Q)>85g6a9$vkT5t(l4wP3===&~ZjYXocCAY86_42% z2NQy24<_&aV^0zPHuJxr)M6ME8jD>lG$C_oH=9#?ZMLL?REqkgFQ~fA6w-TFzs;b7 zA1Vyvyp`b}7OnR@C(HA-bc$mp>OKX(As9~CplXB+6$$H5wvWl4mvuGYsbtTtidEnR z{}mgt?68_de0UqlQCT9Fyxvft5i+}0vtB{ypY$mXf~VOAv8&``}& zF|cr2xz(t69qI)7b-`R{N*!;3M!0jUzyy;xnw_tPTa6_pAQ?H^ag7}ULKQ;ezF&$E zDy`MK@(A2MY1LXJdVhYYqa$m7dVk{j`oA6(uL`2CsaZrPy^dW%Bc6ErT(2Fsy86kx zy^l@rqUc@91c!e5O3wu>nO2hJj5zNTs5f7@jk1VRPFF9rK5%i}51OAm#Q*eD#hJ5J zeu!Obdl%=m*mHPc@@A~zZ&sSv3W)?3_8Te&y_Qi={OBdgUk=P6O8MfNg4XN1bVs#p zLxfj1N7IZ=R?~jO2(xDqwbs5&*1lk%hLS$DyQ%6fT@A2}H?0Pnov(jrFvp+}bX1g1 z9GdX|`@oi0^z*LC^nPReEk%Qhm0Vjo-FyJ)b`RI6B=JSZr$5i^s6V-r&T=g$c#$iI zE^U5^cN0a4={D&0>o>fQu=|^JIgJNgep)lkC=i~BgI0aIeXaAWm%!9+qAKpLiLw=P z*yw+~A3)lmBGpBZchTWDT`PsPFrcx(hP#=kX^%0fgbaS%*&zBJ4;<1<9=^J4!-rT z>V%X1Ge!WcQB3EAya-U;9O2G=N-s*QoF^CckD}(W?FM;}G#{Zbn2<7@a5#mAw>nsfmY+g2 zT0m&~n$JcA=v?n#k(t32!dD5&=Hf-^>d2|%`P1$b9Py>^pzA#;+cOX~wSV=$G0R$k zB0Ft1ZfXo87i)RH)#+~(_lvEj%1MEED*?WE6#eQRe;wNX6LO`n zJ#_ifz(3FC24nK3)3p#SXdbSe}rN{OsV9Udn2Im z!U1w*25I$6J2MMb=kj`VNz$yDV8XAL169me71%Ur-aS`-P zT9O`el2>t@Ku(}AY^z*6$?(ND^dom7C47>xHr!)~a+7Q3-=iqa{K}Gqcrhu2FbS+V z0)LsuC;iq;%H4k(uiS6`zg#8tU#>zo0jO)_)PPVDB%Coac8Lg^=mC&da}Gb&IJa77 z^`6uwd`gY>*6Hur!#8K?smehhWHQ4f17AFhexC_m z2z=RPix!aSP7ky$Wfh|o!hZ1g_57Sk_&~IRFJ?cDj(GEAobAt!Sx~la`_eRJ+s6_= z#powZE>@QXnqmZZChFy1@lvdfhYGnd{JTbWM(WJMR@3MgE_Z;oa6Y;EdMe80kZt6Cm^U^T4c6Bf3b&X z?~d`>3;w{NL6R{9|KrGBniM1(CR9_D-9EuQhxWoK-<5YbFL-UWq5ZbKGDfyY)epBC zm8^SgY3T8JGqQ~Rg>5dIsF@P^urlCqN!BA!bvj*EZDPv--H!Tow}D|Ej}VlY2$k^@D2i)FvN5~kAbg}Kh6DQLasgC zZIV0weV^D*4da_^`T+0f$j4DkYpn|)pO1*fjhrSU9r-E20rit77~{b8Cm2PYES<)i zAVg9k$E#_GoHbu<;|%rs)nhOhcHWQCqH(gHS9ut{nCWcHOhK8seQn`P_JjOpCw!;D z)dWOkSMU{L`c?X1Km!stOVs&WW4b2J2)ky%mSiY=TNgV-z|j^%#txQ!8mf=~1Al?F zzMW?eEPLy(bMgE#Ys3-jia2P&2S)tPSnugK#-PZpA@tth_M=K9z8m{B1uouSfh{MCWvNMInNEw8yVNGH z^7(zY18uoh@4C%?p!CQFB{UGsi8f}I)W4c{9`vXE?~rM~hz^~5opdCVQd$E{)v={N z48(c4^{4^!dHP}IuMXn++{tj(96vbI*^pAAE}MhEgL0{r$=`36#r0S)n}QBBByR`# zK}Y#-;ulPpcq-i|!49=?3nAxd3pWS27h2D_f9TrhWnCMRSCs|e=l0a7e?;NR?&YX{ zGJ+~4*~iHK7r6*TD=g6fCAS^iSfOjsaAcHvR<4$01H$qvFC=Ok z={l*uZGNKwyDL4mn?bq}m5QHX7?hMd(<;)NZ2j>6y#PWnDL-1x{OgxHNt&4$mUeV2 zv9ek^@gym1$6?1FljSN&irvkD!cAMJrEAl+tdP`=7pM*xcbxye5yO|Zc6uN677zg& z#|gyfv3Au*u2Sp`Wwar)9p(vH!H&2#{bPVc4SUAbj9z?l058B46H#9~*4z$*aQawF z8-_!g#|q#%F^Ttq8i(QB=BWoDC8-KwQq@I64PK~b(F5gp%~LK;UpDu-W7oh^0)vQv z!*c^3{I&F-+;`;_8g_Pe$bkH)XJe;_Qy!RS`#8TVQRVj&W%BvcGcr!XpFp_vM*qRh zR?NAA$pcfwDP(W^(>A${fWu|Nn72P&B-<$YQpZk8io;0VUIip!=qU>_MYIyI3fpO8 zT;kZ{D@SPAOE!ZYz!W+!CPtO+LZ2>&m-ttG$kXrEr7q&hU15r5`@e$AUByYJ->H_! z2z1m_C?T%Xd%k@U9T`l;1ghC9Z!lYEn|Sskg3G$I$(lXT5XK&wUL2Q+lJ57$S5+l^ z(^x85$%T2njqoZb0_ky3pj|aU0&+<^{Y=dA+{|*~*(<8_AlljO9tWuCinbbbJep9# z_W>$ax!u~#kE+1)l~p9Z{n(H(dMpch-ff-B#AzCzUHpi8P=T8Hbhg<{k4`d0qu~mw z@9u0hg(@Q*`FHCfpI5Un*yg#Y$S37VS!iG_Jm(K?EV>DNHV-#vcRu_WUR`5j;qr1K z-wisED6~Is+!FIsP%3gBrchDs?)_u9v+yD_bP=;#MkSZXbAUJFCBI z!P-gTiD7#_QA)~#xYxUWgQr; zep>Swak^XpC4T=7j!$p;36yh1va4FubG)EM z_C+f$+>*-|t>Ocb#G3?uv!%+Ili$r~cJde7>2=QPRnqJai1d#F*1;}Uz1FG1URyRP zXMr-XJNDbezTlKBWq#jxKKUe*B+b55u<|5yYSc=roN&##1j}RT!7FE_Ikl%l>r`AJ z^*lJqPFO_d(U{tkU;U7}^;Le$u(Y%^gbZqexiD@*YM8+9y7eKjLl$tAxNiNfh?Z0$ zgH|at54SpL{lM9zTAR2VKG8b7h(g2gkOWV%6j0Ipz@e?Fbyp zthZ6CyR$g=EkVoF*DB@nS410n0wQp>}b++YdLLf$!in( zN3myAPPjNjbGXZuDlD@w579{)ghSEfnoI8y{eO;XS*|7Ar5#x}b%5L-L<~2o zAY32~nP{$&F@778+t}#Ii^2{dtIv%*mDTa!_JK9a`KF4L?JXBXAL6u+oSz_k%|Q{$3RldHO3R1oqQ5A*ItfTsw+Ou zdv#vKm^zKFr;S}JI5>R(h~yAM<3gDL% zGua5mnU=#lAMz)?(Eys+F``%vmzPMSPXyH0M%Gsp7d`AD{tW=c0!@uG`7&%iN5)?o z^>8*Y;XvkIRk+}cXllSnB5F1d7RJ&2yG5?wMJE)R3o6~Y?}UwLEbN9=SYL?&@+9!{ zMMG?`*=vi@`YKstUtrf&#f7J5exFi)lTpHXETswtptOn#&VNL-py#*QHg7XzaA867 zP0c_I0V@Sz4A~L&#ITlWTG;71*_vvnQZa9@Pyw30l>v!+F&U~S(AMj|tg?_qu>7!& zItYFpwv49mt>t_Nn;>3Sa5KT`QDlCDvUS#0wW9_#9(BSo|C_8(uLNnW>M+fyyUilH zdQ+9Wi61X7)=-(N#b?4s6H&u&Vh8n3E8}73-!Se13F(lXOaj{u`ZX{nZ9Qmj5*1Kr zXHg<+vy)DXV6M8~2$W0j zk8nYP>=~0`O}s!8U$qV<(h9AHDiUMT9xcjc&GD;+CP+(x_h^`n+;JzT%d{^SztQpZXF;9o!Mo8P{vUN2G5}VzVa_5tQo1AC?8F2syensvxmivHNNmCtJm|z z01SuDpY_tT8)S#lE+qyL%M{nx4yg=>XT9A?rs*J5n|AqNp*8K#EE0XuaMg3#O>`d) zAJ;(?87`&mCIc3Cbuz>pWGsY)NUB1)4~SVp_gH_X@ZJ|jo_@x-8dGx3(iB@rUHfb- zkmpUemO@oB`XExmIOrTyN#ox#_)_=X?!kYjncMIG1RF$FjU-X#&Ghwjj7U>_FFzIb z8!Sos5%AcCuT;D+=Evo)no+h1N}tg$d%h>Tebg>@RbS7ljO((}7Ka+9IMv1f5oO;5 z(v!aL6?*bM5Hw4HTKfTf5FCKa6?tO$kV=7hb^D=@8dhSTjofAU1lWFq36id>~c9qOq963E29T-R_kfW-wS6-1!o!k8f( zYv=|1_2;})-SyjYdutEwakme6CWn#`j6(P;<2NSu(r*r#Jj;_i0RLe`wTBc3pv$D3 z@k+RxUxpm7xwn2>Pv?ASsl5tjV%Yy-q=9cxKKIH*Bjj-O7pJnAws_5@ATAt7cM~V$ z@pJV^K6M8jz!Q`-UgwvgtvB`Z9Q|`5d_)8r5v!qZHf5x5G9%$M+wF~^@BIdm{Rz@h z=5-#E&wuvVGpd9OsO(P%;3sHDW^5~0^iuf4IbT;CM&B?I7eZf-yE;D%X#UgJp z&LhF7hD~g%3(?Bp>d1S@Vsz2MnOB|S&@M&n^YQM?$@{=yS_@7;pl>}>gdvjBsCFAFra-;8WbhTF2WO#PQ?r(G{ z?K2x)n;f|<6DS=4>D5f3J}fIt9p6i{Wbqa=`rnMAJqbE0z_OaSw~5+vZG-I>ozb}t zfl|+HnZ@%~9P9+gx`%F-`J5p@-949i3U!W|(}{e~ ze);=CfeiCV$KpK3Bl(e@aE|pOJwo089b&VL{~n>dTK%J`x-sm&mjRM5q7zTMv zYCI9G=T<-&nvGhk2<=@+2ny)gMI#}<^9hMs@uX<6xrr|qWO&o+^bd-I-V^SB)m#;6 zcamr@LGS@MY^*%vwvN58mae&mrRZ(!FAKu+1p>T*0%9?KQjlj%4xpc=_-Yr?%3pjkIy7|Lke}2;Nrq-2zPSRo=1bjCc ziR*yAq$i!U1S(#RGFL%dd}La$Y!44tC# zw;>e2D)-Q4oAfSZ^2>D@3!Bz_T$af}W$#F90OxhhPUHA7`&%Bu2|$xPg#D`p`FuJ< zYK>)_>Nr3}0Udw72ZE(|Lr(4%a88g;9EfFITz0qHap)SN+h<>3b_*zF-yaZFbGtNK z>&m{I>b|kWy1Z*h5uFM>jT6MlEN8N+;T@KEcE_3UDSD=suPL0@fDjBbX_NL5!Gi3G zqF6i#RAXp1A-;ZEhg5@ItfW-N5Q4bAw=g5|hGBR!O`L!{&zIJQGs{d7ve0X;H61N!Tm%JIHb}n#7>oaj98vMj|4hNE3P1*g_5t2A)SfZI zV{$rubri0`^ObU|_jBU=$=oB;Y`m-t_4?F2yXeb(n2rMBg0(wy^<4jcJ*< zR`Xu%l_qsJnK~mJz8qKN@tcz1m?i?8(NhIrlLs34tZ=*NziIMzbUd~+JULEVXr*Sj zPb(5S#?mi87fw!ze6GMacxdA@ID6F*I>*G$cZ`NMjzH zLFI93PhJ(G1xy4`%Q}5ohh1$Wl$n(ckJGKZ=jeg~jIkehO^|=8@Xls2z;v+~%nzQN za3CS+m64^7Fg?_YeyM$GdkbwssUK1?cuOi^5x3YW4cLNd0jS62i!H|{roCVb)luO0 z6$V@d>_T6vJ@V#W(T??ST1mN^J-QPDCbS;T1oZh^#d?<5_gBFOl>#sifue^69QbSN ztL}ftkk&hv5;3FSJ+istzKvlE+>|DVfnqZoGVi>Fxe=kK0?@CZg*3JPQ2zQyo-%_q zw&PDJtbd4;T$o}yc6Wq%`O@O272MgB*Yy*{o)um1XO5Zk=4r=6PJ78lQHU=_!Wj9n z=-VU8Q}~YM3!j@#-~YtNv#(rlykX{~))R_zqvZWzKop*PeC!=7#bfz%3r^-$;M;;`p3Q4Z>WB(g3z7zH zp7M3lC(@AF6L&PQe7awKIc_ydXFTgT*LT1P;hul+W#(#+t4y5=sy*R$L-LU|**)+V zPDJG;kQ)hNF4lK<(j}nIT!j4XAX!AGM`~<{*E{L9->KHHPnr}w)5wDZ=uKBQo?%{O z;@P3Xc`|F;oDTzIwRhG~)%+KyYS&4r`TQ==UbTeavXu2{%}kF8U}!VuaascyICH+? zbFsrI8BO7%z!gsp*?Rz@0Ko&({#QfAP`nEIFnXy#R`G$Y(#!F6wR3vX!+F<>Z;W$q z2GFx1z3y+#fzm4dQB5(Zu7$jJlI> z=uNX@$n5&hp@`r39gEAt7W9toW<*#81<(AY_X0mOnvB@1CEx7#b4RejbCL6|fdJu` zs|6!U@4uog6sR#F70nJY^ZKZbdF>yS`RPT2buLO)7q<`*XyP6g2MpN7-0M(6y`$Uh z%?I^h*?IgKbr`XfJh@w*ebTdD9dU@Z=^~tOZKikrS17h)Q3{7^YE~Jdca3J#hDSss zSc^JGXp#+mJIj^UevDk(LIWNyS*MzC`2rod)rOuKdq_%MhOodlh&?`h(Hs7)zz z>J@_yV;~)RKK^Oo19U&f@TgWQd<5m|X~s^?E%Z{oJ^gR}%`Bl$3qbdki+!)7`XB;{ z!3-Rx{v`-dHB$Ht4VpFlaS?yC%8srV^Zmqt{+35i5n*=z{KPU-vDJ%o zI@f(Ur{CL`F1q;g;ywKidLnQLg)^y(R7D*RW={z7x{cml*LR~0F*W1yx)b}XQhb>v z4W0$S4m30g!e}KLW7xEC9D0H29$Zn)^2apl$+$a#_sMO!D!XN-GNk@=Cc{p8ogE7- z&H!oVDN5LyxQYi3lwkYR*E}!4alWn-ZmiXq+mgc+-mBI5xcVqS!BqkRc6Yfhoocq- z{-=egD`Gavn-WZ-=c5uO{^S3O1wJAw8-j^Nhb2`sv)`R6aY6z(x24+7gtbIm@^==B0m7QFbM5<(HaAGNKq{uZ;(L)J97>pkPWrZdZ&I?T*FL*AHkF*I*gyXBpBx*vE ztZv!n2*M0!4_eLDw^1hgm8r^M1^$4kpQ_xz`btKeL2sxNze4TsYY|XDN7g|A=jeHr z-2wQYm#L3n|IRku`kPYy45AVQEI52@Yucqw$2}z`*ZO7 zL^0NC|95ZU-c~JaH)J>4n3ynNFAJZVsKH#&cni-2?5;@7m?G7bP=MVyYN017 z`3=QCIcP5J^E`rJNWF7d9uPi^?Ys%6b^2Vw(FO~;?z860J%SuLl=q#3*-L%nvchDYIiDsSXrH=G4jk}zdY{s(4gXg@20iv0%KKeL`+eK8OZfO=OLc?lR z^@&|OrLIZ}A{50S60A8FrmKf3Cx1IrKTYccf26s({{F2T$0O==9jvJq+1q=6&(>u23@4#G+1w~tw33}FYx+G$8 zi2jA&x2(cE3lYhdygxNt4j(c8-$=m!g@hU8i5wy%PjUB7=zFCMg5b93dnV~$jQ0VP z`XgdMp5TtUf#BYCy)n%z*A$)*VBYy?&uYjzA*3db;dC+CF>E!9KSuz!D7SXg(kK<& zFaOuzj7>B%dbcq1n=Nem4DARUV@RIlSQofY2alNo*&NH=NVj$vDLMfIdyfr46AnOe z!GH|^^959ALePuc1IKHxET~1S9a?-9c@#Y`&%*=O1O{@Sc2d2RN`xm>4_*wGc&|>X zjB$P~d!MkOa*QL=%VKs^p;+$pZsyQX9b=fl)c!r0-V@ooA!tBQhqAlsGR}SU`F?R6 z0PX>0JRRBRc3>8rvNx7G@XC38|5bG)Fb`HzJ=~a7O?}!0FWF2z&Q&Nyz2?0Y$!Ha+ z3sfT2D=VN3lyV9RXbt+3z`Bw?ZgX%BGV)z{&u}=4dpMYQG?@5!%2?&96e!C(j<&-= zP~kzm4&Tk+K-UIVt2vw#uk9mHY$ky_B#jlEX#6$7UE^3VDGQq$zT!pw-UFIYl&_Ve z2m$aOk1)?~ZHt9?NM*sB^b+Kg&&R0(b(g&p1n6}t<(m_&H}?qnxkCaU&xjr$d7QNn zx>PB8 zg7QQwSK3LZ$S7&;s2dc&!gNY+V?y75)84D z0N}SI!*CII>HWX;fUQj_J6PV7$46}3+imeo*ln8UyY$b1=~r_Wn%5qrpITtVviq0P zQ$bpwP{On4j#sTS#VnPZvr!4;jjpVFFtcW!B%;(wO>TeiBCTjxW-#g~VCt0t+SY>Y z1pb%lEVRT_R8Bz3&!l0UJGAab%Q7c$b&1=!F+-0%Yigp=GMgRph5tKo>a>K z25gEzNMzr*S{-*suG)vxRT|cJK^mcFZ{knjs`t2=GPbLtz%|3E4>^JF*WESC(npKc z%iYFmut@5_*yS_B%MAbl?M&Mkv9%>35bX)y+AGyoLK-50lPkSVk6Wb*{U`auD{oTb z&Q7Bl7YZd+lV8k1bI{*g{+2pGQ2!qbkU;o$ME!uUd;uK0$uv{$HD2tHIxwBX zD0*(L+^?np4Vu6GaPRI>)-I&GWvJk4Kk3GrjsGK>A#SfU6v#)~kTw8c26nA5MXfS* z`nm(NocX$b2#a-k1&Gu?Z;T9_fB$b;46Bk}-h(siPq$X(JU5}&RAFIsiIz|Pl=?+6 zKKrp+Q;v)0Rs!_{_Zo~&-hHy3@}o4;MHD(tX<_wREF^njtv?}inJFJ!-wpdIpBJ*5 zQJVO6kxsMUGB9X@e-cI)5{6Z_b&?ME@I*{HYavcg>vOlh7csfP-~VYD*vlC5f##=! zt4z--b|q6A7kwq^yjG?-J2Y&-Q**IR9BNl)6*VUfCsFouNBY8VAOYS7+v-K1MuA#o?uP!8=g{ zS?rjI{qIhy4nx^47LeiOsM^|_$s?IPuFEmIp1!O(_>LIaq`;SHUB8>;pK<58m8NGh zIM5>{--U7+=ciuBb`)jzWnif`e9!Bvo&yyo;Y~Jw&hF3Z5Je%Ck834pV-!=Cx;|H8 zn zi<;`?zR9Swst zUN!W}4(*L7ff88LZGV#pQkb?0Du2y$yC5WHGwSjgygfZ_f4c6VdZbEyEW z?YctB+>bxb`enjn>D``PLWSAxhd4OGMkMu ze;+6``tK0olQrjP?m@2@{0o%d9@$pvQzbHRi*lNwQxV7c&6^tKG;)4~%%A$vpD(KE zLgh>g{rsG*M77aWSSJU zldN(aZcYH4Uq#SN9o9w&37yP;_;V;H@mjh167HSx5OeSPg^Ydd(GQ;!wIZl1HQL^u zeZ1JnF-UK6SQjz@Qh0jPo@}T9-S9m{t>K;g?qE0gGasB2FoyiLp#9hY#RI0$w`I+! zeaZ}%UFQ%x`Oin&Rx-c z!?jWI#!2Qvz(D5o!8`MIUh)PFtpY;BAH#G^4cv9!$Q>xDdb)hadG_zGi~8pKEoM4< zF2n{d`3@`9)T`k5y?|zY7HGwrA2J_V|9Xe&0SoA&M~TIL^!mQ^milsL)oY<|&8{11 zmq6~cd%NdIK7cb9GhfBq+%>H0Sfn+2mi^$L>F3a*fC-!hJp4|0gge%Gs+(22(vCap z6n%M6@W9P9iAV%E82 zrNOTklqs2^(hEG0o^bkGVi?EG_tE=X5+A;!P2gRQY$=|9o46I++8Y{48{Uso;Z8Zv zgJ|LNQGiz&D!1*5**OlazN42Vk)LjilS@pvbqb4HP-GTspEpGJ2%=GsfAlwQij}|# zj5LHT1HbUrzB}W6vu`*5oIHOQ|E4&OQAV!_?bKmrNkFMIy;(rZbeDZAFzk+00Oc0E z0MW0v>A=T$+(xmPKKy(GGn!mJxZ27M(yOy)U5e!sDbSN5ckNwi(`Bag0adly6fS<< zHb;YvJhtjIC`WO-Q}m`>{IEta4i*8m`5(j3grfIqf@9u0?FD+xqh)uZeQ(2NzVPK1 z%$NC*c47bOn%7&g(Q@O-sHGg5jplO{w6Cb&Yei40O;r5{I-ul~K|`|#!cEA^ME2zi6XCVm&WehF@W_I>pSw#50l%L##aM>qjS4D9j;x2!4AL zAu{gLj2Gux%BMHgPVHNLbo!}U=+40O4v*?o&)}5ieUW1naWzF#pLwTfY4VesSxeH| z+k_l&@qj_v)wAES{e8;=0$#^bY%@`OB7O*EaC+RiiEnnz!gT*YtJ>^4E#$?sy#}fc zu+iJ2YVPfa4GhQHdF*JjZK6r3V(7B;BpY-oRUzmFt*AqQ4&-ieophZ@PWuj;&;Rv- z1B5oe8ma$zdky&LVnrLp&2rwHkW)QH=W8VSDeh_j3;1Ix|6+6p`p9K7xvB~EVa;|U zi*Y^d=NptBEh~wCw%02zXvkS5`N?U%S(~km_6hx1Wa{%=foFF7X;Bf2ME`G-w7dyfEeodCa%p^c zM>%ww$(ANqR!l(N`uA+c8&ve2wEvRO0-ZM;r<54r*IjMou8&z6ngQ7DIdcMM4pt6v zjra(ErS0}9^rV7*@DB_NFAp!o&Ll|9tO(`ucYV&zuom1qPOjnAa1|N->O9|EsG$sj zKrXdQuK(Ga;0mNy*HMsd=I=_F@f0_CfPPyk=+$1-P#Y(~%Jqh+p_BjI@J9D#rN#ghi?!L*qV5Y=DtDANUK(oBNL9H7=HJ#<* z($umum4f!H`nHrAwJ$xEoWicSj!qd|ViGyBAmMY;!F;*h{8+x{jc9+H20$HZ!q_Lx zcTkStYESa${N(c$szf$RV=16b7H;wm!hi+&NgM`PS1s5C|8FC|Ogges@_TLsvNpYlz&GNRYs zpi|Vo&hulQ!=8}M_5lBVs`b46oW>71=06Kje;kj?mj+&aI~PbYq>x+0W7 z+Gc=NodH}i6vPfZPrs|-y*3pdE7ey`T30nD+1cc7jn@hYO7y$)yK=B|)3>8XWR^R*qfWkX&T9vaf-o9FL@pC^u7T5dg5tG)vZ%e@%R zH0U4tM5``0?I@jeP1r3PinEsGq$KQ=4#>R{Dkz*R(i8k$JMHLC^Q>DfPHVdyV?vwI zZY_GX`&JYQz_t`8bfF@C<*Tt>Ki@0gOD*+HdVO`(zfBy7eN!YUVozp&KHXgZWiDv%rGAAzYU+#=6jT8BH zR%p!t38_NsO+jK%m0B~91OxDB%b!&Y-*e?8$(JsD7}Na(P)*8wYlOD!%&Sd~QrvQw0ob8bBX8_;7vrmOx&OD%5Qp_I}# z(EePHmEAY}%MgPf64PaZ(5ojb>zsLAE?1lc?VpL;+V|Np$30d`1M%8QO?G&7H}gKf zh!b%g%WewZ$c=K3>-Yobt3UPg&!3E2TE!K_Nd6p@c_%V?qa1djpz1 z53KK2A_(;x1%Fr|-xTiEkg8`!LBx8z5-(egmo`kSN4!!v&_W7mMVsVq+fERWyhpbc!5)`Rnk;ilGW?p|k`=-G@bbE~U9R<> zE^B-Z&mFQQdX6^X_GL=z6|#!WU+C$4UBw%7lk`_XmFGS;7KS9#Ut1_I=GZXn9k1RE zc|LdSg)W){ufB`Nahh=f=L@^u5*l2eduzw2^Xp(i|8^S@Oj45aOzn1<>eZDg(9Bh+ z$?U8NqRl(3NH;ZhK@YsewWYi?KH#2v+&CLoSX1@-R%8dQ2bfByea!H=X4gRv-A)Ok ze$q+b#mrHZrg06q7gaQbH=$T^SN2ZXSjWNaSHkI99~F32-1_2zmQI@RDQ|!NJE+Sw z(X$8&TJd-cTsgGF5Y6-Mr0fKk3GSRV6)I-wZ^Lif^GAuHqg!;G_7Tt&VsV{)Oku5o2yQ+u zJ|mjhHiFNZIR&+W){dSRTn)0$4_@!MUk z#aX6}lmxdU#m`>$z1~n*=7H1?Z>R_$_`NmYI2J|=)_%%jo!-k#v8l&VIfbg6*mLm` zIJB?hfZG@FXnErUh{f*&e*`jifx}Hwbnt#r!-4wD`|9{&4|XI-8~04*60(8CnY=#i z-PD!b{6Tr~y_&`tS75=?(4H3TX!BJ>y$|X2+ILOie|k+XHdZxVq#|U0-wAlzXYq|T z@KD((!lgrU0)DVmQ9WBazrb_%0}MjF=9c?uqx)R0utv|mklbDO{AUL%qf_vXB<4T zv;<#{V+@t}dU|%o@4EWpms<9&=dBku^p6tF7yp`{$q;c3imVx&4Ure5>OR9=*@XpD zYxPdvdSc zg>Aiym$7l@49^F-ZL|R{sjT!+UP0wrDFFfa+v^!8PG8HdjR2WdG z?x8MrW$PGisCfCtVZ+U{sdUGNeM6G5%?C*AC0t5p_a?%y_S~=a%vWu`Yss24bBMoN z4>Ddti{zf=%pPGXXToysUe>C~Bp)|>gXGbnnW9Ew%;>IX1*8`yL-4mthR^9{p1T;d zG$mg;x41)z8z5pS>Im21%X7%*xm`#UUL=__=1naqX!20z6RA1pg z)u#ohzFTAXSb-kX`JbGFUW5}pPTX~CK|7U2y+c95twCF?Nb*y15OhWDql?*&qS{f)T^DsLERvDS3a>)mpoiQc{=aq$3MWtjnMyd7$_mc zXt+OCmIw9{wT3Lk`l@!*2;)_=d==qZ((==hlyXq#CiQ?1yAlRIQOAv&-3_omHvcA3 z`vEPMVWQf;C2wp5Q^e#&xd%O+M=I^!n<_2qRgu#mO_L&E>7D9P;A zO`cQCCM7i65G6MoK;JX>WcFU#IXiJw1=kMX?_U0?Z%y%Tipq`w4p1Z{rq_7$NXVSi z@LXMcH|6-xN+~)PJyE}S&B~KMJW2(7u{y=Sxk}~!cr&62>EvKYbIJ<_gX4e0&UMiZ zZXD^kXmGs5t0hx+E5@e3B>CMtgBGZP3yy!cgm7g=P{beKB>>gB4X^HYymp8xe1*9# z^Ph5e6s?ZI*KlB!d9zZN`Mzp&k3mZ9339OMuE9L}5&y`+5HUd&5FwE2^}9L@Hi8aO zw!k0Bmqz)QqxK2KQx^p7SgW4V99YD719nu*5Wr_~EI) z9yGuCc}I=lCL^ETWa%}5lcC3m+?>`chr_H&V;RV_sjrg(XG4&vE^V9wMW&s_w@715 z<{Bpg$QP{58Wsr($S@*v|}%=+(KQ6XZuYzd&DM{Xk2Gt9;G+M^Z`}z7d}!Qm!pVW1PWhbzAB*~9R!DOF;-Q6lIGXzAtBaU$MoE0DKxp+7NRv7U7XN_az zqutReZRfP~uHOq>erXtqdcwRj%0)j}?LfhDWj6n1>4-5H9lj%8)#W0fUHkSDTBtHs ztQ~8c-L~cyhlrnr=oNI#Q&FZomD}3Y1zfzrBgW|NWxf{3Cr?Hn-oxNh64%IadEb=g zh%fJn!3A*>Qpf@Dq!X2y@x>9Hj<4E^od_}+(43S`n9FlS_Pbu~!)J6=+4NjQnBy$W zS02#t$g}1vWyzsC-;|ruzCvZ?@_J1GVa)_QiH%ng1XAFAAhy)t>6u5e_Xd9-4Ik09 z@te=B;_+IrLfqiP z{fWW|1HfTt%_xQ^3YV?o8q6bBG_5Z81UGsNMi1I3&B`Upx3Wo82p$rCyU@iIrdIzN zukQB@{`$@;9CIRQO!^PE|G+|uZfbWM%NMKEs0TjKtdnhzV|4B2`;aQ8c4=RE#7Gfo zBV_STD&Hr<2{!%!`X}KJJ_7?JS31)SDl3Chp%GI-#Ij{F=jPeC`Z|A1{l)1WNHz(Y z?Yh_4h0~&l_NmBZW}b-JM&~*_3U-{8&lEX`r$6v6%$F={Yw2+LVwV205Vc;ml%@Em-6n%RC z^u?+CTE6OIOqL%Ag&>}Rd!vK^6@fsEw^D@TzJ$a%Ih*0(6n?BKo9A8Z0XVLlox@CJ zB+>ti!S8W}{{#vF8C**D>Uqx_AQ697lmQk~qi}qy>JTmXV z)QS&k{kEdntGypnbd|ET44LZPu;SrirNW(mtgh3bpP6KdaR?^R#)T7@w$`^x2t}*@ zeY6_a`Gon41P=dl`6a|~6@B4Gs*(mw$iv2}tAlObEEs*%(Aw}$<@mFetF`11t|aL~ zLGmRfNlV}lV((Z999NR<#Zo2c2SA+FzIZRi^wY4q4q<~;Vq@OA9LDu~R z?X9t6K)$HA_~|6i2SHKuaZMT&fMONFtB$gGOTZYtx1KA8Z6=gDLt~ZUQz|3f%9#@;4s%8=K>#zvirI+xAr9Ue5;?7H=`AdieWZ+8@05 z=bvZ>jlM%9N~op1*?B4#_xOUY3^`h+21H@JH%Ns?sk+JdRC+KIEM9F5Ujh8jg68HM zW~tm%e23iDOL5dD+4WPsEHRv62h6)KT;~$4BuGE*kBL7IhX{`(#>h0ex8tqeM>Ah# z&PF}Jw-2|EaoOfSz|SWR}GT7nKP9NAJiGCCIQu-s8_3&`*~tTuG;*4u=#^d z6A>IZ2qmG)Zd6>ZtgU#b)u945DG9DHl!I`}5l3@^M4I-096ztegFZ^&P3|^qG)EfA-T*qxPVYo6z6gPL1NY>_N z0Qw_6NEIO-!r9jo`nx;i{X?3a_80GKKR~dOBB_dgSO@LJA~_~XwD87H?{V(M(VApk z=9aA5AVl9^GKu=dkngi;M=#U_^ZkT)jZ;YH$|2b&@64mc4W{-8NKAs5G-z!_hqMzu z<>ddM)M()ETabm5g(m*e6Rmj3=B%C<-%QKjc1&|Q|FWL{o{!EZxF2_c;hkkVU=fNO zIC(kPT{HUrXZMGYh0MIEP~p~2;AVsc!N!F&DCV7JnCTDaQ6V$m1)C(u zpY?t6`dVmAcBs2-Yn*ng1|O4pyJc_xynACYb7FKgEOPEZkvV;@Q7;l$Qen#t%sE*E zEnfKXO~f+*-ln)@kp6~0#5kz6ZPpIqTq}$}9$K!waMU`chHX?u``Sq%SQ5ssyDw%W zqAfQGFeClu1hirOn7%0th!BMHxvzb*WKkLK60-z?zoFY;KTyixsnBhKKP_jHWi}rs z>z=P!)%&zTcfzShi47Jm&6K_KzxC!fUUOGmoZA=bhePxv+1^|dbn zuSD6ISy{pfyX8HF8O2Chc0LULbKalWw@xa!YLdfJI#_!aB>L%f`5WkldCeHTU@3`N zTd>tx{`zk+gT=6%g|9gQI8rwljP;r31GG^^xv$roMyk~Cgf6=Cq zt;V@uA2wpn#Ly|@L$rsTaTR^L;y5~0H$FvLul9UdKgqNk_G3={p|`-+nB;bX4fMUD z7vWHhIdaTqS1TH>MMQt+MuifR+jVo8(SWxBqxS8OhehmwBZ>J7+Q9kBDGRf98S;*) z%DGy7{rK>^oR5`d7F1+y$pOSrHc`DYVNr~XxF$<6tc>e(+aM7W06OR9daXpSLMk*LO2tul#o| zJ|W{uC9Jl7=rMog7GZRw9jSJN?Oz#ep#AlIV8m)&1geR!Mi4XQD%H!!o7y4?(npk? z01drfi07VJU;dmG!dL%ns=VlS7-3da9vniw?dVwS&U|H3_k7k!w|E%j<`DtwW?-m& z)$|yC(U{#9?rd!cb|tTbh|<$W1l!%hcF?Aqc=Rc!#ob%?XJV5(DCQRpF05k~D)ZHr zed8x(`Z!0q{HAvfeSlpH5BG;PeD4&7>AW(JJj6d&@m>fO!b;o*`s|*S0S~%|&@DS- zE>8MVT*FePIHO2M9vajeq1ht6x9=0uEGltD(IkmbUprTnEB#6oVpF+98))uc9MENP zx`xSJgb(EkN92N2Ae z$Br%eS*8PQ9cS;Q1`3QHP`b4W%8R;AR_>sSpCm(V5-KLBf5t0!9fr5Y6it3=Z4Y)% zf%^-Q-47L+wc?5mfH|7~&8*IX5P9w?=QjLcSb)y~Yv@wLKI#g**zNA_($oR$AqM$8 zL~gw*r>mKmT)frM2-SS;ifj5Bm1MDXg_DzRxBBW14I9DXrkgvOakqw7 zV}gIlbQh4Pf!ypP3!f6T-4e&qnPJaJvTVgQD$REQntfBq1fv5v9TO390l)_vC(s_> ziM5?(2Ew}s6bdId_&0$WSJYT&_OAEHDE|c@kb5_<#J;bg-#G=MJeL4<9K>$vZ7B@1-7po1ncsX+#(Ov;8NMrj@ji8rtvf1<^tSo<+MeLm~1&`N|GNyFxi7Oq5#m z5zyMxo+V%tMCLtgQA0dPB^n7KH4LycJi;G(xEjY~$Bxd=asp|F#5K?@lC$Eh8rSlZ zuSd%QQI_*_>XE(KMV01=-*kZuiFX&$24Gap7#ic&t#VFxZwfpw+1TF@dQdY_R!)ii zX=_L#`|1R41*3MqZ13{{+S&=K>~;QRQa2L+b4dw-Pv|U&H+rzQXO=)`uEn?xBwO@9 z+S_x};ZByD)wJo-0pdmPM0+CYTQUhm?nA5}c71aKE<6Pt_lmuZz7DaNYZBLf{9x0M z6_9aWt308ihYqb-9MdSXFVfmEJYDtQD{WnzJ+mT3l&%96d2F^}Y_|TpZkc*hlbl!U z@4kxM5gkbcX`t(ax@F;uA`V3;8;vP7ks}2^GzZSUqc+rt&+Ox`a_7UgH?uFo zotK0;Dj_Hc5qP%mGu8TGi$!umDd5#v48m0UlgR``mI?J!`)M?T-P*>c)w zf>WPVeUFPn4I~s7K7szee+br(*IJ7q3Z1)^sn?npNugT*!%q7<$BMn*5@rg`HV0fL z4~ziW2X9h$CuW{8(Z9gz^jEgPAd*79Sm-aVX<}5$Tl%oJaYC=*m)r5(_v3_WKJ->? zXnmS4+et#Brb<9p@x#xjYL5X1rsRV<8!=_XK?*kIYFqxiUWLUEyJiPfEFDWYXJ;JP5U!oq^5Q6R4(uaXH1sjOaJ7rQ+x@8Pv!t{l7$!L!{;JzBPa z9)rzhxfrXxD_?ycHs#5qlJk{M)g}caZ{D9G?m4Ly(4S28pYsoEB!Q)&zm;A0DzMH4 ze)PSA7y)xpzI8JuRjD4Xo!9T_s%L0b(s|^+%u_PR8u;es5Mv0PM={+zGcvCMDI(?f zkOo*y0~l;NfBczUbjADTDTz?$0q63PegU6D4jy7CS%NJF71MkKOKBk!d-rusn549A zcW%G0g&HN=<1XQ2rxzC%WcB%;dRfBWcsF0k&dJ%0Zye}P0vJANKNt_Aco>B@(kjpS z!Gu!5F;zq0;p;zrXl=rNhZ&_fnzm86o#b zF3`hV++F=a3G!Zw=82U=mqXCZ@XPiAzXoKj1pM|Z@@ypS3`b)sJBXHXtI6)f(S#-E z{*mu_y=b2U-C9h3vGLM#gDSwx!s?j1cL6vZXQsf+8{LNXT5+72hdoS#+E*W1phDaG zd)~!TXmu-8>tDA~w%Xo&M;m4nVQPg3cwv4rW#GvIQH9+VeeO_rE9feS zDWo@6X-#xQWUG*>YzA|DD@mvsywfZzfp&d4nM6TN*hgsP+1+*tp^IsYqW`bMDf_<; zr#sfqVDp2fXD+~2?IV-?on3NSAgy0b_ThR zl(n+?OovwCvRfLfcV}#oHZA~dPqeSx)*5PAAvxSYWOAB+31BN-_c(UkVjPqfEM3B^ zzgv_RdaMo}n{E({N?v?&P&h9MGTX193mprtUkus)N&NdsN1#}+>s8&s^TAm9nCz#g z->)xXTZR<@*V)f$TJbA)P`A&V-!mNG(el>21vIp)n07UCv@e|x>koS8bc0%g`gMz| zT~|n?`NH8l2M0x`eX41o+|X%LH=4+_+o}3$%fBB**&}MV9VozF*htb$Loj#4v%kQc zM4(B^YLUL_H=2t)U1vt&bwii5lcrYzBb$w#w`=d6+JF(lr|J)Q5}viVRz^{_th^_| zz8j(veTJu~P$9TZ8ZBF$KbF+Z_JBZ}bkdoGb!|epuKg2u!vSWm{?j|e#d9~L33)}c z|C}}HCb6JBrPuMRB*~{{`^6cscj7>4GTjdxPq}RxnF9Z{({@I)T|gqOp_&X#IrlkR zJdWkA%*_ZzPAUti7u)W%*raTk5YUAMPKsi_F(8??`-jPd;G5FM$ik%QlD>qaMpK5Ko3m9ZX&8LuuPW@JkBqkFP%p> z<%y1|wpcj`*w0s8AGGl7h&$=uRINwt>qC19%YSd2WGpy_f$AP6BD^^$fhx2%SBbr! zka-84E)N$WG)I)Q75vh4gwK&^HZOeN67Z*HJ4QUqVJiH5k67qF2b`E%QO0nxre%wy z%@ENXx~MREW!T^{BE0_pTG*TWV?uhITm^161$)2GhE)y?dR#>QuFH3r35TV(I=RhV zYtF_+cMrpbO<@PW#FI3~j|t3nlTjzZ1n&ZtGZ;Pr%O@I)loFOst|g>s8$OjzLiFY} z9Eh$z!K(IwcIu5hfI4-1^kOiHyEF?$yLSAJ>wLX|1wcIW?@=WYp&K)X!WmNl2h8*#~{M$asMbgC$G& zV0zM`+oKAf)9=f*K2tqMovG|of%h!NC++bgL3s>7>OEp8vj1UN%R^AB631Sym4+Ox zCK(yM$2u}-j|ZGM)3SfE`d3s@(EHlK2(!4(4+lp>Y>g9AB5@d!^@#}cqH=loqRz#U z`G5>o-11kOg#@88&8hqUuz~i=i}3Kl`Vp0Le%G}rP072F5lVA&EQB>P{O9yB{i%b* z(W!G}+sCJvkeZj<_&TMVeo{3j>~)4AId?J#v$N3&TN+OHs(-&k>s4OAw9)Q&Po=>d z?@vG&_>JUbioUL&7V7!rdQVBsAATj4$48c^>+8y&u!BtGQqG)!kGO{am&ZO!~ z)NkW^?<(}X00Qn5)e5w!Y67B)+8N|#QsvCHcjfh#r2dCCy@=@8yODIsBnf!TGB1Mk z^wDXt3QGRRw=|6qBvvhabb_kNLy{kzB8xhLs`Kdpdj@?QON8OurH}}|) z>wG?psZ(!BPa?~p&Vchs5ngz;O_deCkkMP<>-BLtgQL!+Z3_ovyV$~a2)rM9Li0tk1xEdbA zI3;1I>yb5`Ic2Bg-~$Q)jp}6!@l0C=u^zKJ5G9dUB zZShu)6Qodm&NOHYz@kZ6cu;oHzI7TldsbGaLHT{@q=+A1@0QRutUwmPW>vUJN6n(E z!;!!s6c05$qb<=D?H#qfDf|2OW?ZhpaCB%V7##-u#-lc!4%@NaY$6kYRfuVM<8Fb()wI16bXwJj1F zMux&sribaE?e^iSvoX%;!%cAY!TEu<=u&S4-8+L>Jpo6KzUn#Aah|D$rAZFu6+h}Q zTVlYU3h+NgIgeIfDR3rZngWUx&ue#$OZQG}btjjwu@v%wue?ie;iRAAy^|C1esyB$dpE72RJ5*d zUN21TgG9e9rbscG-hBA@=T;S)&okZ?5bXaNWS+yVM0oB2F0qp+F~)+gB-f9y*uh^qv_%T+L-W^#d^KcQ2O*cudgc_>|rc&67h%GPu2 zzeI8HMcTYsD{)^b@-&b&e2G4mSR;L}nahaAwWLR_NVe!1% zX9Fvq2oujwFxsSV+~RYU662EI%{Cq}LXr6jX--fLT1yL_Y2i!XqmukkOR~~78{0)! zO>hxmPC)6KcTse7S~+leS6SfM3ykxAvLgpFXZQIW@Hr5jTsjGvN;@6dYgAkpdA6;4 zJUR*L6b6@G-85}R)<#D9U!n&dWhAW+i#yGhqF$hZd&Y&-W~lfVS7V2qVJO$=aaQp2^TN?h%7A`w#5c zd2^(0hHtNe z0#nv4Z-xv8OIKh&+Ld*6fM3Xbp`SdDp3Jpw!L$ITR5Qa6O>uCQ-Q*=rYMDiYOocCB zX45<-(E=dB;b+ugq+9njY?0*p)DX8C{AC2W%w*e>sTv zE!EF&SN>>50n7M#$-bnG+>4D>%ncCh2MvC8@ARk2fn=q+&gM(sP7SjQ#nFTmZ+R{P z;J>C0Mqc`GL^AkAb#8fKnf#h=wFTYX-O>3k_&B@`$oS>ojI0F7&|Az2TRF{(+SS)2 z#F7cv1AQBu_oD@khRF`6bhQJLIu5B|!azzc&cR!tlPZrOZQhk^&gpUljFty%oCT6H z`4hI8kLZ7Z5s%xT`sY&_NlR0bENn=p`lqloOv0(pGpYUTelK=yoQZltCd)>c;7K22 z`3`N)neCZKmzbUPIe`wcu$lMc(Yu%i3}a1es8@PJ9Pj_k(}a-ERERy4! zA1{%h@%;3RY3vjm9}QH0jesV+BcJ=|_L|R#$dL(DXz!e;(7xo}Zk((jq}+22eRzD4 z5A1rhsQsAm;ADX1!~|SM)Bhp|Gacb~34Y=PL*!|~FQh-WY z!7IJslfREBIF$(%Q3V0N_33thW2bFU-6HS~pUhLOUCgr6B-7Peoc9(RR9_l_wrO$} zJ+S8X##9DfV;;+uFUj0g5ZNn+SDBnIAIf_&Mn=}zV&63cRyeeJ{+pNx^-YO9>0UWrfQQaWB1&&qzZ%K?@G8=3?-c-ytCfGJ`9TB5s!}u{@-{cm8x1;zgjW zp7r|d?!}98Q`fDAj!tV<_{t2DcCOPm|U`%0=O9tu|&6%9lUD53;K;$ z4S2H=*@kZ2Wkw+^A4J}Ju2}y z{+HVWgmCvCuV!4pzbvx8=G+OLpE;HBVDcX?IhTH6onrXID4ZsgM`$_@c3L@PA{hk? z-aC@{r#;Ce($xh{hCZI{r^|6$Mo}5Gvqao?=qBe@IN{FpmakCw41je zmh#_ppZ)7yzg!e0JPV-|Kp;FqNm`A)e&`AJrjV>qSwB{Pn9ii%eO;S~@cV`+7bOW` zL$=W`oXoT?5k7N-etL&DT}~Wl)Jx@8?n*^JJSlPze=631$PQ>D`MbIs zxs;~(Zdn5R;}<9x8Fn$+2i><6zX^W;an~f4vDFET@=p_Zpi|_r$UA7qMY!6VG8X@S z@~*ma>!+@sC`_t8>qUvq6L-^*ki^(#>LsT1>zd96^t76B(*wh48JXxh5%GtA1B>iq zUw;2X0DE^Gm>Yq7lbibV_ULtkzF+N=_#M4_7pwto`Ki&pYt#};Uo z=?PzJU7LTyRkU};EtRZ(L4sWSo@x*=f1ohF==r4n9~U{XPWbB1`-R$nB*bR#p%cxD z<~*M%h^On4Gn^1$9{|RE_wmXeOlnyi#($|SDb*#c+U*4o1ega*uM(#Uhr|p2f41zd z0*MHF|K62whT={#fG8lQ*#XGG*9-ul$yJUU%?Z$!9CS4io_>(*^*(dXIx7GRLd+<) zX*ggn8%qte`U-#kAK+K=e}EqXq4Xc%r?YYLu?iiQw&DfLfahCtO32^b-1uzXYVJG^ zMYY$5E+FgNFIR>D6MMllQMygu%yw?-EKI~yVc^9(n8V54Afx!ET#^$z)h|q0o8Y# z0J31w-Av-6kw3<4@F(jtAIT~e8c&p#n`HQ)Wtdp76_IvqKk2vHMB*;G2Uhn*&c+u} zOxkXb!Ut1HH?0($s&OCtj+W8?{UW0TmySq?W~&SQ=6$VmKUYS|Cl!+ukOj;wR$l}- z%fj!!@68dA8I;R$p8e2kB@@WScbe-5dk@P zwy6K`Vyd}@P~b}(aD_d=}V=eNdm?`zy*EqVTmIJ3ND6(Qo0 z-G*cCqaDeBhTKjNd=hQ0y6+u+@Loau{AcJ8zWLA6jb^*oJO_&U3?yvP1bE>yAvvuK zW?moBM22<=Wz(`%KByUf{gW@H!RNFHemcJz<%?FkMzedc=B)*G_ z(d~7TL*BP5Sv1@3WubZ8@?`&uXQ}*>6KIdsOT4{Q6_)9E@UVW1Di202TaGS;d zN7Hu)!})k$D+!{D-h(I!f+%a%AP7;D=ylbIZlh(@Xc4_eFOeYXBFc)oqFW`RuU=MJ zz4!OY=llNtzzj2n*}cy__ndR@84wv)f5I;A)$DQeo#yE+Wkb*Q$|d~umwfv`dKtNK z^3``eQcw3{@~|R-*JYJh9xq(1&Vc**(%SH~WndeAJ+sDdo*KM9f^NY(kg->hqTR*P zfZR#4P4l{$Vfm>`y%Pu?NPx|Jw~%F{BbRL1-ahsgpZjRm=x2!ese7xlFsas}-w*=~q!!_kN;`kmo2Isy0v?F97)<@^zP1(C zZm&Bs8Uc39diaNt=P!Hy`bD`D6WRX8$37p_5Ma0do7X8@USWw%wdeuB$gBVN{ZN-r zX8pYUr=kL_|5~s3c~vJhua?c_2_8U*R&HXp@QrY!&y9yxe-Z-I=cEVK2QL!jPs+lu zME3*dU9Oy+JfPLI+kXIG4Ua$YsI7DbHTT=YPYR(4&i(_L6KzetMTZ%xUZUlv!lOk) z&uUIY7TtG4czvI)t~G4M*OEUYWl_pY$@<)2BfjsW&gXm#|4#*ossb zaymD2?bPyz<6St^(Kg)lxw-;()r}wOzCx-!S$KSNE&uiQ0z~6-LD3hO@*row#fP5x zS-Ekru=M)dz(gOZ*SEKXm4}|lhm)HGrKVymlceXK?Ivx&`^Q;7w z#}AxZ1h>nfz~KXrWK%D6%gSC+Uab62u4z>-1A~xhrig6<`n3`sqtVwU{_}2o60aTx zH5*6b$F{e}TYG)&8M)L7d6Wd@Q|0W!d^#-}AqS3j-Q_z%cbzE-|6nJu>-dRjPbZd^ zPqxM=h8UUEKV?f>@K^DW{45&#KMpGIe;~TfC&Ss=4KJtsVW6&yoyof96el;LWm2(H zpGoARLA3@i@5959?!e(1Cn`G}TM$W->hV9F=abyZeV&*(=E0FRtW&pTBqpu=lttoR z(m&fHCx}P*5}sq5Bs?Y7cUJ#lcsK)`+WP#c*KG-S{ie0=M+Mn|#+$NTcE)>*rW=HQ+oxj2Rhk5n6E*e$BgpWC+{DGy{gw71{9c{e6 z#^u`IQ4h?YR~<_&ZT!;ppj!P6P_c3OM$JkUhG-uM>T$u!6pcycN!~j~ZhFoE=Ydy* zMpcgS_u`!YSvYX?XWh5UVZg;H7}Z)GguS%6($6$s;Mo=72FC+RE;r`!B!7S6qV~3Q zm%L+R$s%T#vb7oNPqDQE4Ul8XWZNF_W=^-A*+hPJ6BD<=FnlewaYmrd@6(S~pHD3< za%EvqVfhO>t;WLuph#cr{IShK??+z-G(NuXy9*N{u*&jU7mjr&re+&rA9WW1SzwR7 z*o;o?8h{guC;3jYv@VVuIW1f`K61&jBWBUDB3v)PZrMK#D7EF+WFt6UFsBLwO19i* z;fW;IOMwi}AfJmOocBNHql704jIzbEn_B?ZmZRGVkT<9rfGAW)-bxa%t7CAvUCO5- zQ6i|Idd^GmKKYST=IMt>U-v%1o>#8NB$|8|#5U=TPm#@R#^$umw2Tm=+1^nyIz?dk z^U93J7&Pcjti(mYnY#jlq5kyY|hmi+{+M`_f2o*KL$*ZDUr`y zQOvw!sXu4`dG|1Q3x4bhhz;X-(!B>({G+nnP84vG$yEk{PuU@L^`WBeLHi3$gL!Vf z&Yy}jeuktnTl>9us@1;eE^Mn78!5z~5w|KSbI)r?B<&Z>b0JxlL0c97|BI?G{)wvm z#xt>Pk6@ZrVXb=)QYq{!fwhwtYIeX8kT^W?dY{=^>)`5Kew(v+dalb!-OpM^We;8X zKohe!TmV(fwvd0=aVC^9I+XMV zYqMZ<3(_ieB?WcZWV3>Y^K8|X;_3%gR{Zj#yOkNMizmeeb*MBrQ_{f|36 z58E7iQz>KH@4>FN0T75 z^Dyib?1BWGgii7F5{BdI5yLD(0=M1yCSwK7+qZXI^!eZaG=?F86Cr*5O}AA=oZX1T zmr7}{J0K{RdLfk;q05>II+c0ka47n+0pxli9gW4;{gnZIXlj06FgLCQ{B00HhL9lD z-Bhtu@AW(@1olmjbJs=!v$}s(+`De~BcgugzH4z2HSi@a#3ZuY(1PWa`&)j;LPQO6n| z{P;!dcWn=nncj3fHNQQ?M6AMNemMyZ_`lt1$aAVSZ7TRuNnw_A>=WbK-4j3pagN(Q zZ6yR~3+YDtSh<~BB8WF<*6F z-RDzVN`9<;MA%C?`tvnx$zq7=$7+`~ed5zAMwOF@MMOn$kD2VzwI$4qDw%9;f~%kr zvdqyQ(m2!2$_XBk++`IZ0$$fu_WlNT(!=)D`3P`p=i27!Xq%?V`RxyPR|&kTcQN12 z_Q@Ddd2XY4m?|b{b~x@H;dOVkn&(jqM+L^nl74t6d)7FT z_t;NaZrY{%x5oTKR~uE&0c756MEw4=YxfSi6)C9;kZU)K3J*9uQ zDHS>t@O0Kx{P#W?#AgZ7(i_6@X7;fY(D!A-T@QX(@tas}yZoq*Yvo^Q7;#)WBpFv7 zKEZbh59C94ScG*q85ufh-7u;FK@z?tq&8cdbi-p~%Brf1AiAE|Z;CrAM}Dd+$*hmL z?IRG@+RrT&)Ur?N97U>OlywpCX18lnKPWMhxPuOVwp2V8m8E{$L73(>j~k1^TJIvM z8w9^R-EB`wgB8M0ihKWjcX;Arid34wTFr$#;*kwV4)*UZfOl5Kx&HiPBv#aFRSTGq z4edLYiJm!4ar2i6+qf??hRWiC3WTd)k7O~0mS0aRPUTq;DB;nY?0%m6G7HDqc4nqL z$)Q}?c*{+J+83^tkL*jfz_mkP*!jK243C;j`d>QgdOSkzv^h30&HttHQavJkfQ^Nt z_VM)~^j{A;$4{3srM_J}TFIa~nLGSg1H8BP&e6gVe-S0k+a?K@aDmGGLLy_b6#0qg zTif57x8)6oF9JX6^gtL4>Q_4!&s~_DZo8d>t?R@d{w_2PhI>80I#aNz}F3aqw@l=xVMxH4dXHqB(k@;K$WZZeu&0S zl>YTKIJ1tfFr3dZ8Tk^ayRM=g^VUVgw4@@W#% zh0G|c_&v*`cQ&oGWYtWG4l$ORLC4L-*X1Z?3kH4&W>-*4BS~At8!}*-` z=*oIT&WYmC_wWbw-cw-qkm?e1g7an&*++dn_A7Z4f|?z(bYTh~9s9B&-0i&A zi*U{4;w9-vkWozL(IpQrk;edA)?Hq^kTl4$mSg*b=I=)&%P;8M(JH40>*j0|uI;-@%z#ac}y?k;Av|t8Fg=!yF zX8}_TZ#WDJdpp;!?KR}E(@P5ea>VtD+jpB_RUEwR#`WvI-YZE-Tg{Xy#B^sbdkNTn zE;p@sSkvK!EB6ZBmNgtXWxguYKRBU!bXDv!rKf%%wC!xVCBFYDhg}rCUkhPaR>}|^ z(1V2~UO}o-wwicu+}kg7gSXysr*CBzNWJU7JRc-lj5px#Wv4gca+7{P!!*{W4{@(d zu-%Hka7DQWY?Ltz2v5?nuicw?;3~0X~LI+gEFAsfYp5$~gMMWMA z4jyW1%-ht!5&h1Q(>ECj|BE#rG_h5+FfgFs-j-h9-qw`je#6*>_xAfTEx8fVvyT%E zKwIFzRuJ{jc~mM4u|I=qabjJ>FgACr#W6JI1yn&sFk!;46Owni?ej4qLZxA{L2!S9 zlSf+HG6QpAgj1)5a&}JPm`gJrtu*AownFh(f6=>a%qYC?Vu6CNe*e8 zy+@jMoxDfiV_&+lc*V&dZoqy5ZfG`T>V9CkS+zUa8q|!gQ9t)NROWN}uJVxlT^(G@ z{vfYn^Z?mkQ*Z8xqajPj=JsGU`;Tt*kA@HR4ePCcqrbI)x%y%dzN7O5a4(t$rujll z?&oLa@Keq*%uuBexs)F3D@;k7e*-smB7FE>gYR=3?z)-$!##@*Fy{B*HZQFXUE7(5 z#N*dJ*CfV2LMP6cnhHVB+ls3z$qkxsH7#IZ`_=<$p6g9;vMHU}#M9)7teqanR%Xo} z%7|e~A;Q|if*l`5@c?UfLLS<;T>?z%8ch?`UqpM}2 zOYmprjG!nadPL#HY&C2Yb;X99qdFO_b8973S_q`9+`k~UoS8eREoqb3DTxVs_nFwh z*>?)%hf}|bpHS+>2S3&<;50a#gu+=NdQt|>U7+xp9Oisi3e`$mK9d0UT!R)M^kkQ` zyOaKLP{qVq_*)ZrWjnhHpD#EJZ4W$nQeh_yuiBP%oF%|FR_7n3)$VxbmEIQXxcb0}=1oVB%FIj{ie-LfdZslW4 z$P|Fg>wzZTY6K5p_$xS}jcdW4`1+)f@;6fpu+Ef2cqB6uii$wfZKkZ0s?Ztm@4uEE z(iYM=`xk?Cz4oK7F7@Ifd;wZtKpAGFDOM~Q9fOG%1Z4l5Kn}cn9b4JYp<3a`A15TE z1#dgKu`R%4pFY(fSTmxoN;%HBxw!^i8w5LD&PHZkZ3Jj#t=mrfs{#*-@1>fEL9B!;QTw_0Q^;2>A> z=g++M(jJ>tyL2f{z7A}zL@aY)6=`A{NNpqfP-sf9Ws2$N2_IVIj%BApZfB>tloaui zeA6R5xO-5^id9n=Kh=qOvZ+SZG3)xdy{?By7&=0!Xln##!I*XNW{zoR_x$r}12KZ4 z0B{(ARW05yST_h;RDWrI!!ba?@5DUzU__mK$BYq8QTyEDhT=q1Y31PaFBuYq(31G< zr<_0>Zi8iU^SH#yd-M)K$7TMKVmT+v@C8G2UNT(6Hxlh{ofm6p&1n9f6?61enxJ$*D? zONsnt*bJOk(^ziKA7U{oq1F5BJkj4JeZ;HfqyH;t$V`ZJB>p^m=%tAQY-XN2{^Vm| zYzikI@GE0?l2&156O&>d3_c754iKNWD?Z@UioW5V$ona^B@Mw`$glDPLNFT1dp@E9 zM-Hb2i+P3W(bUZQ7LEk+&!wa!V~MX%+Z>9)xYwnYC*~x6Nos_Pzd4I-WvN5&_Ih*v zFPVzALNYBo?Y-((gKDWzPx95Lfa1_?;wrFxpYGS6@qUkr7?<$Xe9>c)jkQA;O#Lh= zfAY#xNL5W=l{~M&&1_IMatRv70-S}J-P&|uU6g5+*BWkCSDV|gGn5~+b`@MP{J!#O zl`tq!RH9mGQjfJF(7eYzEYXRcE|=9dcP6Y82*5H{(=QGGT({#Uie9XPYa04VIq#=G z-gcta*Gn_jpL%rJ`yM*xVG^b%Zs26JnpMrN4KheJp^pudR|D06>jIMClQb=r22YKF zoJifTP(5d7K~K*^+_$dtIg&Q232=fAWne%vod|2+)5%odY)H5LmYJ()7-He{D?N

    Q2no|BODBhN%1EBaBC;O!G2D(MH7Z5C5`1O8>Myj z^4f{3wFrTs9#&i}t`Hsk9Uu2N?&bf8XCd>l6~?le=j~0=tnXS@5eNUt(G9!Lt&Oa7 zAO?e=)ap;TX0PIk!f-Ja$S=BK`{~|;N~6((&yV9cP^{7&zS9~Ok?BXXo#2NU{ zBa2PU0I^+D4l zm!x~Ltc=d~J&$Y_LR-Y53%IzKp&o!xZ+@sl#$<$kyM+r{6ShK$>Ev+C`a0 zMm-}We0hYDcmtBwBBkgo z=7A#o{_yr!{BmGifrU3wl%9IEx;QC`Zxcso#V!A=jFsfdE`yPa_m53WK_IvXF^k$` z<}OBCf> z8LzIm(S6Xv%a6_ZT$kLGrnvKTe9T1YM1%x~3zk-@U3NF`c9DE~#scRf3mkZR6!7_G zDDFJmSTl}x0v9=xmE;p}!3ZG7Np%<`fyw4E7nn8MGc~IF{OJwF44t0$G|VN`rVohjn}Cl87Wd z!0uVQ)pX$q%z*D(D%@ahjzyd^IpN(-7qbP!c6aycmd@%E>u!D?oG}4G3^QN1o*H`1 zlzPn3dAN4;xF{MvaVeB*lE_3tr6{Fa+gINoPEd{Gq6ai-JlKH}wGBOHaar@m1N}Hg z$GcxOQ^`>W2r&$elM^Gz7^Zer+PwJ6$WBb|wT3l|H}RBOJCozhoEvahrj_aB@JmEAhT%;L8Kh^~uw{xMGSlG)A86Cxqb3CipVQN` z=n;8F`O!!5?3-x9gXDc>Xve-+Lg=HsSNC~7W(c}te#X!Jjo$p?Mk#qWD|ngpzW%d$ zTj6cPHmLSM(qE#eHwOjB|78OmJ$`k+PjZA`tM#?hY9po24(#56trt;dCYnwLwV1A} zm<rP!Ha)Gt4Q=dt-1;%dbv?i?WTCL4={SjkD{E|ZKM6f z1V8`*_4b8ypivLd6>kFCKeWi=i8aqTu6(GB+-fd_*pBn{9-DIkQ|m5W8OC03(7M9) zz`Q=JR?lOo0tjgptgBWw1S07UEX!J$`3(kzOvb+up9%{NJjz^20%F2O5XAtN{r+YGfUL5!vw`a_+^nMHcOg;SA8zg*U6JSlHfB#h=({v&ebvc*ouVR2FNzE(F^+5? zB?=stNIyDPN5Hj}2bNQ*%VLIde3(-*?AEQ$ou2*yAXlq^ppWaj7G!I=+Ao1 zXOl_8Spj19cpm~h_RbU18CK(Hy>5vxct|$V-06u411hVrMnv|Ubu$(=8bBxePIy-# z`}@l;y3)<5FSRpi7xe_D!Cp+J}xJ2b)=L?t?84e=#%fTV;Q!y8qm{? z{p`1ZN+*J?eq;S9+m&u|1Tp?oV70bm9{Syq_bk9}?St zx;~Oumf0K4L;%+13}RHT{_Wg8wrl@PjU2z5NRg2pFLjV4z^S5CW+^%5SMlAB*`ANF z$Dax$mWq}4R|xhL2H=wZlc91+Q`e`W&cR`)JZh(|9VK-ic-DR2CGM*J3mWGe;Wt%_ zoqAsRmUT>hU{6zG%QrR$KhN~rN<+WArHv{OMCwgrq85=?vv*&1;d{zTtvOeW3(2mK z%fgoRid%UhutL;g#V_ig1Uw5|$nsArsAA9IYkNvu{X!jn)yu)ft_K-u+nMhj$hVcI z&3-(*Etu?6=XTHp#ZAqr10I$Wi8-wJeouT>U1{5+fn@5o@yuA zz&`4;DSYhx3x1Ia(0ObEtNzY~a4wbu#kiJbR{oHkzwQ7kJ2Z4GV^QW|wsyh8F63ef zJRP927Pw}?J<6AYT>V2wSHhreGIK7_2Tk3bsfO{#y)ow07NBa{C)3*WChp=9t)_6f z-v4NO=qs~XztksYDgdv=${GfA@&Yl;9pjBV8PKm*{#D{`lJ{n!fL+_sM|I|O!IRa= zO$_r{(ePLfto7Si_KH>_6gWno7)dqs>a`KhUu3_Z&*m1{61K_o|l_%*Dqn*RMFeXpH4{pjoo zxok5TWLMen64}CX2i`fJIifE6R*S-XnJLtav`ha7A>^*`c+ZW&n-)@&{{E1y(|inw zB313U0Nl)n_@ub=BpS=rUVA-^z+6D()7o?G^;alaSojSJR=yYD)%chXP@N|D$|Kp{ zJJ8+8MOBr;JUKaR`yw8ESyA_d};G~PljYX@GuJy0VmE1 zDOYOaerbVK-!e|hU507Hy%#mKuKMfOv1s|ttZnn==$9RQ>q;0Wnw(Qxf*SMX)kXA1 zhhtV8{8#rBg-hqb13$gD++k~c$zppMsreWZK8NAC6OrU5;`-HEhN*5&ONOE5k`!{) z!6~b)*|Rl)(B>q?9Z@d4nd+rB335a~;$0Z4q!T{QjJT7ZK|jQ#LY}FKT`s&kS4bkQ zAO%rMg3w5-xpF3>f`J8?UVJmE3mAJ*{a;CA86NA}i zgUO&Z7juLRBwbRR+CV@+dKdH~uR6`dBh;c5clxUM2w@gZ<2^;j(bVncF zJf~j!IG3)v1s&D`7mMECeL;P;pe^#lmtDgTPm8~I>Z{GBsPN&6%7u_-{_#UZ%>R;S z_$~egn*qV;D99*Saq1T_xB_Z2$&ZDWfHvvzjqlBZe2s^e9q4a3c6mS@*_~w1DF4_N zx>lP^Vz8;%8=2^(I=HD?&hRep-7EDW180mrsH2GZ6t1Wi;7M*-`I3LXI0rNG*t1bA zA}%zKhJnDPG$jH^y1d&QXy|0Cx1M}G$B-X*i|Wxw$(oGc3aJP@Z9O!o2NVrk5C!@p`e)tn^{7K;1!JPWKo~ zi-S#s!Ys4WTUf!wZxHf2uyInoIk6$5VSbd~0}P0Lo3_4>A3kDIuE~Di}cZ zS;+{Lq%z6&;pW*Lo7sVn!yGda`ch$QZ$6S&y7RRB;BX3a)dHxkf)(Y4^r`i8HZhFY z%XiVlL2~d@AH#Zzd8}%$ai~ARt8PktvJW=`Exz|Fbvdw)Xm#puN z>#ceFJ%d=-B)m04^d2gmhQE|yQu>*ztI(iFgjwZm=LkD1BlS(wbWr&k%MW5(+|T9p z`6;nq!K(WxMuBuUkuN#p>r#I4If5{xW35!^tSpU*YoukF>)@xz0D01K$erJ)rYCO0dPeLG4$>o81wgd3j)A&gfs_ra1bIdBTW-RtUN(eZ2^K9Y zta2MeV4LY~G8Y2R?R4~$1`w#U8xfZ`#ZeJofCv7De1o(U-F5f5Zbxludy4B|r(+`r zQM!}7beSo~sr%1YAZSJETP=Fkz@uDiDV61Ag~=hVGR%m2#3PrpS*mW;rorqUew_p2Kd2D-vn}AkcDn6aaB4^)YvMHwXjIwZdG9;MoNj+d2%lmxe@00& zYu0kKLYtRub8C=tL2!yZFz-Kl=m`ntZ?Ep4KY0e!Z_>j}_RW#8*WkNY#mQetc3Bpr zVhQnRDiB_rkF8}yfAOH=zOW9wNj&Sy8I}5a6d({>)(=q!~>ydy3 zakq`h8wuU74R(CJR`p@HZG1CTzpB(-OnMZXcvkw191?+gMtvA`H@(DaX^p3pirr~Y!rqbiPR z>R=brP2>`Jw&pPSlEAkA_PC|X5jo0o!!bJ$7lZW;6Miz`AX+Vxk5LV+UiEKjcU*$6 zy}4V%pZpCm*(YvJ-5Tx89#?a62{Bw5dE+%9_Z4%Fxw{pifL1b&1h@2htKN%f%8y?* zu8fQbZ*Y#-l&bvqZ4T5AB5%K6fNMnQ!A&+54hHDT0A`n19@?u#3=rty68bvSFK zD|u*lx*`-{nbmWYC#k7UeiQSR+OV5jYZKw}>ixuse<1qRq%CM1zPP9tg6@=E<7M2+zzuWU1_FPc>x!t2a zTXUM8xnWm1X>n)uX4FaH*gpR_u|MyqzXafO*;@N)FkrqM9x5Vi#6XE#ZexnKJ-|gQo$HB$`E!LgFo{$Z!D`rp?G0f&%|8+z+-x* zg#q{>)Z|SOAovhDHgWZ7Zi$;Q+guw#Xxh`uaoqvc( zmwtpkJQscg#Dt$Np=e!<=d&Vm*a6S!+{tyZsW6YaURUpe6j$ayMYKffJDBtievHe< zrfO9j=N*+btzOQ->GkeIzGmFQw!SM=NbYKqN3rt#ZFq>(lSL~_imX%~XzZ-EcJp&; zx+EBDVRm!w#`lL`4gX~ia(`ImC%1bYrUD-Lg3IOzS1xdMnLxjzAcCH{RtY?lA^I z4vFEFStIO_JL{9Y+^u$V;0#0GA}7zBqp{Zw>6toDH5<=w^?uaQK)vbt4a^l_mtI+` zog_L@wkG}YvDSjV{acsG-P_nqU)2V` z`Mc@$^d38n>Dwcj$mRZsg49qj=PP0=ty$Ai2CA^}hyTgN=l@>j(EpeUksTB*1) zReM)yJaR3~u7T5iEMsuL0l#8(bGCm~$qcYvpIGX)Hs_-fzZ5X(TiOH)uN|`peQFk7 zw%^O~b~#RcP=?`O%Y{p+Jd$sam2>SX`SP}D!djEYy$ywqOlUrp!3>)%`Y)AY-p6St z6IteGLh@&jjBU8)I8s68_quGEsgyI3wulFzXd6mi!9PP{%ZcrpwQXt(0>Z4txH;jG zcRG1-lPasz0;SGlAO7Q+?>B!qni>j7Ev;z$ENVZflk`vf$(S?i+3!VV`uG!Fb(Q+l zvQvfLL-@*2=asq{qt%BuIrHYX+0Mwl`H(hTBSZ7dVI+RpsNda(QCap1Stdnm&MW| z#`V{ z7|=#~7wkS_Mirm{ETdDJpWnmT2x;T`dF>dT3@hYm2CQS$31_A zGuc$kX7&|2b<17URiXDgAL1yh+XS4ul{Nu_@`s^|x^xf3y1D|H-5tTts}q`C0k5we z-Lf5B9BghJ5XhFaU2WPgUCPqxG1A^ZDx``bfHz*2#Mbx8Wf^%+_3S(|j6gaD@O`WX zyjA!*{Pg%Wd@DB(^yOJgb1AlVcxJEa^-g|ep)#vSsxuMX5?wh_=A)=U5hp}-rK|N} zp=Ajp;GD;bx~uk}KkA4%}E(6momYM@izdwr$yB#`XP zdwue7m|~c0Gw3->4W+7JXtgCVpVCrA&jUDBl0fm@i=g{($~8vjjX>tTah&18oP?v8 zWmxflRCDrrO7X*F_pb(7g_k@e$cWPIi+<|Z=Vv^g>VGJld?QZ~&()rWvAj%K@rBfA zs2vFlIY#)n=Lgzd@boAD9%VWCJ>58k+PhgIFvp0GNZhfJXk^Sl(>2zR9wAU&+sn}p?E}y@efYZeTDMhLq~qf zJ5wPU)M3J2;t}OavD^MG;hyT%T54=Waog;~;2jT>vy!TWR%5sv0{l=tx%lGRbM^7& zCf##iH48Fd8Hs6Z1IUwls=5$Y^XN>( z^$T5R9-aS0t_it-ig<7MzqTvC{y;F`2=B^XBCRU8Cf-6`zsd@9JK5X*zFS``rYj{= zj1MM;Eq%S5Q{UYE0eG!4A1iWpATT*}Ckck^W*>8e!X{kZ-ArlyC8Vg?iDj%9veAhAO7$Q$^ z-qEqlV)1ex^)h@lSg`KKC0Piz&cJ@9OT2zANOT!C$)KU^IXxrCw6;#B*usw>g6uLc zO48}}_)~ISy7{nH#wh-#$knDuT<;7BZ{~M1o{Cj=-BE zx@$6Cu-mt+EvB2qeIr1 z$LbGjq`AXIO2T(Or<2y`igxL zQz1?Z8RY`4>f-Q%z7~T=y}!_;GhupTx|e`pyv-$P3OrfRR4%{1s}n6%?}%3~0P`(j zzuwQdHJ53JAad<`@n$0Ye=S@rCHsXf;p?wo^pTs9rqvs3&K-5#O7#4` zx`vqN$_#@C;+Ko)Z5##>gPKI@M=S5tK!D#+l*mz7qbd^&z*?2Y^Y?~cL5e#9TbsO` zWj;5Pulama-ye!aJK4?|abI$R$`WseK@l34SiHgY_oIFloFyarb(EJ88T|;t$q2DLh8iqq0vsYZ9 zv{!rl&ewe7TKLE($}EW-5e34}RwVHwI$reVS2Scav`_a-}SJpnaV{v4;EHpm}TU<~}^ z`S8o$eoB2tt-!?hhZw4HXu=je{!(CLjqI5w4Y9uAP*uf^tb#wxV&#(=!h^QCxtZm9 zF;EX&(b?7}>^=YDl?O)&ghS<|)%@#aANe0tF0=hqHjyJnvTHZ41D%ggzi<|tV|_m8 zJ~VrFrT1sSggs+0g*}i3dV0@`NwzqgMx_n_T~`d3SRQAx#=(iPTS*D6FV=8oi0A8` zW^yiO0VVk`Q&Am7L*;1fIJ{hO3_iIZKcyR>UrO1s6Kh_uN{J@$WTqnf1(bak3jGlt z;<3M)7ckX(6*5_S)hm>Re%dCWKiI1{3XuT=B>AKv*&Sc z>2zu)f)27PTe;U8Ie2{GY;ATu6A_&Nvz~C##Bl)ykZ{3Vl_gg;x1H_Gu9=f!HQ(qJ zWrQS<4-~}j2$cmtbh@bZ+l4yb0 zoL_xBPPiNgR*>v$&K(X&hJk;o^9{h>04oMO+Bq7ks=*Z%72jT)6Lij2sT2FXR)YE^ z)6kgEf5i}HS9a=il|k=Aa-%DZ0Lw0buqnORkvmGgk$?`YI*I#<_GE*or!oB=5ex@H z@$7M!>$r~7w(8JC9{5o-Hjl*1wSv0*O-N2FQTZFu0S@MsIN4}8ZvmKk$bCPA(PLHctFQmWY4hG_F%QYAfO8_?OQ$g+q5#m1;V{(l!>+B?w1p=~IJ- zqb2fY%Q+2s-iU1h<@YE+EEXrlZYdfDbLmeK4riH%`ai(a{df5aOlSTpoXE;$E?Hsn zyQK-S7=|GON(zyt`g??ONVpVh!HPdoo^GfDZF6h{NFkiRfbZBo#KQ~6LcAyx4$22}ANiU5H1G9%8_SG%w|sz#QuW*e_}Hex zdBw?XpBPYhY+3nPVK6|q56ROuBAVO={fNrnGoUtN&HD!pff<~=T>>MV5GBDhU+N~> z+Wl2E*LLI2dm69$vWCndP!WJta3Q-&&<`bSzcLX7z!oN!Gh_7i27}){F>}H#M6Ivn zd)i8d`db;CUFU)jlt zeg)|t46{&F?!WVUtvY!ZJrI*0^_RqByzm(mP@ugcF8w+2YJqqQe$R+ym~U8zMDdL5 z*A5AW%$W8#2CD_{Bgg8uY5bmIi1c~lUFOSz)BV*223V<|+)fm_Is+<}WudBiE;9={ z<59-56*@cYBM)uH2OSO$gJrHrkxl1WAw0`c6a2!?lfK{b%8Q;@}0tqUW$4o|rHh1&3$FoYFd47SPr{u6x*9BC^ zFYDKb8MX9QS}p92hOv0lgMbVuu*|m@FNgt|f@yf&JUgEAa{umoQNM2u!BZ_@&NRV@ zCpRv%XC~v1xz9VS9BJ-@D<1gm_fVWb{gT9i3_#HNIZ=N6{HD0Rvvm|4Sd5S<#_%KA zm|J=;XH)q?-F;`~={?XZ;*c{tJUc)myF-dMH9ft-@o7^7Np}l+L}WsW)PEZrr+=`| zB&5ffoht#4E0P71h8(Hboso3ZJW_I6vf<+dcTMQz<{dbglC=(<_ zG*g-s8^0CFD5mfvS1AQ?mIe={xQx_>{S8N_63 z;u{?KbyPY5P=z4^_%n*T>~@9hc8SrSHuSOBVXu29yLZh>*Ro00u%<6ofLyoABhXVH zgO`k!Az-XHpH&rbFx9Rw99)yg1k>{LlFeIfsUMluzJ4{~ zm%tvSIq<-}Y210y&zv&6W^Jjwxp_)Ws^9c7{=03F>)*MhD3X4EIuaSy2{oVz;-9G$ zIz8ReyONu7lBRp{*PWyHfuUqsDo@*v>JYN*0XI<8hYKay-%q>uJ{og74*tHJ(KO?H z=WvK(evL-$uSzEvxRq0oPa`#_oT$a;S=tjW5hvmk5#>`7nLzjPo|h<2prfiW3It#~ z5NKSA-R~?1FL74HWN)6fN~95k>|X9#^V1|JHofR%S*Ci+eA}dk zb3WsSc-S$P>FXG}pgSp7(v}_AYhrAKYmJMUc@}|9swDbnJPzdj!TC8BLsF(y^YUvn zlGR-E1z-$;KjyyZm3wAuan3FbInfNc*HrZ5uBEg)A^cO6!_gx`{36zR3pNr1jo1=_ z>6*7MADw9AcZY6>w$svGG1xs!t63Y`t*>)T6VR-&8@BK?wguLJk!?%&x6PH`&4Kh_ z--D%S-@g{!R@cQfTV@Mc_QLjKDzDstwV*1z%t?O{cX@GMDSLYmNc6p?eLhH+cYI)7 z;bu=_NeSj74n4yR9Y7w&R%c$0qnlWPyt_2Te|;J0F#ttDw=^r zCxyb+o6klvB-A?B!|qH|7e$ExdixD7sUomptG@YoGwpt-%Op(~tNkQXU;460%_a{s zqQkV!>6D^F2I-fJYw?g2k;oM2XjkA zp(VLV(Iti+XUWO1(CT}Cih{JJuAmXbe?a~TO~Z~BNY}qplF#?u?UwhF{w@HG4-isG zFn4bv)$={3d8`blCN88Ux!$SgGN26%{tz z>I$6mB3j((cCQqkP$!`4!S;6TZRSeQzb2y#)?LM^;Frwk4OSxSuz&qXHFf+7Qx@jL zApsc7w-m9wYLk4{NdCk|t2mfS{_9R_V21mhyY)Z=jKSi?q7c~Q*-;ZqgfPYE!~{-o zxFV^79a9&$&Z2NhBRux`cEkgX9%6ysJ8y;eA7|Fkt=!F|nBl4QIl;r3&uybM!@%w9 zTw==01tNk%)wQ+FH%6@Mz7eUm17uQU%a^=^XBdbp)`P?45>PXYkDmhwzb9p!)XfAV z9zJBQYS?TVWDm_vQ{=%xcF5729M*^FjBJLEu>n5peGXS;UN4}>DD?ZS0gkrX?g!Hn zI`>;jz>KT}CHRy1x3FVetBzq$>j`8{H+t@NP$x0Ht;Ha5mTsQN3}(IgCh?W0F?(jl zXQ=t&?X$I>O7GczAo~$qTB5YC_=C(E+t2vgy*=(dJbhG_tYzcecIZ&N14xFPWa?#9 zJWKeO$|@x3Q<^Gv6ZN1vIe^ZP#lm=p)VL(Xsewn%bdnzz)~xbP#_ukWnDx+>-?AzA zS(=gbNmS^R?6skEmTfDPqvhu^vR}!=L8QdgrTNnzPk1bH5ngiXc5- zO*}hB%0d&0Fs2tW`eHU;z06(J|Jk={=bU0KuWDW0aU}45^g?^D66i&%?XEeR>J{oN znwNuVWe_Yut}G$BF#%140z|ZUY4-@`B#6FG5(KngU(&8J_2(5=-}wv#jseT5Lh2vj zT??clH5U$`AjVa=|>T$nH z`a~Hibcf&VMN1ZCKukCcK-sLz40oc~lDe#R0W^xSKOOI(@>P0e5259OY4t`PC zu8rq2*LQ^-8XZZh3S0CxRDQVWnu0Pn(_-~=%##fhObIXQer^BeemFAtWD+eQCBmCi)b;+Jm8j&q z@LyHTI_?(JUm88BmxdqoavB&v`G9xl21-+YoloHjVtDd2xte?OR95Dlo}QlWsL%7!^!M+o zG#uH;sY21dX6jPz0{lg{QO`F6b;rW6Hi!3fQ%;ZZ7McT2hlhvTPvxgH{Y3j&rG8fp z?)_QOb~Rs0YK?<4i?8DZyAJVtx%IGLPS*GprC4US;)6n5ag0i(qN;F1nJJU94~5&x z$Fk@ascNlM2T!rUdm>drLlfcz09P2w51dOfkd_1x{ z(IK=be}*?OB6+cL1JEgN-MMLJE&%b zhOVy~-L+?bIN@=y?77Hl@zhX2POD*`(hfl`=wbGXz+EVtTI}%L?JDy};$wAdIHq@K zVJ}(WN*1zH7G4Y4`PJ8gkMj49TpOls+QzES{#aQmR+_xkM;&pRcx%rx?^vHiY;7;B z&Lw7q;Gm@LYa0fLsYjenO?HQXv9FJg5ONy7R4 zC9c(!*rj5n2tfR&jnyfGhi0j+BX>3K{i4?{$f;?J*si1!rP$q-39juONMlVh-AYRL z{mG|6I2pVfeso@e;@I!jys}UEvSxPuko17M?2-C^M@NiF#lJw;mq|{TuW2FcMn+v< zowO#b?(JbW<}37zgtcR~G_P|ol$vd7gQ(c4K)qw}GyHrDMl9)CuO?vf}T^=w*aqN)x~J+iJJY-4cMEh36`;992)!#03_Ey|NIucKW8Q&;!ZWiWO2o0jt@U%EM1#3{mtc^+1jlPp?&`y12MiwQK6b~>$ug< z@tSraoDJ?gAs>(g4jk%pPXc=lz7+1dy&mXJE3?Ib&gYRVzcgcRsTlWOz^aDV^;{ZyYPfTqiP1T$l};n0CE{(Il(kR$>BEmC33|izNO}KV?x9 zGRyp6NT}p!F_udG!YZgR?WlWz8|~DUKmG+S@fg}8h39mqaEQP389$pwR?P~dcWpTV z63K&BByV%pO-IIeUx|HTt{>^{>XLBF>xauTpVp~0#=3g5?KosLo~&p)=N-9)$H)iA zrpY5>HuHmK4~||oOqN>@`n4OEf~pj1N5n)L3tGXYCQbd!ssZ$%T1rqWB}ytXZ92-e z{EnGZtk9Bgp36mPZ)GCL3+v#8BX}tkb^OfaBr7z@oVf#it>{Z;r2m(}o^mmRahOM+ z(!d`9>_km#gS_>yJH{p3y8QUwbFpy0?wSmOjryUrV9nZINimKtHM+{0!s-g#5an$y zW;B0}yG{38>|HsX!60VGr%_|cI!v!>Uke0N!6?jR&advLEdE^*n>yRj)V4jdO&d}8F z58xhN@o4AXMd4fElo@Gx55~T`sI}A&8@)J^pJ}_wt>MdT>W2&3g{+DdC4%n_2wmQa z=w}CfKdn3cl(Uk2eYFsBO|p9MMtsl{x_x+R&cbSZ!uj)&fHZXAV)de7YB{$(M6+Sv z7>=QpnJmx|BZB9mz!E0=)Oa)N^{I-}W*1dORP8O(3Fgfhs|#M?&*Vr1b)$9RPQ<`O zj#8u1)sqdyF_V3O zt@R^|>C3runp@T^iI&OK91d3k`6!V6v1ZX7i+C}iDuyZCyyn=iUeME(SFE>E<-eCJ zgp=uCLpC!o5!DviNjz*U=0Qeh#x+~rh)#>nl z_hWYXa~f6EO&5tuhWa(PylN3?o2wi=9=AsBnZVYM(exwAT9}pDYQ%L-bVi*8=z=rJ z_u=kDtRBOcb7m9-8FC^%|0k{EsU^vU?cR9oZNAYH>^;{jYf$&zJ0fT#Dn#RE`XAPn z5wg|ghSn}FUznx6hbL<}0$W)2pZFjCS&hGEfnKt1SYEe4F`#7T1~!via{CGS z$-~bG3&GB3Hl)?h7*YDLw{3VGxbshyz^iDpxm*>y2X!NU3 zjsR|{KMxdhxxgD5IHr|gsNwu{Aw#Dv3VNPjS8qxYjpb;r>G+l-@{!&6th52>`_AqJ zHLB9x%-nxUx{$#L{D}bvnvN-|y~6zZteEAu10r4R)|q}H^^Ae3vs2~c1n4C_ zzkDLtap|DrTOu0_T12JGx~P$_>qA}%92bEkf{o0JnJO4L9hHHxmyb<@4sYp|of-tEVB?;Iie z(h3(2h8EH)8nj~OdV=Lf780BFPwO7m!N{&4ftn@*nv9ttj8x-`Qcz$@R{^;R(PD-X z6@^aAt5{&!(hT8E5NBRzJN8TWp2(|gz8nzml>qg;@Nm{$NSIs>bsfnS{gofJUqB3O zBixs@$9-nHqGpxz-N%2eQ~>D*83K25&pvfhVm%BKh_6I5FJ|wk+A}hQ46L_LY?uwc z`aAR}pqXzi-E*jg#d$b(Fg4C;I97C0cyI<`k>x7xH7V}!P9pQO_vqO&$*)}!=9&s@ zj=WKboxZuL^WpjN87HgH;Wh<(vdW88p8x~p2oFu6ne{TlGcMFp#YiOm?+%N1e?v6s z&gMi8uizQWlf3vx7dF^uR0Y^l8p?o&Q4Xt&VNFAqr<_?0+)C^k6xe)<77K*HT3QS)5a)j*1FMVHiS@VhJum_SX>e7qzW z-Q6WHI$U)(bZ#y|xNK*4w;H@TK>|eIV;0rkpc2;$o6cGx}#G0eocOvP##B~ZoGW|S0X$9!g8h_C}yP#W%jSf?DeQf~J`yrKlVW^NhSXTf?8RcYdDJTruD#<$N_ zDwP9{DM^C2t^;DVw7=`?Df7lppxM6ii;hc0Te~k!xIdH6ojQ?OBOsdA3t9!TG0-C4 z#q+FouexVcrvu=N+6Wx)B8m~B!}P=um9`0xv|`&>lq+(1l~ozDc7R6sehX5)bn$}QD0R{f~rD*qN=nhfy^U0of3v(vexQqZ+{v==p*wuZP-JtkwZ9!ZlA`3zFA;AbS zeCV>9yblSszf%d@K^jk=-yWJ<9i&ECUN|3Uav}a|KJ+nbtPgNIJnc;Wb`>POTl%oRIhdac|3KegmT$MEI;YTm%EdwWh`Dk9j zdyj}xnDdjk7^MJg$K1z$`ZuhgHUj>SgR?V>@@;#XzkE%LS6lW|m&{`ji}OK}lL;9? zFQKN}+ulSY`CbM6mCa!E6iVk{FGZNqd19Fb@#p+IAdSo!RIR%XRuw zjxDD-VT=e%PC1cxmhJffrKh4$DMY7CLPN@b85okfIOZp0aKDU=?wDFq_HEST4Q@5E z0*;dq@~!cHZboi~+gQE>Ea%qQxSISW!Xn>Q!0*P|zGfJ7o|Cq?0u5<;;@o1b@AXkU zR^Y}4bq2hdX2clDKPbVb%dYGdKe9-~+|6e3(kQT}Ie1WaSpuTed) zSv0yEZy6^@PBHAF4q*<1OD~@-sU`?{zqQ9G)k#`jcvW>C%nMx8KuU4HX6dAVA&Dv? ziAv=hH^uGC89(|~8!yq}D>?ptQc^|8S^Ww#84-g+cB8k zRcbE0ZgZ8Yej}3HaIL9H+B7P~>GgV50J9$)7Mz$FuJjjt`N_LmBSpi^vl5F>(c{3! z^cR4gfn9HbR^N2st?!Su%S~Lp{Fa!gD|5|tISsa7Y4Muz+jR_>mYL}!!nWicPNT6v zO;>HaiSvBZ+%pj#(qQE;cqn9YVm=Zn&t-fj8sUMvm`Rx=OAKS_=nE!5T~N5}n)BfM zBnt#ef8Z%M+_ij16pW8z_|>;-yVWkQR0@DUBov;sY|R4PQt5zt4LbFx^Naj(@$RBE z!u%S#F@M6=HtfLLQcq!@U2ZTz>~_d%v6OV1o_x(|vU)Q_n4yU2cJoMDT4n9544#Fu z7&W*&-CAWKG2gan+BT-2C?&Dw^SsEqzGED1qJ*h{nPD?rqZve+;AMNI`_Y2)hijrdbK8USCd2gyl0#8&ZWZk+TC>?m9nN7_p0R1@0 z%wF4X4Tx`)0-h;5(6VZCs6mXgGst9r*XdOlAAiTp`uReTT&=}ZM%db0)ducFJJSZ3 z*Y+3kPqvWF%wDNeeXF?mqU{-m5VI9(>a$#%D8U z00F=mkqaJYlzt4z1vlaw9rI)Tu9POLvR=CYv7dP%KeJg%2E9X%s~kq!=F3|U&`RM- zyi3qJ^Wr-%n~HP%B%jrI*G|v!;5UVn11BNli%Y^kJdArf(`}NM>37WY8a0?|{*&R? zY2W>GjveyET6&dXU%7A^L5k7jai}OS-P&!){2y7D?=Z+gwRx4CXJ5-$C54Y&XOPJk zua;g?(9|nQ9wuaTRU0pE4cgz)$ALzL4b)(w0>+_FQp+gIaNPtJz3~1k%UoC)m4fEH zb8^yXy+U+|GhRe=B+3LvPfLNy!@!eHPWxWoSX+m(*-y&e#=_Hn(W^8(Dsei}Y)Ka2 z3u`omdR&$M#yPb^JlQ=95u`hZ{l>YKG+yX)Nfd1K8)^9_0lWeK(qQvpoM;ou=gvfq z#l^*zW*Kc5MlKjZ%XBPsRsXb?S>_bsJ#jnyQlNERL{^sByT?0OKm!z6)h_dvj2y|f zGrjoa-S7XO1)%S`Sj98(W)?potM~BLi`Y0XMX0i$kL0=}=Q$0@JD6ngHWlNH)OBV=au74W=ZWJ!l`&ekH$sUcJRRIEfIQH4UDk&xvrvJUO!&uZx zTH@o(H%9Ue?MWZ~< zp8?Re^!5E3sY7RXdn5cP@;a3mpbOiQ@`LNH!5@e@8`pPt%khzlV(zBp6jaY-!J`@+C2PZBP%j6+yR~X6*ZoSP2?XMe&=cBI&KSPSCjbMJ#fop_U31QrUb&qz6glVWZwV_H!!TAY?EM1~dHpFmk8 z2!EzI=V6s_vmY62(=>QpE13xP4)bu=YA(-ymgX*Oa&nFL8PDFOJ!;7w1@TUgZsubQN->%L z^OJL{Rhzfv?M4NDBV7c_hrIOX@`<&*M-tfR9>p4CUZVUT>*bs2w1TV`54qHiXmw5J zX-{^WGpeeDqoOG0_equ@KF*^00sM6-KkA$M9l$%nzI#`}MTzkuA$DIQQxK*mgDC=h z*eFQhkE2=(eFdv3I9(`Vpa-sf?W4?hfRQw7byjG*@R>$Swk-98=LLe_yQZtJ9LcVp zmAO&zh)F>uWooI1dxpevO+y~ql`f}a;QA`N>}dgAnA5sHY$wH;pprCEU%aCZY#3{8 zQ~LfJB-&}fx_TAC8wLvwKLkHTV{Y!IkniO;HfCJz$yaVC+)H?koCtzQ^OeL2OhJ5e zb+yUld9P0&m!uq2x|VlU4m{qWvf{=`1{!luwjO65p>=^emw9UyC?MTvSbt?n?ucIfftqP5(U}R zi&4&p4+~@gnBGfNDZB-y`LO_BxwmD}1RpDgYRT3lfS>(dG103=`_Ym0sQz zmN!Fvz+L@tc2cf=*R@I2bx*nF8pcGa@tcEUW@E#i=Q^7t&Fvz6MtD6Aiy-iKKveBU zr9fWphAe6+L^$n@eO?qJVzv4Z+(#*d$?uZB0QzY#OFvE$T~5zP@s*|M#c`ZiYgRNepk_KpFP zYK{5#Ds?4p9sW9w_xmOzMI*QUXbp+GO9kPl71cch_y4N?m*N7N{$a%g{hVs>_>z%e zom{5^(GeS%t4U4t$%t3kOj_Sd7VpEdLrs&W+)%;Dzt!<~iDxSJBT!l}p+IVFiOe5i zMXX+j+jq0-Rvg>Lj3I6s0=JQvH};31e_Vb0_O-y@S0L8bB5(kFN!FyOyuw?OJdQ{E z;l!sO%c`b7k7@+t`GXxIXHKP~I(^bZXAbjz*OJG%Mjvzv0)n|GGmac^n~=wr?7*Eo zx3ErPaf&7sy98V5ZJ4egpS?oZ*KWPe%K?yr1ZlgiVHNe8tR&V+H3>8Qc3%)E?#FvR z#MnzZm8#AW7gIdT@JVAE<%Al{ZhWIDBE7B8$R?G+vMaL)^@aY6f(rFhsh`irExzd@ zt=I^vaC9Cf`HiYXyy-z-SZx(}Zhv;x^*4yNhdHpvOQ$9(Y=5;LQGiU%MYFRrZike7F^SFN4~|QTy7yl0Qp+6KXJ?M8m%wrncZcthDgWKD8}^&eL?M{sZ&!`? z*)K-{Zl?WcXVl5{4iD+B-yBLtt|5=H^nJ@zImb}V$gSDBe)Evk3}yF#FU)`04RS2< z>`ZthG8f9Y?R?iMd}9!lNq6~F{vdcH5~W$>Mg25jv|J@FYYcrldccvC?`E>vzE5wu z3D{ig5RCM*9=tFeZ+d!SPN`7c1)ucw#s|CKW%}RGJLJ{!#HaBG&i`^8Bzo>Gw*TrQ zHHVe$oe)G!$iS~`@nO9O8?1rM)AsBFoCxjz(dP*r0J6=62nAl3QxT&p?ybzJ2i{ZS z_^nB)aZP<_j}sna_+)8c-fyY-KO3IrozG9bVReBC_9{we7g-F@GfULc-e{y0AbQ5| z$cvOYO4)?e82zzy`QF-yDeo8zhZB>@W}6{sGILmxXWy0dybx9%7%godL6{ z^mf|*E0*O8!Yp2nmfIwcLJ)5S%43+T^Q4ma(7C#I1yde3j5XH3Bbn&<7AafO@v8H1 z(t!vBiZS;B#_*zzyUt@crb4dHPUO0w&lA^wqJtjT$C_bAKx$I(^##4(&Q#j zG<&-tfvm$)l~r?;s#llGgQxCODGo{&enb1l35jo}MB@B2upUZV>z(R-b-jPf``N}g z!4e^EBY`zFSo)OkZ0my*aG64B=n4g7F;^$7&1H_Z*L&E0m8d5f(6g1XaR_y79PwI? z5FK9lAl9L35w3PCOFvP6Z;og{-#$P%6qX9!+84>N7%Ca}2S6)W!%bAV(a}4_;i#`$ z!0e@E0`VLK158?dasM5eJwgN^&tdT9x>j+iVs-h+-l^0odJ@-*33>Ou!rrsY^5D9Z z#?mtVKCKxaC8c7$z^i(xn?txrW~m>E1cQ)Spr)YPhTy~8QF5`l~j52O~CZEV>ZwemB*LB1u2m&)rJVc0)2nqw#$blsc zY^mRV0D4wOXs;dFc0vKD?YYu{1O^R8qPM(@fr(xJK)iHXp8AkdkQmsHgM<(MYW@Yh zCS1k_-^@1(}Cm%B_z(1ObKK*RXSO>j~gA5a;c;%YNMp4AN*FHZ0TI~lZdKl z*W^JR93r$Zbl-3Lb&ZkjfdFlfxwjuI69rEg?u~KzbG(k&XOM{n&pc$fVjhXyiKxebSc*T=Veli4pJKLVA%nZgiO0LgAyx66xgGQ_z=YNL z)pN@D5R(c9u%dffj0JBMJgY{P>wVMbI+PLDK#%au?7if~k#KT<}S}f7tgSx9oNLKs=q& zRQ;xfsgtveTfX`UB;6}r$snKYZ{4@YIV_Tyj9Ca#@(Ne6pw*JRftQA)mh5NT>i-<^ z?9PqJ$VyM<)SE^jKDv1$8Yz3hPWk6pC~S6?77mGncW*}VUN`QeDGFqx(l$Clgd;45 z5gi<^y@9h=E)!RsuZj}uG?&rnWseV=Pi73oD^KQTUO5{Mem``qYz4%csp|wbOtv4c zfjo%|PyBX->0iDewFRIJIbO6r z?QHY5+n-dW3%$@!|hK}S$6H7x#& zGi9Bj&Uau!X$G@sBQSGu81(qYnAE-x7%h-QjrD!G)(TZlK5;w%Eb;lDjV(rf#*D|K zUAObLEM;*D6ApB#VS>p5WSorGwnn80MZ3-iIkE z<<9H#Pe0sEN#Kn6Nvz%;SAo`{$ABEx#}|+R7ABZ0ry*`4tAIf-l?N~@ZCl+AkCT%? z{T{X8z@H=9Nr0?f{sz#(_&!IrIWtN++*X+z%dM>T=n<_SYqm^U$(}|HA!)~y1*YYJ zd$$qwXrRKodNk-t01@AI``B>owBoNVx1l_2<}JC!wHwhGpYq zD@#+K&X&|}N%AmJe1xxQb2zq!ZL~)3cl`Ry{#7_AaI~10Fh5t6Rz=8Fy$QdeT>Z-f zb$@$c^VP*Q4TdkAR%Hw|b#qr=dEp~@RvCYh_6%-wff923$X+z)swc>>Ci7jawYgK; zi04~s*H=pY4!Y3 zC4w@y0IAclLnOK%I9FYcSK_6mLyITLxIefe2&r2|dJ1XJbCboSgV|nN$L_ zh%L3F5>GF~-1s@h^57CwW3ojQ@0+w^=4XZC;vZVCANms5XQM!k`_%#aXmL2E&gsfA|MADa z4Yzx*XWTp{_v&c09z1L!>359QbH5J!2mMteEcB?3c0_r99AtQa1{cVNgWtQm$!>J` z`ewoaVVYchdG$2;=0bAziosj%Mo~f&$2u|}sIH#teBE2Q>{X#<(_-N4pw<=PkFk!y6i%14v0#J=bMt&Zgyk?|Gu>B zwLR&%5nFU`I*a=3nadPh)QmsB9iL5_H^qhWa@nmmmZ1$u$1_>f_$a`nm9vdLn^VBD zNLM&ka3=!=e$3eP@zcf;MoEUOs*Z#EPcKEwwP0VVC~6Ay_pI%4P1rw(vS{OSen3;W z^POpo7(VbXeb4*|9^O*6kEyOCs-yFzt1CU+XP}2^FPZc%4}Lup z=^IVgwaaj9V>6j8nB-7^G+Jk5H9&JMdns73k7JP!w`K;uq>~!Vawm6*+x}3$kd;Pp zF12miQPNTNO(!))$cz;hh_ECz`guEcy4j14Sjjaama6mNwne3z$EOxKr*p4%PWUT*OLLs^ge5l$;IB)d)oel{XO`{b% zeTIN%S5|fPSYk#alT<54i0>i(wEMxcC`6*}gg?Zow{9eJr^4(V;SNU(oP&GRmS?Mq zCl=S6pdbfJ6(4%?$y_(ADWoim&tDceL-gJ$R4-GM5SavVpL5f z1Bh{itMg9sfS4l^W*%iq1soofp~k?Cg%4DJ*0DVS}%V-{N_6 z81k%HOIw?LM`U1EPM}rdflB6SlY6@6eD&}q#rI20v9Fms`A=ug!Jr-Cu?4D#WnsW3 z=z<75+7WTtrGjIk;M#vX4qKDp+KU;oK%&f>gs?>MeS67fyV-8Gw3|z23dZ)S{ z)STJ)7@yi#CggpcP6EoOg?{uw_2tJxk1E4sz)j8sZ0zZ2$b~Y@UF|#Br*8{sP&6&y5T%!)Xp3>C-$=*1vJ^wXdQ8PwOF7>tYWd=aE zF#U1a^j-dlVWg!e(l$xpyg%4%?8(MIU>TcWE$NX*C$GH1_v*ZY^MrYQz z?1q2N?&%cnX%7x!cDZ`tYT)J2$-MG73sME)#RR2rn?2aawC@plht9!2mVTIv0ds^cI}F@zw`pN# zM)f^khOYf&p~!CnkwYgxIotkzg6gkjIFY6uH<=6bl+d@tIP3E!%C@A-Eb?tdB|P6Y zYiO%t&~qrjLJlf^zXVQ&D(g1qXV?$WFJ7Z24=5_sGFqLg$)gI;wzD#*4g)+Jc4j`h zbGlUAsPs@w5TvTA-I zY#O=dDp}ma^tr{-cc}#kBhMn&R4hpT9RMkpt7IMaaqMxp@bu>rJBuO&9rkMoi-&J$ z%D7)m7!o;O)2uo^-!6%AnK-#;H1HHV#+^|T!1@*}oR2?=)Qf%bYwws{Ru=_T;( zzH6`tl_9Oktn<4OyZZC>;-8JRWY_lcYJHY9rEh1ikag6+n)~(})A(2Xbf;`3qh~fM zWM<3Dj|s{VIO5)I_e1p-&+IsU9?d73`*{id3ualDp_co*D@*7n{K&QfD_MRLMl468 zYS!^ZzJ3?7sh47I@XMlCRA7WScU1D!)oU-U&WHcddLzK{0;5D?`!)G`=9`rJd%z1Q zN_+=BWVP7^I&N)#$~CYap1F0&*CY^gf|gh32C4*`fLDYvY-je-$8dQMg1YzS&9ScK zsJ=OshJ9?*&LtJH7A|~_X49IRdk^j6rn`M;;!U^Fk#uj||M~b+lt1B{<_Ku{LWUzi ziJAIAKCVn}8uP9*8*O{x2qEOiEelyGQ{wywKI0dqu-wDic&O*>#zuzY=A&{b=cZ8< zx?mi+A7s?9*bS{eQ~$8JV%^^V$q^WLI?fwfBvP5|x!9pw+$wy~c}T+bvM}U63z!0zm{F{s||Z}p6d!wdGst->uZZx)`?r*aLG-gRY*1Esx0rrjf@P)?&c z1(fvv!9MRF?D-45Ai~F-Z6!dfOa)kjq}ZO|uNsV(*#3lN2ClPJLkKe-3W3?W=@z=+f%om}OdQ}74=mSG1XMYQTiYdm1hrTr%DO==8cmZfpxf>7MT_M^R0|v z34zcrKwCDtzJJBIK{I>$9`r&@l(CDNG+>xpnp$zZp~vEpE}tOYbov1zs5)6)eDh-h z+{o&nfZy`zOyM)xhkKZVU#|O1ncu&+un9~<>=6`#DT(Gzf4+{FNJD>0jn>t-&^Hmu zW}>`s#3jI+Sru^t6VFB_>^QjTeAt{5_%qu97-UX<4-*)1%SsK3Huv+~2^8e2QNPupilU4lI4rDTL zx77DPzRoHV*%v6-S<1M-Nbsf(;f4g9xq)$Fs&TiGNIgZL>hjwR=)PzHso+?DE0^cP zM84MhKmDvW#xy1MUL1>5d-_Lq-!MdoQomn)Qy?3x+r6FO{u_K@d!PxJZtTDU-;IvI zz-HJ{?c3< zB0as4fxnkAwAhkoA}iOEzB~Y>E5sk*L2>^m-U*qDAlwh429){k7jWsGlV8IB+gj^l z{I74#P;m>s)Sjy_V)8|O#Dpp{NTpsiJ8fllE7TA*Vxy1gQ+`yeTE!o~Cu^;5_vYmV zCl?v1-j^S08GFvMzN7zHZYEVa-f>_Vu)s)A%7vp|-r&27>2jK_pp>-^uc>mHR_SLS z{#IvxJgJ6ycZ;>{2-_dxqad_%F8i9hW3epre~8KVNNGi0T39-cqJF2;ycU@z0W9=PDy18bA5S`P_R2 zz&#Lk(>aaYL+`?1g#Hy=-cs+YMqD~Ubo*#RfK~(;sJt^w!!ZE)+<_H+JSl0IvH*eN z;ge?iTNaNPUtvCtU(@`!TXIbU&XD6rK1qG=Vkly2yshF4i{bjNlU^UMQp#_SuqLz8 zVJk>5t}ZMbdS@jA(a4rGeEhjQyz<^rg9|H@MZrg+%>XM$^Rm4U8AR5Oxff_?ulNb7 zp&qSzdDo-} z(-RpJZ$Thw$|y9nsfA>@qIJ0mf?sd20R?~QFyN|&HD@hVJw8G6ZP1b2oZPeS=6uH~ zkCyO&@2s|0`)(1Uzk6=TeW!t3Ouj;zlY@B`5XfK%#q8C!2CGV7gg9qR-Cgg_Nz$@HZ59(1ak?-$XNT8vELaHMEnAkvuxjW1_F%eehnoujL}&uh-yG za9|Aw5mG7qlP6o9aNgCg0HNFiexExLI60mUyLY=D?)Vk;2Ad?A>oUrb z`n3W4 z=sjwb(R+{H6D5+2k`P4iGmPFNq9z!|=-nWC=YPFF-}`qzaxD+6S##OvKKHR-$KK$* zH;1r+=6|j@ZnQdr^RD+#z~)R>t;z#s2CjKqmWOnf#BZrEQq9f&1(P2+#`lxZH$F^1 zvQB}uCrsVVAqHT#o0IR4{&K#OeDouzml)QDb3=@-hAgz{`jvYZ3buT*C}N~5rsg4%YQX5(69RPf4Hi% zG8O_Xt*UJLGyG=@mi!zx=%TeyIGO&oipEBcS>`Qy+@hPgRE{uzf6w%s(~}lWzP)47 zA$2yZwEk$S0cIgW2ZU4K0PoG*u6V zJYUWxZ-bhD#$m1vx^^3Vv}PHzB=6ilLudYnssmxVH=ej4NIO$V9qvu)cv$1{MV*?Q zIId@6eYE=UQZ=^kuKC0o4;Yko`G6O<4s0}R?dJCQFeRcfx#3ry|e+8;XBneNZwDi9Bv$%+4eP(`=VCV4VmmmIym-) z3NwZp!X@GYsn%V`Cc>en44qDptzyBM)EoxD8mfqsOIKZ`O7qTgn&_8gS|Vn{5$iW6?i!Y-3FOzDPvPm-5rIS*j(ZdwiS`Yvt53 ztQ?Qa<8}i8JXtM3z2N)MTT8paz8XvQa=`tmg8cVbILW3h+7QsF#A8qRx4OS^Q2aZ; zJN7ou6sWi>bZ6Urm=W&y2ZI^@`+--eDu1K7TD~8ixE`4Rg|O_eT@9$_2E89UGCPLiKFXWs?*EZ>_(L9L#Dxaw2_GKFXHk8B#CC+!0_tN42+b zz!21`d3BsgM3|Z|EDtg>PCyB%K4F*9HwFDKypB@*~YV@#RO0UJo6Dl;-u{`Tc{AvT8tTn7`{kw5XR1 zOG=pj923}yD<>Rw&d&e+AM+3n56P%X!)w5JNAyFB^a&dK|Hk;6=>ci$_~SUo+ZFn$ z#JReCdU`t=sk~d6Nf(?d=E?xa=I3dKIc}d$<=0rv+W50Lk3by>P*j6qYsF95y% z5J=aP1@8e$l?xW}C#l;8z{?(!u@xX)6?d5{|3lChtQ@Y$gpQCvWWTqWJoyziKYS1f z9`&bs4m8$a#Xobwa&jR(Z2D9J)&B#|7^J-o@m$Z<9YDX3yn zqa@e3Bt^B(2Vq3GQ&V9J*h9mGRpo-JcUMHA-?i zQew}8@k{_YKvOb1Ehjn8Is2l!a<+ z2Xp}KSSs}LF)^1#LptMCHvl^9!|v6bNm;OoVQ>2niZOoy+s%hly4if`NJEBg^CU|L zji%p666kA5Ui|%Jo1Mn*ll@KJ4HI`tM9cl-&Z?WtShA;cDfjEa4+8+Q^Rdd#FVUf9 z0N{N3VxxQK4|TNnT3M%%hr?*E$Ekzz%;qJ1Bx+HP2-(v3rNlhvsfClO6fS_&8R0lH zJgqbY_P%#YCMs~=xAc1<1qCdrpzhDAQW-#hu={iG@GjYgz9JS@{-J2m)Y`b@4G_n< zps6ikybGJ}^2r{YfZt@azbBS&TJC`Sgbj>G{u0@;0~APiJI^_;PB`Yhl4$Yh28Ll}@?I{pzE6xeKOF zndGqad{$iid@=y3mf+k7;ge}l!T<84KLF2~7POJCR^dJNHfFwTtc7}l@561$VheRO zSJd9?ugX<|OZj5s_b_#r&tf(lKJYNi7^?W8Hl<@+1#B9)7Gi*@z<^cEO#i=N7c13$ zt1rPnM~zddxim(lGO8}zGC5SI%qIwGDUCV}U1Kd1?JVcR`dO4Vc%ZiIKeP`9{wKPR zb$3DQa^x*P3NEZBdU&j+Y%PMQ$Q-{9FSyAYPpg^{o53Py&XCgc8|%#jLx*YFQzuWs z15Bo#m%ddS58isK%!asp-o5b?N?L+}+6U8M*sEOAgBXZn-j8L8nf#W9Wt0KZzQf%( zWTECGpxuQ_iT@;6V872;8kql|QGApSe@vKpQSd*vXh3^#<1$~?ZIcVlBK7Cva(0N1 z*yJ=KrY(4%3`rhG*6|iolJL<8P}v*+dx>;g8$5YZB&KIJQwRS%3^@Yw*qIlaG&-X3MPSkLiY+K{4WPsb2+>`SNtXl>Uzn z=Z`Yf7-Q<5Yz8XhcXc@2ZJWuY7Ii5%wZytCuEQbEyUY!QH;96|59(8`8z&lI3K{V4 zFW$;%0sP*}QwO9SP=bx2TMmk!(Sr4Hbnu@5sM=Y&U=DdstqI`NAT5Y57fbT&l@RHL zRuR4h6tkdi(6TiOjQ()SZt37AB?okqQzMN8%qxAlC6Uzl+4lCmEOted-bL# ztYt19M^-Ac_I6t!)5@8e^i$be0u}`?lf_>D@HiN?J-v zHUjgY;+KCG_J!`fkZ72dNG?dJDPJ1C?c3-cUvakDX52XW6^+#y#GB*{#EN-J7^Y;KUWz# zxs6QGBb>d9bvJK*cIN_yYY#q;+`TcvaRZMMTkdVS*``G)U_z{Wx!b>}%)DljunbIK zUZlaz%-xTZU;^QcoArO<4vJnn`u9?=m5Ii(mt< zy@-25wKR2tqygiiNVM#_v@(tXoVL&Np4`!!hIbLem&YZY9!5vZa$zmMaa z|0;cZR}LrY`O_E3%*e<>Rs?J`9aje*Kpz|Ts%)B zc@^SK+=}VgYKs8{DhYSq)qfIeQ)tg#uSThsxD$=8zM(81A%dpS`N!h{Sv{>kTevYjp~M7%tBy5w^)<@%K7>OYvzRtk+411cIkLm z{8kh3;ua8S3timpQzsyni+Zq0+iFcf@Q0vK(!%r0RHc!h`E6}%+zbtAI*tGMktfQF zKPxMr`~r(4W-ot2Up?g@*W(HG9MGB1<@IQ`P|Y;!Dm83rw4cXpD=V3RJ1Fr+Ei+vg z*FvH(3x2n5(VmC$0`DbD1v=q0N@hYv8krlouF!j8fmgi(}Umq`>wkZ`93wO!JPnR}^MgU!j?KDUdgy%pIrgW{RE4$<;l8HA=7A52b4ZraYz9Tw zA}zQrk~!>9k1i%-XR6b5DqpP%$b*4BOMatFcGib!h=5Lb9n>fA z{^ZX*dvIum^zgTdsr);OqTcK|9vs1iZ`JP3IvPg195zQEYj{%fT}=G+y`@U+jI$-< zpXW_FW6!iL$F0`G85FaDQ>;`0ugKSqB{xjYcbm=}(f|85tO+X6-o=2KBfY$wci-c* zan-Zbd5TreH17s8d?SW;xRB1se`HoQiHI5dHk)l6&a*%9K2iCFM*TCaYs&T@o_G-} z8+F@8xofm%-=oakti*3BS+PX}Iwm;UyneK06~;1QL;<+5-`|LD)V?7$bnP;IW5ujy z=lPvG?6Ty6`|GZ`b^4sPjK{W)rRqo%U zhnxUc$8q`jI??12L3<$457quOOxNTQC8#fVHfr4tqkM+iUmwurvFn5?DFf@0~^YeJ#TYj89 zWJV4wPptw&yIqAwI4|jMPF*qer^XN5MtS|>ZH|SK;w-|nL+TT1u5{~^8*8GWq+iY2 zh+4SLSqjJES5o;nIyf$+9=H|`IdF&(wGdWLDdo;sU(Ypq+%iA$fQ@K{E9ChdX>{8L zQ;QDMSi^i!iHD4ky}sdmB}CQA`pd7Y^Pp|GDo}>Q_FOs629DAtTnZJo|0-g{#coty zkYaxbot1W-=X{Z)5wet`RtTBs9Ns4%(6k-$%Xn{yLYU<=?&{1gMt(#moC&i2LiF4O zE5tU)>OOS!_nKqu2K#?A+mEi+<}G4WA5XP%-$*6bqcFuZD0lpq`Iu5)+SHHcCb|qE zBYxo!Msl8OXlG^$6Wzuq*mT4$PPV)&YA4#%7FZUwAwmxf!iIcv z1v02!QIK8cyP4N%$>Ixk+39~J2qy^!Qi0h9s;DNAU~rvj=RZzdneLfCS(GJZ8_iz% zw($u4)tZ~zbLpy08uz&#N0wKITxISI%`O>aXrkWvsT|O6^;DC^s!psQa`yf#UMtJ# zcpq7#Bil^@Y=dv|2)l*np2j_x=k`_Lo(DYRX!4J9$V{uc zM{G7j3#3XM6HUy!TR3`4xSB3D?mBlCf5{`%_ ze?Fm5GE{_C24qV*I+R%VR@hQO>}GAuzNroNcSw5?R>0BS1WO7lA$Mp{orG-d$22-* zA9%%imZaJ~7DDXC(Wz^U>I=wGO$D|E#>`Z z{$s-uT4T>rAcL&Ddg^gRI9_={NN<(nGvKV_er@UA#AQ0BoOA}pj+;h4d8g$Xz9p6TgVZa1RUW5WMfW1)Jx|+1<8C0LE!s?fc8`a$C- zKaaI6i_^EYjiY0b4OzGpferVA-3zz+`pjyFMx;HX{M$|Kmt7Yj242*1#%Of zEss7i@wg+kjf%Pj3<8#qj}BU6NvyTPnG8N*!24b|ShXR^=+`;i1_2w`du9C0KSct!|BA7|R>p^SK+niI z;@;q(ks*(5s#$-X2>ek$FqD!cpjg|*jYz+V_gZP+MWo|5UFdR-gf-cl6p1TSh;QPi z;qpZc^v>ANUF#EFaTbKs_ejR|)VBTZBhK#(@T4g;?iprKPQld8dOpac0x_Ldr z;dmV6qMoNhx_ab_J*tEF0$)!H8NGK0WX8N&JB}s?K)3lF=x=vvxYmyscE?6KNGe1; zPbUe5brciQ(}2fOd|_fxA9!yF&f=pzGbN&@kx3}iu**v2SidAgs@8l*w)>}(`*h$> z4XyFL{%$xj6~;mwxwI^KRnL{IoN7K#%-sxwY~9aOyfHdxh1$xWUsKig{CBqm{&-6* zTGEtDn$+V!B{iYGy74!<9iujM0J=%Jw})iOVpPw}*7X8`JMt6ije0_5`g&*1R_w={ zZM^gI`vVSClYy7leLs2mC4#?KC-p?9nuUNTkivJp(}L*?@+H15DxGut_cxm7Fy2WW z@$c*oMZJ``Mr~ws*q9)ib5^b2glAlH)vGqle{mBI+Gs_7b%nx{@|$r!|I@Q0%DW4f z+)n~>lQF)(+rz?*XUX$#W*7f2Qa+5a+#RqS4ZaLZZ)|M*D+1eI%3kQ>F`j00@J$MO z6KLUWYKd?$DA)ZXFy}V+wHQ3e%<-A_)MBy%qcfz~<(C?pisl$z>T%2YJcvUk8NCkuVr=%sWb^KW-~EqX&=gnP-h{WMys|+cS(v<&QBKUi9>(H7`f?>9jvA9 zeSth8-w_(2W#LsR=zN>$vo3p@BXNpnk6T3_h%2DvHc7Y!Wr)iRRG^giTbOY&c{ zFziM)B9hdx=}deE#tlAGj46F;7U-WGJF@f$w*#fGu61Nv1K+CZ(^WkyQQ!F{htmpH zt+DS&oqtv#v<9k-;&bb}B(KJE9GY^0aneeIVRP3+$i~F>FmCjFzBPHw?P?J(xbDbnM=YmUyzb$ye*mGv^# zzcf!Vp~ig)b|dhi_>uYk-!y0#BZtPL)5>W5f9fDKGCG@~2gaz1P(V%bl&>l~6o-48 z5q(>2XPR8at|OCDeIwW=Nd{7x+&$;)>kFm0f_nCaS;8F}J?Jap$+{s_3ykW6QBC@z za|VxhF%T4)>8>B>;QDEIyQ0#SGO!44$I}fO@%b&S4X|@LwCSR6taP4MgNbjZbGW*< zTFCN~D(c3}ys>*vJ4BtzSap!uXU7jqU?7?V9WJngb3By7gLip0ev#@oTv_PO)9^Md zrO}D4+TzBOHfH|oGfyAs`dBD#d^)%^Qz1&Xl~E@gZu|OhWcJl79;P1dc_(RviX%5n zF5g!nTYP!Jv{K@WytAwjLe_6aT{N-&z=cDjd;d|BM;7B-lQZSFTx96QZ|MgDWazY( zp{XGzQuKLGja7czO5l@3$x|<`?lV9CKgEzq&7j842=_Vy{znlrNCJkqh_Ep+nq>z% z4E*1S*7Cl{=kt1;sj`Y*0Djh{l8o?ug8xPkzI}*$g%8=6ma+`*Jc&pTfd}P9LA+E^0<{C9 z&4FQ+hm<(rZnx_jNCNE~kGai&$JFa|s|uQc3D|0GOLRoi7u6{+oql?S`=R0aZH2p+ zRL+@0wi~lyx>Yre@n2_)rCmRfK3bo0w#@sVrk%0CENv7`R_g%xqCmC}z$N5u+)H(X zwKTtHuY5{xMQFEJ(fE-#p(RQt&r_iXxnx(T(n13pZJK$n)BU4|ftv4Vo}F&dooYw1 zi2Y^kiSJ$82Zd)}fMX0Ov86*VNje7zaEg#%;GTDkpOO#lC=K4xIN}$af3r6eXnB(z zKCsboBAsUzkXHhgdnO56BfP`PVl8Gh78Xv#-VlE&PBSa(rSKa*e)N^yj;1(ZdD-20;U-DRH$C;^mcJtg&^w&VL(HKlBBATbiq$7N!cOE(Wz( zF6dqTE8!V7Npk7ql~!u30slDr^6h@7`ad!0N;}2&nWS~`(oDZNUu#%E^V4Vy(eyZl zAO7&$0<%Y}Z&_XM+M66h>$zfE2A$TlD+|p?Gk-7Y>^@vcbdMHk6I=4X#PN52yxGM) zMFEe48a!HS77jW$G}f1lsDs{$oU%xD#w}F)grPX_O)J|u93QcD+IcBPD(u|yG1Cr)dE}=k5H%v7Z^hD}@8^Jwts%6Pa(P^T(2(xy9^!B?j2qn+4`b=cm0|2b zuYyv)mP4D}9{q%3f21tB75M;1K;n8u!RlVkzTvVH_6OXPvUk4J($fWYZqtTZ{KUv0 zt2IhXQV~Ah%k3A@@>z?qylT~&@iTJ++6jcq^tWE8n1H>jtR@?AzjAP`+cI^>Gu-@` z8wb6LPX}TC9&}rO5XA?*rFw07`Q{&mRsgftQGWc&LX3q=f^w>*yHSRu0WVHlP@eC* zxfB@>Vq?0e@tk3}4GM%3G@(G&PMB{ zokAPRq)9H<0`-vvhaQ%TyH zrg_d8mkDgA%`9hL$f#+vGg zNW@v${oxrr`$$l4*bw)jB_U4r6=#ROJWJHf1(}B zmKFO5dgBy{NI^7Bgk)QIn_RlkzeI9L`(dS)OO?s2alDvvT>qw~sh33R%4t1Xu`Jh;S;h8PrgubJxOquNOm3yrRw> zgu0=NF!@cx*Q%1ZY@*uYj%;%}?sB_pmlUU$@T;};LK#G^MI+=?pC_e%5n+moawk(N zPF;^kr)wP~K~DC9#hgZ5YjV(_zOw_bmREYw65_$aiMafejEYr(vt&jC{bYr!g3z|G z+!VfC_f3}(&dkb8&hbiw=aFdqUlQCm!5A}9pXeHYyj-LK2G1UIeGjrtgl^ebX=7S6 z7d8BGv#or3YYZqmau=A%k6%7|kM6zM`~2wlP|8(URT)iQPwp2YOjfzTQ1q^AWL?$- z?Hm6?zst9Mvz_fDO zVrpQW!luImV2QGr1JuRt+G#X7<6m2AK5XClw|CAqtOW3^i9ZL|>@_JkZmU01SW`p2 zf80mW_wjKzGYI)}ALM2Aev*GD>-!iO5z)kyF)&)HKkBjTK3{Ox7?Ub2Zn7ftC6y8{ zlaYj39XF(&98k4tcFfG-5HfhtLo8W#wV(N|=es)p;8p~_+4=co?PN~TM{!)61){KD z;O<+g=O@=2!im)b)rdSReQua@Fe&fg53nYc6GfB##^tx>w69fIn^yzuzcQUtaDFDb z0Q=GOZmLIDn7*hSLAK&1HL$UO# z_PlrI!Ju;_22!V?X^v4bN*`#|Tvz+dl9InNOSZV8z#(lRAiSsDzq4(&>%~25EWpj5wwInU&5i5lY!?T>LO`3N7=mQwC&xRv#nA^|dtR{Wc zv6#*%oyGrrZ{;bfZSwSXAZt!kNDsXD5Vm+Kl)}32=agg%IlRiE1S&&l+^*If?yL%q zW5yz!AprBF$7n7j2{_BjUc(@GGlXjuS|{UYYXhXK5?U<7{wGP{U5~>j-6|}%nKPV4z@ls=dabTC4(hN~Q-g}!Q{i&VhvK#IzFKg=vV%o6t zT6s=3ZsJO^*I-3PmFam%uXVMH^pt$wpGLc8{N3!m|E_D9eIFNZjr+6~|UCEnftdgX?S@|S{ z1+v%AE%QU{VPR8pO}598Jg9Hib{=!B5Y%p6b2gxD*nR-zd!5p8RwZ!MHYgI}O$t&U zRNb7CwISIN1NH431bwNeW=95gaOC+7{Gw1Fo~QebykJw-)(y5npM-dSLI(#swI5mz zNUb6isg%CFtOT9igJ#ZsHFYX5lQ;XgHFYv((M(r_h4olibep^YQl;;s*tnyK2#md@8ic{;jl_o`OIp>!@8fzTS{&jYFo!3OB86G{dk4eXK z*V91A&9y%I>(Xdoj5zT_?bXA`(5CW!(}s|j1GZ<&F{AySKP`b-EB~N)W`zM9bJbl^ zcqW6G-&)~JSRcrt(#gw3 z9|LvSLw%UFbu?blSUX(u*>qrt7FxE7wI}DNIudIZv>EU=kF=*ksX{VjJnsLCv#}+w zVMs;`u|l(TS13=KdS&Gk{2eGUaL`@$#;X^i@gkOlx;$+3_MBDu&njj%Nr~MGV^Q3N z?#7$OoANZ!{l^NN?;el*|GF7Q|LbOO${@ultl2 zNmf=%V;{PFfD$?wNyJs8lbmz%ed(zT_JCJ8OT>m`@Tq?=7`CxQ{U(Mb>dtvq&e#tx z0k`E?pdDdTUm?x!LY7~V=hzGWOuDiAIyb_tVC|=(dFx5!7Mbb+JSnWL{lHp>aOHYg#H*uo+^?Zq_xIe~i; zb_+rVpxXPv{J9?}!UR_>42x8ZWuo9uj{I-<1qDU@yKR;fD{3ww89{A2cN^2jLxG^l zLPlA?oW`7iyrHxY!>JQ4#M>t_pK~<&kE2ZM9%W`Fe$b1NFdHMTi1D?K^JWffB7c<3 zl%9zFPCNZUTV;l-=pj&ee$b%dN*mTM$xFC8T&ZwY{yO>P+`&BwUjmQr5l+ma?`nua z9j(xGTFtcQ5&hm@9OPu@&`BKGe|>uvd=%(c-2?llJ`+=tc*3$peSZ$ZD4P8UDNgAj zrz*v?!zSdpH8AvqGjWqX-Pi1d`WHmOq{D+>rRl6w66zlUPpbsoBhly)U?xVYTjBS9 z1&Qvl>NGLgtEa<8rtYgP7Z{>oY7T#09(kZTMRb}hn5&|afO%J~gSMbP;6WIW41FH& zZ9Oc^G*9cQfGN_Q4&<^WMSVgsA?`1+Mki6_WcMXC# z*ggmPjz$P6SJ}yWOhSVxzOJQ>D^~aT?B@}SGr%#wm-D$T)f3aKM}og2yxXQcT(Gkl$}IN0*UyE;b7Ex zu~TFNggJy=xe|8Anw4EFoEY9*c#Hcdp}qGXMX7KQEg z;~yF63GTTukG>KfBP`X;1qwTu=c@n3B+RmP;dem0MU_JiOi8;p-nZT|zE?(j0GS#s z7K7q0vHmZ40p;vpNSAAw1|&D9?!(8J;R;3inw>x+%bGtd8vIc|ox)nLth_d49) z^BhFzO7@mXIzgaM=!qt~816m^p>;BHX?DZ;pYGN2K6n;90?;12auEF23N7r1Mj`Z2=S8pzxPhHnaP(ncM>jM zat|t2WCo~cRy_4DedVU6Md^B)467C58$;sFV!rq{a2!@&$)s znu_da*TMeZ=mB2%mE;54X-0wAI?apJemAqPzsLoV0e83fZ)PsFe1@nUqF{M~>hYc3?{=}9FFR_c54@tjF-*JTR>D@Q6KYh? zOgL4G8WcV1atEV5E60OyBVur)cMC`UJ{1GxpKfl+S6&oCT*8S7NA|^Z_+8cu1gf+- z>Z3xt8~S`)#^;x^#~tvorQmzI#kfBwgcDid0*Z<5r#6oryMtn1IE^@i@<}GU#R4+u zk<`+=Q{y>#H5Ng(8lTdy4u(He35#wP+P>c^GL?#g8t8hlSVBo`M%}#4tNnb39tI0m zFtogLCu?l-K<@z3)WQu>@W&LsBc|o|)!xC?X@SxV=7oqzn1%NPkCo~1%G&@~`)7NH zON4MD?bAPT(6)sW*_axWX;~GAF!h*eF&IK zXWpP3e$oe>@iTI}=ZXoT(uG<-cKtky#J~e#*2#U586@P|YY?g6VAK4#588-}l9b@7DfQ zd;lcuKVRzS@a*}D^3yO4&|99&x#^P-y1)DFd`vuZR+<}jU{0VG2 z5ZVl*C9for{zdEn)qH@rXlKoVzhh#}@()Dx%ZX3oI*N0CgY)zGpZfT6*cmUc;vHo& zZgAwzB3S!%NAFI4FGG%+i&WF>QlH z_^UHp$v$cX!5XH=sF55pb9~66RBcc2ri~Ey8k~P?2~IiZESW26F$_r<$n0&_D1mJpg5S6`Il3 zKDe+gbac|fmw@+UiXC=n8Ce<9%JZZ`C zfBXDdhX9C&-jiuYeZFX#M%mnx`|hl&?i`ZQ*Y^yX@6mL761Z&@3XAMgmSjv>8cI7@ zJ#+*ClEx8j72tn^+?8v5>Ucc&kD1TF>94rquY&vi>L2>X8}g1`k^kgjz&#CWyL~0k zKQ12|z@7TkunwFzRr!+xK8|P2hAOio5Sosv0R#8lS~dxw2031ajbD@Oy;ek0_foZ7 zJk7)|+^aR~x1qABe)21YhMNJ~BQtqaz9~e$r2Wpl>IwEMjo@c$r5^B=O7;%LqzaAy zwq*C-gWQIw*AT)-ez_%c_>83lAC?D?T=^Cg&4W_LVh|H`ihF;LoJR1vPyY>P35=PP zTlC~!;@F(&3dkkM8azXVI_bQ`G2~*=K$O**@t>y#y$Bt#o@Z{=q$)IiV6!bc*$oud zBGK~bW%XopB(2bIR#$;4liB7?VGRP74mZeWh9X&8I+UH@7BPii2wIPeZ7W3zXqby&IYw1|foO*)ab{a3$|c+vhv56wn0n z0><4uH*UayYsNvVJ5d-EMu*w%;*Rwd7h8k@hf9oeS9}TPdR{6WymdNNd2!xYlReA& zenVGJSS*yXFrbhFPuiqjGEs@(pVw8-XsMW3Xb{z^ibmY7-Zliz+VmKBHLsTyr zw;lqmRx0F@k?ir3*Na|H;VCmr1G+yS5jCr!^+k+@Im)rycCF3l)t*wEL-AWYzD`Qz z6q9hAss4zYP7pvPv~Fz}iKQoudX$Bx*0sdX8FcH)kNk!dbq&mAo_MNpvpjTzWZ5{`jp+dM)gmq5Ds=k*W zV*L47g5$HDgP%p**m%it*(N>1ixu3kxOBs%+pK(hEMsb}N&}DxpLG7dAJ%Gy`P!*k zx7=bGiQTKccJ%&HVOl5K{jzS2(xL~H78~eHXElyeLd}4=khEpz5~K?c!ZL5HE$XJL zt%AAD>!6lNHhdHVRQ^d%_W&S>x5(1R1)oE#>4F*fx$wJpEQ@5*upuQyO4Jx3S(5ep z$uE~pLowvFQn^Ga%{4p#Z5hoJLgV_rHN@j+r%7KsTK?yGvqE%REEG_UZ=6PCAP>tn zfF3$}(~u&A_$DG&*Sv4|j=*$RvOq3Px3zCPPt~s8#KB>HF36P=CtJ3W9HoRBGW*IO z;U3fpA?lH|{laEIJh}qI8>Z_4lM9E9C}$R)&)fTy(}#7eaMR&5K(@ppVUs2aPhA$f zeP8L7=v|6;=k;*6r_?yE%vQkiFGx(??qf_fGOzaEUb6$qmuo=|6g87X8%F5A&8l8Y zeQ$clSF%bR70}VOU4%aHR6N5nLlY%*u3_W>znH9#n{BZR;SmGuhYXJ$m%?oek*1qcTeK)j$M7>CQ_&Q`o@h3ZaK0_ zMH@s10`(5F*zV2PM9VLDw(LSpeI2Zp&5@JZ!6l&8I1}hCEyd}ihgLg4waGS4yKj^} zwp>0?Y@~aDsnfQ8mgzaI_3?gh-uk6CLMd=#eWm6TT9#x^&C?7^4ZDzie=`I zHV|ltm~R=+bsi7ncAcNDOii6BoM-O_n@lh&Tt7e;G5EB7H#488WKy1ai3|*D4$2$I zTuq0H6ti2wKCfqj2MOJL9iQUBUj|E8E%dYlz1@9cSjXP79%dI7(v|xr&E1P*2`OK| zes}X*Tqqzz;K*#&K=bt6VfwO>+UBV3UPEq+Dmv%YVd~Cz$Vm-vCEJzLspCBq3qd?B zpDKwRgI-@MYKgrte;)WnKR-3&3UN&SB!Gg}UVZ(oIA ziYbNqMOv<8PH@cUJKKaJK8Ax7wCzBu?W%>}g4EyySesxnEP~K0hyALat@jFaW`FNN z7Pd%_UJa$~<063TB4(2#@){!V)Yy4qEO6Za=fK^Os#AUBr_-elrQbg)tDRV1w?JT66qSO>lF`qn{wa{T*&Va4@OH^;h$kj z^-cSac+4P%4kAY z;jq1jNP}nIK^{jhp$RNB@VFXzamV|G0n)L6j{NzfX>Me_FPZLX_p}+t9=R4Rj5uSX zGlky1&6JC%aeVqmEi=1&UpNU`+0d(wxK5)|mm<6gd=I`mv+Cq-SH4>?Xg&;xJL+9sZf10yZte`}pN-iIdIq~Ui^v%QQ&cRJ zeZHeKS74*$xaK!k(P+#66e5c07f66iciOItzX-nlbM%|ms zjl3d*GOXb}de)`F|{c4)2d@3~e>c9Qrt0 zk2{$5zk47S>-vIMnJdoiD63qgrtL5w%GED3-<_G%#b|%!d1HqyyBFmIl$ozmqRg>4 zTmU-&OM8vxy|_1d)RCYYBH5yCEr$J>7JXD1dT6oHNKXMlZ0Pz1`fYZ z#CtBs;zy7=c5Ld&+i+7E1A!V1O@h#jS&hXnbAt32iO_>s-8qp=`LFExRW!yE&H%IW zH9e%=REc99(;_OjrtM|s-Spjz-&qIy(T%Vk5TpTCBTlu%i%TllSTpay%Y5hX2JYRe zK4dA9*qRTD8ow@th*nFRzeS%`HwE6-ZwH>9bNX?Cs@Nxn4)SU~1IT_Q%~)s#Bra60 zirosJl1W&k0=Oy_VcU=N9@??UKl6=b8#wBj${)OpFME}Osf~JC@qaxd$E{2ez&kB5Sr)JOKn@b7xurns-aLKwp zdvAmUcCSd0ZThI^dnXe^=P;3Z{Gkj~fvTVM51vvZef(iDS^_Ee+>(>K`GW_diVe%0 zIcMzXY*UD@adJs(bkCXgAZvAX2cb+yRAJA}T19Rn>y7qDrp%gaZ z@$396YpKx@?$Q<2uo;^LA)Cim8s2#C!D2V|$;&&NQ!TFMp9i?xW74mTFZyAb9pcZA zviOuZZ_(0{lFZEcR29|L^{uTw3u$-5`{n<%J6z;EukX}H3I(aPt&IZX@%!*Ao>TXr zsY{K22a=#!lf}r^t@vIaXtUTP0k~0)j*6-KVGtl_h$McNS~e=LeEO@aA)7(DyfO|D z7hS9V;8{#Bi!kG&?e2LMiPMa_6T-W$ZmJ&r%$g8MUQY42dRV!RkgKV|NS|%*+c(+$ zg{$TICy^W0oybv3+etX$7ot!;zd4x=J&$gdnn*tyK=1{iXHWLzf4F1FeDpDxg|VQv z_LVr!f{v^1yplT!aD_!BDj+;Elvj#o{ciDX*m+0JA~@WqW^F&*hqT7iK8!d5uv9Wj zb2B6##L#e~AN(zzUW4Qy>9(Mzt@kj2l7hfn~m8b^SsL`TC9dcKNJ$+dr#;k-(dQG(Ek4`VjhkzSF2gZ zQfBIlf@D$4URuepIH&n6vLjZ31W|W|aO95Hbbv^c(}Dwo0Bt42Yi!uNhkNf_{;Ysc z{n6aNGqMH^O}}!ngG*$(R#PCa`lEfext9_6+av&ONK8F=#{fU^h5~@cVGi*^&gSh! zYL;8;wYhBD&gc7(>s&8V@Ye@Zrl3vQ#w=Ejt$2}E`+CPi_Nu)11?>~p6`Ez za}5(j$Km|)o3NsLc3U=7=T7%5jN@MEu1p!b{*po)pDX8II-rxSqS-zUZ&Un{DOJV( zVPPdYUCA^`avY%dC#M>WHlgrdVUP7JxeXJA-Th zg9=N-Nz!QV%yjqLT*y|2T=?bP&S4-T;P$v&7Q2s$KU68O*a1awpSk@x)u3?nvwd7W z_bgnVVGr#pl{Zh+A=`ApC6egAuyj-M>JW#@@eXN!+dE@Ku||$=|AT8jrRxPw>Kih< z6!22e5S9$Q=1RK?mM84J@>Gvm2)sHnlJwm3IueBNZZ8GL0lax_Z{U&o{CyHNlYh|C z?%H~)crP5+!cp3_l2=~TpVpTD67(mr*;M}3_5jHnkIkOW1ekc44&tf>a$w_j5)KgW zxT~Ydj(dRaF%5h`Slv@Fhgm6;x}f3{x5n=GPf}M&8#&(5)SJHhA(rvs$wl zs4~-fnLl1M`tJXu=`Ew8Y`^z!8UzGsq*ag(LApdrK)M^GyBRv9Qyf6LTWYAGTe_Q} zyN2%Ox$f`p|GZ(%V)5cy!@ACM@8kIFV=s*F8zyW$Rqw_^rw@AY*C%YG=WSt>>H1~7ST=MNbRhw=mecH(Rk*4SfJF&e{ zTg~YF{CaHPqoNm%hZgPN$;IP7lB@_-Tib#=g>WE4dlt@jqmGOpl=CzmTf1oE{RrAd zxZyFJvhfX@s-*1g;rC{5SK<(qnS*dCkj=YQPu$*IagJ#!7RCIZT;;cuAYiU4jDMgB zHdr-Puh)9PpeUE?YAYq(?4CjTDg!Y2ZBg;+3@{R!HLz}VV#HRrrnsh} znFeCm7PV$5tefgKNjFtzkp4$Mmh2M)@*~y7$G7M5BJ;gYrOX4#N!mca}fyG zEGDLd%17)357Hjf1$&AeoaN_r52j<82a-xrrF`QLgd5b_%?JgX%yzly-51*EZT;R< zT)fU}C?GCBPNUESgCtV?x&30>IaC+`fK#*jcn_GG5hdV_q%x~(&ZPc3zhOW4rjJPa z982s7YM|>H%j#a+ka_4>^0lV0%7A!UTMuDsaMxh6WFts2Zp+X5C^{lB>E1OI@HK<6B{DCDzM-3iGq!YadhNBWxNDG;j?n zA{^{#4yjyA>D|T1dR9CH_M;DZj&|n6HFZj(CP#t<6UFLtb!tKGxs7*p3ASI%-|!mJ zhvUu`6BD0}7_}!}c8$T8omZCIUl2~(bQ|F=6=~E`1J6*e_z!AhqJa=#ouOB5xqS}* zgjbE-mCG+>Pb&(CbNS%%9R5~gmb1rL3J6H0&Jn*HN+xLJCfA&2qET;+;r)&R9mtvv zjIEI3eZfvl@_VI(@gM*UqY1e$Jqk3IbuuvSEeV;R%{QP{yn~3MR4ZMJLhe*EJRNv1#W4$DzR})(0K*;!FqU1394S zASI2kDH#3kFl*#?(S4RYlYVvTJ#DgU3n>=~*0(UfSJKMk3IDR9C;C^kIaE1a++`MN z&K6Lcx8AIn@>Cd>Zk_%~trL4Vd~Gwyb9`EV$w$KW$Pp{BDkOciw)5}<9X|W~&adGE zHs06yPEV@4S^&5x zRS=BEEqi6wu=MPV`Oq`f-z^aa(|+#qiVUf2AMH&HxxEEl^xclWTzY7R9pxpfZEk1w z0hxOdpEFaQ9lD{u;p+2utzfTj8$nzhFi!>Mr9 zv^R>u$)8q|Ipi&ouuF;sVS&I7P%9+BsXxxW@J=j*d6t!BGb1hAeH!?c(g|5nk^H0DE3=d`;8?*FP7Jm0xw2sHT0t_)y94@Q>gXRjhCDOf z{(k<+@YuqG;_Ku^>Fpf@6tgsyDgj|}|B39e$^ANH3)`_vY;xt-us58SvXZ!vb<0l) zGxN&nEDpH9AnVV; zrW5Wvc+g+=<;du|*1hgFo6T@Tz+~863Yko>q1(C3Y~O z=Qe8=hDurn#TzC0f}+f?%htoEk?VkdgHOut)^>$s;~!PlJ+Ilu$$q z5(<7gYZ5zxc{LmfV6FPuW|5BHk0kHj2C*GFQt%^M#{5`Jq>c5&?FB(t z8Z%P%zqh>RZEwu5^jA6BO1mRSBx%WgeBrgYcv*bYs2P2$^+$ z1Yb8_V4?4)zsBsC+w~uFDE1?a}oA2p_vgm!GDm z?QO@&J_tzqkY}o-OPmZxFF@?>FbP2W(HMQEfOnNI@p3#A{gSoIv*^Y7>tUFX!RXCA z?uNCasH7EsflN#1T3hVt6zBKS_a9%67zbgKg94OO!OWw~+I`>AN)K=q`x;|Vgha6t1gk+{lDQf@2fkmqY z3PM?s7<5-qs>x%ee*HHNUS*HP^VM>~=KeBOq>Xj_dzP0rWXJNeHJQy~gVBeg!`1`G z6|+w$7%E=xO$8+8)?Aw zXXkKjAmoYIa$DgwYBo1lu%H{#vdXQwsDV9hmq9K7WCD0~f(W^QS^X^N${E;|ATfWV zRYH%fb97AU+vLU-S}hy9me!iaEy?xvvjtwBR!q)e2JN9i%Mxp_aB!NY*j8=%xHylbRXf(HMP*6|ILl~)NzUiNSV8_+?8n*yI6v)Wt4`|gXO zk^Q$Cfyg~UWjp%)Uw-9%GKy+202$trh3D7;W_^R@2ZrYNL{afnu+zu60rgUTvf~7t z%j_*5Et1Bfqj~FG-75$?GD9i9{9n{ShijTcZl(fTK84grAZ$a|kwVjJ_pVfT!yN-W zpv&~CdgguppW!MBN0vDw_u2H3M=CXmqp+{>JgOEoHZe|$F&6c4fA~P(- z(KdJvw~V3OgnAZ!b$l4SY!=<88FS>Wdt5=tAop|nhs^sZQw=Z;K8>SeN!g;v7OM6a zA`F%3m|=euB+vGAmvc4q=kpie%oH5GzvWu?+X6b}Aq;a)=Xrh&CZ*oV%W9W-D7ykCuHiu4*+=2rO0_bKJJ+OQ~Sv zYdi6`A@+{&ppE4?9%TngL3bZRd+l}~$!Y21=ZxYHWrF%o!C>?Wx%!{?q9I`P4-n?E zZIO0fUEzlS18Td&8C;+A8)OB8-24d0p~$ue6GISOtl5v)VyASkfS3C2x_G&E;$_<3 zfhJuD{U=8+`7K@q@4}i@2f`_-Bk8Tv_^b`7zs46mSmGts%_E^6a%g9<{??@pdv0X{ z#~-ZlrjXg%PqSc4!~a_zvHsuk2w_)i8y;P+h`>QP(`Ckmt_6ZosS zM$Us_B@$xR5pyM(VcFlv$AoEJ3%u#AaO6aYd*|XJ?wfzd(&&jT@MrtIf`0X8yvOCJ zHVwve*ELIn$iy3Ex|HHk&W#k|<@&yBM3+Q!mjMP>G3@~E@?Jr&h#_B^EfZNzZN?u= z5zF1`HcSIpGupGYI-22IKqf`B;6RM9k$oL*Ln{+Y1!h$H0fEkKoW=R(DE2RA7_d5~ z0sI&oZ=olHgI=+HbApuEzP@!A%GG^wO!#&!+~Qn;y2vh9A`6A?%k{b%DgKpl#Z>J6 z@7En)2%+8Hawd}S7*W?2ZDJMHmi zOw7gV?NvXiS_X7+m&19d3WL_KfXmUAy)(5}IAOgQD4XZT^LyYvtSHZo~h?` zaAGIdVuR}IOK>Qp8jp5~pJI?J4NuSQoSct~%4=Zkg-iiAEb&q+*#&PF!8$kA0{Xts z#&ya4qX1j^te8y9L5P5C(;i(QSXa#=Dc6|0Dg=TCx@vzw^f-$v0L5FF|J2K*VPOx@ zpiF-|F2^Y3LSUJjBotimW}ACypu6)NZdvyc(zQ=g>aoLwx&ev90@G71vLgLDcgTni;|&U}VJL70k7M>tEH2i_4{3#9d^V&PesZ!+GtKdF?A` z`i2-M#B|Nr_1S8A->xaSvmc?)i~JVp9@rt(Y;#IOK1NjFQ8=GJ@ryNvWvy|INDAousYKGi6{2?CP?z}{}TMA)NJAq zM?oYE{5E*zm<%U}CBWeChcff=KT~@J0@MSzL#$0-Wg%?m%DBFpDfCMhSllq2~0As!jLWbTZ5`lv;gZH8%W~I2+AoxQJQE4oecc zHQrye$N$)-@0xcY&VJ#h9W~(!=f(oL;wy3~i{qDTi`#rWVZx^aa;PS{OMpd*UY0Y& z#EfGt%*l3E+&ot*hJCiPTp#*ug%PTPWGAO>p;R=S81$L})4Av4@3W%0Xr2dF^XocQ1Y z)=X`+z}R#&kWcU|>bo{99{mB}=N9MPM$a;Ica5^Y0V5iSQscKn>^(-Zzri%77=2*Q z>zJW32KyHZ3|aid#eBXw+ZU#+L6}N>PjF1wClrr!D%~sj9HhMF{L2p5YU;#{f@ES+ zm}^(x1pK^aupr?*JW9Fj>A~8_pgf>cZ;%GWrAVrit79PD08o3;dB1$@((4&i#m$83yKzFB8yXZOIXvFE;DyW zoAIw~HgRf>`SI1qeKBxOuGqOhr8 z|CNdIwS)LK>SwZ$b$wuCj7m!c*A&{M$Ii!8K*#03RKXb;z4x!P{oFz@m?`{l=i3Y; z*%1(9n{H0B5XwK}sg*@N?V~2vNDi9A+NqT8=;R_w%ngE|;cX)Z7rYx>-mTmcW9r#` zGmCk=CA+2}|1h4T(Z>bcH)(qXfs|&~gt<#iyKj0IA1EWf0@jV$bQUSb*U!c^=`|NE2pxZt_*-v5YjJZ*Y&HBt!m8?o+mg2L}? z*%_LBSqn|(EI&dOcv3YpUT5sRO|V6sK!#@2o!Rl-Nll9$r?Z2L^B->YpB~$ms|6qW zkD7FG4mKpl(Y?gMiJa3NEo?0*Vf5cOk#ga5;# z%s#E`IvGUS=TrEjLu3j6=WnO z*Yh`<3YmQwZ#5)RSw4M>NPl~}y$2HIFdZ`x533rNu*UNGuOGhiC zPIQfKS$*bA5hWiPP8gDQGlT#a3M3UsE(jGaq!l$}L^^$mQFLkTd-Px1y7Rwr5_!5D zW0HKHWNMBzR)v5^&k=06#4dmVc6Ci)|~`3ZoX^CHznYn=wiUmHYK1pwD9pV{k1JD0RuH@L=HtO zJ}7*oZy&wAG)}lwBA}8IlNdT~ePLzlVeKtK9Y^`hBq_=ZzrBp;Ke8soS>N(4%2(zi zEL$v8DRVh~RI>FZ4?jQ6^gZ3%+taU9r(b<_op_I6wkVdM%21-rNM-Ef#fYQ{KDb~!L(vRTk` zjp?&Ye45&9QkIXn!{VvGCXkbc$g_=5zgm##Mz7zN`sD^h3*5KeuW1_G8LZmac(;Tw zSlmy~c%24{D`piqh#8NAO6!BPm-94<)!d4m!C4jSav_ zQR~NA2uMTHs-D-dbIY0vuMAGql=`TjPEP#pf8L(9Uda>iae-ZSu>=c;)_jJl+=W6@ zNxK-(5fL zQg+#Cl8;Ijv`loyh}6S=#Jw*gpJl%r@yYCM{BQ5k<=)<$|I^&vc~blL8rb&^+gu6i z5UNtbw`yRs%?&m_!CYE#>z{~pFha8>T)fd(rhxSLW?%jLupzeEa`feR+O z>mA#Op_$J;O0Lki0uO>bM{I7qCIRkrpP;k-z=|XOJ2iwr2@XH#gK9{uJs}OoI@7PxNvC1_s|53zJ2)i(nPQj zSD7*MhtEA(oKymGc5uO>r+%Fz`;jUetX%Lp zJgvNq?&4nXU-y-m>ld*8(d|$w7~7l(YIsjXkBQd(#p0`E98|k3J3|!xOPdP{KIFk<_%H}jeT@b=FS8-elnmpDxSII3Ea^LIe1oH zeE%?Lm+(FBBPVGHnt}+4Z64mps$Aj*!{$_}GT)X#$7~iT&SlpDRQ`}y>EpKAUhWjv z#wWlTGZBOKlJjRXQr$)GPBFY`3Lv&&t+AJlAHAb{SmPrYO6iBA{wKk@9yczl&W z7_Hd;P{NP~OcEu2#xr}Un96w6{0ZMl%r_1_31*Vyl-)qA4_th!HJR=Eh7ZYym?MC_ z^OjoiLxnvkH|g1uYV)N9!%c}b;^5mniVn@6LDCaqr4Ma3y02xX<4hk1KmQQ+^#2Wn zm`X%YDfD#O;t%poh?ggTO-pNBYjqN~%o|ipAzp|;FE_#zv7<0~i08mqM0@mreX}@i z&CnWrfae9xfw_Lm5#+*V^i%{w&=O3`1fq6Q9xy|ED%T_HKc^8HI~7Q41LY{1aQsaS zlJ3LOu`%7-^I=O*eHn$O_y%f@wwWdklYd-|_`$LUzbMDNy-I8-)@)|96&NB;zppHR zpg4U+2P*gGZ7oRhkYle}FlkjU?-d){a){}wxD!>+*iHabTz+3UboySDuvJuAvjn8} z)Gx~orH(lNG6T{L{dF?Tv`eqjvlu3%&%oQmDQ66X2Q#Ib_n{(3L>nxKby=}q%Zhx{ zVX{ylO0sXZUsiGm-_@2CQ@2c}CkJLt`1f|)HZgi%^3D`w&6UiS-&Jbm0e#uMe&z6J zJZIBt@G{=5yvl00EuE6bmbuG4j0#tou^ zP~u(WQ}vlRao8FU_SAub`Pr~7;m6t4S%l;KaA#Nhr2S6)DQLYR?lT}tpySP=rBd#o z>Gxzbjo#LZxm~{k+QPgz@d4v$34wkrZxBZ*O#5;&kZLLo!v^`ADx*lOvX;bv{9h7l zQj)NrK54KuirJr+QH(-0F$QGOg;+KSbVRA;cm8!0nI(BJD%shR(F!9%=uo?gP?SdL zrUF%W%3E=ER_E)(n!SS8$1Tvu-&X{Fd)vP)wMw@iA;Vu5@GZGtD--A2#<-5x7ud!m z&_P|C=RT`IrF5BQ{o(SnFGn1urKNnLHv-qxED!t^svNbSBcI5L6>+k*2XZW|WP9GZ zu^iy)oIH#kmzDQ?rF4KWl2b6fMl*v`gM<{VlhM^>w36i{`BlV?;90u#_v~fv5Cb&h zy75Dt8EsY!o5S6**GUm_>>)?fxM37uwdqA`O$9!DVBNzQqz5muxu5*2n2f!yNCVBN4wxetS)!nAHF}DPMl~LD(1W!>#rWtuW>{oB{sDP-#c$p-p_A-Gw zerod0As~tK3{AczI>OsDa!S+i-%v{UYpn9$EqUMmw-N}q2ux8EL1kUXEGaO9MZ>~r z{WDrnvNt1_sG}!cP;!Cm3H^rj%`nqIpzQB-@aK>jRAXHANDPb6bg=CeqGu|Y;_vA7 zu=$_dtTy~h`1bOWl@jq6EAC*6 z^Hk+MEQ2hUbDwfxq$W-5Z3gJvhpT@IzJ&hWV8)jCIsjUlI^r+%^kdA;ze!+dA7QC& zA}{8tIDWSltQOK^k+5a)w?=4J;Yy*3@@S^-b;Z>^1H%U*O5Hp&w=m|>WGVyg@xNBJ zNElVxlMi2E6{{?AYs=!#bKXrK0YBsNekX~NT(BpFOVO_^`^o-E?Dp%mSl0pvZ58CR zPz@2^56QTTDfUvn0Ci{PfO>7Fo-{mL;3HDa`e)@9YU76#3eWDJTR3jm zvU5z)Ep`N?))_Kk;Rq~@r^7gjNweeaE~I&DS^gL%h(a|~Vw_`TE^3tjoq67)!hc~; zIc1{$Iqh{0|hDdwRCxx(9E#{Fry8`%j+OJCpYqMr=p z*W3fRY>s|MuNMmY`pKpD9}h51iWH8Jpt|NbZlCsN%jk}iZ^SHV)az*FO=F=^J~GNUN8y7XTX>lk$pt3PmMBv-K01!cS8HRIxI9@ z$ciqnrMf;~25~R?%Pvj!X0us4LQ(s}`}>0B6XM!5p2U}u@Os;y=-7eldjGT-Xf#-( zbrAD3zSzv~F&Cf={@;qPFr8OGD7oVhmza!7syux_6>HubVPW1&{7mINU`-mzkNRk& z5lY9}f|-7gk8r7+N}FpXw?Bw<6A6c}EKUl&od!d7NQmKG8@>A^Czxix1U(hh*=Z6? z#kG=00dPv<71qfIM|pcIp0J?tChk_kP7Te3#)+a9zkHP~MvISHqh3aR)fKRoMf8Q< z6-SO^1w@I81wzJ5>_Yuxr(r|q^Y46ILfZ;w3Ry0kiKgZB$#sp;KK_+gOHlu*ZaZ%s znKtd#H-Rw1Q-V?KFrj$nu8ml8mwqnK&XjeC1!tvy7~yG=)H|o)kN4kd4QZNJNjTPr zl1_V~+Mno6jFm)%Nc3};-MpV4QKF)vsGHKxh-^kr^GA6yM z9QPGur4sG?uZdSZ*0^7MfUD^D!(IIKx_Bi?^^-yGielCqq*uzf`f*-2I z&L|s6nFY^>T^kIM$3<1#k%=PKG}20i9fI^$({b>j-L+1x9;_Gu6d=YNQpDX;QYs; z)s=g1p@vp6Kq2r&3+^j>?t35vw9HpgO3DO6^n_|CI~9#zt7ObLnrCiaMp1rV6fd@|O+a=Vt#auJpU*B2vv!dbv(F}l=HhNVM2L%W7ZS${$4yoaFN$|;x**OVi^BKP zc6`eNyYJ($ARN4ejgI2QwMjL;yV3;feROASHr_B>$f|AJ*!{;YvgqDTyE5_?_ZPnq zg%g7zK#sHYF&;f?^n0J1esptB4&Rbg3MML@Zzh(+AM^Ozsv@6*WWQpPG%#4Ts*Mxp!z%h^i?~0Xm zOQ5~N+nt$C*b0cZ7-3lRMRM_qWf&kxd=JkZ_THQl+SyX>`f)_{OPwL&K73SB6HK2W zloW$>EON6i==fyzi)jFlyA$_>%i#nljJLCa#BXcg*ll2}uTLx%CQ6aDQnzGU5MDxC zaAtKVvdEEmDCocr+Ci(PiqMAH|2Q(i!l4 zYVV}Hw{v9AXZ$?OC_$$}gWCdeAcW#RBg~H9KSJt$R#{NN6s?y-*`q{{_6_9o~X+*NsMPQ^i6STY|vI|urV2%Dcn;14Z)|%4GaEVi(%~;5RNqKyuQO!og8+qd5bI%Nb z#tJLgqp%fajqdRC-dHPbCdtlQ*BUI5;70o!L)@V7a}5rmU1uSeZLd>1tqSx?_`4h?))pP1-~GOBT{5ElfYi-UruU+K>t>8htT z^M`&y)$(ulEYehz8CTZFB{Ni$q)Fcbz?=o>>eaO>bGS3vLy6hS-JhY`+N?3y7-G8A z08eiEvGUyF@q#SgXhwUzPo3Yg{cg$83^hATOVuv7x7G8<&8e_vXQEZs)vM#pGhjvi zMb@i|nKaT6;K^xZ?Q=dtIWWWSuYW(EQOnxL9j`xow6}{j!>yagnm)gfZcfR8j=H_J z3*64VR&nJ-j#SQ3tT*_i*01K>&ZD9gU*6{WTx1>-P|a9`i_t4e$*9QY25=kUDIqQN z1rl_8T4TYe8NPK;ym@)L*P+@?dFvQJJdXYBaQ8Cyw0xJZ`hRucui*dHfnEjojR@Ty zYScgFAO$en13DdCqs3G(uBo6C_vbV>V<%<=r<;QWBH8o15dPQ()v}&hz@K-)asimW zBXkO4kZMgMp3B^dyr>G}x#=22K7PX{@x64Ssf?DsajZD-w^PTo^&mcVAPqa*!nw3> zk+80>ieaSiBg^yoWt4D|;9AOW6XtvlDV` z`Lj;+sIpXFwcrfe(g}imck1aW+?OhQY}YPce_xT)@#4)YakSQ*I4c3UB|sh+3p)H5 zZCs%(M9_^4WF2=9lIO95c&UBPVdSMu&G)8Bn_eHy@Ne9!!XR8n-3N?Cg*EVzRvWovQYjAeW$}Jf=gTy@<>sgCRD>ABI})3@fMnJc9%)S(Tr61j`-+#aj(_JHUn-^yKun=Ur3L zF&SS6crsz@HR?f{em5H9P%b>k)gr>g%Q$~C7fLnw+3`_%noCfBJ+8U(t$zxaMX$D= zUW<)Cg}`HTCjCP&u7-1~;_bdIiPntVd*?APbFKs2%?TuEeIpTt^vPX>`w;rE!^&Kf z;6oV);e!HwIamjHa2(@AiY_jf-_5fF@aM3PvpeF-ZKE5~)S+0x2c$CIEcW7u%yGgT9s=~W9%NiOAjtprG!6=k6HdbBi_LBKUBkRNW*#3?P^ie;QwezT@J5+7L z5kuwVafNk3Q()=wnRO*i*JvJp>-bZdyFOEGs?_W(X|WY{4@IPx70sV8XBQIJ%VC^M zST93xBkz=@JNnr7yd*O3W6c3$rXJP&Ve-%Xz2zw%{OKPwf<2`>;&GV>P!HV%}K&RSle>Q z+433_Y80$vB(jNT6aQnR`nR||xI0q~JL$6Gm&*UlPgfSP8lyN_F+pr;3T%sl_q_X3 z@MuD2S8JWmm6Q(g>yUEE^_VHoB2e+B7Js2NSxI#^0Wwr!#cb%1gGabG5FD#ax`6YL zc8<6+W2n>VXB}}pMBei9HcfZ6UR%Gl`!{bW|9L3xwc#z?MacKUNlIGU%7-<~^NvFn zn(}f3;=trjxIFp$^fXsp@1$as|1tT>Wr>+MyLY!|;_qT^DI z{n6giIxqBkY*=DyY2e+ezKy5vL-mnc*v})opan(beD!mN)Yhs>Gw;BKCn3>bYU$gF zkH@!^(%F8Vw%vA1FP^?QBL?^LgWRRG+Mr0NMQ(t)(W{1dRL%~@wKqlqy!M>WVNc7| zSnd2_^?SQXS2`aTnqmZ4oHEnJ+O@kH{z#nuZ{d@~uh{?AC;wJ9F=oTCvHd+Mm!JMt z;2s3c@&T;`XjsTJtL6*EyJKe-B$`?p$Ce37%4vZ@YEm9h8dyhSm#QBSYf{13P4W5P z+*k#(X+Ip(Ud;o+z5|FLa5>ekNd8va`683?`ayxd!s4Qrm14cEeyP(^#(PwjW36Lg zt}I7oD_Bs{O@{k=cjpv<)8Jm=i!N0i0iOT|A8K&W_&lZ_ z>C=<4o)2!RGg$^|ODVTM0JD~ucCFqTeEQvwrC;*l#_K%MIv2MP{kQaWo(k~ZuebpX zl)hUU!?i98k#uAtL)c-_0HdIh7xu7d-+#(SHZEfu7<79rN96Z{81ngvkMR1{ncw;W z`|?^pxxk4JTz`^%%fs)&bLF?D z`B;o^%vRT#26Kn*$f%E-RwFxSt*gFP>>wwG?th{{Sk{xj5Yxeo27MpR$}&1#je(pm zP$I+;)V(jIsPpS23fj0d0@Z{1OR-qak*Ebr(BlcBq zr*(U0PlqX_asnZb0_`cFZw2!t6aXZ)g+KDX>>XMbu~z%Jcy;^Kp;L4t#^62tUddhb zVE{%ZF80tYP~V}1aPBaoVU-|=T)1F0|z|| zcvxh4z4~0A{<|_^7+YvwaXjhr-HkXH52@!iVk;+3KRPFdDN%wJD`y} zhkeA%9QjE|eY5#Tom0Gk?=$~Vex;x%D zqL3nP4od#pxE3VYZ6C}NVaIbonSy>1rh5v&1O05!x&IfgJgebL;_oG3L#B2hj{eAlv_LEz-4~l94jhd zWtdTL;q#PP?zA9Tl{wo3o$?`W@2-r0jzt_xj1_2bAcPn&FuObNSfd`=BidP6{(6-# z51)ma*D$aUdr`pu=frq+GhCup8dehC{ZM+Tcc%dI*X|CeVi)no4pZ9QGH0>?mr{KTBqTt zau_z4&f@YmUipUgJ#X>tZ1+8S zw`Gy-q~urtS^hoLe`J%B*B&>`I{$9Mgj_&RR zuWbKZj$=ZqY)tKSgrS>vi?#0BvM$W_PX&>VWvv|;YBoN)R7%sh$^B)^Zi0)bF&#Fd z;-K|Wcg>5*Nx*x;#I3lgIrj@(w=jZPFI7Mdnq!yC2JgNhXl1%u1>3Jv;cEo3dZvjN zh}G(3{B|ZTpY0l01*o;NVZ;QzjebxCs#)6WYgl-;ZNV*{PI;g?uM%fpS9&Z2IxYt^ zh;O$j~+2N*Z`TQQQ|4y^^@bbszTT5+YsYO{OS%2B@Xj83hV=#g7qW z0dB8Z7FtZmi!`6M6LCpEp+&a;%Is--u4HuO3p*vwprgN%d(kCnKQ-$<9;CIh%~^W> zhA-Go`=_~fTw)}$3zqWALca{T%jgdqppYOu;N#k!WZQ2JIJ!nQPTO=3+L^W^w)oS) z355DbZ)|BkLFQ(^ym=OIEyTUeCO#eJ@v=goBWD?2?qtAr19VXmlE#Y#y9z^K25>St z>FJzG*duP2x9!_KYUk=R9R6Qf5&KuX<(@ohufVp}ZbTsmw%nOM$&NAmA`_b^+E7*L zOf;)>`n%(KZFi)F0LxzlKjvY5_6e$=Q5VF3@PY46GGQrv;Yk5lD1~-BozXA6f;;(f zp{-H}Xb;%y%gli)<*NS^JjF_gD+Z#|oL<|!7=dfmEn;tc>@n96PlESv`R(;>{NIp9 zYVibz4`qoMT}+;YV-!;C`ir{`Pfj!;24146?pDtvc(dicfeU-Q*#;J_mqwQqc>bAy zBE5X|-HF%8hOmu546uqMw+s9uoX&10tm`KZ7k}qL1q6dEsKm7#gvYBXOIjqzse3C> zU+SI5zi)+8)$kl4D1A zLi2ybUtZ3C#Gh%x)pjch?l@tPY{^RR@iY{3C@$O#@D|Di&)Uy{o_ z^Y=5>)_<(6wKge&ojjFfA^o4oL8G&mDs#6Alp0`*(i&_}bHxB)L@&dsvlMP|e$QGPZ-k7-L(llx9ycvcFwMv3W!4m?^69 z%JQxq*Pk<#_ulS!sFym8bKU9Yjc)_R%UF}D9+4SZ0DGe<#rgLgf?eBOUnZ35|3d=@ zi-`M=uYPVTk7_>1V97kmXu=5)XtUxX3kZFL9l4skDW(81Z+A>lqN6p-Ai4ctHQjtQ zH;zn?hWw_})F!li;tS zj)MoGOs;0evLUG&+WQ5;03OfQm@3sfYxzxb@v?uOEb1a@oTaMUv%kXF_y~=&%Nq5K zn3Eke(qOXLc~bz0uo`|>_Hhnb(@_iOf7~mc1_8Z4t>Xrc5+lxL3Lst;Vqx%m@($9$ zQ}{0@F%=B@G6aI3Gl*(+&`6`VjcjvFkwMN_##ankgm`5K>h|3lsp17ZUL_MmIy@u^ ziROTX-KJ}2GFiYzB#kNMdThV4k0rt_7z3#ecMiS8`T(3W8+MzN#5)x~2rt)s93(3a zJ*YNt#owQd$6->9hcUd%w_DWNN*|GxH2*qL{Vy{o7KlGWo)2xbBH3A4S6W9w$3zRm z?8BQ4z{OIPcn2!2VHU$tr=GMI6zNvlNVd)BH%a1S0bqPgx(=02 zKv;pmiMP-CYF0EwjiRZ-#qhW)1FUy|_il;#*V$U$W`R}3OYb>Le#Z*!i+2V5Nr4$aU(Hv z^juo~>0E5}%?~EG9%ru4Ta3eKQITjg{Nh~ha2p(-9TUf--2p!+we&{SRF<_@8xzm37U{wjajP7 z$-BOc>d96V_-W3r%=ql!v15W^^V~M%)-e#T43^K11+E`?aq({SYV?4h&Qn#6=b~lf z=&N=HNu}Al5TQ}U;SM{cFxuKqEr#qFn{YF%k0lU8UX6@xM@O8ewZm}m-a|lrtE;qD^BTMwa*Sz)_#K2lm9YTtN}g-)Ci)$WCtKT2B4;rw zG_bMp9t+Dsgp+Ns^?asRoFkDs_MM zDBcZu&^v;ATsp1m?AD0B_5g{pyH5(2lUJ0RtURkL|2zkG5??mi`FU^5pw9zn;)=Lu z(<2s^zU2{4ceLGRoq?-D6rHo{q+6Js@IPwBGC%|m1Pq$T{ED@jtQ($Qx?WpWes=lj z5*-`s{D7-LiVYVzt@JH`RV;Pt9ZoAvelh$kT*D+y$Wt zw$&W$nIMgC)Cgg(8L5Gh~c)ul~G&ga=fvYWMa{?gKw(cT`zfQvHT zNEz5Wen$G|3|*P)WPBd4TEGBmH-#*hjqX{e3k}6czhc#e54QTUFTAqK5u85zvht33 zrs8zq3kify62XeMc(m*Xp=-jDguLx7o2s{<;$H)@YjH~C<1Hx^OOhQR8%L^{qD~}# z0xHTgV%j+D|G+EX@ZXes*biOqK%SlJpS6Z&#=BH00b9I+ViJsDvOJK_=# zd+T%0Qs;k}bq4#}y|*V8-9;Vuu(FDN1tJHX1GJDInzA3R@kkzQ)HlgSLxxjU${r>F zSwTeM2tP>>#t=fIKs9N5@uqc?%Ef*qZ-hE+9HCWP>{AzRqp&W*6LMw`HUSO>K&BKH zkOhdzFoV~0+Lfa!pd!+F#2Ou0mCDh{v+ta~G-|p7nF@;vS^Ld@7K`NS%V#Y2=*S*i z8DrHVu{GJp@rk4sAVVCREROh6Irubk&^n8kPK?{yA0fJDX(x-L z*WXP6#|7_V1Dw1|nZfU^kINj0Aj*yKd=zPZQT?AaZs>CU#hPSX{?d}!6^0lQ#i@j0vuW6IgQ>Zb zv`R0C;=BhgpM(D*bbL{(7u7Z4zE<(A%2$PN8b!^W_;suFbrVx_3$L(Y`L!E4F3x&r zFg>eRb&(?mv=Rj&tR}nO)qqEX)gCuxk~BpNPe-ZMm>lblhf&ExsaN8doI5p4jz<@4 z6FdERzdk(SNMoS^_Vs5&`zfEsk&X_dEgxZ*9hq8^NugO%6CKfE)U$s{M|!I5pHonJVKf97zj{b={z1@W6^@6hIf0HL-`Cws3qSJvvGH0M9oPc-RB#fQ<0 z40MBFE05S26E0!X4+WkPu|tpo8x`kD2^j~ZpIt?j#rj`(@7-cyU@GlYfH5 zbp)A10+B$orkGYgGZ1ECFmSJUqQ$%cwiQr)mCMP11I}Pbp67F$xC%Yr{X>}eA6Q{= z+Ft@S3^74UEtF_o0i}pD=ztb;QE@*uL@d=v3Sk8eWv|8QFh%lPj z;40mcG~~d<0lQoic8A5?*TQ}n=4d|SH18zlDdAqI$w_NPfLrtqN?&NEjY2DsGGK zrgeH`Y$cjIERd=`eV33V^&PqW>|?n9W1qOzTRQp&y6~Q-Cw*xaz1Ffkm(FGjVe=PD zP?*wvRE>9(O8a>j@$0zozQfXM5uR`2qVH=~>{HsAv3>`kpmE!SPG=9);O(p1W8v0C zr&mVa5!&@k){OfbeG)7i)~G!K$g+CXyyLH`1u*=gDJxC^N8IB&8u>xmueS^7yU#`^ zg0ew09*H zy&`uc)EKAqrJM-P{`~E3`cJI6+}1w?JW}8=EU4y57teIztoFrqu!wha$JK9fzgtN* zFqYOR$KQtJXKYab8w?j%c^(_9%Bnw&8Jx1O;+Xn;7m8>#er4F6g(V0UkRHMI50XyU z`5UWe`c5eNWqQM{lV523g!Jeu%DbaqQSK9@dw0^?v)+62kMSiXlx%;7W` zX1ZR!d-k!07|UH!C}d93%M$WXjXbY!%bMp%2u&evZuRsKVW#Rzlgk_|1&VfE|GMsIKKzI=X^5@$nlfJz+4J zkRGWS1#Qx1?S^@`ArH^`?CkcmhmJBUeoN#PI`;D$j5!bzoEU%W=;?~yxN2H}QR?U8i6E>B)$!qP9=?%4)?--t6;T!f*I zB5_ z0e?0Ok{GE?Ld?l z&!UHW?SC%Vl*lACURixCUIIO#S$%=nsKg=Lh~*$lEuQO_4(?VBRyO#xeZ=P&_4jKN zZ#S%F#?c7H$wYe`sS$gAT!4A!;#cyO+q&$-(fi~mte8U2;}jl+9~9sd%wmY%gDfe$uszZaBv zzT<0i#ZTk!Kit3d?rTw1N?Uc#fHVEN;9g}aJ>t*u3EDt4*1o`VwGPUp%D_Z^c2ZHRIK=c&`tf7h2&xSqOvLn=21*zX#d2 z|2hO+9N6989ZX--)MWAb({?I6vFQ6v!-y^n0uuh9SjD)PUX4w&SF+%3@!d=A&OrBO zsVA0>&OO$G|15GA?_K?$0)N0L6wCWcFzVC?`0o4D{!_k(PG)lbbsyjCA4skuBr$*0 zd|Nb8Us!PkRrIl@?dQx#D;W;aMuRu+Od>okYaNRBkRHB#4u?rjbD2 zq;me}%9-mLi^*tuO1_>mtzyHMrJmWcu}tsR zq~rZ?3>W)k+Ix@(+bWyOswXrNQes9gIgn1U5ZC~l@G@Cw9vRo|9%HMUm>Aa%-uH5I z@H>pI;Vv*Q9jQ{Kai@#4z9}Lo=uaKbHH}?b#oqMt$=%Klx#*B3BJ-V z*5CMJ<{+*)UHex3AM>gzNwCW9F8+qT7&|o(^&FNDQ^fyst~QCrRfF#G6dgL2-82th zT4=v`3wZd<6kzS<)^jrJ{F)S~y|8kF<<7vw+Ot-lbFwwNfFR}8cw+e9O&x66)+DhBW656)$tGLZXUSm1pSBtV*0pI*&}cPSR6XI z08uw|uq~iprh5FYIEf8lPR%JSrLQ&aCJ~zjN&+SO&v9rIHak1S43bh=PiZ zni|JUGD~5Mq^%rNX_0S(R$(YHA$v!KU{rw5bn~Z@?)(R4;#Ux7rfb7dhdh1aC3+rJ z#^K5bl9r6Bc`#}wxQ`Z9dNy2)B=5Tfy5z#dH^z0O-IVcfgV5@%-n*X93Y|@X)m(Yc zl|7eJ*6Va-NnV&od%vz%TV8rvxqd{k&x*GagHq;jX^`{w3%D$1LsW7`Rb@NVBe6La z#^EQ%-UlZ1vcm-BkOVM2;0dvD=l8X8tDP{K;hybx?HK|Echpa(OYs#kpid>)LNIeh zQUmALM}?Mh-C{P)nV0lxkQ5hgCeJE`>hB4xe4B_u)$&Po0>tGf5!n#BBvk-~sg;`} zir&*&m4Lj2EjY14vR6FLmP7codiBmxS#}*-O2Q==`Gd(Z4!f65lbgt=*g&V3y}e5> zwU>6^+y#BoT8eqODQ{u8)lZ%ap~NNHm5<0zbJ7})8Mv-gW+I3ja-34p<((GBYw7q| z_p6uoIW*`5v-kq~xGEla_j$aEbK1IMRIioo;BpBXC%D>>!@%z}QHs<*L^=UI*LHJ# z#ezxIO^hyjL^%vxflWPFF-I|m#r4fI;z9xB4g99o{^1zvyUgD2jvQv z9^8n6Ic^=98uKpnVc@33;nG-D-vimGA{V@hZZJtK1|XKw92F%Xma1#~d5M_G8?N87 zkk@W!h`rWfHh6qH7_oR}A?SK3Py6u6<6wRRKdU?AnNFr)>Nu^NwHdL@Kkm&v@J9Vu zQ!l*7SA^vS4Yu^E^KsN})(5;bVP)sI*U)I*`RpBd!!_FZ=vZD!$Ncu_+dC|ky2o9o zH%Y|*ganYSm8*qu7NfAjb4&aE9WjCw%={4rTXtjTyHl}R`?(6C+4N0b_%ZRS&c{cK z#VR*a4mMr!QI}-4ZZtw5!>z&p;|MgTJ52_t(I+VUm$@i>|9<`TwlQu-Hhy2USosr` zkr!cK(Vl!4MFM$hY&ij*lHkU6ah%y)iqUVcRBS_d^l8&=@=;G7*N}LVD{=Y|SecPZ z*lGD4L*yN~X>Fg5;>Ujt6N{z%7@5q8|2G#_MQDp4FnfUwaDN->q>l z*JAQV!94KpG?Nu?S?#V-k=uM@0=_R@{YO}oVO78W<&y?dhQ*uAG=-AzM;g;a#_@Cw zYr0_VvBnL43pxhU?ET>4Pq`ms+u%tNW=k0#JDn&lYKS||G;zS%J3vq8!5CE-0AaZz z)k}!7&Bqtxs_9Vwl(Lua zes!r)evZGo#L9(J_hty>VQ96h?#P%{`{{Ev;rU&rHaF6O{+BJN6a*P?#aqkaIK!XT zh3~*GO$ZJS=5gAeHpld>TPoy$NO71gt6F7M3kuD0on^>f-L&=nOm&Sgf2B6gjkMGU zi1Jdtp%$=8aRi~M+Pfmt%c&4d!&cv_#_!gi7)4?rm@rl|89RV)_Z=y{-NCuZ5qTwU zHuO4@`VMqDhTo0JFJrG}X_i)1E5M`y1aUbze~MS#4>R|f%i0Z?km+P|8^?~wmx842e$b_9OCK!!OqFO75Yn5( zl?g^3h#1jCQ7bsGflSoRcFp4!8~}g+^7y;?JHiYD&JsMf#c5-J4w=_1dh1AGvRC}k z3`PnAg{WJ&M4XvS-}126#AQCe>)n2zlC74TH)FGoVI9&IzT8;J;RE`E|CJiN`K*t2 z)JkRSK&G?tt5}65SFFCFi|Y>m$M5Y=vfW!Y@uqD~546JxoVj-& zjG$TN+oOQ(UoZf!F`3pGlORL5HR>8Y>+Ciruc;@9fh+g416) zfxC*)4@notXZ>T(lGb3BkDT>WS(#xS!2&jV{}wFJr&8qHUSbT^(XjK zp*fedVT&bWZH7B;vt#9H;;m%@xXUC6rOT!E?!|8DLhD;{X)`Wq>cn&=tfR*12O@#C zi=pEEvT}<#!9K%dPO76H#^gdo*SErBtdwB+Lby>LUyc_-uVxOC6`zvLu9CUCt!irT z%=@20a(=EvLoQfO*3+2PwAIh_q9TR#L&bO7L^TaZWW(AP@amc5^D>#P<} zE0G`32YThMX5%C~i0Q%1P5!R5#LZgGk4BJptbcS*3Vi&%04)(~M zszSwcXK9CZlbA)~;ar9$v-&a70(Vxk?++#9{Jsm@*N)w_KBGnJmvsEDx7i&@Owr8$ z{+OVt1zTuHj4TRCOKDYkM~18ZbsmkHD^03}dvt{Fm>GkRzVHV0PqU3CM%h!A#Qr`0 zhp@d+Wz;-xnXqhyw!6EV?0Za}1cgI3@Jd+pJz=;`3Rx<2b=Ym}>_g~yWd$8%Y_{p; zlMK(Kz{_e(#j(qTKyP-!Wgb!^8x(skDR4|yZ)JF5J&Fx~H2Dvhd={JEnU}>-l7l-6 zxq3&h!hWrbK#+BsT{%lnP>M*D-q_wn?i}|b%O^kNMWR%?sUw@OB3=gHKMXI$T(fz5 z1nuBrjn@H;xx3hfZI!1k4IF);1{R6|EI?4aVr@rjI#HYYAHKFXLdamggk}`gOsyJ? zOcExQad{JnkQGSUrYA3kU9;K?o@7{L!q9BMgx0K{SiFkj0BL?wHk)fR2L6$4w@_AV zBQ>FR@mY6ftS-WI>CtGx!Bf4WzMXcG3!PhMBNrO?ST4F=^N~`Xd?b{M-BW!o{okh^ z9JkwMbM3MR^Jb?)^Cb6)?42@UD)xROh)aDlq?Q6Imvy5S-D+<`kpNFb-SmgFflUuC7kPj ztcNHc>x%0UNk=g>nRu$kM?TI_K_KUi({RLm*ZXK?rtbsO%#}vr#nDU7JycMh00O<9 zrtMv~P40q#Km~Y)_3a~g+Yb@^TPt#A=oEOG=y)_38#*6S7V(?GOK(wRp@Uy{hNfA_ zGUUxU1MSQ1)rC9eztUOS)kma--dRchzVsbvbRo+i$iHGkhzOa^7Uz5@~o3b%3p-+=%a?8<6wg`Syuqn zQ=Ztn27*Bk^QZ#{#10GHZh|3g8&31JdQQ`lczSJ2pEbr@{(+fKEmiBqlB5sf(3k5{ z7)Z@z86J&I=5x*JehMf67(DE1Z_aPBr|U&;nXrt!W1&j1P*$uCN$&_g>V{kzN;{&S zg2g%lMgbC3bL-e^U0mkTBTPHBgP#cs5+myQ0s0~FaQhcbkK(P{E|<o>-(0Am zc7^Q3hh*&>W9X^P6Z$#nGmWFJ_-obKc=U(`{G2XYeQqT zooG^h+jR)Lm!zX2zjJdhQmvkeJllak;K})i*`D7)@ma3|K!aaRe;j(yAYh=YRH#?A zMle+Vl>r+Jg(1KNI|jH@Oc?Y zJQ`&=Ju^*6bR=euDXV{&Tw0+sE9@&z??WcH)~g)GjWDr9r>+s~W?2g-XrG&2dEMwn z;Efg-f?Z9*AoGl;uYX6Fj^^{fMT%NyUY&1B$czz5b#So+altc&50u0N&p}Ws2Y4in z?1agKe^j@mD3MeOa|Kn?TcA=73yq&c$X*P7PKW8qr@doy(F$WgM{+=w&VkIBWrD6> zQl|U=c>yG8IXY1qNlodIxkb+_jkgM~Blz=kXT78W%k>t2D|A^{|+X+kXcd(Gwyj-o(~%Qt>ka(QRKh3rmDm zY{-6b%a6GDlQK0%7fqj)X+t9nU|APug?Uf^M%bMLDfm0yEgW>@3RCub>UQVO=#nth zLAg%Y8)w^ZR#sO2D>VY1WVM~>kGgCwCuQ3@X!&u+=I$#V0Bb5!6tGEt=81{BSCL4( zSGX?0!B_){9p_Lk8Y?>|mO#?p#45Hj2t2U(xUvIYM@M@1IlA^i1<}>nJC$p&n@e#E zAb_OXJ?2Gv&=ziYGSCPrUsmU1p;$pNY84W@xSuo>x}o{2OpqcRWOq`?^DrAfnAtTX zI69RC`fh*OK8MH{zK8hB1P|oDk}(ll^{U{loXN2U^3nfF3LO2T&KQ($L-T8aUZIvrAo6Ai++Cdx zz<3ut0*=Ixld7bkL;3lc>d^~ja!Bc*`sK;2@VnR+NOpoy`+|gB<(MH#DN#Y%!6if; z^Vwm)1f*1t#<>+^7V6pkP>L zF$~Vl!D?nJ#s%ugkvw)()9<$uQs~E^zg=x|x^-#&`Un1MK5D&DdCoa~O z9%Wsx|F-Uvv>tm!E4?;Q+wW+Wd`~~an(473N&eXurp}&g%#i%^BH?GGG<&#z=ua|1 z68S@Sju@#@?4t{}O{p@<>DNmK*S*yLz@;-|uz860qmtz(U)#K(=%7Dt^QBoYgM2!K zcr>20QR5VH326U@$75?9H*1)+g!)Se9!X>sb-I+9`YPW`?7goJ)4t71 zu?CQT)q>vFM*{YzpI!F#tcM9!@!Gh$B53Khr!4<%T|Cg5>6B58AgXJluq5f z6Mxl-B5^Pft=1*GQ%a2AF%e!pB0s!0x$ zI=UifhRuafSX|p)UxbI}yGaDD8`igTFYrAYx4PbVaOW)6Bs0(Gfvx|)Y9Xo}uX)Rq zACsrC8v`s1ijN>w9Um*4t94$_C5&y7RnnI1P)F8EY(paKkbHzkESEs|0IKO$Q5K|p zpAZS|3`|wrdPV2zPb+f<3 z2f4}(UTJ0IQAT(FXGbinsL3JY$4WAjv?&mt7CMWLPuUhH3k8++7r<5n)~nl zgsnbWFP)KGjA4_S0P-9l(!P|g5PUm_fFU%5a`r~V{0b!>1xb7NP^7SHf&{U0E*pfj zBMZOeG}!mxP>N$wZOS}XU4Q52ADuTlyszT?;9LQ%v$FUKJ731Kek@Vrlq`oseqAqj zQzjN9Ee1zvt!zO^<9%nZ=8)M#6j$O&qAKRnr4jQqn2t8znhYk=vPx%kMWG z@|+;UQ*i#GD0I-P@Zoe|xa~p#4aUw~^TfhIdWV?m#^!%kxH&!=s2#{Kt)2}<@}>z! zhRc9&rnW=pk;Ne&3#O4|$Cgb^)z&PW za@QXU4e+>&7w~85KONvhTm41o4uLt-o3&oV7OVN? zud-qoy=(jH+~RGn$Q3lkr4Q%6EYqeZ{m3n=M7^vjOF$Bu;&F|&6cn}ITvMug(?47+^)inz=!J)+ zHv4ST33eSoS-mN3s0~2*hi^tpb5D1z?G^k?qRa5Wyu$ETIpT630agLnRo>*6GOO%< zK~SchMCLjIVPi#4d!U&x!E&+P4}r84;ejDhWcUnLTOf$PTf6vr9rg-;mt0HT8aLER*Sw&^Hc|=sd**3=B zDJ6)|AZFR0tv=1CUW~Pxi=zPnL2_~K+_>JcR4MI!s{&oUG7k$ppx?ZNI7hzWu=k1^ zW$*cEf#q2_{9@WgFqf9GofJ4!^2^LtgoblC`m~snI)UQR-3r%aNHtxqe_| zR0~y&7IdHVB=xHbS^Vei_`N~6$)y-s<6xWKf>Hu%VEU)-!6w=qB*Znm;B72*d~@n|4yE%=^vxtGHeuj>-Oh|MLWdG$1nnJ$7xC z!_NM;%?*I;iYOW>GM_Iu#{K?v+S7l1N_vt!175=>iiv>zXWuRr)_!;2SEMMGuVdW3 zKAMo7-!xaTJMeqHI-oAE0h5wm4{te@;q}-2$|3n%QbDXG={>42Ih7Gyw~hVJ%wW=Y z5O!+u$Z+cs3>X3EfI$L!u`VudxARH{M^kO+sfzmoz(?ftv9btjW`#T5FA66k^Q#I+uxXiz-vaC>p3iH9X|)}d%l}# z)da2b3ysZ`m_Ca8**(9K`xsofv<@yc+6lwj^&Z%))8XnB0qXf{vDr^EOUv>|T%PGD zEyc;Yl|y?z?~JC90W}K6M93YIDbMc6`7CH-@v!zlY_U->I%w0e;$ibPh>nm&5tThp zHU#4$v)1fe#cnmevuBC!8tAGej&+8rhn!OjO~4L?>jh+n*IFzx-z7DhIdCJjr_oFJ zdhk|%U+|`{{;u#I;^$*X_q+mm;66F^LUcVBP5$V*AqpFi^UptO?HsuWyVyW;n%9r? zS^j4P*#FQH3gZxLn}QhYV7*c{Bs1;$aZd`j--5z*m1_V~lT0Hljwy7dMSU(bZf?{# z-!>=VI5tMd)Kiz!A?@cV^*#)e<1r^Jwa~5q(z)QFTklCykS5w8n*f~k2U zN2P2Nv~j!esF(?waktdvL&BtNap;K3&n`tSc-lMq)1A&ChfYn=rk&i~=`d=6%x*q( z6{@uR3wgmtdwNgDs??h7o7rTgd*+v8mZ%z9-L?JdiQdfd*3dzM^NK|1y8e*EP}+vS zle+1mn8A-*50l-}wc-GRqNePtM;lhwo5L+MxtMcawi|p-fcb zEMwv0QaeNwg-6F1>sYx_)$8q%V{=hYp>#GA?o%KB1*@hYwu=c43K2fNX!+wQJ*ta1 z+WBm3iaaULyhDXT)!oCn6S-zvyhLgtt&DVHlQyzgh|F~&6Knf@b?nI62SHnAxhcWg zv89ruVVJxmT~yqHFmck)F{;|x2hZ;HfU0!fGHir(#7iwT5E{TB6YSiJlV1x*i-eV^ zICE>hgNh{=N6a*9Z&I(<8#BiaG!a~}H*soD_H4$|V@VD5ob32C7elajT zOS-Kww)i@)nE4AFgWv3P`vY5RgkS?1m#p>?5W>|axHydwD4&c*v}QJ-IwBak<1;!~ z=QRQvoMIa3z^;T%`S*#FM=(6wRr3*1<6DL(meHF1m;Pa&5o5Y=U7PXCwrT9TFB3(aKh|Ww0P{E71{H;r0T|L>)6PHj;^Icu(Nn(;y*5F{! zTEot0j(AjuDT^@Id_5pu8pb4&99);z3ZO68HE^tzr{1cImvKO+N%QO41}^pURrEA? zkHGN#+jl{otq+a)8C7ab{OmW_(3*gu=Q?7Z+g79YtiH5+o?NHGyaLugb|*dm@sKH+ zI=<0c7g@by&+mIO&>T(8das=S!oIK}12*tUxL-qJCgi6D*so};pRO>X&zTYtWxxy~ zoJc-1{!E`1`r%=iU;6%Tinv$trRNaFwSPnNi3(ab+r-cuS|n+sp`L2R5j5-g@iK>} zuE(-at9T}q^#5o^r{9e^WyvR7HUT~<*{%#U-;U z^-Y6JO9-F0c1=-q0r^#Wt3tmG4b{m!TI5@Sy}?lhcfPcG39!+!KQD;!o#V`A=$K=c znPV1rw`s~=pYv_E2p#`KKj)#NQf1a;tx8n6^0<#Q*{E%W8_>-QAZbH$JRR!D7FB{H zEtqD(-rFijBwtopd&?ztHU3g(w%$airJ=WyXA_$J z%MN184oeFejNgSxWaj37zrGgn-{-Ag{C>TVO!hnbSJL(_(@sU+d+gRt*Ft|--iO;5 z6kYq~3F_oi}s$5;np0XDHocp4prwQz}pA+mwUBQBEGg2qx;iMngi(+E2z}o$bY0^svgb-McNFcn)|Q``q)R$|yxhkd z_l5M}!sw9u$eq$9VqYb-qx$TlE_zgzqQ#?>)AftX^Z272dmhK`y?yovHNu!ACi?02 z?cQrB6;8p&9xibcq;~FSZ*GW}hIOl_v3o<684597G7 zVPT}W5@oh&o#9(6;_|PNz4Pl&t_4|o{vn{dt9rOgV&yNj;Ln+T5ql;zhW+JtZF}uy zr|hRr4Z2r8Pugcm0#C?meK?WCf|x?J8qp6OR%^bxfL4#MC`_ZQX?PsW9Hxo zot?i7>Pzv34L$#IYl98=w=ntfs&96}1l^Wl#g!&~G9O=i!(*j&B7 zJLto%rwE}lq2YD7-X41X5$3_A`HHyKH>fkT9H>rNpDX$;u;N`i8-^I%r}9sUeuRE< zAPkuRf!~(SZ;xa|XT$#tUr@R}B>TQ#&x||n2!BO8tk$r3Ov!&qomN|N`A;N9Ek*~?l6(JIVfQV|jrlO0(x8pzW@`ut<^ z=t*$-<{GJWAA3M)>wWHPyI>K2ZOH3mgJnu1yRKcun6^PvS$r*EjF5LCH3e7F`it6T ztr|mVPXu;DQbDix+9#aNtqMofJ9jQ=6h%iZKBkf76K$ge>EDZB7tto&c=UC1Pgz6J zc(>J|3y%;R1n;m_ZPtCA^n>c>YO|}Hp4sCCdhORuvBbf4qzTy&S9dPY2C+w6I>Ru# z-)c=wi|0f~TMPgF*?H2^?|8ghx?oYbclj#?Co5wp9n&uQELB`fibq7p<2Ef#4Q@Xy zNWV_&^4%e}x}5Af`g;6huS(>vd{W8bn+Pk*#X1imh{F@BH8rds<0@$0k^##5qfm*i zYo=6@@OLFN$coX%Ndg)FM)SF4pOt45r9KT@0q6fHKrLrYfffGhl+G&jJTw z5(k~xr>l4=APOUItW+`%#2yY!<0s2M^A_2K8=jBXfhoyhRh-FbY1{scb^Eu!A0~mY z8TeWkwGFVSvdu#8Jw5_{O4uD9CZ9FZ@$z{5WMCdUiljM0z=YhVgYG3nIo!Ij9Gj%iEL?Q@MzjTb!e@TGZ* zc5(p(>7TV<<|JW0Q&s``5y#Vx_P$bTJX8f^@jxY25d1++TGo@l)D)oLy@ zRlTf0Mi%nCHdc;y8>d@P=*>Wu0p*;pU33}a6!2uwzA*walaoZ)C)swlyT*NM^AW4& zdH5X2ACmH56}~bsImNEhiJ4i(UbCGMfwoB;IajAmqMyLYkdZ{L3`&uP_+AQT<8X?6 zDK_0pWICk#fU?cBxvp*)-8HfF?oE1h$Sz%?iQz8yQW7EdThY~i2C`T5`cU4P(okLZ z1=2}}>0)^02YEaSw$gNHz5PK{3;+ens@zjB zdC#bWPTb1*5s5^mJKu@i--U@XUtElja#8u>QN3PY`j93!|7 zp|s`YWH&e0wbuRtvAw;0Y^-g`!6%A-{4OFf1s&n3hy*M*@&RwT!`G{4JH;5`{xifF zL`jQ9%Q_j9-?y%qwb95%oyl+xlb;xt*8a%Jo@Y*u+uNZb&&I|KllwmT?>x{2tX3hv z&JPMW7;yZ=u#(%8kQj*Us3QJcb1L~6@KM)khs4-U7sb)wNUqM>Gv7fpVtJqLA$|rs`!T2x-_C z(uf*1L9*e5wJt7R915vfDp7LE$!+&DOicZk-<&SyaS%$=IGe=g&vN9|5eg!L^?e<< zkgbkswi5gj9Y;6~HlRfDX|13Oz)g3U0F`zeG|h%WX3;8nV9r;|r65v)joI=WvTb9; z-=QXP;xM~Fv}Egf-TEPw(nt2&CEJK;0)b-!z>crn%r{w7M~P5S9VkDMoy%eOW4v0> z*n#dDEnhtCsN4R@hL?ie)Zjj1Z)28jH=*!5=NGMSlfk_GfTlP}kWEi;Yas^;SWF&h zO*7Llh+{pO%wgW3yng-mmTdD>(RZ^D^u5lC56oy1Aplx#XT=%KX z?Ctvu?>{r&4;AQnYQi&gaFdtK1oa-m+JeDO3bvYwP7{VZg%`(PEtN(p8GTvFjm-*Q zu*Vvi1D>3e=t;^45x;+&+0$mVatjPaTTrq#?gAS8XGexuj~y& zSN#&d&I>=9%@njo(q_)G?qvJGNujWWj)qoax9-Pm1o;nCO!wOaF|$JYA;@A)$6V}- z5+h>SppztYon;WwcL!8_-aaOE_=Wl&mMG;5YRnqG`%FN=xl>p!7fk+x1Ukv!H#f}J zUOdd?ke)UIVLBlY=1Hh>OV78fVa(uEYoM#xXHigI54^nfP(p%;6E(|_5NQnSqwTT$ z!|G{F=42~M;mb^)Sk7zhf_$t zMEuRWp66c<&PxXlou#XJe+aN}2`_dU>il@n;}O_opOS$7=C*-sskMBrxwp7q_j^>uaw6&(E(9#E$Hiajasi(KMo!Q#*#q8`4E5%~SHB zb;m=7?iP|K%k}iO)*`jXDMH<`6tY@EkUF?sb|8xThcwCc|MLPYQktd(+O$(@y1?-l z0W}>cHOl#*(`7P6U;mgEXceoc_!g4taRWPjg2<#DHo&g+y4=eMKlgTb@zqoJ7I@5( zj0dr3tj{!3C1iHjiZ~#Qou;b|m>L(%bO7i2l~Pqe*Utgnf*&g!Js@iu(?#*Pc)fbT zm2F86apkIlAAhl{M)ROnBk_6;Cej5qPM!NQiE{o_-1ijkJ zLw7I!m|6gSGmi7o*j(cIy+(XJO<^N>hH0RVfiX{BuoJz^VAQU~d=%}xEg@^G)(8DE zX*$xkhg}>byRE@L98#yFMmiltc3XSV4|wFi)XRF~rG=Mbe&X1Q6yjyRI=SiV>lS&x zeQWC&3pVwUj#p$@(Ha~3%F1zbg1L;(jZ^1{q=~x`79GDTm7UJnb3kTTo%Hc-(N{{> zf<*pY$Y|T!`ol|h56^>EaNTyY0s27sP8#}FspsgEVp8@0+8JG>(~|+%$U#zk8M{^n zPlTP1Wu41{{4h5XYZXpFqZStsz~GduK_4IUCU@C8TBxix^sL2zX`tf`0`Fy z(81|Oyi@(!-R1oIOd=H|4@b}=FsSid^NhhHCCMGgf9x1#RyUX?GAdBzGSu$<-MUVL zj}aya=v*V70{C#n8PGkripEi)ns44yb?z|QFa80$%4um)eDm@@HDGb*bd`YKcCpvC zqWT(f{Sa^-Ja)CWnDTL@KZ3%oOP65hWcPSw6=pX+Cz)P2Y5qAiUe>+_TC?cr>qgM? zDeDz!Bb?qb{&;%Z6mpeLc_x!tFR1T8$xeoJ4x{T)B6rqJQJ#-3jP(CPQAw3j&*}wz z@|YUW4U<#u^%6Ebci&EahDdWh#93iHLcU(uE6864O&odA>TH+{?0D(d>R7l$nJcVC zHYd;z`Ab^hPe-%LE|Jm#jJ>L>WzYZ|E^0W?=1?SIPFOkll z-{baf%kagnX+F(~i?M}%4*v>f;i7QI3PPUiu>@N8Ahii zyQ~@2OTYOGE=VuY*GR_b_KQuOSOc9J!ACY~&VrOl+$E1|M9u>K-HJyeTpJZ7D^fv! z^r)JYI(j~9*WufxOxBV>?}L}TJeYX^wqHBNNJ9lJz#zniL9UJ`SLf1hQB2$dtA>qG zt}dM^+IEykkrqHA6F5k|u>VmFLIE8*n#gQlJ>}h+wNt}|=7@*n;s1@8qBJt~`PK$x z&X(R~WpB-ejvw5NHv2nyR566%ZuDJC1`mcrKR^Pq=jr{%xVdmL!%(Ibgp?8^bKnDzvuZ+Az) ziOTe-uVQ7=uut4a$9FJ_01qa_Tcl*so5-3=!X+b2yhmy8Qizr!Z3n>RAG`RsfjxT; z#5JP(1$sLlIzgFF(%3=1322w5N!`z3McL?=oCpt6uaQl*pR!hoA^)Su*^&s|lqkX+ z#fm@6=Ko{w*Yu~fl^7M2nWKyX4?DCb2bf3^DwzUsH+0EHz1&gVQR4mOJNkdQhg10z zLx2-DV(~IWydJiFe41ryF2l|h=JyN1F2jor!UxriB=lCA!ZhAtLU#W7c1m#y^7<95 z?2?Mf?5%S--tdA%dFLEgR?!(^Woqif-Zm+9Cr#Enu$;+Ej6DN32UsKKA2F7xn3}N| zE`cd|7cXr#<#MsGT~S?ovUO{5BpyQAZoJ%* zrs4TwPM-^FH~$UqM^&6WHNndkPW8l^BT4?o&qh=DPf8(-gUKR637X@GI; zA829dvM7fG(%~e`NrH*rVStwS@l6FJ(oEU3gRG3Spt>?Jy^WkGmSAjG{!+P2szDCk*@n;^#5z;a2~n_Y$1? zr&om?aU+xh41>yM=1LvLwL{OE?tq3{k0m1d>lf$8Wq*pi*E&_K&vc#!GBaW#Ys`Je zv1wTVs5O=96*p6K+SOJ{!(yyK+8A!Jj*lV9cxZy%3{HL;{mwAC^C->9P-6IkLZ~*D z1VMuabr{K&r3w68YT?>ljbsOPdIDlyON zFpx;oq_Hd?<~XPSBKkIO3{5b$@Ksl7p%Q;mkf14m`T20jg{_)Q5C8M1!;GKYFFh$v z@XZ_^tclz!UrJ0Hw7VJ;7gQ%f;Wowex$y&ymP}kjX+cgNwnQ+mDv%y$!K$4P;Sen5 z@=mF=QIo_fp{owTkCN@oc;~}>x!LGXL62<$kmwt@rTJ}<$)*9}!0Y2?;(3K0;vL%9 z*dFF73^x5Sd*fN_6NXMnzwyq{kzWM?5}#g$>HS zH_evIPPDmx|FR*E@`!k8itsCo|Ib}#_{DP;MaBYOC<^msegJLjz9)`Hm6%TGWu9@2 z!>voFZM^~if1=m%@i9r3_v-(^^pk+fgx`2}I*6OfjHH8iO!-cjJ#biz54ezU-Fxq= zWR@t{bT4!u(RVN|rrk8>2R}u`AWXLsNl>5GFGd#jwNztvQ$=ySt^_A4z%E8RMAyoE zKBZ~i(#CUV7j(o}g_4x&q{(An9t2w;AiKM$Iwoi5ubP|zQCK;pH6gg9E|#MqH@m~G zwMN;Sue=hNaINOC?ZKlOkwRZBsSNu={Z6XPmyjJK6y? zk9F$e?uSttjp)B2TeC$dN~b#+e{Jiv{Rc^2rfQ=v0F^VQba0m8!yFJA%GKX-Rc4Su4yFVh)295eqkKuY9C#G>8}5er?(Dkx_#q@C8ZINP60us zyF+OZ5JkE>Mt662cc;YY(Jfsvn$g|e`F`);^E~h0+p+D~j_cef&xA%~>Vsdd9K2Vn(Z7DwKHf9}la`x#iqA!V1md&RIxKxsPZt&P z0mfx_wI_Y$F^@q4Zu)El8hQ1WlDw&ZbNhYF_M;)RgwuSaWJ4O7Oeuf+c`UMwT2_cG z)l-OiieKO4;5~G~-`3+ya+jE>lhVeKV*lzg_xM}~=vBa_6r1p3XkmqgQ>LEXSxCPZ zD&(wc*V4DPjz-TB>^t0%OME%PodIe>2?9VaQPt-jAM0gPssL`v#&h4BImoSXm0iO` z&0N8zXV{6=v_7`>O?xygKCb0l__OS#Fl^Ik-0XvKf@}f_1Bb}^WI1P8tgls*zk5a1 zRaEkypzCHM4@PxiO%A#tqOfFp_zjo~(q}3e(NUdGsL5iau*$q3`)mFqP~)d4UEDjc zUe$44FFWMZa$JSgO~FTiJ{|c&QASL=Dkb4Q?HV6hqrO>yW1-4{U&0Bpe=+aM8 zbuI51xhAYg;}+_7@BtbRI!ulkB#z66uo(WVX&3!{DE$*0dgS})Aj#Pdy1&|uOm183 z!2T%H(b#`4(ki~Fy)Ph-zO~cPQc|gF1&R5ng+ngqxl(3YkqO8v&`s&!XmYj3=DNy? zmSd%yGmVFZEYFFWSviB_TZ%ckCJ?s`r+cz;dfh<85vmX6`OzMo%;7?vSwl7RSB5O% zz>H$SvdOaAy!P|3eQM}_l(g1*v32U>aaHbPkKCn}o3K*m_`h8zeN#tO2@<2Io& za=$*HysyQbm(|l=lG4*{!<6>Z8gF@I~ClNg3Clt4A#+G~~I z9&Cr|Qxzv8oi$K9A^ZjXOe}pQkO5+Opr8DV9(c5Yt#oXyT7y5aQJ2M^P>1UBfFO$L z+y^W?jkvQ)F4Uz5lFO9BDW%V?wc26faRpHQRrA$+9_7&oePZ*~@b`5yT*Jpx;aPn$ zMs65hQD1)OHd%hrVIkpTCTWfy$@qKxJ8jpZLI;QMq%GCw=K?e9;c-dYDU|Mn=_8YNKa{{-jWOqd^6Z6dJ31l5s(@= zf_N(M$0q6C8Dbldxkz`>!v4%|Pu$5pdDtA$gpr zMKU`W1TI?Jty@T$tMZ#U=4V6aESG&EWQC25F(HX`&Gj(>Zz&7iPjCPtT`TSV)GC+h zO#3!zM^kcSOKfJt1*U`U)>`2xzNXCp+?NR3jHF3(Kx(0l9SZ0Q_p?u;;VK|V+b(jSoCjw1MH4&r?>~;_T_EW zLGe|5kWzX(WS}pzTL;#gj#8Y*q2Ia{F3lw8|Ecb#`w#IBIkE99v(=AIIvjLcK10c= zv8P2V$iNLM%a3*bc;)d>`@D?iRv>yQW*#36xU`rf^f+Z^dB2r3(XH}f_zhe|1xGV< zUtzS?jfYuB&&fiW8kt{t*{emdlIqX*dG*oj8DS`>MVdNTKpC>2A#qPel{JUyAIeNO zY4WKw?#G(_%nbp|jG??G#`W5Twn^SV1`X*2)jA|2P3L+QbkSV!j78qZ7zp_}#$uG- zmbFc*#RNF-H@WnOtl2z-O58gYc#gWI{6uX&Y|O%`T)}iK{94Sw)}?qJkAnHoz}q85 zadof;`L}WxCBYXtfZ2FNE|q7dz8K~b?t2P7b-KnP3}kozFIgzJzW*Ak5<{J}dtRx1 zH>)#TK#4l5Ym+G_6mDxeHhSHvzy{OwmU8b56I@q0;DqmjgPOFy5nQ@#IT_4>mnR$Yry2^L7mTf~ zPavb6C;z8PdGif$*drRb+9J5!zv`b1QoXevli%Q**lFYGM(Ev~OVrlHa!`rlzSjTE z@Wnllll4^oAI&AmC*o3&R72?&6mJqN{>YY?Ohn6i)-`Vdb5${vvbdL=<3Fw=>nG=nR?-fnI zx3&FMCaDth0*cgHQWrZ`v0kYVp#uQaW52JFTkmrJX?`&GqjN`e`PiMwX2&1v(^yyN z&bNLe)6}X3;dTP#UZu~T6um8*tvNmg^gEs59>4Es2C~m2 zOC!Zu6iNKYGUKw!`IA7$gf?UV)E~(hYueK`z4J7duV|j^`vUR{YAakx&LAJCJ&qer zolYuFW}=FwKpkAfk+;b50w<}WpIPmnMu&Ddo593*apO{4r|4PxLkgButvoC>FdGFK zKFjlK>U~b8&!`tVAcx2=P{@ha-uFa7IWOYtq0=X8f(tgY&r*-q1pos)TVtINeoV@+ zXA&{>kd|VfpXH`6*6s1M*llU9%l6`>vpq&hh=t*I_2R{z=23T6cIbmQ8F`6kY^{~)FPF>H#m`3W=*fx@~@myHA`|R9q>pR710ryG>y$aE)F)zE@RdhQ~C-DT) z>e18T|CK0M963x{T{Xq9c;hr~RP=Qib{g`fng-=}W|=MeK8&p$R; z)JQ0pODMV}ZbPo8G%Ek}EMt6uekE;=2Arnk3nC!^IDTBZRj~1=ST&GoV(dTQD8;|U zuLUv0uz8RNnmPq+Hc^w0lk$NF1@YJI)%i0Q^h7*H3XYg!Y8nOmE!SIM4I5$K0JU)# zsy>Cb@XsO%$(~H0VMEmI{VxV#W!Lm&jdKkipPOKc9V`km6EibQ-hVET$KqpHY5S=W zY$GGAm9Odsh~~t>d)Ec9AC&el9&Wn(XM1=-PA>0jP+4lfcz4GEBw5_N?MKk%#5ajq zK2=-A(k^nP^qd-@7s28l2cfSgEUF#l1Dq#rem-5h4jN}YyBO0n=|f@E&7J5oo=>kw z?QX71dtSRhIr{#>T|zeY(^s=FFKMs6J?n<+7OR1MTIVC)uwTXlD@%=dRx?JXE+*Uw zMjRR1@^*Bs3-lSg3*Rq5Kjq~66aES;&}P$0rq)k5KZcUKbmzAeK_`oZ%QQbp(|(9| zm#FQse0_sfK^^garcvYCi$XXE{znrW{OQ}(Q*1QTkFAM2Cy5h#yBOYUQi3-x3^9bD zfGIbQXeRI|KRMS^VTgA-z3y2m^BBes0jJ)i^ z3aYL7tFntcKQSzW2~?<~Eo1X_RZlfv#lEgu%v21 zq&0Z=!M6n`56m55EibF30@yy!>`zQj;$l6X{~ywi0Ac z6$P%wzODA#yjb@g>pz#4jgiiI?V>bPIh)K5X<{u0HlsFTQ?$RnWwjw)L&H_dTAEoN zv#4j5xVB1&HeyRR?ZIdKOn!Q6a3P7y<@jWofP;hM>gJ}y z!ez;+2(`l3YVuw+pnkpJMwHB4(7iU)(Vb+e;T^oHlDUnBrAqldFJxX3_=WVRuwXoG zmHjf*S+qJPaQn18*QAxWi4HR2A06jqO>y=aH;nnuYqN-Mo-AuY4H`X%%jH2zeLloY zQ_pw%x715)$T6?NeQ~ET!9J*!&eTgXPgjoytfc%pLZeS5C>6^nb2Qb?cxuSCwphL1 znf51h=d~ihK4=->(SHXh-Uni4*J~}40~+L_O`B1#QtgcBeiCm+ar_tb&{Gk70#AN_ zh&`r?WCb@HH^S3Zza3S4MY6wgZ0ZbGxFUq44VsdV4)j8hF6G=Je{maJ%zmF+tTSaX zG*s2OZeO(A|7Y{3C|Sc|e^!-YxTz>v=kzVwK2=dKB*RyU>z!q)Tg#!I9#enQ>gbf= z{8jq>9Om%2W#3P|_OjBg>w3@*Phjo()c2sm9IOFdF6*BR;&y?MMce&<#rQ%+`il() zO8jiq%iQkq<7RC^PLSU*DR8)lJuswoYqbF9ugXm(^O#Bl==nYM`W)>R3%fybRVt(C zDML<>uT?5XpLgeXN=WENO3J z&!G&xn13Bm8~M>+@91~R7Zv7KWR?2M^%zjq>?JUGRb1vQ0+@N@UtWYyPK2c!G`2VT zpqdX$Boi5!PTwrc-kLVN2(Yi9RaZ{^lwdU^waXI69dS)V3%1gm*NjtOA$N*BND@Dq z-Dn-q?uIM62PaM}nDGHX$dz*p-D!k-9SwMKiw4>AKW@cU@(yF%tONabT{Tsg#}n%3 zO%0ZVT?sCe&nrj|Iqe8Pg=dcEq(RhJ5a(yUyY-Td(5)d2j4B3$Pw2Ld(8xvPU-;d( z#a=+Zi$kSrBMKtdAJAefqX8E&dEX|mSz}l_I@31fvNMdB!`5U#io&qwxw2JD)2xD% z*@$@}b3gi?))3OorD_`jeOi)^v)Pu%DB{b!a2x0T1W4En{wco{_VSmLE;dhqLf7>& z9;61|hJo67a)n1LKb~hHpA+`W8^h@^rgO1|3$I(lcV#e(e^a_bi_cprmjXI2VE+-= zFe8x1DPGfQMK86fFT)V3Z&l0e%tx%PN@%~`q;vcY{9Us?%aYZJwK>LF>f&OAr6$)= ztLkP^Iu5J>I<`f{c?JvDx_&h`36`suh`p7Z%X80ddGJ`OqE=&;h8VSj{i^A%Wt3?&LUAM`{oieN)PeP51~I_p-4_U? zbGSF`B9SUmC>7rDmI9A4&jdO6TEH=K<4F)c^n4`+q0pKtfD@cE4z-|-uHpyYvgKI9(1Ik}9R5Dp?^0)t*_ zlDGq)RTy}nhFna4Z}iQrN*MAFhL4x-A_MilR&q=Y)6nB0f>f)0NHX}#)581OI=<>D z2eiqPeAD;FEFmIU{d=o-!9R6XEiI-y;?obJk1XBAO7ZKw!)Z~A<$4*B z2(m~;>yau;A3pQzVDmC+B^UMn#A`HdmvbJfRtL5{^b~0`>_kme|G<_m64TVfA#(n8 zwx~-|Jfb*7pr$;hK8IE9sDAhVvH+EPH@^;N8?BJ7cY{Wr_#e%o)pJ3$4Xf6dQ&$#! zPWykS*q+`8=k%XVx$@X{%T~Vg!=EcBKl_DwZ869A3-9iLgd411h3>K|9wd+-!sjyc zAgDa9FD^Qpf;67)ro#$SXf%kk(eSuA+FtAKjf{#?V$3#|AZ;IOXtA~(`S>{OR6bq4 z3`}7J1OXchpAzqX1AN5Xi{3Nbyob`j9vK_Vlpc~=r}1)k)1yBv$hU@ZzeYa;f8XB< z5E?g7(I!1D6x4T#!|)^sO@%2GdMg8J-y8_b9|#HS-q&^~k+fxj0+G^gB|EcPxU@B7 z7;?wZ)NE;o5J#n8RTSZl;;faw%-w$q`{DKP3Rho~pWEH5Ouz6G7F3kuXdEWX8j7!t zj=D-0O-5s6HOS{GRNk0YD&*_i^oB#0EsN@+Bi9dImBs3j%|)`$?_?3XgpzR^c5Ebm)%!ShDdO-U$tO5n}BdPm4}Ld?<`|IdKhtQ~a>hEU7J zmmO)gXgP3|xu(PXO|hr22S_9VtY--xHIVpgdqWs3_gzIC!=)Ebk;iwzo!&(i9@6A* zC&jLg15$i+RD;v*l2WLccJ%(VjrWE{AU?Wa-Mf7UjhPQOiGd^aI+aP90Pie|MxsOD z@O<0wG0mR#bktSQl(fd-=0z(_fkAIL4s-cB7P6wP83vJ93lDy1;F4|y#@I*x*#pbD zSxT2*5FD|E)?m5FZFvY*ikaLaZH2Fd6twsX?MW92l!Bg@kyx+}0ohJVRuh<&s%n;Z zwiI&8ea`6~c^iAGc(J59BI+Q;^lq*+Ys6K#P6xw00i4TWV?E3Ui@PvaP46?KDDM=z zW0yW|QLaSsU;jxqM%LOvbL%m}_c*NFs;KJ~vw{KnuBeE!BReho8>2th_;8>6$o&TE zOosFG@(jwH82MGkTHA{cAY zBnGS>wP4)#-Cq^vShJwfqjR%+Hf3(KE*ShQ5hwtM+9SRBnzCjO;(GW>H9E(Uhc3@b2#B&e;N4#|;4LZxeIa=BF8I;W`Kv;{PmAvjM*AMs zkWUTOBddas;a^+|&sXClSBw6+1RcX)xa}qjbUr>j5E0Ga7cbSdljy?tGN+*(hi}smJ++&lxjVCQnQ271IVB_yIy4p}I!bv4{o`S$~rg|UhQ1!<7|f|``n<#KsnQ^=Ir8d8bF{Rz=)%(2ijY4V zIO5NEq*fuA!Ax@W!L?jtq&MkAn;+M~=*Dnm!SW$0qpA1Bn~r9E5GX6P#>72l_Ew+@ zqvX`ybhwU)#5KO~y*vrG>Zm8e(hT&gT*$@Rc@$++J4V3v2XQ?%mM>(VFsBHad^mVv zCHRlSd}aC2HOTQ?IJirLN4R;X*h(e9Sw(pdi&64zjKj((2aOh3YKr(@c6y>S-T=F#BiM zDx&qGtNrJf)qa&gK@&;Mz%`x83M|ll;}EE)Ug_vUM(CdWr*`;%)X)94VdvqYexUY) z567wpo33~az3k2GDHXn#V#eOqGu2@&6XFKjk5OQna@~jd##5a|7!1IEe}Aj~J!_ct zYJeP}Zk((N@eNBzZKxu;sKcphcZ0*%&XmR?CQqfT3gCvVDVZm2koH=fj)z^(+4zAQ zc6@0*=afWavy&fpUP8J(q{6kFXzTF1kzjf$_-ESYIa8BY6tef8+jmrimvj-RcmHg| zSSVo=5s+@NX7)J-|K@N#)8SpLqWd_!k1r>^Zw>W4F7EU&jDf+V1;Kns+L??qIBFvw zbtUcpFqaEjL!%)3+`oJ~*Dn1|1h0u2ECDk{a+I)!8LR$FVhFJ|kb(+n8RYF~H2A-p zZ=ptBLM>8j}B329OLJ)Ct&VM>L}dT zAn>RY1~IBgNZP1GM1y>*%R8&?I}gTAaKjTfeMSs%WeytwdCG zL^HO#_+`Is;p2a_et39jI;$~ly1jraq}jh4zzSq&B5UWQLT8WW02kp-FV$&i>*6_h zjx;PxOR$8DA%qbPM`ve>@yi5esG0W;(SFKGmEsQzep#=_O$>=oy;t2$7jiv2!(6U? z6a3tFwjlUQ{~;0SXiV$idXMWWT%g9CLxMq zoZ@@0@a?RHe2*HjUOP|^l7W9)!4<`KA+t4C{K?dtzJ(2*?Sy(Fc;c>~2Q)fxIT(Qz z;N$j`99Y}%dYA!sZgayic5pa&Kq#Wo1^FMFsx0{*>iLcNcQ_mVYtJ`GRfp2|cZ_PG z&V+^$QAc*HE?YbmQly9~LKLr_Lo@u zo5c8Q%DESemfS@8{Buk`SMQZNC?ju^$!XM(snzq?MKhcCed8O5&nX_O?j8}{7r#^4 zJ$x6Sx%_5n_BIEm*QQ-SzaPC+a0%`H68#Uq`=5y|M2-QH;=mX#djvV24cFc#Lw9T6)UtKveK_&v^+kNvlxCB^0(PBdGd}8T9zJFZJ@-`df?LLmz*`*2-uW;(0#6DI)x$kyu%m zrjWZo_jJ~P+XU+=nG^haNjKKSo;_LMAfmvFKxcgJCZ<^K%<&T7Pn|=!y1u^LXl`~T zQ9Vp9kH2;u;!b6d78d-uwci$&c5$yZTL2#^6%8u~uQ3<7@orzXF{H{p+8u8?7wuDi znL{X6nHc=D@jP}GLfVo`I_#}sA{EiMtSN7L(Ohl%H-`)#{odUWT$*Ur zK^W|(u_T#aHD1$OAxv;nlP}<{vAd?DdU!fe0F&(HKWQAEaIup}i`j9$_Y93NSc?&s;Lls~fRgL;dq;VkMw#Cd$mtNkM*z9`P_(=K zGjoe9CwW)mcpl$I)Jkc@*BIl2LQzI>+4sAqMnM4CY%k&PY#7oh%M#+UeRVT_p;sY`zZ*kpsQ5JWWPG zYo;cWuy_7}r1pTEq>*~#ge11ITP-xRR#A>!WFzQ@(|1llH}cW$;bSr6Mc0=$+%D^C z|1v1J)5kjdnWx2w<|DJVW1JBr`QD6*cp2{~_d<{PMR*zb|f#L&zz)Ta0gnP~|^ z1TvNMn((y?r7`^?K8(yT>Wl^Sfr`PI?X{FpV zcoiENJ!B1clxmP&;NJV4zFj{-ZOe72#4JrWrLS$su&H0{wL>-(gO${r%9B=&nS4Oq zV0vMKvCW^fqri|WZ|)4QS?NniHslvM&{{`G)D{KrB{hdyuIAME3rQfqdY@#P7c(dLET0AN?%jA|O*}^Y+RK z%ISU;A*1e$?`G4Fhg|i?)Kw0MSy~PH_{tqIKmZzKl&sb?YQyKT@Op1Q2A9F`3;1?w ze*GsL9FjNGXma!0;DJ##0}H&%2ViH-901ciWFuv|wWwY+L6ZM^Xn>fGCyS?y7%|B< zWsNkth^)y@ku^C&!DLl2Cb?*>(i0bI=Hp5)g%eGCevK9XI^P{3V&|7~;+Y-R**<)6 zIRc8Ip6R?9qIYw>KzZAOJvlcwkQ~Nz-aZ687HcNfbZq971wD(%h!*rN9~`~?`(t)w z^anp%RN5)(gdd$1miSWlV;i?eksr5^$PSKCc}iw{vEu5 zy3q;hEU^_{at1$Rqs$fXUZ@WCOr_q7L|IPDnsQbs9qQx>UUiDc5=6ebWO7%gB7pH` zQ?+rcm%3${7KFe3fXNXVE)jU$d^@9v^6dWFlrYG#e%Wz*jzNnX%9gTm8o4HtPB(A8 zPAN|#7o=GpiDt|3$9Q}UeHs`#X>>`s zh5XVvL;9+GKq+EJj^yw+gw*3CEJK}StaWP?6Vv()1G_-t$~|3E!PODged9@;)L3m-{qvyjm-62M^1*3md~(JK^b+FuVs#UG$}QX(yj|m>sHW_e>xP@IBJZQB-ztw zO5;Jjvv8?a8eD(rs?0<2tuc%(SLXt1*U!+7{rVEqVwP*>Ffyzw&ki4E$~75o5`*_A z!`1gWBc}@RTSxdFo;iOx9nO{G1Ns2i+BQ--Xe3p?DvYtiU|!1{>hon$k|o`Z&e#vG zau2hDs5ad@eAzqQO5^-n{e-f4YNbXTVn@d-k!gYJX0poKQnpZlR-2jyFyBhqY*srw zfd5#_W+NN8c7kgQ%ke$cx(Ui3=|$Xk0eN5h8T@O)sjlI2a_)C2avCuCP4s^t^GXZ} zB<}Qn&cT711=hsu@#gbh2Y6!`9ctG$`)C*2s|PA9l+dWX!z`B|6x)k-8ka*;0@>|6 zenSB+m#gg}A<|@V3c)%Y)$#D)ueX@H%?NAu{8;9f5;XXEK|sskhR(o$j?snORftn7 zpQO85qZ612Q)nBXmcXSRrihcp8E>+zi+J!W+qTe3QJ|l5fL4Qd(Y-i$R5gjtoHSA$ zZp1vN(8^ZYyg%PO+m2S1+GQiv>hIZg_ZnWE%LSn`pZl1A+;4bBKhUhKXuk0DV0zZWToF*_Oe5}&tUBs4e2h6rq zXId7iM;kD8>X$&fL2S&F4U{dwvtz5~`X&4eC$oJ=x-42;4Q{38nJx18N4lF76v$so zg^zB@^CuPq$|2xT7{K|r5eryYo)2I~FP7>YXA5~OTx=~zW~HO?xN5gAY8=_IKWJly z|5Wpv-QCl*-4g!%`gPb}=EMAo zNzvrVGK-Y(_%iZRd`sULUO46F$iHE>IhlZmxvKy1L5+Wii*3N$0;e*WyF$@}W;s$! zqbVhBoF_J@4l!BAZEtSg=V*@gsOkf{KBh&lbDRQ-(TEuNr29i`szeiu{?03>;A-V^ zVu&}M`W+gSk8r~9YO5r6Ts=?#5YY|m`9uHP%q~T;1bJifBJv?ismx16{34@slseZ> zy+=8qh^Y&EwAYdJ$N*{B84h;P^7u7eBrN&5&$g9PIq`MjodIJcd-5(>q|N*wI#xgq zzxT*Db*e94?RKo($TcxR88bcL&g}mup<9;!k4&aWw}ci(=qO`GFWl{Plzq}2TbDPD z%Nh^1oy{116E=sq);~h8^_^q&jqxTaEr*X-BPhf+ElewXtm~*kMe8#*8>O1#2t0Yu z^7~YB7EFh+5o?PjQHI69kv0`X?=o|tMXo3$s5xR|hOg_0iMMv+QLUrdWi2Cdj=tN> z6P}+$NJ^1BLvrEN8$DQkek1R?HG(9r=tZo`S*HbN@ik{I-}c!; z-DjIOCdT?v1@hq#n(C2%Erjt%JmW+#KtjYhhZ#WIlFA{ z(s2nN-q-nbxf>)7%2spjUXu)!OcKFpmfjR9j7pOHXq!37ERswHf{A(xkTpVs#oJCH zQg&LIa z)+z^^EeahEI^`YRL=LRiPkfhPC6zx7VW$8h&PY-~PRLVgc-Ir2AViMrlQiJep{lYf z;oRW_$~E~LAs%$lZ~tl=x~_=fd3n8{1H`SNIO>Nxs**#4IGL_g2Hrx>Q^k9>z2(tY zr`&zv*Y(H&IQ$kHU~(^LrEQ1nT`Z9~_}n_}01)9)m!zc46^C5eJY&xgMh@57id|E0 z9OvQVj`OU0Qc_iwBbBt%v$=j<%v9#*5d-yP-CP%k?YbyLUuY>0+=N0gn*9G`fyRRF zbreD>qA6Bul6Er*;84F~W2ydSS`{*g%jdDU#0g*!PbN+PQ*1DUp$kIoI?nx#@YpsC zIQOggspdHr64fHdb#K&U9efr`-ZdM+Dt*hNxALvd2E%Yw$;0%Kj=n#(5j9(QRQNJP z8-?K8@;{Js!owbTx6-Ga`@^U`3cPd?>gB+CD{+j?{@_H#41Cs8X=H`y{%3(ilOfFI zx(FwjVGY&h-DbCx%jDeZKvB-~&!d*8yn{0L2CjFD!at4p?5F8Cbmp}^kjoH?d7$Nf zB|u<+haWjbtJ{7V9fRqUhatJ3D=$1zRb_;=k~u$!Cb(WTWEe$?+A82=kJrtdHZrEt zt26%G^+i1F<+a*stUWAkHQW}K=EH*0*uFnvuYx@=*|)uDr=#MIxg?HG9TQ%Vs>pz^$U z2nben#@*W4H0);1uoOf7uZ3s%pP2RMV=kvaB%x89)i?<+!=m<6GiP^v(4=7%x_0{z z#)?t0UUyGym9U1|M5%lqy^Z8^a64ENLIZCYoMu{{Rx(%3vz@GsQbE*Y{oYGZi9}NB zjm!ARJ8>tqjP3=b%2cM^)Z3}hxxD0~_%vMvW4Pp?k$A^cO2H1~wpkw=WD@}WEH+RR ztBp#HEal>Kvp~3ZM{6@lg}U?s=Xh@%QP!E$=!E)$aCB zwg>tLz4{=Q0J}yskAxm?kmd`*EJ0FS`cIj;GV}ic+yR+D@!DP#9tVtnQ{* zNZ&rs_I89o9mPyIl`WEscr4pIqS->+g^ak9Uiw7<*+HlqP&&h{ z`VWUskuZsFA8njBUQUT=Axi~t5a!>fYGV%r*kYccDnb1b0sx;VFjP-&+M>ODeRNgF`Ln;W4`)9jz4e-inTy z%|Y*0R$P=X?`odEx57`vjVdD=A`K}^u%_O)9o$iQK!ul8e2X}NJUNFOUedYR7is2s zWH61Po8h8jLIWyadG`QKHT;*M>rR5K2Rq&`^9($H~PFS0aPk({P zq1`g~o^m?khrmo1BMi_ku+8>^#N6BMP(o5s>q|YtS%GBZI3;f z+fp%SM06y1gD8NXlBr!R#>h3XO%4Y<+LP+xcdQWdIFBdU8|#}bpAM4(|LHVhFOthN z((HedcI@9=48zTeHhMh&+Cn}wv)8m_L3+iHyN(73QbBRl0*62G!hLMB(M8GU%9uL&MlcJ)1z#ebMqSJ=$Rm+(+Y1hm+q>fJ#`8A`AGBqQ~arT`vz} zoz9NwXY6Nw6Jf_h9R4shB)$h|Kf@RmG1*8nDhxAYKznpkZuX&$ z7UghQhu(37*_yuM159x*e3`^+w#5VW!||+Hroe=#0qQ!pHTr1?#~uP2OH!YYBFQG{ z4U-o*WLM1eP-2m8g1_AF7|@QVpe#&!|D$j99sem+$-a6E8g`?QkMB7BseL}k$JW0) zX09#ZdtW}2&sF#wPG0A(fWxSEm+*O5M_CnOdi-?dBys-}>%*5SDiSwwd_9Z*KMT-O zgom&=R`!ekD(#+hwm`cAp=mjo+#8H1)An9Xxt&qYPomXvHtMU+e~utC#c9L8V75M} zes^_7G>6T6y`{v==)lRmdkW}ZA-7eC%2iUxJDgOjow6hy8eEelHKJE z?P{hnBtnmUoMDADoz;VUYkS2$eo-aSu6;u@-gCUH4aMOj|yoP$~c!*-oei!+TC&& ziG>o3xy;#ysY~_a^s~$(3lx}xB!>`x;5^w5?}Dx}YQjS|BMz_iwA<$&PMl7UsZr2B zWFn#18z)!za?=OaTLBwbhIct*)fz^Rdp{;0YDJOq8OsEM$K`^OTAFsrWG1n#t!+1VlNqU2MCRPF${Us8N6xT8zi!IE_~v> zaUB_&Y`C`2o_u2rODv|@?$r0K=gztLMAwL9!c&qFR_E1FrdL6d$zl%&uSShoWy)JnRfR= z*LLDn7!w`dsnM!34b-Zvl}K}H3RiMR{>-+4*Ci|zYmo6#gKOk4$-bvM{9K>kDJTxa zo1{zNdQO1Yz^-xcX0EmRV>^b)KH|*p22;xeXqowIRA%k@f!tdhwYy+>Dy=dcTcD{~1`JvN=U$=E5u#8a+H9bA{0hHtD z?93hH!1Jrh`Q+h^A$SdXIU-od39LezirzZ+Vcj69^;m?DpX=tMx1&c4)3Ifs4z98O z2%2tiMrLy*zptad7r|T)edeP%slqz61=4-P_+Qt*zjt_2!rs-IKh8{O+O*6|X;Dph z+-JWLnVG3uF0d<^1GH}`>bI2yHm%P(l`74yHCM&VQYBEk;~~f(oCn8Z87JUFxk9?N zBv^@`JCK!kwI=I5*!^qYNs>LfB>+xVJB`GT^m54LTIsU%+r*tkr7?hXsi>}*2qk~< zA8|Uofc1Xtc;{D#T@1*k#g8I8!*;JZ;kg^es%N>-qgr@yQ$AeJ?6fuM`R$@QrZ>+b>a+eV-aN;f!H= zv-oyo7eXq&-ya#(;Oe3arObEoo&HF2ne`@NWYv|EH(Z|&aOnvo@Q8^%zR=EX^WrHo zPHOI!0uToQ(6R~1iKVFK=E|+g9m?n`sVHtFEhgh=aT$KJ6kRtg@WSRadgAJv;j_-0 zgq5)pj4$cP!D~fv)Y{R7G>bkx_<#m|5j(PWE_BoqmcDt|owVpBTj!C)!;aNVF$|x2 z|MFi#z!R0D6RGzkoF;|`!Ggy{akX>*nR#ghz!wgMzy2x;eRtcFV!hN2P2L?iuciD@ z-4Z+Q;F`89Embfh{B&hVbb}x0fyBZQ>XA*V-L%I<_YgMnRj$|;|Mb~DTZfnJdRh|i&TpVs;&NuRcq)nu>z>Y39Y&( zV`N4TGA2>q-f=b<%k8e9Z#_oSiatp3)^DNq&bVN$iYlb9P@^--0yL-G71XJaYZgcGDl|GJ zl=A4qrL+IQ=(RQa&Kg=Q_*_zg+48-F8!gltRj%&;6rT?YX|Sek1=BREm+94&Y%ksk)Fv06;yrnd>4|u+H{((NY(ot4Lxnw`IBCK&7-I0bI z(SF zL-7Bhe&>sSbTBT9+jOc+cR&Uq*V()PEKj`hq{UKZY6PIUxR!)JT$9jVp{$d-Dz@Qf;WC-l9%%P zJuqVcJz9og%`|Bz&1}hi@KLY7z&>A`I$T8oR6WY$UwiGYJG`sB74OxE59rqb^@=I+ z+(E~kh$H*i(v72KN1FiYZu(Eg{u?)l{V9rsS;-#hmUc}IJWBXl<|0qC$J5EHU}{Q; z4$i&X(!Qd-tuvj_nSM-&Y_E>$=O7wtf2dt?NP2OLP ze81@q$$*2omkMz^^7yrryeP%#q7U2(U9_ zp*9pKax|?SXXLK@n>np+{i1!6FC2%`JInus+J2y}yJB{Mou{28&L>TWR|M!1(%qYIbgXutReB~BcL;qK5#8GO==;5lKE9(_`1 z8^xEU*XbHP_56KlMWFkj5+RnXKv?@vMsIB3jVeF6Qu_i#mFrk_BcA(+K5pDWltqJF zf*)9Ds}DaS+LS`YCh4}vJn9*=F=zu9LM-^=llNO>JMZy)>J?K%C{$kr$v34r0UAd6 z7Mb2;OanSBk1lMm(SF#~lJ5e_I zLAK4x6yeJa*Owk0ygd~vr2SMA7JX`bQmv&G0^^w~8D-|J8W{*p`0+hOmS?W>$h2Cx z&^)g*R~pZ#7Q9+f1I!AA*ig|=@}kawtEKWkSF4JIS+=+S-kjk7qv4VU4jL7_dsy>Wm(+a76Jq~^M2=?UsP>T><+WfJ>7R--EA!1 zv%aJZ%EtepKuK0xvljH<@;!`|oXIMh`lID&eq9}S%S+byS=>K3D}x|1qj1PRm2b0Y zrDJvvFgQCGaA%g?>oT^D*d{z{oY8YKv;fr3<~R|-(;9D?qq>U!*)t$f(EI9h_%}%> z5Zy+7+nB!Ztp{qluL9rjpZxkL^iB(r-e*OUsP#!%$(0$#R zDdT^e#DEFhDJSsW+Y)|%u^MyREQt*N%gZLz7O#!kxtE0`*#1O9XOEd-xFur@=H6g0dGY!$yy2z&x=gVJ!A)p?6MOpy+zJ@D=j|~$qd8rZvO|5qxi7t z!(!^fil*H^?p%xGAdab6b|W2iJ>{wZ3r#mWyDJ=gSmB&|7<69p} z{}HafS|jM#7PgYF#jgb9yM1)f3brFb@4xqwiTV*!?XCuwVsL<~s&EALx zAPbKL0GED!{q`;Sz9i)G-7AP9_uEhED?1Dz8JJme$e1~tD(i3E_|~Oj^PXv|l4)nv z%o^c81KIix3^0~JD_*R_)pRQ0mIIZ2IVU()!DLK~jK3$>;_pj4*v@Ygd{Sy;xOe0C z4yB|0k5>aNnL=e!E${wP*3x8+=1j`mUev>tIeb4SN+8osI7Z2?^IT-@35X01BUF+67J>yaKJ%p$Jac>AM^uh~BY2)ui4JzF|| zwr>+>I<&z778>_%1IuYq@p&uvF0jW@E2g&4mV||&E9&jm%*@Q`smCyfiI9YG-YD^I zPbs;!F#B3ZBiqMB0n&0l9%Ti(mgzbQAiF=;N3UKqv3L3C-&@UZW6YA;lceB#w+BE% z$9%nfxn4OgwFVgDHw8F5>|=kjnhgMu+@#E_TX>ub zg6-$t(!)u&{i@Z7qs@$(*Qk$D91BJzYkI*F;)B;0E^(_EV0`vm>J514J!WKR%Q2er zC`EM8x2-7ESNdOUlapwql}g|iDT$b5jUeZ%s+vz0N{fQe63hC`(sDMnbw0IN3KY}z z(Q`I5r-vPnXRTK6?6?aT_u%dnt{d8%WJ!D}t?IUZ3ZHJ}pJ0?-9(?$7q*6n<~Qf(X>C_2^cOwxbGBl-vUD|K2134v%^ z3dj;n`Q$*A32lAb;&Zd9?UE3I+$^rnBx;7-@n?F2R%?$zzJ2|gxdWh|1Hkb|T4?Ps zaiC5q@HG(;ZCM!PLW^7Rj>q?3(T7*4?VaxZMM}7=-f@ICijnFo!ii9D*I#talxoM{ z9`~Vmk9SPANwY1itf*XMO!&V}MCiy0eK6K1Z?DU->x?@G*M7@_ovvs>Z{#K<8Nn}z z4?cs96J&KBK}c9cTbTXZh|APMhO(wK4{{GNrIWdBUR1bBw@WC zLy>*;Z-&?o3Tc0?;}Rb)FUHU?a6z2t;OL$Ae_aj4X@M$)4dTcz2&+kAg|@AA9FRTx zO4NX$i)CDZ8&m0%l7+GdE%UF8kA-EyGD7}&X+;WxvA`rVgl*;aM!O2e8+x|pt|zP0 zPq6I2hiv|%H}W-&Vmdq^CKjCuFeB(?0$K^i=J#k6wLRxRpg$_FC(Px&>ncFo-5^nd zRk4K*=IXMbz2LjTz#l?^C znCSDkZ&#)!WI+?P`on0l;>v_cI?N9Z#f`_yWdI6m?1f&&%2)}7dup1wM*DyMNYKBWik4N1P_tW=dkE(ftLn&So%lizn9ov3UP)ydFIoB%$VHp{vI-z(e5a=}{pYM=89wLW3g@rp6mOZp7QU6j! z)VvnzUQ6|fJn%^d2$CWQ@7?B_FQlrTQL0%d|EVLSM=|G`pI!x~x0s@~ze7OPIiYtS zynq9#Q+}?V6$dM!SlU6YaJS1Jd4s+`9tQb=*EccWpZQPZ-nMn|z}o{YAgfJQ^@#TW z(;n&nr#*eCzm1h?oRh|+XZP4jW*N+7LS6z!jG*0j-M{O~Oc=$lZ%_oj5(?J|pDl5o zgx4CNP&slYf~nR$4C}c)6zGxKrxsa1S&J%VFxwMPPTTxR+d;Y2!?u=sKyq9ZV{+%0 z`ATjo&NM`qTNR^MXCzn$uIQY`fk+vzoBHia%N=4!ak zbGtg4dZ(sXag@XZQ5J^Esl(M&-Fw&`b1h4wC#jPCB2o8avmnznN<5( zScp`N_%FitII@7UT}8ErU&CDnp%bL&W=iUQ0gJ)IM1FPxjkWEeR-|LcDA5337?i|x zTly>Md4!XE*JG~Z=?0e7-;a%6B``-}hK*MYtXNAbNPx+pM5ldFRfn@iEYC?Ig+mda zTLsbT7mQFan9L!RUvNM)@GyUGVFhs}<;`wOyXo*vLBE5-+&66FaN>#A;a$PgNDY(8 z)#26CxH4{Jy)&~Ip&>YT^GPw3cLVY{yX9TA4Rgx<1sg;Iw~vC=!GNdo*qL1kkzdHT z=YRL1*tfo%rv9#pD1kK!^ezb2B*U9+Y}GzhXjTxTve{~w^XKGDVWR5c~W4C z3GCQW8z6r3c+9kgEZUCl`^(fo*m0k#;vn3tfuh!N*PW9aQ+q z3^}^TMz&&}Oun%pWg+EU9gERu8vXS1)y4%W=OnRc`zW=PN>(iMBm~yh-}9Rk9$jB` zI;`0(?)@;732ZOdI!{EPy?vKL>=VF}<`E1(m%+o3y4GRkG|d(;5k*Dm?s-f1TgLF? zd^vU7S^&~j&0c-LM%wMkvJq=NBn#DhAT8E6)cA69rp?X9Xk4L{X^LA|D*HTdc5i{h?-?Am1Uz5iuDKS5A^OMU zUKT?39&`YYpf-UeKXR(MWZKfUi7ye%B=_3@lbAGSAuD*-56xcDz|MU+Vfc}i303n` z!&_a(>ijv_Nrz{cFPb>eU%U^T^jO}ITlbBB6VCo$ZA9WlQ`kK>%H{jdQq~mxmz^Yi zc9`Oa=qQ)`t>=$+VO|(Dp4(mlFxwCS3X(X$q=tO|3-a3Xf`m*aP(sAR4rw5DJ61s< zrYgwu=Q0NhVXcc_-*TdgV{DL? zu^*hCQy|(?{C(dfKD-5VJUnRj+^?j6s;{Z6tTb|}3R=nJw{3_u8IR|S z`cf;!KBgX+ZqpajiC0#zWSd0N#@ua@*NCTSa+VsUkCcf=TgDubg}CLW<-KV0r}`=r zuaxjN4^rM@I8W1WGuwgI)WCG^KjbH0a;}G-oS5(CPrTSW6wO_WT@IAl*qM)04drR( zOEsD3!bW`HEeFFmwdg6UQ5^J|e^NE`JMh;{oDS|UCMk)CX^@kD!bD1wj@pxu;Kq0u z-*`|M_*+?6)ZLCgcuqlG>Z;s5#&Ty3I2HlqnVN2*nik&mU zTW&tZlZ?K$nccmL!!U=pwvyc}g?+z1je7Lwg0%@6f~k&9xqjw^1%{H>aarM9_wVL! zRlDTEdDG>4|Hc)vBHm)!g<(&vao5(!32n&O4!3KSh>ri0NzZpKAAZAefy8${-tN~z z#&LpLLPi~I*1=UoPv}D1#F%-5UPV&-M`-WhqR_||Jp1fw#k#JQ z-(L$-zHP9(!ptuq5bsL0O_O#oYE~QIAOe*f;gOg%{D$`9R@~wKpyV#6AeWK z*gAOr2$|@^)=K2JQ`Yxr+H7Q_66(OMDjS3i-oKraY;guPr*Ch6+jxB~_J3(`QO*|{ z*iy(250{2hZ{tDwRKxNCv!)!7q<f^ty62*1+K+kAIm>*!EB<}dX+eDb zR{K)V5u)&j2qHIH@H3L>*G`dB&UBccCMQeT7bV5_*}Wm&I`f8TlO(N2{D0Ee#f(x= zWwUO7>Dnw4%3Qkk;~$W=f}fBGy=XnqD4liU*p0N(7{E;TA~W3@YFgO`-6dmbx#Lfy zoBD;yHYJaFd}&Z)w}-PI?xibP-Ctv`#WszlXVx!@e$_}ql#3qPl={BUIccuE=p^`~ zP56*bJmRF^ek|%it+^<5crd2vR&PFkC5sle!#0BLJKeSR;QcL#`oX&Ijev?vo=|@rr~R!*V&{4M)b#Tp&E@G2)JC21)NsDatqvs>D${uMm5SsiiOrio z!FEZUL7FknB$AcjT=6?bf|Ukg)w6@@ijGhFc7A3?6;j~r=>}g!2H?NF-0gs=M4+nf z_35aDbgd*z#&Dx_~<@rGj z30RRwYfFA$Vle%o(5ArZdzKfVHNNPrJAry#(38y*ROzQ31U;Y+U6;Tg+_w3ly-!DY z+tFc9e0k6=DR8Qvb zqUaL4kkI6|l`wET#3dwX?w=BQFMgF*K($)!LD9A={+~G|0>xMb@|#4@cFE(?wFPLd zrVWJFZ>8TWl6E!jvM+ebu3?ycex`y~LdIonBS=`Y-`tQsE>(Sf3QCw($~Dbj@GK@9 zu0I3L@)D}fy*+h)`Ug_>g_<@Ao>eND^)Qe-5p<6$zO);U1Jcv|u#!Hu1)PFi}R<9g8fZj9(PMh#FoN2vH+(-lBOg)!a*Rrb03546 z=&^fQP<*ezL$8uw*bS2lS<^SM9=K=rqYiI`%B$N&BnfgLK9j}7Wd$FS#SA2y{Km+- zlLT(WMXN+Fu={jRr+cuw-DNcGUkRx1d%j7;{H^UdE22GbwwYbO*cx(^h_OetR6o!0 zUT>!C-sWEe(V!Q>DnfE{OGwKI=q*qDKRG+fLK#v%g_1t&$*iwde8(??A~}A|P6(R`mZ3TG{# zxMaMEWg=ofG}_W(k4=*=HjL5`@LViw647sUELE*LJUX2D1LMiO{R_Bt!vlQHLPWT%-QC%pXRO`Mj z_l7VafpDv*p12qT##(IZ(l`I5k){x+nY{&C#@W3t&Bo5hLh-FX&kf_sa~5%(Dup$) zSdqXK%ipT0xa8;D1HPspM#sh&ycOy>K}Z*>z~)q|aL^BTm7*oj`3^RzbB5;)iBHW$$kXK}-AO3D zTI&r^NvMTB%m8U-4R3+P>}I)akcbyv-gC`0r?2Lwpq{sb?#WZ*w?S!UJF*o+uK>JN zElo|$y2?ruK=N3>z&YtMJj*LAcj=%{la?sSMnpT0mwA`vm^9-m7!j_Wd{q_N#QmafLsOtEaPA=W)Xc*oK--#mS&PBFrJSM{v=7{Wl>L`hvMwiKDjb0h+ z@0*Bv18QO`Gs&OM5DUXUKz|t7Hb)Pfsa4KJuTc)3g#s-rcneHJw5RTlDi-_0E1j+iQxlCfUPB`8Qu zuw^3W{8<#){5kG)N@b||%bt)&FBbQfU#aBXRS&Ff`LHnMu3qB_57|nBM?t=wwRW3z zXOoo3lJ%!=t{+cAxHTatgL`vsq@ELgj=IX}hi|s>9Y>tq%#wQ`bIclX^|Y z`Z2Ek;wsKJNtqX#wfT65qPr)9g@YA>1P5v}ax$2VWWJrTh@eL6kQ zUmpqeU$uo_LY?;K+09ves68jNI++I5kT&4#FIhRvBNV%mA-V;P z^WJ`F)u%UE+|zn$pBJ&u`#{|#XY%7dW8B=}EbpSp3i!i}*C|$1I_=ebK(q7&&BqsU z4J{&c@?b-v6fTZPwz`=Pr*;#WK&H#bg7JTfBsCoOv#+NS`&-p;y&~rAIaFuU2*f|F z6h-IwQPsbIE~t$?n8~@4MhVdDowTxZ1i54k#^7}e+Jd$i5&}QDo>x7;#f^vtrH_q` z5w6xcbf#rIT^5S8q=PTA%34~|Qf7D>97c#2q8nB$@+06LIO~*nz2|f8>fYXPV6Tgn_SnZ!i!a$}Xxm|%SRsah)=n{#sd$>qVe6t%~CKP2_z`7wW0ki*5mZYO+vP?AThh%-ShQ7=Ehzz4jcZRd%1 z&P?-LG+`!B1AD7tP}l?lo7bcp4g*7{KcqKdZY#lmJ$wBYI_+r^>3;F?H_6cD6Kr9~ z-5`Ak$N9tC`@j`$Ywmb0Cz>OF(a#dreUh^_RNWu+An>WE=jZm|1(Lc$MRs|G1+lM~ z`_Z`f8Aib=b_eSXatvVEy)r|RfHH~z!pF0v-OL`f-H9q+XdRn}hX>G@37p2sp9EiO z7e}E$Y<2>z_>>7`joPxrQi{vt4Q!fJ70)LCd(mg}(^T;Akq;GxDIdNni(TyZ+sA34z&lyt?xKh)s5e9i)MV=IJahlmJ!v*QzFq+5r+YAd#xk*v z6%|pr6~C_ai0j9RzFycCNpuqH`+Hox0bk$@D2Mc)sn#(Jka+~DJ8di3j$bI?9|c+U z7sumuJ;M09ArR1Zhz|XdnBC@%Z&6sAaEjmL4v}X|`E+FThfy=ni|9{|%ReAa zqX@a3lCsWTUf4DfLYF$Z9FD8%wXuh{!>k2K$tEpiHzB>S>jv2xpQ5>IgF&46k%iU# z6rT=<*gOe{xLjr<492Lm8+lG|oBYre+i^C<+RI&!rIM;nl;e5;!dr)dwpF6B>qw_W z?ei(>#fE-A2qOKi9p0P3S;IzTZJ#q;VOP^2CO?woFynh;fAUw)G}tlV{og*l6BbVl zcBOZ#V$OLVjG6T?L-Wx2}N*>b4 zoD0A&FX#s4FSO$D3LT6SHYx)%`f3dep!`4pH}h1jCO}S)>Plcc)LoD3OAXgRi|w_! zsBbcq#E*M&o*pYB89e3w_|XjRe*x69CQOC=|bTz z=mBdjC+Sg$BM57PhCD0H$1aHUu|-c-WwZJK=}@1I2@wN`e#AjsW0 zv%M*IgF$iv4>s@og2=N(!?Xm0?dDFNgPX#55^XKJ4^}EfJJT4qNI!2#e$eiI$Jc7f zI_=Gkoogs%zHVstD!Hg4k|9IxQdfEVrZ)3Z*{hxZe6T)`W{e`&%Oxr##ja}lH_=x?)ivA+HOvoNh((jy7vyre-brY|+ti5Jn_HW4w9$uJ&MSjF7= z=rKx(mv_!?jLtcFbWeP1l;pAm?^9V6GIS?&ms#}j$+`8|&4h7QN^9(kp9)hNukb@a zNTLeGn|R+r=KoxJv_?&Nxr?UUcl?&@q!b!*vLw;LK44G8a{F~}`(ad^eqGx?t)^ZY zD)`oO(Y_{<-Y7L#MN_MYwkv^NPSg6UEmiPa(Ur8FSFlvNY^CpPjX}t_?-GMrNar;T zAD`b`r(ZBFU)mj+C9!MzRt@*mJKWbVwYy^e(uxNe-B`mdnv0(7cH$hO;Ty>ndfIY4 zAhjcZtiZ~pXBILBX0Ur777u%P6o(@nbeO|(IH7($Cw{0mz!@K&nEdPR@x-^;%y*G? zjU>bG>Tjw#B*08Y)xPdAOoG?`9mh%ID>1>|cc%IVKE%@GNb!x4t{5TP6ZzKWX6Hl0 zgqua)(~w{HPV-a#v%#7+5x~LL@_3BRpw`}l^dM#%jG@$nB`f1$=*eQHJV%4gTvG0&JjPToQC^Uf<_qvu2dYRNwTQ0)?i*zG$&&2*9smKA>MIvQ9~tcCg}p-jlyL zVV$>+cu%zDHy(Eo6kyfwGP1+NSr-%1Jc6Ex*v^i-)s-yRB$5+HqqRmgLW*{dDy02W zcp#D(?%T`i!t8 zu$%A1uxa8k2zJ4&1u~qv3E}a3pU>ygtUe(0Msep~A-vRnte21-sI8tkU@aitn(>W3 zLQc(TljY@fnD>NJf& z`qxs}Ddh0~4 z{Z7WQBY##s!)+*1P8PEyUwnI;F;~sC0>w8aICpIr(eC) zp1)$5(u1ig@cjzz_Lnhivl2qy3he3Z32W$dm+ava7H!Ct^w0aBlR4L2ubdoj53*i3 zY9{=~UzpHNlOzC3P3hm6#0S4u;}W*nEn@oF!f4%0$HWUe%1dBG@Q~?JSk9It?C>uCZ&}j0xbgh@y)+T z<1E)C#tiqV{iWSmiy!$~vPtDN77xk6(8dG73WnSh+T7NLY?{LI5xhS| z3>9sD$il2M))2DZan#^J(fTi%wPN4ju@~c+WY}lW`PFo}dCx zKL(;0rDh=LsplP&+eqCk_iU(PG+P6!JSIfHz(1{ramXAo$Mkug?>O0CcoE02R@tG{ zrGhxf-{-lnsAxMH?gl7^JoohlZSLo>MLlI={n^jwczbhk3Skq#H|E07g;^?UI3In~ z4pD{yVLtOE=mKhYqKDp;7{p_1etyAhx`_`M^-el5h0MWzIy>aO&c)S!8aw`O7#M7^ zEJouUeOEsc_iH&fepPS_23qj^%MfD6{3m>()7-X6+*KlneOV3|^*kH(`Kk z=A7a~@I2`?0&w_URGgVJEN5|J{X*-qFS0*0gQzGbpFRXnG5(F(fLp`x8EE)#rf$$C zj6|7u51fwNz^^E3awb&eeVT`pM3)AwPFOnm&|M_Tr4q56?Ooasp7<4c!_}B2OLgsK zFIw7L?X0)RteKju;0%MYocDZ$JTFeF*%V_>{*VT55xhT@`MmM7K>J}^)Fl)>xBAx( z`GY*1S3&FyW}ERapoG7C0r=dEqZ_V3{ghme1u5o8VI*0l-*!wbH`=y7p?VpTUu>~&(tcO*Ygx_(bK5x&X= ziC7sD6`-}b6I_$UoHmKrr5)rl=@xSxPTdoF(z1MSlRSLuL+8lNXl9rio(`rOF|}Jx zFsWd&X&ziPJSCCU1NGvGb)^=!4q)(StUlx@88jHd6++S?JA0S?`{Yz+E4hvp`+c-s zhZ}ahcd_BKBvk4}aEI7O$5wZX!gd=22Rb$IdQvqXYxL#f0EZL^iX5GY11;b%sxU9OjYG}OgL1g_Sqpqn>N$%2K0|we7x3> zjEjpavk#@jo7ad$hG51{Ta_2feS@s!rG4b5o%p?oNvMOLh=jlc**m{Cgwv!t%G)>j zhC`7s0z!gw3F{?UYZaPX8d=_Gc8v3uzlNApw<7bxI7=B*0m+4&KQ^JeVfWCmdy=cJ zK;o>RSO>peNr49oq^H*peW#*u`oT&%kSd$kd5=lB@{lNB2Kv)cEz(Au-%!sF-_|Af z@*PZAH@v|F*3T`Q9k%f)K>BRdtlwFADa_5qH9J4=3z~V=G|>lS%&1@yKdIzwkUgaACGD3EBr6(qZ$woB^+KhY^i$(-w>k2TjpuhAQ(^(`vZ1ydFcXA(-I$wV_7!|Sud$NVL zK{-^^pSIftD+IF29e+ScnC>`=@i;kVDqH{TPFep+EhyDGs6e!QVYQvdRBys+d;VN#OCpIVj|w^eh$*scb)T{6YRvvugKUZumaEkZ>$l7C zCx7r&U0Yj384 z8y`g+XL?4rb!U*kY15{A5Jy9RpQtKjhQjUq2ApVD7fU?5mY4NS8piNGQHw+5cFo8%2qrbKYgu&4)`yzMKa*Ea_J0%+EF zX$AMQ(*Yd#Mhx+FpSCa4X}7a_hF`l8lKWP$3K^DZ5+RdM;RfFp>lUbF9t)%nb3;T6 zRyUmFNSOo$xt^!^f>!mn4!znMMA<+U2Tv<>%g5?b4uP|2!07wABG6pXqdV&qa$_KZ z=WQ~X{K&395Bs?lL4Sq5AQwE~PKoTwBi$r>;z6s9B9BFqGhBGF2ElE8ZwxSRsS3AZ z%ZHI9aS!px%dQ_O^6H>w`luLUe$PIw_7#UF#@Q9yx9fkqo>64o=-A|tR3CEAJ%utX z<3LV;I8S@X#vjgiUz<(E2DZ?;PUPi+jp=p#lhtJpA#X^o5IdJkNK)Aulc(T-n`&QvZ&y6&1MnMlZ5u|XIvP9-<q~K#2eF3j;7U8fjQa1anzba!~a{KURxzRIoH7CAzAsRdF z=kdJ5gYJQh4XGZy^u_WHb-w`r1w~wSk^gjfkYV^$K%M9Ji68GcfIA81l6CUwjt$4F9+La^l5^>E1UEVYImNaqiliMU5u2^QMtKp8NMs}Zclke|4 zr;njc9tU(1Voy$(+L+0emA*gfIL8jB$35sC&r@~lPw?xQ{e{OciY`IPw9EDmAEMgSXza?=M<-J(o?0m#r8+E#h5EuuV0Uy8^5!wAJ; z9IdQkF1pi{w_>)ed#H1T(4;%H41b86O@qPERwBn`;@g+bu;05wt-^Env(YX8!!hKJ zli`;C8ZQ3eDPQ1+o7m2E_ZfiMlCD|(dS>Y{8`TSEJIPv2<6A0d&Zf!K0jcz`J&X@A z>=FP5p*;LXb&BS96<>DIJrg7{0(Nn;%MQEjVU+l)-xnco_!H<8M zcCe<{-?uk!u(01Wj=_H}&%-cfqs?)EDl$*Bm4OgJ8e^xH#Cd0|xcjJF>a#(L%P6?_ zsJ3SxpzQ=}h$Abwmk*48<;V9j515zdJQ{DOzNJ5Mv@0Lj)`lfGo>Ds(FB!0zOt7SlVJMd=WcBJ9EaBn&Q#7=pR6K;2 zVRW6uq+DVhKKU%df04|$7O4rg{qvzTvh!254+J*>8Cej^2^-EMm9cUwEC&9xqV%{FifQOOLr zpR1-&Nm+cA>?;|(kHB%<>(d|pmJ`dR3~ak*n97(6d@|n@Gg#m`t~8wfrVvdy99Z4e zUNYEfcnl1A7)omxypLoull5zwcR>e(H*equX$DC}oXN99CWp@4y4|}KuaBVyD@64U zyHjC5z=h4I&-pe2fi}4*@jupG!fUc9YnKe7xbDef+z$T4=6LpoI6;M{^h!I*oq~5e zxa`u(hGRv~ylxsKYTUz#T zO8%C=DT($|PlZ#k+weDVrMu8;q^|ULvf+jiO%`Ye_{;xi0kr&8jb(4wXDFi-g7_2Lq@0`o#Pn$I{L!b+%u}oi;pZu{FK$@ixx68#`a;?-7e~r z@J)%-xs7s8lPuAk7!rb>ldK3$hoQ>SEkAWT6^1GMbdL6$LprA{*M7eSN{9YJa$b1n zIJ>`fUZQnNoy;c9{kwR>H9ejk$(G5(ZGj)Ccc!`%bXicrHKxO(iC1395@mLwOd=84 zepj|_{>cpSX|W@D*Mrg&V41Os|9eIa=!a%4CE8|p34n&*mOkthH)&t zPa6D4Mm7w_6%=UL?<>SW_RBJiai{XG9q#Xg{=+oT)?YY6zr6k%)^3s5CFgKHPAz;0 zK$IU0o$P`;tD)+8t4DV_8jnUZsvOvMJzeV6QxoLo_5g!=UyuOH|KM?VpnIEEW%9fj zBkmSay-maBwV-;&%GE}>Yc4Qgu7S@QM$3VkZnX(mNrvBM6)^5ODhfQ|o7(!V8n-)DE$c!8)^z*H*y_&}9%HVr%2g0&2fQ$#F=OiDk&8&3cD?`@f4 z@S(iMe^ts6Hya)=r1u#Jm*WU7Q?m~&@DsM`SLjXMW`MNG10q@#(rb`yDY$nZk8_g43CN=|A_IgsWi~+5EjR1pa`O_`@$jV0z{fS$3}qX5#ZHiowT_b3$6h z?Z5%G6LlSH>FMcb3NL(lMz)geg9>f%o))iKtJK?RBmcO3&jBzxVf1{5@^nH208>{? z<~p7B&*ZEKexZ zB&nK-7Rs9khl9$a=wSKcdV;EOLJEeZ#16{8E({cCQQ& zX$Zebkl^M!-eR=CC<1T79GeMwO6tqeM3gXewoxa4cwk7P3hmL{usreHJS=GIEpWR0=1B`uQ^w7|<|`uG4n5HS^3XcW|J4zCLg&9w zSyCsKoPPMD35f*FQzz`PQRy&y6;Hgg9gr9PqPJ(nK4Sl^ognBZn(kq* zsfV3*vH>2yeTtYi3Z`96(?^4}dD^^bme9sIciLq=jHwAeksl1~cx%-SxrB{8av8wZ zE801yqV6wjhwtmF`@wQG4Cr_4#P0J95GiNRp&8e*dV(ZEo>DxTKaO;v%EWA2a5ZU; z?;SI0*qFMdpw_#{ZWFo)79p#&f+^GNT_%EQQc<0SDY{w42$ps&KO0tYzk_aYCTf=6 zVVh%>$P#qfpb8N2oPI6G!%gR8d*?$9Yp|PRSd)ouWRL)Cc+CHW;n0xNB2It$UAek2 zW#F#rQgIV-RL;-a{^Q2_`#H4(Bo+5zDUX5SU@AW&f-m!OUaIiMwYlF2SL?sg0CZIQ zUc^<4{78IN=^h*5Jvn@y8gp;}(x~MI*^pQ(oW&A`(gPd53wayhWF-a^Bt-Q4j7J|> z88p_F+fD5+Rt0e1^<&nRy4&KuygaYEOb~SjmGaG0*gL)3eMv$v8f5${xNy`%bJ~Qb zvq|*XETTm1Dt-g5{JqIbLq7H9Xep?KOCK1JVJ-JLGegMAOE^G?^uxY<0B#r$Lf zg1O#fo%cSWR+IPOwBW!80F$L%|A_|;G81*|Gd~lCee2{^3Jl_^-r#!;ce7b^5b%tr z?+PJY_5DsAUN?w|Kw23=5Ubt_2aIgUIeOiv_6rhx_gJIuYZSLya{D!t0c4{+pNN|2 zN!!>Z8yC_tQPEuJ=!ny6d4cxT%XU3b?%wL(UxCCIBGC)XLeJyBI*M@mD`^S>_7Cm^ zkD;J~uBO25ycAz%*wmNg$ldsq{`;zz=fe<4G%M2TJ@nETXBFdPS-?Cg1=heb;7)p$ zK0-IXkS6^zSxzX|#aI@XtD1NicIJAA$=QXK24?j4Bp9Q;y;}BD40@M{xo$k9XucE+hT{S z`WsJ%1+dYEp|(z^EJF<=SOe>~3X;?D|M7NMOXD@wDS4=TcFV^buP=%`tkCwZS8z@i~fb)sXtzheEqP3n6Sf%&rKj+?3<(js}W zDou?A{(|sL8ygmkMC}cJr??_j*lH8%5cJPQl2OuIdxUd7okibRi!r6rXtPtT|Ll*D zgl33?re;sCCSsGOCX{2pZj74Vz(1>Wb?rO;JG*tN>V|8QE)+ZaYG)BXv=i#XgCG6X zX|9Qk1du|MA4;A7ZYb08Ro^S#6w{<%O2e|_?K zuR(pvs_Aq=0)X?%ETv~M0iBJ3q~GFMB{Gc1RQ zRD-en4LHV9{u7-=2B0fH(rFxF-7z9pejqLnR)#DlHR@9>-!~7r`Wgv!j>083TBAQM zC*vr?a5bKz_4EKKwDwJYD6Oov~_s%OsS-A2>=Yn=cYzY{L!vg`DhCX3k+W!VxUCc6Zb ztPr2);e$`@jOjS@+olM6e_Nlq>N?xlKa=2R_vUzrsBtV!Z__2O^MbqITe;YgyzMzk zqxQ*?@Aps^{Z@{jc8@uohxHHm?PU{Im7HSj$t*~LkThozLch+;LcQ$}^jLGh4z^#h> zhxmr@$eH9I)XAB2ZKk>8t@WLgY}HLR_igHD5=a@U;;fR(FV-l*f!PdTRxx}`10ic+ zDSrGWervev3x?)!M_|ZsV$_FC%ZLw#a(>I@79&LYex~W+B*I2Q&LXzKYz{wbYvT`l z*}vo&&9sm>9SnEzxV(VvGX1}?JOo-s0uP<_YYyNpx6}VbvAu;bef9i}yKeR~3_#X& zNX3OZB!#ZOKysnFPSkU-01C+NcHzXuW+H}Q@8yAH04Az0ohVOKFk_qozzvgun<_oM zG?d*KSPpb~&I27ThN((LEMt{VE8zmA*axL?X&Nc0)L1!$b+uix;~2YvExHs9ZT+$Q z8%!AB#(9&7MLv9sQdCY@PWhSdO)0uTs(qEL{_hP=Zey>IP&qD3>K}sU0^fp=DVrBQ z_|@+Ii6AfW?^YCeNIEC4TsQr{db_Y@-8Qh?K%5i7s?Wpe*uaB7TvB zK)pK)W%&Ql^wvRb{onI2?$8#eI213WxD{wiaV_rd?(W*6rMMJ#2u^T!r$~U{#U)5_ zfA0J9eSS0fX zM7IW=ozVKX__&vAqZJczpPKDp3r$k2<3ClZ&-P5MlC)zS`F?jN8sD}6L#vhTnnEj! z=ZG?tdP;=?j;Q6KL&+NQ11Aa4;I8tS=6_w;kxU2=tGvH@t+-55X;?8t*wcbjcSjdo zt-;o-_k9C?$gly}Z>=F&3J0g*+4|_A?XkFg>8C2vGz^q^vh5T%iz~ zfw$napWbl|>o4V>mrk#Q>Z-#z2m>E|5E_$(^5;!A4(Gp=T<#ott5UlNwp7LBy$9IE z(#sWd#{6AAk+@i+c%rxE>-nF&%EY@y??2rPMFCNpcZheb;k7bF2#z{>b61Q9e*;^9 zEi32q*yMi`-^?Ui9YoD>#9jKe?0C$47}O1juR&C2vqsh`OVcX=c{kX4LQk? zjqq0ww2$d>uBMC|rA)V9I4I{suTWaw2^>n!`UN-!Gf}dI*i>x?9R$u%NYQ71H?|!K zT40w=L{e=1#V$LWjVW*-d&1{XPAt6LvxWrp7FIGats2FFS9N0xuJbCV(2AD!v>yFD z6I2;`Sd`AlJHneEASePA3O(F+ciq?Q+Bxl}oOmCn^|u|0$k3o^%v*iM&+y#z^&F;r zH!;7G-DSg?v}+tf{yl(?7Juvk)B0WSMQw``1!La)+%5~`JG(w;@!#?r0FvuYX1Puj z5kY=`=*Hz7UTv;HU*A~&faQ5_tlD~Cdl3M&F^wC;)z@8G$0P`D15 z$5`gQEDtYQXbmD>JdqQy1I!$X zMR$!SbpHQ6c^JJxLC2q5>iK%?jKBEo2Hguv_b^_Cncd{In*kfpXpSz-hfIL&se30T zdQ;cP+G5!j%x_}bDQcc(I}rnpo;}d?M<}&(KC5oEXr)K8k#Vhh0{-Tn+QqAG9S0w$ zq-wu^f^Quznf=6F|7~N&`CI-RA%RNXtPI)dNIL$F003{xcXVI;$ogdihn+u`+pUHX ztrlTu;I5 zplk@I(zIRV@fZ-2SWD{4AU4n6JsUURCF7*axWVp=?N!xZCtfv%l2snk%5Z|K=^@Lg zj#yj4_4zR{bmro4@)uG9rbY}ON1MyH*d^_ujD>10#Q_Q30v-T7>r5r8mMf>+loDX= zg@eg+?{c=@jfq&_lZDwE@D%k#eS^QsLHU?Rvgh+-}~lMv!cben=X1+x%B$$jBoo z&2{;7PwA&@*^v=`>Fnw@tlph|>9TAOlET1$ZEHdVl{YAQZZ#Z%wCkF|-vXng1}!=b&`NP1#+$layN}gE=oORRWUkV0CSkz% zL0#3-Unl;auS^=MJaKlzro4s-4T{WBpI?oKG~U12F5k(^0y+=|#}e@@X7z1_Z5r{c zQ6P8vuRrLK{j+$l%y&?Y*7xxdJmuMnzxZl5!Bx6F7)tCUt}OHch|}5p#-wjkBsU8Y z8G{!6#uH+R^q6C2)gR4MSQ47E!9tTe%toh>UGJ5o!sLA9u7T+4p>SGF>Ki} zdXLjFa8;Cq68Gm*F7?nVQlZ6O>+*Bx)ag?sA0OMqD}Z6am}c752n2N;*9i0Z!u|62 zW3N%VUe4*HZe&(KT5czEfa%rdZ@64`t_Z=|FE&Apq!{{ZDPQbIEz3`N@4QMKgB(Ew za^5q^S(RVg-zqByH}o;|jQH{REfQP|f)#pxw3|g!{u>clM!1bK9iV}$$(%JH*2ow= z{OCl?=2INPs_9U)2K*oe-Xj4+e{JIiu&cIFH3zGfr~HkB03+KvL1|n|Mmfv(9_^xa zpnLi1F=ooupBQwK`bY3vaPkjV`UeB*o3p--P2fd=3eFY+Y(Zb-w&8u+uD}C+4&?(a>s!oh)NAu|_<05ore_fc8K zrQP0ten$t_9Fbu@VnNx@?n_-5O zLSe>_zlP?k#@uBis$yv2uoJpQ57HMg+m)-r+(EoOi2}p&Uw;P83B(MqQ53Xu-WJJ- zn0)5wcoziNdgWTg+Pwt2_O)s5C=`l{<&*1(%VJYsu%^7k*+p-4w z0z~Q5DA2^oCk9Z!t%W4izS#Z-aHS>kygXfGiJj4b0=&>cqLf$W!2^0jrP!!nWa*8`-l_!gkMzLUX zfB~z<=dxG*QqFMA8}2b-9)bVL1<(wLv#Jk$zpUFDU7KW=5qF~KqCx;#3M>7eXU$wT zi~&mn^b9yK@8_!{%WUV_kgPxt4^SVrFH2Tg_!5_bPdMA5a?!NNnzi z!xRfqc_#d-d6Wx<`mzK%?3j+UA@wprx~_<6y7aPhx_AI)*%Zp@3-P0yb8=`OsMM?Z zYiuUWM7apvywu<9{&Cj3`F&batB26fAWe)~r;YSk=3S#Qoy3oYI*O5hZ~ zmvAYp92-HKrW+ece{qev(T$fcgl;GNcwJDSSzpf6{R)0q{!n&$(Nj-6@^x}4s~-0oZHS8QevQbzNj8(e2uBd$Mrug7Mk^hYi zYBjLKP-kuUEOFi8=H>=9T8ZCy_ab{eBvwgq|1Pb1iFmy|Sxvh0*HDPCD~G3hOBOad z%=g8a2EwRN^xfViv0T1UD$%>XiCGHrk`wpyrGy8{k8>OxX2XqW>ic4b@KE^pBcguc zA+27;z~1+P5vNblywiA}uR1)qP!0I~Q<}gBEYZ`(Qcmo^)MP|Ja06UlHDBm@A_{W}4?-Tl@H6 zZTFdPRqj0Su67yr-{+fjPO9jNE`kR< zPxi!{1?fzTmjBcyUs7lN?Z4saBv_=@HRN5)Kf||-5W^R*Z zC==_Muddw{5$m|xyv`N(X^f^rmn6htPvr05C^E_DK-uKi&17+11MtF zpn``W@AozRs)U;ijY1A3*(+~nko&Sh;aOvgQAb$5N9=(sl*>vp!}AjF!%wApwmmLq zW3-!oLUE>IfvY*?pGwd2l&&N&D^7pDM#o;emel2SEh$x1Zd(;J_Ts5K%fq0v^f4`XeR_+X`J$Df{_Zo9~w4F}U*eCpv^Y*lhKOdZpbsrhr6 zj>>U~I`q>8!;N~hB@5%`w4!%>Zr{tj0C^cKn0kK3y}!RGD>Vd7#of+twIjQQ=p~5> z?|o-uwbW!Sc)^&3R3fzj!{=%lWlz7yi;Su~5&rCOX^tiPYd5~0v~45@UF?>BTp}7` z&We_Pcz5u~DLwz~crB7yUs517;dXs2Q=e@5pUcUhV!l41gNk5_3n+@_g)y z*UrU>;YB+7(No#=2L}d5QRW*>wJ*+3iA`#p*s3YUy~T0RjB*ROE#60`r|)Y#56NtH zApX#naa11O?cwL=m*DyhcM)2y0qU|bf@n0h4&vA2waTDg57Za24jf-GH!;-wCUV7d zFpV=&wW9ynM2d2ll)pF~o5PiG0l2CUy(OF>pe3SP3TtRY` zqqreo0w%|5BNtA^(W>9@ez=6)HeB=AVvye&FRxs4-*{$hrVfb^OfX63C0sC{Z(Wug zRBX&{ZTb;pzgsk+=i~h$dnU@KDLToK3uF&##{nCpFoM&r6n6a+m-?@(SuUryJviCm ztVYYZM7B|@<3I2dBL;x`$u>W%v{2JPq}B*w97l7%aSZLYtCO*V=KN5GS|m3kghYUUkDo2AIOpt1K-&2(xDr-y z@N|UuF9(N49woq~Yh$ox#9**W0Mqm$M`67|*`skNYacD)`dXo($uU1KFBrJ$PM&`( z)7}?07@?2NeUHM|?>{9iUj%H-_;a!R97}im|GWSahXw>eD{V0UwMR|V?8y>qZvT_D z3h&m1Ai|GJwoWrC?PhY>kdSN57cNrym;GfC(ItWgdS3fE0|j^1iIW(qKPm0?ZNpkJ z%EyVo+=6Ldhs9g~V;C2cz09AKEO=r&!`8Vx#;afOSGz0C9a0CRi&RRb)MCF8kcRBZ zD(vY|w>QIB`9kV!su?f%K*O3;Sm2n*^7RTJI@>!m^2zSZ|NAqt`g%OZD3aDXPx)Lu zl>bZfolv}IhdJ_f(Dv09sMfNBdi^rj!+Mt*I?R#UtNc^^2q#*g;#!BzC+D@*n|plX zrIwpkb;$U+uMlem?9UeAGzp|Fu$pxJV-0={Smo$iGn=VSP2-gf*Xdc!D?>x0w%0R~ zaOTWwFc}C9LXDTFQ3%n;Ta={npsk7Jvb)*QlP_Xf`W4M0KzThtQrR8h*ZaoJZZ+!W z@5g1T7rdEEvO4qRd_JUxRLUM{s~^COFt~W?JNsSuGyVCc{VCaYIMd#lK}Ig=E)?q6 z{`L3z=y;Kj!P7De#BqIOuod23T+)46rmLOEMM_O=X**~NAe}L)6@S9*vywo_`SjuA za^B2S9eo;VXMI=VSlmV|I<}u@Ak#&6n-7-VxKGxrrYjO3^xNHM#X-4{tKuneo=zb1 ziWK!BCC2>-u9asy?H--VwB5aYiP7L2+V8-ghP|AT$0dwOM%OYDjnElQwb}bI=JJ9) zc|jz^xhok9TfTWvg$KM9Nd6(wyO0C7SI^q8s^k9K=lzF@RwgDz5 z^g`%x(s*mZHXYP3wY4i6)(}sZ72O>z?MvC~d_KXW)A8N0%5-QeM?#>$is(^sv}CG) z+6(0nFK_Xxj?T2dOR?eP`9IS8Wsty6&p)Eg|jKwVLq3 zT^MxXY`de373wg#avMjPJ(ADb7+lu6g%ib-Ph&8OsauQ6G=*{-OaDaYrsz5ip2%q+ ztoCnYlzMF#(!xU2IZ!szw*USUbslWs2a@Zh48PL_3Sc7vp21qnj62OG7vxD0e3ZLzg;b#M6X@Grbfx&0iZ3Zng6&})L%#B3?JZNweX5<9@2vYtzM2?%HXp9d)uo0s zB&9^+D1}>14B+&yCeNs;bGDC^zy*37vk(2Bh%m;Venmgoq0S*y^7_N%bHpAO@npqA zQt#hc!1js)d7ZvUKNzl^{(8yeNu}t?d3HdUQM^VU9a1Snq6de`s=;U7PC+LAlUi2~ z6mr|vRP`|kgAua@FTj412`d=)kIzqLnS`7%|B38Z)SIR3WG*OOSwT$)VK5J`9}8pt z{b1&iGG-~$qJ962aq-1o}K>Uu?KT}tR0J3|bIq6&^v z2zN^8$p1uMz@MxIlrPI4+}hbkwj!<=wqS&i$enzM&xc{YSQ>lQtQ@<(neG%q^_1b$ zaW8;&h62f8RJip?1s*6SfXl-nUx^*n?uL2d?FOpuKiv*wJ;q_PwNzICyW--&@&X|} zJ+AFWWH{kRa3I-D6#k^o0n$Rd+0$c`MI2XPwUM$LkDI9AlI?iY% zrG1WMTNit_(c>aHmiE@l?X(OCN6F z#Pr;p8o6-uNCj{T{?s<2Sya2^%>Rd7?pNx_^^N88ylT$2{A&^KU3w+ug};-bcQB&Z z&NB3mtCz}KQnvGc#V7wbA5e*HyG3SE(!HDN;jWKlhF5_qPqR0-tI5s z!i7f{!)k^f4WY}!Lca6q4L%y*-cx_?sVsFp+ml}@opmY&2djS(s_9TsN6;9YySZ`a}k7P&%c#thh`0wFcH7@yjoJ0JYeW+^nOk$y+gtRlESXKnl8gPW4ypT;B`%yi zsd}2(;6V4}K7V-J*X>xDi1Wyq2f(y!n@5jF&}Ld*F52^ zO{_}I8vLi9blvtIuBgm_0Zl+56SPDnPEKU#F%qa*t>SUqXZb);o;Y`MI6fmFb)9a* zocS<-;B_g&MuMpQ5Y{hBYYSkR+DxyI;BcLu0X+Piuk(4X^>*>1474%=JcGfY&U+e6 z2v)T3#-CIWq7|tyxhPyu-MzWOOeU34AwuGGlQ`ivKZ%P3B;sAEJxtXLRq-`Z%{6sL z{1(Em;Lr4zkxs|-f~n783g9-Bb`cx7?1PH#8cVwos-ioi$(^y39^m5DszhfNg4iJ< z=}Or9xx6_IJ_i$IPw1o^7wAedwe5S*f1EEyZAy%6Q>ZjdjwwGV0$Qn|vKT@ zS*%|Mrc@2Do7RYC-y1H^9G&60@VhabQ=}F=c^gfc&A*avsZ5>-_3|dXD)|oWXkMCPFMeue!wx< z<(Rn(?1SG|oDms>E?)@)xF(>3xc-q;FBG|;Ta6$%*4eeW8L=TUFctC%nMikQ_a0%G z5C72-zlMV-WC!#!;4ixLLlJo^HNZ`D=3d#jUl@o(yN|CZx5^Ngb>?lH=ez9yEWCd}kH<5P>@TPhIRD+9Dm*XTrYUIjUPVbQ(v(=;`v z;K(HQHuJAh`q~j{S96f`pxMBG4S>~{{^tn$dUaH7^Vxq!P|C5*IL}Q5GnwiN1Z$Bp z<|LnKRjehw-{KV@HZ-7VV5mWQ^!_p||IFl-&lmQJx_O;%9~WZ9?CD58_2x}GXzCTM zI$R+6ZuxAg?M!f}gAYD}5B%D*KD-YzW=~hpWs)7gV^lcsGYY0~@cb#W++=m2!M zM_PZ^NZ9P|I!=Vl23K>Twn80nI8)GK_ynGfvhK@Y<6lzV|NK?fc->6pn$wt~S8k8R z{lt(cNdajIqkmrUuR~ViZFqVD+Y&VsyuubT!0!o%xq}oG6xz?eY_{Un*r{cJ$>K*| ze*(y2vi&*entC(F{LIaY2@}yu#v(;X9O)rlIoYGS_<=uK%aFfZEnRseAy%!fvGv}@ z*4A{P>Oli{Z)}H)`ehx@_1`6-5+!CGJ@t}ssH-RfBfI?#7mtV1?aEP2PI9}KgQ!8* zQHKN0q|2#$#e1g-4>5FFMj&n^_y(j*UzNx-k<6CwvV|4!puxwWHdZ>7&*`G+7 z98s6Q;c>N+C*F<3RKi}zI>JsyA1k8o3hm#);`6PGOh25tny=hg_h0YAt_DT3o`98L z^|By&$l9$A9csa*=)L6aV-w57TIJ9mWulc|AsyQBzvu<*$=XHt>cC?~r$54E`5J_& zyAU@FP|Qmxdw_;ARP{TxqqiyL{eZWmq-2`&SE8iw?p=Yhl;6((CBDJ9sMuw>t;dLH z;gtl7`BOq6&=}2RF>>|9nYqm8Uq&7ubAY#^MX398i8fm@`9>a^dp!2hvfc69V2x8m z!nJdu|HoVXns{2-zFUj8OE>aol&4R&MsGLUzwSMk{INks?ubVnimG~{h>6{PNpLfu zf%`PTLYejZYeZumC&gJ6&V#T(Wt0sW=0jWSc+`$~FYB?X{vrlY6o`>lWFNbqh{HnL z()lel9R&&K0%4*!>{HOU4!`*vtgP@ms^6x8)p5t4&jx*}h!>%`_F#v?|DXHG$s6hxS2}#t zM0IXd_L?BuzMQF%PP`^y{J&rIzKX7sN3RC%HT*CGQu4cdpkK?AcR@$D9AC1mpJD0b5LJAMR zt(J^*R3q6ZcJtjl+XQ8X)mXqR*A4W|gMCFtA?7&d^P&nso)23XzD)F@8Q=aM!NmiC zM}30Mn~j$PmNQ^I>a#qCT_PM~F&!?N-sH77C4FpKhovQ%>^&~NT2Py#i(|TVIx-dZ zFiB8KnK51=avTz~CjoCwf%n{aoaz0Xpg>xg@&3F%(ha?2_q3W@efveOxEE*P z#3kW0Lr>9%OyZEN1(M#=uR>}ZcuT)-F7f)KU=OYw;&~=~WmU0i4dxXat$32Rh+9kk?uOo4Aqg0`p-ACFCki(T&7D|l z$D3VEKWWoM)F9|`Q3d3fEpl1e+V(xp-H-vgRBuWH>qLa|03~~u;NGC@a*@qU3TKjj zX`wyO6RR?L@FH`dhq1)j^$xU>o_YBf?vqqn?G6#Qt*yF$)ocGL4T@@~h&PiTkUIjS zHGDr*f)XbK@xd0sg!w!nnMZ^CO*LERfoO3X=BG&65-k zI%~6a@0F^lgn++>2_75!G;rF6xBYM%x~G0YvvmrCYttT1ruF#cE3_DKB@?Z6bR)MT zOYMs*A3r4KBjkEpOu`yqZ}ibyBvklaF~SU1?hhJY$jaO8F}}$75`JX|Ru|(N;b0t7 zDLK230jz7({Q14$0#jQBPTh)T&|LTNt1b;>yJZ+`e}BIcC}dV&{~sB{Dq3LcpZoV( zzKP{)3)i~B-n0s>J1@_?Euloca1Fm=&`QWssI41q$uYxbrGp9~zsDAT+HhSgaa3;v zRfF=dH92QncWcwPVTmE$Adn>^?|DSZeSiSgc zfVFW*<}NW`WoMxC&9<^JrIC{ls!e*t`XCK~k&;)Mt5^TIyxjfBg@{9cb*!?~0G`=( zDMiu8uo!B`*)m9R292>}|5Fv=A96ZJ;O>;sHR;Iv^2*fVC+$j>assf>pkZ;s93*Gk z?3W}Ze3U7-JC7u9+bEsq%iz@312_5Y2zaq3X7HYcZb0eZ*j72-`X~ATkwz;@zct3O zBL%IwK@`PBxP?~NT=HbZO@uyHu5D*U6Lx>^G8#=xYcsXKnMexMN?0q9X$w0$+SvRT zv1d9I$0aJN*rFGQjvbPC1CzO*aC<`;+-zIRkwVJ=N2*k%Cf1@F>yk5&geb*y1l0nQ2cgG>OY|?`=%uCUcr~fbDr;`9|vBr&;}E`J@R__RF?j)fSJP% zg7XGYCk`RFR~O$*p%1^P3Y}?Z>n*=)|FjD96Y3HFy--wky*09> z#wLVdJL2y*;in9@rJ_OZlnSe{78%(vtqZ0MMM@9uqLJ=Gd#-O@Hl%Sps)-k$b6{@ z%I?XMin&G^3HYCBQ7_ltXMwWP)k?R@(r|>slZh6>%6aV+sXb9$>W`7xE_b_@Qd@{) zmR+53aswN;^$&m=Bot!r+4RA^OjH!_*=^FiZ6*t^=_a3EIWOwMr1>(53zJOZ*2j76yB> zU^{@$;c4W8U$B0%wp8WV%|`C0hoH#f*;?i9v2>TMVNE0F4w<<<*~ zvLp}U*C=tEOXLUI^3k1>+WPYx6etvkH^1mi?df`6Qz3GEv zRi9xXnye9{_g~$CpAOdOHRwcZFxEMWIV>O#cPbY86K^J^%|~g2Aio2Or;g9ZC>SQ>$h6|Ih zl-L4nO9}w1`1NKbph0&iS@B;L1WqaIeG+MIa;F^vP{?j`jcNs~KkQ8Y&0|{S+lmK5 z2OmOxZ*}DscxnSYMORF@y@U1cf_!`w^Lft1YnMN*`3U*7rMwpB_v8TT!8wz&w`FFy z>#g}F8VhV#V3B<^qD6)&rpkaL!ti1$w+^g-c6&Ww?50q41VciJ)^lyL?L+VIcrsn) zBSDEjr*Yi&*sbWE9R72Za81zfW?TbFE!xi_lKo2pbq!DPTn(aIgr$M%BWh!e>^Zx`&TD#8~*c}4nbIB zf71oSn>-bviCgE}HJAFus6(6u*b0YQDe_{sfvz#6wb4$C$7aB6FJL!}z~WB|!e4n9 z#DsssfH;q6wl1C#TzaFh`vn8Lrgl-GUW0Vv#%V7z#4q#txvx=J$MJ6z;p~n}Ixq~| z;^%Gh$LO;gUFWYSXRt$M=b4M+9MDHsjoY}+8cV5+G{lz|`k!aPqs8y^oU&Hm8O1D8 zoF-FET%u9?Kug;_aMHYLw&Vo}u{I_FYz_ok>ANos`l`bQrU3JETp=+~yn6nFa9tKv z&V`AZ2h$KjvI2fJ0AS5LqLY9221zMC4mm!}Sa*89uc3P^8YiamG2(9Z!*24NJ1-Xr zApprE8m;}Ey|JS+ywsAgUVb`_cE&r9EuxwZMg_B_*lYGI$2XUvyV)^OEHR`~ykWB> zffV3OSD-?w=uIlNFq#?Q?ete(W@HrppgH~Ir?sa|x+3h)DV6@^NTwtj_%kq689>D6 zP=H=sa*Ln0tC_Ss1MyQhp7V;7O8mHD4pMiM3p$hEOIyiITW&J!K*zw`t{`<)*XzZT zR<0WNhyfG1ZBzV4-PwyF)PFfxQ25;z5>&H~T&44g=J;w zuU-zKdB)w08dl_h55=LaB>nC{!;NL4V*TdhL#v*i)R~?MIW$vL%HeghrUy!@os8f| zszw$C;AWK)`Qo)ld!bgn$;eY)O#KqdZ$&A*TvP>{E}4Du+g5iPMHSH4q=pfX!tB+h zz{10Gci)^muyYHVc?BD4L?c!0__KqpZ9#`W0W$K`-`zE!4hs0nqCCi^NSl!4#L zjBuJ)FzUgd$Pvx-kx6Ne9?l$jL#bmipb#X`>r$Y&d;3}Rg(xOaIOO<&M~9N(=_|EP z2RZm88vJ{!(-YZT8fv5mw(;L&I_7_74Yp?=f@p|2{9mcXwZo4-?I!r)h#!@y;Z0iX zCp*{#y*qE=uT=Z(uvktAjhM&iV6z!Jra5ANWhgMI9nW;^UjjF`k1@VVZ+P=Px!#|2 z7CLjWd;h@#OcUy{#;6eB{(wi2n*6ycTa$3t=Zuq6rH4zRi(I5++7+vyr#FY&bfD6% zG+@d=FjRB$?^HVJM6{v!LsalZ$G&y=9~BY9RHA`D4v*RdOAU2MT1sVFu}40FmxVeS z;T52Y^7pz3B6%s{kXSY?eDVW7q9jzS*LV{%7Eegw_Gb1gDU-8=NGi1UVGY^~ErBB| zFrRPv6fk^#5W*0*j&s>`UyKHiY^KoWhYBLq0pxLndSR*(3Kmyvk@2vgCI`%J;iKKO zg{Xtqz<5)e;M-_)={rW(&5Q9U{HxB9uR>FW#+!2FWkeCn1BDIgZ}7lP^3xfup@`hO zr~l6ja3?G_kiJO`G)lCDl~)TJr+a-E%(r_9uC_6KaOc(pNG5@LsGTwS7_G<~Ad3>Z zDs?zI3OVSn2wRNg(AYzJoN_PLoIXJ2FA)Vy$;MdCD$v$dbLB!*rBWk>(-(Yd-JQWz z@Wt1wS?4Zn>zP#{buB=|Ysa+g^>2qPB`h}a22enWpeUNiyjZ{LlQ<7Auj_$}h`qhN z9n6Iv@JWocPj1a^fX_FAyyX~d=kBANC77{|ZpO5TGBZLuYpR!|SZ6Czf?2)VKw%9s zMio@kW@{${XM8GjRVa2Zz$u^7Mx&l+IaUS4!8-8uAp%a>)p|;af?fQ=LttF4u%}0Y=w{IIUST2rO^F0Mf?vcBBtC`M{s6eq({>h=vp5&c> z$rp3GUbL2*?oT*Dz;L1tn>V*)-EZ&y=m+)PH?Q0^jmomd!cGrDXi}X+52nT>{MpeU zc{7V-Z=4-~#qD3=Gj1=EZ;r^vbm@fqfU&_(3?&|(r8Q6G!7%Vh`$)8FP{qB`-`f zv=h!v?xYAo85*M$7F>Q{?eAw_>9ow&Ud8JkIptgX(1m@JZ1Fx%xzkJzq9{5(Jd6Pn z5d^*xlPG%t&y+qob~_=f?s8I`F^4j$bW!jPy=#lpYmBh!)L<6O3)`~op(<1uMs6hzwUo^g zpAr2}GzZKSl6!2gr3GMSrCS%!uhus`I$o`>#2EYAt3L#=7y;x)vSBtwwMpXWnR${n zGb5vF#JNO+A9`gD=u_KJmu^09oTva~hp)QVI#1hbxZ{AcYAlJOo-?A-92~RL9Ls5< zu1y9~8`aP!Y#)CQ3-=gUxDuI!$-zjGhXsX|$0V0~4x7X`Xn;~HDk+q4+#46@;<0T` zWfqcOd{;v-H4lxYB@WeGvH}791fORgbP-C?7o-nIQyI-$v;q$LXcS5;XjumBKi=1k z43bZ6_~>({>0=mS4^XXK=nwNId!IPP{gp!xf!pgFIf97>O!zw;2R(+PA)i4Jtz$c5 zlCn!?^VJ9eN8#cH4cdtY?JtL60D56;y;h(V0LyJpO)|~ZUUZIRY0QmuN*H-4vROo< z1K6czmQYFLI)FTf=sHNdOFs{G0v0XltWcQunP>=9Ue)p3Guk?&Z$KYFb-O8;vbcd# z*2h-xcL$7J(yheUM>{Syv^886OVlrB^HuscGjnrp^JMwo?3FX5e9%c3*GD9DxnN8! z+$2Fwdl%Lmm+J4Mffjd%e$NYcO3yG6+MmSGQ-U9Qy=G;;Jgd~~CjMj14(08cjro-a zwvDxD%FApUQ!O-rS=>krRPo7fx1^mksjSUyeoGG;3wEXtBBu;h%(?oD7_tRg!GDF< ze!Xeme)udonZ!2@h2Yh%?mh006E(H$DPaZIc}Pz`@FOoyp%}dv6uIen&H4&+Tp<9* zky5k&Z2ly*wj8?h*VN&h?dLTmV&TM7MzoJI2-8lCq&Lbeg1ro(X0>&sWN!*<@#)tu zHj}edl%&-zVph|sXwp%RNBP#kT4`&ZpjxOgeRj6&=kWtt)z9&i$py4ac-iOs)U^xv^r}<#{e7a^s}WddfEi&<(L%dKrT+|qwfNi~Em9NK%cnLe)E6w_ zj$+pqSfYgpalEdH4}Wk^r1pb|=OYf0R^n`w#x63BA5M6aIP!+E2=kjLoK?m2hpv z>40@}MRInpEKF#|6-5k#`V?or{es2BiG04`)R*dEL=X_p1+M2_|3_`7n6ix@kI^EO zAh`x@vAWPzk3JmbPR5lRl0N_E$*EKpQNf|~y)0HM-;tEsI*5X`#}y$d4x**hWRZgP zV8Qxj{~ka5J1a9_E_+K>ZF3j?`dZ~Sy%9*8>p-sEsZDUT{wAccR%JsYq&6`L{b#=Q zcCw}2tERgcr7~MN!+KUqAVj|nsEcfi{A2zGuj4HbrFM#H5;W^OA_PRaJv+XcWRQ;i z_OXWOmVQQwaPj<>=}$Q>cyzdv3g-ylXWgIhRXeVAPXCzQP))m0JI&4O=_n0qRA4^! z9_irmU?W0wKGN9=$NJ&c!u8fy2#4Zx1>DM=Z2;M^xQt(}@4^%HDT~I?qd1&KRYQ3s z)gD>C8~xyVQ;r)05Z)VU!Ujy&ck2}NM1f<2i7w2m&5Z3D{+D%X<@8g5?*Ky7 z?Ho!_VQyX@Tg&H_-H;#!c@KeKl}u=HvMqdlUueI|&9tK5 z$B}=zva35RR1g>HD%9a)pxAB5UlaK1-=M#FU*FwsOxuoQi-m4I9mNPx&X>`Mfec;7 z#mn-&(l$8xro^%l?yuE;B9=`$49|`e3&rd#P=lC(7uU1wD~!3r!}~tuSI4^e)9VSY zEd^smNu)Jv3#vxt@6xc)+1BR*-=Wo#*pDO;j4zk+*vjW%Lt^sm+GbW#u7K)`jnym< z)+ylgULjD18QVBzyU7L;x?p{^IC}3bqm@c~prM%>o&&tChIA{mBGJ3gwp({x;4UFsy04OLYCu_5{hK z_cwQXNv<2dyUs+o*^3LuchY_fDonInk}og-wv(G`8g%$E?M%br-6r8+SP|RNdvrTv z>u`IdMaBm$6hn9c*W_md%*Bk%C)ss*gk_8wi?uf=k$u0KL`z%tG0^NrY(?8+P1m7W z!tiqdveI9>Ng#NPzai|imihE>3b-&mL={SAvakbRq1glR4?x3kk%ZZXda?ya3+>h3 zik5ZTvi z^;0)^G!#AhfW8L^vImMxXpK7X!J1A;Wpb?(%8Ws%u|Fm#F+vS%iC$Pfcf##u4+S-_OY>lGjBl zrInNtu!7rN3Ih+y!8{q9Bc9&${LMMOx7l4y`6>1hcOFRQm7k5itsrp`!APefP8{n| z_y%=D%%6T+l@KeTMmHiC(ZubXV--rR3|`7C(LjPI zC`>d!AkewXMjwfCGz(kx3Wm|u^iVY{(C@tFBLtt0UMH}6b@c+vqeZ=}Ld7!SfN<-1 zru=ph8?quhQ9$TO_oTtfHOF=sWrag@X6rc&X`=~0%Y9*oxe!^GTsz?Ib<^TZ>;h@$ z+VQ+dyl!fN7InGgUbPXqe3~Hn7d??`=1C9JIrbX5Y}`64iSh=zX8kfc-@nPDKZzq6 z{+g$%j7l;rEEYPBFy+3-*rd_5pUEUf-oStq&w6j;-&M{6JgzhiFy?`Lw2Pm*E!udq zM7J`%97wo3N8VZw5s##{=AJMHzmns5v?#>|h3$E&ORd278qVqAxH)z~m{kZdUFp=H5ACCN#C`%m1^p zAb4i+kGXmRyF(nL_cP<{9qjWFWAg_a$Ms8bi98?l{i3M(LV-^IxJigmM7Ji7@y1p z#LBY9JH`fHUDyl_4c$F1Fp=OYa`1jg|44lGxPSyr+~fm{qm(d|l3iA1c1$~x-sN%K z(8}qRNWHlyAxIwYtmvdNf>~nFdo)PdG?ieO8Gud?HH8miBwGhI@pyA>r_QGH#aCdI z7==YN&%oR|N8rE8b(j?(2{re5xj{Ux$G4Q9zUV=^vTfRm!CZ45n(f(ZK!7nWPnLeq zv-8^j9&CU5!ujc$jW+A$pePtVufbK}l_%ozKV0&?dDTzWjQwDc6`ZNO2+Zt7(R2xf zH2jH00{Vr_H+(is!SGJ~x4xf#J>1DsIia`!*3MlEYS;RBfB9d&UF3bsD-Zf}4#1A^ zlVsq|8qlujv4+BF^xRscxt(LXzV-6~Xx7cmZihe6jo@kYi@(qJ)qshlJEi|ruY{-bW_nVL_=h)1l%6Qm2b6%w)(!&-7hb_s z@TN}%*lu!%qezgf$~AT7(Xa!V0xNF=*e}!b#*5)I?fLSaV2J9QeQfo{61x$L+4xO( z?+R>3Px9AKlmNfqk{-Ky?Zervrfhvo#ecVU(*1-)(Y301CW@)WSC(BIh^AxhVu$Qy z1RKO6y8ktcYz^4J;<9v$Dgm7bf9A_i)lAvooc&ka*f8w*x`fv2olb z-j3NMjh(bfV>h;)#4j+cw|(`TpkpXK{CDc4qhPbI*Bjj^OI9 z8e)_@~pq{#I95&1{*ie~NY7bv(6| zSy+QHYmay4pIioYX-2B-eg->z=C-R@Fjd%S^^V%tyKfQu=JKkie=aALFr0z3Sq zOXy?mNUKo*nB|02_CTHHs9}w*MYJRRoo9{Q7UO)+{$;B>B;l#8M&sOHc1|3eJd)d@h#lYj1D$tj_L^eT*AX$n*OlWzAJ)vRiJ ze8o~f5-UkR6|i6hEpu<|)`JHd)e-)~yd?Wrnik{@AkPC4E05)U2}qEdJU$B^E`6{m zrzYwva-sN*XFjox5Bebq3Fv?bsE6*|)T%cZ9`7x&(iF0Y;w^mJ3;hB}fB{;~gNqfZ zgy{f_VgtktJKt;lUQkE(t|Q;RD)%sEH(y>!{K;^I@z~eppq=<__E%=v{ZAXi4vVoY zW7^+H+U3&wU0wa!Xj-?^BUr8AruOb8o5e1tfY#g;m;gnTJ2ELa$S-tW1u|>ts{E9Y zIv9V;ax%Mr)^n6)%R%}{Q|xuZQr` zlB1_WsCy@T!B`>f`kcnxAHtPI6P@!F)cAs`bz;>}%|;~Ds-oXdHlp!H_XQ4({gx4I z!$lF&VNx@~`A?Z|*jGFtj_)^Fm0GO4{r?EPpFjqV2CxzjEc##gXV(Fhz1?i`5X@xy zmxpvh(UnzTgc5Aa50Uor0P&me zKs+x%2X%?^tKAGOH*BAc!RILYgo^9LG>GQ=z-S}eeK-BeT0OwAQOglrbI+o6Yf+*l0}3y04{r-^;C zB-$QvM7IiLyd9O{x~ z@av#fm69Xxp20_|S%V)}s38G53t=|S#hUX#*PV!7wagBXO8O-f-G|WexLe>X4eq(c z3{8m2tRWdIm|V2{LMNV%5g@D1O;-3O95u+ZZc5N&hidhOxCl5O{3GGt>3m2ZNqhN@ zUVnXFkpKMcsSd|e z!YZo3=6vH+oZd&B%^K;CKjG>ReINL0dix_%adu9zcbxvUbWuh zB5nIZdC;?V7smg%dbR7H9eP{msP&S(FAwCD#Jl1z<(1Loo0$Sx1~3M*OnWSoI&>mh z2)$KIa?!{*L*mFLE)!;`tkf+tnw*s<8W!Uhv#Dg`pzI zq3Le%vlY-rxg*=0>3BriN_K>R99b#TF)6aJ9EH^&AZRXr(*11s2Baj+lIH8h?&*apjHcTmmKKo1oBm_=V~U|GH?BO@ z?Cnh5Rudxhs?wnx>3C=*+4r8`J235}gPUoP_u|gIM1cXmF z)^N~dj>~i`t*s>#nvy;APxgyMzW$ibF0Ma_^tGuJCi z!;GI05^SooRMO`=E>5c+X>&T+ugSY?X9HI z$=7!#6-ak|0M=0uqvE_f?ZgL?-dFvctEIBrNREGFIhYJTzx^YW^vCi_fJllpWd51g z;l2j&N<@=<+{31xE(-(vp%61+&3&w8hB-8ns%2)J)G>qtAQ35KY{jfbA$=KXLP*^W zbhXqW^u{~lI%_H39R%&<>U!Sl`S~0Ti8mmPpx&{REg03v#HhUNox!7TgUePK!a+FFG>>phNq5+?9;@!2&@#8Pu(x;-FmfW6o@1%#yppOqy@J&vuvC? z?!TU?V4=Ad%%52{p)kGZcb<}To~{+;;UTKFwB@wwJ^Y@h`aCIlIpLZv?vvWQ@yL4& zk}^m9ed@|un+q}C3}J)#`vhmo2P-;EapB8I)(>dA!l@~YQggywNfPc5qnv>;YhTt- z$K0s=t2h@uhFX+Zg_H7k>&RAZ@&BMjMjc3W|3@sj4>h%){~y>C{N4Lpo;yMgdgwYm zNHDp_-a3f{Z}H;ghF;d3bKeq#wlIctX4lTekg?4QB+yM+wL7yF;_}Gc7}Oj0Cclg9)2<)WVOJ-2{{%!z8h(^2w2E^aJR_;ce$1D~Oy1vBVW>6%8V_soep4X}?<8$~(OYCo zZ~Ti+$ek|da6CA)4yGu3D$*)|Ww)zxo-CcW44bvP&9YrnB4MRf?3^CPs}bT(JIDzE z<76>(xxuYI4rRX#uNMV1*W`BmB>mxsa({j<77CDz5vQ3fhAo|qgku_rHe#V7%3LFw zu-8DDS{H(*0OUK}@4UBEMqhrL2l&3(ELQti{V%k4$^H-?BXd){4jFrXu^Y^g@dvIELXbzj%PrmBOo82gj8B=zQ54M`H(Of5~E_*dswE|2zBlKCQt=0-M_l$YfF3i-}Rbr z4|<(jwf!B||KJO_12q&a3JlkD-q3IGcH;-;dD)^coSgrus*2euu@_cog1*cEwG2&F zu+bm#l0fx8wAF2MEX#}30|Qtv63y24)dJ6a^iFra!v*+(#_&c(;;%ZGKjz!0Yo9TX zm#YXYbbs@(b@d1cU9@RH8omXG@>4qv!M26#o%UV293!NL3$YV|3FCg@{mne_8^05{ z*OETJV?5@F@!L;%5s|Nb7vA?V{NG=7tsdYR&z>Ng3FA4JZxgO7C+1VQ@^b)i)dJ#|xnRJ}h5NN>K7WyM7 z_Pi^}ce*C)Eb47vyf+HH*UV-&o7v7*d?zWx!Yc+bx#8k7Aby%X80xg1m>dI|OF2DbaQNB{Z;AJwo2Pn1( zAJvk2i1Dw?hG*5;vK=#Qp;`rdw=UUe4 z>s?N!CKEglpx;W!vcX%!u^M;ha z1dUND!TeK3grPxS6_O!~q0_pi<-MY8+hVBO;hNmBb3bmR$VSB{z{A44G;<^7>-hg*1c0_@U9=Gb2lCJ?Cl>MjS zfkp~pHJ2m#)hKy2(rHuH@=ucGy_1N65yizY>jrS-f%&_?zJ^g7_3}@Pbk@BU9!hZ+a(v1_8nmbBQAm9tydkFVmF}_4tOb6SL1;~8W1Wk8Ja;hwqvc?Y z%kKi}9I|<4`GvFQ*v60lPrz&FW?0y>h91e8b|;q-fO?v%@OpZ{ee2$T&q@b_Kc`h9 zOm(Z~tIMvU(EQbOd)!++0(UdQTBpRf+9+eiyp@`38ToYXvS`ReN(inr&5(KOOcb~N zws6w8H!Q{F%qvkzE546Nfc^ho07cT>!JHoU`^Nb%_UwOb8~wXty2&(*%sLfm2&=$` zOo(QEAXz$f&BF?3wKS_3j-i!NmvSo(>wfrVZIiNck>*Dc!SlT@7YD1IV!xl!2JY~M0 zWv~%sAT`t^EykmK)#Pq((c3CK2+%pquQY_N^D;HVN*n)EV zX32P7GRc~Oj^mQ4*YT^%n$-18-bqDemQI<%r$MPfu$$e^_+tGWVP?bjCr&5?ni;ZO zDx1W0FlHY_Idj)Y^<&UG874)H3wMsJ8XPxDnIdE$?9!JMG~=6s{`N=p;f@AaRcX<# zh+$85alW3*sJmd%=NQy_QKK9*2>I|xAri%W(?%v6?AbqK+Av_{8W-|jII}woO%9!| zdN+Hb%E6RmFxH!(`nQK7|2J>=(Z40##Yr#fzh#IQ@bGhfUC+PYhSR@af~eASbN2&2 zMu8do1awIqo`x527${Zm{MPf<`i_*ZAn(>0Z;o-om5&CN&@+s9`dknPOtW)KzwU(* zF%I@7)6Wp+D6%)ya9w?auTT%vfqmntFC z&qv`; z7T1cS>(HZ{?#%HYMkn`~BS(n~PsyyM_u*P3O0i^zYNOPkXdL!b$Xm?t425p9Sn{lY zjH>Gyle*A~dKsA_ul+A1;0AFB8n1(KFEN=`n*_wmYlNuUZ5z}{p`$))FU5;J3f5kI zY=G$vMaHEamNdnc*sqy79rXKbMBMkI3*U%XyrHJxVDj0|O~=G>6HV#bZtlurd^RwF zM)CAw=*R~FRW2seIb{Z4z663oi*XoE+8Vd_CEtO<#D8T`!NJz+)D2F}rWp z&Sk)?OzBv`GA{blK<`(cdq2zxlJ2vWUJ*@Re*T!9Fz*Ei`2xR* zuc674r2yd6m7*@bs%HJQ;iy4&p4a}xp(XxfnU?1KblB=bv?^6CrFk;PDx3G^GE?q$ zYcNn2Q97UXLHXj&Q(;u*z+;^gJtVp%*$%WX=_Tjx?SL#JqAv0 zVl+;@zq~fThEYJa9Ho`c6T*r5#n$+d)?`kuiTS%+qwfN12K;egn_*tV5aef^7?~OE z5oI)8Ot0!AZu5}rc2+V2mGSP#!U~&3GO2(LR0w*DfYSg;YvOmuDS8;k4Tho(uz~5H zBNk&s#@$;aw^L9+dqk%OOa1bW?eEwsbFEHcS^+lZ5e*++I*8MFz>2WUZxudg0!t*T zSPvuL&2dQ3{LAz^;89G#y?aTJ60+*7EI$o!V5#qh9r3ReI)Ccjf1H5aC8Rr`L>b^A zr~Pdw)2>+}uF4qm{8__Z={BH9ijkE1tBH(^k66c7YGgCBg4Jqfa3?};hRxXC=OuXs z1((-bEQ0{+SY+JEn^d3Ny~`sG2>&OGYUWu-ri#0X^bzMQ-qH$g6T&D!WVuUtID?we-@(J(;`<;Jbsxva z_&l4tzTVl$-I zH}he&4fD5TZf7^#T~MP?3EFoO+m^qBiS>^ksA{)KyZ>#JaLn$!Cy$k-L0+q=H0Xi6 zZzb}Qs#gepi1N0b6jHT1n`IB+hsdV(#z&?U59{$WT7=kKhrN>x^f^@9AnGH$_q)Q| z{6H%lHd}lr(sXj}t5?AEt#Gwn}YeN3Ypt@fcBML53?X)*!t{2lc@=luIgrb7Cl${NBc6?Q!*a!BCAFd9z6H=j;PCmmfGN3c;qx8T^V~J>nvS zY!9L|A180zJ((u`a7l(SdOCA++=M?moiH-(jx{$xp-);gG7XzPwRyj&@`~Ahf0-gB zmDtTfU!dW0!J=A=wx|}?)Nq;+6q)TsoAqqY)iUIQys4np!37qJ4{eJs?QgzM1)|yN zgnZD2n9=Q{gWi}{AM)TAwlh5PcX`-eF!~9)&%k29=~7%$(&lmt_P^&dvn zJ+>64S~TOd2>b_MO%b8rznw2&^=oODm2pV%8Esdw(R5Nob(C31r&MXv;lBdA<74h&w90 zFV)jsqt836Y<7+7Nj=QawllG5oYsm-R71qZH7#BC-r8dLEtgz%!Qm_(JEOXs3H?k)v2{KlV`&NV&5u}AWkNW9S?%CY#tokA^?H;jCv%3!7c-%emTJafGr6 zGF4eN(r#8>e;cgx@6^J~A3TjLp%|Pt^jAqCYEZ#&7}8b#Rbl0BYC1nZ=8N5p_^ zXkBQoA+*e_e$)mGl{O5m)%;2?mSXm!-*|zwFuUn%#E(s#FX6LiXM|QnZ&(L;hkKzr zXwG%FjOP4FDSZM|IcyqHFBvy-nNXppzH&~yCChBI|FX?l?M#go7mOt|n+TUGZnrq9 zBYYY7chyy5eul)tH9?}_ff<5abMaNkd>HFu6 zU)&i4J9SY7d5e6Lom&lKh3-o{PbP&t^&y%P&v6$R<#zmB`|YQC8E0#{4SyvjRGZ#( z*AMZ%Il?id;W^R0dN);bWSyxvq=WFK&g?iJ@@PaSDno5s2I+t+--hN3# zOzNf^%!F~=97rsac#UYx6$|cu>A?DhKjL2==%yUcgy0PNYj|qDQJ`V3?CPMd{`H^B64IcWzb34r3aeWn`H(=Xws5WHH%6^zgH3i2c*O+ zj+|C7UWfWbr(c_jhfB{6ietc};ZN290BR`z2WCSTPn?D7dZ_KFV1g65xD8^wT?Z(` zhrY&!qJEA~YqxkPlmF<>@XJ<^?PO_yZRk|H_>GKOQnR^s!q z{z^mxj%+|-pTh}lW;hgIrq@)?yHGKI9|$tLj#FCwXz<*3fI{TEk-uFvOYX$If_JzF zV>>qes+V!cHsjry@2$pkbgR1XsD!^+*aQ>S`~@+9dBPXhBb+v+S93}GSv?@Y=ubvJ z-L9J*F!M3&%lwC9fX!EPO)V;Oy|xVHO^8x+`u(MY3^82kKd_KOpTff6a=rHP1zwgx z3zPB;`YuYI3OH`zf4Mv%b~cTfOF5*FHu7K%K_6>T4XiPMJ3cFJVL4TzDg}?~dql$M zooaA4t~O&jle;k-X@i#`K7#uH?$4< zzFV|hYxu54VTH4?#{LOjd}w(1m9Ku|*#ct-awu60(@WcUxLx@YG+!?N;R2%jmz_lU z^?D8(u_Vqb!J@n2y7OCd(YiFNjcGbC^myVFo8+JAcXM+0?t90MaStj!gZIE4P1kCB zNy3~7xt?;)V07NMcr2>8I z$vW7}3fN08vp%mpeB1F);U{xO;pGs`T_1&*ZKBg%q6tsn6I<|~SB|+qhwFbvUjOvP z-Hz85pSiuh=kdY!x|ea~;@%d$`Mm7lhbUMezj|NH)?Ok4Y0Ahu(%9;vG#%rmu<9*HF~s^ zK}~Csmu}Fw1#^h=1!}YsH{F@{=K|q1XKN}fJ;(f-w25o9%CpTSIig(s+z`m8oGaL^4NJPFimGtXCp-xPx3wXe^SuQ%9kZTm%S`?p(=g@|}IP#l}k zz?hB?n_y=;fxsLX^Fa6@rCw-vXt;?X#7{CC%(ektn$Zl#PnW@zjcgQmiOKM#GLtA zIk$}in`%g<;yj~QZXFrn&fyZGk95U0VI4Eh9Ztcdh{GjzR(q-_n`)1K!L$gQ_8}dP zCgLI(VWPm~u3Mbj1~S^T7-}>)uSNZb^xsH6_!1mn>XYc(d`gM} zZjKLQf&*pJb#_d@AENC9b&^m7n7lwM<% zBvDoqL4oF1-TPgoR$a&r$W^KRwM9-rLB+yU3Lz@R8`Umorb!w!jdgmFnfOhW^TrigwIC?KIPx=&0xiax60C1f={jSZu>9j%?{HF46S3H(VWJIVwr4JG9T$ZySF*7$X6B>X@wJIw==_Ao zOZLkm&8~W=+UKGTVrs^dhf`tOJUrXLjge$i%#JP|1R`WJhQR_wM-lB;t#prn-)SD(1B5LjCr`Fd_R-(z`#rS4$+;hEu5BT(vIB zNl}Dq)4nzu9YpgRDN~}4wxqpU5s7OZ6dtKI0eC>WD4QM3H_q|j>t&p6n!_+h54Cbi9Sx!;mSd{w4AuP>7?Aup~d3QrB_*3SIF|RmbSKbs#;w}@vv*W;NzK9I29`# z2)_0v=&jpjXt2{TNwxCC$%=zN6Z3KwI;6FiLUzj9JNdeM?+R9yIU~?~*2D}-0KHNY zY9W(Ek0uRSSYP{6tuf7H)`18wdOrlsdcZ6{6USEy+}1M^8ZE3`j%2f|O}~LwW^N*9 zjG7?WecBv4Od`B1iLQ>nPLQ!v+1x!Y1tM6@m8E`yxZ`Tvul~K9b~)~_bGsJg^!sN5 zcdR)`WE&>84IAL8Kzb6IxYI6}mK11JuD`b5!!O69B3`k)t0S_!@c=eUx@G&eso(%> zHgx#)onv#M&zG)Sxf#&_y#sX##+WQ_(el|V`1lIDX)%x&g76S7H+`751N;6JKi3OY z?E|xPPEx5J-6%(_;l%#sV4}FVSm(Y{>xZ7tR{ztX7Gik^`TS|TftHfW_=2$!kQSR> zUsoDq)rry}V5i&Bo+HD_tWRrVf%}YG1#sg_N=sRTZ53!v%k317>J${`?O4X0k#5xh zKdyqX$E3oLxSjLn8AG{kopSg8N%F+|A?wh;dMP4udhi0AG8@;P;%LvR_~qDQI2NHb zwAid;OR|fyt3z1EfPePno4p?r(8Z~@ApHve6{eSEXcm;wSH^@_s2q_`e6Hr zT4=rEq?XMg{@>B>b0|0S1a|mhF1G$rq3yIR3ud(RaiJp`yG1cNUx)kXzu~#~Si)&% z3t;#c5LLrGS>gsS1LRG4N}S{C@`mx_sSZBx`I~fnJLj>W&lBxu)M82TiOxDRM%1o$JzNJXEN;VxIiY9rq-{ z@C{zCx=Y%Lw#39>M)N^9O@%v0h5Ie6GU@_hPC+(kS*;j%8H-M5plmOyYb)Xa&%f;g z+eykM4xkiZ1##_4cjeBUSu}hS)a>sE%q)>pemfbhE7BEbr+AcoFY@z&PcXDBkDgX_U;8vMM3T9y+X7w7Vv z?eOGXg|6M~*(ldn^R6HC`rB~nKA*lfqUy?_uj?s>CM_XRBJ1et1UiH-mt~0&o3|Z% zxT^k*Wi#!jd(SDo@IC>evYlnjiwB1V}ceL7$lo!yz#QABo^k;KK6|4{vtWhWX&zF+4{1_%`dTuJy@YY$SJ@ju(aIFqNKC^i)8$BM zqAIk^zE<83#XYXZYiE<7eeVW24zN$mOm+;kdE8(yZ+Usn>YOMR$%|L?_=W~4X?&IE zJ~qHd^JluNQ1%o2nO<;wUXOL!gtEB_5D!@si((H+@)wlf$O?S!#qfloAfz!B3{Ir! z0of4`vSJFOg4r_pg)J@)SiYyBFJQ?(4{-UBqFOr>nGhL82V0IOoSY}xoV6*EW1Gs) zakXTMZH&=0^ApL5o4t{fe6upngIAyzSKBw6@~k0Gy|h}ITwE{n;OB4IYzP(RRzL+zU9YNi1_LKg}iiGrHkm#s$xQKyki zgMo)DAG?kl1dlI*6^$P+)(!_h=C_tlmf%TrYdhi09Gdky`8br8C6P=~33g>64gDI0 zE`$t2e8MC5p#jJm;nVW!0$Ar=P}+Rn8X@-64OE*_!dpI+PryJ+RWfl61xtmtc2^ z?l8pEC^1r-O2U&4^IxSIQpdwL_5i`2OB0PJ4scyK`>}c^Tcyr$Pv<4n*_lgU*LaVD z+wi3L{;z9`G!N?R=bU$!(Q&1suOqy{<1Tw{*P_9%ikDBuH+yj64{&NM7xM&0J}34X zt}S%m74VBlU27Q;u5rc0@xKIAzY5Y1+r@TpmRWi|GoUWC)!(_d3J3`V);!IU(dv}I zu6e-QQA0Fm1bmkY=n28rVQQ?H%)?URws%=2ZtU@eu&pxeYMpm`*L;Ev3gs9+^RWNP zclxr#Ir5q#{GR?>yw3psVPhQkQ|vx0DUxm22am~Re&fJz3a(6CK9UXvjRx*_*XG_0 zvrn-H;-(h9-Q+oJDju(aRMcRM@9Ohu9`)Q#^J5Kw~d+DVE4?b7CN~+-4 zeW35*OJrURduCcKQ_EZz&FSo5UK&oS&DFMUR%T=y06K%R`0RtW4AymD=7w@Dtmh1m`UA=Xz?Ger}TGKz}F0VfeLB=zZXDEu;D*US`N2PlGP^b$nw5S zq-@t)L-J~Kj3JpL_=R^f-@M}bJCO)fXrOJ_asoT1O0ssBX0>ShR}Fbb*)5QYk^y++ z=W7Mlv@8C(XjowIPfcy!x`CtoU$~qCpW=ARi&&CzPj$}{yc-B<8mzCbB{UYR zOZ7T+6L`x^D(Zu)iW)6>nkK~8^J}5Fd@hs1Yi)z7*k;zc2^dwEGW+SkN3k}VkVPnC z2|q6E7c~}QtwvBuH^WXwQL)SLYjB+#f)NkfKr!@I4SDopd$$j~3D@X2)I`WEp*s;c zH246P?dD$FS-u1`N}bafaHsmumDx+b)Of2hqSz$#yW3qOZ9Lu+4NuBBJ!g*rT_E?) z`0QLGluOKTmV1q{8JJOCpM#rk_n?|x!|Rhl2IS@&TBGw|#lfK!;TZb#UA!IA%kj4J zV3)DT0D<>iKu^_@EJS`V7rkWpsXKOA;|>SdsmX3o0Q3tf)NW}(`JpWV#re4^1qs~R z&Y?UuG?P^PJS>cFOZ-mhuQpyqkCKHxf?8s*Wh>S zho5D0{|Hgv(MiF{G$`McaPXZo|3Kns$pan3rL~OnYo!U+OH$C86ICYv>BB<gdmPQ%yp`@u z@DW;rbomm?9f4a3?$!f_N$$@4iK;2}KaN@YkLYH)cldW)>Yx{;{kJFUoqtF9%ye!$ zRcvCk6{ks)Qsgt8jMpt@o7o~Vc7qe0snfKGZX+`)Q$oYNHDXt~=qHWvuoY9pHxX18 z=bKSMKk9HNMirx=Q#!M>k%aQfks&Ug_oh9gOJ$s)tG)J7hK^i;1kt=wfBO_l2Wr8p z^d>Td4$I}$nK9ahEHv9d3s%?h3sHq#TIU68M8YnCmZFrp_4onHar)qT2yH#YE|zf1 zh-G9>xM7_PVKzpH(JS4?6=UWT{U7;!q);al?`=gVP^Ggj z-&RTX?}p#J7q-oaux{+4431ypn@ZQ~47fJ&E~bWg^O)Q%1blz(s5b)W6aPSS`ZZ>b zS5IyrysoY07+X>OTzx5xEv%HeYSyDplsGG@UBi%JZlou7bGY`Cg8lwW%t2ER*@ik*y z0S4FH_OwWyKM^*pr=Zd7ibk#*oJIfEn4F5X-Q_VnqVinFGaHu z{j39N+cM}JVNVCG)Al35dt{IY{Z#UyR+9G2O0+k%9kfT{^3#Eja~K(y>QTNAq~W6g zMj+S62$a;{kO#zJ^_q=wt@+WZLoA?E#9l1v>5!^ETx6NwdOmn8m$;vRmCFfEN-t)vZP%ij^92sN^>M(XS<0D zUnl=dyq5!}8ltV_4q<7uDspw!pZHl&zi8LGG=pQ^_k*%p|Cw`xwrxJDd6Cn{_gn$R zU3QQvpkm~J)xQn36>nD;#icfEbU8r0dt-72r=gi78qDM?moGgJNyo7}wE5fhm(? zasn%Z5`1{?95kkFOqdnP}_y=mjtBl2DgF816hWy z9^pp$AVU;zM4X`-v%vJL%pyFW_g4*e!87M4%ccrbXXfL!$E8CRRc%}U-7qV=K?mYGMeySqx;uykeq?f_h zisNtk{gn{ywCLkI`!zx88W|NF);el)wbS1xL<}-2+I88qA}Enf)Sd_q$-*t`rv{Dj zX#Z!(#D202LXx7(WQcalh}3ONp#xJ>(CD*XW!lQ!n8K{*KDJy8-^c~j3WHcqZ>LL_ z)%s4=D7XzqzL$NQ=r3U5nk-7xrM-6yCn zd^3hrQJm_R0WZ*xdJY)btaExbH0j4x{^RCKckn@NIPSX+Y8I|Wv0FOxjBo;+t!&X< zc)eL4n!8K_7Gkpy&^`Q8`%x0GY~Cyb$&qwTeGe31pl&%&JEMr5`6= z^$-glFcgvlx=NGy?O4oFbVQhn>RjCeeRKSkvrui~3GEw$JbP&w4=oLn#@u3(qn8|` zU%dhE>KYhp0a5t5tB;##nylA62V3cU)$@GK!=A>;%s1PFN$%>bP*nHo7$B4SirZ&P zpE;Usmq($&9EJw-fGn3pcRbzomjDMnVgmcFGUinDr;q5f(hZ%>*W`GI#0;o z;4)9AFV=*z5a2mRPUUsf*Ez$Y-B<%mI&-T|tlF~x0~T6~fJULC`evyk;%3gkaX|vL zptC*$K~?Ofurm~2Lx3dmd2nw~6CB@otN1u0SQ5n3`qtwV($7QFYH34M_xj-=+g8cR zAFCP6L;`TrXpm=)5Vnx*McX>uIXTK#KF}erZbOC^zY|f6>=10@bb@!h`rOONG{KmG zYYBM2-Ed27AdfK}JI(EU$MS@e{_Qe^(&s2U1&r=(a_*C9>Tp?WKqOeW@Yraa7XTM0 z($`zH<1QRZ8GoPEn@NlS+=hQR#ga3(j`V%jWtybBWqz_NTkitl(}`jAO;SI2t!!+Q zktS|i;i5Hz0nYl&PaY1}X5ZE*A%nmXm?@%i9U+@IXJk0z@`Wb;9FL|@?kx#!e$eqhPh5hiU| ziE5r1$o@#Xr0z?%)7+b3n{?ZEO24<-K%DF{Rh+>_=&AtDP z=DO9aF%hC$sgIshx@`FMPfN_j}oWzb5SNWMvV%J!Lv6{I=R1^dn`zLTG{sk ze_KPrD|6TSLs3t&_zD7wkSgfbAN&#cHt5+5Y!*)Hw@+hG2q$bsG}bRy$8xt?AFZ@sY39tX zn5PfY6d%ZFD4(yG(doGY8njlQNN(FHnsbsoZ}!R9t20y7f*2LCmlzwFWA`~%us?H< z6fBD<>=*1kXRZQ^8_p#`)8@Im?=Nu@+}@13t%1cUQ+Gt(5Tc9t85HyNfWb%zHr;N{ zwz`#Hj#ewbD2LkgDqFxj(1}6|lRoQ4uG3hM)gDBaWeSkgh2B~`OlCeSeSPFj^6M4U z_CxQF9Y@)WjXWRvou6}p`rU<>Nv6q~ zY&&gpF4Kf53>%ozwtlac`ueQnjxxUl5fip<&nFR$-AqqVJtmb{v^j3^4QKze{C&j_ z&eF0vC(Dp?Ud-gdnDAz^#LyeStL@SwLp2bkCTs$2ngxX%iK+$J>Dt*aj3nry0OrRh zQS>D}q@^&sPrqHYZf@r6)j#=K$BzrbyLncq)cv^CN`-1(Gc(NkflI4Tf_Lo>3@e*l z%q3xTAQW2m`LnIkqq6IQA3`e4t4nY72{!Ov3Zfiq7Dv&+JYq1?_1ZseBs|3Rc6{$~DIM`uky{*Ztlv!}P*BhWWmQSJRCH{K`(A z!d*7P$pSm-s6{8m;r8CyNYxh|Ciio*v$K^O<}UY3sxYFc{$8->%jyu#Yb|gt1E~9| zSs#i2VpG1U@`t~d4+gx`T6s2ynIKMT1^e9NF0br3|HG(c=U<;TFl{Yz;wza=4xELI z$dOBCh=c5A(%IC8Z~+Rs=(5CS)9RH)Ww7SLIuFb6W-k+2rHbYKVZmSs^aI&7K+XvB z-1DOgYf<^3P<-H!tHhbd73_Mm`Cu5eA)LU-Z=mzJ&}H(6)($z&5C(QIe>V^VwGr_= zG84Zr=BLQ9f$!|1Fikv*!xOH)ut++6bOen>+rLs*d@K%(Lm?@mFmJ#i_w*x34Jhg zI!7}s=z4`NziDR+m3-?=<1A>c;wt_M_#5FicmuVWra`-oyxyP5pH708x4Yg-n}n-X zJg(Y9&xbG7Gb5BL`uCS~jJ9p>1+xTH5$8K8S(V4#v)95E)sv&#%RXb`Og;VBv zmQ(+-kZG;(`K)oH)>p})5&5Myy}sHZi%+LtZ#hIDBdXVy=&w3-gT5X_x{3OT@npZ% zsc4=T5zE0Mo$9~i-Bi_a?{uzT0#c7BYPv~nZvwSHG@~{vSd)smc9<4V#=ykN@J<%q zuRIL3lIpC9+opo&O(d>Woj;7|qj=Xsx(oOeyb`zf0B0oYsANZJ*N?FgIIrn?nqLcs zl2dl#WAcos{CfF6=h!-cVgj@N_|@E~P8$T+Vx!f(8H4K^WRy#m$9*UpWM;lxR~{|l zY7v8cC|Tu6Z*rw`YD+8nmeTI}T*p!;5f&D0_3ZOvec4}js;k#H%>q{En@&4k623cWj5s#Pdtvjsf@&6DIKh|C7$VD8sex!H%E&rm zwmyZ`bkdHrbcD8RO0}#vftmRPM^&hnu}`C1-WF*yeF`7w1(iX$SJYWRNiL=Tot5P zE$-1Sq{HC+xfyaX&QQVKSa=oGA~#Xqk%qraF{$^B&S2ZPY{}GD#0Im|?Vl>|2A61r zBfI(>5=k&W4;R@o4L%zDq%buq7_|C)%Pz{XF>mb6O7HzGED> zL7`tzLK(tpprdL0wYuwvQXV^pRmAKD6o=wJ|Cx|b%U1z!|5^ZEB$DleDy(4qiuKcp zLlfvdx~@nA$vCz2q#m=+>&$>w^VWnqIz;6*^ky4IeLLdu8&x+vhS{j3XS3B@FF>Cr zlG#h%m{jSaWPCyPyRoK^uh^l^?!?buzDxksuWWB!1)woD|J=|0xzvT8P$R3G#&Yu_ zn7b@*b4J5c`WBbTc)zO_$D5)vz}41l6{j-fN8!Ui{V%IZqGGXY!T2_q&ozT-#{$Zx zBG1^&%UBEOn}<1EOr}FGVKy7+l%3&ZFAn|ZTPrOz?H>=}9jW);!1$tcpj7?ul-nC6 zB{o}opx1yB7+{3x4c{dTxHhJyx_Kr=`fS7>mSM|f((J*#kqy7%h_=5YN4b+uJlVzC ze8BL#>!>-zli!+t|1-JNJs%$NqZmhiYfZ0f7QSnoonzPa7`L8P-Y~=1TV*UhPXV;_ z4vfy*e=E90DPmMn-9=o%A-!9^g z#gWt$r%4Kb-=Of596gu2bj+oW|cGb80}7vtJXH1dOpe8 zzGybM`jgK# z3RF8mi11S(NLdqYxU=ljS=W8&#sL-HLM^TM8^@KBpBMEY*uSGpFO(ToOB$A1xXR7# z!|IW#&~8W5hLWYYdOrLzCuYR0FdD%?I)J|dW2uD3bJ&0OrDHjdIbNJ?*uRhViGN7E zYokSC6Dpm6|H#cu8oJ;=9C!f1-0Ezienx8O(x8GH}H_LusPhD3$_Y&dUrS8dYuGMxA z`bM{gis*U$LV*Tr;5&m&4L|tj*>J{cgAW;&lPgC;Ij_}x<`x9KfJnjsdoP%ob6(%e za(m>OU1al(kcdzB=5lOLNq$`RC^iHYwEua~v`Ui~`D87cDRg660A)09n5?D@@}K!N z0)0B?>OZ12kqhn8Jbi6*Cb@&EyfH*@S9);#^mC&*g(u1%ITB9{i#Zk<*r%7O)sp}V zFa#NEgoGOGg^l3DKq{F%Mdnt-mZ(GJ{2d0ejP0mLd93AjHMeY0zsOJ!1d-_+E9m!# zvy&N~U>brmpO`JEr}=|1_UgV$jJwa=$Ad`+>}R5$wv+Bdq1dsrtt%+P&6;TdO{`<6 zHdm)7!oEiU7rNhb7qsU4^Oq``(L{I|f$HGs`F@#q>jJ<1x&ECope7rxhZg|G#-9J5 zu~8En)DgySZ6T5&(QaNyGr1O@Qdi;_Ys2%G$ysEvxWpVwWvEv$TSDCLvh_pSsC0$W zGKs=+wAF0Q`}u;bFI$x-QZzw!m*E^)Nf5IGE5$OqrZA`+3nji8vN?I z8Qs0-H^8n;c-3Oj*`{N1V#4Oth<=v&eZiLDvtF6O`!o9dqHX`<;)l-{EFV| z9Isx|pM@I`y3lFTZq-Q(2x50{#I^*kJCn4Bok9$i{4+Z93=G?g+MCOqu|x zzQw>s{d#+|@VEMnBZI$BU8-;4TB7yrcnlA0s0y$7E+SDE5@4p+6({Sih2787$$9XT zWmJVcg5eP->9V4P2fv*DH%mWc?wQ`)2hPyJ8FLZ~*|Duc6r_)fNXx83qCb2(C?{S1 zGr})j{Y!TDO1V@7s+<5jHb-rBm^D(?gdp!a>OvIgGgG~o-I%U_t^V&s1f_;osrWI_ z|LCTY>K>Ik*fji&|4Alt)hx&aJ!nfcS!M1^s{4$-jm1r4`T<+-ymISVyc#^lDA9rx_Ie9@b3e(LN{E!411{za{Nr#wj#w>j%7&}oiFE34 zNH2fW+5pxjNH?NBafN!3zNyl~ShKP9G!E;iBPzH`3w0(Ub>YT}y&lHD=$-E1uXw6D zP_+m1c89++-neH^QaZV&ed3m@i~0{1_R^T1~yzC3^d^rOJ< zY4JlO(`!)%@9v_iI&IeV)~+ZUhmP$!q(~mLWZs2z>JJ9MGV4~k5|0u&%5R;>F*(|Z z1rE`kz32Q|+1aW|fjQ-lem*vDdqbuG$+yI&dicRmi6pbfl6~bX_lb_OTwdvFh!a5x z!y&yVL|`kU%G;WU>H#lpNI)GknfH8*H2Q(&r^SXlh68mKZ_MHP9|M*&j>7$S=VQtu z8nQboe@YJRo3Q zaOmHde8-8>ze$>_#WHk{4ViSJs8OFQsn(U}b=QNLflS5&B3DsiOBz*=)zm{+ra6Rk zG=TH}ygfgytqf!I4VfBUDP6aUM=R*wU_;|$Xsh%&S;UsW{A!X}x)k(f9zP zi&{+z(MC@(7c<(G4f=m5%B1h?wABApE7A?VUR10~1U!j~d*vPrH>l;yM+W3Nj-{oA zC%w#-lYbyr`6|icp$s#`3uvCRxm`|l83T5B$K^JxN4vbmEd1!Lfi|!GCw%4W%4j&v zWJrgnJ+JMs;=pEO91)RN-?QY{M-;I;XBPS@u{o2$Ikw2r~LnU0WPOyHWFkgryZs3^$?WUrl&h=fYXYEu_u3* znk`js6IZ05!-ZZqZd&pbeCnV#5FyknI%j)Qd}FJpuvqi zO&6;SXm-h}JuDpv&l)3qY@Y<=o|GTPVKhSwjqlM+sIq+9V?1dHFQ-lPb0ClpmUz?Gn5=ar1VkdG5(?vp}9o#feG@UL+%%3#BmG@IO1x9>K@h{6lw`&h`-Ghm`vfK~v|0v} z`q%Q8&fCpm`^x?kZ7HW)A+~OK-872PGPqgA_qLPClu}aPJteYrq^};; z?toT_1ku1fMQ8mTp5tU%2#7wNNq|+oeNDPs+evdL2Js47DSb1z@G`mHE<5D9=9QZ_ zScpK7hM@O$*!+7Db4bzKL?ZdE5$(r#D&gqk{y4!v%RlD~+C(J@%MBSBNn^`vzsEjo zX7K#3oIFgs``Mp|mMa5}p=f+tD(pjQ}7u<7fkbc~KpRZPF=j|wn6|JMw zhKo$1M9FiQ=f`icvfI%Rx@SR$bMHZ$E=`;^dI-NVj7FSd4aaSa#Gg*bRB+^%5{xE@ z0jbD}*{_G^Hj5$jywNJs@E?whXy|JrT-(vRMw-dn<3x&ubxsoT6g)CFR0hUSZWXCN z4}QdxAKx+L_Jpc)ACf=rhZ-D-)9VOv1{5Z<2^X8chw1FtDB4_u}k?F3C_@ebC)HM65|(KOyN3yFzvZ4TVZf8z6s_z~8G%xsRQoNVvjtr2-1yZXRM z^H8hoKCYBsUwhb=k-6=rz}0nyM)%jort_)puKu%?&_ssx2}TIDWB=I$twJCM28M65 zsg=rS1DLe!Moh{RIvUs?XX^*SRUiT526!0X!m3NfmMsFUn&9gBqr&OH8S<>q_hG5{ zK&Anyyq*!U@naVnc1}0~7nb2cu=FcjE1kjy3xVL}D|9mdw5fIZ^fqkk>GI{&zr8*r zwN8i>dt4otVG#O8uTNzp*6sP2Ex%4?n#J4+wr5TPUb%b0e^7?rT$f`yILiv}d`z!e zY^ruR5^A_^Bhf-{xGrB*N`|p=51Qm9X*J2K`xntve{%8S94v}#sg;zmO)L7>`KDZv zUdAxC%%Q8K*Ut^bz>hm-F+yX&=!pb-N0AS~ytJrRAX1-!Fm07}7gX1tmtXOkdy7M3 zhqU?nRVCO>)1iC0c0k5Mp;w#o^3Syd@BBL!Cy_>+zi21WU)p7t_WMw8G9KOeinHjP zg%tr(g)m%x>%Z@H220dYWQuTd3=;cROt&f3WX@6!`Mc`CTqL{89NJxz1rdmvtoM$u zT(sF0uwsOeeCyOnHp@ugO1UGWU_-Ssn(U3$(|;3kz|xg4Z$**{1OqVmI4dq}E5sUv zglTQzR>FMd4b7hiGZySxZ zntU!v+uFT=qD~?>*fLO!DEK{8wQE7TZME+eXXW+9g(uWE=xB-#4ciDw#A*n+Z4mFj~G z$q`h<%NI|4J~h{%SVPGRu{uiBRWrH&S;yYG`si0{6`df!%~5o%LS`C`wKL~I>&a?r z!|zHE6_U{I{<;!vBJGHgNvvS}tkcbL@N2q|!BLP7y@FzfTln1n7~$32Uw9W%zujG<)zj4RQI{(_n6tyz)l2Z^}uA?6v!M8RX7p6qB-Z5H( z)QU^BHa0PFv3kBmwp60tPr7;lMRd#R6=e{NpYDe2kn_sC0J*eLZ2v?CW?grE{Tq$%oNOeXoqo`KB+v zXkMVHq4JVBed^oY(KpXvxP}{QO<+xihv)Db6cKnZQ6&Lm3nD*2uEVuOu4TVmlzHQM zNF#uJQgtk@U7fM3|7~4KS4Cv#26>39L+EkL3PL@1GgS~kd|7sh;YGA%{I;7?zk6^+*n({;DRbaT|c0t{goj23Er&*jVlRmiPt9 zy?cxz|8X$_@_}C>;8ttyhcHGAO=LhCo$d4{1Q$ahd-Bz(A^sPJi!Q~fc0@x=rXb0_ zmBGKh0q?=rKVPg~Rmd;jA1<;m{eJHtrALFjUtdbEfB1SA zgl53d?TyQIbT&rdcqDB&(r|r?<=H~$(llY2W;I9Az&J*T&RzHDL2icWKGyT5;)$X^ zxuW1e8r|ab9>E)U9|;I+-a?CdZ}wM$hVMR?)bwBLG$jvOH_awK@|{G-q2hC&nU8aH z$#Ij4_J51v)2XNmYuz;EcpsE!K0VOgr*CL3k$s^WL&S4UOuwr=4qjB!rKQBBwwFL& zf14go++$b+k*P+sp3g3F5sGZ12gsVVb+iv$0rMW>R_;UikDId+nc+tvC~; z5$?C!0Z|LlRBk<^TPDX+jarpp?147}GX)f$!};$RrE6#$LZ9C!Clbdzk;$;2L3i!> zMUoR6qy1B;&ZF`Qo|M9>3lhJe+UYwn{4;=1vm-y;56DAP@qJG^ORBEbRomyDy;&aR z@M>>fWa`Wf{6)-c9-Xn0WpFywkm1rH0{S#9omx%AJ8NGU-RWvP&NGGb3lt_p30g*4SZN^` z@|u3>t5<%(N%+wUdItC|nS)YLmcd~KMedS=lH!92f4mp-eNeeMP4;=VM``k7U{ zHd-CR@|iA)>BA>fpxmw~>e9b4XOg&)Fc&EKEt@Op^UPk6%9P2WVp7pjbHw2ArRh@M55}~fE@E%Vn81`+PNsRmx_e@tB0&~ zFjR~sT=+Qg6s-y2MFUcv5iXl~vuL1xgn_}rM zY53*0Q=K4hQ$l#<=70vZTTJgMP7^Bpu(tk`oDg}1y6iUE;=&>CpU`bMeQTvOSd&*Z zq$%iiPc1{WDHrDw6Ul>LWAx3r+`wNyG~DSIv&qd#`rYlq0|a%7{O6~H9$mXE&AHSQ zaL@-T!}*I_$wvPw-*pm^yv1@D=ML7R9VEA~bLMPx+TF>O%5Eh8z+WN&Gsd4}Ta zR1#i`VMkURs9kSuY8-Q@$gCcFm)x-}D3+&sQ@s)T_Low*opb5)xjuNhS5%4)9uwxt z)GHdZHI4v?*3whLF=`aW-hYXD*Q9K{2(H${Q-If$j$D&F;jdtngm*f@+R29b-nOjj z<4%Z@mB$3VxFLSrB3ufyWW|aY0;pr#@Fx_iR#{uYN5M;5#A8e3G0-PuosbDIXc|0l zD<6AVfg$V_GLQ6nN)_@dJ+gK_V%)tOh5iLO*$^30K^X(@Az7p869&zR5?#tR*Ys)X zEJkGgFf3bi5U%kRUZQJmY@C{&)&u&%7Nei^4GI$VV9k=(u)`Ksu~ z&YXcD6`G&vU36R(5IL-_c!s657{UE&44d(!9}qsV1A=3DjoaHK-#d~EP>l`?rE}L` z!!&*E*aNtAu2*%Y5!>KeCVA6fWwW_w6`?QL*1SnW`qvuDk-?+)bz<5TZ_VH3sgAre z?t6>_`4#)?O}Rk!{5w)EZO-k1YN~XWQmm1|vznd($FHe+X|xG5CFF8LP@9koc=KY0(xjLYaXRo(MNx_egs zBmwyvbFEVv&~TzQ0Aq%aMNNaqJ3vJ;DA8VOY7;vVp#5B!pdQJe0lnNE^gaWdt0f6BhPU%4%7Cg_>QHKA%w+ zGs0qOM8oILwl5?KecgX^0FRrG2A zYW;rIt!o=wcMie%_S>C`Z;;vfsRbeD!GC;mT8$%z*fxIYIvZzg%?|(c09xDzGc4<-l?ZWtBbUhTJZjp z-D=dyk6FJ^vSg||fzTEkl$*@>=dXnO>EwN_06_9@SR$7qSuXA=Ff5gG#&sD&aiTT< zl~cL%?83zMz@74KCcA*HYL_9rS4#k$qT18qH)W1a*1?bau~=;aCX%(?gCised>##A zjAAu9TQ^@ySSAdBALFpI4F32_YS zFezVpzQuP7UwUrAaTui~ZCpFA>zD`+pdBfW<1v2~%%ActVP=E?qHQGCz0wo*q1jk5 z$l|7hj&zW1K0y84*&X${4NZ{d5(rM`2ye`nU}u3EZjx(l^8Le6mdR*BctVyUCIY8@ zgXtLduvMFSdZx;7D-@FLMoxZlKV8*ZI1>ST=pfr%egm*EuMrGv`}YUp@IaE6%iRS^ znn)qm%sL)`xKp#xoC~VJ2f%2_YsKz5+s8byhEV(CC7AS&RKJru8#wbr5&W?g;u31R z)~PkE-G%@uFbBmu4Ms*ti1z^!)*o_GNhFp9gr$Xne zqgk5yF1BuOtam!d4uxIHy!mSg7#KEif)dZVwWqfdlboM~RZ%98g@fB|3OvwmKPu?k z5*eTvhop&@lQcLq)@x@^FetBea%gx|zyxa6@eX1Cqh;S zI~~x(Jlgny6OOC$Q{PI98Z>`dGqG878gl|h)NCkPnpT;D#RzFYbL|s}b*^9WFO9l6 zXcfM-RpuP6L{-I2%;$!_Z_qBTPE?FBL<@1)9d%mo2nXnpt({#l-J|TW2UD6+GFcoo zFl-DMvi9HAu*N{j!HsRY4)xs0s01L6)Qq_Q^q~V&PmaklRIW_LFn9iyW~!;tOgzaJ zU2S&CV&d1K#$m$@M6{kV@}!bkKLqH+A>4?eIvL9I+szx{Jke_L(PeLea+=T z|51UmJfDo|1j6T=jF@cZFS9c<(H$!1>yc+g1x=LgY&*#K0vAfnNoTnHoGTF>vRiTU z=(Wy}5&O}vUcv0WnF@nPLJ@Q7AAX~!OvH+AGWZdnnn{#dZl>U@_93lco%@G|aN=&^ zVP%(&3-T;n;_euS3pjH9vyo~ULP77UC2*Om%AfB2N9TFMgGSpP;WL;s>RB5OYVrdL0ewHSX@_bO>dnA)1k_OSo``0B3R=JWj5=h%qW32x}ql_+8#F8ttf>z_34b=%L5 zH8tF-wYmy;>y8E>-uYSPX6L^dGzu?yQWuQ48uU+6fRY-z8alyNd&mX-Qg z?Tx1nMErRhju51aiQk2&+hzARb=@w7Z6h-fDD z2!LP4MeE9vFgM1YqglNQtdVD#Y8NfO6SnW2P5Y&aywPfCU3J|+$0q#g7%b@Z{9eO? z>iq1w4YKA4-1@?24&kkyCGQdA3Lj<@33U- zWGW1y^x8L8U-l(C?6>6c)6w2>=WtgZV}=PM#%{vb;to0#Y{g>}Y5Ko*g14w-T9R;Z zZ5IjH40cBT4e4HwvxjvHa;=9=B%Pq>PiqfWbyM}*>+lEH1rl7VAyb^r6*M*kw<3UW z<1=O7P`+(6L5(21bB%R=!ZEX_;YDCK{o?ERG#c9c#BFK0Bl$GA-K@ICTsyyUJ+X+o zw9w-St)ADp_8InmB2%x)D*r!PmLIEVjAP|oQeBc<)%xi3+I3>U|NP!8sooOD)4519 zt?2egVC?Ui52)3EG=F-=WN0;{03&H`P*(5gq6spfu?HoK3Tr%E6W{FpYreLd2Q|hX z#uIz)tLD_R=4n@@5;s#t_Z+JafLs;DL&$d*l-t6_`R!Bs(=Q2TF%>u2s0VN(xvIUj zOtr__ek}|Wc}sJxMA|1rEh`vT)orR721M0P%Z#;ZjlgPq2Axl&_~iRj4k6|a;u7wh z=Id2Jd?lKE&u{_7Tl0dM67@t$DZG?Kj8#^QBTj2(H;nN9FY~qR#>vF5@0XibEIp3M z#BY1xLc*Q`O!LkfnZB|3BbQnkU>o3&uxaP(1|h`iQl49$fOK|DW-5i~S5N66Hp``m zde&0XUn7Na@b6n@)$)#B3iL3CjSkg`pGvHDl=9qES089#jhJaA0*J8?3^)ki%IgHC zBr9w4mF{bG;7`38D`ca!wG|7JovKqBH}KD|Jy9g}uU@_CaNekRKbHGv)TBKMtNpfQ zh1?{0!%v3||5*3)xCb{kx5NwQYnC{24?(|%haUAJFBD6#ehubGYKVdxmz3DAT7mG7 zJPRa($nQ?KhSvo~Vw(iQEvez#V@n@`<-{pAsb2w%ZOo?0sLt<8yf}r#_=5*tU55!g z@9{F_&7U!*fP1lnZU52AKyU@|lP96gs^K~GZ9$$e-JhY|FSGS0uB>$(hK0i??D3+7 z=n$S2{~d~OKY7|k<{52*m2+5?8S17oIWX~=mB_gT+jCjt$Sw1l%r_73f7-XPOc<+6q7jpE(;4FPV@yeiKqub$1Wmjda%*8zA>oYJ-k@V{WM)O!FlEOq#dW|gN_ zX>EA24*e4+BP&;*2^85L((C(_Qgtq>Ubl|7?Gxl}8J}iY_kNO;w>IEo-P$wrBE&JS zBQX+kXG%KVu<%domlriPhd-m|AHz1`7-G;y^sT1<}r;9#U`uP!YOL(UeH#HUr(!UZGq3Z<_6AHs|sf)MQotZriUMS|Apnf2Pgou8 zhK?Tp07NI(0jnd;ILH9e;Lk`OtM90;DCPr_)b5=#sVH@d?soFU7=H(L%B)C-si>%U zt6xZrse;7!Wi!)h9;6UBCM&nccJ^CE8h$9QZ`8MG8E}sCK_j;ry5w7IEowx6A40eX z-<_2TdPKSO$ndt;5j6`=gEM35ZPL2+Ufd%7cv}js{xnGv&n+N(BRMYjrS7wl2m{NH zt5>n`Kj6Qe@3iMTG4r#9fz&yf2HB)7?!vc95we%|UV0oLXmx;jYfzBN8l=UTO?w%3 zf32yOW=8RMY>ar*f2BV_4WBiYb42{+-=+WE(d%W%Ig!^gZt|eO%o;S*nQCJ&{m{G5 zoyNJjUiw#+LW*l&0I-!rE>$K0wDwP8zvO~GSDb%9_pevc*UG4C-Qe65u^7y#o0xq! zF{`$IU@ZO8#R@zxBi;eq2mdkRk_)2!v|i%^#=d_EpP=*1<*Qqa^kzUifTIqtMIWcV z&yg0X|EwouV>`OiilGZ(yKg3T<&e?tq-01r$gZozEib4NaL~*@i6xZMoBB6%e(me& z5Vb}zXzIDSCe@P0$~shpbm5y)e=cS~nRtpPXEY6|&sZa=fR)3mVx#r7$?)TLCCnDsEil@Z@pGN?=cMFIbcy8QNiwes)sPqIBR-)3|X zKSxc2UE`JjL=ATAowt>1O%9W|J^IUKe>c?nTM4eG*#jM$j6B{LVJ^M9UrZQ6`<)vd zY}4FTx#6QBgJUJpxAHjbW}4+!6zu-)exe$|(SoF^*c`R9k@)G1W6&OeY@ol#)&TL^ zH+};&UH#66J>wr{TiWSd)b5H&Pa*809ZnuYkQCJ1eA#^4$l% z4{2(}@V@^1@2ZyVb~>SlY&{jxaR%Uuw&Ho`J{^<$!qHV9kxK1Z*|162BFOZ*%F(x*3+<~tcIM^9L~Ph z<~&HUY1qu?m#<`4K2jg2NXm_oaHV zVs25pAG((_Xzr3fkZ?K~tYSU7+_17p{mX}&^2<@DRkhn6wP4eF9RmhV#D<<--jGAa z4)Z=F-J=FR5O{PKY{{I8H_+Nxp%l5L2)%tx|EvA&z7~so-4fU=xf;_cCj8B~%t6V8 zeQ9z(=M4|x)r?&yAE#4NK#`MyVND8pi|5e7Le2gs+dT`h02;XKvs&MhrDx@887O*J zS^BIUDf=ud`-b#x8rz+Z#NO&}!Nc8(;=#Ff8l0lQQC1dRN{aJesPhZKBFWX2ZOax; zx*#%Pu+M7gnJdjc`71w-C}HNW*2mu_V#oa#WKXsDcr2jUXvivfTVk9polb+M3qA|| zr&x9El5SlZ-2oD+6ny5i4mH?(wNyrUHc7Mc{|=R-Th_98n8Pun*of_Tq8b#zB7(n2 zvJ*b?SUj|(F=#oulTE^{0hI;GQbi{}V~y0jIb3UV49Z;Y7_Yi3N@>k2na?aQ;vi%ojh7&RnoyaAs0*G-CSFmT*yAyHESoW!tI2iRB8~M4boY=3+$`d8J))(zMapf1s z+Og-`S~i!98mUsm9k=Ls&N1wMfcUPyHDOB&y65Ou6hJ3}IZAIFUsf5| zxl_TA<}K(}i6R6-T#UYyMkOY7qx9wseU(8B-&j<#ZEiTS=?YJ*`1kOU@XoICIEGm$ zbc=5rE*gA*W8pmu=;ic5h+St4x+>YGM?E!Myi>7TAZulL?Wb{Z^vw?m`Vdso#ry`V ztf}&4uMR9PlW*sIrsytZxUTQOA+oj}QrKYzjyVzz#t~@--P)$FgOh^4dmjk(PMgdM z%-5j8=m(DRolUqZ=!_Jf+Ti@+lWnB6O1-dRfuZ^Tpp(|Mn0k$Yng^FbjjxdnkUz1N zw~Il2IB7_s4PnV@Ew(A?ryUkM5dj}wv9VYYjR2{~LvES75H|Y~q zD(YCxmV3&(Dh5?HqW)X7VRj54Lg3btDqaQL1jj?brmm%aM@XMh!jFR6KyT6n=o-FJ zO}TdM@K0897)whHS?fJq#oeDtC21;`s6Xp$8hvj!O3SbJvxo7^@@T!Co!qnte674k z%5P0R7OmzG$^Qu^pSky3=_zh|MZnInaEOBA6unoa_bke~Kdo<_TD8zqA-Q~EYtFSE zvwTPV)2POQjPY9xH0tK@1K0oTqi=CeSSfd`Hnt^yurOv|pJXAGk4FrBo*HdTY-Fr= z0oL6HfIH=ob=lX*WAjg(rg}Rk7Vc~+0xytF^iYMQH`GhX+px#r>&~~j_Npc!)INnT$|h%_luAf|3?KqjJO!gQ)7 z;m->(pBAaa>ZJxi^-@|aptNrd{`oXEp0~puSOUMQ>MxOy_k~`;W4qglSx9AxR@!L) z1Y{uL_P^unI9dKh2igmyX{|$YtoR`5fM9S|Ul0N+GHujx5KK)Fo6+{Yr=#(S%zgeV z+$g#iQ{ycTQS~ftOX$#_pF!4XQ4@70iffbDIK52kL_Q_(Pm6O3c58Ke}z*em?{u9U+VJ+_GYuJrR|1}&1JC(S`HP1oOO*6U;2-%;}o zc~Qjm@&NuB6bYS9>`AwA0c-l3nMQGP{;pxy+5C@Rdka$4PT*Ofo-{dvb;=!Tq_fs2_^`RIA=)o;t?*$VZt$q z5176irEuvp1O*7fN&18jjx)8owB!R0JiiRuN#mky`-5q0|g*)<9Ympj1XvyB<$J@P{RASG)RI6Du>&)(B zMqbCU7))s!o1%+1CV>(}UyCq5`f^u$kG@ZgIl9OEToX|XQ~~P12cq=|wK-`Ti!ouo zn3SNgjQ%4~;w>oP*B(V{Bj{rq=`TzhY<404LhxSMncLQ}`}y}G1^H;DClp+0I`;Qf z-4DbXk>wv8urGxk!^Hs5^sQBX6Hs*~vd^g{9r>5ec6R!m8`?mz!u-Z%ZNuCYqH`qV z1~e5y-^Fu!9IFEAm|&}dLE7VT-+uG{^gtEfw#J`69b9hQHPojw9BblpEN2+D&z#UA zX&9IJ-a2IsO@Z2_!yJ?Ua#3l2e>B)@*VFzDX>4@a8Q!{=wu9Ph&!pbOb-d!mv~us# z%jdO@57LYGU=59NYwzWk>Y%Off6BvNvW_y)70Yi){8+WHHgkO@S$t2!@h7_)w|jJ? zJ_$98^D%dGR5_Yc+=Cm9-1s-`rBBt&*pr0BinEx7J;D}c5zYL~;LV__&0yg8+lNw8 zWAb57I}gYEP{f-Ef_=RP*xr4T*l9fNQy@s^*nc(_q&Rzq2?VFCzWR3MhnyqqLyy$| z{n+d*8sKBWSBD7gLj5^}=i3*Jjv7V6NUH~O<82lMUi$r;{23O9;W9YJA%KR1W?jss zF5=1T){bpCDLv&GLxars3(W@D!D(4kjXWlUI}8#se+7SNHJ)#jx}j$_$mIytg-c$& zNkVh8Kyi#j%|NF&rDUNhE@u72USRsZk9+YIi7MI>6&;|Z(}4zB-EFo#4n4L*BlA{y z2Mz~)V36azLU{G=`gK)o@zv(m_k@fQF=b1-G!Pi7SBSM#B7oMi{nP&A@>z#np?w># zQAnewK@=s%hZP3Ko2!dQ7%<^VtkSfn(&#|T_6D9T$2akOE7X>@e+5g2NUz&4!$GWA zZa2w2-AoaGR(C9ezQ7N+qrD^y9QLu1CIwt_x!InkXIP&?IPtdd4sXWx14NBJu(mE{ zNoFIuXFR#;t?8rHsaE}3vy24B6Z!|SNFy~XpN>Dy##AHgQ$F%{e&^cN+ttBgP3P2Q zOSX~R=}M9?!Wty20&{l};-;YUVOpu`U-~7E4kCNxTBfD*SXGLt~ z`Nuz~wXEDb=5B7S!3JzXNFD3i!_8xZWVQ7iMe1bhR$+e9CbAznr`0pNzb^c-fvLLT z?r9(z;6D>=p)m`|#~b%8gofKvihpXUauiLUnc}b6aJDs}`>Pdp!+}#1e5d(oYUO7Q z%}dQjLC3y`X&pJ~A~I4AdplkZdb>9|@6VS#TL10{rTiNOU0g%N67{JM=nlkh970FY zhP%+LuQoJ-qL}yC$QwYW&wp7y_dr2l#%7}R#iN^#8wyAUv%El!qwk81)8f%Jl}=Vp zP8B@d7rOWVuId!B-D5_jSbTv>|U>n5b;#I2<`F1l`+4u!O!W-zo)soaINfCLu~m3}c~uB`V%8!>%CdI2HkWaCF=Y z#6y2c(BXuF&$lELlE7-2{y2Uo@;4{k+plzjO2A2J&rN|{N*n{DYVS_6D=}>XQVLwo z<>xBE-fDTL9kyefVYcfD8&&bIMm`$E*-FUz0ztMl!sfRlI z0esg|iUM@5;hL))Ab#E#YIv7irKQtu(B>3mSf;NE!Ld|i4D~y+v+~_D%Y7_N@QxRG z(k18vuj8XzzVy>S43Xy2ge1u#uUa6r>Znoh57SiaFph{uKL;82-?ho#hx!UnEb_&p z*0xK|oZ-7fq5#!!R75ROk`>mnxNa|PpX}zk?;zx%dhoDM>xJyK=z(4sa7MNHyu{s! zD6;-knzYe&^Z(jBf%>GvA-5Fse7~sUU(|2XPOw%mEW$x0qeD66%#=w}m4J8?TI!E7 zWLavyNhM_&lX6p`N6}tmJ8!f{N8=X|Wk6iij6%`B_DLH=QX3bXF8tn{($bFQgI_?l z#=DFFu^Dw&V-QjNz)HI#*J}PrOrGdR{m6O&A@AG5Eg|LD!{ebR4cWVOT^=(HVF=;H zrRW;3BXOfcy5|n7n_mbx4sGWbJ^WoVLomsYF?)zkrJZj4A<8 zd?&-F%)|2T1u8=BA`jWms{*qtNDEFYlhZugj}Jy0HTAMTNLn%du8;GzLh2HJl5YN< zByFs^Gos5-c@TUtO}uLa`+ov>uz8BuryG?kSNT&7?n?HJFMsZ2DzD%QGX8z?p<1vPz>^c>?Uzp&i^%u70~%5w-!AvT&4OZDUD4yX-_ zeiKbs9Y@;8U;{e~94_yjG_D+^0#Rw(QZ9u{92*$t_c^5eb`0><{* zdJSefIzupR0HL}A!5x<|hg?@oKHMFcShBx8P@pTek0p~-FRh_kLp1XN=;`u3kF0>& zjr=J2oJyo16Elx1LgI^Zq#g$m2mrQIQS! zF0Y@AYZeXvN8zC13Tup*)P}h#l+7C~EYF7GgT?BV9a;u&!%fBrj}N4?t0wZbyyT+6 z)a5&~)%lg|f%$ox>&9U^ei?rlo=}AS2s_(YW3d$+2BitSMcPhg5#=|TjN8t+L>T8pF5gn1tdK`jp2ksKbBmm@Wh*mr$9tN zCTdktyTH8&rPnU|jZXa3rPY6z`F*v*1&og+e4v2W;i*ARS z1%WP5l8rt{G!#;SQm6qd*m)d~&-JrPci*3ITRcSLm=s8~H&OJ0=Bq1rDUx;0p zxB*6?Y#wWpTJ{Qi_cOM+|6JnO`c*mN?6s7VJF&ei>BH#sDgO^sUm4U^1FT(~qJ`pK zw73=b7AO>oySoN2Uc9(Nu>!@4JHg%EB@luXFYX%TJMX=7XTF*I%D*Hh&+b05dvX~} zr;KYSDFRBkukXTw6a_x!N}i~1KdT2F<>*+5pPD;il^?}R>A%^-#oP{w`i;J1<-ZW` z5Sbk4(an9BeM|J8IZz*CWv!wWa4@OdJX2|+IB>EB-O0=8hy6!z8LAD89VJD*y&t_` zGWf4CHQwi(wG7X49^m0SR#SodXjLvn+V4mho!&22*0*ZS_MQ>sv7;YzM}_O5`$&AT zar(GD1->_7@-NER%mdafF)Hr;>2#bRL-&lMd7|;pksgr>UeiYRIh|RAo>2H(A+rLs zR3^YtJEJ+goa+4&e-ilG}oo&$9+=BnH{Hj3I47;nriDPKjXEV z?fXMhMep=#VHd{ZYpc1`G10wOrAwnr>E~QlsggYEgU6bei=&ofS`D9}^<|&b+C@gw zvJDXgt5cB==OV_mrwS|etW)T9l8v}?`2Wdi>(Z2K$-DS5fVD`IHh=jCYj*HyHoh87 zK(4f1t2Gaci&Fv?mG%qOg~n0rf{w4TL^YBPP`_h~Y83SARE$@rd~O3t@Cl}4lZ{5n z3N*4R8GV~7d0WrvAGzRw@XAw1+so!Qy27~JE*QtO8NF`+Ul+gFD8C#jr04GOcWAc+CR-;4a~ml6>78751kWw#Po}}vG0R46!k6JFEMnf zrqr|hgH7~1)~Fin7f+Vf9wwT-e%_XlPPmrE z-d4iCnLEX(Sqv3i=XDS8vAs6|3sCE}$#U_p5=rHHBiX(`8stI+x45Hxxs+W=H6qlI zf>}IQtdeXhrk_9Z{0v2ZRFwUz@SZ0%{;l*YkbZj@(`h2^);thiMY&J)W7}^b$j!-X8iRAc5?%I;|GwR5db#SFo2W#=umt@4m6li zUEqeJ_~Tg9iV}7h^%$Ba$a{qtN=@y7a@~5*g6q1@L9^qQnDlVpUNV~ZwD&Y%nL1Re z(eU755!uS0@fmK68kP#BVmfS#BMn);_89gB80uy}-b20n_>mPoKR+;q$3OpB@3Du- z4dx#r6i@8A+x#Ef5Dp`gE8J=7KLJpqlO6DyRU~SInXz!w%!jIAK4w2_Xmpo58>Qk1 zwc?1NH+ya|Mfvy4;_M`{zp+T(s_fydzue(%(;UTeJtB5D7uPyQeeR|4*LsBTu8E7Qm-s>1#*`ZfeNBIu+9&x@AGrt_J6C$rMe!(MuDC+R>_dTgJ}afoSL#UY_F zYW3^+Pd70%BtK|LxNhC$wgtXxpolKkeKPWSEJK39s{aRD+CBou#m1 znI6!@25JU#tGMN46eosUOS=Pd9jO zAwKpG=Ie-%Z^Bq9|WGKVlU%=NhPTSC;>-&Z}Ni0JQ zDlTxdx6J=ZFt188k3L<=+}(ovm#BliD8x8LS-*T-2@O1_i#LiGp~>-VLoEx|MzQJ> z644rux*^m!PEOiv@dv1GK3+%6P>L{BpT0l`wI?0a+v_szO7qd@C$ZXJ4-+g-<1~jl zUgoG7L*F07w}%dvTvOR3cag+TfE7XtiSPwPXtjPd++N?dhRfUf>I+h+Q@C)#xp|8A z2(MWvnQxdZF#!iJBp|y5Z6r*fgw*h`=**|0L{)`Waz+%}!MCiFR zl`G;e281eNGJs>1tH%8H4D#A?)?CYT{w**fdPFC{y5i<^BI)b>cc1#V$bDmYooiEP z;@`?wR^TAQ+d_hVkL4#V?oLvgrWQ%t$%vri{Sg^PMn*wy;kVRXo#eVSNJlVlfoC#5 z@WAPDd-q6~2modHEqV(_(eiSKSU}Kjxomr$%G=`2ZIY2vm8usn-d}8d=okvCxIa+G1Rb=;?m@>AaTysZ&zfn9Dgw zxx^xeco>bK$`UZ=;Zo7HfdEA z@-P5fXKXpTb8TBeZ_sAxBwIzkZi$&PDiu7y=sZc+%)Rk1_2PE{&o@XO8(UW1opY4l zRU>`+&aAd~l2m2~Rh=rS6MXLNR?##%*3Yv;i2qYQqP7GSrjf@-(N5!5hN)9)4|T5# zB=lR9;154;R>xuL^?Srz*}Nocv|1iG1@n;y&_L(#jA)a}4N`Q^ppPe?fZ?hIP$6sp zi>3F^6=|CQiaA~B?IGKf7m~}Dg8)m%Nvq3V>e@F~X3|5&8?q+s%e~E*I-z03_T8dz zg5Eok;CNsosCbMn?&VIg%4w1b+s83NxrvYEh+90Mo4+FDcp=sJ&)W($c35HlN+D38 zdi*9Nu5Pknvly?YopZpG67qa9@1#|==$})$NM^oN>Cnib&?zw5*gSEFO!RACEeW;=L#Lt*XRV9bd0oG`f>RH*jJ4 zKQ91|r9z_!S}Lj z7YE2b+w-cQX6lgUVJuTc!jv^$nqhzc=#;s)?)OZVfeOAXnfJupExq<6Bl$%a5v2zn z+}T59zO9k z1~A0iC5`P(?WxA%FHDD|8`qtZSv(rEX)J4eQL~A;S>W$$ZMIl{7`5Ik z$6}d>HAoW$h!*hL4gqI2M&WZ^f6`!`=aR?bf^>M5-Z!glkC#pS7I?=enwPdRzEpgr z5^wpK%Tw72T;DUC`z>{fy|hx9kNR1fnFUin{`I{M0Yn#{9w^WeO;4XUjR#uqeiDaT zv#qGJ{AM~;16Jy=0(+Z+9&LM`*Vk@~+6N0gqIM9ZrjdpvzrT~<=6+74P&`SDLL$xS zM1ryAT#C!s<>e<#h}*uqWfm3|zVm!(%#eV;$lhOQb0o!ANa#*$4TvQg+B~P5yqKr> z(cZql7(x;A%|G^=p?!hDw%mDhu10`1%i44PnE}(g`u9o8=NY$nTDU+;&?Zt>8)b`n z)1E(A5>iSftt3AABpZYjP(yjUZI5JEC!g5mdhCA58~iwa`(GPc0w}3os7rVm~ zk3%Q~yTnlKG^;zlT_SBlsdb$4%ttYs2Do`%f@xkDKk7pBho?9Ko-L?_ovSV=C*yRt zi&5&nCc@NAUdCD_cKL}ncRVJ&x2N{aX9FVR)B%SXMf&tHuEZn99~DLK%OiucVbI0> znSkEaxp%TLxY}xpzO(pqQ!+I%un=NATl`+Zr>zAI!(vKjdk7^%#4pa#NBas^u&yBf z<|sg~%gB~xrFIzcdwBc@LNxzoG5;*F(i~1|OUUkLWFYKk5gv#+9YPy#@-kF#e5^Gr z7IkF&ahJFrQTQb|5QSx^3YYUmY~=fLxJ1+N=Y!>=9Q|!HnH>_jhNtuA+tW|LXh$dK zo9hHW^u$`PsuIzEI`;pqrbV;Las9%Eko(y%Zv)in6YxBcv=i4Bymv{+=Wua8OE!w> z&vXud7HL5=_UVn1a;Q_BGbds~nrk2i`R^oRv{JM_wC3iIX!?W?fVwjX2R#}RinSCl%gtn=#zvni6Y zp}!Z^hxU7+PU5``wNaYVDvbz4nSomM`3)#GvaI@x2i~E+IUgyW>3+Uqpg%abHbu2j z+TYUevos<4Reb%D^NetCN{u@7Bj=9VnZbt#f#hLD5o>45eCt^6T6EZ_gD}o`4}Z^O z=WzJKYrRr9Y@yuf+6S&-$PGyO9a5Gt-T(~k;%1SIGLAhaf)&|)#R?ncgP&~s%gJbo z#IySX=z}c=?Dc1Ug6$@@8ggI()?t8Ya@?M<@;&-&fy!*NrlMh>HqUP1q_dEr948i2Ns6RDzI z>;C)lzYv?|7iif%@4{F)zixwp?!6!nPw(_JCYw^W>^OS>j(JaCmV4DNeftTEw1#Mu zCJ&C|{BWIbP@f%>lq911C+j=e$Ns;6xwlOI62i6%jd`->k@<(x^|JEk zySLPNoL%7|F8FFLIOy(|741Zo>HjCHP4WcVle|dyI#E#$xv$^*lPU1Y8GvMhK}0=Y zk(n{*8C07aE%YyFVdf$(eYHn|iD{A9KWw*!G8B16wi$k7A^mpA65!1k$xItp?}Chs zje{wNw(gc#=sYYGeu8xC3ON$-)J-L6$9(SvK z+mFyI2!p6R^vX@lyQv?`RpYkTN7i3LhGxvgtE{E@2eJXleEKTwtze$87T{ofRHB00 zCU5sGQ!V-H=|{C%WAli(>V@7^0Io*o2V^B1O{{6S@q;rCIz~v?)WHQQrR3gnjj(V5@x%E@-ilb z-ohrUJK&m(=MUY7rr{k-P0;&cVh>uGSi??W&HTf#pOu578Nq!RR#DA-45YSPT1((pHCsQWz?0y$gTh*ry$A5Hno+6c9ui$W z@>n!SQ_F0rzj}jG$`lx9DmwwxGE&jfrq2emurgmx{&QMBnKZIuU_0XZx0yE4$cUzx3CtXr7Bx|_^ z?J}|t{qtYV7e>A*5M9`A=|qr>3#U;`&j5qX;f7f!h`k0C-A}OkmhaLo7LZ1gANYm z`Ik3eG!N_?c5=4za-%3ODh*{|hoc=$Upi9DbV#+!)ST2vKXD9BFKoovrQO{!;k9JE z-7;Va;cVl|b`AXXVuSnKIPG!U9KvltV^hav+`t`HEzTJb{e1G#Bvl71z>V09X6&HY zV_YOE1H2~*HH+k()CAm-y2WgnHw{1aXo-#w_u7_4cp7fx0=(+nj` zgd^7zvM}AZ@Vmq#NiqZcL=!(EGmthl2v>WEPh*lzPNpef$`l?|oN5lend4QNjc7sE z)IxSBD2sYmwu|Vf3fLT?nTqM`evBPRep6eXsSPb;k0P89eXt&lC$ zyN=#9y+10Rc+U%gGSOyku5}$m(^Ncx((jj;5;6%Ovw^>ly&Y7)OD2ewASi&o=o^g1 zM*W`Jtu^Ly!P&<$D>hDeNC;1Ud-a{An%C0!gM5JYx=rIRq@>v)Ar`q&E{PkAH+|VW z&L2Z7L@cENMK0q_v%2h+uIXsRGn!l^DOalP$o>@5i}$iQ)^O{FxL0(zL8-IBdC?VX z6YtLyPu7*73qL)Ke`^WP&a>UG7wS&_1o@4`tflR|Tl^=wtq~F)Q(le;o5kAJQG7{> z-a~{LBB{Hv-G!OOzKRiOm|6TTQTsr&c`p3x*Dq(JkjlX~V)mCypBU?;5)C$|5E?Zr z5AV-2^pvuNBYD}bcnlzoLnAxO_(BbXtVoSAa)(Adw7%v;#6BVhJT*m#!oaTi*lZNI zu6CS$E1CotCIuW;4ToHTe8i<&=$xC<4^2d#s z$%&IEn0S`<_1?(s1KGjJ45xQ>)X|!g961)X8q4x6vBQ(o?PW?RK~j@`$7TfUM<|pJ zcHwnXb9%Jar%n8-+S)MWi9xsCc)g?e=taMway-o8QtX2O^*ORVW!y7IP zZduRH@xVvqFO9SmGA8VK5I(`$%aDiGX`$#OZX!#RUId1;q;=-fU1W2J9{#>Hm%;mQ zFI2RwTn_OY)wTkqf0erwqrH;Co}1LkZ$5uU5ms)*$>wY$a4>Htz=zM>9k!wWklDNo z2RT%`)8$)<#p_(M`U%IM3b5HweEhsoH|yvWeYjwdX=qD5%HtphKRao6 znHa@R$Yh4HJ+A+!MG8Vke|cPgKjJbaGb6V39AB*?*?~SwOrQnML+h%t-!NDX!&=L4 zX{mozrk7+qAHuEKo$fJ0O4|PGqGH)V6SdlIaE-)dYTogC>l;Cm+7?(}=9fhB0E$yr zfoEyrhPP90x|A^-6}Pxge3Oyu9~*CFiRU@DpJUpW<;~7lZuUzF)&?B4nvULwRISNj zM3~MuN66qs9f0i8$Apx#w*NyFoG>(kL{oOe$I-ZmmF~9vqFHzxU0c_`Z5=-7j z^Q(}Sd~kY;g>|qp5`N+vHTAUl`sg&1%m9l-u=?Og<~FA1#ObsL%Je>qo0i6&9s64q z$X?RwbKI2xzMx+)s3ayOvp$ObT2;B+I)}G5XKuQW$C}67S3I+r%Oc^Jc!~4hlmf50 z`FQu^(ofXt(p%r*YYZ4S9mydDq0U#SKOcNMG%+k+JH-=7flNnf^pm7AZ6{RIzi&x8 zl&V2oWKc#srBc3kg~1^gfxp+M%mdb?!=ldfTQ6eSbPGn8SHEWrDZTkPDUU>|t+Q~6 z1gpE@6;BRme^c|7|6Z^lc#1#E1n6owoT9+iQ?7r1kYAfSn$-9|p#o{LJ+oCc0G&W~ zhCiA`BMOk26>bkT#~_zyqb&a4Xe7W`Y1RadGH=MEgEWc%{zx5`G132}i^QwpuHBKDH`t zY}Bl8s4RPbR-JbvWEQ9AQB6l1dd#Fw74Ym;g*87JRx`D{%ie(vsa|*f>R>58U7Ntd zo+vK8(1%TO^8R`~J@?&;e^K_3g7^H^w26RubHM}Ilu)#@vPbK2$5+s zoa@+jvWSS6QMv9t>lqrAX`Qign(^{A5*bcc_OA6+%U?+f4oF^*E&Fn7GZnTCdG|}& z>zGg6h^8~oFVDWgsF)3E9|>zjQ5)W>_)(RG^{$ywV4(JF;{4M=wGOncS8O87X4glX ze-$lBF-dFG;YSGm9JkFv`MI#Fv~mShQ(2GOw)}|+*kd!*q_vS7F}X=7AZ&OSLD<5!8_oM__}h^XP|5^PW%&o4G)U>d-773Y);hJK z8NDzFWsvSCLvos%ldp;J=`D2SfZ}xJ@>GTXZi9tNyOiy<>>gv-z`+qt@BpOUgvbmz zxR+Z%bRnJcueHaUWC3%FB zVmJqgL830%WcDKoj;uR+3>xoUf#EW~_jxZaeF=A@#4qXozUxwVJa?SeZX0L>{j_NA z^2Roq*!;2%2m#H}{j*oWM8nnBW_bR#dYZDz{!gRm@W#F3KYxmkY zF0zh%q9fO23i_^6vNY7=(%-yExy#Bi>R+smq`xaZ-|wr)w;rgIg0?bUU;06D?y(C zQWrQLFr4_T7kst&A>Db3gnoU0>*{sV=>=WeX8zY&UkJ@LCe@^r)J4zq=A9649kY_( z(kDlaCC(p`?!yrkQ3yO;*#&>eXU4FNRpEC9;#qXTy+R?qLP)n+QWwA96!D<}F|W@) zi{$1o9SlQjq@~_J+)lFpj=#+vcm&qDM$-bZ60p;=-%dMAzIm>f=uf@1&KXNhl*EM_ zkp1x?O5=zRwY6e`-IdkPCKt`MIEBDUUb5w%oRBh6YmEfGgLlNNza_NC3S=e7nG8Bt z1LA%J1X9Br@G3g$9}t$8wOj4M2)u0$k@d2aM7D`O ztt{+mzZnXxp+5AhP%gKzX10rVkXoy(2{55;V&QoKpj>+`*MILZW;NjaT@kEQSh(>= zS1e)M%%U0)^YEo~kx|jF7kt(j-Eu5lI$Y7~(yi9kHS`g`d14X~d^z^RigMxbf5gGJ zP177ZfY#XX0=3x)$iwB~aIx>Vitd+B-giGpcbGE%95^pxm`sJIj zHuMcF9!6!_I%}P6gUzHQ#Tx}8zdH%A-Jgnb5llrotCBfxtFN)tCxUS`<_}NS%7#|9Pj`E##I(}Qj zyI}q>BiwZM>Nb>b3lDQ-HX0pq#J&s_r zB1AB=!!lqv+OBjq^NpURuUmC;S!%=xD`!E}2#@bpxssbOsJiy>Zn9Z=-l`z^-=>EH z2t@09wnsur`tBVSYn#m!ww2t6KX~W&dj*5^E#QYckke}CU$4R~qzEq}clmq{&m!|i=y@9UjeH|RR?$Zo3PcDE?>R`+0PfYCKOQXK}n8t1&Mb_KmS9e;CFN&H&d{wYz61=xYcvntg11oJI0 zedSt7>uZqU<0*J*jXzU!$gEp19CkBU+8oaNZdfVmOEFKmQ%g31gKIhMrL|Ba!zsgc zNjShN91Le#kt)C}4VMNvndBBi9X^c9bHsuFe%oa6v7uQYQL?6&Dx2veeQPl!4Hd+^ znNtwUQkCLIZXCFEt)(UZxC&I|Z{I*1aBN}s1A6AMEeT44eqc{VhKSprRb=R!C1GM@ zC?+B_ci2eBi_`*4d$~pdd)`?4_j2UTU7Ry=6OF!%`mERTJ)DjJ47Vfa8!Q4KY305tvJ# zf(ihtq2Xp1!)tYJR~RocJJIeK?#6cz ze6koM#H%QmHpDC&Lg-UH;}dMhE*kS+JAXW z85w?F(oduHT;Gat!x`N126-+1IfHyN#~EkqT1=%~JooZ?rzu{&+a^A0dWeY?_j;20 zPV4HYrlTJ!=S<~sY=|z)hL60zC9c04@$UVFN3#9cUjYx(xN!$%BL$4=LJ>7+S#wN9 zyfusp>HVioPNh`KS=pS0FOM=KJaF@Bj?l71x1S9I-*q+F&&!jxV}|4vCvn*{74yr4 zxid1VK5i;A;nhy>`hM9|X2jFvy<}!Fy^gfFp9_wi_*!A(!{hUDnsT{&v>$nQlPUeT zXye&A=`vZg7ZLb*bjTWS^P#|yo^0+a`$)zRhx0e_DhY${Ok;CxZK;{QL8-kXr@6U# zlfjAe!MjQ$7A*25-@WC-5q_Bie_VLr^Y{s`lhD9X!~91N-+`><`=j_BKMZ>r$=$9! z05WvOkd6XA>_4@MADw0hli%cgg#EQdfVe&ZhdwBFBH&6?FBiITRJSf@F~ecJK$&e| z>-Jyn_ZO}w@Gp)(Qdye%rOID0$5fMQ)1bQ>?@E9g`%iN`rXdwsM*)%Ng)#iC)qoWo z0!0srp<>PXXrPSIqH`+sz5Q1ToNM9g~nGEy|u4Ha5|xEIkaW^KZULf>>RI3#nm zC{#t*eNrRkS{`pu;C!*@-zQ{ym&n77O88!1t*PA4g_|5I_V(n`4-p_CFWbD2it91z zYz#BM=S&i?F{Kf{uxUVfzq;nd(1u+5};p-Re(Xbi7Tw+wTmae?+37Xq6T<3U`x|#)z{X zTI3;^6F|2N*(7%qd)482o9NMJu<&Ln^%y*cS}}8&^SxYoQH$C)ClaJ>fg7${$C(ba z04=JjBs|XHSZX6&bY8=fYo*TNF~H;FtzGg)oM!21N6hUgeibbHQ<+tO^~hRr+e*gD zI__%m?eIj@w(p}&)}p?Wk&Va;-;T#~+lv?OHlx~z>ez8@P85l18n zbBJ``sJV~lj$RH!vhJ6nv0g?B(a+qU7r4f9Kv9zugMT*bG(SD5AlX0P(5m;mlT8-q z_7w78L>cto3pm(kpei^XlCauj3XpR*!9)9r5QOk0*VLA`20d6y0oZUKWcp0tvTq-8 z1SHMF{46IBC^BN5hn`>!MKNn4q_-S+Z~2X%=rN#Tv6 zR93GvPy{s(mLJk!c$?bu4Fa72FA^L3H3jaL(t5(8IS$d_|6Is&y{oaA37ke(&-^&; zR%6go%>ShwxA@JIF8;baU{{_B|I$SVlNY@v*|ZU&_#&DaW?ij3!K7p%|9HkNZKTY4 z-b;97plpp-Y@E5Q?gfT8g-R1tIq0>7H>fo|?H@<*f{W%@&QE3!U^mo`L$LIZ?1>TY z(6~Q%K8*g{UMp)VIHUX_!5e3{FP)XMC-N1r&!~RI=dO_8?A2L#AN1{8{vxC?Dx~kP zl9Qw&?wnC8c2(|ALSk@9gHMY_hqOUf!|!MYyF_V&UwrLKxZ3XcE<({HV~ETe2Kk#j zj{!yPVH$!fQpgO4Myw+Z7FNr%10Tv{H`y`VG?*y*`zve*)VHIr++GmntrNVPr zb+3X|uY&M>ADA&Buku9dZ?AHfNDN_zW`%(N^8(0!m~_};NkA|7{v<6*-tlT#8#E-6 z)@m9BHS;Ykv0!x;*pBk%P z32C7Ho17!qAMhAG@csI<%)~D0WXkK$3uDjCxb zT)XX$|A;v}r#|_?68B@?%bi zUjq!4S=)?jj?Hg7xsQ1?hOLw%bNEb)3_`s!;!`jeZ(g_+IQAcynBk z^$_XU7V8&V|J);zi?_Ty+54FTf&D`fp%IMU@6k9t7eG|aYi;Z_X@K-$qQ&zDTvbC!N*dXy0APw< zdH(-U9ldIl_%DX?(m5f^^dnEFq>pHAyE;^83T)Y`ZK|{nl>HlQn-L-RNwLG0ctctC zS_4Lv(rY~=MqYY$4fHm3Rf0+%95d-{>S+fmZ&L|c;>F{fDPu4m6?`<;S1z zbJjFo%dZdls=mf{j*fytS@g~488|)7Vp`LgKrsp^ zTEHxs%ba`Ei>xh>`wj$@0C~_#H)qL8}?>5Cubi=mAok|d*ytF~c{B3kO!?^=?ZkH&^E za1;Y-(OmzZ8n!4i$y7#S`9Cm7{ zJF{e(D39kH`0o2$#r(2dmNRNk>w@Zcwz^g3pNEKmxjJudlqp!jK_-w zdHVd~rckqi`(n>m?n5CrxzWqqAQ+~w!`%MG(B2o?0pHQTiG<|ypwnE+#q~x6`Sx^+ zt5n6Luo6`Lx|d)O`%~z=l7k&_169s3Sp=&;4pvkC?PRa!67|XosL`IeM#y>pQgT(#;oLp2H-@QI#oOS-ZT;^S zZM`F}lWyUHLV##hN?5gr#ZzkVlh{53VNx~7O@n5UC7Tr9La}d+ucu47%c>U}q&4Yy zUHc31sDp8T4_{UPi^mU^UV9Dgv@!x#nGx&^7}Dq{`(o8M_BicvJobq+cFiTC-ge6t z&DH5gUF%ll_exCp9vKxE1yeru4|2+eq}_sVY1KxSgGf70OQ+1y^zc$`hhkDZbHDq9Ib@5luC5{dkBsLwv%OEX^5 zp=zfKEt2!N6O@5J$M3v1;Bx*P!xIX!4e%_#;Ur}3Cf7!)a*=u8HiVa`ccWE#sHyE+ z%KsBIKdR!n;kLc9#YayiB6U2e9npfS87DbnWmh4!shce8OAr`c7s_jx4YWOxSE2vl zOycClFUj^9J`aLvot_c3hU!_#Fs}`TLzNTy+TT-ek-`FAs58DVf)!x_LFuzk`;mqJ zD4+xX#Zi#v|6mj{!ITW5^Z4af1-%cYg7#BGV$kN{=kUDiCl6Fd2n8LVdr zNB>Cqs}+9vleeV7vY24b$LBARdd%Fi20zLdRS775GROwRs1xTlQZ z#o4XB&(qnIB)gPGf8uDt`)*kB<8++VS{!rhADEli9CWg$u*FiBw@@~uJ`;cQ@$C8w zANep5YYCVr>o@ntBtqlhpJ?uu?mO)}#TXI1pRr{uVI;<{T$S4*UWZF345k}-`Ayi8 za~rO8%8d8KK=J-8e1YB{2ThQXg9mZmRfIM0s%Ys`Wx9JH>nkXKh-S*bj`n*6(e*xY zT&K)7h>MANqo|i?=E0w?X`ZxV5(aRt{n^79EmxQA>mdQPhh>oA2dlnaZx{gf4buaX z05DDd7W36#`6jn|x{*ahHfWSiJ$NI&9IpOm=7oD&pqz81lZ*Y@p6Wt86s!;2eeEv_ zd|lIJZ^nT5`_3_@IN-woD?AL~o9SORdk{~(#*jHrjb(h{sAYDGTStTj?ekyM$Mia{ z+R(gDnC{V=TdlFM_4Th=FPVg9Ux282Eb@siHhI$NnF|g^67GYJ0@Bf*;?dqmUkl#< zkmZP2G0AC;=EGCAw1s-s{V@f~dW2Dx(@!YD?XxQNBp$XY_;bTo7ZAqEB`UzeTvNqg z@xIR5LTo}FZtX)IY4fYt4ZL!T9Ig|*4*Yxz6Fm}t+w#SBIDn8#|A*>`T^Cja!mwSa zh+oPnr&eP2;ju}zKcyV%oneT^m>b&|RWS?lvil@~g7@!25k~8YJ=!8ak~yk4)a<82LxVpE z=BtYcHu9pfhXtgvmpKL3`<|*O23*}v(tWe|tmc=!ZzC>o4m!1hBXLTCZeFfWfn$uE z*QAeC#?lsGWY0#)7utxgec9GCCRzyAf1$>qw)KeGKLWNk$`MLX7MSti6fwLf4lpa0 zC@4@vHM@^`HETcp)<5^6Johr(p(p}i1^D$#zpPrMykt{7-g+RIoXq}ZJdgd5UyW{= zEu_+@BSS-OsItPmhs6s29zw5UHi7B1;FGOf4w0J|7OLKaka(P*zE0yq2Ftw3ymKK- z?5e|#ENU{*nw&t-ADMjHjp9Uda&l;6B`+c7HmTqxrK9~0Ok}{JQE4q&2}De z2T#E70xlD0QHhDXzBF&k7cNd=B#?poFNo#XU12=EN}9gQgPzbg5Z-|+t76~ZmPmAt zC5aCOY%(qKiQiR_peM#>HL0k7x>Ba6zYWt|o8q>pns%9(vA@oL)bW&Ko#W|B>3a<} z0}BNmlIu)JA*-mJ-qujQ-5bVA_}T%B<}u$94(%A4=ki>lX&Lxj1<9xdU?vNQ5QJyc z(V>>2eITfXkE0I?7bB;lS1rr>kUuyxqTE<`ce=2gm};U3GBger24Z~pd2H~^^ z*~u8i!arQoZW5}n^A4NC)!Chkv5!jMxSIV{jFvMc#|$4y&tLpUCniL^M8pePWu`-H z9LTct9F>Hy2-_1V*@Uy%Ya)Xb?C)2dwgB5Ag{Y^H+JYV*g4WkuUi-{ZUi->lCa4#w zuVDGT{HO$j*f=V^9V;iJ|J~W5F(2Y@?W`hHiihp~aEQzS$goPt@P_ zb#I2mn&ik>x7}kEAN_1`WDC%gZSY=%XaJU$nadThZy@i*7TfLz;F$XEErWO1Cy``y zYm&YWtZrmJtTBdpi8lPW>H)<+q$evwvl3p2NZ6K`*uuuC!ryl7S*MXR_0X2;yn_L?oH9J(N1V+Ju(W`~U61m z-s@MCGh2>zu3LXr;cqo*b>7M?^E5`k{gPYdsT{R}M)lcC3E6ppN8Y%O*hxWPGe#ZN zL$mzP>8Fl6`_?xhID;k8O|?KKFk9KBTv7hy8Ottm`**78B*ioH=kOxI+6%Bx2j&iJ z+?WdSBnZmI8P-*SX+EA!JpQ22cN%H}3|MbSAb?KmuRt7R`i?``jiAY29lxtIIv3JQ zfwM;#y&>@9vbl!q$IUPGyL`-|hEXl#OG(p9mtZ?g?y4RK70Z3aWs-EM`+Cg=`YxN| zMsb|HN^Mvypg=J*0gI&5>9v!kH0As2LnKyZ0t;cLAS=>~WU&%kc`gT2E$H@;2fm_y z;_7*pCFR6l6f);UCGjah3-P^-KO66%L{=xV*L&s{&I9Bo3poeNrrWRh(Q^^ayr1Ru zD@;avOFV3i8~xU%qWS9qri~D``NdG35H=2+v~xf>_g%}02SqD5v03|be3l};?A2*e z+%U?*6tl>Gl)b4mf<(Q7Q-5uh*xEQE(usVPi#0r28MW4R+~=(+iFHJsu7?0CJC4|~ z8mN9&!$TWz*JQ}}_O|GcVlC^3`Z z#?9)_b6pOv3&8!XaoV*_^(Nry1`0pX*5Mwn&J4v>S8*WK$uQ_oFmdqO-RU_q@;z!T~=>lXzBpE*D6J1d;$5!L-QirR4tibS<8h9Naq`lRu7+ zpcUe8DW25lGC;Ti@?ld&)sNm$i~@=wdP&qy9625k!s3TpLMofgR;x1V#JVzu{2}wW z??fx(39WNz$Uo{>S9j}CP5iF%v2BAx3Jds496_DB?EG%_>%2X3 zL|A^=4KbtmZ(5IL3y=VsVXmZGC#E$`ywF(k#pKXdS~IhK;Os;eBjt_%aUXra#9|_pBazkOWSePoFHPZLMWvS1u<- zQ_-D8Rd-+g%_3^5&}%F(SNL|>sFu>&xL#Pac-1z)*d}8PTYhfOfy;+3`lVx2^vNwA z+6&rK%o)WvhjAaz9)h)`J%XEgV-rOY;<^=>Cr2$mw9&=PML5^ndFVKP9Kr6FNJGr+ zsTX>dV5;@;PqCvBf6b(oFJ+5FmW5%$&|EISLlndP;fZEGnBrikvNDa7K$)8#62E>; z-N!lj_hW7ksPDZFQa3WiGjh*>L!v|Nu=VRyU9w>aUXbog&cGuRyb;6;Jok7X{v(MB z0i+sSmSgbk(HWllP99S;@+ndftbtX}xXL znYlf^qQI(TmUpU=Tp=Ekoc7ES+1OUmEV?v^VC}J@4s&@vVDzSUwVmvGUBL9Y_gR7C7;Zkt?px9 z6T3j)xt!SP@^U{GaV(=Xnj8HJ(2a%+4Ycc-v()oB>vL_ zS9jcYgPj!FDuY|@f>WLT0W2))OQYJN zyLwrA%C|PjM`+_fDO@xwxLX{=fv)RIHLTujGadvM!`-Dz_bpEaPG{hd{CO@66TeAj z1e|ESfk96e=|et)G}j|%m&J-%+I%{$H&Mf~4d_uG)ScmJxK;o8e5w86coyNk&v_%E ziFi0v9pj!k9nt{!d?F^>zi$v-J9A~UKP@UN3eCe5F7}X_dj&}fTzi@R+$s<>$2lA} zx|DC|au7mgcnb%p)ajetJYjz5{uTw{j4|M#%iJ8_a|OJB7V-a&rf-hQtpDE5wr$(C zn>5*;YO?K`Y#S3N+nmfhOtza`ll`9O`>x+wXVtn_|8&l}Kl|(pdtVXJ&9^Y18~py+ z*JqJj%n;(9DrZTuoNfhuYW+CyirHGecL|AOmUz6960HMwJ%lRqevxmfhvl;JsSz%zXi($~S zG9It@hw#nt9&D7ZTZ2&$v%B#}K#i!H2_!es*I1{ilDI!?CetJyn74-1)pR%(CR}N4 zsgYP>P|g#nVE(-yfZv_>_%nhX9eiB}sWIdJHJ{oWAw>qt8fbq|>RViCK=8rU+B$>~ zz}?JU^QY^{2{_2b^iYHj)ey4EzNJQ+~zCe86IkSIKjaJ)M2vd-M{G8kNa9f7dh%VzZ}V zb&wRgcd!9(feR;?d#-aXg#P~Hp?Lj<*NuIl8=EEAsfp`z$MZj2zklTwgsrkAz6*IJ zroJq10*8{-54GWqRFjz(B+(V#(}LElM=*wSYk>=XZxWk3@HTq2(P|I#D+qvJt^oWZ z)Nd;$cA>TczUKP>A9z8PUM4}oBbu88WR|sl`Pa7``W%YU-maUxp7k5xXv_kEtoco9 zReh?XTNM+Lwrk9Uz4}nTZZ;`ykRd74bYL@VV2+ly5o7NCRvN`;QeNb~w$|#ANZRkd zE=1R>sTVItg{03NWsRH#{FVm1kFu|u-m@}TcO01!llFp|FOI!Ilh}5v}7M&i3WVH@EV;uiMJenJL^KKbQjftN0?xUs2 z`^U6anc0h$pUv%{iRAj_N}*4n;v(A0VugSmx4086*r0e~_?L_7*moUW%~2iVZPl_e z#3_27)-u6mRH3xH`f5|c*io|1HZYgG?*dckM=5^ za-h#m*J8{?k3`UZjFkNNJSK=0=1Q<3AS+#>2Ko1WvsVr~2U)y&5zmDCMEmOaRqm56 z*i|ACIjvzFh4eTzz*u8s&7U*NJ!+Pmf@-^o2`K`2Jx3zE^o*qUd2W=!&sz8` zV};uD3msr!fVpO+IlTE&*WTKe8FB3H0O&!IujcI6gl!Z3+C*xj5%j^Vj8`l(U{<>B z>Nf-1XdA%-)t4f^zDF0)rjN>4O{a&f*wS0+N!jQEKSsqG*JQQmbLqt^Y5dyBp;|Q= zm;bD+jEO!J#Di6Hk{3OW3y@j~HJciB!de+jfwxNUAeb0)6@RAOi#$m8#QADJNPD+d zAd|$iHtW4hwRh7>WD3|Nb}!4;Y6@)|PZqDgthRVYL-J<;msfYZWSI0&EDlMs?b8%2 z!8i%F--~d{hPC0|;=ZQE!|2HsHARm3Boc+RJ^BU?xIOw3&aI8HW9j9C6U-5Wwl+R` zWE$fgBwZUpCbLY~#^t+Wse>H=qPz|5M^t$B-B~GE2l{i|lOpzD&I|Oi}g>{b?iu&O9muT+^$G<#*i2)jj$wGnK z6S%4Po))pqcIme#1{lKK0g7h5R@FWXTvAFMho4$<{|U814^V)|EMu)dYNlp)Ah`}r zrw@b0Kkh+FL<1E$V+SO1;2FP5@}c?ej6TA$R4n5$5_7+8@{WL!@G076pHuPcA0V~@ zV*!rJ%useQ^{wrW(UNV;07SU!BKwp*l;zsyGx&%>^;2SUKw_(N@yBhkx= zR(RxGayWj;M78fsf!B8+<9B15iqvFhWwbF#2WYk<-5xI0j_>e#POp$c+9XjG{Qd2C zK0ri|Z$vxZ_OQe2X3CJWp_ZqBIAt4%v=fE3wdc^?>G0;2(JFzmTWwV`#yUSa;uh<7 zq5O8rf{}8_uwmd1Q^$}y)10s3AP_3cS3UH=$D8y!=Tt_6AFshlWS{=uzF^C}vz@~$ zT)o?eeG6uu6pjj6OyR?CP_d2zN>kDE_}`L-V)OsH%-!~K24b_)TD_*U#Wr(l-X}gI zFIV4m3+EX~?{lC|v1zerwimaF2&FvIsTJJR7jVgc&OluT8PVG62DKRU0R+(CDx+K= zH@byxnaD0S<*cQhhUC|UxrQuO{|~a6cPdnNVB~QXl42qv&67cZ7a$jM_#&WILkX73 z0=5SEnV$BI1!8{@A26ycUGFhM#>OJu#-PUiyQ~?^B}&s^HA=|VndnVXa96&#hC22< zs`@`KKu_RGgsa9^J}cl#6s|nB;)VqTAYsyJ^DA~rva@_%IpM!2Q!6zhTIxYP+Kjs! zrjS+Sg~yQI^P=+K;W!vMTYts7v*KY5RGW@stKyi?Na~5_-Ah546RVgoqZ~oMmM*Gi zl(X3zaOS4PV2#uCP0c@Po!bWB6f%ij1zrsD{|aXOlX!ty(wE;aY`b%gn}qCj(|-DV zA*5w1hV=KjM(BalvZT}f#ckw!>(%u7W9g~(yIi(- z$jsd)2^l}DA`|Kx*o>;&0HOl!?dc5zvZ*WQ zpQ&)3(VoCH*_W;;j>-My_ndkI>-9afsj}Aa*TW)J%R^%XYsXTCt)Xh6Or46eXMdj_ zdl^1lbdWTXr{7UFr+fOwzPHxZ_dPRh?nzH1&WqFiNhjN1Do47EfkR#b=*qKV%QR*%j<)FXD6W=#?r#%dS0S@9MGWAI3xgl+Oy;lws61BX`TnVT&GLT$KG zd%kK+ErBcCPYRWia%eNZ7)5rfCy$k($0s=XbzdfczXtgR+qAPmM*v+C(Qa@5jprvG z$RPwBu?)y+#$amUD#YIHMk*xv6`k~yb7#Nq;IM34{-vj(PX&9-!&ReUn-#jX^mJ`6 z)X1@{)5Fd#7U)Z`VH5w?P1yk&J&m?1we3erPobICxjR~&fJL;fNxYiJPc`D?LQQ>= zDy8HNQp>M7R7VNNAtqOY^xdeQm`n|9#&n-TY|P!LVOfQ&AjqUDv!_STq^E$F?8Vl- zACh~kci6xzLB}%9je$T&h{u~tnodM>m6V;V*uWfWgcUpbTfhp;ddGR^>VL3$gr z^hX|f(A}5*gH8Hw-%j`+nq`felT^>Io<-^MOU}u=`@Vcz|5##Gc^ifD4L=x=SK{U* zO5(X$I_T6X-kA0_sxQ!Dtgla3T{W6UGONJPop9LCr3S%<v6z3?m<$=D6K9H*yxsW9TNpwrJBJ6$?68f@#6oN_L2aZ$p|Qz+?%K1V*hWSOg>4 zVFR6U&6osPGd07hwwqH5M?&b)_H~DTs263&?Jj$e(==sb@>G6l^f4PX7-oWgt7I8+ zwwpyUy$M_lDlP>6}0Yn)Vg}0UpeRQODP}U5Zp@t)rd}xFL|0E)v0nCCS7t zQZ&HfwG0>g#zgo}byF{GBilz8AEI(HrCi-Mq{FVLWLb#uG;zxA#s;@A6*?`Ebs0IDW}r^su>0!cLy>j8Va#JtXDBD@l(^dId!wavdRpglGW}>!ki)X)6NGi z$mQ_+xJihfbVC}!Kmpu?XWQ4scBX4l?IHEDV>f9;DXCtv3a_gM=qqRIyN@(Eg zDQ5x|!mioHp(0_{q35Y$TJ#(@L?=;SH}&?Vzw+vh&{GNoY|w`eqyjJyq!-4?BFFrY zxckcgdR5ZTPoL->eYXp>ngY@BC23=CKNqWH>vA_2iSz;9v_{bGE1x4E@(+01w|$I~ z3QhfdvyfUOo4L^ZZ+QLcqLwmqi9hAhp(C{NziKpu~8p=kyty!2z4vBh+}^8Yw1{Kjc?N({BsC-sfIUa=6Nw^Krteg57MVlpTgX62ne z69Niqk{Q`F#%8tix(@7FgEa?)w2}NAug!pLy@#!%_CG4A=lRUCNiu$PADAkuJ($uu z&91_l8gc2^a8pu3X6?DdFn-&^Wz;VRc(gDD`#BX24(N`+0`WTw>+OnLZr8v}aiWRj zr=>R)$;vp4Inls}GMkJ@gNHc7hZc;M)|4SmM5b+mD7`=Odl4_U8>|*ztEesl`-q)g zELRu4$X}Y{gROm<3hue#Sjf8=;{V7geUG|0{G%l2BAP*d^V#%xwCkMvn0H+6j0N_O zS`4So482=iO^7OKfKfl4LOlXjQ05 zg~wFI*NXR5kw;KIpNK(HWJHTeKiORaK2bUtYqdN3oBNGeFql!Y*zTI>)~N(9N^}Ow zmv?^>p-n?W!()Bc%KsKj)IEY}IUaV0`f>=O z?ogARcu@D(<7sy(f$C$(qc+S<%AIV2#h6lMeJ=n%=$kb)f z`S0hmyZeB$1d!Fb6Dz_2LYS{=H|>(>?IbwZYF{G;+gUG9lS39Q!~u)+aW4;t3e>kx zJx9_G$z2kRZz6=VYn}1=8JEZNVcL9tb{e0T$B>Pm-;-YT@u8bqC`Qe@~hn z)yI9oR?EiTwSYfJevZVMh63v=5)c6v=;$U0^tq9atLFXW@bd@27s zi?h5zp8}RjO{k3CE>pAWpp6P7?@&?wC0o|Bzx0^`-d$X>qRad<204b6Zdf z7SLKZ=l3mM8P=698-!Mu_uLIiaqP5tH;m4(9gt!$1w*5RnVo z;Vnqwx#56#esIl`u3Iu>WBJxCpqTl2itFIR9r%xD!+muCLr=RSd1e}YTF~OZ$19yc z;ZnGzE1=8L!bM4{X-ZT_Xe)E+_@=Z`rvlG$?@Y=IkO6)9`_)i(P1;NxF%T=zs~NZ= z>71xA-wN8sgz#o=y%9TYXe#>;_ae4d~^X>s_m+$sjnq-DMi}M>B-B1F zpX-Pt6s+x_s)O!6RmOvEmi2Gz4wGasmc#ft$xikJ=;_ioTN#uFe}Z)l+I#Eu7~pH% zFcPY>sl!?wVjIk)-`I!Tt+hcl3WPfNA>4+UyF#EdP5cEj{<^`X%+yvMKZ$pd>1MFfQGs{B3w^cpK=)P9}O zRA0!Q{-N0}r4qNNfd_+vE8`TX+g3{?{dfh%H@CW^_dXtp&v3L+RekoRwnC^n7f?|XmtEb zxUeOi)W7m55$k-F;_p=lAC21#xg6M+z&`=vlB3xdE8v+tp5^KD}f;!b3(FyWOUH z-Kwo91ylP6N_ObG2TI*!9=s!}1*LFyzRs!bb?WMEbQw-%f?U!wY|`+G%}^q$8prS|A9R`&&$}xs>~;g?dcLpFB$@7)8p69Ikhmn?O5Zk&BPda8M@U&x@y3UL^wcUh`3J?q{uFG zS54!Urd|GNPG*pw=f$?)?F~oAzF*ioTa@g5I=h6;-<&ybyEmbKWcY=kF^#j5#E%pRscea(MGKC8nzGlbU+iX5FOL#Hy!=iVO; z5zc%F>D$yOj;PvFg~@iZ%S785=}m(2y6{Oz%KARt!y_V8(@U{om_4n$w3 z5egAIY3z4Hoelnlab&(Y#hb`>*RX;@>L#h*6CMk-DK+0W(5< zN6fEr8H0aEL!_bMjnBgT3u;-hn6+OpYft;}ZqWzRZdvUvX$> zxC*)JrtGdHTzO4XYK14cpp*=M`S3ITYq#@>afL!Qlu~y#T(PdBcxnH-9`{AQC^e4% zqA(F_rOrG--3WRI8m^4vpuAW9M_g9+A_@)1!DwI9#vK;yj6e3{Q+Y*!Ux4z4vwV~I z#X08CKg7w?s4ZW80#MuB?5tSe=h;=)yD;GxL=@!`VP+I#0BiqB^nHNR&Is9(AYN#M zVRXLe8SN`C4hYrVk0GdsV!){4lcNCHDZnoIT`(qlgqe$%_tt40HFD3xye`ryzW}_^ zrK;#S@MKhw;yNB-qxePBLG>vV<^=V}isg^n#;DuIkGLK#3V-8BPYJNvG|FHJGX7{KeML$x`ussxp3O@GE-fq-my!P+tM7<6vBI2KgI*ZeJS-5UE1vBb_ zb>Hzw>wZ_6O0KSm>pxT;i=lIQ6-#R5z(Irrsm~K+O|&q46Tg1p>sNN@MALc9#86eP z2(pfCVDA`Wl`Kb$VIy1#?=|*n_89-Hwo^ao&82-MRv1P9lp6KHg^i`UT=xbk76Q5U z@A)1pmh-=->g$fi117)h**R+a&w0PXPuSEb>thdYK6P;sY<#30Meu#$o25KxGU->?))Fr}=pZL*7P%SDHUxdh2h2c#G>w)RuJ6aa*H|QW)=TxLs$!}1P*)H$#Mwo-?L5SxOW&x zLt4D1QJp47VN6(2=__50#GqUfuWY;O?gIlE&R^{fNHU@tE1OYc`iXb$9D zxZM^^qx;n}f_LsdaP2;z@UYel_xiah+m8+mZqg}GK%h#dDFwDj)ueZ_T--GJ=YBzV zI2FtFWbChYE|qIu8DZjcHE5znQ;0@j)Azyt8RM-rQw(KRgQ+{T^VZN+>O4e^%Q@SJ zIY?qQmZP45Gt06zHYy<4ln^^6ONYt{4A!`aP@~!A%}}t+v?0+CloDr3s+@K2k#FQeqFu^f5zn71l`{`Bs=GYUb?>;aDER zXNdSE>g@_6C9p!>>zx9;k=oO)f~4%$9P@beW#kPg^-uQ+1$%wMrNOGs{r&!w9tq(v zK;3zbfo@dM^^)Zh`X?DWH452n9s=}EJKc7B#F$>Ad*8Q4Ar36VZlklnbg!h4Ja`yf z`qD=Qse!Yykpl6V9K1D8enVaT>UWr{12*8H;t4$9-Gw5{LVW}U zd-92-i{O~B#w70_+Z$$ZMA*UizTjcA=m}y|_wz^wg+}FS9hBXEQ+K9%Nu>}jJsYv4 z2?Y{yN_`rst=m1WJ3-=asYzn1PpNpK7KvHeS+G-Ld#km2R%)NEo~op)&OOx~?%oGI zUj&b|W#kKXo+-SUI1HCk`^?AMzC!|Ew>?qgPZjl;;ats~)Xag0Z7D7hi z7HTJ3UfEneQGcaG_HE?eFo%x^kuBMW_R`mS3xvRh{ywuEEJY4Mh#uyvLfABijI)Ny z$L(kK{wz)_hsisnK#V^fQ`i+=Jyyg6grnEA>~HV{2W&#CL234;@-+Q_;n+6_AYL_T zN{W8R|GI@rGE7KAw%!WN6zI#h-WDs>GJV>Y@(@;Uomm6bbjsMDU8#AxP>1$C5|1Qu zk-nkb_h*9RYW*axR+#N?Mv*F3(6F-gw8d=Z&pXWc^Mm-2Vk1NKA3DW)2<2p9J6tO% z_ooNT{ei^kZJM z@vqGKty*;zm7S)Vzt3Ow5$~Nl)h&O!@?SL9E;ZMlzGy%L*zF!={M^}LoY@wNo#};j z_26A%;!`#L`UYi+bV{^uCkiQyb(94NkYeLtdHIpxW@7NK;p5|ltm-)=6u8*E%xCXp zMpe>Z8<6&f-hvpts31!sv+ZB{79_n?V2gIBop?6VXf`&3*$*f|so?Xw6ua>#v8JTH z2Xv1t1ZL0u;-?#**+Vm0OkE6SN5oQJ;m_TK^-#~s)7C-l=jJ{6H9?JFBiMmPbUBKS z{ewamQ(|lL*RxfT>@YZP6CjduEc0BZ!IihZD4bPbchuNuq@PAi?ybJ_Dy2<5ef8N0 z9;+6gO`J37nFNlr^o*!YJ$nSM2+q*22<}YjSf9x6`QH!ZNo~}l)?2Yms|l!7^9<2_ zkVdOb$`R?xr@RBcdq9f36O8L`5Q4zi^I**1jQ%SPI1^1WN`eZ2+20mv!=@9yo3 z=uE+{W75EEGdI4SQpsZ-Bi;eli%tnu{I@0ACG>?0vURJUHd+wZtgZQ9SmG4ehY#J& zT~Uwejo6b#Kcj#C4zIYbBe)A_L}kT#(sm^NUXmkG^7DF+AoHY*ElS^?_v{_W3tN^4 z3E}K`(G17HI2d(N!~i!URJ0$Ab}XHe|Nia;U^iHaP7&;#?(fO37u_T?v19KE4QDvS zkRKkQt5Z@zxoTeA5d5X}<;75L=|T4J^XXfHf6f1>;KQdf`?LIB#-eI5`;*d%V{T1i zywMwM1&c)(g6Sp;o!hwrFG#Yp*!%pFk?h-eT;-j#OV?|~UKT@W)lYsXhmRp`^LFm$bl%*Ea4{7|U z7gs40^)B#co4sP4=Ce7J3A?R~+9)K|$ui9Fcu?wHjgM8skNHRFSGw&L3K6&<#-jd> z2bNEo6TI1_bb#Mti+yxMg5?ZAFPz-GZB(PP7YkqY9_{~dkqZ&aZnOnro*hDKVQ@ez zc7l~F{8&MIS#kYSXKg7rimI8Ox zlCzcW2*Yu7cDxlI5v#AitZDwIs}VvxA-yLv-cPYZ}=<$19wsvqfFl0uMG?4>i{hh>mO480h_e z5>hg0E!6dB)#$b8&VRO$ELcYI?M{Pt{iehZDY&56SpWSJxS_2#jKIbS@`~gnIXX)_ zvxFH&N#_q2<>mcA;xwO?z>^4ee<~mX>`h*rJBv z@MR{r!zQd`c1x*wr8ZJjYmz#wXHx*=WfI_2qbR?d?+{xx4E1od?uzAcF)APenG%YO zkKj2x8}R+IIm8_wLI065TsW4Uv_)#ZuROxU9#=Ik4nwWWmUX6&=y{qyWYPJ@tEw`2VnI7%jg*o=^@MowcvFV}_jnU)Tr)cw1b&_5pY?X1xhwl7&fyZ10UCK!)mL); zb{$8QTgSou#-+^~KuC!# ztD>S1a)KmNnTgb;nO1<7F8Z_E_4tzESI<7nTlQ*Ko3Qh^7V&Ib?UbSTUVJVxa8^nE zdBt_Xfad4Hv3iI&=NTHAM$Ve=j2MScl&2v>_6ZWEV|zw@y*X?k@<93#Z4{CGBS`#6 z{l&AR?yuAmrtANC0rWCf%bB|Q^thQN4{)TNzd}-v=0!24=U{b!gtnZ2+Jbt`Y+&sa zN`lYw(R{6c0H^2HhRAt?XzslN0wm7qoaG(1QVPUky_O0Mn-)WitpTvF=#zt^-+Pei zOix~E><$Mx){~Xc#LFv_7PagN)|1VfjQa6={=l83R$X5VWibyV<}_B?Z)xsegP$0l zEj@HV=GK!o()kG7XJs%Kc2*5INH@i9tCRUFj$4Th{80LGzaQ_JR$=urE(ZD}K`1M9TXWjy1j-5_bu+5!W^BeJF~9k!%3&;L~pSlPRny z*I0n;Bl}4YxnffL#5RjJH$`yf$vB#?zR>&&-;lUl2sEXZ2xgn9a=acHHpvW-5S!@ z0_u-R1UgW#KAPjXSch}V+rr^Xrq7YDL!R*BUI_w+mjjV%_K1mG${^U-rG?UKDOqY5P`I$RToNS;3ohQ8GZ4`Icu zSi%~d*!@|K*xm?of}U)|1mn8D<2*z_x!gukYlsBTZt4`p>$O58S}i8siQ>Y9=4B*Vd*j}tO%2tP zSa@sSRrfF;=~c^O;27H^>-kgqSD#JJyU&(3;_+P2DOt>PRAvMU!dzGR zRY$R3PYu%FEWIzRS(mn}q%oW=^67Txyx02W(hECmFWdKTUKWDzJR4-1BBOL2j-Ool zQx^*iHR7Zeo3-1m#k(x^^$Utx+=*q4@aA&@o-(ZWPqLiL)>Z!`zmWgAc@wI zKR{{83tX2u-Ud~}s*~AEch!uJcj8>8aBd%qB$eL^auziCbKa&@VP$ne3Iu|EJ_zo& zA1D0t-{JI4-=%n(4~^l+u-`w~Pq{-v{j-L!I+$pUICjLmrX<}}0sP*;ojmH`Rk3nh ze{J9PzRlVApNgl`?5GL9GxP3|-($QbdD(XB_Hkv;hJ0b~(`PAyzVl&Cn56>Md<<;_ zgmig<{lV$jo@jdXeEd5Tl!1HDn`(8Xeb2^PSH9gVo%Eg`wo&9J7-zhV&@p=N_W1FU zAH55#KfG-Kdz@Jxd$$ChsAI8zjFIf)ufj7c$ZlRsiatSCdoNn3iyQWPkE#Q^>7{8R z-ovZ)at#jUD;?6jd;4~v)vCb&1MEUp4;?=UA+_7IG`g?s7Dm%^b607A+9XoJ5M+Pi zKm3x)tZsEN#lA+uS_eQttponV#9sL)y!txYiEKfFG$s;w z`x!dXW^ZZOe;AIPYl;b0u-bvNSRZH1-xRa7wEINl^f#U_kgj8?^7yCbrrml+UT5l@ zzj)sAm)XTgcN45#<@zz~g-*ad@;m(Gg2wh2KJpJ- z?fGVCGQwFuJ4_eMcYc%MM@ItHnz%^E-)6gNh$X4tkaYZEK=u;(X1bv-DeFGRUA zqXe%kOQN}w>-yvcgb=Oh*Ump)5f~Orv?qFz6#K>D>jL0t?ypw={&wmL@1y5RtPz(b zlqC~FWqb|nt$A(s3rye2s5Q0%sp~PkwB?+fRie^sYiep<{iyU;(d4bv5Gg3At*Y8T z%rHJ8+}L`Sw*Z=-LF2XrDhma9U5FN)y(2m)$JmdbGbZUsjserPFh zW+-nPg3cfJ;AWM+gf1&ZKPW|?|5=)r(^1o#O&rcZPy;-@?$A3nqHvqj~2N60YjLt(ckQbI^FhT zX%5BOug!H|zoF_M1kk7)H`!y4F5-G9HkQ#BS=|Mkmqlj8pZZu+boTGw7JuUznRK3) z0Gyv0L$9Y^9jfJaM}NRq^V=@~6<=2RpU<>Mw=VVUZT9}~EcfkA(77jfEOYScM#ew4 zk1U5iFe4!&YaQ=z*B20NrRJu+7OB*1zKR;v#wY$Krr~Wps6^u__Ki+wP+5%NMm_yC zxMR*?`l6oR-;k^in~VIvB-ONxDUOUv*QEK08n0UeViY2)P@wI)m)h<~t==qJ+rckp zWY0QEln$sg&I&NQvHX_ADy)kttkqDQtWEGO@1Ld@e)hhOiD2sw+?5aqT2r(zE!1LX zdD!s%?lT}8M)qIKzt`7m6m7*GVuy=sxVd=Sc2HuV()-p)2Ydk;-m&9C?1c z|L4b{Vm}s|2ejRapeu-j0lWAjT9pUF36++=paqUY3Cd8(&LyFKAw49cvzyooTN^ zi;c*dJz2dU_jRtH?~k0o-o!YL+R92#J=4+h$aC&YkUC<#`I9u5;;8)A41T%J(77{O zT|3_KQGz0J0JY?9l{3_tZ5pWmdX8(inE0hD^mbvpd#BjLTE|kP*xW2GMr5yk^u_UV zu$|8{e=joP8PiHRmHjKasR8>Njm-=U=`@;OHR7MVs5;FYs&`=8WQ~g5H;@05OV#f?tovw6+M-OM+$C?XXI>KNy`qaYaq7I6-S3coFS-^1 zcciSJ`-l@OYE=JlKKx8v(_}kmG{a}pL1mDUj~Qqe`vPU(X?bG&SDmCmeR)$+|T$4V?bnq3j3#LNx$ zrh>{`ZaIu&6t(1heTo2wgujQ}=gxMqsp0w{Q)qXDx%QiZw+bo}2Nr4mF~V&O zZIt`ueP5(|Kjf0uEvGR<`tEJ!{ac^o+%4?8*C_OfM~}*d1-h{D*{C478)5gi#9ozA zb6?uMR%iJ((a}GzEm%z#{}JFn;z>~4bJF#(;%$?AMY|6>YqLh(eVa364gx4u9;{=g zip3i@vH*3@M`_-7u;j?aMi^iLx)cZu7UGlkQ6Ea7TpBqjo7^PhK!u{l*;>7!AN z+?J#w&Ui&x*>*Gfh`lPDbt8PJ7;V$_l&-IP2B6{8HT*GIfQI9GHQe zBZ*6Qn(t++)&p)MS(gakSB?8!XjdpyIG?R^d@AtTC|SmR2vC`*8*S0I_>k4u+xx_l zfNhpIJnhFi=CTI&P@&I`YLE-~A~tbDBIb}zKA1?%vZ3?C{S@_EPl5~C(^4s<61lGI zBYqV3d}Xf?BasOwa0stmK`l}bq7a_q&fHiTLHk=!h>B=9G0qsc^D&;z`wQ$iej;8o)Eu@eI?kX0zwqtH3OL4Y&!Y(GYXqV_L+3>D~sfT+IJtXn-^Pj*c?t^#D)FuPd%!4 z((}3XawZ;KZUuy#F8FGe1&k=X8#W5k79BO6Hses;L(|yNb=M@SKK2N`YTLDN1pzji zH+~ZyENh85aXNu|77M_C6mrC(5xT%_L+dZB=!U)s>R&5tKs28ijmxRaa3PcGgCNkSr$Bs)o!k>j}7Oxr+WLD4L8zR>?T=dDsdazv;{pc zi+=tL1{^_)h&}66S9`vbH*{_E94BDMv@{?U#W!$&^$$eSyq!VRi``Wb=^Sq~R#qn? zu7(V0KwIzFo>C{`ax&lqZ+w`Kyz?iBwID%sGGb3zYXIwDJ)$?_z#uz&TNsKVZuC%) zQqdND?d>6{E8G`+Hw~SFzw3p|3E!lhtr z9~y$zaj&X9{qnN#TmLZNf&$JbNv?D4AqhykU+1wX+{;7#$0pX?t(>S4of9a#{bzrl zO`;L;a)mvCm=vz}KdxIy8yMxV3D7zdtC9>r@S7w?$!m$PBRc0pm$EZ7%hx2T|FiW!ON1^z` ztJbhp;B3DjIpD?opChXC(g{LfU9uaK;9z1p8f*5pC7@BXe(XKmVg2NRBT-Q4-|X)= zvDGPB%OKkq$e%`S(+u7^;Y*x8vjI~$8D{3oM+_>4#2W}A-Y{1 z-+NiXmB3g%#$H-vAS@IH6 zmY;Hh;rMIhR3hYsSJs)!L5fTC*mcI1LSo7l2y$nJSnZGyzTPFa3aD@gE@=z#EZ}-q zen@$&geAOTW15}*rMzL|e5D^_+A?Y}tx(@NeM3vMY5+KQ-Z(B61aiWmRX( z!ykhhPW{E4O5juFsW1)oRaH>yv*--^+awFJ>*TH-gLLL)Ki{!=fE5cJ2Wb0;{(ThE z-u+p%e5X1_0FWhpaDsOrI)+|T&t8zz#blGCXtNMaX|&fFmwra86jz_w?hyBzqU>xc zN{q*sc*>|8VhpHpRsfeJnfs58rRQ0o3OV_Di)(LT$_ED30*>T#K#0$CH53+bAU!Gt zK^?(7TG0u$lD24>k>nr#HJ}_Xcm1(0$Th|s+7uSi1>fdD7Lv8QdxR1@DKc`n*X^+G zqz*f0){{3BmSus$3rK@E?6p|;wn%2fK{4KzIKNQuucn%mq3fADzD*aoZpN=-Ofd)R zmXS9%3$6?Ca&G_nO|w#HJEUiYY7*YSDG1ZB)WNj(Z%Tw`#DB;F*`@|CcmgsVpNiqG zY7dKjaQsgmn)|yo7=e_>k<^4pp(#~Z_RG^5Op>MVJl3Mf$jAoBy-M$C#|=eU&yn<~ z?1!dG8lWyH^J(j2V%MqOtS`82rG(z4h)JuwHvZ^ zc4f){scXQ1&^d!K9`+*da4ssRHwY8`7b(`QsMnc+-fho9*yyG)*w<)^Z&QoTM`Wo$ z%(L8N&k$=RE(xa2R`R?I?zlP%7h&V839nR14cb+*7>njg9QtZXx=|fF zwP>*XM-=EvwKq#&P=K;D<(!qao!F6P&fP;L#Y5jc=ZP}~3UBP#o=$mBmwu5X-%>?> zdY|n_MegqIN8Nv5`%VSce3$Lb)o(;#y+SG|-xWyi(SI5D`$QhFMBVcF(`3os-6U^e z(ty-DjCS)dRum{Vk64F+%-iF$yVD5R?tL>DuY5H4uS%tEh6m@UOdJW&@N&xA<-4^T z)yd|jAok5Nx^S4w2E3)T-}}%B<4@w@3s~*6_r1+Ilov$X*r%|B*_19S2jd@99&vR` zsFdBrCOo=r>|w(AyUWvtxP41s=Rid7!+f-hTe^2Aj36JFg^4;C+`e7vDL1)ftkyhuBi@Sw-?{(C)LVtc*#+CW zIKkZ=f?I yCaBcZbFyxI=JvcZbH^-8I48L$JnaoZbIgd!OgreHZ<-Ty)J*HQqU@ zB2PloO>Moy6>J~+oUB^d34?FtW<<8OAo=i>x>p^48+R}prY%oeiIOz=Z>=lpBQw#3 zXKL0g55Qoco!+z8Rya&F^okBkm4h0O;PHzsm^*pBEvpbX0`gZl8=uKSQ+vKhc#YOS#Hd=Im|UtXma?n-Ase)(bJIP z>^;B~>Mz!y)#t{QPEUV%`a*Zy>&YqL4w&BKr=ZTKs*Fq`Ipk@Chdg?@*w({coO+RGHIGfsSLkOImj zNpCR2^%o7WufwAGgp_=pP)%zbHI~cqyfAKQ%c+sq2=9(##SA}hXiO*3{oHV`^jIU-J8Za=lk=vk_QwZL;5EEN}o1(53-=3vc1_vKvspql(zTH@t#$)Lm46es+%Y z6SMsVu3vROi?x=~3O#I2x&nZ}esA0>yElYBgPcUcRNv>_O?2(UfwoqvfZBh_5I@mx zU2Z?>2oewG2u^-W4E2y(iDT_BgD5kQ5?*~aP0os9ce{wG_x}I{;mutQaFmC{J+a>J z9bvdSb8^O#-c4Z*7u9AAzSG0}WzbRjrT^ZIp^txMwwv|b!gMhX_L(MhFpJeHBSpBe zBX>u`*Z>Ih!NTy6376gWAj*M-J{fg7Qx2u!s0!?5l5C(II1Ofm1J*-ZnUw2l47J-t zd=&XAWf$}eEu!j?6g>d{fZj7Hnw#Hk&j_F7R`?Q zJnQ=v(tam+3H4tqTy+0P>{l;eQOGHJ`17fJ1^6>QO}~r;??-;7B)ktjyh|}c(}@rF zxMC^f(g@VCMsnT`1RiCSy+k@`ryurO`t0YJ5vX6jvKY5Xp)Q~YX>>;(xr18c(>u%{ zBJZHnASEu{c3|~TJ7%D93p?>;Nob8iXZ$|u0S&pXfT{^{I#BRnGoUz^fI8YdcFOC* zR+F&|L&V}3|7d;dMi95;3-feCa8b|*+;B10bJ<8UX6?5ET9l-*6<6N&&T8=&AUMrfofLN<+vx2P6M9%wi8N3kHrYH3Eu(ycfgY|5?l!BDoQ-G zNI3tjh1MP25aQnxCk{q{%e)wv=1aHAX`yAv?hwr2eP4|QTePmoQO94#K6; zeA@(lI%llZ&S|N*zQ6vn1ItJ>A2@ggCoVm-uH@H*ag-7Bgdi_~%YDN#Q#+th@EgbO zgw0r_vV9uUOts-tMQNys&o6;KA_$AXgj0{rw{m+~DQXks1j*0A{jvr((qhefhW#^k z%@R|o%~=0|BVII;@3JsUR4QdXIdJVg4^rMX0^^~o2R1%cBCWa;juKPVn~1#Qcw|>s`TO;r zs_Z|jtJ*ilx*8g+CI5>psE2|Aq*kxL|5^#(LlpCRTXUqnj4g^^JD85-L_o8$lD|lu zxY~^-LN{N`~B(8L0b-C9)lK|6z$$=M%9a4D6fjJ!vE%@ExYYxRpUKGLn$K z<+n0~tgz@%dzdL{9c>ts={XE`m`bb3v0m#J^}Es{(&;8mjNjX|{4SDAlR}1fJ+`;K zI--MMDNm`H(1ImuJBQG0e%`%z4@HV1 z9rt`DtP1FTV3L&hOE1^jX=0d$BmgTaFHBFD5Ry= zFlh8h=nSw#7)_G_rK!8f_oUw31e;nbH(8?qOyM!=-k|3ws>)v?VOojy+Aa5Qn$o39 zz^C5nr4<^G|Ff~nxR`_T&ktWJ=th5iSgu>+Ko8yd|3MINj*VZlu|hVjZgIoWqK2fg zf1f}=AZ}u5^L5x98cXs@-;<-6**{;5`Z8x4?Km zbH@qCVM;DAZJ4^16AVe{oJT4d(Tsd3PKLTZGsF?&%5c|T%b;=A5GNhF|DDKdaAM1N zG~@Vch)*3ls7CE|PXnuj^hf?1R31f@(bZnclf!OL_Dc_>?hCCO4wbt0l!y{iw~b;A zygXmWAq#*ooDF$!5N({5`<_D(;;iWEpek*eZQYP_AhEvUg4I20&cLe#@n_Jg@H+O% zB{H>5xVvkKS#)@e`Rn4(^VMGS-R`R6WWUit3Qh=*islh+YIOj4{WfNYN}`-Nc#goy zkbB}yH*Y^d{Kb3gVGD;ksFe|t^SGHNa?I&v@S+(OY3ANKN!I3KCbXp%d>()I^Nk9Y zJ&xsv;@A&Yz2CQ?{*4Z(Jz5NZNCw-u0b911o@g9Dfm}&o7ll2R_Bk~TOr%Xe49*=CiPkmpImZ>I z7wb~hQqea;Q*6)@W{{7&zdt19$*iMaBfw|QKpW`6knTvbskL7Zk!%M-xOb*de@N6% zLU%ed?mONVJ3sw?=cvW?nDEKFxwfT80a=?x;+RXU9KgZ@a&}g;y^wNx^>X%S%+|d^b6HhRV1SEy?!c1II1cKB#U0uL5)zF z_^1$>C;l0a031$OE7tyH8H-crE8l?2j|n{B+Z`vd@BnrtA5->($JfLpSp8Hg8dZ)X zrKZP;(q>Psid!^%`4J1HFYi5boOo+rrFdAcKZ^Ff3H4*$>)9edKwhcVuOhncqyz6= zj{jcR+|d9Nob-<8)CTmfobdo~rfzy1k8G(z0no#S|8nQ+N;%Pt> zYBW6+H^e1b+19!^o*`HEqA%X5_6Aq{*TlBwS8W3{2JAF6whB3OFDbi4er;%R=zG>p z>jh}G$Rh`=Dw=P6a`cC)dXT#b$dcHi=g4;n#7(p?^PkH+$l{)TiC7U@{+Q^^G$C;4 z=l2@uE4)s&*rZApXnxw6!xC8xdh(_H#q8UVeI-G*>2@UK!{V1*(gwz3TSf|28r}t! z@)7ew+D33w#DT?+MUirtNxBViiWZhx4sh;j@QicEV<2Sxi2p@!2||hiAa|itvO6ly_EDS<65zV?L0fwevZT1isbH5 zs5!xZZ(S_KGcd~rp)cBZY1#A+s+8JmVO#V~$tDa}-p^h-3!Dugz_v=7S&ZjaRo-LVhRA(Wau>~>wpI?ESC0~Cj zp0qC|`Ct|tPrXHQwZgTZ|BbkFKr0adq2o}ZKvoU7G^j5wg0si_&WM`BZE`;83p ztKzr3HVDmf;OI#r#k3Ge2~dAUXk1%i?M88ivs07w&J9B&JCn!>j#T?{T{j#EhV_cl ziang`BW9N{`?W=wxB)R<|4{q8jYU<4a1eT+;kiU&@NI&y#fRyTP^ZlcisdX>@FgIs7C$N>b{`Z{gO~az9}~C1Ww@g6wpt8t0K)8ooaDfXR6m1}X3!U`g5n0m$m4Da&!UaNu*+ z+l{i|?JSzy_owiC=3Y5q9lwO7hI|7P6(ekQp{&NLz}U$? zgbeF2YcXuL&rOmyV;=*1_~fAMkv7Z9EH~SJY#mjjGt}rO;@G)y z?a`~$(sL2ioC~Vz)Y+;fJeW}EPkn=jI_;i3XsYwTU8o$mQe(L|Ic8F0nPf97syIuH zeh8fJm*$B3F+U*+6QzL*tGY$F(!y3WfNKQ ziz>><5@lH7heHM&-7=MLx^-wQ-vzeLgM#AP=%WVIJ>-JpN6Zy^uT|ZMoZnik{*EE@ z^P4*zvidzp6A!52R(-6Z*J@|s=~?ltETe()ztcK&%?U;yg9CiO!JmjGV{_sF?7jP0 zGJ5yPEG2%zpt`fUSy+qY>$x4n_7eB+&mSxZ@o%nsR#$7Np$g}_!iQKQB?dL4Vhw|e zU8b*`U?ZX7n?YMr!L;M)OfK*4d6`3D;H7$SmrMCM8tbJc|FH+;7W8JabPiDeeRqiH zrtevCm@(c-D{HrqZE%b1_2az9CxvvyZ|BKoS^>?{$qIqN7$J1f_zD3U^RsM`>~{$1 zr6ga}Y5zUZg0YcCG=rQz+bsuYWa7Kau5{9jNFzP{_6)gu)^@Djm`~EZGj7^gqTL!b zZM1hi`!yv$WyEMTv^s%dsF(h9@!yt!&8kySCV3#PI5ymi$7~Mhq^h>6w$rVvN)-I^ zraQOdC|}R3SkEi5YEQpB<{Y}kGXRpEAhB2=o|ITaA7rLxx<6CEZDu^}x3lxHBb%aO zvnjAv@Qj#B3L-#f6Q0G2*t&kBKLf@?Pv3&h!W!LPe6cdP>6qb2xU@@Ov8N85N@I18 zjdQ)Cf^hCP=tn<)vzan0nB9LYJIhZX?taHKRi$%s_qeopu+!1Vhwr2g zO{7@84_I!`G(9SaUDik5ngy>l+*V zzK4r#@I6SOsx&1_#D0JWxO)BVO}G`C+dZk)-l|JHKF7z)Z?H_NI= zLxmbK+N^%nZHcadmudL+5cy%ozHJQ`DedOYVlA%;PW7e~ylXK*_qQrQA0KreIq`ux zuf+s&LmZK{H<6GRzfH9=O#+$Lnl+ymK67idia|X&4|e) z|K=5Iv8)$UBCV|TKaVl}hB$QiBO{+=J7vCpnh`A*_c-bd@|l*D)?5|4$}^xor$mu!B2+;q#HHywG2b2NTRJBEi`fat^b~ z+M8tn>d>9zGrTc}@I#w461^zrmnRcpwDbN1Y`f6}H8kjYcDV2`ZfX_HISC2SlV44o zf5JXG+%RZ~S~-_p>h$cm(Tx#sg9P70Gu0qeUj`)15X{d1HL|k~C$(A|rNkF&MUJZZ z-JkeHOnT0hcQO**Ws7G8O0R=@JuO9?*5WhMI_xcS$G3#sTW5S+FN?ij$mKFY&@Kv2 zkH2ZgRdU4*NF!%G<`e>JnxywM6&g2ubGVVc40eIP-+pjlwja}^o^vNwSci*n zzVm55%cQU179UGwn%uCT-O^|-Zl{?67|zo$9obIDtg7Qvb!dW`C9=aOjM}zucpjv0 z06so1tBn@S>^(o5y$XK=^Phdr-PZ`&`Jx`WrLwE%?oWVo!wa;!)b~J@?!c}m_XM7$tJ{nCvxx>5vfgJC=vwKdo1^!}C*{I=4kpd}!N`uq!29CO1k$lSQ> zABPhz672#)`~j_J{7z)V|H+P>(Vu;} z-Ini_(H|s668soalk26%TBK=ctZ@NV_U$``uNcLo>+)0V3m5`Pffib`fd`PahjhA8)};j;0l!SvopB{fj?yF+Zr9DYkE)5zM8%t++rxVn6<3 zRN=6Y7~q$&D~8})Mt+(mnoi^SC4`TeLmB||<_CQKeOgomJPU;%|%cnWH%o?yy_fkgNVi#9)>iS7*ZR$sz-X(XW z*MI?xQSA3RsucLIm_7dh%tvQvi<1lYmyBCl{Ta0^USwiO;WvLtj}*f{b#hf`pifJz z0?ekpA=PuO*G~p!ai0Pv&Q4HazO=ACBdNkYT-6A=<&U_6R+DwIy|!NeB{?u#Q`ewi z)2(9mp?y)K|B`T#5^R8OMY1)_rkOS(x_)wd59+pw4bnxu&vrZ3e1N7HQx$r;Amh~- z!xz!~)0&c4V_`Sc)t-YEH7zWjo7Akr|0Xc!))AGuY}9!<_qZHSZ<6=9oD1B+3Bpnv zYWkGsMYCSDO2W05$4oKsDrilR~at~^IA*FDmlePl9JS_!Wlw@ko z#<71eOA*E`+aAZUf^eYMUUg82pwsU<0|)#mz)_J4H3?=g{P;S5!w@=xI9svy5$IHr zqU5a4_J4%(nk9gcoCNSd6_GiZ-yO_4ndjx!iLTYaKC$QVjux<|pF#*`|)evUcGM;IjiF(RE>}j=8kT7-Bc4MWP5` zV$;z0ZSY|FT{G+(vX$D`iNh_*>TVyWA#d&GE zf%{&GfqIUMlpnCnPdgx_GrKrfrGFRlI|PjOQ{U?78`a$7v&Nf>vLs%rX>WE~7+!TN z1^V}%&jisqBxeOg;%XA|#GXyRlXEAm9`-J!_F_?LNmIJWsn~E|>7pU0%T3&#R~Yfm zx$L@+q+KW|Dc$0HsKPi}bjkizQc`cSYbs8pb*dKkW`V>L@=R2AFcHSFCJ<=Zg`+AH zvZ~npzFN*hOD5eQToph;&crTZwI9(}5B9}8LXAg`G9#XbfFHuz#WG;BXuOu|+h#Ij zkAKj}4R|g!Z_e+(Qc2s^eb*noa-z{bD{Jo5%wGxamos+J9tIXB6jCz#=KSMdlvvl+ zIQz-)$6#P1&DM`gPg~q%^h=(av zW0so?!@M);#+Y%Z+Pq3-pJ_9iqp7=@3M3Pl%)!kO=Ih76aN|5;@HUS!6g*5SZa)PU z9c12TIAAO|5NM%03|`@XdJ}&xem6npJH|!QTGxQDhDR~eGlth5%Nu;^`v{yUDoE)I z=bCjKd_-8@m}?Xf9?oe?Re2HjzRs-JgsnsC53{Yegzj!3?sPB4Yiy8PF6gXXw)P%F zErD?tdQt+d^DOT4owV-6bDx3%mmVYrU~ZF(uBI&GRvpJ)v>JuR+UzBu^b%at3}D$n zSNz!uiBl9MFkvZik|Tk8OVmegN(+M@&DC}Z7X2t7Y3Pc%9_pPP4Ip^f*RJ!|Dr)zD zXn0Br_>nXA{6Wn8CAQiS#=@2vp>bN? z2`|cHK9OWjiknmG>k%m+JcNN&W0?)1X;c>eHX@o&&(WSlk5X@EAzv{keQKRzXA$3P zQ^MXQZTg^(9i(qCk4dLFDF&~uP{xz6pgKv zZAldzPrP4ibmS28Mk(gg#s;2IHN9*EkOAa%KNmX({YH z;AM3Cd)^++aYkFOp+In^-aPTNQrTo1%a4I|I!6SY#%x{9P}A@^C=ixt9~{j9C$X$| zHQ?`bvxVV33;Bb0>L0+4MQv?$HU_V3mAGGjF+hd)`AS-S+WzuW6Oh9Hj}_JeI#=dp zy(ZPABcIg_{A(Pg$b{q+1p2#JiEVg+r38IG}kDvpK8ta%q7BO$Dz$S4O6$E#!2;e7kDdRfi1}WLS zWLo=M-${iBac_A{8-#vCy!||G=Q(MnO*bZ$9O(9AMKmtWFwf+~8EYBsazN9DgiF^{ zdv9cuE|mSV*4WrrgJGYaUrME0i+^0LmZ+iJD%!Jo7!m=gG|eWh3R?mK^_G>JIRVNn(E@x- zb12;$Z{41T2?5)GK8!HOQI>4BGsNFzmTVf(>bof!4CkSi$d={wy7clXI+W6!!xbAZ z!8i$!WIWnU6P$7*m6+X%Exi3$8%Syx;2>vX`VAT+PbU$ewc%ZUx#B(vQb~UG;8uv% z7+i~g;@eQap`TmSHV7CVTdPX2I-Aowk;n_$|lxja1u}=2>9=rWJ zhOiuyn`73-Y~P$b>n}2JHa(0q4g5bg#EU9s9Kh9LVBPx$O_gj>tV(klDf?Gp=dQ_Y zE^N$f7$#SQ?HqAU$29<}SY zfqkDwUftU`Q;>4zvck_E>a)G`t9in(HW(_sdtnRrsMHV|p?<#f8~j4s#zZ2^T-%>M zP1CsWXPnSy7YVhdQO++2fGZ*9JdR8cT$;OroF542wYz(p{AJ7t{@`MTx+a}~Wjgqr zE<`r_T9t;{mH2({MCH{8c_}({gTpXfR174-9jH`9FTOV={#(aRLXsS-BtM0E1jDAn zMriNa{>qDb80}bpJBhktG&D1_7CXem-0QF3-k}!WKn81JKPeX8Tep%&R(xX{J8kRU zvg#kU)D*vL05=v0xHpuW((3-NGQ_@N_(neR^P?N&Hgrp}PB>PY1DoR77ot-6b+*cH z+~lzj4a=7&B*6tK2TdfG?(t{Xd}Bjzq6}%Wc7UgA^#)(v@~b>Jt)mH$uVz)){hXYC za9H=QR@;gq{r;K_IVg+W1ykO?2kkbXF7uwP*z4aid`waey78oSS?elO>D#hHH%TiG z_zpNeJzM73N|BVIZ!peN*B z)xUD`A*`J0?8ubN+Th{wULb{nAGfC*+2l<)~ z8Nh}Fiv~MjgVMA)LdOfCI>)ghgZmrC)SMXt+h|U!5(os^TR1b4#f>{2USU8Jigl~$ zbd1r#Q0w?*&m*oy%t4E_@LZ>onasBADFT^5|4oVJPOMWK%_@w}NX;mG$ve$=C}oOf zH{M~bit=SlFKZWdAY;`;{gM%8+fZtEokRHooj)Mshwkq~3EjAzp*iY(fY1@2UKv9I ziF=_HYrT?Wgl@pIPzG9K0-~7`gdbm_p3JzBSI6Yl9SDinrNww!ncbHeT`x(v?+taDwQ-A`zE zT$X{57$FS~F_QvGi_rqk;=E^@m}Tn%ukYQ&vi5XndNmcdI* zQ-jMILcCp}af;yHlOQH%lIOP%cQ)vTZMTrY9X6E?hlIC`_#V1n@CjD%AS|wiSGRa+ z&DsXq>u!Yd6Cc|YAP4DNQCM*(drCzNNeS4x+SW_O>G6_G+z|J>p8RE8nOE@nkgkr- zi|%ut*wBm@8n2l)Nj|d}j8{;J!3v|D+5Ls1&HY7?e<{_CS7A-$80yVVTT&2eL6boE z`}UWoOC7#!+#7xKP|_pr4cj8%dVr9^yCD7zP#eY~x%YGMe5$AV*41cmZO8Wtw6s^;*{Xk{eQbe1Q`N=23`O*62 zY@X&fj`jC;CnF@V%h!K&jneTZ_I9qM#|z8r6e~=C0}*z2*zxUy9nDXd%}m`-)_s!7 z_+nwyULuRUIj@(5QFoKO<&aIlv+G?R6k4_V-)j#XWDM<_wtYm+`?l@ovo$8UtS9tJ zN{k1%kuWHzXyF-^@O_(br-gSv(EFryF)kbi@^MG_s3#6Q2Xqpv|ocXF=7b&O!U--x9Ll*-lcc; z4TKEz6$*LE9Zi`0P))n}sNk~nh&Qyn-1gJAC+NQ0o8uA|j(yTk=_0N)uW|gF&R_}6 z!rKQo8QjXx6L8Mfz{ykVgT`gO6lY-<-=!Pk%3VL-6%~nC z-?yGR_+2{nKtUpDzuY=oq#x>I(pJM|X4`LvYBqBKQnfW#qGsc16*YvMqti(n^Ute7 z7i_i~c6n|_1Sz3a295V}wd1uuCaeI5iwf&q?L9E5m)+WW&^R71Z zfRj%*Q58+wJzGbsOhLSEbu#@wFSmVg>M68fC%qFBO=VHd3jIjMn+*=~hjEPB28irqgZV`X98ZY#X_OPOW)7~2XJSE8f*XqSH z`vOTqpK)TJF{C`!7faGE-j48$IAB)(ES}cpr%J#HHZ@l}CnVlouc2C#CCjF0z-CtV zk&^AC5ep06Jmm~Q5qVl`6REpC9X@aLigi@iSl;Q2j2CGRzI?s^jvP=fN&98of3VzT zODqo`R|$nFsBqu_26qm*5u&%U@n!?%SR!5X84r5x=;CMTLbq@rQ*tkH^$l&02p|3G zTC*kV92I>cUIs&4;?Afpt*?ZRI4O^(4u|&3G%Bn6xUNjY-(4tr&a-yYIgY0nilhCe zfaqm4_J)0oFl-XDgKI0ViS;7hTC#sI)BpG}MQ*5H&~4$*+Hq450zwjCKh=$c40epE zcEl5&D8Hbk`g?-jh}(%juQf(~1z>bm0-6e=H|pDFl5F!DsDN_n=Yc>KYZ$7jmDUrm|Y53fyc651$%4A?_Ki zRHKy+kEaf!U8Y#+lj&xHlngyk`qnIDBToLzet>)Z?DOi!&$JsY?$7w8Oev^2Uk8SW zV)`X=(jvH$oML0WRuxm4M=Qc1lfU@R2-lI(7qjMIuW5s#47_97zf)*X=OfwLH1X`o zXkEW;_+~sBKh=>pSD~RFVH|%^;t7n!Fu$fC1U88}sK3AIP=Rjls#~IoP#s+@?Aw2{+LEdx^$u+^Ocb@GVwWPy^6^8s zymy|<5-{=@6f?x)vrTRN>|d{7F-ZB5mD(RkI6f)1xP~VvtQ*R6*K2~FM>yY+Ktt?O zvI6K@fi*zx5+3dW>>Eb5>M^*$T5R^0U=x401a1)nuGTAM!EljM&Zy>1)qaO5{W_KP zdJ_5;`&CtLfB_bjN@!wE-1cNT?8J)2?N%N}T&qz62b+M+3XGV5?w3EXAGvbIl=8v* zjA*9OR&XbXFo$bQp40xTV<05x1dE`Tq{x`_sIBz-_ecu0Tip(T2PD@dmP8}sh>s4ZBPWm`ZYvi+6`j^niKZ2V?7JP1Y6~0FonWo6^^O^JXr< zXJ4>|ATnhdZu}in7EJaChS}l|ojb|~dbU>QEyQjKJYj7T?@k7J_V#P`R3NuxxpMJY zrh~XlzFavyqB(VFdsN$=dCInqn5|kwm)EW#8HVrTyF?Sl82n5L#lNjqHAZ{v*n(O{ z7SM&=;D!=92?;#7_Xc*FwaW1+htSh_`{8zKNlYwr(x!)ZQfq6|N(0s0D zD9P?BJGQmota?VTe!>e~iGBzisD5FCpZva8P7yW<&ExTgW&1=`XRi9|0rnYf$A=<9 z<&)3Xdjlv`%p+-*Y9RMY^n!tY|O*eYwfbin7Y~KhrD5`zPg2xsj_C}e0w2T!BWel~eR)*9A+9XceP%5_2 z|6%|FcdQUqx=4p@u@7{G0;1-d(;4hWY$EwsIieH2J%+188l8!X4JArhtk29e=P}o- zX3z&IFmA{~701 zfI@DVk8ehY4T)0k#AdOC47CrN$dLZ_6pW*~RWWDWnw7IKGu;HXygOBHIwvKST(@G&n zB=vB-_xI%XB|RoxZ6P~4jUSr80dSdcy0b1*zQ8WvgKoB*wD4SgXJE~zg8#^z0Z>9mM&|2o9*p!;%V#1VF<9b ztpP1QvKkyg&WVgJ(#m}xiD@A!Agm!3LPu|n>GjKBXqSA5Ad4DG&o zSSMh&!XO<|shgQ!tHa_m0Q&bdyJF0in7*G^@|HB$gw{Eog#i`nNGWv<)9@Q3=h0$3xUfLemxm>n1gyg_TKgw`>>`FvX~|G;>$hgcVZ zaYVbsn(r7K-L@VUf>C6#+ZW*eskQ#G{01c3oprPM=0f}B3u~GG?4SM}VA%hfBZB&q zYms~Kjwb@a(=yPf{lGngZ{ud#PonzG!WaeULV+j#wrfXEYewaFcORj9PlSd?X~sNZ zzIt43Q{C-=p3^5E(wTTyr0u5i|%9hDuZ}`9Z>4-#TeW}1f)1V zQ*ZiDLyRynaAb@UYWQrp+D<#rV+eG9Iu z!GX>vNIQJ$Rv&kab6?X=$HCqnVaq*c^G56oLgeLkzR((NYcVB?cKK$tZ%k#YaN7&*}8#t5ud&ENXOkPZtz3# zL31nR|7VNT+-bh~F|(r_lBiEuUPi0eCpP}%$Vlxi_!oWXW$$lq&!1*Ga(eO8!^8Dd zJ(B&>7i~;azMnOa7w}n`=Ur5Dt_%!s4ni{iQH_SftfOQN59B0#4mB~C+D%h1Z?-?F z3EF<2T5r@g#2%N|c$q1jL#3&cl-p_>dQ-QE8^U^`eiz7F6r=V&lEk$Qk+_b6T7ML+MZV0L90K*#o7y zK6in|G@=6+aq88_VK^j^vqz(^m)!WQg%~Z!$y=yDQ*|6&+(1NtkhQxg#0yQMO?!`XXHm zo9)%&q2=b`v9Ke01&IRFTP{C1!M;_k-_>{_aJA0xnlqM0{^pZ*Q)sLGw4@zpDkHF~ zr-Yc{K!1VwqO-@KV3pEf%Ix>RfTIL5b`%g>r79;4eNqr48$o{-3aMwvP;5~X`3bv` zXYN1aq4RNhtn;>c0Q7otg!%&AefQmOPKKl&9qoG%r2SicsQxKbxp7XrQlg$gBl|`U zMX`}!`3H~T7^<*`xEIVd?*>b!HE;-6^+dv#TFl#?2~Xr0ZlN2CXxcVEl{U{2cV0d8{_B8e4BNg!2Q;PqFYdBEz=ZcM^1f?@ zb<@&@JDUYES`uGt$G4hiI);`D4G4E3hx?0pqkRBhMma7Nbn?y!+n3zMm=Y^by1drJ z%RB_ej;JPg%6R*u<@Gsdf3Z@PEJ5RiY|>~BtF{em3}0t+`*=6N4O7)v_t`zNE z83Ilc5Sq$A?<-)nEQ#kZQqQt&89CF{-0PclSvmhOC3nTLKqHCefZQc86*dy>;{dS+ zHBN}|?eX~f@pA(Ug;0-9es`m7m-F!bGI(fI=Fz##EL|94BRNYg&DXf+7YKNe6aK|b zC;Zy8Cg64fiG$i)y_Z^N6PbfF_4az*T=J_nD{CaMgbR6^YoOUZM>5Hn@$5mJr3>Zl zyyEVAOmU?!r_flA11g7q7o4eGED<#|G#ePj0@S-AwAr}_O3tpGgp1oCiog5f)XwPE zw|^hDbR2QVA+^olH{KZ7!?ZZnz6e!RwE~ULG9o%_x2tUdFB6yldmfc|os`|{k}i~2 zvxQgWPBOE+*NV1&8UnYlgtC4^&S#`z4i4F&s90y-Ii?qLzdm;I#tX$rPtbxxjE42Z z(WT1X!ec}i9D@4~@0%qafy{*tmGs8NK8x{m=`c^afKw*yKJj^)1}fwuP@J?t|7fEQ z`27cYmG8j0Cu}?Pg7zkzW%G>AkkB5iD~#40Ym-B922}TKLXdbH8fO%@ST5kS-JO9n z!*mi8qkyyc^EPgX+IOn24&h zjUt~91-wLPj)@p1LwCs@W%;nE_D6kDF|q=`w3jP{^%kTawk(8+@G87#NbNy}pNXa$ zhIrKMNR8m9?#&JLG4Yw6Wd-kYKRQ+vox}A)z)TG_T4k7*iYQv z{P1-tft$2bnOtH619-3{QVECB$IEH=9impB1DCTou<`tWRUQI(eLg+YD}6mQDqFCT zM-2qTk({DEJpCuCkwrY9c+)8}ex`aY0A=nofGbyplePWnq_|Dzn@(vu6G@tBL*@FL^R|2 zrfBodPEbR(1Ct(Ku6K71Pluw?+^kMsMt6!N_)7vSjeOIRtI3y079wZUV}W5(FMU>H zg)|v))IdT7Zv>N56LqaH{}ξTQYaGF}{Wp8n`~aU1$`Uo2g%eou@$&o5n?60526 z8@DVtD0*K@E*1m!W|6F8A7sw>iXLIU<+a;xU|r=AN%}A|KmIL9<@M;!>WXo3FV6A7x}inAy!mtSz?8UkJ+GKvF7tC8 zqVCY_$D%O&QncRNK9X&HF3pDD=unPl7ahwj4nAB;VBT(}j4v9??R~!q!<=ejpI&dyuJXsReZ}T@uflb&ZF-gK8o6tI zBGlHOwR7T(w@uopQbHN>-T6rlSkd?Oog<}O+DGYD`xf6MO}`5vH)wGaKQ)XW(r6- zoFv1)A{JQ~RyCMxrlYLyJN9zotW1ze&lNPGMF@8elW zV}Xg?Dxl9HVFRf5!AB5J8RsZOuoKgpNa6eZ!b|I}4RJbriW^_PlDaH2+aLH0Jyxo> zwsbTZ34fV7&w6qQM($&tRkLp=>? zHf|4&eSK{V4Qm*Ye|F{TA^v)t!})Zenfr~WYf8p&fxi*LD}%qmb(Eq0FDu(tlxor- zz+(?D5bxZgnW9m4&oikqP{=CK)}Tpc+ZI}~@=t#)hA5%WJh4wbR6JCXmZ`~G#AA9m z`}e7Q7x%CO8vlH4!oqr4J0IQ0eo)sikp?E@r@D&L*xA779y&dGbE7p zXv&@_2y4rqJXs_)3sFYN)im zoHZJ)s;73&$)Z?|mRY)y-QwO>A(3)d4_8s6GR~W4ye3DhiBxKpJa2nQcnkDR558e` zkT3~dW@F3g%DG1V?3NEd865B151_`%D8wao*KD#=yXsW0!(;^5ws|SKWi!_xjKqz; z6)u$3BPF81@Uwo6$X$Ttj9P#xH%P>X=JYnKt_c0KEFHBDkJ$z zl#p9J4p(Q!_P`1^_Uv(vTq(WGTFaH~<%4cY>=vLtrl;gAQl%KP4c4V+{?8`g{kEoyU|MN z+G_d}BUTFTsCg#R$ZTD7>7@lZBvd1$K0Ua4L0Bupb8!%B?@{#0USQ6^;(_8#YuW!z z=_KZPTx<<6MRvNJ8W!*6wNALQdkOP4_ zgxyy!_jTFYTCsrk523st{#F|`OWNuPYQo z@w>*Yx&4Hn`#{O-@C7%vG<_V_sPe+mVuPUa0LHD=Q`wDOewbj1C;#k~bJ7NX`syRO zO(M=(=e7n!2G(8&sr2H*Qfw>v7(d1!4RfO0c}I;m&VKP}h-{oO)`~uY@oaUEOfM-_ z*dD!FhLPKE?jRz;vjwWFItg__DlWE*_bw|cnwWHb~A2Dpr&z!7?{($4tFu&Qktbly=y#J z6RqLEoY0p^YzZm*me$ZHtL32iZ;>DD0_s129pZ&)TVts=@1s}9qG$7X?^;?R86sQc zORKIIgpIc}DhPAoi#geXzLb{L$_qbtf06kUA4XWMe^K@)VSkCBp5(AuZn+A(X`EXC{h!Ba$<}bvfr!uhXvIZ zxvHo*zL@3)RCq}p_2E#K*tl7=?Vgk9GZ;*zH6Pu(E)$ctz>O00LT(lWwBwZa79lx4 zC71rh|IbAC1Op#gqaHG>l(%D(vMbVLWFMp!)3Wq4%-_bd5q2C-0$Q;;qj~9p3rq{; z0s4kz0y43%XzqNwrRgIrOVpg_<2}n3WHuasf$-x0ors z!z1WE{D(sd!U*uS*@@aw?;Go)HtXl!26zd1lH*2nbA}}9X+$Q1H-1tNbUGUwP?2&0iKY=eQF2;=5zDKG2 z5e0{Dam@e;0mu&^a}#49$KeIH_v^9E-mZxUb#rF(Q2@HVqvSw%Z|LyOBc51Rz|s-c+4!wFAoBYS z98Z@9#sK$34T26fp+rZ^qtV>J@qr{;RJ?u~Ve`0)`#26IQnW7`c9TC|gSABX8yr&K zOM>UBXcZ&@6v~@WeJUg!gzVd-I=R7*3iNst=cmAoJWKQoyFMepEPt=)-eIZNTk>E#6ZVKcD=)p&aQ;4 zb_y7lX{k|s<3Vd0evLc|m{AV2P(9;8IktHI;gjl5I+f7?MG#v@8pFDV8^KPx&Bv>G zZKA70I&`%6HdH!FHN@tpcrW%<5L!h_cJJ#V`X8G@?`i5Ve@D8z?-0T%AAIT{3k1Jw zjz5p|&-GI$sE=WPmL5-!%Kc9^`+HNlzNbcEwKRNzL_?frN7jk*J!|2=Gu?aZpf=Iz zB&`T;lmL-Mz4kt}wgUf?B-$oBz~teCC}=`U`9DjE87Cq{zGLw8rTDNq+CU21#uX!? zX;OWT<0Yx#Z)T=iafRd~)oVDvq-nj-*ibfsPiovr)o1iIoKT<|c{uLDS)Hr`5YQ!V zv4WR!y0z!WDR<(xz|FmzDska-?dO2jI3?Q7$j0miABNp0Iev5+kO`i?ZptKxVi>_W z$O=^ZBa-wB&Nw%#%I?Lke2IQ^(#?xfnTgLiw!@R4P3vBnU4-=ABHInI>0N26vGPkSC+2K-yXvIk&IRNC-e?j- zCZDR+Wpi75rjVp*?~g>E#_0yzPQ4@(X+EFu-XU3+Yao}`qKa135uw*|rw>h6=itF| z%Zvn_2BNbu_Ra)-2R~Uoe=hq!@)B;_Z!fhD+2)>d*kJ=_*R~dD4AlsZaHGwpm>#NR z)u#{GoBF+%(_91KDU9WH%yy2xuQveWWe&%7pg$u#_v(X+UIjME@f?fN+Y)zld=6&)I{3)lMc+tRvC#OcvM~bEQAr;F^uiAWb^(gKT1AGI3VRoF}_g zXUwxWz*{Ij7I-XUCp8_Mw6Hd^+azn7Rb)5bNc(}zZ5Io;i9^()vMv@|=dGWtYZm#7 z0Lzu9cC;aC@Ms2}Ub4}Kmn0xjLqTv^Nm}@vwAo+@bZNBT7*~yzi))a1=O$q<<@t6J z6C7cKVIK6a+K<}{xFXQr80Df1FmZ)_zhNkk7uao%YAc>FVHL0FcU>$u5fQif!d(3| zJOxG}r&q9?!|+0t{5G8I=?DH(Md=!#da{k!(FtT)_zZLo!};eU9a)IxSvx!cZW zduZ|G8x4(`Z<_SP*2V6b#tj)E1s`No=;4UW#MC(zZsNM8OcqV}RAh>*?ZQ<4OFDvi zO#h`#(9|6OK=62-v;?aP6oNQp{4kRe4=)q+usI(e89cRhL5R4Ml>8FJHGl$N-Ar|_ z^4rzOev}n!j??ql1VFa8@mOMg;CrU(#-ImOv3#5!{;^Y+Jk?71NOu%(7U#vpNdWPr zY-Iz>eNyr=DGk?2R=7=d48PU?1lc=2{n~3WC}~=NaRs#In7Mt>XY1X+t7Ok|gVnVM zaZ9k4Fj?A!P}EppP&PR0u7^+rC+L~2HHEM(F4+UW1a4!PXm`rud=csd%L)YdEh31x zS+M~$K&O7CbqH^o{YZ`}=IY>b@lXHcdTk3%fz?%(Yf)bb`~2a-&vzb%Bynkr1W0PX z8_mfEz)WrfR4=iUy$2=*tx>j<5~<(-Xq@WNyy};$eBuS#dOjTU6KJN(XqJPPbQO}t zm+0Nsz2@tVRmt+JxJ&LrEtAF9H3FB!3k$L}ga#IWHpHJ$dw83cf56eVz`|v%4v)@G zkgt79Cz`ur-zwN9ym(Ra_~_c&=JlVqM6L{seG3)*1&Q^@eQluV%B|}vgVre{ceyUw z_w$q+xURqx5EaD#onb`$r!eGmYn~F-_{T~U1g_u>yShC|;QB8RY2N(ne^+tSq%9|L zrv0oZ+JWUCsRGk%vY$Ya>r${+7$;}|s|PIB8cX)GAsY>V?^m}3HB!VGLJlwp_e@AR zYlI)WVkL?66P?=D44=0wGR$wRqG0U!B63J1F2Kb#8mRPrja(peSS5bq3gIy*I!doD9H(({fGdH*op5UKZ>y1pWylr0 za)U^wI$n@>fPo_H-Se%z8o-&>Pau>{uN11Q&^cf`dz`7q7JO<${Nxuh-wMbiN!x2d z{gCdb(uDJrBV|Cd8TM<>12_vQQBe* zz2NEzK{5=@qP0}qQ&S)1`X_kXvHct0tdINr(OjW=Oz zO_8tk*CiwarxLq-`R`O#UK^)P{pUF_cD;ywvShdP4Ck^LwoV~bt^2UT(MXk%hO$uG z96P%|<`NmxOEQexoVCFgkC*b)zak4krU_=4S4nkf(PYp}+b0tnftTg`PaW3SJ4k#} z4nA7PLmSFb zPgc@t6xSwbeQ5OeAkrei-g~hT150Mw&a-9AUa{chrbbXPlJED{jEgllN8x@WFX>v-fLYDrhE}iMAFG}M6B*MrI6o%gJS54g!%Wh-(N~D{(ZO~# z7!x3Dv$=doHlD)oW`%-Ic{}*;4Z09d4Qb1SG|40X)h&0|VntVic{_mLx#Zey*>y3AaOqUj*O`R%=fR~^R6x~72WDo4z+||&aJ23hj^S9y z!2s;8H)MsbSDu1y0w070u)iTRAcyErz!4oO!O*o<>S)GKci0`lqpz88hTfP=11VoS zXCoY4dv>0JPD7$-wjD{s%4=$vm4BK~C9Alt4L`NMBR^Jl-K zy18u46KQyPz4l5mLtOzu*Au|P|H0n#hUMF17C7993oi0|dDZ`{b*-4TnRTSa-p3IT zZu=#Ye%B1NM?!zR@xfGEtTg&9ZPD8iw@*&2H0#D^C-mqhI7GbjBdIWR4E+%R-Tlsi z+-8(i@euWnF;L+!B2JW$>Zb(7!NTH~PRg#Pv{LT|XwN?(pssW1te+v3XU5l%h^ z8$BC~^)>zAw`6q=T^UB<91%?jr~UyVhm2p3#1-JT#?$NV`U7ELS23P+&q%wtsAHq8 z3n4lruJ)FL*}U@KwFSI~{5Si>OC*Oe)!<-m!*67C9!zSZRdcM1C#oh-&&@|aA1^yn zj#wIQK8#H__Qu6M$wc%p_emJfE;OLc=d=SQ;dw_>V_ zoNuuHunVsUT#{7lK?lp$$CQ1;){yvL!)J~rY!?jnyVH*au`!!4RuG?P9ow9xDu}SL zDBE^z3jAGK8)j!Z%qa552hKfndLD#c#&D9RyY;GftXmmG6c8NM@WE6YF$ZT&#=`0H zZv^l~lB;#92-eWAWhQd)(t69yc*|YU-}-%nV7q~y9uf929F3R8-hBKU2XMM*q53jY z6NV2F76kz{2(l2mUyb#eHTG+!M{o-Jk13dCL~_T03m8ZCI+evOiC>Z3%I})S)4$&Y z-56-w3Mz#)XIo0RYd50|P4Xl62JCkUN%;p`{&K#rZ^H0Zc&*e=9A+;h*yu0}Z=T%^ z(Wu3FHG^%0+aihjnUFq0iSmwc_YLq*tor2%cW9~&}hm6FSFy2 zrrNyvwVJ_+3&`bKgq8G})8U4iu-ks+Ei9NqfTssbi${xq7l0>1_ATHj$>l~KsP14> z%&)L(Q>U=#N;LIo!<-?QF?M6-gn}Pmzm#ykvXQCFS1Gt@qY#}i;i5|NLcJDmvywbt zC@L2D%>w%SFJ0E3Y)Dt@R<=hmO|7k7tzRSwu>QP034HuibkW_cD)lVhe4T%K18`Qs zn;m5CZhHqnIg@8#jU+?3>5*lq+6e3M*{$P?IwQC6WLnu990MRGe8k zb1XzD>rHvU<}sv}{2C|7?z!+0IwRqHp=C`&xb}a^G@z=P!6pKVQ@?pD4AWuo_QVuP z;d#yXJN-P2|DsZgu2)lR`Fe^~sVLO%Z87)${)V^aENsL$RMjI?nF!Oa%d3z@AYK`# zVUDu%Sw9x*S55Mn<%;%lr;&zj!`N%DkZU6Ydg4d3WdI7w4CU+pkq9Jn;TL#_vj~mq z{@Z47z{==s^>q!lEFT$zq373h9fnpTqH6O<$fAcu8l;#39>ZOf_HE|Ek&(7|+N0Yv z>1MbB6f)~tN#S`00dIYjmd<}aq&AR}{HOJTPMZCS%T`*U_*>w*u4w!>`g zrGNd772&72Qnn3oVdcv|6&QWvx4q)>i$pEKHTSyQd4Ec{_kE#)M*yE=(O zZxfP!Q~x47#zoy*T5-9k5YG{-1^U3}iT_gb&-mfcj&v(<%bvQ}^a{@4JU^_0By@%i zkxi{~ZQ3u;aoNs|I+Qy|8rA;sc^&gPk^z~S*XQ(&y=;DZJvW_oWi{)3wv{ii>%mzd zn*1>M=~aRvW7wu=w*&MIY@{3Sw!BZ_wx3>DY00iPpX!Ht8NhLifXiwc^}oydJs=ab zUZ@43G^#QY^}9r$C0s*StL$Duf2|bU9kW!5C**+%tEjg+`gpMcekp5>&hbW=2nMO! z8g3_v(Rs|l(_RfMT1sLN=Y`xVym^kGV7~}@vqDXsItAt%My%e>kO=U1 zP&vxpjhR$Pug5(-$a`RxhpyRdIeE!%C(C;P}|k5!(^(d1>u*C zSvKOUF0d7DT!~>aJjBuLV)w3;B(ajQjk2G&Y%SY&S=v^eJIjbm@LV6aL@l{~)a32a z790fpf_gXel=*l26hZXSIs2cX#n_Iu2JTW&k8N96@z~$54L|~d=G^brNUsg#QvX)A+ za)W?t-;=iMTh&iIUAFJHdKJYdjWiN?fxHseL+$lT zlotuI6=PrV@;cDxJStk{B~j-bSi8J^ejNC5$?xPy*W6xH3>*u__g0fe_SnF$6W|Jf zbDAB#g}yMsIm{1u@6uminl@DpI9R5)stm3)-nhES1wPS~GsZ43%j_Jz!EYw?dbhSS zHL55-kBjy;y4v^=t>czDRVVla3iXn5IANu@$d@8FIh3@Zo9xRxzvV;fu-qwHm} zJ1C^@|Fd+=nx$X=I-H!VK9bD4aX~2`>@*p<(Cw=I;zqD6TpGF4SXt!lc4)60v*O=mkY-9gXTu`nb9!m)*d!zd1((IlhS7JkHb zIHAR6My955i{|~p}c4jGTD||^EPM2N_u7ob_o9CFI ziXK;-|1OpB$kRziCG<8v?1`Ljg^)bz+s(ZvH*Rrpak(w4X9#+qu6ZMV-`swQ8aOt7 zK*TrfXEAK_N`glw=L|1z)v0YU2DnNZHIrl(0=Q73yrjp{rl!CEm}&oMKqD3o55-~_ zn;k;}nZ_N5h+wW4KXkM+Ov zb-Wcv?A#Zf4C0`AIlru&dDH>bK+Qf5);DiZ(r+vs(e2cqk1v^V;kDv8Ox*&%V#AdT zI*99@3<7o{FX343J@7&qZJl6_^k3n{sM5TS>57EzhP;nYhBQB;{Ny2-jEJGCDqvj* zHL8gzmS5%mU_L=jKlFZyWFV1MFm`A9X|l+6iNEjnyUpdp<}+x#`6AK_HiSF+GoO?p zXodQFER*R70d`lDL>Kp$F|zYI!xe#saY)Rtb<`U6n2lcJHo^qe^^zt1rJ%+n)SC5k zwc-DbRhKyg20*1GRd_RPg0_66D68Kcb?knkdcJuGqx3B)-j8lymYY5?T~btTZTa~4 zmhXrw-H8c2OHUy+_fd?AU+r$*1{OBnfjdUf|5!nqaC7wAs^YN+HG~uU6@Y&%LCKi3k zvS8QrX+ZGVBh;TpwBe^F7_-Va;-`F7ec5$9K*Eo+^_5W8O!jeC1%MehU6t7Q=SdXz^P3s#qK$ z$85vk*Xi+b#kSxBrzXl`o;9&;w@<5lcRepNM%m zoCY}X{q}YxTcE?1yG1T=^QiT#%xw?oTvoRA^tsY``{??jTBhqi&VVyJKW1_@Huv_E zJI!0OW1(Jlrd~FV*Rn@OP|#^s%vECSd}8iRnY)7}smsYT-`AkbL7|9RKZE%5odU7NY>tT6ozn*mjG{R}}Ue!_{7 zX4srD`2cHAxfX#3aa?xbprMocBwoFlvAV`~34-GzeuZXps*a{pG=Vl|p=ic?-p}s) zp^v)0<_aH_l?!U`82P%|<`&1`9WSE(DOxMv^X7<)MDIxEDFF8Nql3LV@&hDF^?BKw-o z)Sl~VBU10q&VkxiX$&pbcTLci2|S5{p^#psH{-jka8Ia8Sju|(_-f6Z)CL_}j=j-> zjf{--hbnbQU11%_yhxUb@G8H2nY3KD&Z>2loX)$I)VM&yIHIDJDmdqa<~u;56A9rX zbPmgxUK!Ad^W_Q<-%Eq~&o(7&NheZ?h2#U~jiS*ucvKBbXC8pzz!yr(Sm!0Q_pkNa z;#}G*!ny?s7}jYO)c~#6~^3C931dRwOX5m35Qo z=f(vT;3^WRNWc$_l9?xvd7DOe^}X358&^T{I|{vSDyl`me`m4;M|Ym-6wS;q8D6Y7 z(EtDdm*`?{;ccDw-`8LyD*ufU6|k`d@R)<041NX1Us9oKza-06seP-2aBDy^t-l(z z?$&G#(`zGMXpJt;_6kVIM{EudsZv`W>n-!(sMf3%Tg+hp;r3EX-&n+?Udx$$hUMy2 z0!X6_uK3ZIxu}8KIVG`gAywSv#CrdtLOv zzLMpUg>3!DBpgT2!k{T+S?Y&kLA;BUeCEupFVVUKo}2QvLilpkvMtKZArgRX{hxkE z--f#r-&?I+a14j(Aic7iRQYbZM-b=$Ty7CN-VjVEij@&-qT=61c5KJ=ODF8s_^79k ztOJd1g|&>`_~HeP#gOa>`$RM6X9SGXc0>9%8mL!lpG+=HFXnztvt3{~mHJrVWHM8! zA%l~d++4c{l$%;VLf}KS532d?g>^vdG73oR!^jepQF_ivKAHP>y~>ua(PllTk)T!! zCv2hGQF+HXby#NLs-cO!`G_PWB%0mch*qt(h~>2w`{t}sl9|p#PF9;Y?>OxjCvScA z5CVQfN8OT@1>qTOwJWP1kJ=JsbLA>C4=?UEm-LZrZ3Oo+Eu zsvP)OE{3SBeBywLzEHFyop-p|XH*Gh zQS%MA^_vEvi~7zf^Z8PcFdrSZEPcpDERI1BTMI3AF)B{#mr3GdBQ6?^AKiKe9p?5` zO&K2iCRJ1BE94PR#gKYHaWj1)g5fIYvjK6m ze?zV;=B(5LA+QR{Y(i-O&n|VdQb3*gCe~q*k2*Yb5 z?mZQLy;%7AgpFh;fqK2JMXOy0b8)`j&BrMtCx-}*=%MxC9`d`xWeq<%(;{VIrn<_T z{yd{?LA4mX4(HUYm#Pgr@#a;VR!er@93Zl14Ud2@jj2dK^ka@%WkC=AxQk)Zo9#F3Q{O7is5jrpK3Keeff) zwKt{&g8>R}+*3sgiCa`06tP#|@GNaqL#NK*sm4I0Zw^d8l()NyE62J_)l=UB2u;46 z1vTAQedSTWyMMxJZ~>?NMA*>JZV08d7gokml4We<6!Vz&1E!*^7)-(OWVVPhm8ip+ zjrJ@N%^N|2p$@7h)_g|0^p(*MW=QeYkjPdn8qIs?@0wM|Tfe$nj0R6N>=wy3b|}}d zOCSArD@3hSy8|M0!Q_+;Vr+<79QF}XyT^xYlcl8g=Pl%9t(Ns z_YcVQKDQY{$5@}~A)4u{U0c*%QL_0W+kPHRc}^%@S|{`jJ-&IDh=h(uTS##Oh`jHydm-;nlV-W^fxZxVTC6qsAgt z2}cr!gM-I1xQ8RPRKc0)#J81SO}Xth9aRrh@{^17-`5To%A(?XLs5GnH7?03biPk6 zQ|$4iWnhnQ4)0k8|BmFN=FoHTv%G)t-b6_ohnKpD{bMW!3G$`y9)mBUNV?Eq-`2=c zY?{Y!yyNZRN%zw`y(n72Zs4Jo#|5a-j=&mdHbm8y#C%Mm+JVCr%8BQNBzX#nzqLBT z{qv$9W6M$nH_1H5`Wo>46doT+%{vC)TS0f737=typeO1|;rDW>0NI&)R)EJx?71G~ zb!^#R2H8kINO}c*$FfzB&sMbS^(+1~K2+hKJw(YV{cnpC$|jp>4zc?Ef9!Y%vg|&> z*CzW34E>+BN7df=ITKMU>$g3)&R}Gt#o)Z(J1Wm`n+NlE9My4oU?OW zo$S1Q-l~5EWVl#`1A_0CKBTc$aeTLm(OX0xz2A$ib1OiT1LgFlUlP657mh%}vMR^I zCD=gp%!$t)$`UtAR&C`4f+N8!{x>m{n?REO^ceos7=D+9#@)hlRObcVIw=`KKcG5> zH|t-XvXm#`w4&=6%7@cm9$7ta@z7Ut=DH84J;^3+i>>=HLwv;Mi zpF=!j^<9Q zm(8~twoPAZqQTFRU`0C!-r%Ps+Pg`}gYbjt>UnHSra{&fYo=eA;FK>B+o2H(e^_lu z)QvLIJU{=E)8lzslfasBtz*UaW*sCeyZPKYrRuJB%b?u`^uAGyu*!7v(QWfK^R&iG zBQOtmHab?oKxTcwKH~DFPP|W}MOHOndiPHNuAcs1b>)#(O2}e^_y#DHOQu-fyrkO6 zmaic;Uys*L_nxT-=z`Wure!t7kA|q1;Fib4G7T}!c_61M$v>K~?IDqkoYW<-V=uPA zrP#*Xky5$Ni(~*RQyp97Uzwa>*MHVbvzR$6*tZ~WZ%}~PM%RxF^YPE0pQ#M1&XwYu zrG5yu6Np3^Y{n<-ZPQJl0k%Mzt$+}aN_g&FD5dvJjrT7 z(CgB~-M#tpvwc=T&zjeKkt4DUNz*O3WHb(3;xL(`t799Sb+enfqBCEG0l}=vv~&@a zf52YO6rb>g{dY3}(u>RFu`_n#v$1>SZ5tE>)0!O+UB3MNM{jjNO<}0K zZR1%%aRL_M~|FIQF!^NnX04pNmu>;1wi2laW8mD&cy zSOlJQOj-kKdc0}f?$^vuKwnI85gdp&U%JFPCv5x zb)0(ItOrqKmqRg@yXo{V;Pt96S~zeH)exCjOvl-B@(|xJ;8BRw@2Sg37Et)+_h=-< zHX2q>P2hJWUis>Ptc7Xu+zP4Th0wcjU|ES>4NWi_?qQJ;eR)7jCbFO1cG*$bWPM^C z0tEADOd3m0L?tN)9au}z{|8ag;7^_VwM1%QVfcSM_$|hzrNreb?xd{kfTCaQ0TaD^f{hXL%_bjmXC^>-1~ zMU9U2uW?=hmz(H|OwYl&&L5cqxXlRaa?6KC$BI9#_u}pjR!|#dWmUsRF<8w#I z9q;jD5On&m&aAZd4HP=7u~nuzUsfp?rm{5L(ordW)rVSe0=nXTJa4JreZ~|27#Ci+ zb9o>`P}fw1tRN+teLGKE<+d%vc)4i3o$gKq7KsS`MX&e6eh^gay0p;A*;oOBroPi!Y zaW!R>HBKf)=>HgnG%FX>kTKwCSId_>-#L(G?6=gyceR{ep7q^*%g|H*lA4?P`1si1 z;X)gqu(iN0onp8{BW|LVZd6jxeBe|=bH%Zbwh^=&gCgBjoa_o&GQ6a>$uHbaT9eSmiifK1j(x#TUsfPcy;I#g`Dvk zNyRoj#j8@={af0Ug~_=ymjrnFI%{p0=zsjWUrdW&#?Qv*&rbz9@;9cXkT^WkvA&Bd zCQ@c(VD3}jKgG$1+gN9BrrCO$w~jD<)$qR$jLAT|XOtKtTh1vN-pGo&wa>u0xC%#) zZj*|Q_+3({vv!X_I>>1w6Z3Xob<&v^s%A#Nx>O&yo^h7kJC*t z?`paNR}1MfBse%ITtpp{a%_b^`lS3bj}TI@14gbWqgYq<_VUzEiYXjB<LT&+)B zb=(V(0<7B1P|j7G>Ore3C54$Q!-Q&AO#)vQ2~YDun{?p#wCK@@S!H` zcbNg_EkiA@winl&sZhtjJzi1k)#Apf;_0=CzK#u@lNldrPyi#K*l@^LtGN|TS4;s? z(eF^keU}_S*G_Z^coFt^VG)i#g?5-Jq`as{vVWU&ddoxBvGV-tulnH^GF)j8$ZO^Z z*;rca4Ok5fse?DTP?`3GXO`T%^%yN%!L|^w9+#{{2%s~#Z&k3dyJFMt`+J=A`(geu zX(@`BnE0k~Zz559t;Fq-ZEZLWFuzci_dm?3yPdl#w7-^ysCxNr9J{Ul#$xO)+Mc|WAFwL3tx`-8acAfNfL ziMU^mpaH*+WKn-!i!^AmNY!m|mFP`44i=+!zyXA)iI5{4=3cnUyrNh{_YPj`6#l+^ z)a`QUSnv4>C?3QOq zJQoxSZNp0>##7lHoWOxYbU=~~NvUqkOMK8n2hwgN;spG7Ub)?v_drkcE_zih`jOQa za~Z(dR!UW^IEpKk5+T(;jn7i2&#Ldia1;Y~!K)tgo-#W^fY408E6S2aj7F({i?S6t zL})fcdO4M1IklH>WjOs~ZT>&~6I{dK{d40SYHXma zcFEXqsid$Pw1$Ay2afgel8hz9ykUEI-mWbx)~#>5yCOSGeC(|T zR?dQ@GPhnmWz)k0P?2^rIUFX__8~fm*e9J_xC;U>mlx&a@+PhO)f)~*>8P$}M=5D10ax@$Aw9IBRpeRO|2`KNTD zt}^_5Re+9iyE}>5Vm2*mGEoL7sOYfSZ95C>O>!Mz&pWoGi%qMy2P<$M0imL<!cv5Dqx$Kbz{XS122Y7?_OMoh_hw>PhvC3c4uyH1D zn+B_Zvy;v9ib>}Yc@^V#he+(|6>i{jWKQkpQIG>2G2ATbOLH;wW7)5+#n5jMZIs_U z-2AnhTMV=d3mpo@8ZFmcA+q`XNU9gecyY*R8vnUoFZ8K~FFrRDsjHqYx2|!NEi@KB zQDIkt-u z*RSnvZ}m*Yi%ED#C&-nG8cg!bc3*wvxy5?MDuE%pq_fglk7ck7V&{EIDx?`wXWjF9 zNq*`1P<{3o!%bO3PdAfXr`xk_sHM~M$JlWI`%eT`J*H(2Whum4tmHO=mhzXig54cy zdA+!B%PE5%j;{d+%527=sTL0xaObgCk1slpNUOR%*2Z13HBbIc*bu z5K>Kjy-Ahn%fRjzH@~2@Y{BkiJ709;USsK;sUHe8MNJv_>f2l8cm5G0TSnHlFmqk@ z{7!Bad*j4!hI^8Dn|f+nTwl~LzwGp_OCkHoEe>8J-kGlX_e1jCxDv&A*^U@j+ZNGB zB@s+lI&3sAyX4Nsncf{%EoEu1{Tk=8I(aLVnzYFuU8rHV1^WgLWzkFrNqVlChZ2(3 zB`n+w+|?nFjf1@~=6JpP(lJ)8^8v(^4NJNEC`fjHMyiGS!n@odcRGJA1+b`zt|-Gl zSs+=AZ5g5>(oCu8vL-QyJ)W;fZGR7QH}W zht(Z{9?XF+Tkc64rHo_IofJLt=K%%(Z248EW=9B0Z@uXJmwb$lK~wi-ST)=9?c9q#?{%;=i#2sC=k~a!>^V-C(6I(1i zxk?_c;XGO)TWwjff^A5Y#n_j1rx(nyxgX|;wJ;7Nu$~sj7T6V096Ai()$Z)}qf0&b3mQ=pVF0@C3Efou`(inYbNSRX%3l(c<9JNivJf;tB_l%xyUoOP zHGZUfRbaSUHVgeOH<0=JTmfcXXqWxwLEYmDlMcgzOq(6q_klcB)~0gQR~{ncvx12K zVI>F#Btk!!?wiDVL$<3E-8R=X2^3Bk*y*ZF5hx7~CqVj`o7Rlqy%ivWSkLahr`MP-9n)f21S zfqR?7Pfn}SvM+Chs+#}j$Lu$CPdO7?@qQfodV%uuC@I`S+Rj4zk5^=+VrT#5fi({( zL%3&HSJ#>N*-7HE(c*2Xt6TjR1?h^y_cZ|v1tiw6nU@|>SYA4CzE_;~`RK-)WjAlR zwSzaR=kxXkHbvoxo*Ji48b=77k>^b0n#4@zRzkGq5u5%2Eg|WC-gc{E19xGXY+)-` zY08tq_4JHAeRSh?zZuvU^kl%7x$r`ny|2ogw5o2S8f@C51xx|zcctuqu&bLj{1Qq7 z>k8Ssu6~QIJTJpn#Rs&3O;0v{6*UjS=|$J|=+omYflFPn1E1hMdEoD@d2rWOOsg(N zI#*HK@tbV|mXHUUOWS^S(U^|=3I1fZp!O4F;kEHc2_W9SQMa%YS$*vp^&t-^TT#po z?N*2uyw2If`0eXsQG@JrVYrLSatTxXW!LEd-re!58gF?Mv}WZI2bfm>66t`NE&_IP zl2of+gfIZcmxwA-*ux^23C%v^>knDxZqAo1CiP8BbEfRi6zy*^yx5|NN;lPuzF~0{ zxw&xGY-LG7+ve{@+6rB4ZK>q9cVfdPM2KF1^*qAdN7y7A^>6By*mT`nYfV8h4Y)7$ zxDTHMEZ^;u!pO~A=fJWs#D_KlPs%vB9C`R4{QOYhvLH;<++nag!@~z{I^+8fy9Wmr z#PB&jajuS$p$>{4uBUMMnT8xd#bhzI8uKuyVCF2+^85R9zzcgMG44L~cUGXb7#ODR z33A4%5Z%hwCwt^W9mMnQu!|)tq8|>U=*i9|zk>6^OyorLGZd{ny7QG>EBI+*;e$g( z{p7xwZ}#h=H6zA#TnENT?0g%?i)@C^!ak!y+Ha=-D_`F;Sc{#g4jRNJ>DSdnt5o|% z)I#V%ysQERs`cxua%=;c1)XmWqwq#;H`{~d z%hj%*<%S&0C6J6w%fk(A95$N|65Y68&DM62uFe9!db9xxoU^%W)vccCxvl)Kh&XSg zkk6yhj)tS)_8k>e!G-W(3p6JIsWdjkJO@&Ei0Ey&+Q4Mj5fl<~M?b3L)HZ@rzLsu9 zVx^A$d*`HMQj*ZsUU<1lztmXLs(PJ<>l)|%McOn3j}Lj^zX;$S^ODu3ys`roBm-*&cl|I3=o(D-s~#}{RJ1Gg>XB{$`V2PtzE;D> zP51M!6;N|&rkod(WTnn8w&{+f@`7Z5j`6xc(r2x7gZPDj7BQVj<|w&B%hEY1n16ax z>s>7rDmpCqH^O1z0#jMld@2CXZxUl}Kf>0spL)(n@ZAFz`1|`2^c=6~zbW%x6khlW z7_<(d1E5s5(~&qq-qjb~nJ1;D}^ax)V2B6;|yr~gVlYV8w{Mx*Nx3%AO~ zbfI6r#`FKtbXHMqwOzEvT}yE-F2#zww79#wySr?=|K-*R$qQjJsYg@zaMCXA_zpJ=uicB0ZCIc?)4yivN>>kNnx)ZHdu_Q=)#F zyG;Q2V^=_=q6$^dn5Lw7}y$k%J3rxwJGjz`G!NBf{}ogG%!i=J2}Sz!N`c=YR*@jidCv&Wxdy5+V3L&F*?y?q-Q=mXuKp8U z{2C}N_IbEa<{>p`=;igvW`$%BVR(S-?S17a-C~59&IsNRz-$ISuI-dn0^)KtO|jqV zb#VKaH<&x9!d!(8Jgm3%KLVC;MwdUoLvQz6yejcgS!5HECp&&&{{ve zWT_NKbLhce|Bbr$1dw}dbQUzY2=KWCj6aWj-u=aGrNRTps-x zOzXmr2eTf0n{L(Ith7(!J~e(P3t>GFQ4#&Ddh0y;;=YRFXHE9u=M;I%)W5Q@Bra9U z5J}tq^g93bpAW`uDAvz^4VC^G$ip;<_A+&c@9!|%A)Vd_=!&P5%gZ#|zn+bL_iwzz zWZpZepm&peY>On*)x13Om2*1$69pr)EydCg4k{WA4^^&2mVrPnjWIO>R}zQ1weGG= zm$c#MObzCt+==}^jmNvuVik+nn7$FcRW4)EhlH(m5tCE^UN;)pwy_(zpAN&qOe$*h zK${e>p7Kos^OcW(gxzV^8K6AAEANH_fACnraR=cKm~>DTZ8B}?E;kQPo2h`XxokRi z_Qr)3dW?5;BflC=K)>+%+NlshYB@}kb*+zNW8c+)cZ%*(#@c%nZ?VQx7Isd*&BI$qFqOk?W5TsY+ux%B3@82Djc5u#YKByw-65!3>=E zd*l&+yLWb*5nm*bSI@QO8027~vUu28SkSSYv8R#eJTwudQl@JZcC`?Lp3aCyRH+_O_Akw^2Y@Gm|{}t2Q=Y{s|P& z`?OjEu{Q@*N*|4##XmOs|FZy&UBfT*OYJET+>m?f2=x{>Un!PstpqZQcCgm?a~Pf` zdohGGsV!T6#=hy|+Qivxy-;{Ov%mKmetg8&srEv#5OhHZzL$PuHvisf9@4ix&>HUV zNFlI2g08395B!omC4by)#_Fh7Rn~+k#r$;rlk%7+_gAnE+Twq88Z1rN7wfr{o*zq< zQWw9-L2JSn#8=|e=v@-j>yv8Dc;zkDFqttH@1My6Y4|nsI9%*fKKFVtrg-{jig(f( z@Wv1YxmX4f!7~b`POK)Zr%26h!7FI4by(*}Z+WV|MKg!T1${-T2z->2nw`xrgsTBf zDKNY$&88;4UP*&GuNahD+k?=$>q}$L;F@-I;V{c{g``tluuHl*yI3`!kN?@$WJw6?J+EHqJr zp5#Qb3|s^ARd!na0*~$awt}xJ;3$jG*B2(m_q$g*BH8>syY%TOj^}7Fd4Q)cY+3V7 zQZR5cO>|7p>EUdNzHtT8(Ch#>3o_frpqp(iea9dhB(NJeAH zttM(REVaaCf+n8hco$jLjxqnT(&<;yLJRDO>EgY_ZSSO3#IxP}=G(^={-z>g;z zGcdYDD36*P1G-Aofi{ydL-8r=FnwzSGSIyx`S;&*?i6d|r3u9sUqzX{?uxdPHt_{} zFl)?^c5;O|%?;qurKYrQdSHy`Rx#TITEUQzUm6RlfZTTzHNczWR9ixSHPN?xxl<5) z#bzQ6fNavMv_4%U9$CsNd(pK^f)S9aa!7-${8aq=W!*j<3|eOd{~js@rX(&s#IQb&QeLoHw198UZNA7;lqN|v0CTmRSAhk4=;!)7zKT!m_h zshVATpP<8crfJl;r1X&P4nOBKmH zEJQ%MT&(y*KLgCMkx-7mfFWVa(kvNAkiPxapdw0uK@GNZx!;g_h%SuB0+?)|Ptv0i zb!JY_nm{}VA}$ZCxpQ|p3;rPKX0ZHZ9jY_xlW6b)kIHHBMTeQ1xJzC@DqfT1v`DQdo~#M@JcwUa zJH0!yB?kl$1O()|mvBJHFqo;e3=rW4o_9*jbXEU-Ou!- z_6>Y*4PJ)UTgRlcVa7of=MNe16VwRwDc*5~aS!k?jKF>IjfGZ$ZzqGK(e2ZeuU$r4 zOG8@q?2fzG450ltjBSXPz2|Ktq}vTY=osr(*&TZ2QuS67&_905qs<>;fRDEm@OqmR z%_%S{dRf!3A0RX`tvAAricrpdz2tCOXC3AKd!DDxa+aVvh&Z6?)+|4Z0VJ)(+CgL~ zBYdlCYQhi4ZbbY-Q8oGKu;#KWZi)lOqrg)!_$1xES65eRq?YBbmThzBP3$Mjcxkqq z-63^#6EVAm|DzYgH;{^pd^ecF8&1s$kA4=ydss{ZcsgUM?ntG2|Y;#FK+lg+1eye zbmU+MT;rA8qRJlHuqJnX_^(UEzZr#AHh9ZCOsXH$C<22kwEvS}0a5HvS_booCBxlYbTX(iQkPPC!G;BjQ`zrSrlC2WGfV|zFHc`Kfe%;~V3U3Hgc)+^*wLp$g*(|-d ztUX}@Udr;#4P&?d_wx?9%sx}3)7n6*ZuHky#C|lwTT6~!j%v?%h|@NdRG;@u5->~^ ze!~*SgJ8g5HRXHXJf(uBzLKSyN*Fhkv_1_f;$yiQPR>R~j4V`#Sar*ILubictGxlv)`C95%cr2ngXEx;(Qo zbG`M?;dycP)ujsDvBe(-PUTN0#t7?sH^u3eIF`a(Bu5-JWr`-AL)z2E+f^Wa@opFf z@0o|F|C!JQ?i?y|IfubDuAO_WJBb|l@(6KuP${qmk5G}FPT>`4*c|=U-`%CflE~1u z;P=bw;%EA^-s#rx8I-gk_{DRm$L zO&V<7#&srO5Q=*y-ID@t2ou_2FS~g1y?0s#JOz1us1TYZ;1iCkz)@$f#*n#OW9W65 z?HYl0@vpu&X~+(N>Bm*uw;w{a_MRPZztNMlj1oxV46VW#J&rY*=`6wJ%30Z>#lK(o zr-TIjZ-wlt%u)v)tO#bD~gS+vQpRmCY~ zaFu|K-~1qpSHq@Xy|nd=P6!^8Ni>1nBv~4HC(W60SWyRXPga>nc#`1 z54jhd3N261NCK{oXBb$TS6~Ctdj2fkspncUeZ&q&Ep@K=Z%m$C$y!Bl)ljHNwN~fu z2X5+_IU!PGW?@C%_g?Qj#Arlxlf?m7Qn4&ug2ODEeXpLiPGE68tG?tb8Fr+N@S5^e zDbxWPPHS@As?BfT5!UAzTartqq=c+3=Q4rj-NdqPWz9!^K&)TTiC**PMm_7 zMr*mUb0_$|1wFl<^oCnk4s1Nvbc1U|!>zyD<%ITR*&GiGG0uYPeD1Jlvu8wF%WX~8 zgViUS#cx|=3k6`lvc!%Oi?z}?tlgT>sjY%1X3BxU)Vby6s)N>wN8yPbe`m0X4_9Tk zsPVve)Q{*nM0u3s<2_BshzY8)R-alGnxZKV8zNA3v5uhIb^~e+URn4F-5cgAuJ5gHNVcbq{@9 z!T;BSWV1nj|I8x0pR4H9-tLax*84TK0sct+AkKKHO6d-R2lo`6qo}fxrFw0-!!!ol z`9sK@?(IONidj5wss36BAX4*u|H3%}aj+}TKlQR8s|VgnIQmzC7jFRDu@0&;^@oiO z+-FJ^rVcJQKy8m@9SeG-t2+n=D zjR^4?jI>Jt=Ukg~MsTZSQ=RtE#BiUIPcO}+tLd0>jH=}{vvzaI2|i1{@mXf>=I0U! z+a<5RntTRpeBQ?0j{g%PuQMTT@w=i`i2DR@`TV8p=;m%`MVOuV247z$k9e!N8W3N* zA+GDXS*Peelf$Gg6MSFWG+=Jfz)2)+DqVDz^>~X+&6PeBTub)%*1*^aId}~G?P({=K2Z6Ru z1@8nyBFE?4nPeKbhz&Z@`>@6>=&O6S+nIH&NUN2jxS8AXUh%XR3!C?gHq*l`qis)S z)OMm|GE8uc_pVy8Z93B;oAK?AH@C4Fk9}=;2P34MKffRzt>rt$MR9GcbTYoIo+Di* z=Jz$)khjp+=Z@Wy_H>7%+wu=Z(J~S@=F)gkUA>Ye(0YDy`(}B z6qCxAWF!{tm(FB#EhU|3|8|C7DBkB8wMY;e&BqPUKOy*e zRl~P7fsCsONEq&;(tJh7@Vp8wuR5^iLC6q(g2=!6S!WFYp|wHjHvT*)YR+(o&5~R< z7ePmADR(!}jcndj-qt2pGR?d(owbu@esa1vyQkmy3Tgi@=Wt26f`G6I<`K$&2lG4w zxt0KR3+4UF@{#m`2|u|@n^8^QPAcrZ+e-);b0}EG zB&u~oF@a{T-Vo2GD0AoF1o6hnekVgS)q05w5Z=J`|J}79#1EyL_V)FmQ|Qbz9GN() z@S{d72&kPW$j@vI_syR`?Aj;DzE`59#Q?m|z0KuN%r8e;?WCy!8TMnhDe2Ietn99D z(_2kP2e+b*!F|}_z9Mi9`~^AHAUXtDR=7#)3&hadAMIVYYPycms}mP2;XHS?D_YEG zp$#-pjk_t02bk$ebL%b!y^@uYx(6~a2PmNpw^=8kxnhvc+&RDuSG4%bs4qCo_T?m? z_$nt;Ypsp1z3c|-vR|Q_Z#{?65*B^KA1`5p-yC1xCb+jstc4U^f8uei zt#ahf^EUCW0#{Rvy=I&55#4#XnegjYm%S$MgTxhch7WI30NQfn3Ck&jy-t zOGvkqX~s(fr_2kQnDsC;JX*Am{_)J3MOeLYO-K%7i}Z4ATZA84z0?{Ryo&4%snyRj zm*J*gsT$gQLhCq?8`t9<0%8|fr`H;xUe(VSMbizVn`^N>;g&eh2`pd_K#<%RsxtrYlCr0w9u9aSel zgyBdT^^y3Fb4JNg>+R-}@$xdIU)~{**z&ZhaAKy&c`Lz_wXwqiOz*`)J zJM?JS6aXZoU;IRwhew^P2;`)Q+bFC=0VP2lCX;cjsXSMULhcoa;(U!iPhT5q-;JRc z;?#9FSB~wE4{i(l7IP+?uE$qpq&9{y3WUywvePVV@OCj($wK}7I}lV)LGr+gSi8&X z{{2l>mV$!?$`sit#+F}KK1F<|F^=bJtvtIp3#Zfk2oj|{K(V(%dtkn(UbFhKmc5w8 zjxU9V=g36kwDEo~pLAKyK02?2ugK`xTH8mH6xu9kWw4!F?J%WWhZ$xZ%2j?XnvG1- zl7fCMT5;q+*ReUBRkyK$q{063j)exk>a|5&*C4y};4W~IbYIc~&$K(e(D4_AQ&L=$ z=FXY-Ed#8|<+bAj0&n+vSc68qcgJrY4n^y26N2d|dX43O#nW?sBjIfx&rBriUrp|d z4$Ch=Ll;;s!(HVM+RZ6LE;R_2--tXh1Y1t;>nF8Z#7*u`%toflEt9PB_1v&Rxxo|Q+pfRe4l~l$MEUIjZ zxF)k=pa+C|sHCJ)gt|W86Gdd4N9TC5Z)TSd%V5>bwu{wCziXwc9T#kqInLE8Rs=9m z*Tr*Z`E6>k;-jh`&$dgVr?$Li|IGBNPN_fdQax!>=1@OrqT^ZVH%L`gv?m|0=2Vr2 zW0URV(`F@+>bW>|%lB$xGoLI1hZ;t&XyPg_rJ8d4`OCwpN#&+jIu>r-1aZgj!&Sz#p`Q>jTB7`g3=19(u6;jo3gzwApvmCAV_(u| zR5^elVks5fL|KYg8&R7+n`CtKP7Q8S+vdTL$i{8jE`*zf`^Je;y-l}e2Gu~i{dIQz z-^2}HywMfG_#WD%oIe`**Z4e;N%AL zkGm%a@}a5&?*wIc*W(8VjA^uA?tJ4&g6`S#ItZbc14X%dm95-8`WtpjE zOb*uzWc-_4%edsG!}WtOoM(kbOj$O}4jE^I%w*L1fb8+n`^+Ru3BAF8b)d5vsjV8s zO;U?rZCMTppN1VL!j}`VN^|30I59n%8YO>X=y8Cg9w{KwsI+XS^Ei%UW7m=lu4l*- zMk!RsjnWU?uG2>+;1c&Wzz?ivG4>arA_mX~OoebggeSeqcCm&BHkoap6 ziHN%5_`LB!g%&ogB}j;~l3nf4NKNKU7+iFs7POZRbH5S%)MBEcc`ov!81Ha!taB$=fkvl*haQ+pmQ z;pVIA6|({sepa=A-t^;63~)01+m5~rrBQKXQ2XPGF5 z_8#h}H${_yyLpp4?`+}EkBmMuueZ~IWQ0I*+?7&<@fo!e97F3q{JyFN4MpyXZIY$Y zH-9u5n$ZIol;9*RN{1^c4?NANpS2$Nfm)SPJ7<{OKCo*7!ND~~9w+HZ(39a1G|aW; z(%*mX5UGN6j^;+Yzt0c18EW30PS|5V+OJ4Z1tb?$@L5?@8Sgy)6ot7A) zC!Us8x_|`U6Qg^nEJUc&zrCPn4G9`Gcw<-kR-847A5Nc;A8}+q@i9lYqJOH_DMJ2k-n9($YcNq~RhAY>G zoLBc_|GN5~r@07~2xe;KWsoRF@1potAd}C7#N}|hQaDzotX*&;KWDMPP#1GFEO6TM z>BEH=y^F-Hx)V4Qm8PhpLnx^4rEfQxsM>M}SsWptvZR>^3{~iPaId7hV+-^&R6>Y>afTLsmpaiN zpjoF^vuLv^)X9yrc4*Bo;_}Ut;cjG;UTrc1(5RL2fA!`MdaEf>7oUVwDW;@f+SL6{ zBf>iO1J(AzGua@`YVIfzL(V*q-eIvjam}AxHgNUii}M8q^ebp1STO(f`MP~3-jdrV zDRfhjU#0zFROH4H#Dlfr4+XK|kFw!!8!c+vxPP619d(U$`HNd;B*TGA|0Ky1kPA^U zOX`cT?J9nG+8mScVUC|1^Y0X|((=xqE6j16Z??_B^y*T!;M3R_wn*13;q^C4pDotA z5n-|H_1W0_`@$&;RXOi&gZz4;I_+HgvL0MAGzvxeMn7gW6pU7YJ_%8bgVmUMr8v59= zE~jS?o--29G!4wwth;4)djKlq+J`8h&KZ$2ms!4%fS$76B`y$NkGzB;C$JQBCYiyf z?NoW+YFQ7#S}-%_h4b+zw4TUcfp5pm0%dVYyJqKEG4G0!}6GiA}I>`C~oI^-4RxxN%}$ z-SAWKXxXuYqe?7s5LIy6KBz$_9yLgE&j0qlOj%KCnvj41{L1T&(5aff zLVDvHV{p9~hq;m-64JCAyKBM)TY;^5plZ`^>@@D5RMsGCDe=AGu;$$qEx@ADgOfnL zraXcW6!?-Fe2wJ^x_s4QF*4-%vTLjCt^ck)cY=da*WE$0X|(d11cL)O(5A-Y;QJ+_ zHuCdPG?qCvu{I6gj1a(8by@^dL@O{h&TacEjJcn1zQjNZu+?tglWS4D zC2c5^#q8BaxZ-VRwxq*Sk0=CF?a3;VC$Ae>-M|urXu3{B%uqALOJ(Jh({DdJ@xua; z^dq>&#PEolepz`|8_6=Nt+qTwKcn4k{kHlSqRwPSledJk4J2=SyCfmSW+6}N-p>po zkX`o3GKaCk@^PDJx#{5>+}RlKveejSz?8{Gl-#5j)Rz$n)wbWnBK&X+NrGyf$XO zVha3%CgG;wdWTT$2T^-r+?i5*HuIZ7thk<+PHhbn7P~C$ai~RVU+QM>I}6y5ZH*N!fwd(@_^emoBbV$lkmNF`f8 zc;529QAw3SF{jTI4Jtj{Z%zc4Qx9yeO1P;{U4~MuE}YbHF|5wc!wA2H$dt`6?vQ@I z_SBDHb{1{?s@~t^U-ir!)|0LA zUo)0)3S4Yc%U838o*v#KrYQ1UmweRYI&|yY&JOpbk=qLJcYXG=AJ+}c7X4puZ``g0 z6Gim_$t}a^BkoW8_2z>Q-;E`3c1s`GJTCaFJW0W$5^Kop_l;!ksWmbSE80v)o_{v9 z{(j`c*7=-q;`hi>xRWMYyvtuq_;DeR zaZIAD7MyCGiTN0Vu-X7W>t@(9MUbjv-W~>_&b;J+sOL5(>3FID(+Yu-gKdYc{a0<7 zCAo(?1qpj)F6Ly-D9U5B(Tgvd$dq7Vwdlj|IY`!Vc(1mY{4ZTCM4O-=vjcVAaX{|w zj)>Xk6X0xb_9|ASE1UbHcISsTbFmi&o+n%D%V(1Jnt7c>n#B#XQ;Xz1 z8z-%KcOSs@llwi`7D1umcJWrVtJF3XouH`1lN}!FG?0?-`>6HF+>hB`>Ig>`d$;ew zsV3H5$4UEJ9De=16)C3BeJA}D8m{)(=TQIxe8$^O;BRXwmnO;$i(kFnZQ905lG^fR z_f70P)$dJe%u-V~qa;|S3fW#6%PACx^0z7Un*?MXKjSwTE%nP{{cg$cSF|au^l8aT zR2zp@Ao0SN`2@7Pmw%lw#ku~5tg9u~p)3@k#w}*FOVmWBl9#79JA=~t*Z>mRuL$9nVp^ORY30?46-s=5n4J=uv0yha>0z1|6)p$;3pPu7#dMZ<^%X&%cFojWRvs%ANx(}F?c!vVrp!Ef!;V+eqH`RkX zg>t{UJo+K4QmywG{itZZ;CeR&$@DLgP29yg|Hk6T6uP(;okT$FpbQ~ONk09)(ozMm zL-XkfzMdoa&_0x4!epNdhOYv)PCd@sFqmrX!RO0-@DhhLsLDv{ww98Zt2TV;M?;~r zc>{tvdgXDZ$rlT5qAgaU<`!01+Xe(Q^AZ0Ch6SIFW&!`IU_J8h-@d^Blt8s1%qdByzJIs)=lg0Bv@<&7efiIxD8cO%eE zO9oN4Rv&U|5rJkF_M49k79Zo-7nym#9+4J`C&%%^2~1ZrSQSCRG!ycPs!bhaS`0#s zH2J|GzK?>K(r`+ieOiTqDpdXkGvdh*no36Ve^BNRKC*R`a#LS=ir;uG782nhp2mMF z6N3uK-48fdKQU(w0^i^l2gUdTJ;z)*wkgn1?tjyaV;~V4e5fgXQ9p48u%RXr;7`tD z2r%2xNVH_6R5a?PwBJ=0{Lca?N|{&>&dvHg>TXihQqb0Ac@fDfy;jil-LVfRPyd9s zbNO`c{Jdt2H!e+q0Z>`6(zUDuIeWe`Z7-oMGuF~nfQ<(2)Vb^fQT90pPN2P;Z872M zUmJg;$r)O|C!a`VBuyeMX@j3Tmq3sW>1Cf?4=H?DC>;ZQ@pf9m4dPa{|G40eCf; z#t*h?L}Pr~-_(ivd{}?rGC#=mhlhtF3${qB6|3temQN&HXmGuqK?*2OLNyNEuKpaq zXkn>RRllfJ&WJ6IAGhS;*tlAYYXQ}4XMJsyzjl0qSyTL`)3`e&J5^U*n&4W4sda_J zCLM+DAvr+V8x70;+i{I#u?~K~1w)EDX8<3kh_&E;>h6$saM2>Wm5dNenvsvzX_uhf zKZVpr_EwaqgV5g;)!t*E@yQmpc1KXuoSry-$FZxB|IbfM9Q?giR zy$P4%2Z}FcDSPk|pD91Is1tYp-AJp`Y-x0c5`kIVOg$z$m2g3fygwNUxm-JVF*nm4 zZ9?!+a;0fN=k$OiE7036t;}69=dVBlmcx5Zf)8xG(@a6{(Xma6#tw^hIAfAZGAQ%J zaBCYU0X~KDBL)l|qYs}|XVfd7PG~mylwO5#JdC~Clp}&T^i-ALm-kJQVVUhF$>a}R zBy~oTx`!%P99bJiuYyI3btrLfO$RcGmA*(49El8mXNPV`BOL3y1Y^{shi0tes5bbC zlN~Naxm=D&J8Dg77WG0ON7xMsDkUyvZdt2evvYDts{HZy$Fxh$T)VaXC}yJ0?JPu^8N<@!Zvm1ChJkFBfvEc}?fSBt9o=Js!o+wXkx8NO_2$+V-EzK}#Jkp$hA_}pXyrCP73WS%!~o@&+751=H2Z_bIC+JlntnG)1oRj3>0n1E_+Kq zB9%X@vD-{$O|jzEs|*cZJ+9SlsS-VxDc-v_w}(GHO01KAD1%)#waOl251c{@zcGgi zu)|j1?$p^H-wAx#aETWXK*^eE@)Id^&@;Ka#F407!nAedh&6@%JrDO-#NR!eGa~bH zrnf8cH=@|E26D};?)w!h%m%(NJTmA2mwsgF)gpCH8ksxUJ;Wsj$ zat=>`&FuNcF4KTb7s(a}bc4x3t~dPiLmUKImfz7sss^fAaZ|c4$PebgHMAkAH!Eo6 z#R$p;PW(jz;Se_Zt|#SE=8KZq)v~We&j-M%4{;y(?}@doV{WW!rBvHDLZ?H}39X;2i)C=LrHh7T`5i*rz`}ZF z@@-^2oy$Z7Mtr7?#4S;ML&beKAK=_TUH97mwu-^&F8?o@4G$_)SS~YyL2`j8Exj)A zt~WxjF06=Rd5D)l&EK}{fF4TA*ihp*VaNh=v>Dc@+P10sdv+!Jmr}nf$Vk0PENDC! zHUxl{0t1W9%Be*o1K7UkiO92c3czkzAf9)$#*S#R7QgY1YHNv15__u>4V#2WXIq zzhF`AJ{1?Rex0-$w{J%9LhcrKL9kTu@J7Pnl0xbR{~TE3q?PA!do6U9QnV@Mw{@q)`v^@E*HXcEo|$VSbaqp6pV18%-^N$uCMH zp<)`huM4M6mF(5od2{aHXIg9sYF{YvnI*jch@6y-ysB4iY5eZcavc@8yhNpSJYBZr z#u7{3(1rm-V)>hfWbvNSIqEPE_o^AnidR)y6M;FzFnItD|!*+|S%oI+2BBtI^M>^gM;ce~WI`o^lZil}&E zpqTnq@msJ!w|B*;1pT_>eHO6x{BI<~jiao22$ql}x@{TVpXYI!IKO)!kJB;NNN}a= zZJ1MdbEcH(Z0d`h z1=t&ZIQ(;3?gW-^dwBF>`tt5OSZ_{b$MtN{<9-Zw><+D9lYFc%zhCW3XaaF z9oHIE@t>`6mD&ROKcFj!L?)Ngb8pi9B;W@&gi6LS_b%!GCSR#KJ<%sWneKGi z3X%cFln$+BsQ|*@3c)Re@$o0_TGEYwu?IQrwml4B$9?x|`zQ91YI)SGdzV+sTrC`I4Zi1QX^Z1yQs`wj)FyTrvi^f2pwmd>u*hc1LAd`LZg zzUflppik{8s^)vfb|tFeQ=pap;U)IA%e*Fdct2gc(}#HknB2?0mWO;LJoI zb?V%FEoo}%t~Rr2Cn{1HzTX6_i?b|zf7QKUX7hY({L*twd=v*dTT9v<4c;HE1pG*^ zbc7tC@6Ng7WQRKG z3%Q1#K3va_P2UI^8+Vz=FCEG36tP1NWMk9Ns*CyDv1kNhJl6kii|Ledg%1@6@ zu*aug+uoyD$vC#c#>2@MJf(FV{!=S(8J$+G{=G=~Z<~Z_iLH{JdT2dF3CY$OW~&58 z6$8};>$%*u5Bm!o@TiZmn0TG50!#DF?kw{A3UlYW5vq^nUY7JW-6#RnBpwnT?|{+6 zR&BIll~kT;*0zajO8=b8MxzHjJ6@=JLfn~O6d8-s?t=EI(c>w1KH$c(*uhA1fMjtZ zbq!}CX*j|e3kzBh5JKXfqTFM?OCF3aMh0@KKrWSzUq+eigJ_X1+||UDkIBPWVNrl< zB)OGTP{*%V^0x(3NS&orkt+U0&crp!Se=q`K-OYp@Kjx+c?rFmqf1QvyW0yaK!P7h zjljJNEh!?oa!!zW>=RZ}ruc_Dd=tVr)GE#WksA$$*$m{Qr|`Nii?M+&qm-q8vRP&s zv6sJ~SKZJ#`!1y2z1Nv=+)a#(0Rt!?iE^4%8=@FI*D^D3mp_#!!1818WE0=Pys=m96md?PrtG%n>~<9}W5H-{)Y0 zyIFz?J+@qpPnw!X*89MI%$P+VfwLHI7_X^vq)BSVd!e7d0+73L=!`cgw2LCl5Q-nN zbw2`}i{m!RliG(=YS1gs8J`Hu{Q|pO&MrkOh6gH?pJ!?~k{MqwhB>mV`@q_5Z4NYY z`{4wB)FMY-;1H=7chzn9U8dx$6%Ct)p<|*TN4fNeCc3(8J@kNRhjlc^nx&M8$Gfr^ zMX_GH{x!qj15~GN>8fJ#zgEh3kvUDqIh*sf*bieOC6=Iha~o$pR1P*j;d(?$etT_J zk4t(y;>SV5v3$~q$zd>TrlK>2WnSe)P7>^~wCXR%J<}|!BRgK;Bjx?@pvdOqO3JY} z%uc2^aWB}aj%6~}PCU-N<+3F3Eh(r zWb1{MWY&$>0d>>GK=LoIzmOcMl%9&E%yzTx^a|gq#T+?-4_{;+H(>h)Hf^J;_lM5{ zn82Q~G^5YAttw^Qn$A-dYeREZ33fF0P#QB7*n85TQ zD&ERJ{Dod>N9<&lC8EJ+qkkSqf#=Mju9NuNHk%Z3K9Q)!EnGL|6?mh>H+PCq0&QS9 zb9+R}%MM4)y45=BYz+Eco~B-udM;r$rLJJpXOIzUy~KR>_lc^)zaynjr$xjk=dF+Z zqk^)X>iPE3UGY9|I;Ymbxz}Lgmg^1mz4Tz=>P|fx)e5dAB`XVqQ*z@{am4o}iL8c# z(+nDAl6i(82SSzz0>Guq7O6b>BFq(Yn$uR*!;Fmc-B%2nkwLB8<&ki6-TKT0)se0r zIPczIT=V)uoGCqRTTE}*ten#RotcEdbDMDG$MfIkEbrDRF!beUI`kEyQIz>Fi0^={ zpDr5NteE4sFQ{V{Nx-Bk!C+#3y%52|V9mzgnd<7~EIQ_HX7;>PI&}eDno<)TWb(1w z=hp3S>~e<`=vgY;_E{`FbK8TM>vb~jO9KX6z3AH`l`4=3|2^)kPP?6`?14VNZu1+! zS#&M>c>*3Go7kJ)VEerwt+XO+akis3+m`ukLwCtI=_E_N>@#AV)*b+L2zNsm%s5> z%8iS>Pw_75H0?bd5X;AV|9LYQ@Av>jj(*|cEs@Z54oFp69_5qHyD^S>vjAQ>$frVX ztdp8u{afK3{#fmx2=n+2RQD)8GJC$h==LxF9(fy>TusfwmHky!R)tc7Ra`VOb@$UMi9IQnqjl15Z!Ke*7@0+MIs zkN!$gW$zW!Yv<$fb}){XD`ZtI<)#9m18p*+XhT8bb&76Lbu%T{88nxe#Xo5EV@n!f zwEX%Hg2VC9gKO88w2rA6N9spFQL@>CxIq1uY?lt*z#nNX#fO57S7+|m!A!X6)a4_k zj-l!EBebp4rDq#UOT)GL{TjTdG&2-gk~(u z1j(4QM1CPXi=t1uT$hY;iNqL~!m?IK-;1GtuKhz}K**@LaSVrzq%Tfxg1;Y?UlUF2 z9T6W9pDIN#U0GtMH`926kc36TGkP6cOwDv&EoO#-30Mu$@I&B2hp^K1j4l}f6bXkuxdWxicJtIq*j5mW&LDW4~I$jVq<2oM1_ z$1EK*=_nWDiDkDb?VKcACTNb@}Nus>~jb9ePA~?`iq)Y_j zJvjDQ&qD3^ZxZwwfVVtz={~Yc%;KHKrHGWvvRgE9gMpT4iM(=muW1~o^mN-1NZN)-eE2-&}k zb0vk|-Id4ZXS$DUkhVoGnOBU0cSz70hM|MfZGFp$X35}KRK#?Qg_5nBR2Fz=8^g7R z@=y?pSxt&2Zd`W|XZwb3vn>yJNmfZmKp+svo0INBB_JRm4a+BDcrP^>q!^`F!o#8 z*nc>O`w=czG!ujgH8l|;2;NZ0yOZ`ABn@bB{Ex0eQpg_6C1Y zDgJ#rBHM{rkq_ef+oItmNwV<+C3y$z#V%zx*&6)0I08V!`xeDFL!Fq7AVz|fuJ|Dov{qvL9z zwHv2#n#OEw+i2XNv2ELS-ei)-w#}K?jn!yk+qS;B_gi<(@64>6ANxG}(avSb$Qwho z(R1&-qaM6q_h924fBvu<^t2@+ zQpS95<{^=Iw=5Jtj`vG)+pe1xv0Wm#PpQi4f$f6YMz~3IK zXg!M`X*$1!&%KG8N^sgfQ^lB@FjjNescJnv-^jnZm&3 zDvf%ir;3+ScjAO&f3iAI|8-_ zQNn4Og7B5Sa{BB}U`VFWf}8Yzf(J81rYf?B0Q}4P+qOM<1K9+BKF}$k8!J|YbT%&% z0@iw$X+|!v(gq#D%RvK!@W2v!$PawZ2aPEJ<_mu$yGsa+sRY@e%Cf`o&8kNrtj@|9i{)HI(GGU+~Op0QT@^gdxp(k3$!ishQ zqjIT(dn9MIjkd)#A#tRQ_t4pr35lJYmsSC`^KX0GAsGHr&x8vuwbZIy3MSNVSZ|1D zIM^L*-%;YSke7t|_GaumQc7HS^_}(Q)!U|epZm6FR{37IIE0}Wt7iYt3qVikS@<^= zp%|UuFX#OA>Ef76#IU}i!KCZEv`h7=)!%HQEs}-$mLsiOswqfI#<@ZA>IunAvi%iC zF)3HFxO;r>Jy&+Na=n{Q`fX)ZwU%q;i->oQ$_}VoS6`Ys3%lOIzl`U`lh@B5&s;1b!{Y*!}6n=xJi+Q>fw9NJf`E{_NB+~OF~q` zaG)7Jtwau8wQ(F{d(O`d?RL@L=lf9<{qQ+}HM%`NTCM-0+LJ#*QI^-{ag zw0&p-kwcDGp8DH*GRsr1xcm(iFHh=7V_6#!%8C~OIOA}9rzK2S5zN*Fg1NwacFUOa z9b?VizX()Z?|me5Y-Rnkft_4A2DZX2CFbAwrR*n`Vdvpqe`T;EJpB10S{&COmc zjTcg3d07mYMJVMR+@|ggGb#9y?>jHfmbf`;$)k+atoQbP-sVLYR8RR1^t5~)Ue>=q zWG(sZA6lpP1YcyvJI~$Y3+F!ZB6Pp8>rfBZQz^5XF(qNE$!6S;w zm0;z-)82L12u~1q%wpO6p>?X24X5^#Q;xdQ&l9Q9gIxE2JWmep55eL2LU4^Wj;Z)8Bg^8B&~_gf<>XSJ&-xUdb(O?}l|BbC$<$zse3Y7Hq34-u zk6&T6{HRHR;BMvje0b(p$E?AIJRx0p!jn`+SQEyLR{ZsVuoqGxUW))pUfu3k2wx*m zn7uMPX8!TD4oH<<3uQe?limd_lJL`Y9q|MQs^$Z^;}=^MWUznArip1I+Q+rTZdN=B zravql-|a>F)LXi~EeD9D<>6;z_sO@mCApDh1*EObfkE zLMB|$534cpGFy`AD*pP?TmMNiiouG#Fsy=VtxdS-TzLZ^hCeYLY3x-bdv{Gbh zVN$HVc7BND>3ZzpOKCjREy)MD6+2X5_1Qw%#N>?B*5VpCAF{z?mcu%kK)cdLeRl%? zDP|ghL_=EH0B#E-3gSGa349p?wZFZiBnf}<)B=7_0DKk0{{xc?GBJ57Q~cg#@ZAqc z@y?0@>`NXLQFrePk5xO)C23aY69+rxUd?^y8pVM56zM6&8)m7SGUHj$7wR1tRx!?XA)+qw1@Z{$BvkQOw5xY zrpdsZ|8EM!UrPZPu#C6n9MQSk=imk}%){PysyX|D=$p85%Nb(@2*z4g&(VXOd!$xl z1vPU13bUC6`Z433byALyU{Go#FX3%w3~v-NAijnLyNCZ>W|66V7`?#yYk~xp+Hwc9 zgXuq}>q9`J3rMBxc>Qa?18bfW-9_xw#-CHfw#%iqqj2bqk%u`;&d%qH1oa@U!!GTb ztaraB&zLwa>Bb9Oz?jQ3T+aO{(SrxEZR+3eV#Uc!mBV6m8E9O1W z9m|F69(VaDmf2!>anxh^cGo~WW2sx&ymgLW4sAO~8*R_BB+-l43td@D%Mc1iI^J~= zdHUL|Is$^=RiuR!xi)*Z(BD_O)2l5jVz`}M_GgsCtEa<2IRHF1 z>Ooowg+PO=Mv8P3`1GEL6?8gLLWCW*lEQ__ptE;)h19>3NR>}zjy!Zd1&3f4zd>cw*(Y54Vbm;MM3Nb z3G8WQk0IG8gd3r9Y|;Mbcn2l1%?Y#+&7rau)h4-QgK2kwzOdc9?GOx5u2N0Ho-al{ z`0^gNRr=ru8&mRn@H%M#*-{`_uD0BqCHSUR{>Pyfy)FnoJu1Y3E0)%L!0z{Xt32!6 zPv$1(R>%7ngF{0-hJRZ`q2!Px0|4LY==z64m%T{Ys~~sh+IT^;SXXwR;rq1zyi#YT ze(IiO6MAF*EdiQ0{JNpO5|O#)T2r8~`yk;lEv+w#mdm2%GTR}wLFz4^5GU!*zuR$= zk1ZkMdELYv<;Wk>7)t9?aald$>L@39Ye>Bn^<7tr(`D0dth#eeK6kxvL%RR;f8b=h(muungvFDQ7_<68#jc2u&hTzSNh=@^4wMw-TgHxZXpk>$l z1$krp3TziiZC$<|`umegXbTAI!sBf1KpI1GbZ{WO`-`7_B3FnHjfmH2BQFii3GGUr z>5Iey%=UY|4^ml7WjXx$q`AJuHJgRGjI25#H{MyUG4c!&fMjGarsSbc-$yK)!L31Q1WAX6@u-frZB(o?bo8$pFeiX zJpT28|J>KDgb^J78<<7_vE{I@#TUqdy~y-S(-+V>@I+*aL`W1hp_TSss_a&pGz2}Q zQtUCO#?0w=L3RQXuX{6jlke6MZ-Lg*XHHj+zy5r>AsTw}jr>o1288uL@tLL(I2;qD zhiW4Y=K3#q0o#b}rbWcAGd#<`SYdFQeeOQJXcm+lB{u~dN&IW27~x%UFD$etVTeA4 zyR3%wH6Hy_lmb33p=iT+2=}mYhE%O%%jT?vm{-2yZu48wAXy3h2-~!lR@RtmLZr@` z@ja}J59bkJ0RgU&&!J#g8c=0IIP$f>JxhA-?@7_I@$My*@9CI*%Pn#M&=sS{i&RxV^Y?jXT@QCNz`M;Dk#c^;_d-z4lqnj*SR8Mu zv1Xd3hJ}yoQl?MM_o2+tVCX`10(F?e41KzW2p>B3R0jo1*XUQ?5AjE`fv1mRbBQyj`gkgln)1MTIfFLm$;@f)3XAeC) zGF?W?{Iw}wzN1|kF`s|5stX;cmgf5dSxrJrWu|_;|9PPtLQc%eC#9=H zMe~!&ClO@>lY2Oot|pKLtZLC*?Ga$@lWx-0gP~X4g&(YiG7&Je@uiKPh>W=5%_Jb| zarLoq5emq{VjtrFxd@8z7cX;?iz#JU7qO&oksipTuWk{Tnm_PD$+l4QE{Q z{LNKP)WyBLwrdjN?|6*V7-bMou}>#nec?u@VX^Arh)=@Ra-|C2%~V+;QGRZIP|SHa z5IjCaUE9D&Mxz_wDco6?q!9WJT6NY=rSPwnLyg4gvpNyL#-)V!pZKvLtOY~CJyelI zq6p|cN&78e1h)^v`QLPoPG1O|!kN&{twcqTNr4=Nu0Wz?m!ng106!B;xJQw&I)IVv;W6Y+gy;G;aEk5y(r>B!w`UPQLTM&ce66inSxwVAxPj)> zrc2JnQDki@uGrIyb0Iv`ExOpOSk;_*|95#ZEJe$EW2W!Pi@ zd)=hI$j4$1+AX}p-}l0DM6p}bd=b+tI&c_GBK?D+mH5>0eeSG3HAEtGi|Cd?!Nz(Xj4F1Q; z_r@m3TKXdmtj5{mxHc_sOVBo<@HFa;cdU#>D^*1A%aeid$%h-N>e!wXPLQ+4Xt{oIyH3=V> z?Ojmo0gQUxKU+L08pGLc*W4XL>GE5^Le}@9_LL=SuXBNqBB#g+)|p3kakm&0zxZSw-sYacOYcyA^FS zWQ=^n@9m(G{J1@zIh@kikXGFj!Bu?i$5-njl}-2zb;_(wJX-^Eo4X2*LGz_Mkf&)` ztuvcMO0Z7;4Ah~s=Gp`#17A3}hbWGl#I?T&RjF0qmf9IjlG+y^l0N*%VvGQ}Lr8WA zg$dgp?MQ{;OT4k!mT{bFX1S7Y$g|vZ<~px0l*2V1IO?Elsk*Yo!$8_=nDf^#_iqOf zJHhi`T;zWnS*m-NcA7{l_WS>qJJ=*Yy3S!y<@9}p?-_Ih^&8DMGp@9aWdqDl&B2Yk z?j9OCi9O?cUK^Niv*6+IM#Jg7LdNCE?UyVIQTAigReo0sxb!9%J*9zcVm(e)2;`@9 zxNd-WY)(yV6DXaF;@@?NEz@Y5n36QyNR?q4_qtxZX&zEIf5 z|9Np*5w}*FE+|{34Ofwq)ur8v{`QS*PmXLk+AoFJ(tmU%mw5C+E43R`oY4I8ew{;n zJ~jr>JEMH{CJ`#i$$)&`FV+k;A725`Nz_oIHt}y^5kdu6477u`F8u@ICc|!LT8J9* z^IeMWe1G8J%z46%z_kl0TrNPVo7hM$`UURzzH{lu=1JSWnwgQv=Z3?=QhKpTRj6os z5$Ju%rA)g!a^B2rOdY&T;pmE`Y4{K^aZHnIe7WZG_pa# z59if{5m0M+6j1tZWNL|IW_o2xW$@fpY`Nkx$HrK%`mI&Uf>&*C3VETwNbc*4ABXC? z80ukpFY$a-%S$>3Of}Uvq(34h+b{HWDQxwg5kU`7C0@W5y3^e^IzSwuODhf6w^Q+` z7aa7%KaIrPmT>6`#?lCebjJFI!D>jfDd#`nyywsfZ1e@hf#(thV-LnKwhezbYE7q5 zoLrz)VOh}}dLowbjPMiRf~1DCT#7qTvxWOgu~aJjXrS9GePopI+%(Kbi!g_W#dpY( z)%m7Bv$fs;P{p?D2aW1~ewP8B%HvfzzN(gyAgsK)rtd<5%VSH^gq^q_E+J2_KEgbM z$?KZu5c~@o?6}C&;AxfKB{A?F?fkG|!$6p=nqN9DbJEZM;nxE`HLjXEW>!(&J?pA9 zhGpN1RY#tfkgZPQvqkTv#~$7nX4$87iy#a5yKek|&S9fys^<^>9MXWQaQROvY2x~` zCW6;ATfszbtrXNLoq%iLAtH)=4N3Ed*4Fz6_}&)rgD`J|r7%J{V$KeRHzX`GT3 z@s6TKEI-KU#jvR-Ykyo*>hUXt;Fs6OW_|6ySS{=DjFi>VrC0NA+les%Og}I{PPA_R z|FEdK*S`Q}NDA@e4&4%gbl@!F1()CkzXaWcyB-BO4%QH1)G3 z&u>|+Dbu&|7u{>8LqO8yPaOtwD~1~NJ$_+=VC@8N_BCk{DYFNuODshtSgR6Xl-{dv zkmS*Wsb!6X4sO!v6Gc9O|0zrPyL#!FNy(D$S^tR+^NTx=t7oOVB9Whu4&m3pG;}~Nc)L$$#m!j~QjJTlMgSIG#NOh5?05b+%SPPR5R~)PR zO>F7f7L3)g;1W;OL`c1`XuH0`_=h{qjS6xbm_E3P?alUElzzq`Y|~6<2gfv`#SbY~ zL!oq9^+}uIn_-WnHcrPibP6d^$C}0w z|7LwU>qmv>wM)gsR~ZCU3(@gv1YWP>!=;wzx`hD50*4Ej^Cu1HhE3zELzrwQSVybr z2G5<)vz#XkgLid1-g|%y)v2QlS(^6I`WSS__lf@o&|IR!d9%fcm^X2pi_KONG=*JH z24v&W%LD@)@=&uq_(O(CwT5o?8OX6skJ;>UsM@$MnkdwU9Xw$LN|zWM>nU5B56Q=O zE}UNMbF^_XpgdRjJz6gwM5e`1vK@lwm<+gq)qE^um?7GaUQhXNVU4UF4`1&CXWF&U z>q#|N(>kSs$q)0%HtV`d?PClp3A=Z$T~7c8*VJ`hSnDf3qcKwq%r%Ajm-BMD4~4NZ zEjkRL^d+odB+8t3?QEUk_53_@!x!;!@zmvN(Bi?!FT|VOF>#>3`2O$;8!-(|fBWy0 zB-_O!B!V<84%~Ci8fRJdE2}EU-%c$$MgFYP-8vNUFQ@!#130E|)?I&V+YZ)R^yQQO zp87*}4KxniWgJJOnh;el-d`4f4~8Wqk6R;zYSSd<>2QW5y-r}EX)rh=l|hJ{|6O_V zBb!!f*r##OQ!~X9cFO3l3VE)&9!%+QB|hNu-M|496R3pjj22{eGUGX@>p4eDGiBxX z3MK2b5oN&MOGW&nKJjW@k;F%C)4xw+Z38kAaldCPINW{z;=k6*PI)|xvV;4Ip=z`F zS0@iLaZf5`ft5ft`jnHolk`I(mA3i^5JoPEO6vIow|?+^=@%0tAZ>4^)~V^`e2V)u z9h_ZGcCXD>4wJ=~y;rVpX-|7f*7Ttux?Z7@1XAU?oFZeKbK`>2MY<(h(tplMw!BzL z^xBr#xWA@!J}n9QmVLDqm+Hw|3Ohmk{YH#EjLlITqnw(!D^USxSckM3 z(1lw`soFr?Lp(6jSa`3G_0~Uk=D+UD4iltmQJhSB$DJLJFLgRL_ihvzyT1wgq_>qJ zJU8`W3I6Mh-Q>WX=`{Nqs=iR|U}aR_?z7?>V;RyI!xWuzr)4CYyHeRCyze};@HCZ* z?YCXZcb9^R8BWYSv2h;n<4SMTOS~_|-^FVY(3`)+9>^n6+pO@E27lv&6na zs+dT4E9?NCrKrrmp7b(rS~+3s!S!ZFblDzUI8;IwT9xauF!vU{GE(&r@s<R`TC=|6wjL9a4Cq&(t!KKVJ44~qQk+O>Tv z{m>~7=AmjIL35BInoxek!j@J|!n9+Dp;jUJbOe7z%P3-;wtzf2a5|L8T4Tr@NO3n% zIGT5h%!71)q9Y(LVcQ&O3|bA_$Ze(=;LgN~1!o3y%I1!keaQX!V{cBBbf^YR>SfFJ zrDbldvp6wczap)M-soX)vm(hrRY^kW3pquX}hhvPuQ=|Cu zCa7~>;2J9prU>!S$jY-bzBgM`$93jBSB6g4W7keUjI@VfTTs?$>aV;%p0zzn@cA`e z-aFoGJFNfdH0!KqHV}0XIYo8Vlim5s`sC!KC$Gf`=b5|e^;mErGxvma4+pBkzc+o>C9N5{8LicR zZ*=LBycj1QK}DLd$<+m6eh7SvI?q6yI1y<{>3`Uy!3OE%#VqaTZ$7RGbplP93oT!~ zV?0J6{+jn-7ur*QvS<&%_@j)l#*Npcy^ngBncd{ctgaHQ%ZTqTCE=YT;)2K7DH4Pe zT-UYe>Vxr$>#2AjDPJS>0ox+JVcUMh!48EY!e70BN#4y#%>lkP_F36Fi;3@>GY05&g}$?m4MV`<@-; z2gsz)i8Csr(6WM`qj$>6N~`yK9%)!4dNkAz*!OQdQ!9n?2@m8P7av)wh{>L>IrF9mFXZWf_^n7e(=}>6dV^vCYjJc)WPZ5WH)V!HJdaD(em7x z*j8_rEm!rqL0t+K(5~b-P=T{2f0kMXz5K9EWbs37r0{#AegJx`#A-Fp{fi9x!!Kgp zqv=cm?^^n?IAZlHP7Zpj%kdeFRcO)vNA&|sAkH$jM0q~(4SBgiSd~SJj=^tZ!WcTE z*XbH8!QU-mJVNitj0$~uQ_I@CwRSO+FF|TOk=nRM@u%ji*xGo*QH;?!Y`~gn4F|CS zw7Zf1R^Hn3e@yxaqIyqz!<^h)aw$TBr3Xy9hv`v_iDjutxW93#%;ktQonC#LAhNHF z!9~JHN?)l(NpZ=SjO_gLTAZ6Q$e+n)4}>VlFE~$SWB-((7H8P`D$_MX@%~5bgkGt_ zadWF;cPEA9f{v>>wOmh&x;GoM((aXui&>8cj%$*SeyLemsxBkwP7&tzR}dGYGg8Qu zR(V{`728)QlLCJ3((2yx^thOZY-JoWgDZ-AdzZC=T5xpyv(|3nQdlFq(jp;cec$uEJ^w=?Z|evlh^ePic~4xksdGzP`Y{L6ybn1P&Y(Yal&brfN)BGb59GlZ(01 z4kSQ8#`23Nh$9vlis)Kh=C36|(dT6UIdBrwW_&@EnVE@5U}=OZi-tp8I+>+!C%dtl zLDivtD64CkRnxSR2x&zjoRYcWIeqhr?|VreE@~k_lxH76DTh`xgMECPC&M*hC_coW z_^h7p5J@q82&84$eejFxCxlLYPl2n_i*wrBGXif7&FE$Cy(7^RT?~3hZsqwawH(3i*+pPE=``vs%6o9M4 z+w`)FvD@oU|C-pFzAHYVt%cpQ3(3(to=ISYY%dpw(pDvY$qR|SFm2K1@wqW0qeYNT=Mf-ZQ@U**Pji01WzS~om@|6}U$QuuWE zK2cHi1t8aD2l4o@*ef8|$_wc6aBB zfYw7hPGCJrwb&ikYbVP4u@{E-6m1?g!4~F{e zLrQkyya@l+0yrOG15B{L1bd5>=lWNk`L{hN?aLfBjm3k^ zgV#KxdE=61)W1N2&bdrf*SkUT!j<^RQGv`uNnC5$MpC=EBz1V@x>IFMxDk7o#`$OoBtA_{304!|Vlogj(b%evABjzzLYe6$t*SC(g@ z^;<`anSVvF9r1H^vJb!jv`Zbh;6bQJ`@m&DXRkPs3pqyCyA{pGfm3c7vCCo$g)ZZs z3bOwpgRS+$cJVMNB=MJ~(Q8Bx(G%YxZ~UW+fE|36>N>zHBPUD%H(=%A)6K$Lv;T0_ zI<#Zp81kYpm$lQSxwP5SH`mVgYKiyPM3h^UT{B=(`NOwrNDwZ6(?xPjioX|c+d9mZ zxag}@Mfp&~e=M*NAk#fSagV07jAJR8OttFniXI!RP5RHGMNQF-MGO@M<=;GKOhN)C ziT7T?Q99oO_wiskcQ(IRcRNvODui6K{WLg=Xl0&S%;Kes zVg8?X(CTPoi4R_0$TH}(Z`m7Bh0QBaK-o!O*#esWi)k6~omfVDDy((y8c zx%My+*CtbG=`V(Ee)87_ezSh1QBprst^O@p{|knKf=aztEj_9 z8pu?>z-Xa<^Hr`8jd>ViwGI_@*U}j@m$IM4rsVN5bAk5FQ#2`2;y3-%zDD6nsrLYj zRLBjdHL22Nz}VnY$E{m3Yw{OI+F@ULk)x(kd-J&&8n?efbT8^v}Z)`56k} z*VCxQ9j>yhqP%L(4bSTx%tz51AUB*z<183lL8oha*xE~g_QOI-WzQ#;P@TNe)*A`yutEFYd}Staxtb6jcgPmG=#2@nh)2*V+zr(3UE#& zP(;!ZtxOkCr>OdFueEVjccr)N3Kuigc2eiLoBpK->>a6G7S*qUtEMir#0_ zh!ccV3WmvoHm9BLpy>ub^G$a$Zaj;YHz&8Rkxr0 z(n?R9nNX(oOpJ0*W2IVLbfOiOH2t5*wDU7ovS{`TeA(Rfm)6nAjkCXTM!8apg<*kp zIN0{Kr&I+#C55R%i@@{v_5~41cRPyxlac=^SD4TUUP=->bshC@fcf z4TKmOZE>#C_-?k}Wt*rn?BVC%e_DRPF6r}6rWQ9)3^#7B;}fUdl1tcI8T+07jQzCv zL}E*(<^nwjaO+>2TR@{fXC;g?f$P?WXN>S)&Pasa-${)EZL=#q_q;E)I2QF)2OG|* zs}%iWOkG`20zKJGy#c9?7YEH%4YP?8MA}2!+vc3L-a)Em5Va3?&z!Xr4d)&8I}SVB z&B5q{GA;5R9;VhB8zTC8W6H1q;$mRA=%2;{4pFK zTQQkBlgI2*tI#z3U#E~ei6-5M7u`8t8Kilida;{dZG|3aUu#NC?plZf>8r($bwls> z{#Z>s_Y(*(;cNFdS~-?;Z~q!qu=;8+<6ph6RJf}2Mg7k0T{2zvm9>36G_4&?TG$P*H6EGoBLx=F__=N>}jy4n++=j>k3@ME8Bsa=PO%v&Y17 zGLrY)rt{fe-|JFl8=Zw>$vu0)m1OHZNBbdnEq2uj`>&`cb=q$v3!tiZ$TIbd2Vu>o z)rZP74 z#nl0$!Yt|XN@mma&m-4b(n(!;vO5~mLAWV12N_s`;N zDYFDsI0RMP#|+wBEx0pz462gz^c94PBT-ifT@xBXR>MRvkO$HLsc5A1u1HwfYS^b? zXcfw(dQTS%5FNOfVIzc@jmL*@{AWV#jT{#lL^_k-4x@T)(3t+yO<`&TYMJ+Ea$wVP zNd^J6Or}s|^uAZx@pwaW0Wyr5bv5BXU=8wSamZ(7?j|(Jg@PJiIxs@!Sb4zF z(T$q`!Z{gD!fC>>RE+Z=X9n@ zVo!BH`MQ{;XFn6;sX_PUwn-Kcw@fu^qA$M=V!v-BMO;4rHU%!i+G;JoRKS%I4(q1? zsp-+jy zI<$NSMYbjb!V>y;SpDvhlM+9#pOuB6cI9b)`2QBu=Ri~cX5K7FlGMFd#`4r}EWfOCB-CfPH#P+)E@E;e>{mC+1;VhxD?T&Z$+EcX1oH`1Mq zoqq3CVGe5{)LzqDm=I8@$MlM_Pqp}`>zxVlkT=uUBGVihS~Y)PNh!;;s_onM9^0%^ z=gzB+>+9DEJ~M$NQLaqiZ`-uG7EFO5si4bLvE|Xn9A4Y(JT3eH9CYiN{&+*U2Ajs5 z7L0UP%nTvCV^YB?8?ek~u*0TiW3EB5`_}>ArWv^C4jVe9^&5N>+-9d|I_;`4| z@*81k?O&~HBw8*dU4@E)KbpBWG#b|gt9;|HA;;+rEdWeJhm8ODpM?V38Oy+{iIj^t z7Nf#!e8P{1=VLpqt9;!QmiUv`;7GQn}Z znJy}DTzKDxr+?h!Vgtn~qLiQ2>{kbnOf@^6A!WDi8CZzvmWZ!${fl`QsVy-yz0m&m z2SV2>b-Ha~j@$J{s@nL|Z(UfMu1Q(Q*S>JSW)t^-A)@ff#LeXoMtl3NbjbT|dbw@y zG)Eg8ZsakXjF8dNT=lEG!(Ir|L(T{&)4|1cHLGz?d=ME;_^1_oF@)Gm{>|RgtU7so zUF+UN< zJ2ZxCX2*ihmM9@e-u(uPz#}IPTZTJalr~=KCM9Qkhj~UlKyFaWocS=2<>HX1<1x|hZUmQe;v~qd2zP&$T8Y63Cr0em2(3k~ zkG~~9A(u6|k$WPMsnRO1P6urB$Bo-^dA6l+qJIfZe2bU5(D{o-4s_Es{tv|3->VHJ zfs$sCME1k2QK`o`oDczEB7JO#i9SNVV%y8c>T)jHa4Tt)!RQpN-1*#b+IUJ0r=Kl< zw}!8zx~qR68~@MB)^=-1T+80~UtDGxTn)Z*syKh)M&wanWplK|{5_|Bmw?^l5ZQBk ztI=f~A*21e0sW|0!^i9<w83t2o=)EiyfGUT-uN zV+#Z`!d4RV9J!H9OZ|6M=zgsob;kMiTZCyn^Y&aC=9;s9 z)e93pv}MQC?y7sLRw6QE2?@z3aHzk|+U=ap${SCvTbW3}N8uhC=1(H$Vxu^JF^U8f)ePO)=2KgsVW8Fi4js>+l zt;q0JOBDdbpW5lOHF7W~emy~qKz+%P-Nr(|IHUdrysve>)Heix9BmsWS!`AhlKy2^ z)CqcZm(N!EI8LU8BLZdaL1YEE4T6m38m5RJkxtxNc9p)#^sL>U9~I`)k#8o8bLmeu zal4=?bLSLC1r*^IXY@@l-(A>?{nUm(Mfj>i^oA!=Ir2hdQIM|{ekj#&*uG)BD>a4J zY({jTHna(3W|uvcQP`glIa4dDkL@z0?#Xd%5oXlg$UAI@)ePXqyBrSq*1y*KFMpQHmzDsaa?#_&tw%L!3iTo8Ff zRmLj)mQz8Som)$lnz~#(EZa*B-AEJV^Wz%WtiAyYZW<$yDL$*XH29b^%@z0oO{Q^d zcEex&zkJSA5kIadNK5k6l*0cAu18bnHUaDh-2}fb>;iV%zAIcsC=G8+I!&8n^u%m? z;8Cg)_m_2y+9gZ?tHkOCMkIV_k8&%ZmvrrQB!K0LsmO3*K>96t|ACsyPV4@FA^I%^ zeFt|_WGd(mVw<_o&>cUxPVAAc-M!roP(xRSKb+b*j_=6}4pz;6E_0N|C4|T;M#AoY z+S`5HUP-9Y4*JjAJ5a`OR+lHRgjWv{ne%S67TN;@UO(GHvH>=$!h6-pE}3Q69; z2E32^uVG1aFikqb@d0UoBWBI@|IX1~gdUOwbXPa*1EI@KXGw*20i(6vIjoR?`4_&N+L1*}xB(Xp%7ylJ!+=j)1 z{RdFfV%Lzkzy*EPE)8*PjrE=3DlGB@;u*BrXDinE&)k%z3&^>X4`~S2QCjBrmj3s- zFH#h6?)TEulSZ@gNc=XAh4+{&Vm10Gx=+Z zC)dv6vlb!cu_Jz~LAePB^p|X6=+keqZv>>4nuzQdujlL*HC%}k2EmY-{x#U{RoeA; zYPGL;Om)oag;igGpqiLI*>QUt0z}dE&kJ7u{_nYf(O#bkLhpae=Fx><`M%n3gIVnr zJZ`FD=g4gdzT8_nl}5gN^n54A*p!Ou=}FqE(4^AewHQMR-@?Y??MX+B;}G^{>Mf5b zm3-1oq3n?jv%o73zz9B;W-2tw^IMnJA_8#l-hHGsy?~L?Y=5i9tWY2^WNmq~cr;)y zg7*CxpKk$cF0E!!u3uKVU&VPwpVL`du{LY{n|>%gSnjb_s9s zO{U^BmUe`IL6jOpj*Guo`nfG%4S3OtgDP*I8Y6Lt-{@EqKF02)il~`mV9uadYzd9;Z~o?4DapyWf>(AbzTjTtqiYsZpgPeW` zyqvF~R!%MheB9RPDvfu`Qu?{!-H6YB2(9uWgHxHBG=kUfh=5&e$z$M}g(!4-F8dp^ zr)68NkDYO$RxW}_V)H;huS-_-9o}cv$kwBmVZPgW6CIJ$+wtABMz1~_?!aRdSdLb| zQ^vSY3p`gw+R(0c{C_60-M;z^Qy#=+zt6`fMaFOT*u>@nt@Hv6druyp?pk_Zk|E)( z3y3|2!y8Z~;IejKgOe>4Y%SYd_nPg(H6(6+mR`j+m-svG40fxfcLs#h%{SlQn*s&c zzT+3oce9inw8MzYL;Nhp--5ZF3?eXEOH@nw$ub{Sxpp0!Ka?123A>OgSeM*%2*X;X z<`w8J`R$V3U0+Ek!6cQRn&T$~(R12@2sHe>k=sO$MQfW_yL|&fmR;@HR?TFk^Z*H+ zFIndB*_<%BOVmp<)~rf8*)w`z;itMU*%zWPX&Mv5qC0Oo<#TMe7;PfATlO{OE4*VqDYmpAdPg>Y|}d*=9~`BLg)ly)Ng zmXR*9X25Qa->Q9)$8ye-E2*)JK{Ss=U-{Scc~1Wr@p|pxXY%|yvHfuk)Ntua%eL5Z`stSw*L!zKmmAz3zzj4f4LTzr@jx0KO;)-4LWN`-AS|IVdT&KsIMSKQ@o zA^q*>lR|N6oe6rwq!E{!64$a>d9CmX%hX*B+E-h|kJX%MdO6Ufzfh%!(jwu!P(>5#- z(Vj_Tx=aVFI0aQp8PW6qC)-+5cqla3b#F@bY-)H6`x5O9riN4%Fg5n@#XWwgWuUq| zq$+kkmSFhiAWlJh@lcNXH^P{ZJ@9)i(p=ZcZ5gJBu07amQ2E`&89@TF_o?!ucsxy> zMjTR_1fMSE)}_zS?1T3CRh#J-OI9@cv4+K%2s9$0;5^OLp+jXhn~?1PIvaC z1yvwRevj?e8KOOZ-E{+4?(Fpraq5G6;r>zROM-g?A5U1%E9}A97gh9;SAxI2%PjTG zfBy2kEUnY4Htgo`&7u>wmL>Z`kY-i(7sEY?p66TK`oO>k$xSTYUlra@ zi19wUnyq5qy$DGVIBC^~r1rtI`;WT}P8!Q?Ke?ttNVUSua2#8rZ>YAL1f+3VJd9fX zTUG~;Ue!};nCR;WS-qmHilrcbT6aPzq+Hm?V;83x(M|`bB392PTa7tEM#eTC`NGQM zmZ~!AaV$h12;$H8w?Om#Ny9gwsxeT+Vi%YNlv6l~jXrA9;`(O!>kl0x=qSfm})09b0VV6DgIh&cu) zAIavx^D?#Cnq>@HC!b)Y)leo%<~vzO9yO`6utqv=OIXU(S4fd_G_t>5MS|9W>E)uc z9-O@Z^YpeHV4eWIOzBU%45|S5aEp@i;HB6VzG9B#K{m$=SSO4utnq7yOlD`Bto~0c zZEp@;180EnJ}mjmnTFUbzM1SIUIM_`Z+@5{O%9W=axO+fxl*lzS&e7$zouT>%W&H( zX03r68j^m-^2=I(va;j`n*Qu18^B&rq$*9lRH^0=PLrj)`rGx~m{eDj64Njda-p;8 zcumg4A7&EtYU5}j)nS6f`OmVUcuzvN%gxfWKf^F+i#BHQco*@-6(xmK;8kk0 z=d&<;sgBE{Q)!t%6YAAI=OA(``kcRNM>vL2wg{hfI#F;QEH2+)hM8^+|Ggi?*KfwS z`-=nOo5U&YL~Q-OdWDDN8XI{VA3kTpAs3DOUkVrGM#vXpb9)prhiP^wlolXsB6oU} zn1pnkjXb-}>EWPvQ=7M}B$F>mvL)3ucggo_M_7yeFLn}3GN=9U+J5?#=`~QF`d>BH zI^o_8%q{)87a-QPX>S2rRv3cGAVLd-wMW&QYziwR>=&50EeX=r>{NknB^2JS=Kz}r z{XwhiT;y;*Q`!l9iN0mzfM*R7MMBPion0cEPNcT}ogME-*Y!?>5y2l;&x(Y%i6jtM z6>1%N5H?Nz%z(Dp6PkH>xgVLMZIKCul}dSPlkEcQi1&uQ$_{NIEXBHMbks|XG&bdI zbcA$5K$@>8*n4zku>gOPF+o~OPrmoz`(cm|4Oum;EmM3-eP1iu zfP=5kCYEQnR4t&|+PH&*R5=0P{~PFivH{OGDMSJuu@GUkPKOX@JNqXu&CEH59F^v7 z3HS?F)GwC)WB&UvmQkLPx1)nR#k7dOLui7HhU+WFl!M!A+W)#N z^GbS&@$if`5$bk7>fU}pB-WT-y}z|tEo3$BZ;CZW2hpl#?C}s9=-UcWowON9GNbv# zbpz6@c8EA8h0TymXS={{N4fYRGIQh2$wLa5-T+6Z$^BqY0*`Ezsf_$Tnyxaa%|Kh? z4lV9hT#LI?yl8QE3s&5{K#LW3hoZp=?(R@DIK|zA!^?g5y_x*@CYi}3fA*ZSXU}eI zs{Lm=4jl)#-=wTD&ZT+SZT6i$w|))-pb75gG-JY@cDq|Y$6X<4FjD^-UFpOS5nlFP zO)NZT$+8h(_Ga41-cQQU0=iv=d=|c{QDC$><0QOzWwHc35c|&i_lkVmn-a53E4QHj zXN_Z?YfSkF>{!WJOeMzRDtXt@jxxLp=<_In6}b||;Q4$xPq&pz#8fDX=1 zE|0IQq~7Kt?Yf2P#gA?%7`F3rgY4)lWySij_u!!_#^ z-Bjvb2arGlgrKicQcCa(x=S(T3hgjNMr_O%otbO%qI~{^|vQG9>&Gr`u@w|x! zCFNgNRumYs$gZHrweDe(enD7nU&}4lnPW9;9QUu9nJPIS(o_@(| z8BQF39TG7wf*yOB0L`W_ZM#fSRVNJlvU1;k)E5EKnY`CCr(A9shF>U~(1Wq1CF8XF&*O`+5hDB?s1;1Grr^jC_W zh9&jK#R_tDhR)l^f34}6hx^;!hsDwf=OqCq@p72jh5$G!;?iQI@h%C=-p|5>s!LhZ zbEqZ%P}NqtqtQ3pdf*19I}-u zADB{~NYx_J5TVftNbq{WgTjRwT1_J=^7;W**}A7)oVfNm-SnQb7izxVp-{gs{T%gk zXW*7B-a5|B*--F^n52*q1J4!NLTtu_#)4m8pl%ewfCNlRz=#KD(xh0=59lL+Ksqi~zb z+BzEIhc0SxtOmnzHA#GH$rcKB*{E=7`@&i8OJ$9uX^<$S#MP!1e;R$VBi58kOVD+1 z$YK+Xmhej-vX*9ONlmDigbBnOBX}q2lhqz9w%3NQV+jkq&~^=4EI9W7<(NFyA4D_z zDf`7K?IU+Q3*|NC-3aWWR7?aLu9(KA6<#e zy23MiOW1^M#u7;+7aJoTmR~OsRj2=DxBS!pv%We@_@;=2)wW5m5dY2cfZKyn0ro})S*0!2FtD+ zB0x@7mKiFRpZl*^o-B6_Iy%GVw?F?}8o+cd*NO|RH!W_)PUp2^ULgccC`3y_4HZ^4 z!&B4d^eNx@_UJal(|mD51WkaSH{f=t;Ft38+(w-z*$oD!EN}34lfHH2+ zy6zX!6M5aiTAQ1SXEgEL92^qREjPBVE~KXjFYs|I`M#z7<3uaI=`L zp0XQD{JUsomYhJ+ubm#&ic*H&stqfeT$d@RxB8*i>a@KTSvtMz4*i#VH*xPvu~gdo z608?5+T=dZOyk{ajp(&Wa_A2A)2hY0qhd+L`zOuC2xh%H;jlL)UX>t;ayun_s5@NP zRnaXTqf%M!teLZfZ3mVNpyX+ICW zT-$;G>|bglg!2;w*mm|sEs4V3_%6Rns!>hUs_zPa+7QAcj&)0AzetzLN-nw=VZUmh`I0w$thLiLk5v?F zb7k_n|8UhMEv)riwkVI~yBy05-?nUAK+6Ccjnb@pB*AnO2?u(hRe>m{%?RKY%q$d* z@7x!U7i)!}zfI+{k}n8*ZxOEIHFfzTVWjXop69C2#o>q<|Iy2B>9Jc^yXf#BY97qt zI0{l%vD^DP691bQzpH7mU=|j)^_lthewa6|8&O5I^#i|7-P5lhJT=wBPY+a_R1aAz z^>@{Z4^@f}Ymd`x#UAi;iH7NyJ}=r~;}LXh7O*z@rW`ax{P2MwGtp=qF%N4AHjYz! z%?#Kg2}cwqsLGDBhY zSY(JR^t+CTOtBHkLI*93cRCG&^0>G(0@pl8b>W}LUo+PVd9rVDmv zt7yT7%wyAvO~6h!OUQDn;6=~rW1<=BL~x|A{=;_j{P!a@V+&=uxWx^;{T%*ph*6XG z+<_O7M8b_2YB}s!ORWgc)rBs$dd2ziuyUKAlzSeLu_>qCf4(b{u&*#VyZj`%(5@?YOuhRr&gN+QdIiM5{gMSxfQBH8~ zUdHzAQv|t02^SXE&A(O)ozX&YmIPm#Ab%G#0KwdK(a*!4P*@J)D|Ls92j; zxj${2Avi~d@GsN ze@o^^o>*++@}L{8;u0FNcON}EB>-$Igk|Qsbb74#ZinRxmxYGzOiA7NSXmyx1YCNh zbZ;k}Jd@L(e7NF8Ibh7+I=x->rEZ0MfG$^|LY*BzbR<0P zOqA1U)uW|PxIMfX<&vAdHnjUZ;!)i9m@-(GDlTivF424;j=qa#L)Zr%Em>Es^M6!C z>-JCY8s^FtIf7F1gA+e00M+~D24ekR-|?d57+iFWBtSP8$%%{Lxcvyl16>U9EA}sc z+A${34xmZZ2yN@UR-|O^tL)8ODuE=gQw;@GYnHRPUEQ`BhI|1uh?0Uh1m;4Z(690 zxa@52E3)}eKe##?z|JRk-g5;Sh)v=5f5Bnr%Te$dI+w5$gR`7xj}ZNh?I@@_FVxGa zZUm!cbrEc-a9#ZenieYdNJDbv^(?Ud>1o^@UFe-J8d?v))U_82MIzv-8td<#sHe~F zYhsvy*kYO#npbJ~`<4ig1Ya1V@XBfJ^Y55|lmXF#2$^)i6qbvsy<*B90D8fhxa2K> zjGr!VbhIr3G5DYQ3_oYUTN{9=+0+pgs8Z3MVVV{-`dnph^?TyZL35pfoT zmxk@EwuA<$rO?C9S_m0y!BiA-vpsG}5p(=ajH^gTQehR{fBRbU z@>5XkTz%n9<3h&z=oR#I5-+IE1!pS6#5gXvh;?UR~d57duHD;+cXX^KnQUK}rF z7)sj+rqUTXnyMfS4C5nQ2+c|BbIT)9s5FIwWYi4wWwiY2k|Zt=0RjR-y%bBa`9S;; zlzPv*@+tf|t0`H>4%xi{0@x~pA~SSyfF%yd(?_&83nTHhz}!oOQD-n!m#Wl;bWo|= zHuoW4Rcs=sDS}odY^##cTJO>$PYFjXk~>t;x(8}SAFB}0i<+mNZ0<3wozrwfr}M59 z2Y2bb)Pw^cXN54SbH^zF?KU4jzCVo;v99&YT#yyO#O$%}Iui0Xcq@x`*_wZEFa`hV ze=!|LvqWJ+Hj4e;Q%n0u66?6?zHx&-y4^7}k^(#ajY8QvI1k&_S|W_t?jB%zSCZFC>ZO?vwEtgK7biS3OFL4Bvijq&D)!>1eN5XB& zLsO>w0Id-}I)=h4)zfY@3CyuCrxb)0KrazQ)!auWBk}g3#y}@tL@!okRVt!)z{@{5R@xC@r z{%T^jo)Kh|N<8DgOFE(8BLZHOQe7^ee^Adv{}2@BAsgJvxRsa4VhgRWj>#hKS-s?7 zKt|AxlPttRTG$)E_cV6q0cGA6FG7q1Oktm{Ij&8Z{AL%_c%A$xaso@@bS8 zu4m4}s*Rtri)_z#e{?mbCIGrada`3(u(pT!w;8JBwJL+Ze`xE(Oc3-VjV2hf*JBxN zf=&?P>PRkrZCw$K+H%BAgA8Ai2!@CIt;n+o#^Ah1@7?a+EU+1cTil^lV|s_7TC(|q zrF{k}gZJ3oyrQ?xJ+wKm4yei#{Qw;e-Z?)th}suro=|5y9zxdV{HsO&>QjQrlmPIp z5OD?$LK)8y=X)0IxpVHFmu;RJfG? zV!}V?LvEcaJlK>HAY-=e`~X$Wt4nT_Ymc;kZlqa?KwC80n+rvx-?(7;z2OQV?S)H9 zU0wZz=u{Uc5K0qgYPMeRp4Z7AAHP$5@t#*{K?|lFhdhvc0G$pf{u5AfkdtPY!tK+; zVUr8NiF5t6PQbY7EN!P$5QlNrjC}iiatBPs+(q}d`zuv2ng5Z>hB}0nJJo-5X=qr8 zIF`-NL5cE&$j&P$$luzgDK)3q?q9g?X8f?2wWrrP)L-CH_2D1q&8*dO*<5iAKY;bbG`)ii7^~BZEu_9 z`ZC|=iIoQM>^1Zz-nM?y9{1Eubl{8JK|>P7TwUZ$i=cJJ`bVbcrV!<&8(mQ4B>=rk zxU)DhXBbPI4CIV#|5jTk$D~`OL<`=WPN>7oUZ1WBX}DKKcDawzWkR0`08o7U0QGse zij%8Y&+?zpPT>YPFIfC=0E4_;zVrvk&Ywn`Y;}RGCs*F_Uc}RQ$>&ok{b3hA23C{y zjM=x$t5X6r6ZI^&rU(x1-o8cD&#}N(u(>5@sQs~KF>Qh#p9HR^Zy6Y1nNMm#W~{$i zdI=$oMg;FBNbH4A&DNfHaQ*ycR42@2it$%k%m{eaf^u4@aiY&ax8DMnlclmh+DN1Y z8nW)J{{%tP*UDvKeEwJe<9o%R&ToO^RJNFJY=KqDY%E4Vq?Dh4#UEOqYs#Q3<&GC0 zQVU|quRFy|jbVcM4jej{KM0U;p?CUUrja(&V>~h_Vs&@l<-#mozS4j{x=iQC@&DP* z{YYyiF>Mxho33g-(gX20?H4-#t+s9v8mroDhU_ciT!Y7?5sj_Jjw-@a5-4-GdgyIy zsTO;+ckd)MfO!>$YW3Yvdl*81W3QpwKEf>Q@Xtv zT~V#|yXEfFRJJl<0B^SxkpUU}?c*z1*QJK`wA21ZhwsN)hsv`B9V&ozoI0WvQ0=cE z!Iu3Tmqn@Gr_#7*PBo9L@X$8(?xp_Sz>5^i6d&5_ze_AQf&_vyhv`$q>d!-#WJwTpi?m3=LW$=h?m}M z#bdCaVbuN=iz*U%d?)z`aKqcI`|%T##_%$eY3P-X6&!?k61GQ12W%08Xi1Tu22@=VMD~ot@$hsUNZ~W)N1-XEe^Vbt(5Baz3Tg|PiMwqs+}>IM|$q{`24On{&VxzjPC3FLiB z4Rw~j#PChu50SaPG;+r{cunwRzf!MON_qcM-h;b#7}=UP`p=`EP@}#2mjPv2H*Sit z(>()CGbq5x58Mg5dSJq1v{?Xfkl!u%}+(T>93ETuxKvT zfVdtQNXV7xg|hEq}sALV2T%RLG{=UxC@wlYk5=3gT8t2MUf8qFOaxwgP z*o;!GR1ve1SLrjN#ClB${^DYU19rkbrZ=x4Ww9;Qd4pFh2fQ%eByQxh>NlpB=84^g zex~66f|+PVm34|y>qtI~-x5c4r=E8^?9a8yVa^BuCRuhDQuvSfuSONHN<3-bxdgxF z$2H0R!?a6}mO6c(sbf!Y@1pMs{5rhOW-S4pHwdVTraj-tz|1?R2*HH~*Lz$IwXgnT zg+6>=T3S`;rq_>fT-YjfQGa?hn5unR3Ya)b*xr949N7i}0g|hcmBA#VQ_SfIh zp+n2Rl;riB+w&u+6>Wu%9(h(d_azQmgfOb4b5VT+#TUuz2_~9|=W-^*?r}x1D}|$j zg`tU~g+r>;sV{jAd+6D$iyvWTqoF@>&3i`ddf}W`qlqYj8rpPOW9(9aaWrhTr~wqI zi{saEUghFg#uHsWH?8NoK<8mtxJdUDb-)*Bu3vy zvc6SBboQGr&*_pIQBLqmlQgLx52_EWkQJq!TE5ulDQ$2`lB0Ca&tGExe-Di1tVSRMt?e=nNO*t?XCOdf;=G3+T+;1 zB(KeDKRPD;YKSV&`=I-vRV!iKbX@300???uc{XlD zvIg84-oMVd0j6(ZCfss#80hJBn~pz4M5-=Q2nfd83#B`jImYQP91p(3e}4a&=Nz>A z*IuTDq7PdhAoe%&y+f;^Pw<*-&N%#3Hzomm^@;6->t%j{C}S8~1+3qOW!EGL&8Q$Z zeT`ThwOYNJLy{em6L|i;h!*a4*=T1RoaZar2aZqhp?Y$_|7$<2+DS|^S9uzn(^(39 zKDRMiG=%WQ#KgKlsDKL(M^KmM1w)@z@mlLiecAUT28<7R#SdGbD~13UPf`nzn{R2e z8+R@|(~eM}4=)0hy4~D89Nk0T^9gT=wHi;Q0kS}m9HD2;FZf@Wcot~lwG=2#d1jRN zMIb;c52|C$dFA&af0-XH+CEPQrzboi1Pc9_O%gnDw~YMp{*$NA<6}GvsYz=A{4D?6 zU!7ZFA}`3mE6iEmnMN%6o*77x$P1f4aH34;Qaruy!ISqTInChVLX{fiVd^gzkoN3K z(7M>y(vG}yj&aR}{w|szdKWw{S<1EPSTw8bMIL1|muk}-wtQx~Ogt9v9NlRHVsUz3 zW#6SE|2$f^zOq6B|4g`YdF=%z3y6ctZqbSxg=ooB!!cUodRC~uKmP%H8&e8)ZvYfQ=(m@OT>VtZRnoiFzBok z`O-6@52!(I71wu@d}gR_@Ug4s3*8N--d^T$74;z1zLn<77B zn)BixN@-|?w{vvd%LG(gct2S3OpIoduPW)z0lm0gSKx6(t=WmVDKMM&kols45=VUnK4SaG2qQlVHzjY*k%bDT`(k2!OUhZ2cs0YqV6qeJGX zG>6WL^DQ(PPj;~LC@|KTBvpHRekLaxNeZhl9ug(!eq)|%1ay!ykWdEKp|Hvt*;LfW z?Y&K;*Nf%8tsnIZ6dkXD@jY_-8jrrb?p?I0H0cBc`RZXNYBqeZKmvmW`7ml27Iyo? zB`bPMi-;VHaNKz+BHWQ-e=zp*X&ma`xeocSA(f~4bUeYP#n~>$`6|eD4zQtUV5W?q zH&c!9?H*>@$2Zst7qYH+i((6)-UasW`f7ZtFLwIv&NJps3J+av#1$47m8FXF9wpiF z95O0!-655K=e_va5R#S77ayVce)t4%K?2>pKF)gPtYV>#jFFM<0~vVr$-xO3R=-Jp z{t>oWskeobbFRVQ@Ah3yZm^KF8ulbkG0T~AwH_xJ+PfO7nOGa+xCz8cx*(`}gIAbJ zIsK0C4(i`(OP&^QLyFu-*I@9^w(bQabOZpWapUqI_(L!FNvjTj8!i{59wo%2a%Bzv zzZM__$uJ9I_YgB+ha-}NEwY26ttXf&)6)>HQOR4>Xo~xfv0*?xn*#p+8Ef@Aabqv7 z9_8nqa6`t^tY7Q(C3j2fr=6v6p3Q68Z#@-_s^3VsNEa>!Lef+T27zdk1i3o_*;$Y&Ti$!EAD6q{-zSTSV(((v~93XmfXVqQHkCqOmxctoOGP zQoW8FJN5<&+4mm%C(?z+jh2=yO4FpbEwhbUs$q);GdZ2T7N;iKW|7)tBk}ehH5gTL zx``!Blz`5GX(C&l%A0M-4k0r`pux9J;?}v6s0v9CuB@2q|?Wr>keIw9BhzlQSuh;m<7IoZ@16nxpic% zr<)&XgUHvroL7WQ6awc66BbiYyl%c)IlzTlGW30)PM1c1Xl!f$B)FGynj@Z`So zs&8lhn*Vf|5<+2w8rOh$PAsuR)GnFXqG3~&3Ag6P^Z@I{y}YWYl) z$!gC&`enFnHV(6p{B9(uIBSbnVZe#-Ed9PPcXdpaq5HT0DQ4=xJx^*TbwG8`J&zEp zf|pnBDnH0fZZWVt{s~H*jQICQZ95!f&DU)?Xb{ZdE{leCqQvP z5qzsGw*T_ctGh?Iz^q9DN!7m2qmI9jQ=rP&>iOS%ir9I6*{ix(yne$z7d<`w+o~w0 zNnkzbMf2>48PQ`0swQH%S7fUx8*Bv{OBOXKl-mGh6>J)gFO0Y(JO=?S<*jk=tvj13 zg^*-b-&WQAWbAn7BJMJ~bX@B5GAhx+s$bCUBLm*@j<17KHq6B6Z)Jv?wYA2GULj2V zd3PaIMBP{%`rd5H#NM84TrS;G&N90z*FolGFtxQ?6u$wDAcJXb{;aSwjF-l5$H{FK zZOuAsBcl6z5c7h~MKe@CXK5;Dpd-P&!mQvGU+7wbgw z1ZbMqV*ebaG*%o5(}ft|2+&D>D%dcPN1BDg`B$kbp{6bh`}HyH36)#F)Fm(w_xlnM z7dm`E|5vHX0GfU?wSJ9;yd1R#Ssn@1TrrpJFnf2V7sblZY(ar8`N;yn+k+%ypK%AI zK2Y=Jwi93W@lbh=;!QBMKexoyZaP`o0K|ukXxxbut3u2{;vCky*XErtB%AZWE zigF0AdDb5J;7Md?su0*w7fU|(kIV_29KTQ%e@E2eYgm61Wtu=d#2FnH_bXgr&kp0m zhlZ^P_^-!4nNG_S8@L|n=*QmsHkG#CFGAJ}lcja#8M3WWg#u$*sk>#wsh>G5JRBbb zTDwsZ!)=PvN0OoJxHO$TkF<(|gLF5|@Z}I6TCQvo9X56gX4?uh&c|&|47WPJ?wir@ z*VfR&QtXu{!Bz%GM@L}!nDM#ajuk;~NzRBBfo*~Y0iJh`3}T1uM|KbgJLTWWSrwBS z3P#7(#)LI;6KVa$2C)a<^P1JgTYU1(dPe`z47HjiFSPIxR9$XI= z*!3G9tm-DJ7amu;4E%b^wLfc<_P7Hcp$)qUli*pCke5~iSG5+W7*Lm_0k2t!07ULh)SC_K6BOl4eV^Jace;$OSpZ$?X8m z^Y7z}9>ukIzuL0*sCK8!%+H<;m$DsDgtwE@-1I-deP92{6cG_Im3eVgx&bBer3>R; z{_qsEMuB4Af4M}?oQ2K45XjBxm}X9Oh`oFpr%eN3ppfhLlT&pG=LE0#CVh za59xrw5}Vo>FhjyUz}@i-SI55)HIIVS)!(89(FEl@xK3XvW!HOnYn03uCt=wVuROv zEnV2LmlKJ(ury~xXO4svruZqmpRbRMvppSb{JNUXU_Q)TP2MYCxF|f&3!FGiEqb_6 zOn5(I-0|#@F}6>5AD|CiqUQ`$19oCmU(mLQL4Ee5PhC+7GocL4U10q4Cti>tLEftI zq4MRu?}9Y^<_OV40)Dz(gl_5p$U}otiy#3K?~a75#rF+T@~yq53=#5wzEr6&Yuij8cEE(1w0P5yENc8@;QdQ32BGMLL_UhV zDUI{9y|16#M$~X6ziLgr`qF7#z#(#u^L3ZrQyRN6Ri0!%PMW+#QDB@BkhjZ7YS-kO zMHGx7W5Oe4@o4o02-(w|K)Q;lBuWJ)r(i5!Ip?~L-b!nq^`p&@N=+|P zib)p96}|(xmdkqOl6>p~cLcIamJEi&y0zp%In|rU8#%)+Mx{kr@P?yYGUnBN*TzuO z2|R(nR?%hgSbabzg-ZqIbzJD5zjNM0*j0_RK5`t>7L+f;G7oq4Vleq+x{@kC&qI}C+jbKQ&oP3bGmGy^K6US{faWF)Ow5I?!Er-) z$|Ef`0*>6%5G0g?40{`ZM2HUCv9k!U8^iVl7Wn0%q9kgP-I3H;uI1cqs3W_Qxsut$ zDKcp=bvL<`a}@(@agrS9%c4{)11I1yt|Q-;XZFJFZM#Mk(dp)Q?3}5tM zjNN)w^^zfa>5xb93*E4G8J7|Kk;|pp#j4VoYZN&qNh5f?8emxo>6YoM;64@Uq_-`wI(06hZ6q_&hB`^wg+yqVv}Z3>Cz=7D~B0Ai*W&ZO}7A)m+crG(8} zQVIAzAA6*9t=0y?n2GqQ+U(&93YZ7IPRnP<3kgz@h<)-(5^eo7XyeaW+(ZIBjLP(4 zovK*qP%mzxT3HmHIg6a_D6qQ`49)ZPN_pZ-d*upz>YTl3?^L{Ndd~Df80F`xH)VI; ztfvf)zIfsfZ?GDw%U``OSiRR`a#*-F4sm)vWL-Ti+T{1OBR!lj38C*qK}R3y12-66al#BX+Iw$F<+P zPw*x(PJ+KYc{IRpRJix>h7Jn!6l;Ix>*SEN*v~BZ%$uX%(4S*g-J0n1Y$M3-cs6pb zeNdf8pgt{CJ;#2C6 z;>$M|&v4VDr91ldF`!xM;HfOQQ{+3S*XQlq8O(WbR7yQeXHWse=$VuJLbo`$jZuSi z?~4pmyUEt6-#L=TMT_h)J*8K7C_xwlPY15eCKg16{5}JP_H&A*^XN7f8dny8xMBJ( zs13RUy?NUHGe_Dvg=7ziRiCcmDw4%u8;7pl=p1ue(U=IX7en$~R6DWIwb+5eB~T-r zi%XbMI#{gG-E5drJr3Pcs6u6VN9YJuJav9KGmg7FpV5M`OqisP)>09lWoLlVJ*MK( zQqI+#x3O}sk`RLcZ$>FODs9z1c^Q$sfoXt^DgOjN1+Jx|qnrSdX56K|K>=2%fxW6{ zXRgP}N9gJnns3lxz*3#2-@^xd5!@vS5g*xnnx0d`OU3d ze2l7)^cG^%0#!DFv^{72x_HHu6TRcL~Ii^jeqT6%6!D>tXTSV6=h+i*r zOKA=7eN^&3E;r1UGze6l&Tpb$2uk6lg90^%^SUgjH1U7h@;ed;tI-|>Lvm*wzT$+G z{3qB>Ii!&Zb?p(+!&xN9&QO(phiik*arUJ6`GI?n=%(rC8FxVk-;O zd2KZLw_2nBP%Azjj0CMFyyrw;! zBI3V9l3*OPwfPL{hB>iPE~J`ca??I+vd!h8>_$~sfdvb-c#YLK%c*tVo_eeC=`7@I zLz@~flvMU~Ivf+U*#Y}N=n z{g<5GOgx*a%*x*rphA9wuIjbi#Ya2q%?FMoWbNzSnt-T?_t%;j8NmkWz5+>R)4-2b zI>y@LX_%n~n|>@1s8LYWr>t*%q?Mh2pm!-ms#&5)I%yg>ShdYHjV zx(27*aa6e(2tTRdAzEtWWx3}lK>UbX|HClu<->(YAEcaA&rrv-?5>8o1OFFG;U<~! z>I28)0Gcgh{zQtLx|$~*qUEsK;!q^2@=qs9KZTyt2BU`Dla3WAi_FdAUJU6m2Tp-s zj|K+5I0jWNC>if%gIAhXAHVT(7*y)N629jHBp_g=8%;n-0yy$CT{$pm41{xj=@z5o zXvPXe+-+Yfz>Le8-FO(Rpz=X2U<&@!Ci)G?vIZ>~5Te}*D^X&$9oNvQyIp>nnMqOa zAs_h@xZ)<9q665N3Ds$VueMXs3r#6kE2CcB@vSG?+@6~jBCoe|32l(n<&73!Qi^EM zYd1~yI*J!VrWaoDTUQq9B!T<0U9kt#{-c3-{anrR?3N7Ad|y%>h#~78x!#lcY#VzK~wGEGNDg^9}FM zl7hdVm0oS8YMVk1APxFNK~=)j_Da`fzUb=L?us!(MDv3utyXbXVGf zmbi{zZrm)Q+B9q+49};VNGWsK)SrkUYs!zyt7iQ!HoTQjU_fY~BVTVay6uF$EDnU( zfdYF~6V9`wD2N>rXWs%3#{kWnEw=aG@U|g6ce>Mq%n42)QfE*Sx2RV;+_zt+-$G1}2K6kR- zV~CTqcerYVY0yHQMp*7H>yFx_tt_FFjsAxy){%^uQPLS_3^#+6uPWAWJ5Co;1W&19 z_CqMJFGg9`mL;IlWNn126e6AqiGm)_$UZE8p(v%jbXR5qoWNJP zK$^9}aU$)TgD{eS(3+idvWl{&|5PdQb z+RHSnJk=waYD;g4zIsiM=>QG%5Dh^J?3F)4n16iVv<-5wa#&&#a9FC`K1Cw0QHgFx zHLX?YXZ-=KADuVKZ&tKZ~jn1un|+ zSDC+?{e^dD?l{IVu&qZ5D8h`0!#GtftPnhOba9yCaDElV9QhR2B|W+DJX*FErj3?E17D^fCQ}lGzSMQ}OF#sXPU3r75;6Clt>e0z&Rcjbj_Dzv$}}uHJW< z_nfkr1wF@Zz!sO9-EKrsvtig#J6%}M=1`jTjBq5r(pWnNrJ1kui%pb^E~z8SZ*ws4 zl*jYk5TT8!kcb+(Ur;}(`lr_ceW<@WP1_w^ESvk-5(Ty3nVYf?`y2p!@LgI^?Ly}aInfvfPjdSZwSK?rVQ zsCUp%#897={?l#Ql4M|(6fBr2S;I3OEngIkZ1@ly?=+r<&n%LKcpZ%h7@rkts#s_( zlZhta77;N7oB$UDcQBfeVW;vcpq>1}F=8&G4$$5PTn`ce)Or5R_Jq&WmpYHrfl3YpafFkCA|i#a%0gA+KDIjvicYyo*pwB*=$`EcV;`n*z10$uDh}=EFE_H9L8W8$ zTI09OJkGnUC;n`Y%FdDk$RSU}i$iltEyz&vg?cSuZqduCs&>-q+rtt6r?mjiY$IrL z)X71H2;}Dymx##3=|#C)<371`i=VmQPR7kjEc98QaL}hIkojk0wOsdsdN}Dv_pVf` zM?gaCRkf`!Mu88s?$D$-?vM-8B(v$*vVYTxG7)`R(Q^=r~T*hK4bT zlNnIuUGhLw0aboVD+gWoYclWc@7Y@(_*QHZZ%I&IhP9D~!n|iMy|iu^-(lJ$=KY)} zS>hcm8f7%?Wb#r5Y?#5Ih850%D$kP~;$Y=mE{q5p?6v%|FIu0jEjmiLO`};JtcSce z)F2o2g8r&I)1RWdv6K=g_gxIJD=lHa(pb*uEDn}`cv==;fbLX#gsVt?HkeGAv15&{ zIhu->4K=W*SazpZhStLz6;nbB!Wquz87O!3`)rKUTZ-l;IHcXg6!_axJiT9(F&BTT z?HSQ?6S^&g6l*`bd8aZTXkucVmc8bQO(WIJvF)ikA3j~6*|)3ibE2C$-1z>f|J1%( zujs1A{96n32;|nelAlwg*sN0mzsAY7=6)O7UzRKNT)`x8VZQtTLk)MRlNQNs~Qe&azXVa}|L} z{*o1xZRBcL{--Fiexgug!&=VOQXiwfUl7qfn%bIE)07vk5ymsx_|7zxmzc>S#Njs$ z4Ti?wcsIL(6*S^c%PYmFG2>_}=R33C7ib@zoFO|VACxG8Wq|Pt{Tj&~d)DR}sZv>;(@-!Ta790$ry_2cM;KZ-l@Dc{vo8afw;|4 zcQI`EFy3upf5I7eE~0o25uOjYKs;`qz37fKIB;+Hn@9%X34Bt9_loQhF030#JbmnW zH@|;=&n88WuYDUkORi49SgUMUU4(Y{>@7!VU68itnV^o8Sr3AeQBny%l0O^B9vmCB z8cZdmVIx&4;GVI0yN1f+9xs7NWL|(r}3)!K07G< z5-qT8ueVBVhnWo6=Tx%R+>hq~ltjW$YcvQsfDvb3QJ6l_FdWVVDjtK`GiV<_J%wh) za<0Z@zg*qZamQUB8g)l zlsNggeGb(-zPKmOI7kb?_N~Xdcu}tz9YUu6D7%%74SDbL1i{+@C0q6kH^xV-_^~si zXU`)4IpWZosO}VD4MtMLIuEcv?h!zxk4xg@1NNUMZ!%sxgT%){`f@Xm*6z>4(<+O1 zWdE-P*my{I;&@aJB6^j5ooyinb(yyP&$rE`aTmHrww{|`-971dT7EpaPSin}|M;$EOQ6nCd+A-KC2 zcPkDp4#9%EyB3NBr=hr0f&{tw?_KvLPgyx9SvlX{duH}b+z%POOl2rn0pbbgMDp1I zS~>+M*}>R*0hvb={63n0{FM4^mVL|VR!tn2fjDjIUbP&I6GEts%F9L^S4m&th|R_s zz21cP)?3!~KNyqcX&-%_f|I5tCExSi>rDIGoz<`5sRyr&| zV}~*j8l_dEYB`Hjq-|(i^BP!d=wbNuR;t#_z-r|P$Fw41?YiNWYSQ^v5z!Q z!Y61ulAf6+q`H-faevxwd28&5*zXk6t9N2{ifz2Q=CctwUCrO|&*Ywh=x{88;*C># zB2qMKh&L}I59a3N|Kzi>ASswq($5;Q#*XdY7lN7m(qq4wDB4{l9Uy(edV}eZd zQ-s1nYMQKX6Xb2R{*K{h@#lZaI1nwfTADC0q%f7YU>=McajUX)+gO>e?{}itcxaG) zTkw{GiXanFoNB+ba(niZWyxZJ23gC5C4b`2@Q3r#{=(`|H-wr>UhAGn;u>o{95k~} zL+r|#e8xJ}ranf?j@z!1(fTHnIAge%a06OG#{yg@ii})=#h=AL4Y3>ZJVl2Pnn=^A z@5q4q^G)z=Dy+4MIEQXv-R-deFFoiPkI7r*@2kIPrK(cj@jY9Fc0en2gz>9?CQrZ= zavD*Q-tur)l1_~SUT63i?AF(Wd$LX74Ho~MKeF{cd1(}fNE?fI;y&P$*-gdA?H7NF zmDe2q6z4t$gYVeBUc45WOsR#Va5K~zI3G-Y+s~A>m%>1L#lN3N*EEyjUa5rN{vo_* zoe!--Jn^|z6cGXr2$4t5Kn%$9PF?ZR5~v*kYv3+i$Uww5%ATVs(vd~Ic0!c({t zH#URb1~TmhnQf4zJoWRwU%h(Ij0a>yq=SS z47KcS($~W*>&OIminFdyrEGL;@M9My=LDyhW&mR=bMmbQ4eODWZ+FyC!naI!*@re9O% zl;=Q}&?0K5i`>*Ax^gfE@9kG+-42xgSEGL0?INr*OYdrCw=Ge$&^0R;*H!75ja zQ*X}|iSmigF+JDe=~3mXKBtsieGbCE(A42(@c6U%@DN#hE@b9kXFYbLcBGqI_{Q)J zBeEZ0BO5=H_x3HRQ@u3ywQy7(Klet1Rxix(KQ+7Qdmurh>YS%;Yx8?r{(~_rWBXeA z@6U`2M&Fzz{h}UBBb(oUYNJuOLGpz0BuqG5zqC=mbubN&~MHerW($_O{oA)W9v=79Qi!>2nkbi5>i8deF${CHGG3sz>v$ua`gPoW z`}u{62o2AyoW__>zb@(4tO3Y;xus?F$>11`sIx!vO1-5-UP0p$>yaa_D+_8BoOyI| zv}X|G9;*Vs@jLl8^;Nhz5hkB&HNsj9GG(}RJTM3)i!xwg%wb0M(PHD1mfr5&4c_pV zeuw%myM7-)EVEGi@rd9fe}w-0rIEnbsNu-)2E7uUP?dPXnnd!Pv>zEgR^$=siNz~C2TT6Rp)n` zpy>PX&q|0JtM5hdEtssIlnLp?au^mZ=7oNlm!%ar+np}Qv$MW&^&Ke_#zBJYs5z=4 z>I0P13a`mNv)VXcnaME_85)eC|ptRRH zumm! z&fTUo%x>7GWI_BXtppM3SkNo;+&+VJLv{Qm3=%=Uy}mjctbeIEN_&B|pQFqc5XK~O zi1GeO1vRFxYjfuqb3#Irx02&EB%7|Hyq1Rb-rsL+j9mZZ;p<)o&t44a{Cf~1oQYf% z-p3#=K(kdB4bM`P&XXz=%nC)F2u%~5+{ZaF%!T^dPATQOgv2x!W%Fm#eM4m+{P~4q zCS_ED8Rt8Vl^UYh8n zLCF<&bbeDI%VW$0H9JwlG9_#aUChpY%Bg()`qjeopAJsO(s8~H&h+xJi5`6SXez5^ zX-#1^Jr~!O!Xd9juSL{j$nC+tCoJr&C2xbIu~dMGh$rG^f&qxPW&S-qFv z-%)8WiNDhR&X7MuN`^}G4Tk+8&b82w8p6%+JxB=QMCj>)Z2JvMvg+yYoRFQnlvYXhxe|qH9>Q^zJ$=> zIfyK>Dcbv>rUIwU=+?TN`&DhNtC#RjfB%M?Z@*y5SymXCH0MGsZ{Nrr%v~d7YHqO# zrrt~_kQFw*dT%x$0B0k_1JmHEm_{xqwsW;EW8;A*hHYK0kMtQvKuKFft& zg)BuqT>_nhU+~&eJy1pq$j+xo?;&hYuLYy`ws@mLeB&IPPk5yrS^?SX``ZJskQ2xr zvvcI#rolvo#Ntca^5DHQ9$e=R3E+!1wo+R5RNQL%614Qu2SV|Ff8UtqZ+)-u#N}lU z1#W#aqrSJ|c?{@_di_U*%c?r>$NU^f2v^=v(5IA_6!n#g^+rM9Sm&odjzn zv|nwhRV|}OoAe6Fnp>-aNTd1q?kS=5OAGIX&caxyY#L(zCQ^+l+>(Z>L%9#Gg#@!4 zPPRf$FS|ob-z z2UbQGvPFDONA$A5QOQS>9%EB#O(}`@emty*_xAThw)-rt5SoOhq##pP^iG*^5dlmf z(n(w$Xkx^!_fkh#y8qyr*qrV(lS;;?C;kGEUjHZn?Z^H#~Iw& z?pT9uF_We|On`Hc|JGpx6S)F@S6(x_pR1f#e8to>XON3a)cz2nR>{*aI?>%Q6DlU8_O+9|XH9JvmeqRw$!B>CW{ITm4VU&J2jt1qeVT+8eKTX!)QL*@lYqI}>PyhvT4u%0n zCEIqx2Z$&&qKq)gfx)pIsbRz3t+J>dw!a?QYX<{!m}W)Ljwbg~fkd=igvzs>t)(wsA-~28SMWlNU*6yqZT-z%T z{nwfKXNi46XLG)c{;F~$$dF1PxTC-ERdDQA&S~S6!`gLkg<~?u!LoVg z2^?1cPw)=)*j9qeEdU2iH$VrAR`~IK_OpH?)G*-qz6>~V5ZQ1%>VZ2*7W;URI#q`( z)y`71a{mfWTee)%Mr%r%d&KdP-zLKt3(0DX|K(q>sZiN-BDT1{6m@DaJL2OMf7f9u zFOm0J@y(TZ;hZuinrJpSp%A_L+J5QZ%N&>jU5mZG72CONN$owX3&W24Y<632aWlfz zTR)K{-xRogxyz@fEi9J0%%pgdMh1DP^4Y1_j{SAx0$)EW^)e*NCYpttV0OW!jgd`3 zYobrm-M7I?sI=1oFyjsf&QjqsU-29NU%EBtlw>0IH5ta|PHWab(lq=G(() zom6O%3+emHA#k%C**L>A=F|Kw<;EffKL%~OQ-n-=Up{YY~p6Re{^vhu4(^K5s zAQA1Osccciq0g?&VwO|Q&1=)$`L0|3E%?<=Z$T0CpT_`y;i`K+tD2=)ES2h?;XMo5 z(v)JUB|zo>A*HOa(Pe9r;Ra>tS7nV6p>A^J3UOuDf~8SMvkq z*dE@fS}_#p!@D~k8^cqa%2t~{l;90CK6~Yv&URRlXqvboj8mz%D@6*N>(vO`la21` zQT+4qc>{~sr>K&{#(YOjJd?#Z8pQ3jlvLER+Z48DKBg8Fpu?u>!B-4lu3tWK@M~;2 z@J=tSZA=6om`#I6&>zx|Ie8b6P)VbIczjM#>MVKX_`&~m>47Pery zbZXUg@;sHG6ntXuUyls8x3TQUc-TeSToknsoG&ik-=8F2#>=r*K4a`l}JlcNWNWns(~y}PD~!o)8Cer6x>C2k2Uv?{vMvn>H6z;N-x>)q>*wMmuZQSxH_$Gvi4a|Ac|9a6+=&Fhe2*_#+ zE=VDncD3LNsO6#L)T9NL^&dyY&cZh>`r{AWtnPCG{1x45`}K<5XagtZ6$YN8mT27t zj?`@Pn+wth*`G5SMI;LQGZyg}=hqS;zA=)<1aAhw7!zx_9FktMU#ZcG&Zr z5)qvF7&8}FQYl?4U;)h<*x`oxUedN2Z02zDWQ$2vT!Fu5U3KYCU+a`)h}WDZX7buD zAC_v;`~acEv_ezE)R}vDgzXPa%=L3Eb@OqbmL$}b()!Nf7hpt+oTyGaN~Q3nW3OuxTGdotCIN-) zo6zl7oqn}rlW#u@PlW`|WI#^h5#Rndmop?g0*g+~_OV2p2-sKcS?|~SQSxhVdzYv? z$+`7Mz)i6&ZmNAEU#uMWd#AHzd`4DS`fdSNMa~u$V=4=V4~2nYE}lM@ze_2k7Qcy` zq}fqsd#P}bo#)N+^+<>}hDa*793k$wc}Vb;sam~uG%MvnuDX4KUi^(9+d+ZmN#RWk zdU}U0y_tp_I{-ZMxqDoa#@}*g79L*~pPvGoET$sz{MMyNzSnm|)Q^k-*IFi%LY}D# zpL)DvmXN&r|2Rs$9kTJM=-*@$W+7;}lO?KcB=LJF;<0W%Iq>&ZAdD4!b51| z4+>mJJw%zD^u@k}5aS`2czTljDLBhCR&EjIEeolut>tPIt9vdg2n?*Fn|_s9kSxJz!E;!(q+xVx1>{CVjL(weg}2b5YRtT)_?YsdO_er;A_{ z4{|G>aOquSn=^&c^p>9~IKAP+laK!OLWGF?jSG5b z$WG~l-iP_3q3IyLj?3%sT)Vq{52SPa_W2L}bLAUMHRmY>K<3`J_U19?7Ye@Xf95)A zcAezzkg*TW7lX~CZe*|zqSJf(-hEvfMk6aud8PmID2lDXmModeeYw~hQev_FHl(mB zYy68ox&3-}2WB{%UC9HGuwUAp_}WP8Tg5D6nAXy@zQ0oN z0%d7^EVqktB?RFh9=XSu|8o1*{|kE|k?zQfZniy4vf5oPpu7cA;hC?A?DY9>=svx6 z*q|n>y(p6>5Hk6GmHwwoWlYh6TMd!|D{Qy!>TQ5Y8a2+5y_5a}s5Xsyt?`>I1uA(4 zYSSj8t}{T{uw@zawZedKEOc2}?%u7i*8ErIrqj$PKa*nJf!IG*UQNRkiF`pd{V7PT z>LH#$-4>BohL37eP7jVJ+?KjdVc z1L+l7p@qh}i)yX>vlUo-)y#P;{{9DfvPOubN$sCYTmKf%I|rKBvxFYz)K#*IlD8FLi<=)@zN+jrE7h|1IR2Km&yF2U(8}TWDj?qMG&!+{ zHnhuCmYo)Jb}c!tTNe|T>kOeUv8O_ZoGnZWkXM}G5;f=Y32^IPn&yPQGoS({_;=dU z0Kcg=#_E;P_iOyXue4cw^9ol!&R5rQYW)UZ@lWOiS4kgj?mB*FaW*n-pV`~pl)h3A z04(H0^V8lK*I>E6N=I}#16VFm&g?Vsf`SEi8aT4;<(|}i(5a3Zy!()o>xFXcrevws z9pomqi`PW?nTyY2>iHJ4WZhoQJ{$9%Vv*Of8jf-rFIdYFZuMnn26c#>kO|n=vV1#rP@CPm6*9wkQw7iw z`0i}54?^ajpSfWnqM;Q(3}K+}Xk^676e{f55_ef<`*$0IV)`#JVcZ*G z-62%um)kXZ$mD$1EKNe2vJVq{9ml;Z?!MbO`Kvv|IA0BYBo+RctnE#1nj{-MQ1!n4 zLQf%C%YVJEjdW2aD4*TKS#-8rS)7U?HcANE|Csa-k5@+wmwG|u)k7|6lV_YsG9=r0 zB@pjUg@H3DU_8BUN5j$X<4P7K@5=SRW1q_Q-O*Qz47?AcqVw$2m$)D552hlI01&E@ zgz$z`(Fu1#RQqTR2k>U|-MIdU3y}C$r{-1F%&F)2Hn7^+#-#pxr@VrKVe?lviBDI$ z8n+2x|D}`C`1q!|kI@n6cpy9VAHjcuM7SOJZdf8<{xHzOdGRWY z`kz*If;Qy4=J+e-f?3pMVRo8i4JWAU8k^wYoIXBJjxcC8!jsc1szWi7Wj{5Y% zjk&0AC5$(E7DBaPM#gPr*IkJ07I5*!dWAq~fBI-A?6UP&^OYUxY;rkJ;qER%j}Aoq zIc#8|Hzn+)p7BQQG@wtR@nS9o%8sqDnMz$=AHV*i|CEx$k`A_dR3sCizRgyodZ*Gn z=3_6T%639`rsmlfdD@Km@*!gN^vCzWEO45L-tg57!MekNm(caho4)bh4gltMhMHr_ z5TGlCq)H6~;*9E6f=Z0g2g?l(z7z1dOvgd9jGh|k>*AisEU=RUszm=^Jy<*CI^FP3 zpenS8W?4PQ+A6}lk6y>x_)EG$xG6supV_r`->zeM(C@z}oOFcnEoK z!Ij{8&hL7jAQov==7=-7#=-Q0NCgO%g_nj9DHaczV$l_=Odu?~|D%3dUq@)0@s1<^ zCAI#^VUPxtWHI4Pe~) z=1Ys!EpGk}TcMpFEw15V4B{Vl!rvqRd@88KR<`IxALY?m>e8;L?jiQ@FzLRkg4sDq z7nF#l0cKP3R~vtHOaIrLa(;#Th>or^7R-6$wodrDC8oic=?FrnCoq`A_*r{Wze~xo z?Dth8nj)l+6BDR?sgw zU{uTG+Kz=;s6!5gftPSx$I3P^)I59 z`5G4YJH7rubpK>X1|UBK&}WT0ED*Y8ae)so>(&^^9={H^+^IMpa$LWF5j_M4r}K0^ z0?|0TrL|C@o#8Hb%{QHn{Ub*yZNYNa^TZL$@N||l0Wd9M*YY}J+sJz=J8)Y3BHbNO z2>ge1)dn?h#TMzkV)S$~ef8)5g|%Q4xhf0pX*BEyQ85qZA*KSRqZB<3%XR zM;|ojsNGR@EsVOSC#DucgHBZU*N$(R4e@O{#=U&uPzbOhT(gh+njX z^h4?A>2wc5bu^5=$wu#AKSvtf-Rz!aq3%UK#NhFV^o;sNrPFx1Urf1xsse~LZ4KX# zLZ`}4GBc%Oad`jm_aE!&yK4!rLu9gpscg?rxKHey0C_o5jU-*R#`qU=B&!FQ!{;p~ z+NV~j&3^Lj*+r8CYCe9a9-HFNf7RXog&xZo1gUWEFWvE7_ZS<#El;PNR(m7O+47r5pkAK;J3mjdHV}zdz=-u#i=6RFMDH z*w6M7>Fnd~6|AF!xa}xzOfs<224IwBZ^q|v^!*7jXSec(UvJ>!cK6y^V=LOHW8L~i zU8?Ejld`(~ecQD)+vS1Nn&M-NRjMfW}toXCmy64bxryl z2CC@6XtfhRfb}^LT?5#lwQ(MFOV=@vCIVFJReY>%l z8$KUUet9I1Y?BCUN^PO-eUroXLEqOH;^xCtZ8-EGjbwvZc!>hbhsZ7mMz;Mey?DiA zg+8MWt^Gd-o9*}#T zSG(dOUjURMrJ_m{YgjYW$Xt1&ne&6T(Y&C0+tlNnSI_UR@w6eig5!hzT-x3wv*`>S z)J@6WB$_94CWkM>atT1VN1y%@fei1SUnJmCG@i&YzbXqQPvP!+d@)oU?N3yBCiutFQ9crY?VCaK0xm*~~sYuv%5G=fRiWe>3 zzO~1u@2ZB)pb%J~kcTStkLUsFovsxz%am$e&ynqwzK7!>^HNnG!H!kuUA}}9q7YbC z_k4|?9^FdnS%A?YO5p0)*xA>=S}FCRzeglpHEF<1y@BcF;;QbP9-tS^4~+fV_IGdU z8=FO|AQ0ikX`-RNX@!S0hJh-}4!PVIe-Rk7*{J2+%Z1OAq54DWtl8iht3k-lT^`s_ z`x9iF+!1cblPwpKQ;^16Y^eE;t{QQSGGaW$c`Pv<@za^Xn~F}7-$^qSg?4t!OQ1e9 zB9lV8hNifpqkc-}Pyis1!RG0SkOP92VbqHMl~RGrny@T`61_URWb=TC7 zm)|m*9n9!7^X1fSs$(U(9}AQ=qgR1GM1df1IRF=`4{I~ptrj?uYclqra#36*;U8uTzqS}j0NgR4Nc=%2*cF;%-3#WfJcYD z4t8`QTwgjPpoQqaf?{{`vG{9QlA3G>M6hvjuMe9`#ILGqVt`~A7i6Up>6RBAhh_N1 zIkYfxdH{12-|e6=H`S19D_qgf;?%ZiNLe%?^;$H%elTGjxVjYEJol*`b$Vlybhe~o znxmT~254A;+9ka&iq-b)1}w*6g9fL3c!rsA`}%&@^N`s$weXSXPtcxE45!zCw@q12Ypb9wrQS~G5go};huuP}mf)D} zxup6{N83BYH>}X$v~gYn12M0zx}U3eRR)HzAtea6{2ECKj44tG?hf(RkT}W%eUu8< zGCdmZIsbd2>ZuDpFYGE&`920q=BPVfGq*0@ni5Jf%f8*Z6+|J&gUlhG7^5MJw zMA0}Svwgv$44%QupEzDB$X0>Ut7A887HCW$nOLj5(3xA*u)GuQnvZ)|=2)9AmH;OW z5OVO)tV1OGI~En;+pEwZ9>-1Q%excnV6py=x&C#wG*0kK2qo>EDZzm>@3ms=tVZo^n=N3yhx^G*-lRR zFVU^aQkWWTWqpGs6rdx*bMRD4P;gSvHxt^zI++t|4dXm$8M|0oslp&z7VtpT<;&G% z{C!Py@6cS-)a1KXY5fNG-?SmXVxX%PY{kS1Xq~CN>$m;`sg(_!!pqunSZenTULSg_ zhQX&lwNoI>K$^VfT&0}_#goOfuN$V!6(5|+O;NaZj3Ka zmxpCRxZp$w_p40n`Kf4c!m?OhZ1Z}GSQhHUv6H#;)-udPMa z_~!W3Szg*gVT0tlS=}!q0XOiPa;OY6#IbR4v{yC+>e6ZJ9xpiRhUv#+sOL2Z)>T=n z98T~m=c?K1E~}mW(~A>kix4|VydHLp7f6=;%vNTlOP@aqcTJrw<+2xb9xBbh;Xw@+ zD1N<1=pas?jsfwtj#*m*P7kBBR!601GRoX$-ht!!?0cBQOtXZ!Mk700mlPdS#K!&{ z<)J_;OJDmDzG~Md_1K2>%D33d0KKXHdF>nFPdUaOkah<07b|L#F)9)uiOWp z*T>uXmWQDArYZnyP1M=m4w?`M?>|KmoZ5%}vyIyUZp05UpLWPyhfFX2=A1>G1`j0? zN`leJJ?o!ImXn{O9}Bf;o$_klgOvczBwTvKX6o|}D)8c07ne--y3O>=NwGPW%)N<3 z9=mykniG1~@6+jQnL%yj7iw?x&1%ie_Nxl%E|yMt1BLlYp_DW@)i;C`4O)UwD@x+! zDS5-*QRlm>v(|^PyzHD%HMHh0Ak;R$v7z<)a&nt?SMu8h!}qWLf1ST>Kxoau_zRlZ z>Hhb(<#u0$$I27x2MqZ1{RdXqx`#+-wGUrn*&t;S(c|w3uTL-*?JW1v5aw0h!KnjR zXuhSDxL;q5blkWD!+4$a8nNxUU8Lz7jKw$e&-mB}Y>{__w$2c?vxR3X+2sW7jOK4o z0c=n&Rm}zYWzNBW4w0}u!VetXMGW0VR&egr7*eLaTfR!GZaUgQ81RbF;~6uatKP`1Vm+f0T6<0-yTv;hvpZ3NqE{KK&G#m3hV8y;S zA~zR0%jVZSxSnt+sIIwMeK9aR{g;5q$uml+@vffG^H%UG%xtMQ*FkXHnssX--oy*@ z+LEGC2~1tHfKji)AlOAJspCCrSrh+YgX%x?I(>B~6dV!3RDh`8V0R-oohMWz5rEZw z$3RW8$~%$XGoE#N=LLm{8cPf;lm32DG4q-YX{~tv{y6iM+}D^n)bZuwO$PL2?`3f~ z{>B>K()Z@Y?e*F-vm3sqkS~Wima7=D?NbuC_=uZFGlp0p*3*tZ&wmEScfH3|@`)18 z!v?luz>$6dj=^;ncp<1GqMKDizOWC2WzbrUEsrEq`1bbSphA(9UU883T9-1LxOFN_ zo%(9b$9u1jtu+Eb$Hm^=wW=^nT^#YH<2P%XTdwE4XlULIba3Zs-KI~Qf!1$=m05&l zh5=f|9DI}($x5II#B-Cf!higzP~fka(_qwYag+qRd6GoDz1Qd+}DSq!9&jDDBj zY)9qnv-TnJ@yX^u$z*)j94MF6nce& zMWU?1UyKl)XiY){wH)?7FUCRYEXPXHdz%7hRYUggYOGU#$+MvxqH5NR>_%~=Cykql?4~V zPySC{4mD^h45UDf$7YZ9vV5BSoH0pRDBe6qct3?lbeW6N!yuQ>%+Sc!3MUM@FP2YJ zmL!pH0}eBlP4gu18AE+1#Ra^aO0*`HrRvfC(NOjSh-H)E#-1+M1A$>ot)GDrE+^*} zauwF+>x_06@$D}M@0Qu2|0+4Mo#bM*mR;sWpmX5`FjRdzWKqY714)906DwDHLwCnU zOG+-i$l!GASEKuDQ>^2IWTMq89)ru6$Io)=ml-VWtW?+c!Kg_TX(6%|xB$a?NIxnV zVKM7-8$EPXC|5UZ*I-w0E{ngo9h{UO+dwb6@CC`~^$G^3%RZaDaGhbT*hUA$~ z;{gq=VX@ud(KrxKQf>TFLlkU`$HScEbG=ME^4v-1;RrByeO0Bgk1I>iWBGhPJcmTH zH-rjd@uRC4WV482dvjotcIe3fRqP_mY%TaCShQ|yCal72ND-J-u-TTv;!pW++|rY`^x=SXACqiv~p#R$TTXwM@%VDQ3mP%bYVK031&sc*JZbn3BZ)!7w&Y{ykQu^Qm zy^+;R_^C{*Ieq-{c5ppp;UB!Ot^50A|Aq{#t9%__CPA=EExYz621p#KKj>O0?K}1% zANlIq!Ml5zP-TzSLu8~^Xte10$U4w^CT@&~;6n{e0e>rRSMYrU2EKj z;jD~ww!D;u{j+(v>s>yQ?YBEwZ0itF`;Bv7L#o4I#S}ljk=|_;on{vORWH;pk650s zu9iNI!gy+$tK_rKeL4p+Gu6W58=-xt*l5Wr)Gv9-4O5PgX>>s*5?uso=q6?F4rOGU zmGTSlvbBVB$a!o!=&#`lQ#V(nsY`a6CdZjB;q~j=zCHoxsSE8>82^G<;_e1ni2fT) zPzY(rXfU;R0-N6G*S7^?_8N^$k5}`yS zS4S*&O@OZ`ebOv^z+#8jM#OIUutmodfI#Dva@DGsjt;nBMij2WxtwIT`^^zA>vkxB zDQc&rj3b&AGfs`!kjvm`$~BZr^h;tZY?JW|28g$RCG*y~>Sx9e35GMz#3*F}l}O1t zh?@TL_*&)U&lzf*%Wp_^h3^lQTGH)x$5d;`e~}RB9`x1~+xV+t47uj%(NcXgXrdQ< zJG3Ytu|v zgZ-qP1!b$UpF&fl(FiM_2iZj&t;S0JXK5{0g{>DhR`arBB7kx(1)n|brC3kA^av-SdCR2%;CZ-kvfeZ`gTG+fARkeT+L%7M zs(Y6)LJ+OFgV@H!M49abQm0sz$;W~O|1C{ReuTF-O1RDBuG;gwqp+$NDF!eOlNVV> zP(~Q_NvrQT&Wx@uq88mpAW;ZW@Yl!sItf~w54k?U!gB!hwuZ`oJ6Gd;tECSHWY9=f z(->F{MC=%ZpP5%a(qgU*g7BhG<8`a7`omg2fJn1mlGOf|;Bz>C%Rn0=8G<+SZ0Zew zz8!S^H+3f*ywJ+oy65nj=r#?5pG`ZpX(2tqBI`icUX!s3~@Y?>Ot+%Xn>I)2Ap(XeIhCTa~o$Bm^C{|Xu}6ygZ)o=hj5 zB`KH;z^_?Rqu+Blw!XigrM)w7(;`{7@W#x&X+^1GLxkuiM41_Q7+LmosO03t=)nTc+9Qj%|AF8gC$-fp`y&l_z3l7ZVc z-l;g!saFvaRKu8%6AH0Tk*5+LzLSdjfvy&G4bsIF!RRMGL}3RX(TVs|j(5^pNJ9HwI{!7}Q1^F2 zUF^crOm>-k{E#~<;$MBL9)s<=Kz0d|B|L`*UCI!BQ_d zEcFBq%X4q{>Z3Q+pH@eJ{d*i79nSM|VpdJ*HH8!Te=?f82ugja_Qytnk_C(TXxz?er@N zsUdx=K#A@(Ao55zy952toEM=zw_H1Wjb5Ty_$Aar_`E4ls3`^r)&?fMd7!`qxx|^5 zr9eTeYxg?FcDoWum)>85@kZ)t#73aPQ`X= zrD&!;>@MV=YOj4DRwzRe$HH__}S_pG%e+usR$ds<&yB7T75@7j$+%=5>nt z4*rQX3{h<`RJaaO61alb`x<|9c6i7d03|%8fasd^jmI^4H$HswboWe*Y;I|3Jor;{ zzjZDFhu->fj^`G>eU77`|KRsTZ&XJqc zBONI#I{z*W8AaG?FK%OM{j|LFuK>qAPPEk)0JO*2b6~wU(Vki6Og+m0eXB#u~rAN*AznY!!XHkYK#I2c=JcRRD?oVdZK(oD2p28&dJ|gk)z}# zI}QNed1el2ht@7SGQxO1Alh5apHz7AvLLxH{t+DAX(>-S<5U4E12J&X$5o45V-27` zQpkkZZJg~ytzl@$S8#ls(b#i<1g^(4TIjHKR)plnjG0JdT?&$(dZMxr%fR1P&yxKr z7>iQqj*7!7EZR=GZ;UTiH~-+QE(Qnfqw`SCTK9HunOE+Ja$Y|qNLJsNKX`kOc#rZq zXFRPJoB`vVVz^&zWq%Q1b8CUq;m0hCWWAdIN6D892(+2cWPuEN%NPv}Wg(4Qa%?&J z1EbA$QW*^sX|=xaPycpxVpMnry!Rr)5F$-z4~MIWDp}0-Zq6q6&?+a!HsGwGCv@!g zWQU|KT!1G7HG38%p#a;~iy6UbX0#m*0O$bW5Gf`yY^XMBf#Q%nbZI}ei@{YoC}4{D z=Ln38#_wl*E7!#4j*7qDJJoSOc^O)%dw2GOZErU|z0}M#tPnW5V{d6_zzuRDr=Fr` zZDP5=D*M>oqmBZMf=B6sT_Rf`{CKJ|YW zRH%3Ogd_%Og1RHSj%`0K`-*Kl-Xp;IxZicaA(!UY1iR&AP+RFuQZId%=>QZ5O_iyD zxcFk9{>#lr>TQe5ilYmUhSHmD$q%bXC;2z2S3zdo|E~oIjo^6ARuy`}A2ONXe90w9 z;2XX8P=K}eXsQTjpg2a$~|Tsy68=}{<=?o#=U_|=y=rD|Fw74j}!)-l1Z2HAM$@3 z_=M%>$TYgpAqk6JuP3X6a$z$ zCF3rWe!$W`y@-aNj!4;5AL~VY2%;Xm{jaf)$nJWrwMaj)`$!+U( z2OV>)?STE>cvqTu-8SuuV`@suVe{6QGa(bX+lh)CH{TB(Cti15+v5a9FGIcsVk}Pa zs3_pO;q~J};a4xjGl`<2=5yNFx}KoPN9+SNdH~{=6&Jd*c(x7bTm>9U+Dv{8wcIv; zXBdx=*ry&6#<55z>4qJ7KquxDd0@F!ej2~+yE10j^Hrz}Z)=1sfzLH3D^wWW2JIVDVNq50inT%#?)2P zm1|Uhl;F)MLOrc3wZJ9T)&BrULASoR*9T;;32-(UczZs7ClkGZFV z1}Ce#ewF`ePt3JAvFb7g26iO#ca175)gGa&L~Ck7fPOi^`WBO1qp7T3qX_?KJRH~Q zX>L!TY=(fo<3(~UCY{qIZll1SBPk8(^co7PrU?~LZ5Ct~1h~TjJCc+tI(8(ve)@8p zaRaNWz+rkQRJO)|J0?^+A|0!&AYOVj#BCM{nAIZ4A1^>7q=!QM87i|hJx#&ZbVG<$ zjz~9$xMKp>5LkMgQ+qTZJx%4}rkg{oX>lHHb2tGuQxR!hDN-{n0ZwGlJFS?!Ujwn; zxWH~u!z4piQ=h>f*Of{(R?9jg3aENx0(U$H!Q&zUx^{!a88hf=jMp1m9OtJM@WuuC z=Gd0FRe{}1qk6wYY-0?GBH5{^tY5D>DZ4dR)OKnTTa)xP7L~nmLy;0XU7Gs*wai#F z1-L;CJ(Rt%kDh?r{CELR6N$ZXS0$uj(b>$<#<}O2Ls(Un9}EiEx+#?p>@*nkmX&(> zwsHY4rGRScn5@ zM5stSe!eZaAR933>l~N_PHXv(6%AUg2w_DWb_GwyS+diuh;hJ()xSXUnM&(TD)BVU zfRzq8>WUW?%syAf=X2R{o=)LazdrueOD?jJXV`H*EE6<8&LW+XFI#(kTBR(I8Yi+0 zCURxVC_Cda#s(F;BHUf^^~uWzW@|SDyx4U?*u{lmTDd*1yPrqb{5ciixBH4L{G$@4 zv=K41{kgG$u_xAY?16Q(?s$hfmfX_I|M}>B$xRejz3F!T>u++5>|V>La2Yl>Pzlp$ zDCAkYvR}IV&-wVK8!)@tn5R9-?#+Td)>@)7=7Ls6xSN>P^A$Ea2D7b*zgQl!>xfQp zQ0H7L;&XjPzPQT%)eWoLX8bNwK~d*y>!bQydv!2dub1z* zH#$06zoG6GTy-#8uUGT|td_Y`Q;gN?H@9?u{5jt*_FROwKbc4Ok7MS3mOxo)w-I*D zM|gt-85=YZ?jXXe(B4xf$XrIT@7j1BJLBQ@Ntv@vfW}&XGk2lg5hjU z+Oxuz9Q1XHy>BN>D=<4bf3^l<&D@U=?$0NU4>6oalib>{%SPHAr_HD>c#nxG*2OiY?8$kueeWqIDp`A}#6PMaKn=)dt_rZ1NStj3xd%%1g-ctf+z`!4j)w-727L%c@yIHLygSrFueOk4o$j31iT$b>Lu78rSI@kr1lvQO3cVsZ^SF zlcZ}jB&!Gbk&ZhFFVES&*F{&{J(E-56q5Bz{FFJsPq>82GI^ zIo+gGQ5MaNfi)J9Yc&&y+e16{iTHSjfF{)*uTf>kW)CS9sE5EQ$6&J@=eEX5T0gd5 zuD$P9^;5uXZ)*{!Y|z_UR2IW6ab|3bq)!x;VzzA3FJiFTqQGijQxR`mDR67cbH-vd zY9-FLt%wPG;&Jub(juI3gRYda^R4B{K3lG=osu|}I19FFkgJ&Z#9+57ur;N;?TnSS zX+kU_>}qT;Tn&}oa8)LD#<`R^#ol<$q6G{sUdDAh?xv*a_y(U4a zLD?YNWvMK^j|?a!?r4~(NNZqrsV$j#lWLb?Ma*`aj6y2VM}(of~9{O@=Qu+ z_XY#omOS}I!4(&WtoTsK*~N$}J{w?I5re)?8EA{MSu4P_@9IpuG~(Q1M3BImKV#(UJl@kzaMF!$FJ#p^_bZ%(dIgte2-Zwe%U0u^q&c3T1;joV zW8((oa$7;znwqwzn$=NYwxNu|gQHB%m{m5m(mtP#?$06ZWoktlr;UkuvFo{R2zViC ziL{v&Ssc@S-cy)x725pC%hmOiud_(n9K8Jlh{$5Axt=#3zl4pCKhB(Qd;@LwS~TGA zzN7Ku|G$R=htEU<0&_h-*(GR}DmS(qS&RTx-A9Wo#^U3X-qB4kd@>Gp-(@gYpwlW4 zmULF6L!=e4*)e#m?fA_33aoAlyp4oJR<<=V9g^iC_QZr1czt+yQpk?Ofr$8`FD; zAaga+UV^ljAl!YduqD0u0zKUw$lSe1S6LjN+U6gfzM~>@4bnafGj}gR_Koqhcb)W| zJ%PEtUuD(0PsGz~fZXYpSfP;rI33-$KCkaW+UF8v--5Kyqoe!pPI~Wrg!@>$zHcME z0faj>!?tqoMmp}@ND-Lz)@u>&Aj_Ap#J&D90<#T!(IU2F-;Hor(&2vkS=w-+dJ=GZh;p+ zK&fN_az8X#{ZWp#AovM2|AZd-DSE$(_7yZEdu* z&7`fZjms`u%i!R#c$#CUOm{jc`wNdxCxS#_m}@oZp5Bo}xn)KI7=dm&U>d5Uy#YEy zi9Igyn$O%}*6Su-B*+X0*rQVQ zxwpXjCKH;JRqg6StH_rNP({JOCKF}_s!vu!sZN_DZc4y(WmDTZ93KYDsWq~_a;FbmX)&iU`$+QHxvLhLGHcH$vF?AT{!vc7f7;Z}w%csmVu;EoGAV@u@jN(XL50Z}`p9$u_!^-_|2OM&i@4)QGp)|XA}l!Wr6 zbD0KiRnR@wfm;=GeE7X|xl!O|F59$Bm4W=(xs0%ifm!*H}Ln0`5& zl?@1hZ*4Vs`(*)FBN?_OM;?Lp%Op!}$sSkGh{6pTu(eT8T`#!mBLS~N;-6;%>bICV z5s+(DZFQRjH|&tyyWZsOs{-0SB6-InlCA$_vg{w>ul~d2EL$?8Q&P4ice*AcTi`X> zfJ)rv_~%>ObwK?zNyY8Cv?3Y(kR%1nuq6jPK_O>yhFxHuEs21Kx;r>O6VPr;Mu0(A zFw2(c@$ysgI?AY@-7!~i)D18Z zKG`BOfR1l|oq{XyZOImMJ*$E&9k%2it;$^CPN?PI{CT?HUQLcURp7?bACcG8(uRf0 zh_q>tHlxDjgm9_E>l}}N&s#Qc!gO!tO^IR@-= z1%p2kWZoHY^a{yW{vUg99w*0DpL>71d!|Ms9gU=tM=qB~W6Nq=vb;&|V|l^Gw(MX7 zo`w*%5J(`<>5d@~V&~1meea;j@{$F(xi@c^W|RQg2{?e-0s}@i25(R$$&1F8)Y@8d zP05m4(&)@qGt+(lIMvlXl57k%-qgR(r$5zo`qZgYr%s)&I!`^%lebthpvTew82B;= z9l;Zh;Qz}cIXk7;#v9nlqa5Y0n8jby#*bOVTX>dl(g@6IP`(D(g9c(N;d;$q_IUFe zd=15k<96e?tDmRl%@}W+V{bE>(Ht{s_(n5c|Iq|yoAH{CMnG1xFPb+n&lP_5Fv6XU zaN1ut$7JP)A^)?_xsq)N=cRuWv8!uwG)Z#woBI&Yx&H+e2d+RkWvu+plYZ9#;nN6r z@)YN7C4O!t!r4VKvjyP{1ETIb8|6C_*o=|_;i!gvpG|S#9V9dVjc}epr52;)Vtn2} zGV{+7C=0OF5%gw~Y;^>J-KPX)Yf&8d5CF-{mm2nU9!j2v$b1p2|DKaT+4_0=HcBoH z>-`q|+*?Ry{w@M)>&MiCk{4)pt+V}So)6({!|MMQ!rd07B{P3{iu17?Kl?V4Cjhhc z{l0@OxnINTzl;6(|EBoiH=*Q3c-!|Q@BT5ueFAZc$uZ$PPBQaH2Q?jL07+=sANJw`H< zX(%HV*2jH8{dm($IFXqDs)f5%;5;cJKsNIi$r+&Rz@0@hf1AYF)-Z`&6r_?3VCzjj z`5#!U`qP#5w2&#A`IltmCo8)YvP*-$&VGTk6^V3_>+kt?3ukT;IjKlZDO?0O<+EzO9%}~X6v<;T&{l*p^mkY|2%M@Q zYd}`{60G|0oCykU>$${7kRSnz6NsJeNvNxT$@j3B+0;>qF&A|(m!G$D~e2zWOK)s z==c5!OEYZ~ic~^r(6*{QV^dY#rc^APiXbzdoUwG{_5TAIewT4Yw#6qEdd@l_Xq>9l z^X8{5h{38#2;5eay4|Z55`DfUA%I&|3{a%M+Rz4ZA}?B~zcZGtYJm2Sm!HMc`*-r| zN49f*OdpRMuLHWWs>rm4fNfg{hE8ihJv-@ZkTxzD7%kEtf~|6TCSdE#PDbf9KUq1Y z7#JvKLOM^HiM+wuFbF|V)78k7B|oXO33s7S$}UMYDQafz2&~|K}q` z=6_VN%Mt8y1Z#3W8~ZIZ#j=aTuM{#}#0N23lp?-_$7cjovvUv+X%_J%Rg7;jt=Z%-zGN5tXt(ASMvG>G0 zr|t9f65545&o~tB#gcE_XdxgV~toqx!cS^>3pZ5KAS-1}+FQL@;NtC<<;XZ-kJ&WNTpq#ErPM^#?HazV!Y~{a%S@;fS z;X43q4dsUe`%F4I1j`Q`V&CuFz&(%6=aJq$4Q-I3IPgWv=^ljZVt7L@`!(l1Yt)(% z0QV_@yg<=&O_{>OChj(Y6EbBt|1aHt8vSGe)@6#gy9C}*?Ir6SGl-$tvfi;!((zqI z-2H<5BjMz>tr$obaXmp{n~6O;z#Gx>#kL4=4+y*wgY1Pq`KPQI(#6^HedIz#@8jLL zO;GlEW5tS#n3$OOxug`E(To=}aaEJx?Ce~`x#uondU_hu)Dx2LZ=L3biDNuets|9k zQsE^GvSU8!psc~zRxKmkGhRkcs=5qpn;C&za!P6NZd{NaF0)Fk#6{pD7#J@iM-n$&S2Ftx<+l&CMKv@~*|qUBp_-m`)&@)}eO@#8sEe)QsEjkVAvc@&<*`DdT+_2LkB01yQwy|)V zo~g3#v(t)LOs5qL?IT-gGwc4d34_#>io9os;s!kvWp2v(?0*-utq$1#E?ATEIqDhw z^*<&#`)jaLDyoa?P{1xnu)q%3?FjO7EH1je%!1!jJbpl6*a3ST!SYhTXqRS^Z7P^- z*kJKkC_CJ?I^fDl#pq%UOq4=URdvBbn@!4B!?}N1W?op<6<-TDd==c6w^(2YY-$l) z`)5A;;|BBXfV+CTG3|hbkHXXaCO_R|GS3c}ZwDty8N*C~HV!=@a>Nykc?RB# zkU4(2{5?-K_MRxidAj-~`Z9~Zx&f4}$r8^3YhyoZxvYb+F*HaU0=I!}*ZpN%t6@*9 zv12RY_nM5c{v

    !SD`ac+cYJZo}{no%F2qa>OrF#`qJ18@R#G5d(f`^>fVdC<&J@ zZr*~}a0mRMmJ_Z5JIwX?b6u`U{5IwLZ(vSf>vSv6*#~-fa_twR=MQ=31~z{x&&2j? zxcG|u=~(u4b_^e)RY_v#_oiq#152eMc>25CR`@L0OMK?PZy`Uh-xEH2%>^p#PJe(e zhpI%e7(8AuInxgK_&|}}KNehYnPS;&pG{mtHUC4d$@*NA^V#PLhCPE8`4kJ~|6~~t z;_+?{aVPVsaEX(rWWO~$%JGK2F$x?7hQp5nJV0UfgK%S~#dWuI>G`L{Ge^^}_SHD& z+>|nI#w#}-G<{}Y-_evZZpLdm8d-|XH^*LB2&bK7rVHV;vvZ(`l8U97B*GD=!Ld(Z z^$#Q5;3X+<#fpo7pP!+4y*)vh{tQl-s04x6!g!>GBb}qs>9=6Fo&dtr6As@VD^Bn*r zGyjEfe)e_M$dsLVT<73tZw$SVK)Ab3V%}Q$@8R<%gu4^rY{ts(KZz}?>$x2zlP_$t zB>NWp+*`5wH(=$z{k(at{5Q3St@HGA^qHry_!`357MA_1+T+R56Jk$Wb1C-zw*EuC z{vJ9y=F!!)m=!JaSl{qwn{b}M>i>7muyvkjXuCgrj$`*>*^?hmJEF8p=cS_;3Xn<6F9R3&SVnVrf?>O z_Pb3ea$`Q3Hl0o!XoJm%x8SskP}W#6&{3rSfJLrVGZb@yPk*~bE}>bQ&bZLhywe&S z&bL~m+7!;XAUEx66~qu6=$~uhjMtf+1BZ&_#mOw$nq+Y_j?eO8+#=iN16G|O+sKq1 zv&gmitU9)m%?q~Z0(os8001BWNklJaVibtItr(%%WwTdEDRdjVN<^Ta_?t6+=CpKQ#wg9VQx*s^LTDllCqgPfG zsd#uE5}|}}OUNKj%xwD_12{FUNQIuXwQc0IiX@AjMBTHtmM;|owfVNNKi8Pz;mZe% z`#3Fv)TCmMBba}csvUy9&OWC2^N(#|w<9uS zi4R&l4wSEkKl*TyA7F7y*5|u<{bGc01bYzd{U^bP2a4R3^O*vQj%Lg5Old&30-Prm z3%;c23W3=*IejgBuis*0-eOJGXSX9bFQu6GQN^!*w8+MOiy!ALeq9zLvSN(7lyXfk zXdK-YFU|U#Ar+H=%=)Z%l5EXeYz^eQc*#JvODt@ z%d$Ri7$~x>U$^tN5WG3+3KD2v+9NOGnd_yHFn%%dd@`I@U3JZjJg;jB&Kk+Jjk;fK zyI%Tl&FQrEu=CXYZs!z(uT zGC26;OHx*iAq#N5pN-OgX!Xxv$`<-9&bs?f2%GaCSB4|6BiOmFm(DQX-L-U<>1QS2 z@nnW+XIWI%R2d$5>IP;hNllw7t{;?`3Yog+$q}}^^~2l^oX@xU6ZvnzBv${I@N*iV z{Y0oZ_oX0Uf%Thi|oC?qIaeR3> zGePSp8!_y$1Ptl-e`*GTgzpqI9A8X3VHlrEM_@zgaG24vS zOmuZEj$}Q47E7@iCx_u_Hiic*05!go{28I`e`+edhwyZveZc1z4iZOI7V%;iv z4#k1rBCzKnoIRN9H)9qyouWQRFbht&Y{T%%;j#V-N-jmXyTbKbDfRtESkIsFrfdw# z>8r5v-^TFD7~WxoyB)Le&~sc5hw!tvoy4Zq`%P2o`*675ZTPu&pyY+&`qLQR!SFnN zo$BuWGgt-79@)xS-+PD^D=wy^ql1M{?!fR4u=j&+L&=K}?pBHee?h75_ahdqZo5k< z_1%Gzmm=IJqJt9dV;J56y1Eu~!%~A^nR`Ej-`aq+S7KMj3Q$!{e10O5m76pZ$n8+mx@2F-05d(L3$YOn? zPvLQs`~%humaIK5z}+u!LqFM`3(81aQP^(c9oGz5Z^Ve?i$O~l%T7gMuSsEVow2g{ z&0BEGTDrK#lwG^5ggq<3ZGy8=)I2?R?ksZf;K62tG~*TNe8UbuL<49AO!9F{vrDUj+)+K2dohFFYPX)y4;i-U(K5a9Ze(0hh?&?%KzgjKm&0ZH z=UU_^E!?UgAGcU{RR4F%X+>{KH*$`mP%)7$3U^8~S-pyZ9S`s-hEAW>tkS}y87%<{ zljcmOY{;PXDn@;MN{|oqvD6r?sh045DMbH<&}r#J89N@(*IJ@5ZL+qtgj*4$6J^|r zU(Wf?3h?%%Cfg96)vu-S8%vJ-^)iOgd zgPv-g@mfe|W^HX5i-8l@jN00EvZBaM`wYcG7I%voF=X8kd@Zz^(Kd2QGh}-v%Q}Cn z8Rd0bG&4LEN+7!}f(^$8aa#mEA$uIOyzzsZO>WKk9Q%7g`|2P9G65FY0TV#09dM={ zFb8P$40d=1tI}m!RtLPH22KLP4)Edz4{tUx?SLO|Ho2mw%&+8p&igxE?n9eRZh26# zv)kaPXK=n$>~;jDPnj&gz0B;@0ZXK!BV^^atq%C7Op?oc%52PAB=-kg_`90vyW7#% z;iiJgZdY*BGgy=Jk?ArI_FLTYsN&FSz26wnLH&J&ntSJLJBVP8NzdTv6WFW=UBTXh z$%P>(T=UC4Q!0M&))ics^Vz@Nr0nXt%(er%(`6P)EqA;lZ!zW>6!X@Le*VzF*sI4n z;6!HE@bIyS)wOi#`7>BuwfwJ#D5lrxPGF!Jvo*=$S=2$<5Rety9E`F@&}r-6W&uW3 zd&@?m+ch82nr!V@m=++Mt&y6Ll1uS(w;{Ra)G>` zh4vnfJ^67awqL_FpI*!28-B>MyAE+^-#du`i*C4|p*`mUa3rvqpUe<9Jns0twVZkR z#oT?%CwTHcg_4&76)t5X`|MSG`lp}c{``L4lJ&VI=d;5R>~RIFq~e|FGRMc@*nf}k z%*VeODI)c(E3!UsaV(r~8Clm!nRjEdk3+0xf-19lgfXsY=mV2zKJQpKYK;Sj&>-#c zaKzn(a4V;U`dO|2HJ?2=>E5?C_s}^0c6Kg0N!8%>GzP!i(bm>RN5{No|7*r8cCXdd zwYb^;UZ>H>m~8^H&3H{r$kk+HckV2{WDf?XYZ#t^SumrU`PZ|oabU;ra|sNuig2qh zy8k`4V2FqRQV`e%X5r|II0xf^mNl+@uZ3_AV|Ziu*%pfH+JFlvr@K*dK4xKmnCAe( z^)U-O!}2Dv@&`gW<1;b5k*GW+=TPpsgi_!2;kH8|?JXEX!x&zDLcH8_3FY)97~V02TMFx;0a`2nL#+J$r<5_Sg`d3wSt0xc#H+&r>S0UWZQQFHD-XR0;kRDUyvT$-Z zlrGNR>PNE0PEjD2Cu%NMQa`{p-p!96O-m#iizd%~nh zXXhez?kqN6h-$_wau0YaQ1--Ft4cVdll*JY!v6jH`1J$ZIIlHMcGTxb@@94{wE13# z&6@TEPmhdiP^%hfR&A?h?8RcR;rJl=Sr%@K&=R**4S@Acm7o>U9c40=B=($u+^`Q* zL<~h{fjt&bm@-LEm-U?LEX@urw3w_ND{0TrR`B8mo-m*S>1r8!Dxhz&gqskg7ijP` z*Wx29igbG!ron49V7C5`O1G4;#{=v{fMW>k*#Yb0Cb?-JFEB_?>*I4~3*4%}o2$W7 z+t5DTsnW3t|fGFZliTZL*xSXv4;B;#_k|wre z`V)bpA=pY43R9+*D4q^M-{}wpZdk5uDQUpfDB@N$;0mzLC`KS}44|sP-omtrQx&)s zfmbzf5gP0a<%uJi;#g^hj;>EAYaELa$s60%fI>opuQgfYMvvK8 zj5+`tzCci8%f`@sw6;y5)kIF!S+eJxDw6F@ zgr6E8YmOaY*a1^^K(`$*iUwjwfTtY6#5WAy{oVk#Mew0Bd{%$S=ZI%;bIxZ1EyrwE z11`1{?fc>S@0K`ED(>yKh=0RiXScysf3CMV;u&1|wSc{!GKm47-05R{MzO#S*g7O= z`H;Yg3*L3PAAz(-JcHpc2>$hp-Nb;Kaz4YWL&&RNkdOh>)NMWkGkOv!&v~oKF?lp0^nF49@8(b56R3Jn44^Ncfd_JJywRkV#U!6r+vd)+l;e}EIX%k_3$f7lldZ?9Q{@G~x;ufg;h6WAa zCmX(NfX-b15K1m3uos}cW|MUH{`)KNA3QHQzrRQ=7<| z8$Qy{Vk?QU{TjBL>v63-u9ervZ+Ki+T*sWiCI)Yqk3=Kh{@iJ>9R3UKFLpJ#O9yUZVhH_rYM$G-n0LH=I++=qY| z`|L}ADfWMQJ%;xzx8{7D^(ITVK<-wbE3Q=h#h-Q4dZVJUG~he-?fAL(a;3eCx67xw zzhH9AGdM>oZcA_A2%lqu3j5LCw=4NNdwE;K`JV{;!x-9Eb{GxL9z_GTM}hrx_jaBp z_kb_1|D6ueIR4ha+C~ZF6JM5TN+7@RXacj%X!gHm{Ia46%r@gSGa1+Pk^Ln3!9=(vgj+g^O)K2J1a=38H;j_! zFu394QTmL&ms^99OR)0yg~xLQ;qJsNI0$D~m{tbvqnthmD}QP!>f*rdl+#yW7JeEY z$0&mvc81^IiIV4^@(pvd@NmeeefWfSI3M9`k3iXaJ6w&D%T5Auivxd5Iel%&q&-y6 zpME0~6BCSY+sW8>eh9z?|8Wn?{b4RUI*wV`$Qf#aBX{0_a0c1xijYBj06+U4itGNG za{6YjPdrQJ*B;^V$9Cg9*vdDDZotWX3MDV&x4ge&rBoE06=54c*1($8fNag9_T`Rj zk58`0r}xX*{nnVfa>K;%VR1HEcMSKoMv%$%h5nyqNCcI}8}c&3dqnRrrz zoe1QlWu}q#57>*Rs>EZZ2xe52tzY(L;u&>_gt%wTNU)6*{dlOE}GF; zz{JC#fQd`!dmF3QO`_Mz?FomIWfvH&s;;>$O&1tXgNw z*4VE$0Yfo^?6i+v4T1Q$&_1+raWeb0L8`bf(4hT>vB5f!+p59cnh$Nwdo~8xm4IBJ z{bcQ`X0y7jx-JDn1BP?12#5m@LhF-K6-d^VNbeWC)7MG{X z9Ptb)?+BRpF~x(Mv`4L74Y;nP==i9@jSDvBEjHY(LFe6$;HI3<8&YM)&W7QB!N26Y zxhe#O=Skfj_xD>2IRaZM&5#X`ZQL`MV+XX^0jqL87w3EqxPp;}7gi6sf-|K;*a5rN zYcE;x(Z zXGf$c^m4|F^)|k|+{1^9>!S7D!eL1$XS_$$EmuCaMZc&!H?RTlgo79Ut_+Xsivtl; z_9?5M*-CQo`|o2`n17$uPpgvb{mGrgfpc%TpSf553E%$10x{s?H{Q>Vz2`<}pf(09 zzUog{wL8Ea6nyTPTPWIBVC9xjvQy#7p1|t=Pt3wbeLU$hH>b+jMQ{!aykUdF{U%3; z40gMMr_;ZQk{5G>e41N%gn#Jm24G=NnPpOOFP~tXE@HqaDLU9synlD7%v1wr1L`2` z1aJfmB`aVb!kPM+FD$=)?gN`1pT9^n{c2yDXaZx+c%`r7rAyCmT1dT4qvpI> zZQaM|QmNRIONZ@IIN>~f6Q8%w@T*mF8Oh9_pOEjr7?u~Z@w(+$`EStGwU|wx{eAAH ziyIEip{r{!@`ce}MpFpqDb9F$Ba^Fk0^zmlJkG7o7w|LR;44^sB@Y%~L7gC3>}NlK zaJIZ+*PpwsKBi=E)f2P%d#uO~x5kvstV>3qY_x4jugfk)s!Nf7#3J*xy4UbPPmxR^ zN!~rRJfL$xXi(&!AoD;H=b#{)4C_#|Sar|Jdfm?Pk@FOp$CD8#E9WZYT-9jZds@bd z6&Eo)Jp8JXPi)5NbuairL0N$8sE?dfWacFSEAo$(p~viJ4{X9YDEN$F;p{oin%QxB zj4{;wGuVFZoA~_jF}j9_S$=posiSq3fy`_@_N1n?KP+?6KDD8TD`Sv5?&G!#+;%~K z#Uej#kv-~@8}aF%2w98M7Vd0CYD|N!vZDQIGc8F{EsE5HLLOCQ=lB|IovWF+O!{PF zXlCau=&$JVq)_C1A15v%zeA@j^k^Md`AzKtqpn=*5%_H=%t)fBP zguK?N-*UQ=`5iVQMkipTb;A{VAac;k2P0nXgRf}xiobyQlizeXUm5_0g+?3U2 z?{x%ArQ*E5gC*$evHVfk(=SL$MHTHS8v|~6P|@$`V_1{(AqN}#EslLbFt0_i=60Vo zp_K7%M}xGrxGCpjrrCOWpG1wn18B3I8EP;+V4$4?2K zY$*GnBN)tE9CQSoQn7-%+hZ$maaIGm7w7!Q)Anb@BB|(1DYib3)NxnW;**|3UaQgQ zl~^0&YoJTbs_50~ljvWS)t$ruOzN`5HLqF1&JeGE7mqopRZ@4X*)?<8nzw9?Eju3e zzUhXg{wSG5I7O`dciFP}ufu1F@4u|a{Ze=vuL)&~*Z4X9N9YH8zcup?`|OZK+odGx zw!h`-J2ue&$+|Mt3O~!DFwd;p{+6fr{~OnaKyJzEXVDu!%Xvz&b<_3HHXpk0M*jZB z`=as9dEkcV^wfl;$AK^W?htqXzc=#C8=j_^`@C*v?xPNzgObbfc_+7h^UL&SlDxae zXQ@=|^5FaV`b#1JN#}pCL@M4gP~@|r=kzM6Fr?yZz%zUTfOB~-bNMJwkb_)6UBWn^ z?mHY0m$jFZCx~;L`A+4ux)*GM5-zpor@KG`sT8G;DJLDs=%?{%(@aXBz7CHvHV%u=>A+mH*ZW_5D?pypT(! z;zs9Ra5g@S7`}+g#)qL}9xGN{Oj}zU-Jky|ZEbDr82D!%1nxTjPqCc;(#Iwh|4a6A z+vcyb#StVkpF+t?DGvOVo)F0V5nA%>GL*awEC0{0$o1!J7dYEbe&Itd(Ua58ZZQLt z9e95cXRjdtqxyK1>QczXiu@xW&kDC25@ZTV953ANO+_4Ekbk_so$OQ$ys^ltyH?^H z)cM@9AZ0d8_Rmu|#{~Jk7Vf-y`oOXx&T&CzTk^F1PpFN9uT_>#GhQEk@aF+#<)k7v z?vt52^SYH&Dgv%D?Ma-3h@@dRj#d~Rp2Ru27y0y7ZaDi)Qd5c@U5il{UCzeQX@-Y~ zxuLw9Y*|a^X67bw#x#pDJL2nk)Opa~X~8642LM5l~CaVql^e0kV0+B0K4`YPPP=s=0bu^OTiSD*9eq&$R1uYu7+_!pBXBh!wk` z-=Zf36ywyvS;FtN=TNc@HzGmg4PcTzI&BmP0lBlgCF!;$S=Ux zHd(yua-Su?tEIjjP6lYpj^MB(xFW2>K}T?1&gUrbV82DDRGcO2?NsxgjiF_W{Saii zEURBWc&wp(E2Y`82OYr~Qn4ufRQoOBz+itp@4Gi|;l50ggU-pnl}R&cqQAyzcN>sFm4S$)v)8o(I9P{I%Bp4)M}~o%&LZu7ZvK@ zY@=*34eO24#ucpmJ>k9m7kFWC|4aX0{PRo(|HYQg{J`qh|FKq{B}%f<>Sv9gV`G?J zi!1$X^nHH=b2biSLs0hOFi#^4`PPqYVC(w_qOqzLhrazEoCz$K_w&}jSwJmxI~WOFl`i=B2IP*_eo`d0?JfZ66 zdI;=P=!tv0-o``21a=2z;i)KHxce{*PtNe8RdO+NganwYO1DUkdD{xUS|+ zyC-bREg0U>@H`&DEVu;ryeO?+ufqiP6vog>N^5_Oz+N!J*S6dvDW_#9lf3JB`pS`T z|My@P9>pv?64rYuN1PF!a0O2nCh)Uw#?QSOW9TTwfjc5;<3`D2C6{Z~ZT?#`()Dp^ zuiE$WEzZkz;bxx1Ec`H%8@j*ugY3Na5-$1g2RQcFR#vRInC-uQ3wuBGHk7;wvv5DY zXYl2`#h`q1Sms6yPcx*2^EhVV-e^6Ux#JbR1_wS`Wax+ydCCH;eP;=Io}#eH#5-yr z&rx{C42F&w6dn(~W8YPbyku*BvTJWBL5xVcxEA)DAd)W5Ug#q`6@|Sf`KLnWm#Nrr z{UC*BObXA`{od9tD`C$HaE}SR2?IG-;RObETR`5^+h#j8+sB(UPMdMF28iw4S!~KS zHRBcSgFg$Dm6HlDp|4FZVc@n1oK`I-JTP3uZPn{;LTHc6N`PGn7#Jx=-kWwsOT2DS zgY=KL;fzf3Uq=Hf`*!k%mMPvB9OT{=*KwfxLjK+8WX)3LXK$WVnj7HIId zEzH|i(muPbWi4eK${^eEfPA3azA$A*Ub8ic;-RXRCvNnmO}CV>V*!1wTJCtDRo}Bn zl$J}52e?&1p&I(jhTm&a$2LJ!ri`gbvUmtXvskMz6xWi`E?Odaq~i>xmR?GH^8>mL zRqfZCtNM|Qu~YMyjcK`JH?G0dnwM>=qS>-TF@v6IEq7a!Hg@B>UwUx^S$r`Vn zs>>Vq8r^s?Ba)>aiW%6Ifb>+EbX7|=dohD-;FE8&v~O`-UkkMt5c$r z?(W$m^~QqlYtej(bpyq&p$)o04m;18T4slE)W^7OoC35zJpH)vsp{;BF<_EhQ*@q^ zABdPote)YQ{RnXDAF5|>ZQ^G8(+#(Zkt63{EPf(I_?nP4eJV$D&S7`^CvT{{OoW)$ zg3kK%CaOn3*Tu6prjc;I1s%?c{Ks3Xb&t5ZH3O7 z9OJp+Q27_5GzY{;Vg0t2+7ks#!m5-Z#9>&5DM}tf!}r1S_IpZ=Pb_>fUcDEn0W>tP zZ&j*7TQyi@#6rO|QofhpdCuse)qrm^_|>O?i)sLg<6RfX{=!xW|MqHxy2ro`wMs$V zD8JV0J-%nU-sX2YUHue3emKmn)7@AWySpkuTGht9h2>iwdSdk!QF=EbM3~BTzT9wd zECjmh=-gtRhAO1)Tz<>GO8toDz>P)0C+dln5wD%Uin9T*@jTWF_`yz3$}ifTG~u#J zNzP>KM+}dv_W~hI)X>FIyCiISFY~I$hA?WQnx#{*6e+|);Hog zd82P~VrroscXDeyt#?C(dn}T%U4(v;scB)tB7!Mm?8c-q=We7SmThwybh^;&NxW9!rXr!bx<7xdzFxVU{= zK921wGTasddqNr9J+>wyaF5vcXQfDznK3!W@F3m(eeRY@Lf`(qW_B;2zNV(;Ui6Y% zX131LinlZ_=i-nAE64x*nnWo9X4P5c)SAw&^al!s=3)e7ZGDAW8?Y>`mIZEcETP*6 zRqF}z0ZIg2a06-yHh**ry70e;Q^;6=9&$hrGW|01HQPLaMQ!(+o5ua(ozG$VL+1?V zZp7~vul}B{ivJ3Pl8_a3+$ItHkSf}tg&SfdI+E4bn@wRa6Mj-Lz4@_eUMh<(ci5`$ zB}W^XYyKO}fnET)#lqbPeau=%JF~+dgi29auJadKC%KJdq7n9R0S6N=6l@%F z?_X%JR5aPE9M+Yhnb&Lef|b%2Yze&?MLmSuM9FNj3YRgY7FPI;kP6sSFS;Kwr5}-? zrB4OwgyoVDOWNJgrcCXnnakhn0Poll79j?^S%dGtY4R9>U$^&>EgOgZ&A4y|YPIMi z-pT9$;IkLNB-j)j4R)Jj!Zzdryl$Q)U(b$DN2K^gHdAoN;I(KXcSo+f;d$Fp&@Q>a z8{K=mR>?rHg|dT8706C11ZO9?QYfPv+qTbByn_)PXY@~o_<4gE)6i@qmvH`EjV(q8 zt%Om_UEfR{GOQYvz0F)i*^%+%mU(Ao8^Of&m6}7=0mw)*GR(FU)n9|TlljM_u4vaU zE9jp)DX>==r8*&ta4&O2?aTUCIRz1wP=R4dh@B)i+G0&GnjpbaYzhe>5! z?|9+tiFEHwQ!qKV{uRM{F5X_dVLk+aKH+`upCgU-YO*_WP{cS%iT?QF1%e1wB2Ux0 zgJ-&m>C(Ut)SYrxho&?3xo0aZBAl&|n<&aEvXZUrYdeBO``_Y?mAaul4qA`k_f-sB zyl#3wNk{#o-#Ka3(}+ju@U{AB#q{+t>IwQ#5aaudL;b${R>4QR_G;n_urG3oRm=h` zG2cA3QC`o?LSoK%$y|Vv!>)j3r|a}nbW(Kz$PBO{BXYq zI=&LKGiiV3Q9?n?q}7*xW|?vtn~ zlc*<@oeU_UULC^zEg)E{z^>no$mivdrB5Gcu|4uqvu7NX^6wlfRr5dPP|i4^v!=$N z&raw@H=Ag$gO>gKx4>B-?OJgM0WqmtHFR*V2 zCsG(Tl~Z5DD2vhF%^`%q|9*@oTLNWd%);BR2`l^d!$&Fp0`xX#~wASrb z?3f?j=dj87?)&Ui;{)l_qyoGrFnE)4;|2Y_i}ORmwVT1&0#kY2c0^agxBH$abg@zH z%hx+NmK$WSyLpdnxCo-bf?B5d!f@tij^v}1l3R5Otz-)V;I3!d(dKDEUnX4RBas4@wV}Z^I`p;30ubUrsf)z^&z-hxE^^V@g$Ak)q+beYfhh($Gteg_!*&w8$0NnYLPEB-s(gqS5+p zN7x^8SP^r0Viq$M9-?UC;$nZ*(@I*m=)XA)H@{1os-U+zhV;V=3YeQ)6}y>aaTYOL zkKz6%@j`r$uAI;bgl1;X3Trl}hZhDUwuIby=j<^?}6L@c#Wfh4gRc$0QLi@>C+;ak03zZ`mkkhcjdE3C$S9Qt6-$&a@UyLnz9MJgkmLlVdf9p2wBxuG=9+ zt@y!B;jNXhy0DF-R4eV#sz1G_?m|d*_9jj>(>ID~Nm^{NaQjJanAJK|x7lcA=DK1x zPaA*Z^dm~RHaxwE#(UaP{7Pq`ZC@I#AUZ>>z#tB0g?1tJY9aDo@cK&U?3gM z0+~9W+op{@Dri~*v1?y`@Lgr*UFE0U6U1=sl#Vk<<~26!_Z+hpx>it2j?(7USQ0$J z<;b%8pghLyag5?3E{eH>VLt`))A}S09WmT@*`G+?F^oTfldvG^H97ERm`pGPSHvV( zlLDisfaqcKls%K@$(jS+Ba?jPvxOpO23X<8WgWkV6Yu+_f*I`Mwcc(%OOe!cCc7+ab<5fDl*eg9c`jdTQMF|>47G(hNmog7%)0f;s5{j@? zl~^HJJv3eY=C7TE+NQ(iYs2l{Z&!ocytDF-U?fSS5DQnpd%38el5BG_nDq8ugg!}> z=qHLpq_R^Vf8>2w^~oBY@J^n{=@h_Y*xR9J1h0<^af}usF}SA7am$Iy>Glai%wcM* zqmU|TyHM$dHonnAqzqa_gCI%1_Qz*eP!%}}y#m<5@mZu?MWD+5ELMNKynEf*;*ht< zQJP?>Y63R!siNs@*qqb%(ic)Uf8pH*yaC!?sH!T`I3SsD*or3%!N3VdNi@qqDS~Z> zl=pfY9FLLSYF?R8KXC!^zMTasi(TVaiDQhboj}uE1#17WzE{DiF?*GB&@cZL11cKi z~Q_3_%Z~JB2lkUE2`P0(%GxJV(w)=-*fZRbRfyP>bvqU~`{C#~SOx2o@IBi7&5nqg^P>v#Tgi zo_wSm+&uQXhf&pYE!q8UDF;G%3ghYh_wSzsmNd#>GlEST>X@(ZZx%k@o-Fs`do6eC z!zxvNrfOLr;O*Kw)gr^cpJ1TRu)U@;MsCzk7Zj%Ap{Kl26Iv*Ph=d55iR#|g zZ`Vk%AN3W=7M^TF`tvZRWr6z4@y~$%r%8-6!X%$0m->kFZ#HSnv~GOuR|ZwtL~C+k zUhh_Y&?e7NB)zmX)*dx%(iEikNXO`$L~C2e!~+vKdl+9{q=iL;!TlonNGp2}Mg#Rd zsh{Z{t_SF*=D!*$KusS7&=_SLicOZtmi)i8;<)y;#u4N{NS$d-%;% z9SaU98xInXNd5l#SstJR@|Q^gLO7&SVKQ|y_WA&aMcC6NVcuxR6U23g&>~-beNmjZu&_eH>ia0$VY~2_yyzE zg@YMU14>M567RHdoRw88?cnzyeePCnc;bX_2iEbD2M_#rKp_USqyDgb9YL959PbZa zpg(U%3C}_RBzqfvMubsOs%YHQSh1P;*?q43*pb@*Ruj6{n){W;(d<@OoF{l0A0&~o z$v3*__oiHG_+SRyfnD8h;lc$UlX2zUobv2ON|jf0Rb;LL7Q)78>^eT1)AL=XbifC+ zIerPH);Ba4&SmHkADF}}EvZq6iA8iO?=>#^gu6oeDS&-oibT_lWZ#;10)`Q&+-Imy zGWH@6^5hVegMXJDk@EW@JVK(BkEk&|>N$JKlLsVeDo$YL!9rA5pavbyQmhuNvESh< zU1PgpYPGW}CR}7l@3WE#W~*bU;N|ViR@EMeMJlfXtt_?of+{lj z=Zmiy4NO!A?10Q=jiJNTJMeRT!SA_-L%S?xC6&#rtY}U*%(psrWadD*Nf0PE0xvrY zqo-&uNtc2#eUO36VoEwQKFZ5+b)XB&+UIcMqZM8Mkm}fK#3xiXEtobLS-4D)+(5UC z9HLGMQcL_>5fC9HKt|yt4yzfV5kILelG(wdL1`D1qP1+v|C8QMj~dkipob#>k%Sy7 z1=-JA3iqH4Xg2^c9cr=%4(4FwX-mq8+&mD1S0=NPt|AtmJMP zD)#1Db0(s$dgx|O_yTqvt=R8M@urhv<#Eh;{_^Q zj;~|ft-^OB1%JGYXj32fkvZ-{M79pr^s&9&HT9S!G_g~wpc+>XT{LNpzW&uaj!HL* zg8Cschmskj;9qgAe=!*hEfug$fbV9Lt9j`dwy!1|^G*H`j9145TKI)1rI&C}t0NCd zG-0WdHZ*n*RoA)d)0m{tw*^Y)tt);HG3;=XBa*ArYyl=WcHjJv2r#hi@S&%;Q~u<5 zAbVRG0Y=i5o6XlPeq+(0i)kkk$OJg25=Q zmXskTi5H%2ML#`eYiGY(YeCOXza)x|<2i`FV>{g&bYF}sF`EF&O+K3HruH}J zI<%dojs`#gQ-XsG5WsnSrIXjvgpyQQbdPWGEzF0&w&s)f>|f=eQ_Z(dJoZ{w90Xa0 zHZP*3;0}x!5p(_R@$o&%EcnnRANO(!6_K3Ju+pRY;OGl#X>V%{568?NWoGl$V(@N# z!)N~E@{CGbI*qrurv_%xtZXTlBfg2ybiyUfTi$k_Pd?7lnRPUsto?a<@R)j*vuA{) zHnPpU&)xtG^mVDs9?Hp{uv4byT2o^&H(76Zg^#w3(Ys!C?eANz{oYv2d!vym`$GRZ z^gWrHJo=6=Af$Jp)-FDG@jdws@$WoFu49f5HF>GGFYwPs*GXr)=WtUb;BSPqzIovIhs)Gqr8=Zus250oQPNvW!kkKZ1So|JM$1Eu zHC=8_Fs)KvI31-<>=wx9aE)-v`$8 zP)l;zDLEMHJ8)24j_}Rh=p(dmwr$$gr)0*2yHs&VP7i-gzEPyTk+FnVa?kSM*&@P7 z-~F7iWybd+K5|oZWm8v`f6Q|WjCV>P={>V`#n3=<{SNKR`w4z+wz<2uF9dZOdU*PL z(e(7yNIm*6Wa4j#gW(AF%@z{EWmKEf_Hj|%gKY=^M%VDA8#De71zL&e?B_gW0WD)R z*L*ktx}u1N&rlT4)gX%TUJwEEpdI&0G;qTjE3?#6x0`2ROujVpL|xURT0i(V`1GBT z6emOKXTHg}cw-|&)k^!xTo_Pc%|VIDcZY9&in~ zw2KaAWC1~)ZQ^#u7ULIL+Dz+foXKAoJMw-MPj6bdv%=>qS*NyphJ9;)PK%4kQ#<-w zxNY%|SD$}0KuNRy;11jjjz$89UN7Rd0sCc(b+OJHLW0{3ex}!0@LgUfni=jc<7!LU z6c*ZRmFYDXE~R7;#7%-C9d0Hw>iMKTSxtUTYj#qu_bO7n?TKErVApCkdZV7QiIBFA z?_Lm`ABg{3OTz?$Na2cl_NXv=PaPp*pG>WrDtd+`>?J#=i))eML+yonG+{GZZ_hSL zd7sz}ZodX9eA`qOY}Ybh)i|eq3Nly0GC+|rY8Z;UlejtF^TuXb)4*Odm7}8M6Fg;! z-ANdjxl&u+Xl2a27e&{H5q9<>s`#&8Iyh5U!+FA9ZK(5l~h@I+pcz8o5E0{R2}DbVI8DM z#C^p}5SOC!^QTgff&G+2-Uy+z6-UIg%Eh%R&aan;TZ>o!K-G=4lme5Db24LIB8S$?HtoLKFp?e|C9RQ^yy9<7*nWb7A#RZ99K z6i?0y(;T(hcq4246TY`q_&c>AbTHvIK!B~ATw^uhoKvum9l9bLoHi%e7rA9g`T2_D zZI+z(1*<&0Na$Evp3LsVRKti*yJ7J8_ci?2@o11<$6EHa=LpDgc?5Da`3G0PVR11) za>G&Ek#o8B%$D90yg!v^zx=T~9AqcAhc4Bm$RiAc-?M;8^oMrQABy}%G z-rP%sYBLN;;MbjHc~iEO-VC*0`8^r_{OO+_ijF(9&K8JaGL`K9K$aaCUFafVp^N0N zU@q|~b3OiCnKiWU(AG26KhrliSuEPr*f5-oa4q)y$2&qQ2BrXn&9p@11%kaZ8RnRt zB*?Fv@6c}#|0+RNb5&T+!Vz86lM>Xqm+2)$N>FsRja%N>EBTr?;)A`qt66`Dq}Bj> zP53n5*1k8h$LwY}lxi%}%#kvD#@5ziaO^Il8UXW!DpF_*&8TiK<)KY$H9l=jsO@o} z_!%GALhDX&Q*un|l{Qd} z{oCese`=5DsZh(sTKwfyovZ%HQ?A(;9bXGSi8$Hg-?zQxJtqt4e80tpd1**vq{Z3L z5ZA&)f^S(}Jy2(>OUWHx)ccMpCskwqf(&d1fyV(`5E{@E1X2U6cq&9;0}ZWzW|-Vr zd^b@bdm@^+&hQ~mb7}sr-0_Bn**x|-IB9G-YWpOk);t8riw30SMJdw}*b9&K4evTk zD?FSkJX8uV4(GuqYr%m**o2K^5RzU7h`x*^qAv!Tst<%N)s;tO0%&AZq?adEw{wv$DEIHcoTgTd(Life$r1vg1Ls zjCBmj$Dz9f0wOc9M+;}#;5c2lx5*vN-aS<1N34{iI?{Mm+9&9uam)MgNEnE;2o^S* z@7U-E3f{Mbbo0{c3_`-iNe!8 zv`12#pTHJR-n%}GxuR30Wff*CSH%>tU@x;Grf#KQeV%v4_kHW0GGW@-cuM?c_t46;!gU;d;=;v<&U{M;UzFvM)Hp#x4Sv0CS#lrkIsQS;KKKR)%IGVZBq1Pk9d4Hz}4(coY>D_r~(G3cx+@81>E`6V>ANi>GsA;)% zhE;FAJv|yre}bVB7IqN^iYpLn7>LZ>{%DU}L^E?fd%3Gg)LC|lJo#P>0)b*{^dFZ_ z&i{X%hkZIe?KmrK@q$nOeNk~dc-HTyx3?SVV9?Yk zGYl3j$+_PNsebW3gzDNJ zGxR^9xyvH9jU4~rfO62R#QvSif|ETZ^5*Z8V4>%!9?pV`#QRe$`WAe3ZWw2*?QUkH zO`lA4u=!KsmcE2+(EDH*0b(^p zTfQskpBX-GG#$;;#+InGWp2DbDA+a>V$n)>1V6Qfano}gmYZ3ZHn0C zk=Vb=<6I&dvR+ib>R;cj-m~x=p)htk3uL_9D2zKvR=&obO@=FP1_x~+BTl&qPc;g^ zXku$X#e+F0o#eMsV=K2k{Nb!!823g54B{10X);u4j^@ZePN@jF@7l)4xp( zcn-Cs!Fiv5s4Oa;PtZ5HSi+}@1P~xV^Ce$|vA&%!bp&B8q_@sC?mE3JVd6?bh z20Nu#gG{|h$M#zA_w%gyR&e3lee?N`+inD{T#F5SrS+>`ZK*&i5lZ>2 zte|D-q)bG#!{nrJ?tsW4momI^sr|lKMiN1<7=7h5?~AzU(Rq6?51K^%cT_-aSC%63 z4~NB&Jgz%FBlWkA;z7#wVIkFnGC`!wU$Hkl-`sela*`*F4WA&iXqb4)-0>*|A5{!O zTcv(QyI%sM#GFgUbe*{%l(j?hT7)}_MmnEi+RZ1DkpqW`V-c-XQfpNo)=A5t!-MQ; z0{X|8E>*&GVwR{G=3hVwz=(u&;73NGMl1gQ$^%`Yd6j*Ue!{~&k5memBNd2v*G_{d&3tcwBH^e+2X%UYI z`9}wBGq)3J(`bG7;*_2g4Y%rBk1kTzwFSXFOo(nWj+OKvQFYvWXPWa>VU-rPE>VK7 z%iKnp-w4e6Vf)eJTQ7q`!&-8u3Aw{+dwjPn?yP^;G|ZXjEP+yRL}GCaa*wOl2c*L^CAD` z{Ss_edN17~npX=Ptj5P8XmZ-`%rVlb=;$I`T;T z^7dU8XxlSsQO{VW(xQCJRBozzEPIu+ooutlZ#b9E)5D{gn#w=&cGNkdbLl^}CucLT zB#-Cu=6}?W*RwPWqAC0!unlLo;Y_i@cTUH3i~xJ>mf~Wc5art%x8NT8g~|11QS-?< zx|%6V6K($%3{s{u!$@sC=_`8$#wm-aiT|E9bXN#lnDAjcvuv_LQ3&{9#^*wvL6O->h@x zKn{VSTeN?wW(BHmK&BFrE{qvWmihpu<1*39pzJ`)bk0D!{%ibv71hjQQQF^mk{*BllUE^P(Z7lPJG%n4sF_OI5@PIaQBYAm|uq z>nL@VaidfUre>U2|8XjcB`Mg7Zfi)c;`P(g*f6f;m3oGfc-1Fn#2|Ff`16(2cVA!F zzu)lG)xY9D=B*F>%xI@do_$K1QvzO5`*#GUEikTbO%}H+ufbzw{uG;3pMe5}T2nQ8nNRuZ`XEc5KaJ2e|Hu&VV+wn>^S0U}w@i&+1pxsxNh*Ulti-Au-D;|@Y{0NPebQ_K4ySarMY^e z{XbW+{RTl=S|7%yZ5IJ??wJeBoJaUlpog?7K8Tx=L+o?43`6lZ0onIsmAjyVc_vLQ zsC|H1CH8YQ1ZC~JP-)p@VHqQ`XGZXBr8%3t%-* zIF~)XjY(~6Jzc1ZiukX8PrUmK)2>yj?Dxr>PK9`m~jMDqmYvsus{;GLXjT=o# z%IsIe%Zv6+VVXduov?{*52+fr5=sNOFqh2jHRz~nFwV=)|7-wQ4r{TJsdUl^x7TI~ zcR)M-o=d#^HZv<~luh7*r;+1w?m+IwGj$eO2UD_97m{!@?MG1{9 zYGC@YzdKX~zm|n@b6B`yO>SQ9kJ-vAuvxFp?U6L8GiBG`D59rf*XG+Zc!49iYml*-{iZwJB>!p1#8rfm2_=jIz<)P zqM_OyF@>MPUm_oZ6JS$4z{1lXNP2#+>QI!6oZpP&G!Yr)T|m!2448=8m&Ius&G~zB zVrg~qiC>RfYsRRCUoZLSk_N5{=&96ul}wx^kWsj&IUat}G0DX5*q(;#nkPrQ$NW6x zb%VyfV$5wS+?KvJR^tr(LwbcE<++wkAA#^Dcpa;D+VW!I$n$&=2!dsL$c$>sAin^^k9}Lk0M+d1sWrs5+w?Xs@Cw zJ#aXW1y_PEq#`p3sd`?dB*NOnw|WbnJ|Z9&ti|5@8%y;FjtnevxE&05B3Olu(~?%9 z6Gi0_vExbnL(0GXFyI>?js}?@v3MUoSUgffcFVEw509oMhbe(DdIBfx-ZyH(Lm}Mdb?-ar!nw(e1y1uZZ{a4c(tv5WH*}8!TQ%~IRL-SaH z;TH=}R*fmU0HW0_BP96wN;u4`*L$v?gUw43PWj7VR`f04>cZ`Ywi2nj^bG?RvwIzrd|WY#n#(C6KZ6> zc%}j9?QVVt@>U$U;7s|O6+I_hhW8_CB@F6Rs(TZRshj|=++ zJ0)d%q9nl2VmNb4Q_ z;`FU(c8McUfHmQn`9GTH5y)+c<%I&T<8Hdcpn>{pNYIvJU$Us4+ZXAVY|hE#X7}ho zy-&oC744(IzgSF01RIKn-Wor%7y%!ZNtS87r0?c+@yU_(KnmPUpF2^5#Vp|n5l)2o zsGUKQeHyqd34?2BR;H#!c?)y30#A2-rRs2}w?0&xQ$G`rX$rlS63I6_c!8OaFb}Zp ziP@HH@xw)JxO?Owl3)Sb75H}Ac|*YUX}*4-Y(fs$ug8deyK}M zs5!txI4%Crs7uYDXAk2Ig03ahT{ z-Z5sl?5hO<%@;{JqLKVnedGm8PTAA=u$5FW^Vt|-fxji2=>!?uTlFv$LiOTmLe0mw zHY@Pz7}ODRHM{9P7GRB9&p%zlIIowK2q9?^5nUCUN=}9*mh?otL&DqGE6SE9B5k`2 zR2DJLdD)thZAHhC1XyMOI_5p3h$H_v0R}>fDVs$SY^%?mabM@_qiF>a?A!)r5cEou zYbr>fm%))cy z0^{j@Do9*v=-V{aw8uKGXza~MmZ~b?mXx!RNX2`y1Q=S!B@G-DhGlVRjf;0MYr!A8 ztfYxCbE*;8TSEx)P0~nRb<}p%3)+wZxw)r_J+@3%FoB3cNR!@SwG|nX06Qn)?2SwuT z>Ew8)0b$=?B7Y6k3=1GD-Mk7XW%MS@!lZ(SqkEMun~QRfmlTf z*PlO+-;kq(FLNDRzjX?75!rSmmjp6=GDY}xgMo<{@yr(H6%pYZk=3t_t#W?RZ)>!b z(`mAxOQL#}+xQV~H@t;`@A|zf3PRCex`60sy!~SSgW>@c@Xdd#aktss!rRlzbpIEG zKZnKZVqk~mkpA0BEbm*Ch-ad`?>gp&MxQ7(jTTXk*W3_n4P%>Xi+k#mUQM3^pF}ze zLZbjnUnEMw1+iy075*VO{bFHU?GkGlk-(cHg@1U@EdBm(Yz-4!@P>utJmk%LO3E5v zZ^bupv zw&}<7V~45mIi_OP8(Q<;=7#jgRYlx{>p!2j{u3i^RN<2FZ9AshVc^wt+>r*8?=xya z|87vxTEL2OFgfx(*mm9-@A_ujqk>|l-$3%>TW`Kc2PqK#%E)>xQi$?81eKF6rZlI{ z@X&j<02jK5Iw$S;?ZGqjoxZulc_=pK6(X`$^r|BQn$#*1h=DYR!_laP)&(rOLft~Scz*Wrp)2snn`T+ z=sU~JEluyjc**cCY9WR?1he>Uu1drh&u5DI$JAU0y{cFC$4DYBu#@Dld_pP4Li=0s z*hYpa&2Li3!gRwl=m1xgRR*b0l{20wor}{_7O`Y7O=^@a4GoU9W3=b3tJcTkv!9D~ z2*zmJ7?^AjJuOUjKT5eh>k3s8R(q6MpsMdWsA)ikwY5K6KZy+ap9SZKVzX5|@6V$; zi6)dJs5Dq%Q3eB{eiG(w@0?^d_%+#&ZM1^_7THO_Y8Ge)zw>w95m_?ls`V74CB^a2 zd9x#RSeaOUl;REa#cHkwD@GT|NQ65C#rGkoS6bqGe??2aAfu1qevX@;f0UHso`WUC znp6}^Xl?%BlRq9k);=jM7RuMkm^^V{LeQ^3wd>+OT(t2T82;04QOM2=MUvSz^_(&( zq?vU^sP&-t0w#ywDbfk~!V4(>FFDG)kx!YC*2)-8F^J}&WtScqiHd%5E|=pWkAZZB z!CRVFXX@)-O{{e9zjNfEvlWnE+zCnEZfpgSb$5T5Jp&T8)*R&^2C#^~`nu0;kSSa~ zgFo|+7W>cfd&5`7+jCW}LgA{2*P;AXQB4f>FDJyZIHzoA(ii-xhJB$IUdD~_mWh0o z9kGbzhJAbQ1#>#zjqk(&7H#BS=Fj-N&02l@0-*ev4#5?8!^@YlzH|4pjm0vUj#v`# z))C%Y*UK@)bb6nmG`|LtdgrD*zDFRyTcwD3_EaW#5oKf#=;@B0$(XQlwnF;af5m$e zO>B##`(fS=5~8~`-Q2n>%l67`AZt<>(hL zbbTbR<6~qus&$+iS>P=-SLv5hl%oI(#-oJz3-9XGnl}k7Gl}UBd|Poa3l8gGCiGZ^ z7at-?yqHi)O7pqRjo@{7`dHlW9@$oUaU<2&+rT^Swn+iqwZXWjv}47+#&VHEwJ=TE5nj z3ruTD+cA>)R-hLz(CpCZ*$gr~`Oc%I&jr_nDNtkGTbXM@t~&KzWNMmK)4ro^Ov% zFuh7MYWP{X=;g1ldoML^uZuP{RkV^ub^dY$+2By1V*q%rNMP?Zr=6Uy- zw@KN{`bAIXpoy^3A*-eWQ{=Zo0-umcwiM z{UQJtMpP@6Fp2U~0lls(B!vv@Y?>c+=G1)W9QL{(dh?ca_3&x|B7j44)KmLg#yPO| zS2SO#TwBV=&ZMRH3689$d$hSiVp^lXykziNvU(C?fT2bZf{WdQe!FpQrg!&qm}N)z zzNHquul4wyUi{jc5&L?800F`D)yR&ijMez@*&mH?kXD+lQPryX#y&6FzSKm!Z~zQ2 z$Jt25)%rF$Vb1GES+!nGwuK)*gl^%VCXK!U1_``(K6&0nc>eX`F1H~@Dd^ZlOYaZR zBYL*7yh^VTU#$XdF|SI6B+4-kF<04ecbY#HP9WouKp)N7!)_1 zvW;`q^nL|6gkzh$OPUVLls@n_lHtsC++!@yYR2)Y@s0UEF8~QBo#gb`{4C_b_}e#O zW#wi|Mo^;{IJe3!uez4CyE&k<`YTbpl~iS8Z0y+S1M+?1VMn%5Z4Kr;>-c;Pf!3$} zc>JS>pO*KH2t7}r=W20eYGyP8Xa>M6bJ3GzXh= z+x}lR{(@d|O1=r?=gZ6A?sqB>gq&`Yky?Jbsn!r99{DRPf~d~1I2(kmV}HNv1ZDOE z5o`S^OJtRq0-gQvni9VrWeJa{WoZ*sTAJwCQi|dW-@TAjDIm&4?H*Y z*uERGY)a#$dw4%W#M;8G%;e2D;Q&N$!{FA+P9T@&b+g=8>phY8-IgAPX^vMB|NZeD z;YtG?kE!sSTYeE`jNvTsf!l6gN8_-slDJiXsa^@_kOJk#+7h?rD!uy=@~{CQVpyTMq=do>GesmA>9y8N6kOP9}?;JxWm-KB7Co z-h$bfE+?m7KN3$n?2~ug)_(@tmL2yz>=>=xzHnT$t>3RUskE*LD2i$0O(SE04Zp>g z0U_zZ_f^s0-!eb}RjPYtIEAeGrIq0C)OMH;)?`obuPG8d>PjNJSM;0K2oc<+GT(hVFK99jlj)S7GJmap4aj#rzH-j|h^XJvYC ziXc@weuV=_36LiqkHY%_$Ce{|J&NNe@$7WAF(bE|VjL*Pdfd&1sF&~9HmsxYo2`Bo zFC>j~J@%A!oeI^0&V65f{OPA9LJO}a@~7X@-aH3h**$OJqZUb<`a7adSy_V{>>fnm z!ou%7c{dXVDT|vz5$kkG{mr~#xYelBCu}*o397Ls((C?00<>gDE&H<+)x`hvzL6yb znj`J?gME3(#Rc7BE?}0Da#7CqSW0@2-)RR!!YO~}@|>dEhb`inFk7Nn8OSPU=@&8& z`P9Pr_Xmd=Utsp=)&j=Wk)BqTp4qq|*`sOy)AM1(uXEPy^*5v#SMZo`4d%>w7LC7C zjkZQLOZnpcefs!Dq?0`ZwT1$2myBn7AZi^5xZi%w;ZfQ(S#}bgQ>G`*G!S*w)wo;D zk}T{Vjumy`Uc5$Y%42k|!l;ckP#|y@DXEQpQsB=M7RDKU*zFdmVdHygw@_OJtobON zo|w08?{%^Os?KEZn7&ho=ZXt@jqR@iJGx?9)?6op9~Hd!QBQr6_C~YC@bB3$Cy*-D zp*inbxf0nNaG9KN>yhc2IjD|t;JA@{;N8w%>A>rT|3B4OH!r#CXPiH*SD&!b1Duu? z=K*MTKtfxy8$N)8#1AUA=7i#thkR{Q?cHACRpGSiAql6IsU`i>jU0}y5o;BR_}S8O z4p7yx&ajm{cHQx>gFmDO7~raR_G;X$59h+D0m|kMWj-lR-lb&l**luuN4xK&01x1f zI6~=o)>P8dQ;ovrwTYr;J}FB#ZK>+)fhxI(jz<^aYj@r5vj4}^Sw*$k1#7rC#R|o( zSaEkRP~2UDyC%51yR^8wySr;~iUxOgC~hbJS?io!Wd*p|;hWj>zR%1!@`EOonunGB zGcZxAlw>x#7TBJKSSE{H8ptQBT=<+PBnFi%gocLvf0qZg*=n#9-X%Z{<0M5c*wxh# z8>Eu<;1&C~%+CCgB=eOYm@ZptxCOv7W$k2-k-0uk7jPc%)HyO%Xg=HsZ*o@ZuaDmf zp7PGG4-DvG)49Y1pq2R_Mfw}JK&w*Fk0aSevi*k~shCYda;%JA!A!w01S8cb8JrN; zf^16TtSQ?al~QcuRR|j_JBhBODM_pKf6i2Ws@0d@VmOhx){bKLEWkT!24hoe{4u98 z7E?X7a-k8g(8N_UzB;jJoPP%Et1Z_>AaUo!EY(qj_5dPQmEK;2fIT@iIZ3T^3sj9U zpr}c?#O@ad{pz^D=5ORpyi=cGq#|j?j{-u~0F9_-#2~V3Hpu_~nAE*;|8%JtrT^j- zo~aVLYc3h>B8&vht~vJEUA>I5yhK^&WGM8khF*P*M*kG;>e+VekIc+$^O*x1GRRl_ z7+5c@0Q{YmnY}`=`EDeAXk`i1OJ7Hl1w}&17~twYqH?nLNU1ZJsgUD zJ4%wjT111%>pCww~$~D{esQk$C#nJ)0x*LABRx zxMJ^^rt8CmYaWOgg};^XBICWl1tu1qmc@>dy>8p4G}sj;iur3N{q9_vV`U)QUT@e}5s);&+p6PQ}pS;%2OhVzswjvZ>hGCjSfHP?mfi zYmmi})bKfXa)C5qZ&*W_r8&~$k%s+raYk*h85;aurfn2}8#>vj;W4z2ntWemxX2E) z_1zoyK5FsJ5c+Yunf8wpNr-sMGce+#aO(oz>iRNHcN{mabFjhhHOFIbWaMeg?zLJQ z!6Z?^s*Z~$9*zk)#cG|b!SH5{TL^yekB&BanrXCh`K&SPyI)4c=3zr^DwN3_jd4-R zaKBUqi6wfP4dQJ_fH=noG`G9r4LgNdXxOtV&C5|hkSu9cqboYvM!lM7cdog3-UkPab+FlHKw85s$A zrwo!s(-_C^W!cRu>0o}6nk9}a@_v5*hT0|-h!^Qnz~YpjDE)6V!l z#Y*g_ac<(LAe+a~o2uS_7Gdx0^EpvIvHl{l_v=@o$Oe<5-Z+k;L_K0-1D5~#)?z3j zMg)5a1fFA?)UDKt%me08C~@za{9;i`z#@cFIH)Q}m(M*L97H}(cyRTZ9xpF{Uzvk- zJoj`xZx8u6y`J9HuihDI9+Iv;13OFiEydz>E2OA|^D!g_&S)n_E7B&}K$|9PQ{0+` zdOfRcm@C)|fBSBL>cE#2pNw*r#SAf;=~%@W#bl&UEz}iCmhy5nD|QwaQ6PN@Ov!Zw z@p;w0nF?7y)dRMS84X(-AS6^BCle0E`B z@<2jtd9AOgTTrSlo4O$bLS4NZmTS^l6!1*DZ1{V!n>4G~m21AWFRG0*9r65DC@MCZ z=2UOeNEwW9&MY6RbSb~~#;x|RVhtH{3*O@&n6Gy)e4#UJDT&sJBKc)SgI%Sm325+O z9E?SQcgj;Kbq$qCB0QY(bmBUSwwbe`_{ zX{79w$EAr_U$hWsbO=o6_gzQfAu3Ety#Xg)M#7|0BOk29HDIn$mP}8hb(&k!!&pkB z%}jw8&K{Rl8JnQId-$2wJW<@S4ud8)J*L(P>3}K{Qpgz%Dd8p(xIxYoVqxt4Q~RAE zKxDW`(V4jwM1scq3me!?Uebh}4_%oK^@K~n&m=kVFhI;|2yFWHo|NZX{H|d#B1x$? zEoy=A?;=*^(UUT>>*f+g2DFG|Zsc(RLaRoym95@_m#t@luZ5thCe?;n_(lF)FqP~S zOiu)-li`qd1_#aBf%r;J3XKd5uNyLIfxhfM7WMh}y&rche+<4n{2r%a>70t@X*IAY z&Uf(ou@_%+JwRcm&>EOfy~Qhe*vzwfA5H%_p67cJm(*VM(hkWGYkTtZ&kJuU@dXCh z6Z%bY>lC!U0)`*Bi7V?XjCB{kqTjOvnk09AFxtN>93I;tRr0I#>}odN_Z_QiTm?Y? z^;8Y`4=ZN(bt#x{z{g6Ru!Jb1Ww8W5_6JJALELX~2q z(PLcDqP$o+A6{WAE&2c!fGRccW41{++#x}kZN~aKEw-`?<|HxLC7(Wav9Ve;nWiJL z>wk%eQE?BBX-wl4kqg*1eRtD}pGJA8qo*N#-gNj>MYb=%q|1%F~qXi^WUu*H#s?wkn=8>Lr zAc6G@6A+E;ba#;MT&qzDxtQw8K$;!;)1FlxO^^eysc2cfD=w|BwuQLdU{?{Z47LAq z38yBssSX*~?Zw>gw67l3YSm?bXcr=Dcak*^)s(TJ_Iqdj(G}Bp- z`2sh#w&P*IYwT2cwR%0<+p-;NGQ)QFwKkCyl?1Tr9-35TjFhcrAhU@k&95WdISq#Ns{vtd{aq8RKXILE}Z(4 zyg!&+1iq#S#-z5|861^g$%c-Yt6tbIYyqthT^9mc&OwVHFDFfwkgwcdR?E&i(SCNg z8jsck0mt+HrRW~%A_Je5nr!$kdb>0r?dM6?kCQs z-+lf1cmrzk7=*!U_FSphtpo9T*Q(@%H|Y7w;w{+WIc(WPi&a^-Va zQT|3?7lZa2w3?{xb%o9w&P@-kik=!+HJ(!I`vN-K{6Klv#WbKdh-$zHfm@J>sZq18 zUa#*)`~xo5(2-$mSHHh#n|MK5zkUF?S!f^5ItI*tkOF4#a*rOhRf|S8}Zz zbmz^m8YnD1H(8IBE1^WvQOa#fZ$LzabIz)Uwx0`?E&@=@c&I@AocGHCE?w8shQseJ z3xwDP^?L_hOjx01W>`plD`5BewVLeez{Z+!li@KE+7yi{tr1%}I4P|#*+P>#X5GqC zc`vzxms`zwQpHmF=_s|#ae^;RYZ)_Ri~u}3n3!DA*#OrdGV@hUV?NQ$QAY{SS_!00 z7v?5OGj44B+8kKDkQ`z%C?mhBA+zlZ2Qn%R$Vh4x{klT;0IIK^qgeowE%n-zDcl^# zmSHu(^GL{%&5<4<`QAP68}`bM#C~N%~D#Kv8E~75Kx_e{1o@tJ|29)>& zv=QmE$yaYU*Tr1VvfH1~Qwce%)ZeA24tLF9bhUS%A_EVN_Ze^*E(xd){F~XkXWn_{ zxTleQl1G>=b#_OJ8JaEWcMCfgN-719kQHo5y{I^NE2?526acN-f*BKDN$`!I9umnF z!l>w*;I6yNhZ5AIP_Ak%8pa~p^rn04#&*c2i>m`Js-+j0CW5J^E%(o#e-yF$J6s7i zF8z?z%=~@>_o5%RepUU2!`@BmwJUJ;17rIVJ9v&NmRp#8*h?? z9v2r@3Lt@?`WC$b&RN5w-xQtSp}VV`T76&C9S6D>ANSw9@RFF^Bq+NJPKogGjhvlf zULO2#{U!hXlLW@4E#>vP6pj-sM^wc?A5Q$T_RUm+&15fmitu}f?NN(-^q)%V)NZd# zX1WWzG@o40DdKzO_x`8q^|*NWqc?16LzH3-vDeT0bv={U12=)h_t#ac^c;#+IvIPv zg;aZH>E=)xh$K(7L#XMqVzV=~t0htn@A2%nz*ZPN7zP`pyuN?$f;}DhmgDG>8FG146aBkG-HC~m1&~tLxFW@n(^YaVV&;Bk_5UK<{7;?lu!(YL_Wi z(22}TU9Eg#@;U6yi7%JzlF z;6N9FsqjSc2Lt*86C@u?>dMDi2QuqVr3!_T&4QCC9&TOX@4q=QHgi(z z%zEBipJ56s1`I-shF@0o*v_bt+L-2 zZaqDCrArrdrGG3NGv#w&Z8x1^jkW7Z7wM=*(uj6au8d^ykIdTalfqw{4-3k&dppi~ z-V42;AWTh{uq=RNkdRS_H4i?A!rH3VAO7?0uatI)5O;|PSygGX%1hDVnn=Yuq@c1m zEo;Y-N~-o%$SM$#D06uD^ET$nLyu=8E#n|Y8=IFL%GpG(PO z@0#6Xi+3jQ{ylEV!2EQqNG$`0pL?@+%!QB@WkG_3fAz5cuR0pE0{5^^ZJMsWX0OJB zXPBPZAz`yzxjY>AKysN{BX8TEuiYz+iL)+!=Iu83iH*-}x-3bNT*{pq$qOnif&EHB z*5fMW8_nWixmBg~>}R)27_ITjAI@*xTdO*>#v zIE#DB%uTNYKhb|Z{EGhXr+vGt=meELHHgDtka=tuc8l~}E?P&ZhN9C}o zXrTsw>-}2bl7<7)op-7?im8gjo;P~O_vL(BxYk57sK&}exm_lM9D&Bt%~V_b?cKOkl(Rmeky z*AKs%-c4$nx83kEW`1fj7ydoWotq*)B}!(*Q6 z)+vAU`}Sc9%47{;uoH?L)R`c>jVuLJ~4Qd&o9OfYx1mc%sx_(i*cuAASHkYAKLURDIl}-Zy$Nt0Ha|xtZL&C} z`FZ^c(*cJ>fj?AZ@O0-Cea8folXit`262`0d7$8l(ShfO{3A2zy8K|Q_!$Gj${G0S zlKCk|F_dZ=K5%p1`gtTKgSCWEOZ^Uor@{yX5||G35~R)~w6e#h226hTgA-LHn{{yp zeeM(rt7o;%a~#VShw_Q&BO>%k*rumZbnfx=LJx9pAm@d5YGXk7vdH6J>-rn+=5$h% zKU~DSW@L|a`fQaN-q01jrYy*9u2`U;fDrOK_r*}lnt>2`*K2?1=*W``wBo%?99Kh0 z(BUZMhPO>WzWYyv#nM0jKuTFmSFH`(fx?B z17}RX`pUaI4tsQ6*D==E{o-F4?8Z0c&8!k-t%g4bU=()Gw`tNq_S88^%d>QG*ny~< zsYN$C$WO!0C&^!nvo!-WR=v=+bL7V9kasKQo(gujP7*%<66mWJt}XY3Kdz?4^^M}( zKsTp(vg)1~L5{n&--NN5OUlftoO3Y#aWqI&rk&}$G4gj-@DoZ>xA;=TXfZ_=Zi?bk`M2KkZ@K4kCHKnaJfbE`IOZPc!ztu?T{0#7N!yMjQO5YslA6Ys(c&_6ug$SM=$_&V3lwC)2mB z#O%>AI%}n*Z9-A2`rk;Ek3~IK7dEc$+x!}>{0My@%?WoJq0<6svUxxU8!;o%AnSGV zOil+)>GC}B8T7{zPGDEj@V~$aKMf_p>bzq(8Gu{bcVN0)%RD_W9a7V*8AWiLFb6{F z2m+A?i^I=?aI!OhpRAi)9H7mjkdaQ*!Yaqxeb#zD()wt|L^{c~hvW5bQDqJ(%4Msf zF34)y_g&vxT~lEWlXidZ17nUWBZR(}G94#Pcz8HGb@k!8EqKoUzaoN}1- zwH~v!DZ~nUD(UF9*s3sw@{yRt9fc4Fpfkv4~y<%W=*L zZ7Cmi=3Whkp*o9Ieiv&@u5^Q0=RKKKCe3%TW;8l9khCz5v{{^)bPBS|(}JpVt!coQ z=q3J~99aKc!qd1CS6Zw~+mZCt<0=AxDpTx0?}C(7F6DWJf?ONU0#XysIsTIPb{4hw z6{`WY#gWftoiOhJTJl>Syi=yEInIEB1EL9oiqu!tZo{{T)J4>;*Lt0HR$_!sNzi+> zwZr8!m)4Hxh=5U^U$AJYYxHW%cC*Ipgbv%ZL>fXhufMZJpikls>kkc z^N6NRYQ|pcWJf$jcdz5lJeP+>-fv$8$GP`G(=1$=q?-G3SuIk+P(0)Du>WHL(wPD8 zGN7u?jU=KwI89#G^`OhV1iw_KtE)lysV+21-Rnd0q?~6n%m*BZr;z&(S-FOIW^DPU z1SHdgrTh*#=W&>!v(wLQ3*s9`bP81dW(-sGHqf$szs_5jFQ7reA6Py2xBTFnJF{1? zZAMSqB_&qldHkmpRl;djm(3q6D{}GzePuE1h&>8th!ggqYZmwViOAPKy(W>#dWn^P zyNOY5U?erl+!>dq`-4-0bIQ#`csIUVFE0_KXlK`){sUd+?+alg{uku$O9u e+M% zet<`wnj(4%T~EII-C{>wOHb4lmzp|iY2nW?d6ea$eht#NEq{$Sh`=Mj5=OP$$4(d zSGSghuVTjRW@yfO@4v~EK%&0a!v)1D!xhv!q2CBK@7UyP?JYIYRv60w`(UhaANclP zW%Qwv%rfS)S3=UnmR$5KYE5PU_GfoI;c5|GwBIPYZHfOM--UQ4|BLSw&wW7KT3&dE zGPI5Fqfe(@(tZU6evMM~8>8*h6Pd)qD=ni#)c7&?M+I@6lpmtT>I~~>|9By8$DeXX zUh5=m#2)btp|C5Hvzu`#H+Xy$iq}jg3-Z@iyKc&PI%}+p*sQQmwOyFuTLS$#U55DM zvsSa%VnsH;t4W2rwE$@(A562vB9AFQQiAs%=I)^JC-7t@lcpfPt(m z%2VL)YXKd9FFGVS4H!6E@nao-*d7C@CusWD56o83-}w9;h5XrbhQpi&fQ}uM=|x+F zebm;ab{GabJ9wjDE8xoD);w?RXrzCBLZ%@%9qN`;Nk=RWHQO zF!XmL!Aq|>1V3I^V&&s+XE!k54VbQH*~`n*lg`c+%a?m~9`b`Jes$kcg< z^5_m3m9~Q6$6b%tIcT?{!KLIO>DHfY%|CbKSI@ljTNLR|Z4wn%+)J1Q^VcS&heN+_ zWKKTHeKXL()tn&EA6Gc%44BuLW$)$2YP=2w1vYmAYnJJ9&e(%&Hb^&WOEb$@ebs+V zKCJjnYGieuxL0PDZ8Nr9yVwH!cYtEY-h)#MCq(yQu(q-)yqc;SgA`93iXibtJX{Zf zxr;J`L-JwqY==BGb6<_gFNJd~x%1I98DrUaQciuwy^n0_wwGr=j_$kTnkY>`>QsLa zUD3{!nro}1_FX5-njyiQZjxYE)MGg8Cc23-sWmhQBl^q!HG80pZozDPV$&TfeAydA zyU%~0RD`bnek^@H7E@c{T&pgu>|4{4WGk++?y7t%r}MQla?nX_^cZ!vn+k2i|278- zC6Hq8{}T?)omrMy3XClZm_l435DQRUyw`YbsMJ0G2)nZ1|H2lIG5;9LCro zLW=^v!yI3FWxUW>oMAnt*v8H4^%Dz@8$-5t2Tg9<3E#6?`a!pILAFx{eMP3aj5CLA zA%CJKiPGv8v+6>VL*}BGYw!3cY%4MS(#Q;6L{Q}SIh{GqI0P8f>M?Ua`E=0FZ64G6 z2_L4PBXmz6dv$fvd-UM~9Vw?@0y{O@zs=5l#V}PtGi;zQdm`5>LGHV@yIdb3i9PhF zt!#dHk-=bwhlX)41v{qiPcE$RF8 zqt~*)ABa#CnuWl}Q~$tl&HX?;XBJPvnI?&x{YS%EUgF5lyT6$kW9ua8IJ=zG_w0ApA5C?;}#w^*o7 zN}w^bi_sZL+q@k!RM1};yP@6dpM>Wv)~RGtEiqTPI`|KgRmQV4rgi1#^NZl}VZkVq z0%^5K)&UgqKgt!l@@m=vh{hAORVf9+HRo9hLKVl8$jL6m%2rJpGhA~-jVWW2$msl{ zDVf=!b?FjDgfacrz)LMY0Ijv6iI?CO&3Y1tYn3>xMMNaGQjQvTrBlcNibHTk1@muY z`3ZZR3eR9Lpj|42kl&4b-K!2s@rr4xcDhZyrlbC;Ya=Q1vwUb~>Rk7hJ*oSj2*8e5 zC81FG@#1I*)$)&3UJOKnkeoba`{PzcN7ozaP?)|>C*n^_3WyU*#h|?#<{#pReHIwL zQfkf-!~yDpwU!BDLvAWL-aXYHTAR&m;aM1!C-34<7L&(wS_>993xB~b?02JIC;|)S z-TV?IjKZof5%Fed)?&{EYo$0VZf2iTw?6|fD^eCb>re@n?^l!AMfMI{J0TTW;z~HZRwHUDTC}}YnH5DE!$ymPAnE(eWyOWYQZyZRS!^+| zlWUJkEt*c5{B?El7zMwXHl5q4u9%BfR)x`Up|$pzHCOA0cg)EzarKnd1t9t!Y{zc9 zN|QOPm-$1_UwY&l zwQ4e}^K}+nYMQdY2XCukWR%(_oceDn+jF+ze1BP(ltKbDy@?LUsW*sdCMn*Jn-<4z zV#}GIxa(!Gnx@AsULwgz4003)Hu0JTo#8p8M{z+_!x0?UiQ&FhLszMb0!S52RE`%@ zS-6ydl4ERXsn@zc^isqeeEcK<-}%>5Bi7)}uGiIF65qq18$!R}mncq_+bLpRwO+~w zrYxn)<*)%dC>2DEd)gOV6Z3hfjW#vmmO7b-+gOWX1PX4)q03I@KP5lbuEa2pQDkgT z-6a{E57v}6%j^5;H7_5G&9Cr?POr3Lqyraf@2#m1o_@H$1lEwAn5g2AFwqVjYmRZb zVH0R6Oo*V`*SH#Yv(yE2((@J`wzXhg=QIEL#N8V2C4=!L5yU`!V3OcsdjvDMWW$pI zMc`#;^1{CqKl$*ii>8)jc2gmKO(LG?OO^l1%W2r#1=tZ{v~Q8^oCafEfVO;w&2Loi z=3Tu{=yCcIjP3h8vy@*_9_V>Gu!`b|q2(TNg`hHeK9f9ux!U(z3IWE8a*g7z9Lx{% zz8`dB8a6&=L=@1>B=3C%6?`(RJd8MoTE*$l8Ah={?;90Ay}gD=?sK1R+NNNluymyP zeNKiY@xOh8M?u@X!L0#Q-N`%&jO3Gtti18eil@)v(i)1JN zE*)f4j@TvNszb%hM28Z39!27g5mdah!HKEyjZ~jCvpTaMQGCVtSoxsW#*1EbgY4rp zZgYN0Q`C5*7Q(&0D)IXQ!(*2MQ2Mfz3yLy9HN)iJ#RnyLXa6Won|m@#fqzbO#O@c8 zQft@2Ra)$y)f)+oVD8%C(%Btc+mZ40Glroq32U{ItDoZOllJ*$$5hVcI@}feD}y&k zd?alI{%7^9^)j3xd{KIm=W+w$2UcAHR-^1MUD+_*P4?5InGbdW0Rj6D{6RC!x5#C` zKVAQdE=mxdtP!re1S+cZyUb@Kx>1dDQ;7$~xrIOXdh^rRJ~Ic8h8LMO&I(JvEQb5; z->#ae0em|VOp8`2>0C$S9@_JRH$~dJE}OaiL{Me@3!TiqZ5uqpPu(jpKUb?YE|I@_ z-0aS^PkbiVU{?9NvcaKzP1J8t*XooXza+Cl(BIQ&tn|nZ-cP|1S>CX-_;tbH2t;d* zDRu5j|CT8ZTY~X!1-wMBXpFhB&xz-xv!$W~kqN!i^b0L$9)6A`P5oTI2ieJUpKUxS zSQM_90xFipxZU-5FIO?4WkE89?wh;l5q}&Ry>;PKErRbBeq?4pl_{hL>?4Qz1e{;O z+1Yu@-B*0wmvmLC@RoX5^hf*|OmYvJzGU#cta?$td52`x*iv_d=7&~|zum|kuOMJm zzFy;(k;Md(50gSKz4CJG_o%&*k5Ah@QfjY8VoC@o)=35`U6M3X^sl0j=&iIyfRTwM zU@vvmn`g8I7n$+R{O!nd3<2cG?duO}k9k)U4D!=(DN*BEx+(^F(_R@UK_0iX!usyv zsY9$<1z;2=91r4v-N@d~2+WVZ3eMV))kidg>fG1v;wHp6x;6JMOi`>O zw~1P4biycF4!{2G&BusOx@{4n(&L)PL&B&{(o$roXY7{QyViC1p!`kcl%@N-qFHw_ zR=w;kZLrH~{MgT!Ysx2a7?w^WLZOnI;aC?nCa~kw@Z25crbwAh)VWldvlExE1j{0Z z%)WK*d@~@!m_E=ocr_{d@J5EW%nAIAFTy*g`jFg?vCCW3?ZbXq@^U%pxipZia*E($ zuwK&*X*~8$k+gJ z(N#k?>~O_*ojT&}d|>@(pSvb8J%3ELYOo!muBZyzeI0uNR+~xaAp4n`gf>u8ZG}x8 z=>`9{N@Q+9;(^3Z!8@H1CE@E>Ldvv?t-rCPvR`6d|DAShVnm-O2?Q8=N!R!mH0f>6EVHJ@drR`f}*3RQ^EI@G9AM@sC=ARkyR;xGO zO5iTgA|6Iyn$B!u48ScZ)aPslZx+vs-DR6jCrOv=pywMqDzDn1A#JC->fAE{L7EI2 z8=ZeaD_<_UgFXbWQL)e)(cgD$R?n5MIa}slp4_7MB=L;uwCO#PyVZ0A`P$#(W7VqR z`(mBTBBT0FS+||!9tC^@e!5mUdjKjdUQA+$c3ZFR=*dZvz*tpgNzQe?k3BQ)k4v;4 z``Wces#VbKsLuxX3L4)w#<+8y{_G$Xd2!^j+FhIiXb$M5jRcx@5 z9#D0PNUx{RacO*ady4lqZ<6xKkoc_L4bT<-bwA;{LvH5i5EieWd_zaNqrdsPDhW(Z--#m!tv{2tq64qXAzp zb5Rj8dX>+drf)hf3Htf1F{@e=_?OC>`Luaq=d5P}I^@`z)poM#@rBCC&T9+n+lL<` z1m631(57 zPeTZ0We6r>qoc2`nmhEb+t0ZuZB=&|8?H6?l0esTG1u50W3s?bO0J&xhosMoe-YMd+{6Z|&Du%5N>J=Wzl9-}*_JK;24uI8E8u`q^Efr#G0jdF(`ctaOl_RrjfhH|EvWa9$h zgivt0c&i!rqhEV&I102@Y06L_a#jmpCmMf!>oF#;)Atw0Ds8VTF@}a41ZT<*U9%db z2Z>#iQjn{tJ9|!`7Rm4a73VZS*6q4~)+BMO)R1fAoYmiOyg8&*$0-d`T$Kw_fiNc3g?9>IeChjSILH`qCrU4$J~YkvyS%bT#N|)vCM)IOb6V3dn5O8E)djoh z$3Pw3Q4oQzZ#VFky~q+HSH9O4;n8^cfLa#grRnRvhY$0zIMfQ-7@Ef_oa-M1?>-Gw zs|K3ZbS+#v2g>Q==XRf-H_-CIKv6i?)k6Iwm1Z&B3T_jnqnW@ogfwal80g-r4Q=M# zdfZrbpN?CCG|S_H?h(3{;1%gVszX1bd;KJ6cskV2duA2shj>7DZLcK|^+5A}ILIC3 zP!XEbB2Jl~LN=CnGe+g?i)Sqa{gJ=CFWLiRkew<{t4ku;u5*kkWcff`_NE{z@7df` z$Ao#?w|==5^swHCaOs86^RSikHDYAmNx?uMukTPxO-86ExjXKi>qRBV`r`R4hmFyD zYP$Q=I1_wBx8Cqy|J%DkZQkJ*8|>`*@lFQl?B?-LWm(r7%x5OA-2#3OO-*~8a&OBy zFR0zm*_&p|EkZ*Po_1+En{VhBw4=YLOV=70w=rQF$Y%zOT^9ATRGTTir=(M~+M~f{ zu@3-hH~FUJf?M&k{cp5I;!KDb_iKakrQ1y6n1kK3=>%u070BdPbSs<8EVR zVuT)m*>`aG1}w0z)h{oVhXCKC&Af5>R~=ts-6N4@*m-)Iiel=ygX3Q)O~iu`Gv74| z`LgVV@fS1Erzi6@oi95#(Wb&@fByX0a(5>j`ZS>*;6V9lx#v=3KZ*1_H|S+DMvU^s zbt-{oovUdq)AyH7;Q9Wu?XL75yj{Me-+k1N+L>#M*y01S{nN)k}U%<5su|AYNDH z7elWXbdg{JGan*2k{B_|O?AKURO#$Awvm64Z5cB)l{H=%FF@HXW)pgYv;2icoa(l_N zvC8gL$GiJ?sJQ%kwt)M1U;X-VX0?SumtiAzFYj&ZicGPpSr0m3D5yeryKv}K-I}I* zF}54lhc%<8w}wo~ZfS)PJhwjy$MXNKgo9-dRg_3*P`(XfD9fy7?UoS%xGC%~V+Xl9 zqT9Vl!GG7K^H!~$+qjODSr#`7gMF7l4LhKaxm7NYzY7aaZ_eF1ZG~^iRWGOtzb^6^ zPLJQ|3~b@oyf|8DLRTI(_x7;+p>)L=(ba$y?+GAOvgcObywJ__2Pz-_g2S8M#|EAs zbvB9eeE>C8tR>GNL*Wgq7Cq1ZC~XSB)73E0eX;!2yIASZR2GSooB5Yc+p~N{bDYGh z&6SRF8V9$$aU=TWv@i?y%GibB5%jxXr=~1v)MrGF6_++jOO)35ts44hR~}9iGwCcf zPZ-Gdi#njm1W@KUW^D$d#bn(WQ$3+m2euX5>_Ud?Mk)s}M7P{vMW_(&)oVb%Al}z2 z(&}Lx-w3L;aeQHHhV;d4IgW)WjptR&x9AU>%MEC?6nz4nAY@8uH=S{?!^|stSSk(> z|4S?`L*ha{V0b<0nHre8dKn@>{^$7DRd3<%3>2O!9eDNmX5QR?QL9EYALeX^g(HaW z;}*BnsH4{x)sDS)+7fx^ym}AcfY$3}p)rDh3%M-DA^t~WanF)>U$x30RMp_*F<-oH zBOsCQK9`wi4_W^Tj)YFUa|`*s8khiO9gyCl`A$;ZceEDM&zNIro$;1!cipLM- zc}!bZgr(Z=wtth`6<5u&eNpY%1!tT*CDWdr=C;N$StD>%+gJUm`u&iOS4yE8A#Wnx z&hdBcsAD1MgS=<*2-40$k1yyFaGa-XjmfO*=#pLAwFGNsV58&naMlC8rG4z^y=T@8 zYI`D2B?N!#6WW5h(m)lpi;;Ofj?IdiZy0(I_df609Lc-v94!8EFR2>%50|>vP3P;SCYP9E@?gAPyR+y(^U7 zC)P_?P!f(=#mNt2AHZnfqI7!r0>rEHSXYe}gz(O#GYAvCc!Iz#7<7Uw6{rsul%=X*xhX3UnZ?d*ycUGJ<`@~V0 z2xdh)-q<1?aUrtC!V&$K=B43s*MAQjvS>|Xjs$R+7>&5{ns>65C%Oi2R55z8=pxKZ zK$9iM!VWQ^L?**f-b(9eb-^fnuH_yJ!ddKa;jjFFlMc|t@d3mJzzub_D7%ae&%zJ;=m1Uy?Gz)zl!oFgD1nyNGZy#|*vTiUk?Bg#KHgs06f$}GV81wa{ZY!Q z?sGOQvBWu|VEoTW@nkZSv2cFoCIsPC%?&%fbV6UDQ}FW)LrtCfQu1HuSp=`5^a zMSVO>rzKnE)3m?#;Lv0&E+x{H0Cjf0e5OhUNvYT4Z5_gHs1UYL(lUu*rK5Hl6}b{a zfHvgcbPa>%nhhdWKl+acm@8wy9$Mhm<0f zOAaXuzDS|)rq6ZZ8EXaApF^^8H3^FkwU|vK9pN8BlF)t3nVJkd|GgU(<;;CdE$v$K zxjEz%uhVasL-Z2R*(X_b&b46q4$qvI21f_w+~ldkPJRVgkMy$|cgEJkD|GXx;kDRZ zDS|n#J5IDpT^U(OXBLOi%7K=ta!rgVQcizxqTxe;Ff}#}QSjfm)ES_k9amIF*wx;( zzGPU*L5s447Df(bU%X?rYSfhy&@J6)Y3{6iJq%)f{}#}|u75^ZX#l?^#AF|8j0aT! zGpx?_s95lSEI{wqNn6yrZ;#L;(aX06jGb-^mOf(gezUkdK2Q3XHijb+bJL<;d0wD6 zWT6G_xPW^4?xyMZR-x&$DuVuOB>BbrNfZ8Sab7DZg%B#6%+#vXNZ>Dw5UWp?E20yEoPNje@MKBw*<7coSgFJ=mM ziJsY1NGEh~AQO|I;X8`}rkuBb2BfdMS_>wdbADZnbT@q~Z^s{=MZUi#I1lR-*882Z z5O@UsRdFnBhn%~pysKOzzuXtEKJ=Rr*B3LT-(TAZ^}&2>!WP6p=W&W34v-v%UA*bo zZoCS7y!H6TJ4s$ZlX8iYukQ8^kXWdz8H+qlWRM+B{;J#v(_>d#F*%NhO7B1PF6gbj z0+`FQQs|}E4g4I>OMuKu5AsP0OGAx_yo75XoI*m?Y5?yeFv*DAK8Twv$%_^7^Wvuq zu(FO=++XYxX2;kYFY=M;c%<50o6NWUhTi;ch*{SlM*{OXJZqswO406s;|9k$@HpjE%T2OGh z+zj$U>VeN{Pq~mf@uR^PULgUNW<&^3P|)*2@V0$j$QWz&19TBCxF++`_PEOO-@d+0 zEG0S|NP5O48G) zg{gyPz)kTIMwE5z!RkKyw`8vAVny)%2Cf*XRqEFB)HV6aU?l%@aVa-AjXNxJJZ3uj zKzw71a4;+D0Nw-N==MGZ2h!3G2|&VEU<<}8r{G4F^MY35_556ihaF@biX=gT25a#% z0Z94>3KG^8ECZop`r(89B7dLoPW%jt#hhc{&^ke`e)$89N4(MIN~q{}M$mm@x9E`c z!NaIouM~-g1iSnmW&%SHa_S;EMh3i;t~}}M{$Q0?>%=~;7KdeKhU_6;zsyqx2O^SB zD3QOSS3Ix5y*#35+%5mx?)mXVfixR>_{;~_JVyf@L7D!_UxDuXAARi(k3l2>3&Bnr zQYLAYRtkX+f&XC)rc3GYm`$j#>;&mZquCh`m{KB5M%zqD!Hk#|GzWd90|CPVBxxR* zPV5#Q={D}pPZ|(*FghdQb$Eq0o1a~gv)P_KzSd^P{JV%|>9pQxwQZ2~Fgc4Dk{JXQ z3#{y&j+nogw;JI&=Lu07n#1T*31}Jfoy$F2^|=}&Wy(QppxSWcB+a9tSkr=khtKwey0s={t7AhpH41_Fmk&K=9_yBCZ7^)Dk|{p{H<%-zC;`t#ya5zMrU)ZF8-) zgYgqoDoM`=>ru}l39-^+uvYliQ}wFg6Odg5=BWN4mGed!)925}{wF99t87y1xCBN+ zDBE0^&^(A3`=z3@x+BA-7!@;2YafaeHi2=W+mp}2q6|~{hzoMnzINpD(teq{(U(}> z#Ia;C({cyEc~P&rz!fw_wxri>+&?U_vs)O{?S8y?-iC&d+@0 zJ`dWip7LqKg}*?B+fyGI)mBz*Sl`Op2Dw`Z$^9t`EXFAoh7l?#AJV^yHmfJr3J=%*&&;eXC$ zUBsn29=#=;+eq7y-=;Q+7BDogIZmkS&6#P6U~*BlDjvF zP&pGW-+DRcI`(%uy0^qE9V_UW=@L4HPLUT+p0gL)tWnjvmr=%sA2U>O+;9mpQRKT9 z5P%S#wd7|)RrMYLwRsHY?VrS#c2(2zcXd=u0n&WotQ(u z;PEMo50@eypR&knkZSAhU-#JuPWEGOo?hP>Cgk~<0w>RR#pVj#G?81ddx z#6zCV{r|E?c}nFCF5IP-UwC(e@?Y6FSI10!!(#HE)$tFgdzJ8{NqEBK{@<$MeevxN zXSYQ~?$#jk#4CWvekl93{P-)@b>0lAe{xdgmR*j5v!KM3OS+Kl0CU{Cdx#hBo&y$u z7O}Gm>E4J^KF(2k-;HUV-?;O?Xz*vC)Q~L_DA(9{mfGDf@YpZy)AbDN=ZDk(;O&t> zSzEe1`3fpqX@<0}uT$IdIiBl0a8c)fe|!B(9sjpRMQrI}>zuL)gnd~A9I~nxL0NaT zWa0R`SU9ZUYeV?_$$$G3h87(D?N7hR^eK}CGvxZQ&tly4{}P@tvGspBZ%wffJD80E z9pTfmrf78Uv^#}8)ty?7@T8-E_rQ*J|A2;s@c)e^#c{)ATFzTGr{boB5AKroH&uf+N5n> zy?RaBW+(U9$vlI2`^50@Fe4)?2VnLs9s@9Y1w{hChKGl*Eco?(=tLSo+8^vq_m!&L zj-4)zLJKp@Ac8E?jj8XR!3;ZC)!~cE*D7u5lO1d?vuL^*s-CnB6K(x~X<&v5%GN5& ziJc5qRViex>inYj-ntkUscix3yRSyNCboAHGi)P*IYcmv?KP0@9A-GAm${V2t`S5q zr`Kr++q?QAD65tgBmDCSUm$|>m|^phP&SGEd$tohCLegJPURPCJpJt)&*!hg_Kpxc zOL_EDxABGFgoo@6JXE-g*jaYTQRdA+(Aiyw$vS2=%hh4XO7CUPIcpiJ=Ewk7yONR6 z7)o&q3f$HwKcdUlFN<@a8d?OWRVTx)H4WUAlIn4_ZCxSp zr67<3U#c>DZrD#SE2z#`ge?U`OCu2r3ky7WqQi+3C-}&z$9ZVU^#mZ?KK=wrw}Fu&^)~ zK|Y8#EezB^g+w{Nb@>v0aq~vnPd(1#v(3ME-r{^jbyzC~a{{LmQ#n^7%$Q7w4UDxE z5J_yrCzfqc^DQWw;)$gj@P=)iPE43l=W%t&!Z1*Z*f?ThiGsEcF_ndyvII75{H$PC zTPa{COr=Q0fZfeHPB-Qw!`s-^Y*1)5D6|_?v#MQ~T&NRdRoQCR!tE$a<Z!=j3X z+m$#*jC-5Jd4J5JgsX|?Z-egeLo@ zEZ$#=*yu_g@NDiWMVtvu-r0(AH%q)dHj}?lr(Cru+}WU9wV|s(t^b_B-7E=@o48vg zQ{T{v+N~1rFW&xOcC~a_qhD}oID1?KJgpV6=gsgH>xzD|h`dQ#>@Gv8Wry@D+X7>r zdv_0W?|sX-clQbo-968ljk5^}j<$KHR?BD<0S8cDie*L#NeW=aZ ztCcl;((w-ls}H{yU=f(TFt$WR?yB9-E!|uBNU6fXqbGUBc#4%j^t)6au{iSB$B{?w zVmNjW zCvG|FL|*}7nUA%ks-KCD=w~%YujxE?`Ef)r{fgV{3w!smKTv~1q{@K^@$~nG z0oOV)mMeLXyEw}=WEo*UH)y5oyoT>m9}n{=NH6tk2AE|DbBqE*Qx<2vD@XaBT*C+b zm4mpft}&MxnEm_uuoGC@Ke#4ov-|I}lXiX(Z{26AO`A3k2C=-wV*qBafaq5vs*yA= z4I1Bn;00~~X}|x+<&`{8AOW&gbx42D(kRShhFL_=>)4ZSi~8<4q}xIGIn3#c)wCi| z(uSy*p+1>I1YLx$dfTjOGgZv0vQ4C$O{YnBh+1V8(jCI8&Qq&2X%sqG)ht%^JR+D! z_zQjO-6AS>s81e21j{hPA?mwr8U+Pr6N}@h7$Gh(vR4E`zZ8^BqE@+%M&T-~>e)+d ztC*Ru#RNwL{tO^!^ygV2_9xFC$9NV}5oE!>3j-^UH9C>sa=qU*YO;$qDJNs#$kLsbqs0K`NOlQs1zO@q8n9iAami>l8*~I2O zdB_^XAl|G9vnGKlaGR3f$j$Qp8@KS6FC65r7hc`r!EH%`oB|tTEy?6uo$?Z!iRByE zwa~zADkbj3@(sALs09PM7q$L?e*HSCG))!X!wDiA6&dY zgRV$nY9Z60lUGTc|Ji%@=s1r1&i6AjK!YHQAUS+BnyV<>aGqYfx_Bv0; zHYT*=M7AZ%mSnqIq$Cm|si8zcRHI3PO%g1;8o1TCy zb#+yJ>-+s`c5E!S@1`_RJBpUV9!yoW#Icb!F4r|1+et+lh)qYDjf+KJEypN&-$E+T z?A^4YjE#3zkpCAU?h%2rHfk_tW82I4GX>6u2lNpNSy@k((Apd zVB=^+%3dgWyck4{|8H<294F$ikuh$TGLE;~(8Q#T_lb{n)D?VbD9c{Mp1somw(;*2 z4d(57CrSX?(6@MZKIFV_u}dnRGhpg2sW|Qmb{ar8G;G=*D+a7F%-K5(3-%rPkPC(l z8-uuOohb3cjhV7X58cDAx3%-F$40nKD!yUZx7$qmPPu~1zC{|?CKWHbf)5Og(B(wj zI}?$+NAcI6(#%+So5FowgRsq@Z2tZb_oP7Hu5eEX{4tB-j|KGoP7Z(U&0p8V!0a)* z#PDnQu)Z273!v_j$cH6co`Tc+(PqRJkgjRAY-*0a2OI6cPyeY8L|A@6pAHPhs_T{9`p0IpI_k4ya=XsXAyTl~};4WG2a%I|p?Cn4sWS0yfIy{2H{V2H^ zB^@G1B=;fLSGjIp?2?MLral_>1Yz&(1jQcH$JJo&gm3ZV10$Rw$2&R1gH-q=KTYIx z=}MJ(Qx;;sVFiqt&m3?Wn4+C|Z0gKh!*BY{Jx;VDX&bbn6*o$BbS$~)#(tY8*DP*l z!_`U%-wT_OR($8jiDqVIS{Tnw94%n>P5ywk0NL++To0s;8fkBD{6&N(2zzbA z+?;#Wya@9vO*$5VhN&9aik9;7FE<93MvL2soF%{<-ThUQ)(*m68{u8L_DMVeo?zYp ztLOY}D4Atdd5ks6!Z~{f<3IN}!o9%Cp`%z*Gg8Od!&&*GEafFK`4_1JZB3xFl50?M z4cW>F*~&`@?>u(-*rIzqLD+i>L2*|C*aD0kcsok2H}~UQlPB#FgsTT|wXf{SrhVQ; znBTr&nUWh(awC?1B>`>i@)HR6j5+^hU=C~aa>Am0qoa3Si0o2S&Nl#AKeF&63r`9B z$fB@1ptw3%z>)=!9Xg-989`x*_NsN~MB*na(~7}%?ZG;9DYanMsOnn7y4()(vmvP! zS-v$fi$U4;UYnpWrNK)%r?e+*%Az;YlAM(e4Zt2yBU(Or zsg2ui_NhgTW~{_Z)=yg$W&;LhMkrYtlszy#k^s1s_AE{<((cSywvBYphi#efs8;B#f0 z?=!$`%&?6awNDOZxj!E!B;*$#`+n~Hfnh8$#&)UrLfPh_V!-pR;6-!3e^v~rqrGXf z#%K1DZ*h9cqP8>Qy;())6gaCQsg93~?k4_&?+S*%Q`d4g!;7m@J@iVqkY zn2SWtvgBR`#XC*EEJ&{NLxq4nQt{!|oZ|(yBHVz;vCshQy!l*2vt+LT6KDqQG@Z<1yMp;j_AS*8h(Z0V8Yg!+tNL`Gpq0s9PZIt2JgCtglwNeDw$l zilC?mqq3DHhFQCiMH}|cBD}T*`w36`%r^JIl}s^mAcHkZ0@en_4um_8@M53Y*(QKC zlYp|-!IcEXWee7mg2=f-c4&fZr3=uYtL4w3WCxZ%k2Pvx`4-mbMn(qKU&W@qR%9!e z6HsZU!4bKZFu%p*`FV5QFBlo*m@&J~$T7cQ%EDeo2Hvq? zfFN>~6FJKl0JB=wxRyw1DY-#=7CkgW{g5arw(7Yjhy!CW-~WSvZe zKc@#dy(y7^vWGVv!J83OCbJ8evQ9d}n-j>iW)8VEL3!RzSVx1kDyL`aeECX^7sf)) zoOzjz%LTXBrpWBMhjjNgocV|==?wp^eN_U;7A^)H9IaAbrCGAEr)=?@z8BuI?;dkD z?i8ImRc*abT5&_Y%cu6<$7fESVtjm@!)K4+S|ahBZDyQ1wI~5*<*Z_0VuZfs+Bepz zMGQ_`thcf31yaZTR<}-TDq?U>1FV&_2C)X_wWnt}W7CsX6zhTZm`w}v zb0GuK2z^#g|F3I+SEA_8Xc^`n;|)5L(Z_57vj6*S?ZrUtV(+Zw+kG~#+{gLz=WmKh zEIt-qUFeSiWo24XY}4NB`AkTuZd0Du^2G^Qn+mj?vhjGWq_PPswg=sAET#h7x_&ld z7Vjt)`Bd1DJ^o;Xvo1WgJu%AttbmP% zVQT$W@xZtpEk_d7?k~!l1-0cmc{^WEN$#KQ3Alm-($vmHs1DA zB|8Ch&-qp&YkbrIqP7zylE=fw-*s0LAiUm49yhaUV>WGkjxhtyK0c&D_jN|v_{pIx zd*8O6FaEDKe&FZ6&Xa~I8~PU8rQ)J*@wR-(fA7ojP%+@5Z*i}YKCT)M+IzMsravdx zO+^1+c9ZW3DSgp+&B~CWZ)GXIFQD{!n}L6+WsXUqrH?;n z0YXOW9PS8;tkm-wdE{5&QVwXFhg1#WehVdYKpQXakC;0CKY<#Nvjz>a#n04)DfA7A zV$GI>hOcNQS@-S(``P-)t*kno<(2KvUKf}>Cp?bYWhSiA*JS>_*1LSurtU;t;62rY ztXGmfLGdcUcf#^{)+~GWHNfDRnHiQ}*v%RxvHb0fTt0$YeUz-Lf5VS# zuJb=W`EMCratA4YI{<%P`(?b7f{QQR&+4Fv6*-*RyN@X#JpM~W*&*7LWKOuuMh++m zN-}NvOc-C;rFMxcN^&{O(ECtc7f!S>3sOeV;!*rfUxM#5ZD|GjN zZNYWzF?GUGPmoH%Bb6-YeT%Sn8&E@d4Mn6(3MPGvak+siw{Z_o@;7`Cs2fmrhL};U z{bVCFD0|+Nk;^P0!lA~xp)6BxA#d4uJS_%`TG5Idr~mWjoiNbytG&5n?b>y%3H zw1C++S!~+0nVma#bN>8!hKG-}26Eqkfuj~kd+m;2%-(MK8^68~o`vu%vK7s2ZD!Ug zIY)JH5+&ymUgj#+ZF5uyXMq%9K11ZB$X4{Im|cz%P&SUBU{O8TiCvD8^902?gxkIV zn6>&yNpgJBJD)@?4ssdSY8dwpGJ5gD~sP?mE)1>?`Ax|6w4W7zNpWW@dQC3$H>54 zM9y*mvXz&wabM3Pyz^u$FPS{wNl@ImfL%Ls;6B3qtqm{QlpZk1R;me`R(PXWqvOec zeXP3)ig%k)&om<#pv~3#1b%?YNY+ADs z2kIKI?QieafNs5tpR%-7j8vOX1-0st$tMrv-_g=Cz5NpD@s{!`9 zPYIm$jsKo2*tns=kjtsduJ$y6tTDjaEO&gQ$$$1~SFqPe89!qfva!VR z!$VnqARn^ciTKNs%?2l8Pt&n&C*quMv0ExKz#~Ih9?XXfyMp6}Q5&cAF$2JUpOHdN z1791;^8RAL*N3vaBOh|Y6|8k4+NSPfzVjRGkcyA@<=A1^wL6+5jc+qxZR|~(0`AR+ ztac)X{>-NStcBd7@Gn}(t%|;Kj)R3NrGK=Mw>??!`q87)1m+xc}MgI)S0LGgWt zDGQqE7z44B=6{-Z9oWT39()g^YNV)fX-h0w8=--?2$0e-3^=HZW+o|RMEA`u-WbVpp{@|l8@M!5z0PQOqMGl=okxb+; zCtN1%GV_r`Jt&g0OQ0lIA}2{lhh64EP$UIR%{t7^0>V5{7SINCLawvV^quYn>V)~* zlY7?P|0s6(>ExInDg^xY!76`Iw)wJQuAcWT&Kvcme|8YQB;yIR8l2tH8?vIfl(+LO z_VWdvMp9)P4e9DhbKj@TvT5J~4Yuq&%a~?0kaY#>Ee6bP+O(Ndr>d<6Pb+S)KG0i> z$=&j+y*Z-gGkfz#3z&Tq4V3NMr@bv&z}Jm6X!KSGX=54A7EAWq56jP7b9v;<5#|+I z!gu*~_YVs5gn2#M*4>}RF4q>US29J|nN`yh3(pnrvk;_`3-u z9W1{M;mw(JwISRYtkE&T-f@Jt)O1p(46}9qI_X?Rm|u?N&mp{NmU@CIsaR3TvZ^wN z@Fo)`t=yz|#9qh$_~0&1ZeNX(0^us&TmLjKcfqRiQiOMjps*3)U3t~~UH7)zIQh?4 zGUYC3<>OVB^e9&3LuOpT%Kj^Kl`kZ$+cv3Ko_~>A$>ywcH)rJotm;o=`O~C5LE5*B zhpR)b?;F_V6W2ValB)>{+f6=SASmuc$+ZaYJeIG4XKQo<%by@yc@coHcMIM9k1qmY z?_y-&9Vls&t(-E)-hh%0cKNBqkG8x2ODMSk%U1*i3Dn3|j^9w_yf+&ng`yH>@gob_ zsc@%60?Gm$-gpEr68Q60!jerv!jc6jWVEz!rIuX)$`00yr(@bi&MEw~25DpI;=+{x z87clYvy2lH(>xts=FFLw`T2T;GZ&HBcMody8ag_b;9C}}uUx?s-`xR{ojZ3iGc(f~ zlxW2b*Vc?d+41plMl%+p84K6Q7Y|;pYN_Gn-MGew)~QA0qc8zhd!vwpSE_hzg8rr5 zngKf1#-@?1ZM&&mOhV{5sB3C zLrZsRaA#goi~{XFo6aI@T4LBu3Cis@y|oZo*D}O?Z8;5K)uKcOMzhie zsnVCy{%%Yo9L+qj<)MF71pY;f{5>J1f3PY3V1Rp4;H-`)eZkg%`E826KX_~TQ@(5X5TF6t z@ESm3GbsB+uJ7u8$-gKNzBkY5`{B|SG@#c$52;vwIA%N6fN|`TTUc?rjmujunFp$d z2HzTz#`_QKWaVkWmPa=7^hciM(w5k^W!7vTacRp1Ufh3_Vfzm`zx*(k|DEYGzpHwX zwMw!xDDqqr+f~2M^~BH#%U{5fJ@*=*aC6)q6xb0I6Cn12@VFp6PS|C}gqMKiDWLML zEKYaC<*)xdOAMg;_0FGXy#69Bgjc+p-j>~aR- zr4Vi!sH0@f{D$h_7)q`LIuKqB;norEMU*^_>RFF)*JGDE5nemOZ6heOqhy9$p9U&p zFgE_y=NmW2zJQWb2(J_2F6GE!2jR|;b1z&cofi?_6vAyt4{z?v5foNZV;bRVz*25f z41ST#$1Dkj#C}zs`oyp-&31o-Doe`AAZCnG$4vH$}X_W)1t+|8!%QvDqRUojJ`6|K0D-s%5x+ZH;%`7lq`mL|_j9EZarxEVp; z3O#^WnAD!LZo8nbOD`L|Qbo=x`j+RkO!0I8b@19n!km@!isEcQsZ;yQ%6X+h*_xuS zBZnJH8P}9%w6@z6Cy!8GrX`Hy7@W}qsePR}2B)gXIYp_X!I&MKty0d|^mXX8xoHjL zx(N2Q?`3elimWS2hV9y8CV7-nHszEJ^?<>8l@d06sT_rxmY;PI^pR^7m^Yxk*=TDv z>gTSmu4EwXzWeTHeEf3KSGpPNSQmjir^}aD7xbi+2H!GT+Pge&C#=_=l$o%Q){_qa zyqch|mZPvE&|t+dl!k4J9|#)2YYpA7c^c%uQkr2_L!+1%&=R_z0{PDstk$nd(olSN zfIBCUyOhQp&ZBXMXMj6_UFhX8np$U}@obEgnq~LwQ!o!d-xpA?K{^fhN<|GQ7%$cu z@bi5+{&28L4b8v>&9HsOFlX72It=+GDQZ!^MCauvaSDfKQa{gt>dv z9P3W0xYHcts4F<;3fh3H zLT}fjs2FMGol^0suS)43 zOq*s-=c9XE;GGckeC+%_q&R*5ede&={ z$E85WtS*40hygX>K8uofpyVEYDYXrNm-esYvHq7B*?$%d^vw~2w5Rv`oZdeI%$x6+ zEjz#HyJp((mtR+Y+-|P-#C7C_*EU__a8rJ4+O(PR@vG1AdOT})1O<*aZP&~=Ud%qe zAY2MR74TOFf0$*T9t7aueC|PVAHIj*?EgK!bXHGfoilRA0730b_~}8qYQN6ur*_c} ztdxhSjsFUyC6^nWDo~o3kj6lqL6Hn_IR&C_9_B^!ob4rzwC~;b->44$2uj-KzWNJ5 z*}YQn-hH|s@u5P%hl&Ahz+aSXK2g@sos#Q-IfBA2?D8>w=kO6e<=)8$`6vF02l-_N z=ygBOs5?wh+-4FKmyJm@7#lTxYIHEq5+Dn_@|Jt2x4@iMwBlxo7^rP-SI2GduC6Zb zyYGIp-DR`w<<|4vidMWzv>3BD*&swL4XX!m&$MPo+(a*~m`NL(tH0SAp*wf(T2MAy z@tqIhS=VLMHb>;lWBF;SgR=xh)7kgZg!xGDJ;L1_`&MVX&XWD7KGc0U5=Mo2sc7_3rB~PoMhy{wDzm5Sc}#zVPs$} zk<(7Lq6ZiKaSQK^;P_|L2yc>4XFS&IsPU?f0OqmY&T6vsp z@?qu~XG(U_k$;H{Fe-O5GO)ws%F9@zipW{U$br2GZ*0N( zu=f_i{4K_3c7(_g*yW>FU5k=y5_T;>b@07}`E3meWV9!(k{ieloy0DCWGg2Su8)%T z0tW6I9kNr=+Z9r|l1-ShvO_VrrivG7KiN2(bVMc6{|o5=nNo=aWb7x~Ti49DSh^U% zPg{5yf!k&P-V0SN!@AtY>u3Nv2hNY+%tm;f#usx!@i|hQn4acK7se79pYL@29jglr z40b2m$$ev(4)9G=yXBL+R`AwL`P(8`_qxttCtP6s@+awlH9Vb0bg zmf4W1U~0{Sg2Q(TM!oK!@m zJqsx~5REXJ($Bh=5%km)c|uC<8kFs=g{07I`f{88KQKRnm(sGuvZl0OEFlkNb|O&> z)JAYqLW5g%@X}gR)N3YorYM$NSJhMNpzvEf` z@wPWpEN0Y>)~)2d2nLX?3*5S(QrGXto|N`r&+iD~c3=(2J4{=knK3&CJc-7ZHtEIg zQGs(gf?4ptWs(0a&F)MXw;RA2i*P56TyZxV+*(URD!KVQ20)JGjorgSGj!KSxSqh- z5aGJ|JCy>@6Ku4j1jJ0GG=ugYsS;V^4Nk=8hq64B57}Uro%1dB842Q;A^WtEKHlI& zJk#VedzS%p(`LU98{jo&)W#l@nC;gaHtjJZa~%884!eSPROT1kKa!0FznbJL6I@xF=_csT7CiyznrZ!+6H$jdLIlaekkCx|8E~FO*&tAX^j8l z^XFOC{RHaN`&no1=g#{dp*ryl0FS+Lf|oz{N6E2XUiy2?KL4MHuB@hO`(F@V*n{X= z!P>R!m?uSQ+23%9PtE4J;Ae{X6>K#EuJy*!eQ?gg5qxOFOBqj_-w`lQJ5#JeC*3O9L~k(}Z?geyui?e&PGgrYVwW#1SpJB;2K7(}cKI^o;86Y+Ai^$%2-o

    c@A?4j2*G_pU)yXU zz>k*yWQ1MJkQ22?1J;<`aW;=)y&(Vu$Q2?54&_2yL{w^ zD62i43b|BK4oN^+fPJs*O|}^nh5@Ip&qgcE2b43~(=lP;&M5{bs_a{_7q?9yBZX@j z|H~#ocF?a$JP6oW5T>D!vaHGZrIjb1FQe|IuFYa=^&Ebnj=v$tnZ<%4h z&S;rpw@u)+33}!fJ#&h(VYte9MPVj@4x4hjjh7aQEODvHH+FEUO3D0o(}KfON9gOw z(U&%i-ALCVURoqxvc+0JUwaNWB{&=%fjX4iG%NP-{1M!=(5zVmgEj5*8P_evx{*On z*$E@D72o@I=eN@zx?cUQ>);hP^^AVkOiXg;4WqUu=s_V3tG1X4=$p&YlTwswHpSsU zgR^NgJ`}T7LE}U}ZJH@ZfeYY1A&?(dNTraU*0Q?PXs}+#fC|WWDA;3;lUnp0Zy%p0 zO+(Rh4rGs!>)oqxza@}&t3(-A-l>xPpYjCq9?dkBJt{f$5m!(&Y})@>viaF!z}*H+ z{iVJfKU2_bw+tH8O`$QHy9^WeX;<(O!=jBDvU?0;_BmJZv@7^&v;I>}?Am{Bq>cOg za{S%lBcy?e;0{*U&#_|tbNts|&#~M1-tLx)zb)DPcroCZEBNt3kT7WLXcq0?m2B=X z+duCKzEHBse>C8)e$(c`C5l%bf}S4_xaaSn^ko~lRbQj`qF9ih)HT!g%@SJ;JM`6} zY5>COYcM}oD9PpPF>mWYJKX>K`tSY!c^MzCUq-l3prkaJt67ha^`9a31l0vP25)0d z_dE?*<9QmAxv@&n?1JS=b|Tzye(16o&GHGK5cSlD@ z%j5VBh@fzm>cJNgp1^AMy-7iskFd*25N?KSvnW|7TghOJg5^Wggl9-; zzguf`8Ihyc1BAV8g!wk=bg-$vlXl<2@@oihmTVU$ zZ+cN$mrxyCkCICe-V8rsox^%%j<3m(cFxi{I!h*D?k=M`xQ#HMMIN#i)SUp?${51C zLbh@t*(Z(;sc4sqsp>o8jHRWBrIjg^ zT*=6R+libd2yc;8nDL^uOI7T06}x=$s%sB>Hxd+YBU@Q0U=rDwN;|-?SfmI{O4n<`$i)>T)HH*=jg*PYg zYZilTRU9JiyJrTYWnGc4g$YYm&MA7MFk$2QX$u)C1}{|cIs}!a*#)dWXEtKA-NJ9T zkV@fO7QSWSEfWbSd%gNQW@E){+ITkT>#4&VpzN{Md%YDm+`GNmQ})%uPg@Iq%Sdr> zyh^{&KC*tsV(?0p(X>USBa3UE$-#*#e%jKk*bbZCC`>>cuT4uC4^CDYYR^(>&r+BP z$j>%dv`#HzV0uLR({|WY+Or&*9LCECDs5TZw4irB#HmMAGT8=8c5Vb8i@x?82j)i@ zm>r?7Jx8T2i$la^rdsilwyDpEmNGyad=Jxw&k=2a9cjIZ(P6VT7x~`Zu`5r z4Ze6rfAc`cP06UG!IlLW#bO{cf?E^F-bGAVBUkJ`CvZdr%Yaef?*Iqn?Fv=_x6;6v znwhYF3+~ebf4haVLwm=%M+A-?;XW;J)|ob7U3=8ZJsN0r?5N>4TLbs7-p5%VC9K+5 z_P8`?BljuIru77=n)ZwZ&7l4Jp)9gTkxJ=m z@(l0Jhtz=w^C1WNa_o_c^S;F{sVMh%^MPW(u#rN(;9DBw_ATC-*X;f^PQ(YcgbbBz zmY;?Eu8@>nc(PZBv@#OzmHa3f#};hrIKI@$EdX2!RS(ExE{Aa{E; zf@Y^K_Hli^b?4$qDsik<-cR(*#84S+p@o*eR;^(g+00%Vf?RI0%DmoObNeF|w7B1%0W&^b_CL8}c*7fIlfOv_tt!@dr8Qw{t%)am2USl@EED zl?X2JID2@W&1jkA^9c96o)}C7C{u=}fJ>$vOt1pYm{|i%^mo7I-tF7A-Iny%ThWRe zt6$V&%zme$uCs1;NY-QB~VAk@}*ySaO9I=vfj2xK68ciq5B4>gyKSOtaCzhYW@?mj5 z+w$8W)j@SIMdYLs&{lXggg4LT{&XT`td9v{ZwBG%(Y~PAiIQ#D<%K}2@FKF6sjEQQ z>R^^I-$}MIwJ05P2ycdLWdh+&)AeAQ6GIuEzkMYa6*wD%w|4nigcp#lR0(^xAiQ%oOgWa8!k^dW zs4|&NK-oc2#WQ}geoe1;h!P1$Sy%KLK(<-BxHk%s^NNadW z${n`;U)LUSJxlL=n6PF&!@M0$>2+>K1F{Dr4X}C{?Gt-&RzGX~ZQYEfEgT|b zUD4mxO^=Z+_EVPjkxjwD_LwDWyk!9|C8(sb__P4oH?r;7)z$SKuR9kH62*1+V%fEu zu`kvvdz`ue{s{}lz}X%x@OvHlY!8vxLtNC`H(EzR7qZ;Ro!&Ebl9pOGD@JFo$;B4uS3@B@B0M{S2G@}+Rb3A&+ z!f_%-eTz*SBK%Pc&lS8)Dm(+m9(D!#_iE4p03ZNKL_t)CU4b-UY>!k4bM~xn5%?DG z%ZL1V$;NS_gejLo1G@n4&4+xVWOKo{xJxSbn9pAt2JQFfLoNk(ux7(qMqklwuM57F z$RIzM5Bck|jqODIZQ150jVJB?yq1Q3&J}#7Y_m%$Lf>MC)OqzA|5uKKKT)OhxQ&0w z;(?V4|B^-i&XCe$HV^!_fbCJlAAi9{b}Pz{+6?^22t$Xnc&Fbyth-CXC)SZ&C9)~ABRtIaIC;BJI_5DXi2L26@B62n$+^2|~ zb#dztm~8@UW5#S`9->*YL(ik6&ChNv@b&}yAq8jlAEiM(Z&01PAKi(4@-Bealw$^7 zHz=D`l8s?6_S>ef3(Rf~dz++@-D}Dtj|uOZpzPM5K#CO8COun&BAo_6{e@q75NBmX z{_c?fb?Arb9vPq`a+nYU0Bffx?3tneTyTW;E1PX(BIb^QcuAz9Gc|Mo%{Jw=OjNPk8!6|D8Q$SE-rGB z<&3e?l#h0l6f{8Dm?b-toVyLpl#gYM>u*8EY^;RQidNi+v3Bjc7769M6pQUgu4O^e z4A#c`w4%{>A0HoY<;hJLEnxNrf3TWah%K+qw_dy&Nc%>=h?>ji;loe0UI1@k2v1;_ z*DqwtE{dRVg)kqXWDUztBRs9?G<@hdFiy52h@3V?4$Kibb%d8*uz%d=&sG}0_3}DO zLf9K1Oy_arfJK;ZGij@ltwdLWvW;{tAt)|cz@`oJo!9iF)#sbT^5+N&EBH)t3;q?0 zP5l!nxs>l8JWx~83IM80S(P!NzuF+c69V6|5>WO#QHRH!i{=@i+qUJ{vSlkX zGZ80G9&c4*t$1Ufzeq7KK0;aOa=&BQ67Id@4!&{xIktyBUb~<$8BkOKmCnZGhxl1* zj>5E-B`$Z`+F#aeJ4r6i15cSlds;+_6 zz_%D3wUEY__K!+78=WWtUV05nwT_l8%>Z8<%JRN^$kVP!{A$xQ0NV3rSsm>!`?rG+ z(2?23J0AK+j=BQdi8yE4=j)q%Y2Td>`JnNz{a9a)pDG5F`ny@@MEu6VDr=mGuNemK zm%p6lw|}$BsuSRz5ftwYv{!dmMCox`U-xFkAAiy2m+lTIebv^?*=~hbH0zaL@1RwY~}gvZjbm#&~lhmu6XCCv5FQ5~di(l{SE)a^1+*h|gqn-MPK zVV?QOVH&s+IZP@^-GZp@AXd3Vbw{gCF9Ck>amKHVvt{B4U0q$wK5z^E_D+-cvp6TG zxUi=a%b!AcVRCJsGd{CVd4j;V_)iB$2z-lwsATEp5@-8f;aP7v`Je_4w8(g%t3l!HDcPs8t+@ZJ@cXxMpFYZ#@iv&t=clYAK-Q5Xt^L}&h zH>FwKgqMDsNzoV}#x&iidZNb^D$BKaa*v?;4f?X6_m)TE^Xx?R#2l z&eDDMzFbMKwrzL0XWp(^Fmwid)vu-Nj7{D#$~X6rzJ;$2eYri%xs*$f6n*xeQf@Q` zO@)7&D#xm;uuQMXh9MU-3Kv|8uN=!5P~9;$02KGMBSZ+ zi~NXY!Gynd_41`^ro~%u5s|VdIUP&+ytqY;Pu(vDWx{;Z^){EX)2)@8_`HN=YaI5R zrwLN^VotQ@Qil!um<3~;98rd<2@zkIzk9b6Ks0S?EEPW%@aso%9V@AFCO1h!)=-bc znIRvg7{ZA>N~>hQdTi5AuErn#1z8|pNn#2U-d?} zV}*fX4(d?_-C9EsAIg+QAsPgTF;igUv3xIgy_?4ly{9iJ%xOxZlPDzl5B^(lQ4STY zlvb-MSR;dY0xq~?6)=~!Ayx;kenA%`=UX9O+NHq)xDs^p%3EY1)uW((}(adK>5 zJ<($#)Lc;YYL7oUHWW8Xlie?xe*o<(>`qNDIRhHO-+RFG+^~;#w9&%2i51q>k_3s3 z#BU!ERl~n+M}1P=eIuxa_Zq@3nf%DS%7%+?4e?jGhUp})IzN2c_V<;^cK4JSWYct- zz!o@+-g^o(jYns-TO0-t0Csnsv*#kay2pQZ(DVpW()#Ng(zq&ja2vgGT-7{ClHige z&mOA4K3@N8TyEz4&fg)5ZYXrs?^nZGY~B=>TKBUQkF2o`|0VqookOU^cC5jCl*HR;xm#w! z5DLSWP^8IErOS0Gql~Z09aVJpnrH0x5p=60SQW?_`0WEf+!L`_9WyeyJPXH} zj}MEFeNNH?L>5x#Q)Jk`k$`scrdKc=3z%~%$CeV;}{rb#Mz%=4DeZ}5bNiq+t5*M`Rtn!OABm|K@7h3f5( z-kU!Gd!GO4BBw6w$}_e8(}39cYHOK<1pLk_AD$o)d99aS;FRl=%X=+v2A%5gaQv-%%W z4MM!lP~3EA4p*MVrH*z_9UrYUO)EnBKy5bS;oNMcKaxl@E&aJf8pEx zWYHV$93)3Mwcfw=wHr-wMqCa3mBdaL4o|kl)cK8+guolOah4YY^GvI47^&th(inw5HhKC#XL7i(;(l&3+W; z<8rYOa*4HEaJPD~`ROMQ1FQxg={GvRO|l$t-Cq4lNj>08tdADQjkpHEzKyqEqpZ3+ zbyVha?qcg^A~nc6OQlDb3d2)Njx344{802AB?xNjP(%Mdv{9GlQLp5i4m0=S?Qiw0 z=wm4kS0;Hihx3-Z?u9RUsTWmE7XbpQfq)Q`AH+u@ZojgZS<*9!03rOspMy-83R3In znpcQ2Nktd2A=0+iu%+yer>%K5ekM_dB>`lsdk5=Xcx`A%0R9NYzx4;A1@PD3+m1Ai29?Lyn1mwm-DA- zd&{$?*B(I&&;Tx z(N?nrI2%DF))U>>7o5j6z@JzD#U9JV=|}QnkbOVpVA_0_s46! z-$*{eCn^D7_;MwWRyiH^|nb*zj#}hEEL4qV0bzHlh-e- zQIg)fSxvws6NoF{eqA07m4bHXfc|_tz4Da7ggVnjaW%}eCy6S=um1%c5Xb^AtW|o) z>3_bF#Z9XF5Pu>HsmM%~_tH*B2ojK&{5l*@mwTsie%VPWiAgKWxfaB6PV?J+c%>Z* z|E6?V%x0poW+mI+fYCkX>%QmCfM!6ev(A%h+_?8(9{Uk z_aUItgytY>W~tx*xy};1qJ?RLx*c9q!puTCe~v$m8H;iT=`bE&2#@7HC)T2wuYAK+ z`UpJh^mijX^gjecA)sxNi2ggW|DJBWQe>u^Za?a`#$)r3Rx#zfa}?K#Lz9Bb+TM4@ zzs)S|%?duA&A#bh9DRKrzpZaHHJ6K2eCIx1FIj1#q5HC5Duc=E=&*zTGu=)nnOrxb zbXz)A^6T>zEDUr@pa2X;$+yD=F7sVaw9iO*pF(>>;im=i55aFPn993!4m&dC@Y{M( zKy$gD?O9?lD>4m0pWh3q$59@h#LDB^6F#*yby5ud_38|*I?*d>g2L}M(^X7qvUaOY zo#wECFdE}yUg4<*v$Lzv27s5kfG`6)>Gm~^c1}EPZ}rGJ!WvU=GcQDxT4G@i7(9ff znUy-ZreCJ}Z5R&xvdm5v9};D%n5pN93twVURD7U|&@ArvpfKc&ya<%1WCsV;_zzWm z@~ia}4rlpdc*Ad1lB{|*JYo^kMOJ6xF-uUw>Vwj<`zNMV*8@Xj>B%mTc4kfA+|UQN zzg@#G%{~4ZoS(-Ab^C^g2iJ#XSuTH9D-~N(=WTj%cchS}`f{=M)#+5I_|Z2`P3wUw zc?u;>6p*&OfOGTGit!k`we$XsMrHLlIeO|9nsd5V zGNbVMxY>a$O;zL`oC69!Y(Une&EkodT+WnfhWd1?DCSUStae&>-OJs#OXDf_d26-# z((^Q7Cz#j(nP`npJWiLco*#W8S*O~rkN$p@PQQ0Ke8ir%N}Yj%IM0fh`1B7-*rT3V z@&l+j9r7L=@vZs>M%yX&im&9Bm!mE#~L3(0U zF6TN?)%5o6YZlg2_G*gq-wV!YliI~lRO*8CCMifcbmPpz)%@++RcMIPR{>1ZgKb}M z*S&&8FJf>UekS@T1i302IsUSXTVh;&(#CrMZ@_uoGvh5=EPpCq>2Ag`wnxpO37Y~+ zeAw46T{Q-vGFnV%P_FL!QtbNxMi;&0`&Z9CsxBY>ilLnMNy0m|#aG+DE_ur*`uG+U zUL9bp)V5f=N((vew1qHbi*H=VK*38X3=#D@n)z|98dJu2OnmWU-8EeyzYMUVc}rrt zSyhGF{8*fJeIBz0#c5CZ!eyT)Qr2v3$4+0OKh)_~!W9S};^*9=MD=E?LIvVhSdzv9 zElhj7r?;3Zp2iCeD)Tv>TBA(@kUMN$MHcI>%Dxv&25gEsXz*CVR`A2v6($&-Tm-EZ zbElt7-OSk~kma<&3Fwu6Bcw3$TpVNfkFzfeTWxv$qy8!!$+;Y(Nye4%CQW!l8B&sr z5&FwNS|Vo0#jWCM9;_s47hDgXa(#WH(f(ZPI?rLn8CAupzm#8$H1QQ=k6?+zP)_U) zF|V8tzPW`xd~M&~Z`2r#h`vvDszJ7BzvNLO(^J&!euqiuC!iwKt{blse(`G)%f8+y z96HYkZ@+7#2_)of$6ct)AaDZuq^ir_lzF0WDgHQ&nspszir(~nLLc!zC&mkicpw`* zyAYg!QKzb)mr>xEfTIJ2iBmObo11Hs4ekFCl+XCq_;PH`|Jw-?g8$GsZ9F7Ncqmx7 z4l|E%u9&KatcEcK8|M1!ggZK}YYlXVb-JkF$|lYA;=);beFUh;F5AK3EEE67PO&Q!;5Inl(6-3qB_S!!98|@z4f38pbp+% zz__5uK52jUXKYku*BwV&DnV>x6!g`OT$6j-hsw{`E%rCo;LHF(2i zoCB~Tmn2rxrG<}Nw?bjpEMakncJVf#EdqQ-!AZ@u9Sm?8H`LkeLen6e1WOO2edfA@ zN57Y;URCu_I?ca{^mU8;aul0&JY=$h!)5cTPZim`k@z zd-M~p-}>}l^CFr=jm>aHZ7BOXi?;1h#M+TLF1fb=S&tN6{0aFR5&5l5KHV|T4YD=j zqwbl{99pfrvzFR=yeZv{(&W0KEgAKw^vca>N=L3{gq~ULWz_Bo@>DLmDxav zOFD{62zMwC{IZQoHn_Sr;j{Fha9~xT+Zqb*Vxs23m_w$DI2w!(FF|m^*!$~bQnVnV zG4rg#p4D;Cm!2lXT>H2`&Qa%3^1jw?l?Vqsmm57RCBK)8bSQ&rl}iKr&{m2@KlQWss5^6{9m^%-pLQcA zU*IAyMFWs4r1@SRG+UcF;)^|%X>=DueM2JgfT?3F2djb(3!-l=>venx3g1Ow4+W7+ zZj|$!Aq22ti=aTVjNosnRp?(zO&EcM@BjXc8j{emexb8k-Cg~&$b6mmNV=V4dFA!l z6I=%;_SH7R42kRKZX76(Z|Tk-$`&d5E+HF}6>?9xLCpBAUbUX~Mc57@H9vmx zzk#X@f%$Hqv%r49_yEU$DzPNoGVAz%4_Q1?Kwpe%kw*P5hoI}-Y1?IGUTyyvi}&09 zF{>?4e=|PS!C3x?i!Ix!gN;gSxzrQ}6f!1$4B>w_v%lGO7#XtUZJ$0o>q7kQX4}<` zW^sD5oam!*ZnF3%V5+MZIqq#03*|4JbRD(N+iCC0zRiMdS~dL+x1;TyobVq5e#jCE zO5g3%;0;9A2IqW6hK{CE)8kcS_{_Z3@rLG%)y)UTOznM_kJFFL=>X>_MXF=9Wbf_2 zw!`E&Ai?(pDVpPGp@e8BE!JDLSCj=Z2^1|>sVvoG8!OYxjZo6_&FW+~D&nvDBnKxy z=W_-?sS;`X6b1f|KYc!qNeK^s6t2r80%u8^#CS65T$D@?rkT9a;iZPXA65u9dDQIh z_Ag(!EfK~Aa|C7wxk*?0!}*(T4KMGX`Yas|(^n5^3F~7`UGp5O?Y?OBOfOq03n#$U zBjqybQcqza;v9)xUMTdWRS)KXPY6Tj4|5<#I8BR*6+D*75=eEp;Nj->Z+3QNN0wU) zqJ`sXOt2^P^_Tg1#?Vzki$fy^i91ZV8r?=>+Pw=x08YgsnO+ za7hhK73~of0I43Y zTl#E&pj?45c&r(h16MdLEi`6QLzaA-y<%Ot`ZwBrh@n8st@5R7c^ltUK^z*l&-%~o z*>KTrGJ}3@$xLh3QR-|R?BPkP#h4FA4}VVRwYTMs4`_;44-n6Plq3SGtQ-q@{G{%l z#y?kNV@#D&L7*pGN>2Nbg) z6C-9TTJz4ZfUe-%c+gbsP!^ReppSmU;w6Rd$2 z64mfnzcuVo3SQdU?qv2FDH)3MGB89JP8me?j@Sk3MV5AhokjWX>Z-`a^*cdBEoI-; z;s_z*kT+xrJ2A=C2JB<$iURdI#F$?#q6GPRYbF#Hi8W7g@BP0JB`aa6SsN<3RmRYU zW6W%Ec&pRhucP@bK>_{zNKBBd6obI7WSWqU7`WEZB;sd}Mk`aI(6d9Pz4Pe#Q)pm* zg3GlD z6{Z2R#iC|EHMy$;Iy4!qb19))b&VZS?o9ry%d)}TwY`r zkg^)S;#k+>wYTih8HGy~T;zTVxxA-uv{79cp2+||Ts4;Gy$285+o~Fz@7vNku^?w4 za&+%Kgk}t9wLJNH*%SM15l4FOmhtmE%%ky%5rVrCuD5-KrQX5R&$ras$nZxh$;?#O zU^s8N56wE$N0-;^eDVh12x|1)b+K9zb|)v5bv;loUZk3wsBKaJbI{l#%`7x+zfV5; zuU#?yS09n^uWhp>_3$qwU~!Z?8Ee*=nEY137sl^am&63aN|1xIR!(VNTl9oSPd9L;@-U~lnLq-87{l!W#G2mLNov;(|>>Arq0{{f~dwo z+Pk<1gi6TO1S>Y{$5-_!~|3tWc zZ6B{`Q617=2q$DIF|SV@_l;#~@gn!fn0j4Xf&YD7HKiKIio7og&bsWmGC^nt6qcNO zz@FzpN~Aop#-J=EvNb%}kgSB+bG)dImA~wZHXxmTq*eohu^~1o2D_ptX+gOO>@9q| z6&DVD$NJ}?eoLO!0H|$^Oa)l^)l=(Rl!;fryEW|UHLOD7;j6ndBjPD&EXhU85+4i) zNMfTa^doQZZO(>8mD*Wqd21*IHviO0A?kzz-h?+?qzeBvhi%KsgH|q|IO5SnW1$&$ zRYYax^LX{t{>)JG=pdS%tgFznJ4e;)9L^zwEFY3U*oEZ{Ty3(4c*cI^ z>j=Myc}KK;IEaEY-V!$($6-m%qHkB0I&zh;73+74mXtf&BD9M9u0gR>7>jYK_4fqr zexGT`@lKAZ1P?g`itCMC^>GZcMcei$ak0>;Ja?!+oA!QL3+s_VxH$)n@ibx_4dda! zt3lOH8vSW+zJ7}zG-^??3t9@@Zh7Y?5nTpOTV>1CteX@NBqn6b8$r_DUYZbNf^~X= z!^L*%@cr1?NYTZ0ap!={2G))Cx}+&7DYY%vM=mjqFJaShf3JoF=?H=rdFc}U`8HR$ z#3j4!ZJgSe=QW0sikh@VPX+L`ak(q3Awf4roJIf+5~wAggR?S>!%UHl(vbjaphP^- z>hu}7(%p!o-e6_L|AJj_9GT-ISKw+#dfC!LF6jJQlnb8}lULi23B~*~wiv(OZ|=4ttAQxqhY>-h@ja?= z6y9TT*LH$5&B;-zMM@9f4#T zkrn14^Fm}pcZ=RQ9OkD^O%p{(D$Ts7Gm=e#H(am&(-O6;r205kBTW@1!Y+glh5U8s z>w|Xy5?qg#%wkuB@>r)v zO3HXN3QpGN;-=emOUf`KM>fj3?7@H9_Sr9wh*Ee*I}OEhSw+#k{P;c`9|+6!1`BCJ z?l$-aE9v{d|C%WiY>)}#T7B?~wd9F7MT`%;<@oe1b+4YZEiJk&e>mPBA+^NLJnNq0 zPD@*`8A=aHrJ74BOFdbZFqPgX*p^Zi=X+*c4a~4;3oc9Vkv|F562!n^iFl4i z7Llgw6R@X%Hv-1$7njiUtovZ?@P03T<7thRyM7WN^z?cyd(w_a3SCn8OeBb0`j1G~ zYop6s&usxI<>b_u z$W|-UxDef#q_gE~ELNM&0oA*jMsyVjaLnX-qO7b6iT}prw>>15h!L7$C__r?Rc0^n zpN{FG`!fhvk1%Js!m@kDm_X!_5750LG7MIP%?k+U1VcYiAgXs@s%L9Z$f`0peN+vy z;ITcZLTHZ8s-0o`3Bzv|p^n9|j)$p?$2YLzPL0t&k#RhcUF}@HoTyvbbw9U`6{#t4 zS=g~BWLorf1)s$N;G>BXJP-%!b&NVoKPDZmN8(@ zFkutsA}3yMo%O(_V&#n8u?yO$5T5Ax>DLl<4$C1(F$Dtyd|+fB$kw!@!H(q809&)! zMNKE&Rt|*nl?NWEI<4Jzs^P~TLE2V022F@Tn6(3c;uRmoF<`K94iV+1aq!oG+u)%{ zNvit}bZf!YjwGehVhkaqTKm|iXf0{{JQklrx8)H-MZc0!c>?oLSJ%&?BMbrxI4mTn zva2mGBtGIJ`#s%XI?$S<8xRb$eQqT|)?S2wAC)WnX?fR;(It~JT>bhu$J+L=I+{~_ z=Rdn#B`kZ;QlZi0aYsC~_xR<_B-oVEM#6;9@6XIAfJ_e{l!&&5e;(gr*-Ljr^s>XN z>DiHm#LqihoO`8PgCb}DvTt-N+iBsVtHGe9BA*>E$0G9R)7wPY zJW{Y(k1w$S3j?=}ut0ljr&9$+dOJ}Dr%pr|OL?+O^;nYcGMx&mB>eGYx2HlIVTI&z zYVuxikBf=nIZu3ZtyOx6 zDyT}dv3mr+X*#<3xXfnACdyCef01dz>Km;WQ(8bKNW92DTR4pQ<>hO zDjEuIfWH*jsf^k>bVD-qhKBP$Z{Y}wTUyQGgI z&IG3-ztrtOreq(vo)`CW{NHD#yI@0e_rxL-ua5K1H$D1SG!H*P56>(PWCFCv1KL1s zf$>Mug#s=I^F|?UnK9Xa>-+;H`Nrf8$2e%jGLbQwD!;uSKM{&H@P{E1f<)c;GT#Ex zvQH0zxOA~==xP)UyX*%?SyoB5+!g^hClWv_o@~N8JTEB`#+UB=u3v!@uP6!pA--7! zb7;?;L>GOOV5MyD3mEE%@;hFF{Xdfv1+zEiB421q;s^wT5Ub%|f-X@XI*|_LG`Rzi z|Gy|z+wLzc4j)Z=H%`7SkMn-~8_VjvuEd|9)`{F5d{#L^1TDm!)o3)@P^tMRpH5^Q zuC(6P4D|(%j@|-7Z;=?Nu)~uqi!lF@ROkG1YR8zOpuL;(Q5hM_k}vaTHuH19Kbz}W zM63l0<0$I;>q75fNtP8IIy$ad?t{pe0v6t}B)?;v5uU|1#S{`@D5jWb&^vur9#mTT z>k^Xv#{D(W2^H2mCxzBw)MNH|>fa#t&exqcBp00UB<3*H-Z2U7nlG`F9aD!B89O|K zWwAQtVNS9j`W0=mHv&O&jp@CYv%K|B6Y-zEIw*j1h#I0`9H)rN_XezK%+e@%_?L&< zlEm&vxC_l_n)yijj>TFCULB;tb`wuIBxm9+`hVV;!#L*dwC}epxg>|ple>D$f2xoX zg(t87*Q)h|qk@$hdYIvU`i?O?Z3kuan0Kk~-T{V7pvYmE{ivkP8kk;-PV2^)3?<8u%=npdq_H8p z?vjq7L#tj2;NFl4nC~KG`94r$v(JwTWWW}fj z(<;RoRNWzUS?jCS1D*xnLXi$*qr7X7nkJA0^O#9B=-={wD3*l`M@ex_L=ua3lo6{1 zQl3*%vii=?1~oeb`VD+>KeP}^Ti6|g^vqPXVE*v=wpwBe((t3SLk;))C}b78GJ?rC8Kye zZa2IgjZI{~e%F0Pv8-mC>l?IvseWIbola>Y0}I7W5c=_;A6Wf<$r`D48i~_(QzR`v zJw}I8J|-+t3yh~U{Z`FLB`hu@gMlWfk^cAi3A(!31xqo3aU<~)bMQ%0%-G6OPKcn= z9QTv_T&spZ)RBNjQ&1XzOn%c9M|K?$6G2Mlp5UI?uO` zQlXE39s0K|o$3IeLK`{@!!X3~wwJ$Yvn!QpI{cm+usx$G!@M46*JZ1o5}|wPoCk3R z5td|YBonVXKiq(t&76xge_XL5ITN{WWqkBR6Bv#>K1XEqOn9=?u^ag5{puU}R@f72ahO=8e`I_@Jt{JI{8WkXc99B12)!C8b#VQuRcFGK~rtVyLMJ7n81!R z&AfimERgSOmUJjY?KRiy+$23n{^IpxW9&t(hZs0g!XRzoSLTXi??6~}K3+|t*E6AH z?1lVvykIx=G@rv|q2F8K#v)4p%juA{5|&ySfxpc-i&rKTP_sh5yXM^j%Bnb zR%ooRH=WXmE2g5_%L#}vj7AK%Uwt8{qBESbsj${{@ANU7(>U-D?s<$C9*mD6sbKA4 z`vH?a1}jlXlz7@ifJD%aV*;5u>f^xN>TLf$Z5r`Bxm@Y3aF*nskj!JWN~>P2QRg{M zPN=4pM`#Oz}DfFj0Y4u zj?l=PDKHpEe(mJ*Y{Jg9iY;`!Z-$KIIYW^aHg4h}id-Cf0OMhCSv5FMscZK5xCm zm*-EHIl;FrA{&6Th7~0pzQ_lIw?Id+!+(q0_HVqB-A2jJ?)hG;Ttv+i536~f$nGD4 zeo3nn!l-oPVZiH2u_hup5s7xIb(|LFN>?0ZM0=J%qe+?GB2E_=(mMdfhxB^kDMY~2 z-k6UeMti}~9-2|EqKR!(MpwH2D37?#)Qx;x^>Y1(^AAC1yErwq*iGCz?sUJ7Em_}C zT>H$8v!K>&*XbemHwOt50118NY`dzb2W%gG22LRkXFN;^4uM?uVWO;H|Xgl3;f|FyGn z?b1DD9RbJdx$5|>eQ(#)3aiyDPC}kG49A>l!!OL5VdK0U-9PA%6Z39)S@p@5%>1Y{*GQ@DE+#~*Yl1JI4w^r z29JAGhDG|@L3-kkn{NP{1zD1qMmrP8xzVBXZY)*##iZ-tK-cbAV55!SEuDhs{%2wA z$ZkOvV8%Y0C-|nhg2S!!`d#VZbhv@+JWeOV^1EGhhNe{pf=b5GolSKdyYgyA&jRld zdY)v%9#z9DR$vCJ@+La2cCU-JNx_NY2mq@(!gH;s!kphp2sa`l?ETHx1h18ryf zMh9`7=@fwa?}Gn~#voffe!{g~L_@@=e6M!9u=VjNWIHF89ydQHeR>>#g;TW%A4!EfV}6p71?Cws?b z7n_?&M#|xATC_l>;dH*%T7_M44MVN}nI;pLTeALnx`iXErBNndz zBQ%VL4tIHD&@KGlscod9uudof^vSKWQ7=jpzAY1gG>*m*WDsFRc7!j8OOUK(S!KdALNt9ByHxKT>% zMEX0WWQrZxy1xaJv)L^2+GmV%$yjKw(#*W!_6O7bR3IA-u#@$ulRw0i$7h= zAlM#R ztxitB-DAt^tHDtI`fy#gP_OXo*yau3if2>kiFQ38!kb|{C#~4dYd&?}aBl`~J17}7 z+`gQ5tRZ+EG1P1!RP5& zezm=k07NSqfFqCJ@-^?l$nZLe4+}q$Jx0`Q zk}HW-U~JgZMb?arkf5 z1B<6OTX7Q2>EbOtW$9V3>n=pDXhMLW4BC5tv|j`FM^Dr@l-4ki>uS`~k6SpT~!FpNZ>O4iN;1{N%s2i(J zWViCyQ+fYY7fwaCky+VE;Q3ZTb z`$;Wpg>U@XKZEBXNi}EFGp`L55K%)OQ@M=CN~q8BN%d&R03PUGYPZ}HFgzXb+xM}X z)U>Ftlo)NG=ZcK@#cWLIIcyZ7Ot>YVTCC!`3T!-NTjJ#WWBE8a|0~R4Zbf%JiMHZ0 zF37%jP#NJ^nT>DGmPFsDugEGPXCPYyAf}#cBy$4-C~X}Aur7hU86@ix&BK)WG1FDkW~oAba`k$xa9wJNx{*{LV7H}A-JG>SKXv-uL6OW9!hQ};LA6qNbb ziGMQEUyq;{i`46>Suc@NE%h2dm23Oo%fd7g$h$QJJnA;?RKZ&4-lxpVC28tvPADqq zTVMYnEYUG~DF2@LCzSbZ-v$aIQ)|IL)(yZ?>J*Sli=i1L2(yj!H7_`WSIH_eQz22M zWgVdzLWp&o)P*M9m{y84OF2M)#swCy^qhlO7kdXDGk zb@twmb24`Qypq)Krc~eSQ>vq+HJ=9<=t1>({k>gL|yn%m>^=U z6%GVTBvX@%-|6}cg=hx9Qc04&*4Cr~#I=L&B=Y6AQj~tP5T-&1z1TS7F7m)f-Spww zJZBq@RKQY?pNPc}&8GPdK@l5%Ha+|ZtVE5RcreTyY|ev3`)*PNv_ZQ@&jD(R+o+{i z%?O0{auAy_)QG!u*qG56%$lKDvfic+i>N^kj%XuJ&kI8H2S!LhfUgYyh<*xjNfu1! z&^O~GHL9(`n%se)_sYJS@V!-e6=bL^*!)O74@h@?TQ{8VW6Ry~hl`zmUVBPXNXv)1o0cbAc~vJAaY?_U_tmRD0fI91}k zHLV%1v>tKnWvPxL5Ay<9OgjjT>KGA@wzJ0rf*25BJl$}z+a89+BtL$IFp2&q1ojLa zNo^qK>$X@8eldNSDo2KTgeQw4u&EtS!!KRomFc~%lv)3UGJA#|qQ|p9mPPX1%K+=h zan%pg*bQ?34KjvkzrKMO!mxE0VhBZn2g$)C4CUdgdrKzA#8fVJv4meX$8+RHPxkozkEy!(1Wo7&u z()O6p17hcJQ4|9_S>$^hyKbAGPi7x6n3u!sK|?%xe~sPUGBrbWn7&YzLs^KgMp3x8 z1>yCzN?*?4SFe2=`qBD@?l#1K#n_*SM6f*~4^00m_KI)P^SC0Nx2g=J45?EOMuTsTn7>BHTUi=|;Qn+RE(o7VF+(aKL_>1d1d*_Ei_*T; zS^y=tB*X3Gt4^gy%QuF_E6`7sFDRd*%0`>XII#sKn?t28ga*Sg*X7QF-tMrY`=Mmh zS#Kc^FTy_i;V~xl&6i_*3yzHCqGY|7d_-y*8pLygzS$WrX6z|b>R}Sy@a;impqSM# zEt)2R3Z%m|T?M-xl2*0t13ipMi#Yhk7O?G}fx#T(#06JK+&{sh2PlCoc-(zD=3<`f z?ffTRh>gz8p%l#7fZD{7eQB}5p_PBFZE8qPq!*cNFOUZ6;nV#&QcWZ6UKj8uHWw)q z|D;gR5MnjpB0emYUAYd$`H%2dXT7x<^|yFO>dU3VlUCuGiE*;5`10@xPohsk1 zJfZ<+zW~Y@3T_O_AUmSv{}K9>x3Cd>K6MPBp=E`mLEL#V)mfxMzrK?0B0RLlXpg`3 zwNQ5O{9pp@`cDuUGngP#om;7QkcY5akcK<$>?)9{E10@HXfbRlX04fpwEg4H8(2`q zIYCX!V?b&NA+p6X+c6H^BFbkMmB3t5i8v2}PndqZCqkM_> z_LIe>+2jb_mrz#c@NX2KNv?SNAR3`8s6T$|ihcQfl5j7tj^_#F3@m4i$UEB?2@JOD z6{}g0H9HI;b5{*o$7X+87y9&%-_OKq!QQpB`MD*-;N{)fphd6AWx|kB_(7^-au@zs zIT#+GquF=ouMmpVn$YwEMId2_kp)vYWL@WMxR%y;ccoMRy5}!2i>k@`skBwkGjtF9TVP7Kyc?~%N zYJ&CljyA6uPd{nud*gN`ln(J~wN{rvbH+l_*N2Lyj4b|Lu>^;DLJOtaz`$(=J)ZWA z8nQudw6*E{IAKWukNnzn5U*^bV z44+OH550HpSWbzhe`Js}#5r>t_3%4@@%WPyTzb1Pay8GX8`>*Yk+O?%zg#d%4LMLY ztk&=?=@?K3s*v3)2OSc=K5n+glx@K z$ON(Oe)%u3$iu2{FgTJZk>3c>poy%*MsK>pR-{22j z2+#S`F$08;*gg`KeC>5$=0D9O(hD_EN6}DJ`ZQ2lWLhG!@Ff)v43R5iGaLq6BXdjy z?szAY$vMWSV**77=a015YqsH{OFe+KaOE8@RqAJ|#?Zxk*-@V6AK*sh&bH^e>cLA3 zlEb+-{!A(~G&flZ-8VJ}2P=<}QolA#=L2V|=lnT?xc4MrFfFHm71Ae5t#hf@>?}(I zkVYP#o~hCVSSZ}-Kt_fSZD7a!sqJ#^9ZRlH3)qOJhJPN`8ho8i_T+D1- z*t6`k`a6@s%?H0;Us~X|Apa3Nr#n^Khpg>a^YAprstCdB`vNX*pd<#L;NUst zL~{sWZ|S5!8amoFbQ>p+i>J3BRWnWjA3K4Sh#cLUCzKPWHIZ??$ZBL(7L1B;x#LYFHT{-Z)Qf3f9DU{`$@ZPNV@VUW4pG_oW;hRvS{QQ|UA zlG7?-5P~eVW;Wg)_)M7w&0e!S*VMj1=J5BnGVpEbvI%WSPI=Pw&WwE}bKZL^xKnez zyCc4}XzHuAxM>-WlTx>dXZMa{_L=8q%Hrm+68E}BEnm*$d%eT~lhBO@Ak|&b`bbA} zma95}fvlM!2Qy@1)&EZccKzytiJxU$#6q2`$`;X5w2pTq96*iyc3f!cnzs2~G5j{n zYCwVO-4Mn*f#QvUpovcjfxY`=Hx~JIOK~W#QiU#`;#MgCto$DA6mK>1+ndK{Vi)vp z8Go)h;Z+-|l|MvCeZ+#&_b?#*Ow;URsPEU%qGf(ietY?_(C#`Tziy@s0k5vDSWj;iY`(!ms;Q ztplGs58`*utT&V=LT(t_YOb-z%~dhwO3m!9yMlj1QN@m5g^GK6_^=;p?;h_``w<|L zv{I3^Vs&?%{T|5{Uu~PK-?624VPmVeWYT}I9^#2GSXvUk{UEO^nL^LsFTGEA;P|1V z%U?yJom_-t*j~l>_$mKm^QPmA@X3{@@hi$YB97<}fwItfaxvdKHjh4hBTs?L)@Ni^ zEs+}jkVLs;kd7-ebv9op$7ir3)w?h`cxpn3zyC3~TPSkt5AcpLgM1=8^G;vl=$%72 zGMlG49X(}jXNKgUN-u}0j!yhb9!xI zJkpNCx_6R5H|t^wSy*sc=deCWg2Rb9sQ$%5>pHE6Yx3V7#i%P-evT1fpA#7QnhWfB zFlRwzl=6~b6j{~gZ4TRWcZKH${z`btQ*d-wI8n$Ja!%l@iCPFvcEbzwcS@+5LvF=} zVpy6{9ep{$dd0kp$EUh7(emH$ z0aW!@Rr{q|=Pj+~wyk~QTLs5ebR#k+I^)>}VfOD{j&KsdM*q!^3<~y46o3PE-@0E! zq=70phNXDSlV4d$7k(6FLFu~}Vn+hbhJsG!yz7-7&+`~gD_78>BDq7}-K1{9BeSM; z8_Qku&m&O55qEH>@h8|N2OZCiF8`jg=^uze?o1a$ao&TXt$zLKw>}UP3C_5qe!qu> zVLB>E>rP!WXPzQ6u5NwVc$ccALv9Kmlx1tQ^Jw`_;tqQx81h);znOL2CPNQ?Bu08a zsL*>P6uSUot_xDjo+COdOChbcykwd#^m^-UgTo1L;zboPys2F@^L8sqYKxVG>`ybo zRlVfX7>h>uV5_|m$}__3E{mpoiDi|dG=RC6aLI0Uyyw1-CmiIx1OOL==82&pqzRs1?F zBe)ub@{zi!{a9=Ag#LTk z4&>DYgiXLd)?XwL^mX&$;esnpm2eK8pq?buh{cATX&PpbZ!Yrdsd*nezj5;bXfaCg zIblkoa$E<1^EYegYBb?@J;2hSr1}raIc%i^>dwG_l{r$nlV)wtIPiHuXYZUF^6VX; z_tC`u>QFDlkhMP!IzL6?iifM(i5~nt7jS5oNX+|3x#sI#jby?(bJ%O&M}-92?M{{f zU3n#?xnm63)UWIe1`gsSQy*x7K2O+w=AfRdmFG*=1%Uw}9+Cd==6e$1CiG}TyO|?( zL`QJ)z`{ZqCp~2D9Qe>pxT{_ zB*h%QMV;tVYi>zZt&qp=K8ik3e5(K=4iUHa>jh@14||%6y;Y~wNX!v!eiTy(u&Rl|Fd2dL;P|k~|-TmHI5`VUOytNkC|Ew5R1Y|Sl z{P9KRtW`HTwTROtTV)etZ?KSvLk6b*z86@JrN>bkhzg`fl~}YPvz0Ekw!o_WEa+7wecu3tI3Dv^_SKUGjtnJE zxjyKyEKJ>h%_itKBHAtk*-=zI)Qh3t=cMN5G301kY7?`-`@_aS&JER4E$Jo-w@f6+ z<#c$b-lvZB7fsflxD6Y?vlWlt8=_8OeP<^+8%Hjh;K-&w1siKM+$yT1q^i(xD*>Gb zpX{>wBXna&V?nwQThSULzhwCsvgx}skie6v20PWVFr#eL`G&KQ^TV3am*YEx-_Q#8 ztiFqX^^$QS?ku5Y<}$;9U9}-mrm+|0PDJC6YzK8yxuiaY{(zC2=bcE{VZrHIvnLQo59b!G3i@r=Bg3 z{Wt)F73@nJ@PZXADWy2q@!)z>#ycX#@wDWWx{`d*fOx(isqEe$*TbX=TgGhRRGUkT zBJdAm(ludC+DIwNZ#mM2^SwdN--x6@YC@-E$}hfbq37Z&DcJfgoBbIa*6oj4+AE?e z%Ms{~=kW0GZD*y`=C3*5GP_S3sJIqb5O*A)T6@a&+K4Wvyd4lA03@vwiJjCMJ01$I zc6uF*`R=(Wt3kh|FD8tr7{>z_RNHLUOsdgbr^qx_=jY$)c+U4*+(DF38jm9zg%H(k z+_n6R@3Kk)FA=t`8NEpFQ!=bePdYrnW`Jv6HBNoc@i)4)@2cF7WO1#{u%14-5syo_ z@&0-6F3v)zZaFGD9B_M|YQ^vcs7aq?<{Qj)7x4*y7VjJB4$1_o>W%_aYMU7lkXgO+ zs&7s102<>t|;wNU*nv@K~MLr&c+oas?m!UGu;e;uG-Tb~iTV1&i0WO z`nq01l%>C#qDojEJ1h9I;2;bvOXhB9SSNVX{{9Yp#>xbsD~$kTgo)#GP8(GxwepSE;UMgs++u$oB(ZP*FD;in+j<(!s zC8;%JYP76Y^|zYWa(e(qAQKBnUFSQi!xXuYx{s}p$3PW*@z1#6eKD<_=}niUWQWq=S4&g$uKDYNrzv(RDfE1wB6pe6Ol4h6TlMK5v9aYXF(hPC!e zbjYa2zF@qYA0Ffgy+W~SS9gqa`}f|>1}|Is7PL3#yi zO$KHqI>J4P>XQdHWBXbH!ehknad)MTzXm#2B(wPa-jLO<`Y!fY*(MB-zm4L?lW&_tX+(_aXsHrP>oc zQOk)WTZqxOLQbRZ3J=|PjmK=AdYVGe@Vp#>!qkE?(9EeM!rYv}Fe|~um3_}j%*)26Z4*V4!;75Ih z_HF-RskTVpehh!M!N*4Zk&tTx*;-9UV?fv#_zBWqJL9upR{@ugzi;AO7dFq)Y9`@O zA{=MePRa_>OQnQ&^)ua*B{I)3J2CqzfPClv?a2Wp2jiwVk-#UiT~UVC!+;@chzi#T zJI_v%t`jvoG22|U?aDhQFD%Ktm}q@^e|xMHLzzw9mzs5dfo$Gq+zr_$qoM6eY{G%AJ2P@B3ck$&9ByLF@PV1 z#3JBAv1k3;XjHY?!ymMfR3=+E_=w;Y3)&72)OMGJrKQ|lvWLsS{fcVfRB;h(drt#C zU*a6m*{4~&_}$U(R{PW^QbBGv|d{mXV0)q@yZ zcvUbwS=OxphoDVy;t5CCqf~L;s_oZGt=>gj$urHBX9O8kLz_8N&KAOCeU^jkrY9?` zu2u^-2b@U?(7$c4<2!e6v#~%1uzN=NBv75d$G=MlGZ67AtuwtoKXOMu1U>O$&83^C zp(XsM|FNZ5^-;Xnc_;H0Mssd|>4-UbK7CXWCKoKec(G%hcImYJ_8=F{Ayl!w@l`-~ z=t6QdYP94KvfBWj4{AMEoMK_W&K81}L_N?b@@9e`v2Qc%n`KzG`sk8NPc-oo!5L|v zo!rA>N$p;+nYguf1J*%&G3s7GhWKcHy!x}n5V0kVIe%Dk--QQZ!-0n4@di?DKSlP{ ztfRiRa;LX8to_m4-EYG1J9hgRTALT>fuPxWd#@j#q@7hrwPH)HGxb_B3})L=mY5{K3=Pf>)nF> zP2AFfGXe8>Nc9T>WJ;+=`S)tc&WPi77bID~3_z(e0oHgvFG%j%MT>t+Nm8oE&Py zjz-{%#+_^wneFujal_jw>EjMMFR!{Y;PYM3WB+gCo!r|Uoz2|*Xh)>uO2A{r*5%qR@BZYT9erA1?XQH8c)DdegpDg312_TuzMh~FM)!EAXlPu%^UtRENG z!+giRA6dT=)ig>Em2R>+0FrLR-#_b>u8n`td}tuLRjKSm!Chn&Z-u)j4Xo0;l)!if zY##A=0uGw4k%;$B14fJU2$(?YtP1qHJ%wZoa`m$0N}S2+TD8g6;6Rs;`cX2a(VfSK z{KLal|1vo`8k*D)NSa4We5*+yqn4O~`ak02PNfGqqd9J5rK;f09ZumJ2l%mPS5s5V zj=QmQ$&j5vNW+Bg1l3M@M;>^$8r)7@ei8rOl}y4rWJmP6z1gG}mnL({LdeRMjIz-7 z1sXS0jWzY4h?In6KOs&?d{)8brbkfXQ%2)gWpI;esOaL@qzTTV^jNXxKj=jqIGvCw zd+FEmmDBJxOi&M}3!3e7=VOb;`g`)!kn|GVtKuv^U66uSFy`c6DfyVo;#AF}c~L#4 z*}~J-7Hc6(WlQ8u+nimXY@)1{V^GF@Iw3Cjj`m9XA}b(vLDzw*>y;|DnJF}qnmq)j zbkTk($%SkUjDb#2ET!|cCo}XXGkp887DYwpC~cIHY5HNc{<9A&+X9+wH%Dwp3JvjL zlwhtz(8n0aQflSyv=-nXwW$3HJI+AdTw}K*EiS?o{;eS0nu*tOClp(abfdn3hJ(c{Q^8MmZJxH4w9{r#1s=Yl)JKuENyW`* zp2(gMNeg?4)T#C>BS^odurJD0ED2;Lk}AnnS0~rPPJGcv|K6xaB*2`0rLgRRDYl}@ zrGWCFjUKN;w4VgmmRXNMjTZJ@o2f(nwZ;%XI0dr>_H=2DNsic3mjpd`iBRP#ok@1< z8s*hdEPCNheeti*hmTqBDXJaRX6-c$+xDFI-fz2=sKTo$IM^?*;K*nE+R3+cqRwUo zDEp}IaoVzFA@9j1cPg`>&pqg675W39dq^mZ!{@yt=rai#BVtBGKIxsWI2E=Q9oe-b z*}vXj$AlbDheyuU>2dizlE*~kE8T|}TX5aO9+a=VE*UobD_*3(Dl31g)h9lByc400 ze(|W3ud1XVoo5YyxO>*XW=~OaQ!~@9d+q;c0m`S=;*f60c_?ttamNNZhEL#YflxqW zGh+;$5G?x?s?X>kq1RpL-0<3R5I!diyQgtH$sFT!BWR!H}yV;Cz`0m{8-VJN1in`im4qpjxM$|PW= z`|>r0H~azLVfJPD#}<5B;68`8V2A1mzuSyw_Lcm8M2zgjX|dCxh_UJ;lK<>(>Ol9f z>q|ZzgZsltV66(Qyx8_w3tq)|w3ItReGWFzzBl_E2~Ac! z?R8kEXYvtnIU$dRvah?+8;RL@bP4sa#L{zja3R(KTBx}Zy2=qO?cN|ynD^#i`3?jw zIE`H&4LtSkXI05?3M7Y!vqhL5BDNi$iEidlz)x}stEXcRVhIQA5eKok7f9<1|6{yqc zM-z2uuJ|$<8~&ZoS_4j3q?T6s$MP1uw^>6>Z>FFv9m8J9kWHLjm4u1DERo{8LVT!r zfBtmW8v}bYpeqGzS8W9AK)Pg6KRaPloArw6(-F_+f6l=PXYrIlKOPDSYqCBSuVWv> z4R|F>wWY$gq5Y&KfA==)4e>p5SbutNx(}-%#Oby&=@MtZ22$S`Yb0^GI^ER9MbYIH zz9;tv$k%=r!Y3bGyI6WVkgL_u3hStQ{Cy;}*g7>WrhXnVF?Q0x8+=eJxS68)@`(%m zir6=3&vRYi`QBA8B23aduPqOf2!6x=zGl5aQ3pu12%PyVOh@Op`Q?#Wg~>Ng=A!{_ zQmo+T`8n1Zp4`qH9QJ3IZyyyk6bh}+gS+lxi!dN}lc9v7V# zi|}?i5o`sHYydjLZfIKZGs#b_+j<)#w2860bh2V^!nM6gb0g+%e2CP=39q&mc%c_5 z@vHVb8;l8rpWFU1OdZB!z^yBQJoz)x(9p+Mom>RrEt83E{Xga;@58hRxAV-pq`END_n85DOLZU*02gAE`jurUK5g%ZPcphg9b^jfQ}gZLFWY-@u?3JVTUTuA zK&m*hSJt%KBRL{iW|)d2O-M=O<1(J}ft&NL=U%uqNf$t{8GLlbOJ|y4NSb~~f_9ST z0UD}lo|s;UD2eIRR}lE-C{>iw?^8_GF;=L`SsPb&v+-FD9sSY5`Cuxx;}nx$O_fjs zxSEM5@jBQ@^g$-G;4-RaX^pdk`CFlox=;|zt(?V+G(e*(A0>do=~(yY1HalLkfa27 zx_;;zvlkki{-2iGI3A4SZpTK{GU{{yH&fx^SGo-+@B{-o=Tm$<_bO^?3LLK$>bk?V zxN{cya=6oXxWSt#KM=*Dppgg%ho({B3a^9YVTX&d2{z-=wfUjL#^jAMSwa-5n@z1(60*=lZ*AmDyCiz(FY zgrrzoF?m`sFSqV%D0W;vDE@@QOb)9zZ*}R~s|0>5TdKu(*;GzmDre%5&n$_EV$^M| zgmXrmmrc(D9iUdai%^8S*R;r4(^SHDj&Nv*YWr`xL_d@nFe|T0b}6P8snA>5xEuPn zs9%@p;c5cLNEzm!@t3n5LMhQQJ`d(3g^@@6O{@AOy~2K)XQX69Pj@udC8y=A3?GQGPj}2SQy+48wm1!H za?xP#Rvnb1XV}xx57Jsyokmggd(bLPHgr)(4H*1sCT={+mBs07PNb!8*6cr+NZHC( zr4OlP0{&UZV8iaDxrTvCxr3-hAM5WO-?^OwtG^jc>VS6$bnNzB_V_fd6|eUV;RmSDpYts!pKP6I#Z-9fVN<9^?Wx_aWpGPvFo1rz$*1dk4W!$$ z_3Yw^&S?Dx$qk#ku`WtlsQMyYjjh;W6E3Kbe#_yo>69aBYrZZILx)HHV!b)2Mr3_= zq?94yz0OzbZ-9X=!BK#bl4xD2q=mgh_3a3#lC@36`p$DsM?Z!7_9>8#!TnrJY^Q;q zw#rvN>U#j#ldfX%dwCAhv=)n>6QY?q(SgPSYO}xm$OQ4D+l%fpc0SdX-jiqzAhIa1 ztI7@jn&}>I_6MK!^cYBKo>u9E5K*C)|26waaM3O7aB}-#6L)@vZM7$O2&hX9O#Pwl+#R{AEcT4W3?|0m& zUi)|c>L|^Wx7903zqfrE-s6DuqQ>D$;i1R{@}q&wI1QHbf`fx!kgJQnyq5>*x2`Be z-iswN8P~4aKnns4?z3p9zdi}-y5B6NdSbMvOi}g|m=tjDxlGNW??P;r32tFS8-6+C zO_!WKS+UEWCyMu7)4vp{*QP$)72uyaJS@DcTxX44T28nNPwo`oRDfo^_H#lUS{IM1 z_q}(Sylfu73{4mnElBG*rs6E&2Oq(j&Fh9i)%nvEI6ZX|wf?<(mNq?T4-DPoF>S9H zTOp6|e~lV)^}_Y$(+kfKOEEY{JevU5ktM0ik>vIuo>ZR^(%YxJGR z-A7GQl{29|e`W?uD zds;o%NlAB^3fZf~c8-A6tCWFM!ljad!{d_r4jaN$GG&^d9qBSlCe4djT}O35`mG2y z6S+U~dbDy#<>H&mVJ<2{=|s!8DIO9qUMqT5GFYA_)_K*2*#NW4%IW#dHZx60 zjqFlFPe_&_Os&iVg_{dg8Mlyii>+*0!P}3Hu8@BqKao&$xhYL39rc#R@Vu?vxWduj z`ol#>*g5c8RGB9=A2dJzmCQ&riHp(Ltl7^&NtJ*#Ip^8|QGl9&nB=QKP33P#rEQzw zF6)xo%*2x-={gz6g|4IT!aB6n&e%jNQgPRIgzBotY|EN8@#Wgz(N>K@BA>C^GGz+1 zznMN7rT06$MxzzsCRe47JQCq>f4O*I_hh zCokgwJ*{E8j3V8QO*_tb-EwDZ6x_ z|IH(Dt2LN6J)|1-ESTSzlD^vHx5flDN$ut?;N-^y`G0qQdpmnBKl{uWH^eP2vKKq7 zrWQr6U}YDTyO_G(x`qf0 zBI}y)r`Lt{cVocXD_!oKtwNL*bzyaz@JMiD8QiuGHg~48SF@n<1`ni;HBQ<1g*da$ z>CE?Mi(;p5=-U>m$vY;CUYJR|0$wFaPAE1n~WXuY$%L z^d9mpn=*J;f}hRga;U@^4SAgq^^AMuP&y^pJJ|}QLhh+}T zlmIo9{~sOo1%0xf2QEF+vV-Huvii1}f?VZ*%thHR4006P&6gFkD4)@C8Rtyb!T>c6HctCn+8H@pzfxw`<_rpT2`b<6?e`65Am@S7?)<& zVfts{wQwhtD46nYo*Zh8W29u93(5-do5sLpgj=Z`Z<#Mua7M~vDqUqbwNw01bBR>z z1WwLC!HeqM_crTq%BSPHO5L`nvcNDk+3U?NjrCr^Idl8zD3_vz0Z#n%I#_GczH39d zSnEUt+C@{}b#-rBNZWr`^>!=uzr?7M5FFxwHW#x#w$$I0er>EwPe~!6*M;@A7_?F z1cq8JC_08+j8!OJAt+!m9CJ?5uYAyQMS`r{SrLq~c)6h`CskW!si?iY^`jXf@au|j zQ6)}8cf>+s^nFY%*pB|BF5C_gn*hE`W8MmkG^{S{4$sY@=*$+4q9YB)ddm(&ef zS%-E?E0$$oz%Osmjci$~`pH_qX^*yYWY+V)3xxEip+3B&x>D8VVPJ&phVWl}i&4xd9*8Do97DCbHCmz|6T zkm-Y6jBK`;$lGiGoVgoW0f?{l+uW)E)H!!Hpf7v~c%<@hx2(0Vo>~OOUcVc+^lSd9hpDTYEMfVNlBruyl@Io*+#Y1Vr1aWI#4I0H1uoq6tD-v! zw-m!W*h_u3GA^ZopCPHP3CMWjEi_^mg`QE7bpW@*%+4 z`IiMd;XQgcIeZw{M*jDUIsJT4{x^6W#tk4jQ4VMu-Lr(X>JV)vW@wxAaBOBF9X=r$ zI1yhZcN{Q`kuDJ*UpNMDA0Xw4G9_CrIhi9Kzffu?l7J1l9~vLF6ZlT5#WZpfiG?~R zgX8`}+NY{!oErC#5s6i98}pr&piIgBsbp$+S++6eup~aUs2+$FWMIprIx@B*+?ywq{u8NXAp{u-mIp)5YN~73o5X{hf;N|Eabp-uNN&Bvym4=^ z2>F;b9D>$DpMq-9v3{0v3%d8nei5?&a~_B5?$;49D~ZdZU8+T}EAE2v(|8M<_hOIZ z!COUY`F08Tqck+VPH?c{QiO}V$dr@j)I1ZV1l|T_#2x80h@s5DdxSSD|EH}AVVoXA zU*h5yWj2kG$IqLmFSGIm_&}C54{isIb{BWF{U4L9JvxT>uJ*SQbgwf`0g%4ku`73M zS;BLOs5}K~poI)xZ3>MlRSanh8I)}p`4!gnP-(R}aDFJV4GVlBd5J_tHj`7bJD%nQK=o`9(}=L8Vaeoc?H2c>A>Xh4R>*tfb^DuAfK zV|aC@sPds!51IBbmy|)KREw^Y+pw`^Te2T8 z@T6kIDQ+G)Co-oiV~{J;qXgUWOs#?HaS)fcwwE<9cAAEIfUpxmCOW|~P>frR_UX#{ z2HCSeQm2(saegHq2)Ly38(|R(`n9!pwGtFVORn{0NnQa=!Uz2PnTq$QT}6PP-!h*v zL<~$W)|`VPsx*Oleak~KwSagq{dst^ihL{TTOL4YYw-m?cfI`HX1~Ef^zb#vSDw<% z6V_Kgex*FQu`!J?X5wDh_rpH2|0qvHr%4?PC}U@Dx`QW4i^j9lg^E@E-*Ji0bE_teT*d;#Glgk1md$Bj|Lnq_1*-k#gFzJOC% z``iS!l!#|wU7j?|;$+kd)s~*`e&S_(&h^vel>v=|&k1Yi!@rwOU%S5qcm5T}PulAULf?w`k`{w$wF8j!chZj!ZOMUkA>-c>I zzCUNn#QY}J>~E&5tM;==q{iNFEk#Gf;vr+2Q_(H9@+12vk?I z37yk4w!@Yaaz)T7)OTj^@E(fny_vtH7S`7H`MMa)E$E74oMHO$2*R4u)Mj$~#=yP( zB{Q7Guh~Y?Z>;?ns1Ky8l-k$zN3wB7A&qaxnAJURt<$hY2T5d_S9e8BPrEjmkBZ4& z@C}vCzO56P2VR@Kkn(q`ndy7yiw%PH?}s)brn!2iv=CmGAJFqb@6Y#My5xoVQfi;vT#Dqg^fWj|ZjO|wK2C;?DfG9k=Q{9UT`gU`iVVZ@P&c84)zV;BV@gmVjJC6_?}j1+ zPr<}TO#;s$p1&-CBnv~ssPb6psGzXj&-JdL9#@LccmV>ds8BL+TlSx$Kv4xe3)7RELCm0T2>!n)-DA28Vsp{{JSxC^8gRlt7u zJb{$$eE>BdM_q1VGrqR0r9V|+g|QHVJ_jIgjM;|YJ7qqcP?3x|>E5cu9>8gtp6&AN z<`((p&t2~9p`IQ&I#}E7r$i9Fdk&+L*{eu+BqO9G3V&l-C4dlCPx@l&~AlrR&fK#{YW8do`wSPSUCNngpIe6fTv>!R^82tX=9P+sy7p=K7}dAYs6o4{s zk_@`Z&ClfKzlh6Bd-yl2evk)ONnBjda_NvHygYXKanJF#-cRyL?T(uFdM{Q2Noo9d ztVyT71CBRFI*C{QTNVl#)3%%mDl3AZIdaK)+R;EmUteF@WH`24KexZLv$L)pcGHAI z?S_LVMF7u#7$F$#Bo=zmhPd{@y+P# zu%?ms+Oq_6nV(D;v8szhq&&5=iOHU6GbLOpN!)nIt}|#d^m=AYehp;hHjtwoQ(u^h zF-QsL*pQ$ml>Fk@=pq~aqWddsRw{wltJy;Za-`#M=xq|66WP`?3s3aH@`Fd;e7!Pe zwRjO5Pdt8f+B1#t3`u+OCjCjYb*7AJjOqe|gW4~dyj!K>KUEfb$NzZyAz4Z*OCO@Ej$v)t7Fs`U`*`xU{ zPvB^6OyL+{<3dh?0sUVI#05TeoGx0=)Dvrh`H>&65pf3h#trlI2NRMmT% zMJ5JQUni{+c(^#w;Z66Okn$8j7v>$mtT6&f@I(wA9yJH8%^W0WAN$ z)|0j9C;Gb4_kglEQieypLcC9?s+TPvT!!)9u9xGq+PsUi!*Wh5%#W%M`avX%zbtNk z+6jQLq1>j249?9(m}>Ko90EP*ku6ps^Zk2!nGv}i*9SIg{4#r9U)t!%nb>L-pk9A{ zd2AqCL`B-hc_5-s0|}93EPcbh*q7jczz#MT{M&A8OR>95c0gm&rOqy_H^@gpFqJwI zIMRF1S(!yWi4FC7eMvsssuXkm!JedMb^Nce7Amr4zYJ1)n?RDSw`RDXEpl+(Kh>Y-1oWxo_)$h22}fVK&WA}f z?7ga#a+YWaadM`ClQ+u~J(JaKNWRLc&MyPhLy*I{_wysBYX6@FaDIUW%KOU7MTJB? z-s}&?-HvaI1z6qF+EO_p(GJq_J_a@ZB81(gG|yLZ1K8D6VD* zi8FuR>RP`q_P8x_V_)_v#Ngloh$i!9bK<9yWM1~Bcue@ce z#YvzX+ebbW*(*3sS9#>}U-BeQ?~Wzd_80o8(2IX8&YaKb*#;Ri?P$1KiE22N$baepEFZ|Ln_BmIbax0FK__BSR@= z@!WT-n;GHH9iwVY!ITKx*O<5C!kQz3#ura#f^S1ZanC zDzEML(zAp%X98zf--mAq^6P=()EZ)LO?2c{MkIqg_BPewjd*lQ*}qI234B~|`%ffT zs*wP#z+}(7J|1F(qnp%0pSnQ8WLSbas+!U7Wx8A+EquL%*ozs7T#F=5#e+%!ihj9*HpEzb_d~-NrbDQjJt(Is!Lh%vA*0p&Mw2ouCBc{Eg^9LbK?MDg z@O!3?znZ`;kFVLhv%#~HiskmC6k%0rHeW#0QG2ZTRcT79WGY{)U@&Cd)(}dc6RXEe znG4hGCoj@Ym1Ig`t&V=aKaOfVnT2a6Mdz__v@^$K&DYu`8b;x|;tP@}ZPRG#KMrp4 zjtCe{q{WdArQCw_%Hor9>**I^tmdqD4dnc3>ioVm&2=x^$+~KSGdi~8so+)yp)p<3 zCC9I(J_m+rqH6R4P?@Yb7gY!T7}(C)rV6cRe-HwN=1<$RvKdoo)Ufi$Tghm!8!-Xh zGlNzhC`~$mYJGO}#O4j>=FNUcnSDPD%=t^|fSOOrG*_T^vTo5hHgK5EyRx?i7M5hrGi{CZ8 z27$hu9F1myD%bpNXVBUUn@*uoAGg=ar<-kXvr}R#3M*=XgT5YBbbm@5r2My65|6>O z2B~H{ES_>2M)wa9Jxw_m(W7H~fRvssPI^oMV`PfqbyJ6v<(>?{`brEs@D`!l3R2!VVmtCTukGo(w+y~i_d*a zY6-eS_VBe_9Lhb+I*W7us&jOQT)c{E1Wi>ewa(+Mc}urfI{GFxwRVhnv(8N9{bA_O z!q!W2HG+suFE0cPENkQAVLX?zkovB5%7UST`E#X^xBth-9 z22H@4oCo@)ByY9yeko^qzrH-$MJC^~bet>?P*7;y*Sd2UtaU6%>LGAOxcixJJ>}SHO(j@q3RN-m1gfqN7gz?EK+efYJ{JGYAf{hMgCsfOBv(vec~GeM*j*cxg!C1P7n5RqEe$%k*($Ah{MzF>Eamv{WLNl6+~yz7>D}qkt3mp zj9?8hp`<<{>(_wUx5^-8+h3g62L8;yN}x+W=DL{{A*cW5kf5ik3>0$ppe}F{IsIA|GXmKA4{KWaPM6N{+NR;sbuPh!2e*kISx}P!4+chyvPG1Zv z)NG)`pRtfNwh^rc@RX|&a8l5LiH<3^|HVozE>F3X{0g*ZcMyCmnI!;#*094NtZh}V z5(k$#k*ZRnW$JL%hHD2fh`Je6HlS0R|1k(B?VK3g)u4gHB~;I`d7#az9{^(+DOP>4 zLj~g@UTa+^**(-NhqT^0_`{$uUH$yZt4h&`gRbNU&7lH)Pi09%A@#@t?l=>TJ9u7| zVHGAW-?!%Q_iv0X4wf|jX!R8WZSRk@Ra`taFNG4Uz9oBp*Ab(}6W7v$v^QiK>1^-c_jI@PUA4-n!0Q#J|FhoM*5bW?37&!h z)zUe^f8hPi3#qV!NgHsQnO#J;&s%(Z((hAr!O<3{0VtfpeL;V2M&e5zDlL<@?s}<6m}Uxz|M^5d zcnlGtrponwkbC(hoCk9H_KrUHZ9oL>Oq_KM#xDCK#ee+5FM6)0K5q5UT2wKi9fE<%!Ucuq$kq7i&@xvC$!hr8+ZOy* zU*UO9QIQn;JL6XNr|)=spq%mw#$fE^c_}l<@+{d*t7D(TY9lTdo>g^IsV8l3ePwGq zaPtONFLR8A*3|1A1{SI>*QQ2lniAiS09ui(_W!;cPtKgo&Yz zVdr+%v5(qD!?^yhuf#pJf1>1Me}e5`9fjFB&0akdp*(-Z(^IKGyL(Cz9RcCbs-RaCb8McvxaxB1e<4+`?Cl(Hj?Ov|9Qg#~lfdgQelE ze&v4Kdi5^GL7g!h%1s2F*G)$k_T^0Jn8OJfG zWGaZj{#ZBzk%Bf1X)RD5pGH~>7=?9!Qqg`dC=1}54SchKHl0LsQ_Q*=!=}$BYmUcA zaJ}6}%JjM0^!dEKniD3}?LLGPOo0jB$&ci7Q z#(%lY_Wxs>%2SIfyxiM8>?1;f*|R@*`)47c1!mmGN=Tg64}TpNy)3CKK+&3)#rJaf zUXG-2h+m|hZAmMFvOVe1OFkbLPW1RuMa#?5mKHJL5Ce++dgMM4bfiIAxYfHT{nHG- zsiRJ|TCDm=c-Ot8sdd;I98Feq|Sn<#Fnj3?eoZyp`Tby#`-daK6r2#_E_mf9dKiLDKkB|s?0jGS1Iw=6Q5oMhs}mM0#c zxZR!cM2TbhOJ*hsNM#Y-+OaHKRRXn9q}0>`QjH== zf+X;;boKWA@v5pDAgFx-sJiFipu6_2e*Nmbci+8t%gDTEPh4kwx5m`Y1j;&kR{hu_ z5uB{c_?|MK<{56gW)kaZ!RXk9V-t+Dm3AqOYrJ*SEc@eeAj;E$ zlDdXQg*IvdG24M6W_!HL_ic?Umf)_Jki)&2(c8N*sHb1ZeK%$B<%}CNn`VgYe*k@ zOHghxB#j+YL|O*me3h(kd)x{)>rgW!F{&S7C28u3s5#BWkUwm#~ro^NZAEL z5-({uyT_T{ITftaN*cPUBfRT!vJS^Q1+BkKwedAuBa3uHIt zqLnl*GbC5+d4}JnlS9O5l%lLll{sYzZZOWU(MmEivZ>`f(~R#q>m4hJV+$Nx&=aZA zS88yZQQ}fVamvpWj&l~xa_P=G19h$tm}|!C|hDHF4$cjrxer3 zbfn3;4tw1qcW6C~#(LOMn^O6*n#z~mQyC{8*D>RISU@iV3=R%?>Xon^wHop3UVABm zB4i`aV;^5Z`_Le}262kUW9Vf(0{G^w%YmsIxbizR1`s3e8U&iE8oUA$ys zcHYUd;N)0vawL`^Ugte4Vt}?~@?T@ZCZU_egiYi*ERUZL<_?Yp$Gs40#l18s)6>(~9crRes^YTa>=brq%Vet#LH4A>o{4eH-o?+_zpjojb^12ioE$Y_ zQ`bsFfSuD*m>YB|-mwcO)`DnQxUrN{ z)V?8wD^hS0WYS>EnGxhqo}jo_qi3}0O*~b7CaB}4>PVx`mXR24s*bQ?T>I??)FAVP zro!L2R8l(Iyw8RIrd%KFqTu$cCK;~Ik^d8&JFnCzIdLBAi?);ll|QUer;P^fH0_IH zC`;om6j8etl`s3$>(s{BAA5PF+X*kk{y1#2gjgx%HbjV*6TQ6~fk;?xS149BG27R- zng0H3IeGFVhYmdw7P1hl*GYB$aKyjX$#hyIvuv4 z!)kVJ=M0Indz?zjrNb7S**S%7>WfsfQ#($3v#QlHY0NRT^BltNShU@8aIz;E-=hYZ zs-x?evpZRza`|X#hO0_3k|m9QGj$erp5v|*oFNiq*EW^2$v`!mG9=d&p5_kPIdDfW z=gjq7nLEV+IuTYPAZ7uy36Mi&gspj>qr%kAig(O7+C+q&(P*HcbyIc5_xS4m9GDd1<8)tDGXO--T9dte^!G^y1vmw57~;N2;1ZqQn*Y+wSeqR)m@B+Df%#Zl*m&IGF$w`Lu# zGb9gL0=>n?*iWAKX{J`Pwl#b9n|Ji^;0h)h>|+A^nBbD+39jra@y6tn+;qwP+!ylyJUr1eSK+}j;?4o#8&mX7&No!r|! z()Hcy|EQ&MWc{1A_rDd%|GSR)Z#qU=QaYuPyG3nVI;|=4_MV;>|M?n%RK$fEj8tDb zK`vW}*Un{#*Q95~5);-1?Tmqdl+7+U?3Km90>2dtPL`@Pp4Aq)Re`%4Iopti3Ilah zo<;Kc+w5rE3BqFEZ*9TJz03P@e4FAbO(M18mHbu<4MhkI=P$828$LX79gH3z zRdE^ZUR*9p2@SJX=k5K1t>61jK*E+18avKTsq)}0i%EmT)D8|dhWWv!BcxncStNVw zw@+TpWcfyQpL<5BYb8pa&GEh`4{=}jG~??YqUzmGV_x$0Lz)&1CVW&~-dK8|iyy?$K-Ra`3Q`6}s*-`^_( zb%sxt*?IjG_PC&QPOaN9FvZ^gQpDWvDdl@yuKu~R^jwxmkyWy~TjY^-0>UC2EU`A(`1d z9%R%4#3wZ3B`vT%p4*`Y%X|ViQPObsjMHHW){gd|n>y8$8>nriAvv~ZoHIM85Vk-o zX$ZR$VRs;`&gZ@{5t!O}4&CfUD`}i9X>6H@v5<0k!kFV{Q)L!P8f$6rFR3VLYUmR& zq<4N{Cvj61rgqFA>~>~K8mEcz_|63YF1HiBW9LZ*tvcf^YFlYkC>G8ljS9ln&`L3c z9Y@%)Kr!p4Y7`5z-g)9^r3g;0hOnaN5wieOJF1NDi69L;mF>mT>F?_5;?SW-!j5%_ z7d%+gTL1gjXD@b;##oT&sdju))~HEkwdfI-kN2jSyy2}Jdh}texeA3-MN&1Fk+oZ} zHC5N|B`Qmi7HgIXmZ&n|H7ho?Wr`-t5pBP4WY-50p{0U`UI6o9db1X8^ONlA#4OCUL5(; z?h&tXVO`M9I4RJN!@beh2rI#n ze_4k;F0h_%xpz+q?59ManvK-q%zIpRU9pbK>Q%&@aUQ!m!hczq<_qm@2rG`8QluJZ>SDr*=$nbZ;>rYcB*vp>yQcBoCz;x*h*_URZIsL9718MrvHI(OpOk$uwr9qIq%c{;PKrh3tlcIU?d-w!RIPqn_ZP3Y zlz)BvC}K)k1g2^(nGH>{qj08(QITZUsbxk*lB&BZd)CW{HL4P$E-~A6b}UQDWTH?67BUJWw?4o*$I&=J zRf1~`$uHy_?jG%7vZS%id;j*GQ*1LNG2nwa=UI>8TNiIixjblz6|a_E3j4UgJ}!7m z|0WI}U*L=P#7V7jNv(0Y>ybLs)6;z9y6!i9}jLW1VWSwo0rg1f?mB%xBVM-{p||2~ROQ zrC~q*((hj>qG3jK_SFwzMFb`Un`+}sb4_6w@Pwhavz;<&^mU$<~(aGER+3218 z)%3S9*EFxIDh(iv|3$Fl6FofoX!Dv{t%zHRR{!@ly0(W@#igWaUR(EC z4m|vyu%7yBe(1#2JR?riXt_7O%2so7L|ql#GM~;cy0(YCPkY3zcdVMQ8Srvw7yV8; z1e+iI3*Iohfr;{sG=xp-3{Io^7?&i!N2=m7AvA80m*Z%sI5vADH?I36KRJ7b$&OPz zxo{(8Y0$0b8Cx^MZRIicSBAMgx{v*hn^Z<@n}uu`5Cgs4#EqnoF+)jCeg3?MK*H~C zNYOKQ2R$bh8GmSB1ZhOjO{JEd+BuJ(`Tq-Gi zq=fsCR9q4(DshzX<3hM|p+NiMs#UHn!F5UkoJ80(2-k5R` zz$33iD`Q1;CReP$W~u$L-v{u=fkLA8^^1_04Y8W*-7sf%Wnxtjv#o@zuQUt`Q;5}4 z`T4fRp}KqZW2utrVkT)@t62m903ZNKL_t*jvg;FD&sOI~4T)AL5;Y{X7E&}~i$$a? zK*NwU3PnZCj`k3d78q$!=8qyIC2U&{Mnwh$tsNIwalzi1BBhwdh}c5mT#<>GvNE<4g6x9B z9-pM`P)-GV=ZfUpREF%n=|hyF8X3_fhI6jNNZS^yn81igb~dIk<2rlio2uDt*XwJAyw4Ld5xR#X;krY%h=qJ@R)qG>Z+5l%i_MVKsUe8tq6^x8v@*n&41 zl8q@<$6W7`v%XsPK}!Vd{1o~x=5_vfWD8$3b-p>ex=7j9vRm!Cj&I)kIQu?yh&vAT zFnXwmo&8g!x?M*8Z40N)R{6-#qwKiqC||wj3^UW`xbey=kqFFpZs${XUrSq}jjOk` zll|dGAp*C2s-H*$hAx%t{cw>x#(Eg}$1Q=(IQPz`<+1gIAoH0t#^n+tEwPWjJonM4 zNvxW{j=l8bm8C)aS;)|nhxXxmYS!h*+36Nb_7`Ng{yN(ZSkZ{WUuFuVcgRYdF1Y48{J<;j3jk_g})gFI=yF zGrRVAs#%|yEu*BHbGVm|BZtSB*!5ZD@ByBBqo2_1Z&L$m#8LL(8}d3`qdn&-QT=O; zL?Gq5yy4h~m~d|-LWGhyMM=}x_xK^z54q|Zwf*5uM5Vz5ms0B)4TxF0qj`USsZ!v& zHJ{=K`jJJ%?LPRC3lo3{qp3yd(>&o{j>tnO3bdf5m+@qwT=G%YdL=WSePRlVpYLc$%bY3;)MUb-h1yo zL4CD-`;GMVZ4Mge7em>7KEzht5>)d#)n)9M;#mi+&{WSvEI}l%6KUBtW(j3`Y{*5+ zw7kBEuuWKk`9hKTtV6|+xI=Q$xw=iA7|QlI7)bKADGy0HEWuTS1Lr;L<_yW{oTJED zl!A6^CXN0a_EJOMd0Oqqj#`4pY{5TRojhg<62M9CubVnoQ6~mG<9#k^%p!+o061m| z?#b(XFRvpkHCXU2vzlhWKXdS9Zj7qbf%(v^9?K;^7hwOqwKB+59Vp)VZ0V$hx9SRFY zGVRTQL@Or9$91w52Vw+P#<{A4nba|Al3c~XiV93kr%*0p)Fqj=bXbrsvNo@pv=Fv+ zR}-!?B-eRunfGNK-sF+7k640QvkC!V(6cm-qExZ~AILeu{;Rj$&>gfF2LF5j^ZPp1 zae;MQVBVu+9rIiW`XqyYIDkDa`1o5Nrapa?W8=rD9RCI*KYBOWA9axR4gBu+Kg@TW zcksV%P4FkbcorIv`CJ-mkR5i&-RwXeGG-d{PMyqOrm-FqjQ!!km;JMuQB?twOO@q=TOJ@T~`?lQ|-Va!R^4-E3Lj@^8$Yd1s)Z1I=kxk%YoRG#C!bHxJF2gfKo z*BZUH``9$Q>vGuGRXu=Dm-5 z{{a%-dS8L-ld@$rl#){B9PXVhue71cWW(sMbM~`@V?)qS0dWH($MZL7v8cS;7fTu zdFr0O`CFk%2a0GaB*1@p_cV|x_jaij#YjyHHQ|B#) zL^ey>Y})8ELo(Yw>`DPul9H z1}4jrw<{gZJlTgsav;QO@(fUJ3SD${b$jKpd(paQLviSBSP$LL;RQ9In4R_VVTG

    OK})RKvU{QW*}S*e_Op%)2LD*qwbn5~=F91Tu+6^J;jV}4*vBeZ z<4*%m^V4r#M=7F_{ih$JtE-#2_H&%5mU!RL5eEO~KyX~+GD#s*B>yd)OgT{lTvYd5ttkv_ZT|$mdw-B3UIYe>^Nv8=5eP9sjWD!gDHRdFR zV@2}obT*GBNe6SIe%|+Bb)J9E?M^`+ z9b;Clk2+ZjwHz_WKd(tcSX9%^`|A_P_s)Er&$uTTJZWKVIZi^)lRb9=yQ7o4Pkfv- zpmo`-iRO9J>8qhEv79WIr!z=7gq$+=kx2PvK^aP$AY8iNxx)xeWEoNEL-M(=-A`xURh5GQYK2&J4b0XKen>I7hY);sbZ5e0)-RwphWpuOK8-&nsvgf?_APpBMH;b?mq^+eh z#p|Rq0w=qGlUqQ~x1pPDtLAstBxS>iTp?D@;7sel%=Ya!2G4+{&w~E`ZL02_T_7tR z3|Err@$zF`N#RV9Oi#K=y3Q)nHQ(V`99JZTb45k8`pVd-B?<}hH zjH)D8_DI<_J;b2{Tt2$(oX{?xFY~i3HUn3%5a?FHIVL_2N zW+GIGTugX2Vk^YT$4?A4Ny3LL!GJdz>|sj~MOhUCd?@EoN6}DG;QAIa_KT~STx=!%@|5DZ>9K=zcwzPTB` zhRf-Z2l1_FmBQ6mUAkVW_w!`yD5B3-WL5x)vOZQsZO8t%vgPK_19187ALHx4^F8kv zk-!=}3H;FH)jaBv#}Q#+_UaU#Dl#-H0#dahEIypNg!^Yc&VBk9n`N$7r>}1_h40+W zZ@ZOc3D>0<+@^l(5l?yB5EkerR;OTSR+61`ur6ENXB&zh;J#&!H8dwNW+nGj4gSJ4 zU<%r{43f}I5^Eeja^`CO-MQN<6M4FHliqcbzj^fWX1ix#kj814Ic?ya&LP@uWn&E7 zzHJ|e=MMAb6JD9@0}>!l8|pT9ph8;PL2ejAoKoe(*m#zYf9WKqv7Up!H-$0|jso+_ zp~&dL$(=#ZuY2y__;~Z4?%$B$%l|3L>@)4$a#sxFCdu$Znf+~1FlK;SpoaA)u*B6R z{(F(hr4V9VgZBD>@9F=bb^ zF_R9IwE&x+Bll`+NW4JgEU-kog!mfvuRg4`un#rJv|+gvLROVz)Y)sQ0uc`Y1^SSbI(U!=nT0s zP|DhxQn;9%I)yVuh(W$n*%`N56r1gyYIUZF6&C?1>yxyWmoW>F=}aqSZP_7LcF1(3 zmCALtsH~0Kbh55PHdvNT$;w1m5c7Dxlw2AWfscU0q$2G>z=> zV~YsYe0_w2r+*o{Q!G!|`eZQB@H!FZMja*{vL_r&-J~IGB65fuBKx_I<~gfQmbh-J zog+~9jurPlhf!9O!2Vo2-(vbeWjJ`<-qj@9MZ2Z4W$Q!e9eHHkVAo?Kh=he`vyf2( zN+8~7A!CO6I(mQh>#L7nOw%cyo6^%wIl}dc)JKuR#PTJMg#n!Fq!0zq%@#A3_afnp| zzx*bXNsb;Za`NQK@TP<~59M+>u=$&wK1VXy#@4M@ENaxf7WJNAe#_-DM~@a?mTPcF zd#Em>N=@#VqCKYu{HnH~QPQZ5_5|yrh9t3PoJh*0-m*Mm3nI24YDgL-jfNp<>=}oh zQ-LLN%oZd@dx(}a+^j=+&$zNY_Kwpw+Jk0`!1}miNX~k>x4ycz%@T-~^8zdwlGD4# zsij=nmibKUO`Yx~`}nwF_c-@>#O?Ny#zUh$P|~=?kj$lAqQJ?~9&X(|&W$^#h^JgG z**V3;9X;sgCWa;w%z4*)wxsctEqHY2S&kZWe7F?jgxQO3o`3FxV~-<^d4$~&mX>OnTGPr_;wG2B$0p3!!Ml|VP!a8p&rcTdwZ+P>oJ-_Sxc#A^w|mF$?GT9#0~ z(4dU}Ea>mQmRhYA49s+Ob#r)jAvjic)?v@gIGJ^6Y)xRel07ryjC5@Ywn^1pQn-|& z8W9u;JKENB-eCMl=N62rWY65VQpUC`Wo)XhvZzP39<_d9oP1IzRd?AlH%>;R)w-Hw zPkEd>54!S3=nrKpCf>FlUZsT|pu2o$j?)NxY{7XyhE6^zDv!UA&_z}p;WQg83{Zn}0~ zL)WeWk_X;E?b0*UE}f*ABkNlgS7|?RCGGpKp?&{0DwmyLVfbNho$LKV=9nA)7DQC; z?8N7@K!pe{9e63UDVG><=HGR0`_2LOp8N{t<W)yYzGa@3q0KNLN{ggC|ao=-8h;Rq3Jf;TrFW7f&? z)cjldKk-3&(izpi1;&ee(XDD@~5$M+&<4f?mX&MT?3(6Xze8=25uvT z`_7aiWh0idF^;2HPfsmN74##EiT$3@1W?6IRd7>rpn|X>2s=r!@H9^D6kA3vc|pIW zw}1E;#Oe&6uCsrAj4yP@5mpCUDT14-5T!voij3_*#o)%h_et-6)Vu5?ic>ye369vW z&&g_CU0o!T$=Ch3nLj?X+_Rv!cOzT3Ug6!VwwL@o2=VeEnM~5v)g6xehFGQLw~gN3 zjbZs+VR+ly-o_i=@CNGj`gu-{ulNJm4@CEKWW$F|h}8t&rZz0UAztWU%<<#LxcAJ3N*iQW`RenQ+c%d-d=IEWY#~h{XAKci?lpQ;D5L**u)+h^ODn&pLIk92Va{9MrjuPziq}j>8Z)T}*2aFuY++t0VC|@2Y~~O5!*9`N#IAG8FY@SH=UC>b z>B_Ite^4kBaGqvkW%nv`vnUT)}(|1y5}yV3LO>GC2+V!*n*j<5up z_ulRl234S#%6gL~C}^S=!*Iq38KX z>XIOrwiS8roW2q^zd>inJ8q-pK7aPo~ zKc8}PbO?)1Vd0!o%S4A25V8QWroJB~E%t8tFvxa8iI$Tn<};ygw{Kw#;ACfUa?=UVM2HYC2BBhh<>OWJ zE$r{#)}oLN2UJ6>w#H#21$ zQzu~wdIty2vplXCk~wd?PVZVaUBJ%R7?Kn|TjZxAV0q_l#rKC~ptAk>!2#Z!b$GKO ziCTj90PU9GQA_amw%~qCaNHxZ-(?GCfN$k>HZ8dazm=WfGc;(k1bucV7<0>9S=}2< zS~?b^h}v{UM;Z$(B4IttV}OCdEdc1IK-k)%?N$n2F6-?OAzltxn!swwgS9omkVn*J zXT1ErHTrpV@X|WI)ylG~tBZPPJNvGBGY@RMj2|jKfU_yxfG22*tJ()FW zvU7_EW3zJ(MomHtG977*s${4tl|^yVyS4}zHHoR|WXq1SK5kR5jha-Jn3}GR6K!q} zG)Y;v7-Y%<*fBw_=8y?3j4vwm^=%HF3NA7{;I%g%umpcvko#I}H?> z^r4)?kRiFwklbep{-%Xs_;jJjuVm7USz<+(-<6z6-)eW++CT6I=36Z;U&?RLLNG{k zl4G{!@Vh5RIO*g#>EyUHouN}$WG5YRlMZ=Z$Epg&MFNNP!+h*Xi6JF}Z&C#8I^E=5 z5g3}AWnFik+!+Vjy=O&S5woBO*{ekkn1gjXHLxAUo*<*2PtiEdN1cn2*W> zJhH?>-k6oxoq|Zq=g;V8$xbe|nFd7$7oIGhXLW3M3bH31OrYZB(0;$`lYGAX3Cv!d zL^=~(hu>!SbmBeOae=X5@xiuVpi|E?>*Uac#c3zYdfjA$_uV*?Ih;wgfBKCXc6+@|Ff#K=>3{M{5ll5B^IU9#SN+Li!**dzT713tEDnLxrEG|w*(V;ovxfid`Ln|r+8+`wsAwUrck76iC|sL z)Ty=`U=*1*B)1zy$fP-J2~K1kHkmron59^F!W*Cv2rrLT zy>CM|m8G#9n#IYTMp*5nGn)}s8+yJwP}ll!vS*OS0t16@Trt0sl|G;v;`NQ}jDw{K z%r#0dX?iCB03ZNKL_t*LnwxRRKMzv26-Gr;IC_xG+BCnP5b(qVBchD03F2>iGw(ce z5^?qve;>aRd#+Als)&^oWY#t75~C(DYLblbmPOUFe9X(7^>bsBdXO<|w&|FFQI$c) ztWlHXTqhu9v#!dY9b7X&w(L-tD=LMpN5onl0h_Hl7s zZfVD)se!6*D8$~KrN zSe=5g(~*Y7^#?gHkds+miEHS#*+ufSgYq*w+xYc&LaxXIk|wGT@JU$c9ZYj zv}oCQ7#b;uErdR;l`5Yk6Jw-dBKG?{yrg(jdadoA1OOKET|_ z2npa%e+NL)2E_8p;pfjABT8sH)6B#Ll&!Ew%tnPxT+dT=awKoO6a9$R?2mK`hCH%$ z@Y;cZob|J6{cT#e&u`SJNdr0$2g`@%)c4s+z8Z70WG-+1#^bt)F)tZ9Ey41d3VxvF7~}R)Tb^9-u~0m3 z676%rxI}XEPbhk|abFGEK+mgQ-xGc$4vipRHi~js_H$(`mSC+RgIw7tuo3vzyw2BO z*NWM$unqAtJP-VP=(o#MAG!NQJrhEN2=RKVN6yjJ)fLtcD-^F7F&h$EAufi2D8C~g zHY7v5(r8sqy<8;iYpF8qD-_WT$+RU%EVF)1)*)#~PG!4`LhlYZ+*-X)Uyr^P%7FXHCRy_k^wOb1UaKDDX*3@XHwoGLXrnDI1a}fxGfL`)t8f zp}0t0{J16P%j^92oI?dQH~)!3ky%4}M65v1Z#<8bb+RXLa+9Ppmm{psfS?t&Qqf9d z4rxpy?F7Q=Xc^>4B0LMWl>nd63Q5@zD;1gb%>m4;bg+_Qky^IDe;dOmpW-i1&IZd0 z=Zcse%7!>A9ZaE zQ%!5OE0Wc>AvWq#<-aDC0v1&MV0J+ft@&h=umu?GQpC*I%)wy4fTZ<~k*hhuAbVlH zNTz+UU9nx4VS%_v+rpt+%(6@Ex|Ezv3Y%^{ z?-8@hvu-zceTv)96#1gQc#=>nS=qEM_FZRcDCKLlWx4BZS3~T+6{z9fWZ@3qO_SiQ zqFBQQUAsp}?!QU>(I7dp3s3}I3`m-a9M$wZu9M@&HJ{`m?`no-rIM+8hzg6Su!!p> zrNlZ6Dfwz^f5cbWo^S#SWS_8YC3t<@JM(eAH*-5oKr)>nCM?WewarH-ck}%wi$LlQ?7d7q4})8vlV8`6)$4XlmpG*z{)SEza_ z?908}<3`W*OjvH)5FtXmp6lU|ms^R5zx-cz*P@x#;TIob^;KBmq=FDDqp|&BNm{=Q zzt)77YY7%iovno;3E;$%!Mmg(Ng9%}w;h0HNL-JYjC(|Cd`Q_GFK2rkF=SwI9I*ru zD^0|ZG<>_`oFZmpg99py))tFMSsyh+1~$j-rcUqk=*$~~l1E$K`<10WotZR`Sb}*&a(B)ln%CKt zbNKItA`5w)A6SA;?{nzpCPmf`2{yId<5r?pp^6-uL0BEgp?Rb+kHcxwt;DRYA&2Hy zOg$W0XNFj9u#(OCrN4h0SDr4BIs9FI(4~mi?3~lggmoo3kC^qB70wpPtW7hxp_wat z!;?iaYtmR#_we(PvrMe(MXuez_Vi^OKYk3ODj9j~U_h=G=870K8K_)yWrs|sB2s)( z)@)Omvqn`i*gc@Ejy?Ng>MEPoY||MO-Z9HXrGQH44AmqCN}+4TT2wiqeep$yzP`v(Jho|p`Y1kOav$1`7(sWK5%zJsH>z~8gcsa#vo3LmT z*0Q8*t6FsMngPZR9VGL{bU?^Dxj~vtpPxrsqkZ?=0hjraQJRWapPa4Z=Ld*g9|Asv z(@4`)&Bll_M}jgPt%GbMy8^;42E63}#AhXzu!sqZx32jVg(r%EwX{#PE?b5-Z|0US z{SCi$?fHF^+@vCA%O0Wqm%_%rZ2x)NeZMgrypDOqsWB&mJlVKz^465eTTVOd?NIH7 zIVa1UljBeHJU^@*01nfg&QOs<08A}IvUdm@=R_9gL=JsZo`G$H6ekMEY4x3_do$?C zJdT^gadV`T8HzErZr3Hd$v?9RYT$I`)a_lXZnb_qk2t-U@D+BFE-Q-BBf0DH7)plR z;Mnd7Z0eL%h1rgwXytM2HYe>xeL?dgbC}BW6QFHpImMKZi3c!y#5$LwhMn z+q!(|;EX?z`dXIZ<1K0mC$FkzX9+A=Fr zU0DYgoqIiUdJGuN>-<#C;myF)rq1y~k#|7IO4T)}UT4diPjai)BB%p{~ z-CU2b+ZU;20g8p=-eAZ1>t4+ce1HG7;l!8_s}7l-X1(%@={IuM^fX^RafYw1AHb-{ z;4jmi#&9K;CK&V-Jz42Mgg`k9keyc~OTJCViYqnk@a$9M7Zxz5Dr6rTL%-}AthnHJ z-}zzQIem`9asfGcmdw1D73<~7T5-YHxr0HDtWlK|=8NS0*R$%inbZSf*RBbym{2yw z4M{%kk+Ka*KA|rnWkXz?ZQ`&!yfX0qti$_6opn&uf86asLXlEX8e~a{1*97(=~lX7 zLAtx7ySqUN>F$vA!a{4qd1~vfZlm zT4^`Ys%hnp*HEv~lB+iRYTaeFu!$5Ezum#h!@2Jka@1#zpK>_;{KDyEQJMLLfv}^q z&iPHan_1=aE6$!n$9SjaK|hHVK|O++xLlt7?UG`P(VK%Mo(sDa-yV-|ZD6e$%71M5P%)NdkSe0)bWN>PY^^ z3aq;N!Oke zzxeHl2Dz3>B>U?DT>1*t*czH@*tt&Mv|5gZ8;Sj;(^A-`=76)mPT@CTG_HN7uV8Gy z)Q&#c9@4x8`Pf3pX40&l+qWz9GJ@5S#P=}wyf1&+6-xXQn)U+|vvmj8R}Yn z)P(Lhjarpwc3se^kHRH_f_~msYG{oE@x- zG;NoS1^&;HoK?$w_g^rh$GYXXUT5NGf^t!hOZ!D8{#nkk;USD2NT+kV*A4)3DqS*k zJrlEPh$un_NI=`2Z~f=z1VOla!mN!;P_H-ooNVCVn3}e5;s&XVjBYAYSX+UF#qdw; z?YM9Gd0*hMd5dqwf72!Bf&3wLXp!ne;`K4PS8;v!BC!hr-^%h(ph*j4v^7!6lM8-; zyJLX<*-Xq*n0*^(@r!u(_4iu9c$xE)EJ~f7W&zUh=5CbR8#^CBaRkR2*ADYW04@2R zYxi9ZiV|GCD(+ih5u4QkzcqSR>Ug8Mhb$M*>zw4FqA`BfMk&h1;m#xr@;$a2pND8v zCpq^y@zU$fI(YZ3T)JN^S~bgUT%J2MB&1liEceJ|9Z%um7ALdc)Xx|Ep7E4RQx9ti zT^vqvG=^4VXyAZ-DV1K)o&TZ=Lb!XfGeP|&Mr&u-AIA^BSnGnI`gaYdI_zZJw89xu zg<=c_r|&{ryOA`KaSKLMOJ(L4`!NefO;k*m)q}!7JUp6I5cJxDm%>E$0PsLW8M+`d zoK9uQ2WO(TymE0u8jaP6c{EZ>VGQrT;^R=<-pY7_jkI3ujz>K2yCYmrhXa!Ql;(P@ zq-a)HQrD5<)na>-R5b%ry(y+8qs)0YmXTHJ8s9g$Sdd9eR2Ab#gTr}@1v_7*_>g&Y z{>Da;gG;+-{T+frKG@kdu}$Gq(&AtXRxsC+m;v43&wNSe-fgQ)uY;SCcw;pkSvk`j z8l-=Cjn{_fei zk%^hv5@&Nvl%K&8Yff(-7N0vBRqvzv*Zks*gozyAq{kH)6e3fa()zDPAzW|i)lgy5 zN4JI_=<4wtn+`NnVOfFh?D7$G<{nVYTcRh(t#tH5@9Ry~AM=qKTV4|H>uaVP1W<+% z*~Dz6lxd?V4knXw+7Dg74&O@;wP1Dk19gt_Xwqr3eQH$DNqzn)_m0C)YNFD3@P)x$ zY|jMTZ9Sv0VGKUXV9lr&rP%5GuI>}QnWuJLebX%#;J2c)ob-44qZyh~dG{inji6u3 z=f4c9@Hz~F+1{`Ba@3OEs*=o zhzOk3&PXF;o4?v5hgMD-3_aV{X=Km{Fj@ar6Ot$18Sm`L|*r-^~|E0WYEG;RyPQes{XwcK~apE2h+nr#a?jqX@w%HX+> z9cQuxs;&VC1e7TsFIykzTxda_DjO&7@*f^S7V&P@RwtuCvn)uv|A!w}`&s0Y>t-Kn7F!FnzV!SZQq-VlH{G!ux*gU`}nUoTwVIY|@ifZRs_QDaEln{$(1rWjF$5CoAeT};^3Cqw^Gh$L(%JXh9V2K{O`?snhu;m+BP$)uy`U|g!Q3gIEw)skO zYYnEvjVts~j3$*KDrE$12E%gx#{Y^xBG#-H@e(WN@~Tk6VkD{-%{0y6Lw6(W_HibSL~PX}?PaIbhI(ZE+XaC3u?*CYdBP@>$kxUxONJh_vI7xL5Axs{VZ9 zOqb0d>u=iff-Pg$W$<493ekE8E%L|pU%3Ni$Tjt?_ws#gTMMo~z~;K%&Qj>VW7dm5 zx~nwC!%U%(&is6}yX5l)CNm6-&waePk;c$DSHxV1SG>CaL8xNdr|88iq`(;KVv_B;&QWI~aG4~G|$NiD`w7WOaU!geJo>D``P@iKMo@6;c!V_HH#X5qmk(BHV-3>2W%CgcdE;)=XKdVY6`#45WiEy{T+t zie;)&G>a^{UNOe3QrAI+11qN=IzM_Dfh--D#XMiv9lH2!Zhg+0`()_=&Tz5Ma5?{; zCoDY&mX=l2sB_pBMp#+6GcaM3nD&`szs_bf%twwcPdCc6HvCS->~Xki`{*R_xvn%D zTT9}7?GNDK{qts?8qSv8d9}*ywn~R9WL(*N%x#x5h0}UMmt5%5lrdkBHsY)gS=HTH zy(FKI42Ux7|C`Fom7)4@Qlicv9|cjcYYrFHK7B^|>O8+aQbnM*|{X;SDQ#~g#df(x)usn0F)$Vtb=lL2zq3yg495$ciuv=7+ zoYxgp)?NIPoA?>;>B1~_Fanf}QR|AP!I3a#gTcB$pjjIrOT<0FZ%vPGl{5QxAi}qX zE?Sl-@^%&TZ-jCSm@cH;o8F8+4E;BwcL3)B0nf`aK^qez6D-pQ%u zeeQ#M<%Wv6qc7U2!7zU}0`H6OK`IT+R5C<~t)jzx4Ri@94d~+S1w<{9K|z|%l;d?6 z9Zw8x%=?^{57%0L%``nT=z2f+1O&VS7yn%!H`F$QOJ@YN;r)Hg{U8x-=yqeFsm#Et z4)ssfVL@6$SOZv|CO+57F2urfyojsP6VucuurUc*rC@UBbkR2WT@R7bY33fPF(FdEY=>WLk#kI4BQRD?b?n2my=iC ziGV&U;Uzp@l=Jxd&T5osMA{21Y@`p4c%$ZXxPE$W$=z}oqsj6AOnM1f{_+( zm-`r6iyw&}4bFXFr0bB^dP!sYedFvtv=DZa$>Hi-uxg+UcfD~5tHneD$q zYyXSt*4^mwsr&qJwzkMLQJHuGQOR84*7xtgsAw4*CViFZLQ*~Y_h9upx{?UFCgwJ(=m z8BFF$;t7(Z6RCA$@y>sq`IXSNv@)rO|CNd0XQ*idk@M*8=dAOP=IO+q5{03mFyCiJ z^SLngzpi2_IQ`9W{mCtEbN ziSjH-IkpW__j0w=mv_d=0it?-=ao58fb@ss)b$1tsl|a#uHnO8zN4?3qjxovR+v0=@b~<= zkEaTVREpgi<6<>?dO1{kH3FM(me&7HrILpCt|B??f#>*SqqZenf!X_4l~bhs#dUAL ztBvI+y(1o}(op1VCwoRI|9YBNZF1_hXyF=W>=+YcI+%PSTl_*msv>W z@LL!(YNK#ii$@Oy2C><8z0s9w>;@^+Fhl%Yn*wFl)oBOoTht*6ZJyeN_o#yp%5nc1ruRR&M+1`Cd+Nxa zFbInHKWEqIyc-WGcRsvQ zrnlP+GQxrr~Qez~>(d|H$ zr!}#-h(Q@9x)kFWA^RIMNrUL%hg*$>x=!zn9L|?K3M+6ft2v0=c2=YZT7C5%Y*xBO za_|uT7z1*XSXrM|54zGw?igx*H160k+VrcqX?#2;p8hp-=YP=AFHMvNmQ3ZniNJFc zhiz{LZ4qZ_nm99xavq)&tsQG5XCpk@NmHs$x|(?U6@!2)_gUPxVDMfg%3-=BOkC97 zxpv@DKNXM!4bYV39(2D@nYL}Fxck1go!SS46qkTeVo*5`LAkN9wK8UaxgT(#&-2~= zlqopcJ~TZvXPKadV5+gQ3Jof{*yLo5fVsEuNrNWa5)3tS3hFjr@zKoD(tfNuq%*x~ zgow}8?;jN<4KnjYP_qd?9}WDYa@N-G6_5GCm!OR6ej;@9X0_Qhv_e*AjdNl&{UF)( z?@O?ogG9nCtvNpd{GU@v7(xhI--h|8;}m`R;y~&7!%H$ZcX!^>=nB@yX84k@e@y=V z6}<&+-TSp*R4DMk<}}rbQl}s{*L&j!+e;>Sd{jEJ6CQLsV>R_~udkiE(Y4{`o*hVx zM7Rrth4Qz{_$wvONeQ3CbwBS@m?V#`H!0XMIz-U2Da55a_&G7b`ACGkn8VM*Eq30$ z;^#jj%m^R)t?F1R+=`l4T1WE*os6!f>9jO#KB00xFWsUTl5XdC@r9x@YrZ-yA^|5Q z-4VEjM}+mrqa7uzW!p5qzKe1uGPWG?xTT-}v0&Yt-P4}!J3!CSVr6qz-7rdD`PF{4 z0$1pg_jh5v@}gHt;&Sj$2@U)Q^Lc`p5U~)XL+|~~7Um54|78IjPXq%Fuk1X}XYl+| zR7G$(>6Uw9a72gn-2gr1M8G?vCQ%yd5)r6cU6*G@p!~i*c>BT4^1Q+>zsn*yo1!4` z)wz=fk(dBZqbT#~>$478pF)40lA)-ooHxf4#A<#z-p|HqqM9^Wm@%)TihKr-XDB+DtLcBjoG+bnwap{Cnp0|Sgl%P>Squ26P zDH6b}s(_b$ML5+s8`jB5Rm6 zUd8O*e={X6*z(bPQ?E1agXcc3mIfJPO`MaN==-vfgE^|OkYkbK@@zJ(ixnG`_S0S7 z==Qt|$P~bAp0;oB`mWaB7i)HSoi3}EoBrkmTBNiOPZL)i9Fj!@;q;v@a>GFZmLZ2l zpyR_9%33g%-H3~I+RVyWK8c?E`atI7bWJZY9JxE)1+*i7ZpE-!3)Z#Izf;tY{dz`SMC+xQ_WNk zeic{0G4fmfgbtUB>I%vWWiU#`o8(M$3iZf4Js=`I3;~CHBad^^8d&@hEg7lqry;{4 zm}CGS0BTC$e@?M0Vq2XF9ha%^Bl_-`P5j_@sdd)_RMANDNQ5xrxZ{FRN2$#(TBikF ztS-hn*AN|ftfUD`;o7{|TI8ZC3}{eZl2a-f7*!1XPMye9HWRZzekP`t>#1V96ndne zIt>XpMpvS>0i+0A+OS*;;SdX~{1iMEP&l71^u(di_4jw+qR~d-AzBjm+-98)(kmX3#X7_=`|GE~#Sp?F% zlT7l~iq}XpNJ*n73?1S|I76WGSwxIZUjjd@R5xv1MaJ%4L2$??rtogY$whH-sk^1Y zilSxXoGACK%3-x9ik>y+!^A%kThbNUjt`}J72=QDD`p@q;R$J_7r`x!_J$@Y$RUHd zo|z=YN;MzmVC-&H=Ge+wTw7P~V>rG7>CWn+ZiV@L#-aYSKyT?RUJ7Y*HFJ53G?-Y) zYJ5$EkdKZ)2Evj=HJ=uq3L}((+zu33*Ne+5g;|8P>e$W+sr4L<+nLyNv${ro^Jx4G|gLuP1muMsk>zU=iDVs^BM%Z$6qC3&QneSm&c&ktNi`O06F>;;Nb zlvZEf;A>MRxz5m0Zz_~8a?DENQli4eS;1sGSD8Gz@7|MGdv70cF7ZdpveSHB? zD1FQ=HZv7SO{J%}_fP)uxW^owvu+PJ_+3376MP)}G%S>J@R~~||K_Gr#qW#~cTU7s zUi)WEXX0BSyY(-n$!G=UMDsk!?@i;fVS-{!gBt`Cl4DHGT3n%e&P*ml{*BhE5UhR* zX>rofoZcDt_>(u9wPG|peXwbk=(1LSW^jA_`B07_kJ9V%C4s*Q)#ZVUMMsfH^JXMV zks8iq&sKd*keDE2p2IkLv)1hrq7I+(Vfb?v6=JDS42a`;S&pd26xmrrQPaE{5gzM# zSqg=T-#!-isXYhdW@zc5F(|%T`6xqP%_NmzWfvC|=PVGGaEv_4&sf>7*W7c|7n%NQ z8xnGeos3)8&LQ~uOXrob4+%~UsQmS9>MH2d`Np5rlt`bJu>K0qe{Vnc)M=mHav@7Z z3*xPO2x=^V+Uu>7j>%*$Jw9b+f%B%!oKKcMdOnNH+)eDf7)i?GIhug;Wv_%hx_`z7 z2fG((bE@y{j$04$Wcc8v>&)VmLg{{-L==gZJGsqFzvp>9i`Ro8wG{Jxb}osNya>?= zXdbhmv+xI@i{cQ2tIg34RJ(Z@%n$Vc(XG{jLU%}3W;>An=&`bE_C(N4UaK(2SBfj& zY6OcYDH4NmJ{?dSq8YAi{^<01B`8Er_$j8*Em+~BqoAcE##*SK{68E=4NSf*KzZP> z(Mv+58Z3B;sYa1OGVd%tDoSBnv6BP@s(Y8ppOQm7w6~9UCv$mI`-jeJ>^(9_Cenq# z%ig+8(Qt3>C4W3m9VixKon8*lM+4H672FtQ7Sq`EG@aDyE3NI@^D1eiykZ~eEEr|- zBjonfR~}k{tdm{WUMq#}h%@Q`U}qxfQKTx1)f*H8*&{z@I=y{%qx54|&tYr_aYo8@ zi0(S)#rYI3$J-tQ<&8^DHwu$&@BWy21M~l6)}N-G0xIR(n{CrUZoR*@QoyeNaQJuV zbe=plLVt&U?PW&2p_HpI`pirBFR`h%-5k$m-ZZPwd4&jHz2knvgzi3mutIIi0!y?= zw=~84b!mV*SzF!$0z*OR1-9xcwiI{#V}iLtbF0JA#~?0ovHqWNFKmIv`toLAjv%Zy+|4V~8SeE#e7q0Ke>=7^>D`A* zn8nF{sGZ5>tBzj5Z{gx6-kZcyg)Q9fmv*HIZ7Z`fg!cc-#$5da>AjvS~TfC0lfj;54YRlISpnltvxK zhT19rqo8K2zriZvl_L5u7FB$aK$l}Gn}HG&jyh^cmidapfUd;wD;47<3N9gWr$)Bg zqbo_C_2;B1<`Oc~=7$Z?u$j|v0CmW3HZILA5K_Hl=0}od#)-+X$MS>H)V`|wsRx={ zN~C8eB3++SrNM7M-_=;LABE!v<&{;1i?wZ=!RJ@;FUGnDg5NQdvbX%WwW<=rJ8Y@H z^9reC2I7<94w2WFmS_*2YJ?jWPNQBT*XzL@WMqH{bon*D*ii&9^6T`HW^(o~fQlDI zs$)5x;Pi7WT6A6jVF`Y4sby3kj#G=kYeF_grBX=cm0;4^jXFa^ps&~OoBnvW5Wp!~ z&9q8x0!@Zsm<5TsLJNc4H3*vRe|1$-tU2FnNLQXa3_bnyUZ1cUe>Gf% zNQNbmqvd5m6ghOpLl@PszB6JwvO~b;y@6n#YGy9}#A8gAyJkHe5d?6suE|r~>8-@wo_8dw zEuBY`RUBPke~4V;k*RyWG%RC#`G>Z5wf-iRES&OXEl&N5Lg4zCj-VD(Ga9H}Ib!P1 zmf4>=dU0aapr4PdDy=w|!}ffOd}GZ$Y^wCal`{RY!!sL z-10U_iGI#}>Z8&h&POx2^tseL??26N>UJ5e;qlowNl1(+d6pTdbm`|=xGTHy57*VR z(y`xSx0OX9a@}#62^eMgg^bKAJIaPYVZBq614|u;-g@CB_uDtI?GH=*yXu(FzfMg zo-wSl?R`%?Ud_t&VUV%lE=xFt8Q%pKT_*<>K1L`z6&Hp;0~$piZzu=lZ4i@NX0qeQ zW5uVx<|}BEf$^PDX539x!gKdjmP;PxZcetyjdz}NS@~1@r(|c;QP79C-dbgSna!GS z7Ai{tfb^fC^$8B3u=BrDBh)O7VAf@fm!;`$ZFo2Ph`DxSenUjjGozkVGIN04_~smRos$%SSNxumkP=hD9z(7X-|HRhBVH^GM_2Vkl|7 zYdhj1LmnlLYcG}QpyoC?z#xqCVWTQA{Xt+u5%iR?(37x`4V=BewR>dIIvxD824x`u z_B#&@Pd7HGBw7hHS?cgeZ9bszJc=ENW+kpXcj_O9P2__+NkK}CxfLb!jd!` zqvgnAj#HxpR48)0?td1|Y>O}>gjh8lpmrpd@NShzTm1+#Cn+U?G+Hqf6rk!}I0Ykx zVtmtybD23jDuzn_&|peSTQLk3;&K^;#@=@=Yy`V{Ppk^9WsaS;>ilquFy+Y@Y|fe} z7D@LJg4J4I*hdEW9jc&Yk_H(=j#B0rW5GSa(DE_ZIQ}E8#o^x?Y!GLhqJWWF#wgMU4wsyP~D{LEjEbx zn@*(q6cqFu(4^1m;5Lw%ui?qS9X-DhPd(}WxaVx@rn>dseJifZLa$AXH*?33etA;$ zL-u^MHal=g*+_W?DT_S8_Kaf-mvs2~pM($_X|D`UqDZig!jBV%v;?ZHqY}$}Lf>)T zfCT}49Mk?sWY~}#saEnj@#>y|(+#1j%cnny2|B-XbF4<=%aCLm=OOwZxmx@tOJ;x3 zPk4369GzOLV!;c%ZgRhVNzI8BC`Oc6xgzQ07gD7#q?*@d>4r^bfC~~4VNi-iO?Qeve^LT07M*}E6VEu9oLbDsl`q3@_ra}jBn_#}Dn6iTM6ltt*zJL^hQBSKh9s|#$q zFdO;s_nH?x9`J;Vb8x>k<-Fc=~Jc zaj{|b-+$1D67~e^N^KI*l$hP9c^oauu=#El=`mxzlCk5~Rh41Wwv)Z5F2ZDS!#0Ml zrw&W6?cOkP8=6=<^0o-x>uv(WiQv+BD(9lgL;_eiltVg|-O|FxBhI{P?skliGKy8m znOW{mD_VtRQQznwl4p=pE(kde{jVta>GBHCu-_w$2!S7?5 zl0~6BR2Nt?eo-w!?oKl}AKKt#>`qu|L&c|mT<}thx=XOpZlkd(-2U{C;FqeGv9;-0 zpxrZe;hai|;?$sY?2Mpt_0bM&lRhut$+91>R-5iGeVLZ|hokn_+yW^suvN67fg}ey ztx=tDe3qXv^uxXVV5hyEPvpk$-7L!ey|rnBLzoa)je9CDfP>HJC{G{2Q}{MSr29K! z>?c7Td-~KUqWij~0s4>skVSRcy6%%H8}iCGpD(fO(Xo)61_8Cbn(dk~ysWV^tVCNw zkIaUV>wA6s0jJ)N)Eb08;pQ=nin`#B1|I>m<@O)4s))Wh?`9%^-@O@FtV2~zTSQZ& zFB&g6T4)-3LupYi*rV9mqa+i9fQmu*uA=1gd127+c%0AlW{Ift2Zt{J`68Ux_3?(f zvk;v(oAc_hn6V?_kXS|~b^BE~>Ad%fQ?A5Wq{UiR{XaybYp_DU!s=opv)9hDr@>-bSI<~B z2@AKgCmZg{`7(+5W1nBo!8?*g+XzzP2fNYTcklTsnNh_>G)et@!xl_IjE%BtEQ)5% zEoWGL>x@fY2|;pIHm2Gau%hmEJt}h3V4(>1;?I4y@BiZF%R9nZpkFO-K&rtN-$%ds zHi@?Q>-m)2vdD_QY($akakz|jP0PXdX~HKvxoPdJJy2dVm&AiX1YkV6J>Dc>6pA~c zS96F?EZAHfU{t~tZcbyP8W3Y9@*A&OL=hEeb9DKfUm~^1 zpG8j}zF|f?cFcD#g%&>2tO+lQ)1<-2aBsi>Er4l8qxFpnw;;7s~exgnApDYH2F1#A40qb7Anfg4gF~0vOcu@25U_JP0|8##$ z_=xIf5`w57NGezRO)+~ymDyTQ>y$`eA#l;Qx#=)R`!DQqZ0F|ld)^K7pBugr*to-l zq5(Xcv3i){)3>yrkMe>WVZ2-G2r40mh-FO!YQf7TK00??L#xbE9u}kPu-0y_Aa}w~ z2UZ}1hHaAiZBqG6O>#6qx}&^%8PoN+()P2M5+@VUT-jo28q} zXzoZ1aA1cOsWe&MHBV3gmRY^{R~VD4*xq&k_+3oZNM31@LkMA9FUL{sN|r<8NDTi4 zN0$YLl(+IJtrj(m(r>_m>b+?F) zd8reCacYpIY=m%=F$t)^U52CU+TO2bJ)-ZPW=EJ4FkM343H`jhS{^N%qP~w7dP_`{ zceEE#9PbI;04n=zAu{Eb)?G?sWx*3N;-zAgDzFCjYpY;p3Gcz&HOSBo9_iIe4c#c1 zV+BbaEtl0q;2+S$em^A#JDmt}I^T@u#5v#xxzQ|W&>_pr8Z_6e7h{b zqxYH5rIML**w#z$^a1dn(7KS|i^4Ijk9C5#Ytf(WuRDB#`lf^2H>EI5BEi2PPwsxV%Ul-YuP2Ag>U!}RHU;kiM4tK5%co*g>=+tms` z%+||8nnj)IqEN2?%dYFq>*i6v!g3CJT=nY2l;aMg*Ie0+>8Uj5GbgRt6Y<3WBDQb2 zI5Acl-~Cte?S<}i7tzNcrC1W(WzyEwzxbL-P!vj6FfSuXs_0M7wq?uZo7`W70_8u(R1NHzI|{YB6GRajqM}A&BNz%@)q?w;A6QnBmhQE z!)v4$gKm-yO?W5p-)lExVtXI&Oy+%iNFs1gkYmCsID5VE8_cac-t-gA1l$GAYR1)v zsb-IG&MP_rPvJ_w^rTY}<1jhA64Hc1SomUxJF* zw8oLBtz1S87H^TQbay>W{wAm9uKY^4ie;fHY8AcNOH7irpo16%dBQ9;5zZ*%gfw1j zu7I3_jj#UjGKjWeOuuQz|3dXCyc4eJM;qks<|Mp}-v)=XP`MDr2_dPTW4+jU`l)%W z%A~nNhfA74{;&UPFPPL>vc)Bl>x|E{PeZFgMeL+4yP8=)mLFYRH}N;pBmgRG$!FvJ zXog!*E~ak#VXG+6rc-vE-E(T6yI2atbAfaIDR3 zw4;7#p|v1fN^;_ZDu+O<1-5O`*Rx=x^CyxMpqV6-#L z*s&;t^nK+kB#uGFYJ7(KrH`LRti;(gsvUNjfMXo{0bi}F?OV!&^VP=7AWu&l6h^Cw z?@Kt{=@Wb-`Deh7iD0g<;B|ajW%GC} zLc>r9dRR(RPB7emcB|!cM7sTX`?`HroeP}uOIi>nt-9a&rd^9Pe96`i;63*IFFqcDC^%~ zMX~zERizB#|p}KmaXDdGP`IN74mh!n(vCp^Wt%oQ)3SiWkMOOJvF17d1Gpg_uoF z^%qAo)_a*8LLAb)dNKW(_D8FGtyQ!u7v6}~S1mMMyfn9L$P7VZHDX_@3mJv+k*Pde z8p5A>UU*NbZ9Is5w>;Hf-`)6wL_9lA#a{uM^5}mn_2&g(wEnkP`+om>77uy1x_tFP zmsSm5lhx#t`(AF6c8p_l`2S}?F)cz$$|+BFRWo=TXoll3?d1Mcz^^UnHy6iZ%}0qW zM^VmZHPFMUBg4tgnjLBflDb$ST9xXP>hxyZ09uxIuE_v44ilM4uI!Or9npCe$+^*7^oJ(<$G}d8q;}NQh`^NrC$76_b&W}@c(nNAgoo1k* zESbI89xL`umnp-_#iTloYbFcTzE`|h4HHz(*nSzWv0&6(iV_%t;PuO>eoe2BRm>N& zvw}wZepi3|GutU^vck&lyHAWYhUlt{U0+FQuC2B`r8a>=PfCD&8K4?f51NVlb~ol& ztwQvGG5B3-^S#zultQJsBv78DJP9-<#TCd~N*fuhQk7^lP$$DA7S)65t1#Y+VlLg? z)uw?%1Z09vY7$L_hXU!N2t320 zlEUZG-h3!(3hREB5noB#SK+CF#sPj-6+Q7?g$(`6Oc>fx<4|}WE2Wa{QoUAIbZ`(u7Sl!23bmANl&Bi^M#(&H3`Dj=Ua2RL^ zWQ-F;@Diz8Iu42~aK@q+{xsRd$`&UKLml$|3HD*5dI!z^KRoTMv5YZ74_L$ojYr~#?obGv2PX6vE4Cqi|pRNa=ooD(H75PAg$|cMh77zK+bx! z>#uZa-kPl=*EV&cI0HL+?)=>Gs}`NptW=3cT6ZDm;7-98y(&IrBOStTB#AuME^mOn zK+xmaVNZufOrJg%<*srbg5M%q=iBFJY;2C>;2%{*4t&3d33QH5*m)iTU@Q&}ZdkqW zZ`!S2O|G@}`m@(QnV7hWd+=RU5xhJ$bNz?KciivjRWi4$9Xqs;KEl>4Q*TVYahm?V z*?yV4CZqV3h_l7a-Fj%_v(WMi?-!Bhv1;Q3TH}M#mEb^9Sy%m3<-@8zT*BZ+^z+o| z#}7O$A`$N4nyl*r56HU2k)`wBVcWxs%pN8~l4iC_+Hb0LZ-x^Hc{WKEq8+^s_Jpy# z4`~OQp{=o^UAw^K2`8OCR>IK_H%O;J10da|=VNHs2Uqh*~jPy{*UBbINo?5rk1x`J({U>#pc6HZTy|mx4 z8CNnKQ%AbOsCQZKUMv$yT@O(mOW@%5mGCeu^r~=ak6^~;HhC2Ok*>tAU9$DBxyz_b_O2Isu%)` zg~02Sj^Ll(d=E6xz_2Sz-aTIQ0M^lFPv{1RMpkxY-jg-W6{Eb_61#eV=48rs$iE1X z+jhGYZ#5G{%XZKs!-7cCbLMBPm0K|2iWlX5u|Ws;7~3{1H_lz#sR62s`nA@g*TD3G zV36DV&sYGYsYJN|_%t~Ia(%=FjKQE-DRb&bb6nphOZ3{(MG;s%W>QgdEuJCgZCQq> zyD{r+d9=$G2~N;fjcD7^6J7AXUB}WtepMC5pLNE+7aXexwX7UhIt&=};RGS}_T+JA4$i&{Fu&kMrrf3ZGFxJ=D*f|u_x{7(zC#MJ zlee@W@FPeiEU-)i>8aa4+hdd^s1lP7o-jb(m)0*tZs4Z27Es$5+hHIPa$?43UPkLo zZxHBaIMFn*t(R4hX5r%M_n(hPSOTV@?^O~UUN2nz_)BoeT_=Yi6Bh9V&j#iTihrOx z#I1391p)u~KzNATz#wL;#Td>3zsiqob6oX$6G={#$i1fNXAFa^=dE>QRk`IoS|GeJ zc%4_0iDRsj9D45YDt&|Y(&&vrypxV}8t?Vp1=fy9rn5o(xO6L{eHfQ*V=opV5tR*v z#%}<+`6%`5C;D=XIdcSzZ=s705U9VCvfm}S7SiciDjn5u*+HO#->iCGn+P(We4UaW zKtY-?D3YBo6aBy(u>q_3Sw&axjE%G=cAjwP|1%b6ds=_(siar>aumxg6UA29%}E`1 zt$gg&S~-+c{bb}TamWSdf@~;2kzys8F`Jc|=%`{FOUjx}qe4q_HZ*wKgPW~hqVaiV z5q-|=Do4@0@3^!JqR@fMw3+0=SK4>bW-%qz-Y*s9S2H!HzDAv62wbj^jo=2!;jtjq zzNx9*?yBZ@LX}mYJABr|hY^6x)-)^ARogY&f9b8IC2jRAQEmJ;v_!49x8J+%OZnTPQ>I@ zGvR}U$MjQskDJuEeLAx;{eA*~(hUb9jKH&h!+QdkT#M!RR{ z2e}s=)8Phk%+y)TO#H{$T{(nUpawAzYBL(qiW@1quNb`aQgrKR@ffuFHZ}2F;wtDj zDwp9;y@He~C1bc)_x>GPdl0l+#K=w{&HPc!v`A@UU&#mS(E*_wGx36B#8;KAMEM`r?6=ssQClGHu>s#t4qg z$Lj7iX+pN#cn8t~3L>L345PDQ?9#SV)7A(7&m&er9l9aAyIFsL1X8?7IbsHbSt)`I z0i#F4JIk@=OZTuUUfW@uJ&k16umr17L2dMGy1iMQa!YQsqj?aH^Xd3+X&y6L6zA$I z?~~Izh0hxtuRM%XJ?BAM4pj>%v2P+O9*Ghm{uSjuX-}r%fR-JhondTSE(>$I>rS*G zw?KX1y|#DmF8oaW!3{ku&&e38$0F_k&>=s?9j4hYtLZSzQ)X;i;cDEY0FG}A}BjsuR^6L-v+RlVbrdBpS+3pW6MR<-;CkS;rR({ zv-)qd_PfjgmgKZr`w-3Y*4o6M1a?fVkgp#t(YtCJflSQ4ocHG2-m>T?+Hn3K%e@V( z4$?|3#ZmqhF=dkeC~(Bn=OJO~v_7@^tUNxpZ_;yHqkIt=nOg;OQbWlJM5?PlDR?a} zF=<9Uqs}+TCppG9sKq9O)C25w%4A4bW08O`91W&%x@q(>%4nZwi~?h&tvFr-cris| z!=ny;?*1n1H1gZ`7h}6hSyJZeUYzge#ijXJ#v$`#R;;NLG=wevkRveDw7z1qy52OM z7g*HOIPN343EDyplU;&xeK%jj7q~_aAJ`NkatN=Vmg%rm=JkX%PG|emBc;J_gWmz;=<=Jd|5U z^mehDdhh%qQ1)sozFNxx%PJ_ZhR$ctuZR*Ol!a;%CoE^A?s+ASdM?JHahyHIZP25w z_8TX#MdUKTD~-{M<)HYj@VvHC7>`On(E+6U78#nfHkGu-wQ}?eRe~4jw#gdeaU_V7 z5p82kABXz|R)hJo9B#F8Y`&h$sq7kwwq15e8$LB*iDCst@2kHLiNezW@0H#^*hu26 z*y((ss+*vw@{>QR_FZrX=Gq=iV@S;qpGtZMcP)L(Ix<>s`wHw6CYt^7Zy9ZJ7XH$I zEGqne{2=?sn6xCVi(SxQb|{({(~QmQ3l7XXA|TQ1}zVyj<_8xK1Y`E z*aTvcGOTNmF}pT-=m4bQUphX!>;w+;xc?h+17r(8-w;Vx9*r8suZk0a3~_e(*h~wg zZ{z{v3O?ZQI)B$7BrZ88tix^jQk2z27z;U#UdMCQryz`v=QSDE4rCRxR8 z%g#FBd7C=2_m4`?{7+4SU*h&&@`b=IHu_I%h&dB1o+#y*IQnQ zbc+~5n@;i88?f@yKV=Cyl~Oi?d3FD(7A`S-yZVxZ#^bL(aPB|uOcTg<(zN|jdP3;) z3qVdeOvt~)Z*$_>rzw~QJcPurY+U;!+O8e;KDs5^W^yl-XiGKSfwy`IHh(PLv-7!mR z^Y571NB)&B_+g2n4lVACG1Ef)zx*En;y@k03q!JgWReI3D%=HAXUZ0|N%;3aTIOg1 z9{%|<@vO_uf2?!*A2Tdlg4h0N88I@66NNh>@SAyu3&8(2B(^O$G9VfG1&6)wb};Ue zn4>z`I-EV2f&ZVqHxF;)y6?R|SO{=ABqeGaK@@FAkRnsEO$K8}al9zYO&43dPTS<# zX`41_Z~?bBN&VXH)84ct>9>8m#BQ40cp0v8I#^o z6m(=tphO)m072mXaRv*u*iPcumOS6*!2@9S<;J$p z+Mal*v4cpdKsFd+sJZUlsK zvy$YT)WmCp&Ov*}%owRgoj*32mqf}1;vz~m5F%NS+}qFrW!OHQ0Uw&MRT(1X0{u;0 zI+v|$XKaOxYQo8(KnI6?A=0xM`omoeHM}-*Pu9CHcxu|8zun>G;XLQdT)G zA6g~5(zVq5X3C%hL?Q*sXfo)&dpo$qB`JK=c%1*dw}ZzVabA__O1shnsIp1Omp$V= zSxg`olGRdl>T)~%w;~Hkb~S9p2@CFCaR{eLmzB2srToUs6YOf(%E0U(cdr`f4mpO^ zVK6u`#$O-Z!?!!XjX9^VPJRq)nSt%Dn>;45mKj8f1@4;sS47xh`{9f(sD2m{9r%3E zcQQwOZIo>%bC`3Ac&8>}%~?gHsAZK-vmiOCEtQ=nL1I#}J)0pL4C!gjf_y&DdYNU} z{$+glsjm|bhXEh+HwMUVD6z=4_^*E*ezX~WbeVoiuKEczwQLEPgZnOr`>ukk{|i3$ z7x*a=qD&K1$=5Kj=FbNS;$!8tyIJYl88@N_aL(ES

    hbOaAV}w=h;&Jl3(e%x-@= zL&`9iy;B#fhbl5ejL`fWvNE^wKXe}1P!?l_ zg`7%|na~!t|Y=sMYt5+;<<%g*Wx z*zx4Onz(Io6}632y@J)HCgNF#_V+%_ye%lZIbWONQA*o#W-t@$hXB=r~l={@a}J%eqNXL zDyA-gjX}6+LMv(?3sI|}7vK>$Y21h{_;7Czv+*cj0z^7PLsD|{UP1gLQEW#L>rtdX zmEnpWMYux7+Jf>a*EHY=eCfr3`d~atAZ6fpmkrv2azauV9-(xG5$WCCn*hAgb{@`o zBu`3GtwvQTyXwG`q;nY(N>-Jy2_;F+NX$a*Sx8JTe%{lQ8Jv(HzQheK7u>wE6_R#Z zV%O!NHRtuVoS?vVbGlYY*@{{=nRov;8YJcJxHEsGO*sg<>jhJI<(we0N%L9(#; z_);z@o1V>(&SyvzB#C*6-B8>Axl(U*cWHjZ-d5L<}uS>m)k_Qb{jxkakMwSw% z&8v{Iav_QE+o#PJftvEs2-Q@ziQ|&59Q!J(!YPb!idBs%C~Gw>J~WBCM%Q!K`R)QA zHBxr6riuli3{IoKc0cusTF}Z_b51eXG=QAZ=U_Jp>?TpQMNTa>aGC`2WP+RL4l~#= zz)dS}#H!nmwcKELV5?q#^g6_2&4~7F?I0>j*sAs%_~U;>vxG%zs@XDp>~CPY1wJ+i zED)qjfGV#{h+3Z6H~jek7ykJGVQNa+Wv1eSq@>MMSSt-uD-G^yy?)Von@W*dWw0}L zd9^%Ss| zlZbh}pUk>6a(Qy`KBGyHASP|ib}pcq&ILWcDJf}oKY6r3y9oFkLD0S4K3fkaeaY{# zWf>Bp);4<6^T2U<=sO0#(^u;QRooK@+e+wNk`iqH%1EN4~IB9)PZsYYZH?!J$3pXq7d24~Gy7Ni=isbj-F8Rl=8a(0% zJ`hoiOof>Lt1(*oa^xMsFSixw{*j>Q2(r)XeRplkvD;K+ZNW@`7e&h;dpN|ziUQwl zfIZs{M%ESx_T>O5IRb_{XfU-sYB?Liw=IXyosWC0zHA7;OW6AQa$0d4(Tas&-T7AB z47~hq9?mtSpU)5}7H}FDKcC5I$pQ0felk1H`1nDchtH?;!B+Cd`hdRq97ByA)m*d5 z8Lf=X20|pJC4I9w`rEsz|L-_ChV80r6D}!RA!z}29@lwh?FOM$t#eZ6e{C{|EEKBy zwi>l{a->wyxn&y-5_zdf+pvKTxMNnUYMp>!aAu7D<}R$TUd~)lSYbVH+d>YrtcZuB z+K#!bxHs5=6A%>dThF^Vy#-*P(fdBKbZ^|KE4L>er;Rb1f4S z6W%lKLX}O%N_PMtd^WJd%IUiA~`I>=&D*3B{NQf~eW zo^}l;%Cu4=W5e#Jl22CsXe&#*o~_#1R-U*6{au*TiaQRC@zH4qHDgjJMi9*o*-!{` zTJZ-hEj;S?b7*=R`FsL3ZK9^#oU|>qd*%qi;Mf>X6|N*33Q;IT_@V!8TJdTu?vvb9 z{2o78`wT~0j$#%Rk%a<7tsPbOkCD-uGBy;__gzh!y1z3YA$n0Y+6>+0&hc$EK& zM>$$In)&K4JmxBB0XC;IbR{M2rb1c< zPsO9ix^;!ASe=xJ*kYAP-VvIxJq5G2;9xv@M$-0+#{^BLqN8p->)#B%(FNaXhu%$! z2ge1Q6-=cJCgM@@w&2T4pzUT!`Y&th)=Po^VGDL&rm%ibZ*R+oB>O)iX-Y~)f^gXb zg1LBvIS3j&rwgJo3JwfbGX*~|Iu;haNaN~>M#N!i4d z#LO#h-})ZDR17jceh{;uNGORVjHtW6-@VncstmCR#Rh%q!9p8De?G?%-Cg_uUD=Kw)rkT{){TXLbGi zrPbpYB84GRdRpBw_#nPEiqU3av}s~@*EOrrYS{%e0b3zx=isV6?*9rYTOnx6K#?}P znE+*cKfacBS20^5T`TI@2KRsNzO8(-z0Bxe4G?sn)s~y|HLzO*t5<&(05xkazRs%* zc3p50y^lVk&ttlFPR2^BI;}F@oK{>X?jjnEbK~lp^f|9PotU&+YWL1miqz8D{ge}R z%GjCMqWwiLjMKBJw>mBJe45PjX-39|tJl?NvygeMd{xET`3PzxvRslx%sUvf79;Cj zQg#l_um*H_Grp3-cq*kY;BmBXuxk$>p0N>6+q5Pmjiw@RDkgy0l)k2AQ&j_*zL$_= zHXKu2Fg(IXugX9P?1JDAuFdfH?bPn01q|rUx3K?6mux>pexGhx4dIq7{YteBLY5KP8Shf~lz~P96@CxxazSl9Ksjtwc)K z(iSPOaM++}LzZb*0WxzqL`$T=UN>+#n+XH2kXF_DU@jXX>nc^3nu^VXV>Ctz z$e|AAvLT*#=QTzOMBRB)Zthv-2y&<7uI=7AiZB(*U8WwzYzSd0)((yliWHc3)u^+M zVAc_wtlL(TsTlw59L=WUe_mW*<%R-Rb|^mer%~FsUzc^NPMguBxWZ20|p~v}Lg4 zlA$|Kj1q5+G8ESPNvjO^hB~V1*uG+pdqW-gfWhf8`dhjf3Uy!>72D=>SYd;qh7Qsy zL*IOk>sq@>7c%tC<*F*$^mL|5*aD>IGGzTBtOkQ^#T?0^B-LP?GiuqNrr(jz=Lv@! zPaD<#dU$tL&etQb&JRpvLyS6tRgnTKA_Ycl!LFeWzUH=jHkyhjY{95omw$gqzc;== z)bVqxWkD0N_Tz$~AH2FbsJpv2d#Mx7f>V{Ur$YJ?D4)5AJUbO5rQx$~E3>ejT@72Y zS`AtQ4v}(!zPTKBSa98%ZvJcGpQ_7th5K=u1>2@|-dOx_+ssamH5_HC@liJL0Lc@Q z{$*V_VZl&K2N#x~<=WzI_O4;#9;8~7?Jq`pI=epsl)%kzV>~j z4`pzg1lv@OK9%F%)((c+I!H`vYh-gq@x|Y|h-WVlXeDd`ZCkvcf8X^%c%T;^h{2Wj zyVDndIeg4hj?4nE@TO;&`P%{f_-K9WF2dAu%r>G)y9clTApmQy+Rd7)cQI!RK68s! zS2;p(tJ=xs)6?woZzZ}mPGUl`{kaS~doM>EJ<4rQJdR};+%)Z!d5{1AAOJ~3K~(=e zcFf$)-4`9IDp_}CMs*(9IJ7#ZXzOaU^{$1R0 zYz(JK=crXPnox~i7(Z)yP;(}^X`L(9Xip&;PcIiDXp;$SM`0p-4xz>@s?h{L6dEFg zf``d1?bFQV0vP!eTnH*?qUKEqKw+t?mYsJmXb{A>jX0!jm|K&QfSydj76g6Zk16c} zR2g{kB001hO~sroXxk|mD(Lr^&j;fN1)m;K*pq_3i*kJShh4O}q--;qs>i*@OQ=~@ z2hoIVBe2w+-*FOt|IebYd$nw(4dS&wJe*Hhv0~+E>cUg=)K)l;%JTKxhc{Tk!)p;< zp4nFq^@`cxE4ky!%c>GA*s|rystuXRUp%6Na#OJp$&c(P zleS>;6vfC=Q<1X;Cv0(=bwsQNDFm4%0cf_`O0VRqs)oJr*ZNVE{ zGW6+qlv!Ia?pkntalPV-RSI*1;_90uhm(?7TW~ZU<>)j#@mCpQn-unwg0QIwn~MEq zuoHsB2PDq0;M0E)r8Ob>rm1lLFbW^8DfEJ-qU;DtFQT3aCL{qfxM)9TwGmu>k3#8E${ud)PZOwr^TMw8#dkYTI~wlvr7jn3LFLZH;U-8w}5mkP5gtVJiw;H+QU6mpj%DibaH}9n`;L zMWqQ(YgeCN7_|ihc9i!fB=1Q|%D^`)gRfZz3uxQpdfaWje9yJ@ zRpT{LuDwA23q$&~64EGHXPD>a2PH|*LhtGG%dU#Dtd}!)6Y9*uXrlu)_j#PLV#E(c76;*o^|w zP*c+~B{Ao51yL(7HFG)Nv ztCq#`m_GKw;1O1lT6E15&r9&bF5k7N8Iu7_`lkm-tW<04i^oNFqty&yUnYzEeJS*#&m`PZnog~OUvha z!ZJt%C7HNl)tfTh_yu^R2mWBC;?XkL-xXL-8ML_00}bx>i@-@>v-@AT_q>H#?(Z^M z?90=5YFR4wm?yj!vWM3tPHm^OwY61qd2ZQq<)UT0HjRf@yPsScNZ{esMex)o-kQ$v<2w7}Nn7x}-k$2dV(AQ%w!n!;nX(1< z*UdW>?WSVfqH1^C>2~19Eray?Gg!L~?B@i^7Ch41L)%&GwWjOH(OFxtG9mdk;6EZL zuZ8ZDaMdCBD>vY9AR+0$0N$IBn4<#Q7F_UIgA2-F_9(9Yki@hF_D7>6ep~Y87I-uS zANWtfV~y}+I#ad!nuV_pecsTd* zwYUDtX{79_utTD1R}7k{bwWCDTAenpFy|HVwkU~dNpf1^goK{IpyyjH298Ut+J1qV zSHwjWJ1DAl!xanT>b`@5^ob01Q_XT1w3V^5Ah2E1wzs_pb3qZCS0wY2SXhxnlJXmx zm_?FU(7|kiVEPq_qE_#keuYz3*uL}sxjwc3QK>)9w;)MnV3>#V6Qho(jOSppsn`@# zRpspYipoGS5Uev?zp%Lr`!C=z>vXJEFh9n=K-G&I*q?Q;AKRW^eh_8r}DO{^}@`)SZman1Z zm=)FR0^D!Httq%G3AcXIonA)MZwpldw){r}RdwX@KN`UA2GAO)5wiiH_fH16@=pe; zxo3eYDQnKCs*^sVK()SIGGVIhoh$mR{@XD9#6V+U^9$q~JU+n|%RJ5-@R7Uc9`3XIoZ$Tq3 z@8-*gtSzdfY^SMM6;s5L5+`NQWhx%C4B#MdN=Wutx(=D!A7N6q6Oy`PywZG0!JGv}%b@7SAMMXBSzK%yv#EeMh`l6Y&hs<;KPnv5!eYX=1QAu%g;4%#N8YE5h|==qfod34ab zvz8SJva3K+HHL6Mx3x)SMP08EjMt5@U@%uaz=}VvBKg@GbZCiNlfV6z;=_Kzhm}Rn59a> zCMS<@XY=A*!)o3{&BrjBEuyV))V$6~tI9Dlr8I`m&21cV)v$mH$B=Ca&1%kpT454> zJdWy!A=f40e&7U%DI2=9BAapd;)OvxXESFDj>MysfDR-pOvO~npa>K!1I!G5Q^8qM zCp+cSua#9az;$l^<&~0Pn?A%X%N4&l79}0aU{4Cdx~W76XvI~-Qf)F3LfafS10C-F zR7W43o3_2mg?OBZhgSmLV47DS!Pm-xcq-c0!vkNlE%wxe z9?mD|MpT*g5EoNNdImId=hJyvB(Y?z`RJ2c!y-idN}+p#i2UF_Gx!Jp9366u5JE3uaTsBDHMgoxQTNful%@mVw_^6fJKwxQBBe?|kEW_MXzd zGz+Rmrk(|{d9}!X7$AKjgVk(cHS1@?YB5O8OVTQ%6|oJ1-sPG^F-zKln37hxCgvq( zK?j@dpkVmu2=R8kPCB2_k-;+92$E$+ zSyoy(3k=VX5D!MNdUzu;Tw+vU)1XhYIV#B~mMj*HnkWU9Hzu z2XRf$n%FJ7s;XOn{?Z`H;?1mI_Mt`h$8Oe&+vJ2Keqj{5MIf4On1SR`N$vL#)mER&izRx3<0 zD@=@*6uceS4Qh>vT4Ta50Y`zy-HW{%L{{&kE1jVTOaaqWF9#*}nlG4&mf?}A6VRgT zP!>9c#Mv+d-8TFN@MtHrCnVNa4eS$w7E7_*%-}=2GW+X36?JT|?$ZqTj)DD@N6c3G zkKX&*gNK)nQ=gZ!5w%`h$ipw9>{ZH}hgT25*J|N7lZw`R37xy}a&CG!UppR^K&Y2@ z^B02$EQ3y4G46J_FN&#Z$K0_DR@;ihb)E6vgyhoX2oI+W{{7DkqCb2SA$c)dwzSjy zd;i2rQ}Kg%lpn{V96O~Gf2EuI^_U|#W{WBT3$VmgT$GeLS8ZKfYswZ}n2=Qx)_zuy zyi(#E5ZDI=5BB!3q)r`czCrP2+kkf|rd$AoY zgTU(H5st;96l_r)Y%u=ugUoz8N-(BqOiKK48iDJ=t|(>e(Yxf#cIdWW5D!Kn2#I+KMYPhjL6Df2 zq?(QDwtAa-FpG)=QsC!Vxq7Y6gGn1NDsq@cCfE$FP-_{ z;yUicYBjLKg5kp>i|Vlc!XU|GlHN#dxxXLpDzo;ML4v>=ZW$m%)u4g^@bH}j0Q}co{rG?zzmwv!W0HHe zybZfa(CxmbQ{T|U<<^B=#HLkM;aX9=Qik!BcVkTI>Gv$Xhw&LV53ftkS}P2a$0S?J zwOq6nSSt;Z6SBIjJf2`zqeE)BA~7McPO(HbmRS1wuUp)9QS)^w?4}f|Y@$jrjDUsV z)AwJ7lBkf03?=EA?nQ;_);XC1zb0=9f%GMz3}UHW+x7^sj#{!_;oc(Ps5?M*c~TMv zBoHzcftb?ye{BKgPxt;Y%ZeBZ8ld|ibRUHqJ_k#XJmExH7LybmK@*y;pLGwbweAp` z-QR6)ISH2_;Dxv9;v?-$O?hz<4<3Hren@@H(X&7H@QZwBdw6vb_{c{-GT`_7$!4?M zci(-lse`MGVAnQd?bV=&C$&D89`ZKUt&0*4hZ!Dzn0!9(T@(-J1v)#|vToga4jjlZ zF)`s?kY7|ikPR{J)B+AyBqbtJV05U1tSva~2-cX2li83CruaZa3S@>lP}vZpu;i9TiMD0zYs`LxD)N zK*3a~NP&Dd#7XyjmzUw>ngZY5T;Q>p5RZS+ppXsm|FkLkuE^m$CCKJNoaiiY?8A~L zLonkAa+bmVe=vBm5gzz%2lM|+(%P3}&Jh%|A!dgX%8 zs4g2>C{+LNe0~%sEXW2zWCObVCuSr*V5qUSPGVMK78On%QJct1w$Em8f`V;@9Cyr& zk!=X+e0%{xGA}VvmgjDH{YjeDJwX8aM~M_EcM28!J|<^ahD}I1kHqd$nKiN+X}oFY1p>O`RYd zZUkW6y7koo^_6K}%-zFJQ?}aL+Q{egUb%UNam_W?ux8B~N~O|kQ!#rccq-a+uTfS% zdfy|`J)BSI?%o8zo;~+_7vmK`m#OWG?@Jl{OFT-asd!gH@=Q!H1H3sYc`#-0pk;8_ z796%~IBDZZFk(Akc_$n>@i!g%v2n+ z1;=f{`h+CsDry0qwG56sdR_&o`wgu7_4>!%^-eg8JL?@W#RW;pihmbae-Z@?T1~}C zcRT41W}po5o1?rjox#osF3y2%8N}BMHl#C5{gH%tlxbV=OS=W;rHb8A1yRM=6^iHH zrf7a#a5x^N(NxUY0&}Cn-m6L3rAbZ9&bhY61xFB_c{5W?k!gOA4pSkJG$^3)D-=X{gC+5Xw|mZ4hd4isQynM%V5qcdJWfp*v%PxD$IGU(ukE*HQ(!* z-~fiyjka(O;2Ztw?wgng2bFw%~~M?v#3bs zsE2tH*c0g1WMd@OuW?Nj6m}N!WAN2~t%g`UGpuSI1Kkt?9n{;D=JwTPM%dUYb;opAziM<7w$f7{`H}|u;*&)+J1rUuMH3) z2%=;&JgqH=D>>24qQdkm(kCWu0b$QZ)tZc;s#@^zkH)>AsQEp-7KOtmOuB)-5-)Nkqe7txPmqY@FH1 zhv$o)5N;?BJn~D-z(fU$xX*$Ed*#hTF2Ddzy;hVn+ z{X)_m0kQ`FJ6UOTAR7JJ0Ghx4zq(MEUoX0L3&!Wgp!&(#s1GeqLfg1OXXoW?*#cbs zeb&BDGT{iFYql4A7Cz z5Hi)GX&yYBE2xmN?Er~CQlE_Pv z1x>0tVS&|jdSK2D2vT*{!zP+Qt&p-#P}>&T4LZ1O2Ly?{tP-qdQIT|sS+lG#(ZTMR zYfbF90dag_`V@9qRp%|*r%&%EUCLnl1(ugv_GRspRBXoD+S*>xzDalYCT{@b>kN)9 zxZE8m^_xiEmz4ZXI>TkA;t^Z0*;M>-JoIRqhP(DjWNJ=zPofea7jF~LEFD3LlQeINHoD+C$DF3aqsEn z(=Twsg3DWfn8kiBe0uJ ze+KPFfzu=yA3vz=e5Y(S9MNjme;q%_)%oM3TaI$;hBvWg%ax?=`3$}#X$IOqKzjTO z#8*eL8wIf$UC-aydR^7}_txnh)q!Gmn;=$D*sJ1vBC`Z*nL+*CGG`ULf?L_qbRE4L zb$KwF>dMOuB#%i3muS+LW{VHau4hN+R*ZnfNNBjasPH)$vngb264hj)!X{$cMohRw z>?#xE=@iB@7Aj(*mYWa&b(yv}regNsGNEdn$(q;>ggfwL4rp}WXUZ~YO^&bt9Dj*} zQQF<@w3~_>#}zAtU|$rz_71S~g5GJjpO%GH3CXm3C?&U)i~-$f61GxQE4gP|fuB6) z^@}`s@bKE`lhns8>-#13%Xs$39!@PgI&FyOy!2`zc&-;9PeuFMLA^@W%O&gKd_%<| z#4Fpc4(_faH@i$lr>S_x?W8~WA{}#S3ocJcvX0=8Ef}#3WRH-2`A2X1{6 zGhcZl;UgEbF1Utpr?!gez3X9Cn2O!;D0|M3o3?@uQ;|v;WWH*UxLjhcQCL5LE7BP{ zOvOX-C^>iC6Sm+{m)u>KkR*RqQs@K+7_-3op-~MYd`dw069y+n1oqPcbDiRL2kfUH zj;pl&uw-=um|Y6{34s|^96Q5xN!?>`bgv=`jdTD2AOJ~3K~z2l5mShmqVSasbapmy z)K*Bh{#=sK#Bzm%J@wmzhjRt>q%5$Agf$C_CcGO;O4EJ%a95h)&B{107uGikSs_{zqUb679@61Xtiu!*3`Xj{#d73 zke=7uvi*X@g5FMVK$A7Y#Sv0|1KTI6YS|P9>0$;N!1U`NrB(LG*_R9Tqt`2KhDzV0 z5&(I*10fZgSFhjmI&K?T1~(=p-7YD6iK!^V&qc~sU_T;A{Ej63cNtP&FtGmV^!J6c zS72`x*n3~zwn44U?FETWg)w8DRViCtCU0TnUw9eWlE9cg^D@?qp)HRaV;FN5v7jQ^ zEMXSRuy&F7YVj)oT%W&_q5SO-275t3362C^b`ad zx6(hmi+FRCREw?)0S3b@)n$f`-%js}9_*md_2|3-CCOJ#`WS2+V3j|G9TLPlblsht zlkE8L3SbVdcnJ2r6&~7z&NI7!&Kz6$F5{z&|Dyx=(4=e#Xre~WR&tB_fvJbKvh0do z1l(y2?svuZxI*fF|C0lpXj)8+n{%pKzVCVDQ8H8a0`Qv)+qmuI4tm%1u=nH~;@DBH zo|t5?p})HBuE170ZzwS{zd+~I6i)^H#G3_1z+&U^U6`}ei=W>XfjO(NmclL3lo_rTu9c|X|g!H|7LFLx{;B_N;yhm6jM+JqoB!I z0At+J>}3TZkZ(+2JZX`6mrJTY53E6Z1?Sw`;RkWRX3aMxMc}9{n6Gmbs$Aoe+gEuh zM@1#;kyakg#|}m%_~`|RUVVHp zo#7cuh(|n2IZsl0&xOkV}S2TM#i7SzE9wrm78C zIbLG?pJ4sl4+3lG?%qsT&NBYx6Xf?BOifL(!c<(GkWAQuC*6QR&KCSzz16Qzt7R+m zDxXtvxl7u9{qus)e@Y+QQd2SMF5B)N+uJ`V8T*QX{j?y~srY0soLJD?IB5&ADTBk7 z0e_jn>{fic9X6yh98MYZ9RceegC~1?FxM-Ny8CW%t-yTuy@RojA7pAOO0%ixOlK&# z%Txj$$}(tl6zvJg3CkmMJe(Wo?%u?Pi7fX_OrCMR9THU%HdY~NTWgBi#Iz0&+jTi( z?FNCpB&yXv0f7}Xu-d7TwC228w0s5Tf_|2(3fDSV4F=|d!t^N;3v$u=PH?em&GPH# zFBLGb0CrWbBa*j`6`?NyV3K*Cu5=fk~7f5_1`zB`!g#0{x6py&_P{Fp| z9{x6+;c;8=s4ckrWvru}5kabKXj@}Ajhwaj3hcjr`7P2twd{*SgQ`p{9~Y>Xfcim+9Zxkl9Q4h zn=j`fc?3C=sGj#-;ySj@?;?@YmcmR*lE)?1MXvRf$q^EhlDow9sQK6;;`Of9>*0j{Z8V=*eeEZsJ)Pd+_jDglB*3;f2aZ zMP2Q2Ij;@^ANj~f2K;_M*=&~k?z`{2C{)@~Z1HFiuYmoc8eeVn_QtBDm6tHu!})~H z&b6#tx1IwBGE7WNco*a~fZo0w%OeG@?8|YHsd(BEOlCv0M+%JDg2#tCs>|M(&d?qy z@WfCDSx4}bx(@v13CTO|7z5y8%iu_z-SH|@vGvnWFf}!W^X*9{96|o6HEjNsW}4?a z>A1*G=lk|EVGEAdStu_z6~DZ56o6k3C`>~UX)5r&od!AQ%p^#5sDnvI@V#&8V_TPy zY<7=p($TqTPdI{iFE7yd-*Q-Y8*INh!-H$!@!1g1yXUJM!PCjWc?wWfMBpNMqe?f^UE$MA{5xRki!brh*%Sa6)?#9Le*_JKE2&- zz8rnN92N!%pX3hz828e_5FK72d4+=^6<421=Xc$@^|ZCM5e_&0RQ;67y2HZ{dl%OO z07gU)r~1;%Ja8&|B!u&bz`R7!_s$&7qk`;_&>5Fa^huI^lE|_G&iN4Um8Z& z>_jzc<)O$sr_Gllfoyg2eij@;3)$+t%+l@E-(4sBPg_?7O>*Hrz3rlnC^}?IA)J!H zDGH_vk5!k8&cx{pXCbm=10l?!BI^$k7g0T632+(&PJC{pa_8oI*LGuWysSzUG{^9!~eZm7~QX zrP&|oi|vCh(NEvW9NC5tPLsAeHs=(PVu5|_`!Ga}P~C7O%hp5B^2vFs^~uRVfYF{e z)82KVTSv5W({ua52ScKR@2l^jiYBUP(h(lg*ENu3D0e%D8$wJqKSn5^%g4yvFsft{ z@*QTw!u?niALC^BF`jL?kX)dTT`gPrjpI*n?es33)>cBLEGlGTFBRmP`t)UOf*PWW0V#{3*v&vLV4Ze*dwjg}-@8g>~L1*WggNN~NMM?BX zlD!gZ#NdYE5sun|ADtoJY|a+EHJ#z8E%>#7V)8J2x9)tF#S~xvCB@f2Wsta5VjmDZ zo;G;=fT*f#+f7ARQu357i2qF#J0oZ_72k;|oWF^p_6n3ONZA7Ul&IRfPOW;9Xum|J z45VfJU-sTUK8~xt|9$VSc2*BZlD&Q!uVuxFWyi5iV#VVS98wg@b0W2r^a3G;rc~Xf zEtK9Qy|=W#pDf+d+ZF=1Ep4?w87PI+n9)q~{_D0#3mpVw<&yE|ugW_ISxnRC9M^Z9%^o75S%W^&Umi90M!C}Q?> zYXjwmB;tzJ`U$^Ew*=MfBnksb)x&ERBu4#0&~r!wu{k+pi+K0hB#*d4p2ZPD{Eb z(n?JmoJoIe1q7|32DVO1;su9fP^T-ah-X5Oz@d{_?PI~WFn+a+QDCm+ak1>@S&D7k zxS8JG=lm1tql7QN#7-8;FY6=$^F>&88rMpasb79yb#<%#zW2|8j2JI^U466@;m%dW zZaLG4Qx(7DZ^V?zmUE3b<#F`Mg%!EQT(u^GMt2MGG6yR!Fv=u^z|0Bm3qA}hz#JAB z5s8@-BmxeJfKzl4rYF)wQ@#g4Ess#j!4BYr<2d02-P7%?$jvA_<2eU%>bdKL+SngX zAcF=Qcz_LeKZP_RUhlqWIgy9t$JEEfCn>6Ciz>(pVB((@iJE=7iK=b40V=0xQ8hH3 zWmKD8w5@R{THM{;iWewu1&X`7TXC1-8X!>IX&|_}I}H@K;#S;UZoYfY86$s^KN)W_ z_L4cDy%t*SR?@1_O^ zh9cIx&^efem$?@P*;SAZlllq{n=3^E-op(a zi<4ZM@?5%=z)zVGvK^s_lpS6cN->%Fg+t(B6d4(NfZ=J2u6-fqT6l`&5#5z`eEi`f zSJf4ofY1BAWx4&VZ0Du?N8PM%$5U_+4<#n zRT>}(0K>R;t2t0n#z9oPVclHHd`@BAUNSC)TKk_l zmK~W1tbkXko}>JF5W(Al`^C+I|*+6GuKU`CQtMI=Sr?>f5egC`XXHigVaffO5J_-5+`AAir5mP`#~!S{h3n z097VNRp{jVY$F1137ndK8E(>Ml&BDP{g5=+WL~Ra@L|{sV^WQ)`8=& z0gW9Zg8Fs2WmgpDusYo45@|Y)^Z}qF@3t!Qq!mg6XuQf(yR?gnV(CU@g1dk04~O}l zP-@3)$wdRuh2BQfN`l)&GXE^{xEdWed*b)1zNU*J)0@az3iiYue8-F*3HboGi=xJ~ z7hCl@;3bLharLg=)&R?j$;y&D$&o1f@7zGMxbwkLwx1%)G79fqb7g*rGFG2S(4$ae zi25^wgD2QMbk_B6&J%gIJIJl(AmvB_tQe}r9If23WJNMIB&_|Tz?W^{D5b+U)4wgK zGtx*33-nxNPT(v0v-kIiAkGrRM5yO?d4GDq6XS->J>F6rgKo`vQCV4}0I6zP9_z8{ z>i3MlBRx7@_;9d|AsD~Be+oRzj@@4{w#(?;;KE3wF&91JJ$(nzrmv=$LDx6`%5V~_ zLvYpt?>=_=zKAo4+$o?GYSyRMsf*6$D+89N!wd+D|BZ-($L{{V-vGIpbU zk?Jq3rOBY$woO`DZ`|7L(uc-POLN? zPGMQu9pC&r$NJQ@Q83IxwULfurMl+IQ)lm9!lM3bP${`(2@z)LChoy~d5Dse17cK1vF6DHHO0C$-qJKI{b2ydQGil?_5?uGSQV zLe36kDn~hrGQ`~i1ASq`7i{kLJ1thVlnGaxGzmRH1+ZmQZgB%xRZQ#N$9k1LCw z;BdGGosVt2@T>F_ehA`EmZDJ<2{Y~FGAAvp$FAgRb~( zN7&UyQg-IPw|}qZ80$JwLsqO-!U%?ktWJwxk6QM4rJbTqIQ5tyvi{Bax_v{V3h^Lf zksaN2`cfJ0WcvDfOxwY(96!*vwCb@>vc>@PV}y`qc~NcoT0Talg#;O0iO^6@OO7z< zb!q}v1td?aP{TvUNF|V1Xupq2o5NP5MFyP-ZxOMcGt~sf;BNn_d&SOZv>J_{&A>;%)k@2??tBmE zb#G4i@8TUGP53Ti_;rujuPobk>ii29{d~y~w*+{+w7fIM-%w`oug;nbA2z-O}_)-TvJ4#~+6K4nqfR zLdXUaVKfk!pwk)%=9A40u;Q9;)6yDcwwr!MvgbE}ZH)~7rDwpW-n#A+=sx0oQhpKD zF44zsw8}d0;?n3j2ttSS(@q(^jOH}gdTZfZ#8u$o?44WG*1zj9+Zqn*?hyiHp zE^?jsaw|t5UOE?-a~sQVAUipy1lk6a@$|@&HrC&YQdd3(T{I3h%j5!_;==-ALgT=A z_nTj)Nw3a#d3po6i-`^0Yt}EEJchG?t@!fM+$8!ucWnW>0pMnPn9|~@ojIu?&=HX1 zmthH_CYF~`5G5S?%)GS7_^^CG&%GjLpMAjIC!|z+9w%J4j~<6HhSeR2Cg&&cD5?A*7^_EF14pE% zAXk<@#s7*#OH2DQCNYh$>r)C@KIz4HIj>s4iRkCYBTzGjtVHaSif z(q|V|l~IV4U}s>0VwuJibNBzD$K*(jJQ4$%tyrX3$h4k4$m7E_+iXYX1A%kj!3DkO zsPUa8w2P`dVBCog`gAAo=1jVBYNl5$nxc?HL7IfN>wdQbG~>dDX>wI;Pr=F~YF4ix zV0OU&QLom6K?_X~FWh!V51N~w$BmJWmL6BS8wr{o7)g(4Z=XlUzslq)8bg1YIrh*@Ny^`?s<)2+?5IDVH;f`))n3;8y_f@+=C6kgW*vc~As zdLqX2g8;{(-1oXdgN&on)YcY-mer18YMQ*0@aH|mX<9mBKhLDnkjdRk-LJ%vF=}Wl zt~v$9;H0T%vhYZXp5DoEoSwcYmIyJ&Fb90hBjgudSV#>}73*KEY@ctBOT0Q>&9jlR z5>k>QwRO@}^if}qAyioYD#QCPD|eJ9+?Ic66>_>w-iJ!jy)VXt&pyfnZ)i($vNgJL zI=Y86<@iGM^oP!TiN+&gT#v1W+tq?wS0khW)^i4xN+oM9SV>QzCQigLJ1wUsDpV!c z2>H0p%qGjtbOz7TOAho_C+oP9%L{TAGl$J+PVrMuSBnRi$Y=zXEu~Eu$%?Y-^MHe- zcUb+8g|3&;<19ENOzBs0@p`>F^W9l$8X8j2vtRRP0wF)MOL}@h=MP7K2S2~_ty5f} z;h*s6{{jfh@&x)Z`WW)+Gcm=Se0JC|hC)jQ?O~N$)V-hO4ljs_k-bkZ*@} z5BIf1jx7?-wQpf*DaTAhDH7XY$CPEffc_UR9c}Y4@;0WzK^m+Q54lX87d6}(dV)I|*3D7W^;nxa+M2y_wmUdu6i@#Yz~ev~79 zm@RX;&R*qtsV(@E4Ex+U9DUybd%gw*cRY>kj&LxGfm99-@xI!_i7gP%zg;L&H0)cI z)`6YdwG*EhoC8Foh8dL_K4a(rprj37H`NCxDw?v3B*xw!#$PEBNh!_W0L;} z5)Kz03sKP#Gg5~@OsGFV*W9mf?otYFfF z3&SlIXJ~{Yr%f`dn6#EH2N90j8AYveq^yIU-E&Ej5*0 z^=Y7ewEnc(dXgGFGfzcFgWBF#Y`pLIGmT$uxFi8Rhrguuu!!KxLO)Pp<-hlsZm=Ub zpHNE{N;d-w(~@mEyj;sF6Z)#j*}C00`RclHgbe8HgIC(Z52_fRsu=nabk9>7hQQ6x zQxJUpTk}ueD|AZB{WqN!5{r3n-6GMb$lqg|qOFBQ&P``G+KF&kA zy#1D&aZ%@H*S(96>rWjp(`Alp6-1!-&V0_lFC9k+R`4HLscK!zE$m)1;5ANNa309apVf+ z_K6st3A4F*%L)aFf)xbuI)%T%&J7ttU`D<@T04AeULdLUL4_+e6=Mq^-O*zj)(CiL z#o5Ab;KaN>O^UMsnv-s=Qug@OIWD_XZ6-0AFgy&N&~H}S9w3E6TZDqLvIRzPfZ-p{ z&p0u)E*rc-<(oVMq*=V3h4fOx3qGp-W~tOakrH*ob|{v8CUKyp0%VmWcskwMZPF@V zZjK_eG~(6Pn=>0@OknkhxE7(yc=@+mREy^gujz*@1D>2ZJ_>~+w%9iMQYX*JQsI5~ z?+bS%JD5HD*aLERyV$cfk4x-JrT@nQh}ZbWM}ZT*B33TB&Z4>x@MWNvOli-m7#*8~ zlhI%0FI4lLsIC|k-cegwkcSfh*S-&DBL^$CUEQq87X%8|(P$m(W9!wz5cc({%L4=p z%E@o7T36*dRuB3usJ{^5xr7|@Q!*!_nFWtu%k8CrnoY$(ChU3*PMV%nEJ{v3=#cPF z8EL;2w~H}5DvRhU4_03FvY0@ua9@=8!?{b-eucu(^Ev$?;S}39jhuHmDYDATDCYkt zt@klQrmjB>n4>;Ua6Q~?^NfF40kUAKFl+H67>Qwy>I;b^*W`ptX1N9ft^q*F$iIb5 z+TYTEEy;bZ^xSFg{COT+R{-hWLfQ>go?jNb^wwXJ(JNkuUDMV1H#aIXSV>4*{Q447 zgd~!FuqDOu&c2#PB~4V4Z=4tq^}txm>v>>u8_<~#wZ@1AxK%IXJnEZGb1k)-wgrj# zj=kE?^7l7=)QdZmw(s+lhDh$RZBLNJv&8Um)DBzkS(t3Q`dC(v&oX6{3>PhFkSsLn z>)0dxys}=1$_s-V?B}SW#h{ZCUT7>R6&`3FWeWWQlOj+TPU5t4i%#%Kxc`-og}l8# zf0Ms1s!L#ghH&+`dWqZUe{Hgor#``6v^V>s z6pyyD;Q1Of3Q&+54j}qtxTrQZd|uE|Ul%U>vO>a0Db~07m_${(B<2|re5$}&Nvf<;kLx^BGdgJIrwlas=$%)xqQTB$p<^LMx9TxA#* z)b#w-sKR!DlRbVZs*GKVk@C|oc~lVm^K55X@zzm@=PAhYOUhWVYXD)7$RknWouB<8 zr!|PESom{%u1OLelIR}>2mxefda>eav^rh_A(GZ+dF|dakJ9I3N}a0=x{XE{r_p=I z%Y-<%8yD!L^v%Qyo?t7M}`JmyJ73YFbF+V@w-cOj|^#40lFqt}tPzo3Z0c z>5k;POrR(XEt7(>3^AMScp)8)R^kqor5KCQz1i4({@mkRs&H!a@P338%CEa>&p+Mm zwsxI{XtY9tfjaQWU>L(lSh5%|oZk;EBZ67sC7y#4_HH z7j`EK&AI4$>hll=D_A&K-9>kkfo&Rw{N%M z>l>}3f*@ITQx~<8>r`@y7eWx;d@HCpALPk#e(J3k0Q=@E2jAw&A?q)`6Hc`h#Naa|i0}XZn*z0E*UUPAx z`V>;3e$NTdNsBd|KqBw_u9GPiFx4{Z9OMa3_6nmj6!$@FXiuTcM$k$Z1iGE%p-QEjWS1=~dqli%5cU$FaWGGqqPN0TB3D_Yd#G5_I-$Ql zS&CMNaCp@+%s+K0b);nV@jJ!eejYoEVFFf;XR-1?B{VtJ!kD~oxZ#Ki&*SZNXe6M2 zOuKzd@+(qKH;9YV-cJ}82Tn}-PUr&sRbuBI#7GvKVCuEjjCxZ4{oRxV7^UXBk91#* z97NLVx&eynQrItQ)EK$EbFSRxzIXjmx9ujA>@Kx(%>YWgC} zvg{PZ@VqMq&%fdJaj(aG6f-xw1wxK@*28^15A^%Lnx-Uo&2;hj%!=W6~->;Pu^9-6d$^bA)g_j zv)ZAKN^}*6{(}3BRAT?8aVEbIt=E^rVte?Wm>dz`3>&m~mVy%6zVfCj@uRaz`~#C~ zIxqXxP^1}!Kx&Rkg2--3%k)kKH<51w4eKsqmQBbxtbz@{!(E*wnY0NT>*$=T*82Y3 z#BJy?Exy!O`vcMW_yliBsY4U{2neKq*h`A9s_RR3Tw-~Y%%zd)2dgRM!dnFdtdc#QGb0#D8k0!GoBf2b{kC?kqRfHDH0({un9^8lWr8(9(K0 z&GVW&tl@e41om%jvhirG=*OfX)-rwqn@NBb9|Hmp8g9uRCAx0{e6O27{&tzM=hD~`FZ?OGp!QIY=k?;_gn4rh?;s-vEh7M2hTaB_RKUmb6fp_x>6CDg z>K7AI#YZRby>twomO}4%V1)G#kW*TB=!(Os>6Q*6M3f4UP-bN|wV@R|OU`ta*FMy> z3IjSKL3{jxAvRp-8(rhS4M4d`f|glrJ(GI6vrJ9&bUZig ztJ{%ub`f|aSU$%O{-A|Sk=#N{i^OAoF=k5UAoG-zkh{-a9SWPGUU4Jc7Q?ozO%5LY{i!ZWBB4WgXTw0EtM3JD7v( z18Y)mN4NZPf~aQavB|*_E+KnDc$ul%b+P8q)5pn=_1M-|lLQ;I4M8T8oDPKe4ZtJ# zMoZoRuX&qRuP0{cIu)~Y_5hQB66=q&jE|Ft0t(t7v9^@-?>QQQ@lpLIGUi`kib6F( zotaA7`&vH@qA$B&o)13uK%G7<>iy(;n19nMPyG(bu<%_4qt7%F4pDsV#rG9!bs@l( zy7C1zqT}MA)&zg#_Q#{F9;Du?*vrK6cV$mkB9YF#?sNy+;91N;;y7CqRNwT_4kn~j z3Bf|@ykL^5$v%t`MT$Q~8+1>tPbLzd75^^i{sEY|dZ*DxmY@qRY4>bC#w7{T$&w*W zd_oE*0ZHQVa&nc?k^c-rk+N7O21q7Pc9s-*M`B53QXS*=|u7k-G*8 zUDD&m4oouoD|qp+a>{(J&Rlfo@ggr44)E{uplg$c(b0{2sQ6rk@#47yoVkMfmCnk7 zpO=I!2y+~rOndRxaJ)xhE78ZG{eNdmzEuYpW9+o#LW<{K{M-U1oN{4lXu%t{uI57-s( zq-Y=^;*nu?k#jlsu+{L@{#&Zq(j;f<+rM?zqu_C9^1Yfk?33#{-iZKdD~MHD7?jG5 z$e1d8pgiX5u@y3as4-cGbG@~be%Qb^2PCa7VNEULTL~dnYg>;0N}_?=D0`qE#K`Ii zu4Mw5k!HA1i~UQ^{BCR5_#@EfepU~Z3eK@(+)h;)8*j~I1j4ZR=@>E|PZKXdbuJ?d zyGfo<5OXQ(H}yLr-xwj*FRS_sA;cdC%jd)ZR>H%LY^NjWDDh$AyasfRJHAnajZzjq zXqR?!dPGs*@7kWZrQmoEH;OY@tyiwzDa`nSUy9E1e-oxZUR+j69(doH6u1~4FZK|A zU?h;!_AXq_J-jnS1UK-g`EAtKxNU84>Kq^1a8%{t@9a-DIHtoRT7?G$Q(cCQFw{4A zEM^TB$GR$8e+LW*3)|<*{-CQHq!t3Fem+=!QALSxxOzTVR3q%l#xGO>Ojb!*t8lq) zNi<(j<`b43}3cMBE_?Lo1dC4TrTxtvTv2U zEmsvWYuWqEjD*nT=k@za2w-%g!$*}IQ#jELAq`a; zH<*U?Q}~xHbtDjj}F-c`9qcGpVS`;P?l*PjT^xn@W#k5Pm>!F3Y%b^(tw8x zsHI;+)?lO=8#uU4B%6?APfXnA`bStSz_9wi?9DUEEz+w-XU92$R9Nlo$xIosQSjKR zu7>XVgo{=E`9;|Qp7b*f!RA!^j3XCa@ajr$@Fa~rR(4oq6#z-9>x~sOYbrlud|^3? zXXqmDyv!nGhFZ-}*Rz#k4yCC)dUX&ZymgS`l~b#}={I z+9@E3A-?Kg9N_<@hGDox{i22{^lBOaZp4GGj6do7In091UtmhaK^m0att?xv1x=x7 zWvVcbKEAHZ>I9uRwb(KdSrep(Br2=`4`8WVz$6;cR09+LK$vBl`V@&!5)8&v)nbf7 z6y(bHUMiV*W?o7Sdse>`F8ne_%0W7ip8H)nV8!B&`T6HRrze@jp7ZgsO!+D+|HcEM@$qtJZr#3gTu=zpEtYgJs%`I zbxg;3nEZ&kF<$Y6TjRymk3&mC9iP>h7GBmL^!EKb+L#(SEt}o%-~K=qtpQm0>R`B` zqP8C)w!AKAV(8wqDv=xXL~s40!0nU(%5;99bA|iRyi1CWh#NY#S(r3U zJg>m<$Bo7<$6cm7k3;48{+80hYw?d8v>6v~~qD&|2%+=?%<7>RS8`6=HSl_3(~ z9@OcVJJn0q*+9XB5AlW0vejsP*}Se_dVMh<#VE5V-w>Y`=YzIw$P>SI96sD#=6^X+~V4gUX)}jNW^E#PP#w>N-<+)B4T1@X8yp=m&^^F9JN0cZt<#f zZ%2>@`>8<2>ZpQh>z2!_Ss*U9eQC(B8qfTIP)jc!%&z@&dF|ZbXudfKuu)y zd`ea1J5H?^Gv@fua=ew|-yjk8R{Oc7h^{lE#}|i(@@sSd1ctHTs?(2u7{-X!PM9@K zc!3Rfa0K7i0YYOP*JhS_9ium;D0t>n)8y_v&6lTv;J^c}q%sp~1agvPCa4M#`6@Up zu}(=XYU(fJsbJQmrnZ$H| zxVTiG^AJyd-=>mP{@#JB=VVv{M4Zm0Yxl6D2L~}chAA%72pL2Ov2bys+=|gq!L(fW z$|x=@+kS5SfuS^iU}?Q|YxyG-yrh`%fRamyN4)CezW>wO8WBR11e4<&MfE-L=wsL} zVy;iAl)owR^YO|O_g_fwg${vOrucK1U(d6K>%B?gS9_y^FT`ATRx-fIP8~INVoALv zf)ERnHQ3(iH-@8@6L#$8mC53K?^k1yjYmn+^T)2cnY-%uA`M}5R=OqMfvATGoAp}P z_d=gH(S9vXIwk($=bYE^SBs!``bvhxbh_?_O@tjmC=nMQOk#2M)@GG=q=#pn1{#i7 z(RLpj8fl_g9c#{(`y+?(zxT#5y_Tgu3@6^q&%$TPA`|@Kas5#CA3@C{}SiUUT;8mso>W4H(l8#0$b%}2^KpTjoua7?c2KQb$s?yw&Ej(RCc1@un0DQX@)rSK(-k8#jWg4^Y=>^-Z)l z-pT0S`cJPqDSZWUhgQH~rj+`jhx?>{RsnqmHPBl@#`;W&l}+)Oo`L)%S(_zERgh)F z5yc#lZ~{6M5K4U86MoWPL)ZRUAe3!(V5`5Eh+#)m9nm>1;jl{&^@LGBv@^_lG$Zo1 zS^h4d(sot&QFMeKkHgxUDIrk+D0$u+esd(i-h z&`@rH$X4%pW^aC&{(25h-YhwWpSDDXt;ikB=tSC@o6kx<$V6{sA70m9|ON?0C};Yxiac@6DCk@TsRJQ6cwJ8btzS? z&AJMl;UdcTa8zUjbAymQn*Y2#^e(}hd=MlR*!C9X`bt5iMEr>JPg^!*EtH|cc}eLO zgI9Y9f4u|gFhMlpgR6BgE_-k=snz7t8iBY;umzTPP-`x!v*zlr_OZP*W*=+sG+ZE+ zZVyn(9miplmkg6)7_-~8i{Blv)Tng7Y@7~9&8VO?d83i@Er)jN^rXtxyz3bcHgh)E zJ?z8Umw4!B0Ui6R9?eFLT!{qgw!eg-9E+Iye8GyhSNv~W6Grh@nZd@Pdtg^j8lkSG zG793fJO4`K@5l?Jr}4#2?V;)Mxn`0)XBiIOht;IWmQf;~3A|nE=pj)`V=Rd)W$gX>sKX)a(71ZDb!hVnCYQ zENduCH%z9EuNKd&(2(6HojfW;R6LGY+Ef9{TJU7<^>bKJ6_ymG_x3{+4<2=o;689} zX6U6)t3gaIbleUl4~e1RnpJqLxP61k_uJz!ZP1xAWlfA&d(CiwXHjOk*PAYq_0?QO zb46!kchZlk9VlE$MBKKSUz|bI;4%3GZKR2oet|&j*o`%jA+k_1$YGKHV~q4t%Q^A8 z?6upF`OdJiG!1qlxzclZ#3D?jV}h|#8aNJifdnAXWa;x6fA8Aq7JZ6FvxbjO$(%!6 zMMmk-riBO)e1TWkl7Z!oI+8$X`IduUS+>)!MkN{ zr1u7(jZ};4;he8Fe}vx6mQ9;iYKcYqfVbE2$#IN34L*Hxc=dfr+x}nTybh8?3cQ@l z=s7n73y(E3D3=J6lXXj3V-J}=B;To}&urvNWV{ukJK_5frK@D!7oaK@&`IxN}@ z^D1sEa3K9VM!Asn+W575e7;~gtjst;c*><3@<4hCOR;W48oihNKvp@B&%Iu{wTwos z9a0{n+(B2l4``|DtVEeBny)JdvY$1`myyf@EOkdvnd=2gL8mw&z<=nVT2!JH*ruvw zA#)2vZ&`(7VFb9?uL)bw$nbq{rbJS0vY=o>d6p-ant0~lc$rq>GK?;4pXrx@F91~8 z*YWR&2mzbv-hY{q1R^6NIkLVVA@c>ic$*s1{(CqLVi~nvc%iD5U(8t>Stf}^OFLC@uouyr^^xp@3!}y?T(9N6c$?~RSt$!V zqCA_syzz9(9#Vb(m#I7yhtAKmP zP-fFuu2@Sn*m;4Q+THL|&A-!9h~w@2{qg!dA=?-_e0LYa{wqp~E9PR$iq?)vtX=mg z)3cz4Ci;P3dd~&S*3lKK(ue8p@gyEVuvgzPalR{;JK)`BOkw^VMdra$nV8$qE3r)J zj6y{(?CY-|(75n9;3;T@U~y_Wku;hb9!Uh!M9amQb;D2#%?d9$1OMc6X!llAtdJbs z1IbV+k-kiMAlZ2nwX{ zfS9a$6{T<_K;}|khVj_q+R}KX#us4t5K)rgc6zC~^6_;C-Xi8`poF#Yk-)=+Tj~95 zp!wZZZ$Ock>87ULi+YZaKH2O;s_MaioN!7Cc5u!;&HxmgVd&J?Y?P5~hI-%*X-F?| zJ3Fy~(O{$1-qBH%k;Ky1s4)i=DGKbTx7GoUB)S(r_3}kpj-!qvL5=yRvIG@vF zc^n<+?oSV(P#tuhc<}N{uaJR77d11Ci;^HTD!lKd_wZGtqOE=XX~rpv#Wq^alYOCTI)8r;KKsSkk<=&!m`qR;U9~xx=hVus#7HNcVzfg zKb~xOTZlgO{V4wRng7l4S@1`;|6z?_|MoeCn=M*=lFhLl2XonFLMExoR}yh>@&*Ci4qbOj54@k#?8dN^+` z{5>Can;2@PaeZhlL5)DgeKbjJ5N9jCF;!R9a^)oOjRa-NWXhFZRvWtk#>i&2@vEi0 zmTVWy!DRd21HW{*($5uXU?#-V6VF~+Lsn}BQeCq`V`}bVpeH$wP!tr0JxzTbgyR6Y z;)(piM)~Db(ytb8Co_x`rs!m_=Fh}7^M5RW*cTq~Y|aEUZ#3fZ5Xs{pMm2vEMXLAl zlm9C89r&+gyaTqBx1&7 zCmtk!qnh0gcXxAyaeIFE9pUPZyz-wM^y!h0fK+{^roP04r1K&D+>3pftG|;OtOE0o zvT5y^&viy;ruS1dNT<6bk(tr$U{_LbKZiOT`LMK5=)~30PD40eE9q2^iL?~ipGT+Z zyi}yLiODe6c}5^hc{5NZWaa7`#JCx9eQk^)d{9HjT}Qz)A;>fvCB^NOtmUICGmi>ix4UrVk-Mqgl2{M- zYg;fxIi@(03r`PT;Rn(;Ii?ic3d(%igtQPGLZ@B;MP*QQUp~G3jR|7l-%<-8jC-wp#|Akr+DHaPGmzAKc7B`rWxHy|9))B}$*=U`~=wH9T$Y zlMj7jn|Ds3rPX;=r;;d^JF-s+&&2XSGnqA6jI~nkT^{(9y6C%7*Gh}E`vzwUzO(I7 zzSYMW&z_{9qjxFi^{}OTva^{?;a^OpFZDwQ@lZty?DI_3Mqm7i!n^G(H+>YEuuQNR zgIn`(RU=_-e@>?5d=+MRvNLQf{iFs#HCap495GaZ8q^r}@yjGF=U+3b-7Z%+}{BS3P+brrv6Tm`HF>T-vz!;kf#f3$(q+ zp|^D&b5-r%DhF;hR$V%<6GKak@P@g(^F$Ft8~LDCk#TIL+6~qY(X)%f#Gs&@*m`JH zVF5ISdhTQ%zAkd&Q2fc7W!%?*mc&Eo02?5aexj=JM<{l=qJvJ$TR}zN9O52gu!Gsc zK$ZtZ2Wk=EfdvBi^xcrcVo-kUMw+3AcchJmnyizR|L68|BslyyVw7ynW=wS(dHwv< zlNG%wr=p|^4dQW!aXmNhNO~RQ){A0{M#u32{Nc89G>o;2e?bdPOy=4vEMK4@WH0f| z7)T1}*0a3aEg05I^2w{^(}rFua)<@&arct8&wy10(GB_;Z318VYsZJs6@;hqd}fE0 z14IZ5js~%_MtBL+y>pcz1VuX&j{vmhg@gEuo?T(%aRy^ORD-GwDVJ ztpCJT<4Qlsq^SsJOd{$CJ13PiK~0w0b{i;Ecd20IzouO{Ma!R;$8N!j=H5 zZuLiK)sD4t1QjLgnphu|crt`3rOnB#sY_xC`UMpp*aM|M(4iOcwtb_d*DvQAGN_@n zPk`RdEMffzR-{kH)pZF;I-J`rB1Fff?l43P1SgeK`5~s@l<#ZHs@wc7VG8-GknWE& zHLD*&T1|08c`cj_>1=N`6pEw>4JZiNEqO6b`V#YN2ZM+!1u&LVErL zOWzoxDxo@4`iJb=k+06z4kIqK_CoBU-Oyeg0fRhI(AVzr&x2oT9RGAzrbZ7NbW`*A z>ijR85*Gynz*oeR;7qB>VMz{cmB4f3m5CnY_2JMuZ1v@~DG>pn6p4_}p~Xc*w%PTL zbSB4MGCPaSM97wrNM=BF4B8Z5-HWGasV5v$X$jKF<0PT)4ez^RGR&g!hK9O2fs<>` zn~TW9awvlehEo*G+T)gU(7_ZvR?YHoUft)Zq{I{g5v36w@pb+KpVI=_ddYIeD~7?w z7@MP8emZ;&%2ator}kM+(%IpsuLCwNU!Wp_52x9 z5lPUZj@~nb7$fRWT6MbN$t6OO7I(15!RxHWr>|Wpn^{fZ@s1OtAinK>J;2`6R8vfM zQ&&DzDbE%w{L@YUyC;7^&+1pV?xi2W^<-pb9Zxm;7atNh!jRPIM-1}goDJFEE{jo- zkOwzeXiL(5hTEWnxi5miZW(Mywu-kHT=gGSmjvn=%v7EPK9=w7$*9SibdI@n`}*50 z*WAfgFrOAf^+Iv^?H$x0+sW!<@oUvl2cmpir%lhuT|JG9*{U!H3Sbj%Kv=r2BkmP_)R%P#U6&nZmkRh*zcpr%qxdxlsd|N0$nNbW^yQ0Nt{ays3S>>V<;9a!0K4@c+s5mG#?9T)S|f>e zUc~VGTpRP5D+9IO8*z5?G`8@&Nv_ezV#C&NfW-^RU9_yxU%SLpR36(E!S(L-Kk2dp zbb6bUU<)V@u$1PyG`rH9-10Jp2-$(^o}ADMg1C_*7o;PrZ7z!dy|lQ^N=u85o=20X zRk8F~Xvs?>FOSSi!^PKx@t<8ss`$9vY)x-q1d?C6h*#{)Tm?U5t0a}2wkMZeBg!vV z*L|{Q zG<)b+c-c$PgaM%Y6T|6!sGnMP*~ad1EKyog4vs-qo%B59Vf@iPjOeQUYiCh)N;I$4 zmFts&za?_MaexSoc@dUTz+|p^x&LF=4V%3r<(c%%6KwJ-H?B65)V`rB{b5R0o^nA8Lz>oL5roDW|Uxj+G3WB#uE(lZ^~!1N=iZ+9=@txko%2TK_}a6*$!zEsyG9eq8~?Jq_1tl;Je}h4_Dc zkDUitfC&c zw5^ZlraB;%KkPi;RG&@4ao&Rn3P+cj-viwch@^zf^WlyS1tD3KaUe@quK2zP6zuKs z;S*owZqBhOr@8+A@i5=t^NKTAn3zbG-=p&}B!^C>9_8{)(l2K<|Lkkk%OzP0c^+xD z`mqmc#kDz!N=MH&4`W11C;6XDpkP`eY~0}&QW_AR zXRmcS4G0nb8OFc{q_?NH4Nd{IMlw9dG$I)8fm}+IRy8^X{w4K7^e7c`G4elJ`Ol8a`Vf_lf=xk*BT}4u97*gH-}}k4~I89gEN+F0+B;@ z;40-l!k%~(UL%DxP{+7d#Q|d^&|+zAi|=G6OoA$D<_6p1&fl-dgB~B1(#|#a!r`B} za~}i8CtOyd_~>dQ3F^Emko^Pp^Y}E|J6-+--EsKCxb>l?wHLULk)Y9GjpRwA%3Q=y zdt#2sV1iJi7$eO;^LS#NZ6mlBhOWDqC&YbWN1N_Gl)#L>uXvT?iN^LsXY{48^Kso| zCd0PIEd%!Ap^0QrAjx!`=<`tM)xEK3w!>qJh*9A_8j;3)4`Jn@`PlnlZJ( zhlO}Dn*@)Z+W$n?JnoC<{?V|KsH_FGGNR2^Q=o{HhcfsveM_M738nlQlv zJc}wgvr*pIRo=+8wKu4YK|Ct+=3eNy)@2O-bK48`9fxno$hgVQPL~rIhj4sQ-=JQW zG{?95QP!j#4%JONHww{5G8;vt!|D|U)c|&NfsZ!q(!oeux+i3Z!$cI@4d;*Opt2Na6>r2iAAF zGKfu0|Bt3`4vwVz{(d$a+qP{R8*Oacwl><>*2dY`wmGqF+sVdy`}?bUtGcFU=D+T` z_w+d*T^*n>kTZ4O_;@;r=`NO5ZGr_y-XP!KN@doMc-Pj2Y8;hvBbkEhAdG(V_m^L1UUb+-ETZ*;lGrgE1zxAc9eZ~#*5jzfjU%qChiWurwldp~t&rE>an zvY8&R3pvR+`b_coE-<~7fHJ(ykUqRpTL^XJbgm`3UncDl4?&}5$zX@y?X=YK5>w;O znPIs6(DeCfr6?OJN51Vl&X*3_F4nPuVVmxMY+gtec^&oP1=uX)=V>%M=Y5cKksBC$ zkL{L$aI>O!^2&l>=-@{;?X>vwn8;4D$n;BD$(v}zDG6A`l&J@iBsWV3vAbHq9_Jr= zek|XdD6rpF-IIrM9k+H57TJr=ab^`c8O11<#_}pwqF0R?E&5GD@TQ{{HFAL9?k6b2 zvU~TLRr38x_%Izx?0%H#qz5lK6I2x5aAo0Zv{`!4ugDi`&S;lIS+7Qw8OB&igQ%>| zBO%J9!$8I&6~##z&dgC3Q#3WHljtzoGOp35FU#zMhXgwT6)r<=rNzD`1DZ^uu5f3Z zQowbSXW92lKKmC3wS$bA)kkRT%fAUWhWqcf(McY!)29L&U)%$$@q?@J{j2fDZ~oV< zmf4lFp?<1mL=Pqn=mqD=xQlI^A$~r7aXXc_f2zZ{7QMP==Jf~_5=$oMb#@T!q*O6Cmuad{bZHe zE5p_GlvgQniY z)o!#35*K*FLd!!S)?ZVL9ceZ4Iw)Up&{%9quoeO!r{>U|6GSMNrv#vgNK|MX%au>U zv`4%3Xv~Bjh9C)Fuk1NDZZp{oDji6a-^9VU#j9K8?C>C~Z+ix?%xQwhA+|RQRUT>( zfknoJYvXC7lM3)`4=y)Ixw+SCNy&(znMEw>Y&AWjbXkL|e$@IS-P>7ttulM2;6=Sv zG*sIQtw#{p9pVT$_fI150PwHqWyjc3w9jR4v*Ru*|z6W z81oyWvL?zg8F>3F9KaO213r5)dG&Dm-VzZFSl#~Yqk3eMyc9Ike=U~Z_u$&B>?GB3 zgdPMm(@U}jPEYWD)JY!i!FMWB%6MU-7MC;i3CFb0D88gj-8X-^G=sG(^opMW6@ow%V{bcS;Ei3%|WuaUQx3dmH>qW0cjp^#rq|P({me1%Nt*?$6W^&)ZMNZ*F zU@mp~!o-x*WxwBC__oJdK8CDc?9geAMQnbc)TEE$ zt}&WQ$M9%UfSHIwn$ih750a?RmS!rekEkaQbL_?6Vsx7?2*pYJD*?!K8w<@S{U08v z2GuYcGcR2(hVS_+f07$x%u_H76Y}a*FO$A(WTlmpVo7~J_7AFJMOLxDYodra&wX7D zaTx8li`H5%TB}!Se}rmD@pua+mAFc#@Fe?YLBoa?HBGKObIM4L3&k*~ISM z{lzun93Z$D+;ByLty$RJ(~7Vp<0(h2?v4H9OD3deA7yk@JFN0=W#~hDdPoh1Kh^U{ zS_A)ScD zg22_Rg-xe5Ormtymxo6x&5o1GaUR9Vja`68lbM%Hf6+Xu&*H*qhS_)r{gsn<|6z}8 zHe0iV+QxptBoAQCV`~OI&9iK1xr2I^QxD}}(klNKodXb*PBOJy@$XvR7KTCaGbS*< z-s@LWNAfKNt`fMnKhIdInFIzl{d2|MBM*WpxGikxg}x<)u|qEPhbqMlaxf-^aqNxr z=X`Rxz1LjNcuLB|s-zmuEY&jf?Yc$-W*`RXu&1l3xt9s_;clHs6Bv14Gdwzk(d@X3 z!}g9y?zeu*SbjF~Tng?ZgOUdX#&w?%+g$&cP`em$r?{3TGcBW$Jo|8DA=qf8(L_5w zPb=5d$-`3R9!d$_3uA2;i@mHrIzsp7(dGpk6;rYN5%S-E(|C?hPZfD8_v zvv_O|D|8O#%cOEaFPmt(^L?s(7HVbia;;($*`K)L2v&B*b}dM5#**wAV-jgROjVG>LeMyY}gFEqtP>;cIy|uUi`Mc$XuOL*>29^ zTafwEz34XkYm^UPIgQvn#yY}RUx15DxU;|DsWa49-()+tyK)2R%2jHSPg8)j)VoNm z74sG4eoh@^vFMJ&R$7M(H$J7+cb@;2(=wy*C)@>dZ6$iLwoWQh`}AgIcR5*&H6ifs zT|kP#<9T8C^S5V{kMa_A8oO$%CK(tB97A*vC(B=>nDW=PRy{{uZ{>p7DiXC_WTx9% zP;&d@X{3X3vh+jbPuVgP1uN_#;1qQK{saiVmw}|?{~YlciDOU$VcVJUogqkVl`ca(0nhdtlr2s2cC z%k}rcdP7`jcoG)iT9$MEmvVhu1_uY*-JyX$tQY?uF=v)}$udE-%3XXBBoh2}K|v=W zOU|y;wh*K`XlETwLGy%+(zw5WZlRSTx0{4J);v#c&AP`b<)|+bw!UuDbI8dJk<4n5 zkRNWh%sXAL3GcrTSvupvy+eYrIc*QwfBI-749()SC;H83HT1D9{PGVnatpaD1K!y| zuC~=B-jnjwkW83VoHq{0-xMlU;9DyC?qL2<2P%haDG*ntyIV6L+g2s|yxB%W*OFf; z;XH9?qhvLM%WO0707)5*;2m!Z*dvuQL8|C!{q0Odd6p_faUXr?K`N4MyVb^#|H`G~vPRO#9gB{}Ho-arb_+yeOrqy+jnrLx+32Kz4|Jtd?43J|f(cOg}!j zjJscYb-8?GI)0I7$2D6lKXaVDI1gV{2Lasz#Cz%6+uQMBepR{l)L05#ghT;}G{znR z3$%7mcW7N*o#Qvra3UB!_)!brqKks!sS3e>*2#EVPVyRa@EYwvKb`$wV$N$zC)bPI zb~dhsCJO+jXf>sT@pJ+V0Q@v?jygf(b}(r`ed#Du!FbZdd*8kKo_EFADv{eH0r!)~gA57KXanVI9Bqr@7qW)Q4c{q_P*{XnmHI1vFE*OspE7?`FRZB3=t zU#$50Q8>h>%2EbmGX#Z1T;~x>Fd4K)gOgyZqr)(SGX<%XC$%UguIhyr^)gb)`)`Ua z0rKQv=Bh~H8*ObSRj2_ti&jaiJD#H`VGE^VytoBk{F26VX2bcHAnNw z*~#@a((u&;y~HFG)1AoH+FBLXBpUYKSYVxg{cFbJM*S;uoPdi{0podaFE5GZ%8~IQ zZ0_o1&wSb00r>3@VHqEO#@r&d4S9qeBS?D`t!8i}3%St1%S7O7P^+T1|JgWR2B9$_ z>iF-+N_|%&lRq=D7Xq+k+-#?bhCz7Gi!l`_7Hr>e%;M0gPf`r>YCoheU65v zjTvVXDiAskojUj2!Znc4_#Vx!{Eo)yD|98M%bS>0!J|aJl<8i3KEy;aZLwV=x_3x# zv5c`3VTcKz{*;Fre9Fc3oGIG%>Q^^pgIVSc0YXQ&_p=)0X7<-!d z#=Bjk_pUA9bM}q1F;?K%?Yq{8{93}?L~q*stB#PST084S_tU<}#$jX}w;1777dTrt zHWT5Rzqyu}RJMM?2Vp_-Y;FT8lyOB5eBU#9U@Ft}_F&QxbPgnQ8Cl)cXJ}+aycJ{N z`>mdU$dS;#qw}HvLpq^_xH%Gn zL5wGwMk}wh>8H3Mhb;!2cBo4vIs*oKbQ?BWq7;g0WJ>=MEr!VN#Xs>t?=d%v?Zh80 z+|Di0&K{~pKZ0H{9sWZRb|n$}6t!qdPL7vf315Z05~<-wi5aV;@fw8+d2-cVVL_}8 z`T&4H7UO69EQbs1C1KoVnOs@XYz2D>17|XaVk|FD4YOXOL+3K+39OrC(cjn(t5Zt+ z6(&|wVbl>aT^?%3NMpd0**@U!{zhK)LckH*Fm3Z^da{#ColbelM}C;s=^>UcOHLZ# z=~BHM^)3(ivR1*Xlt^f{?v!$LKjY7AYEJh9#=2H=LMaxTCYCOX z$+V}p7LoFZxU6(CDU?nVOI@Xh@MGyaW2iLvf4tp=&3Mb=DlCE*R#vi)*x8Dx}6>b zuid^vuikoM*h7CylgcVXI+hY%uOfX{e7G{FwNWEn;jhyMmwl)y%0B}y;X5z$Hekb0 z6M%+|SoYXnmSsWN@-SedOM6ljJjYftoV+8{|Cn>yQdt#Hkuv`|r zVOE+Mn*EF1tG4Y>?`oko;iOv%=V-5;!2QKu^v){ot z_(RRMGzRiGCcXm+Swg)vDy>M=)vw& zIxQk7fkrxr_l<-FZ?7bPzlCjCfci^T4Rb{3YpBe~+us)jwLya#*i9>S1+i#UzgBv_ zFs5?c;8YupYDotdL)X?A0%-Yd*Gc?zFYcv5ykd7)3_SV`9IpyiE3u%kBt#-LYWVHAuudF7H zD{0>Mc7;&F+oz{j&imLm^*IlFrZ58@qJ@?@mP%K6lYl}qGemFQfhsk#ZB{o#0yKKR zp2EA2#BHxpv%kURf}V#qEPG~z<}I-;^CmHW>3f|&k3W9uq>i-?-wS$Wx9~v%A!(gm z6vGfY1#|=^HD&YnJ~X%9`g?2Zl+@ZTS&@;jQ(d(*C*JPl1Xq@$vop@@q82b7i3%tt zO-NWzkf@MK*|1DN@S3N`s*zgqPxsL;em~zmXf1%&B=SP#(5tjf&7^W(L5Xqw@sXS5EG5TR&Yus_ zW=2L$QKeOBBFVnzNnWg*5m_-1>XuF>G>aJYM@WB%RCQjzjauIaE!Y1Je2GQm%pS@l zNV#2G65_Ef-J&4{O_N8&I8){*xSo8`lV!C*(2_@^}bGc0o~6d8+k1x@=K%X&4P=>1LlK;aLfb~{#PR^iT-ft&^4&<>Xc ze!Q;f=_20SH)tCY?`H9vJwjZSNcO5Tqfze+8j8Tr9KCPp?a<<5ssE*@2~@7l^-W&e z6xWxBg-lSJaU`cWq15`?K;0g)y-3}Ut#>lq;ppt=JV{Cm0dY{(N)zGwKx4}8&7+Kl zI60n)jlXWd&6ttg7=73(^!QD%>vjAhM&LJg!we<*-yD3ELR;&F-GnjkQ3fj!i4XT( zE$iJi2q>3?SQf@p#_iFtY5uYQH7(JqmAmxPw250n#q?avAaVgSo0s0Yx7Cg_6CbB@ ztoQTvsH;E7;tBNvRpIxTU!L12q$KZ2zemRRj=GA`sc(Duh`;QYl>4Gz!EOwCK?m}iYmDqdEGA$`Sh)x38g{%PH(_0 z%>N7e@*ne7KnTB|xk&(o*~(MtimBS-o#S7va4vY!eA>Ztp6yYzrUqaHic;|>d>jTC zwQf35>eycb$UuGB$+P%)#RZBCoNADeJmVTNNp&MmW(^_gP+qISK zZ}{qUu?Y}a#EF*(q;Fg_2mjLhA(BC5((!@cSfO5Jep$>4L_I0YKdmV$<_r(7)kmxM z4Ja%cBEZG!1a_Tbb9A3I+eQs1whp%u#ylMJ>v!NR*(Cvbs6oP|=OMPlh#=hDw@%n- zHM~Tw5`5C$PuFOb)SXwzG;1;EIaJ-7o`ENe!+wO3wLXy?%gWtefBM4w{KO8zx|Po; zIPM#yCRJ6{`lq_Y+S!ojfZF`P1OhHP(VjO9RwXl?EJ^2?K5Uh5TNC(0HiB`spWLaG zBR`Ipza1UweK&)!#Ijh`E6G z76z$7mr8{e%w}(kH0C*3GAeBV5NfSTp)^L*nc3%L$;opUQfBuybL-)g>ERdnHYP2! zlDh4C{t@TxplZOLPXs06;uh<|n+mV2p&(R91zWGu8PoR!_`W@cV(n86UgQmJq#T~% zhQX;aQ30qJZ>zfd1W)JL;Kq=(dw(7KukwIyY;#cCjTtRlvK`SFNS|sK zLYY?=aazxlXGZ*|5+)>h-73Le?GxD=jeCLTLcO6)5_ zAeq%N<3hPq3Vk-6kJ$oHcCjRr2h+;JothF-z(SQAPCfi@*ypbWx&xPc@T zNMXzt;QF0(2C?1Goh!r%ASIj%&6sQ^7Wm=`&c1pN^!iI;5nui}$&=SfpJR;ez$|p4 zD8OZZMZNMRCE=*if9UY_((wMVrBHT{n_gompEhV|@JQ^PCiojohC~90hwG3USa974 zK^S2bZ}oebDDjF^iiVLMw~UR>9q*RZ!8@qHFu@77K>0QYXS_mz`-CJonM6f&goKp? z2NIo1B$uZT=@{8|SP+fYj7Ag^S5aU)4Phx{4%E2t!SxXT{%fl6scjoXtMfy_mZ3T) z&wEHd95}KJl`ruT55Y5P-?e5vf-`T9Zh?O-yprW66=c+?%91A|f^kvyX=K0t02oikiv5AWV`GItK?KZ-# zgw4H?E$iU4^%UFkC$~`UyVeSkWPuV;8N`eq-9)7(^o^3%9?rSm6$8(d+bjo&#lz|9 zCN+S8s47bAeZf#GFq%TD#6%H3rf1)AZOL<5pef++cK-4L^F_YzDZX4Q$KJ9e6=paUjoaC<1-E-%=?2 zFFXV$QpWU&vYVGqN7^U1m(e{YXBSUB8oqP8kI4hpVt0C9Kwtwn(T!S@7obp9Igam{ zo+=bOl*sJfpSPrYGc1iHJJnqI3jPyzzyoEX3i;A&ZPNk{E@M4Iqu3uh%cDTNLG;hTn?`J-s9SG@Q(7+e88Klca7HmID{DNJCD zfoR*lYYsv%u@^qT-A_#Yi!Udd(2@|&YuipP;j>1@Qik4a1w;=0h|jpOi;RK*B^Pq# zLmXH;_xJrt3<#;yDo>(86`9hkkUGq5A`RREV39Qn!LsCfr%vXU3yj|cd}k*Y{K$|l zeq-OFRxu45uu4Nerl+x9yk}Rvm{-hm7nzrS?nMb`_mm}Vc_f6eweS_%dq{N+^=UG( z@VQ1WCbloKmL>_7KH9A88CRxiQdx}Xc;B39=j9`;pXgB<_ln}>7|BogBHzu>2@r7FPJyd`|3|G>I%iUArB zswvP2JX|G7fB?qfMLGDkpr7o6-qrhUg|6{U-HED?iRL^QbkoEOZQ zlec24N5Cg5?b8N}BlA(QsWMF2@EhCNih|D`4x;;FLr+D{wx@@SqCWhIQyf-KXM~=@ zr@})v7B&zVk@NMms+NniCG@aX173~WCxF)=74tAlaz^9!1=}G72O>3BJuJ=5uHpPz zW}LOe_Ne;_;Z1w)_3QKl{@0rYNFhN=c027ZGA0Y69a$pH2{30t`z4Y!Rl za4qDn4(#qS{-RyptCkT4@1$_b%BDH64mz{QxWODwc%lz&U^)0DR%Rw6qVq~Rw*pQU zwJ;ejYP*dV?i=!S|Mb)a-|L1(C}yK-y*!{W=sCLp_@^q_$boTX#bYNfZh4}k+PzEy z9DpoPNox5&Z?5P8DP&lg3VHyAQ(Tc#9EpyJ*9P3k3K>oxhf^FxZ$675IyU$(;Do5* zoCVm|9G_YrMy1Sa|D7``>-%lC3mdUcC7^d8@zeivPU_0?wx8?%#m31AdVRnX)d*gO z0RXZgSxcL6iGqvumM2NVn_${CWQ|{$M1amht)9g1?4*e!k;tv~5%xkqhH9SWmt72~ zPz<13sZ@^3T%*(20`cHSw_m}}OESyhq_i+Lejhr;`E$9E_Ua)pLNWCHu9`K2$;njv zN_dn9`U=J#AI@qv@}7rbIvzgezNqQR6*gB6ZTb?b^qiJe8X z&~%1qx$HIz2k94sh^?J z?GZMF2rO7Ku)Nz#vAX8S>9Nc!Z?quMh&si&6Eu@64g`L$Nil9b<<91>x~LqT8v{~6(JwfH!A6%)Hfv8t=e?};J|@#kmh#u7^~LR z45>4}&t=kovI|0!BT%`8(KtmmG?6|6N%qF?6WWZf%MC2Ey229@0UBQ}STzLIP{hp_ z;F+9m;Oav|y|ZEuC*$&twG}xAUx()QYa1xY?L)o0(T3YOZnhlcQB*mH%N;oq(WZ=N zrhjueSSTrq?@Ky)1w3az-{e>Ox-1Aus)k@ej145?2*zS;%Va&8@H-XD{QUtG*FzCS zGkW41)@YosTJsuXw0DbobH58p9RHy|9T6Jsw_VqjoEvZpzQa#%l|mory=A_P=m-sO zO(NwXtS<0xLz@xTsFmwGh~pnGp&P%SFZk5s3?#WOUj!@1;~}Uy*a&6SC{wi~5B9SAu6q1;NZ((K5@uz_F9wGQW1)qSFYm#?&iD|nJa>P-}}-DhP{tfa*{ zO)WhaJjw&1rR@q+jQ_5;Bccs6Noa1b%Q(T{zx(#K{5>5hQW2k^u)hD8#_O9j0uWS@ zFFXM1u(Cyqr4rL+bje+P9DeycF0u00RZ{8$pthAG1E~MOr^vm)i~gU#VTs?~{{K~t zxn94ISA@SmIS0=nO~MKfr=15ieqFqdTLVP{4?$W*CbkQw&%eZk`?ERC*Ji(Djs;+W z4Pf^pN+S^vXwKElEC6yYRI+WZFx%*;sQK|3$?f!xjleKmtI4yY5x(W77$ z`}`B)<&)Y<0eXeAt*xQlgk?rylu80|$qb&9vLnCaIY0;eYSkz)^j8((N#?@vRX+v{M%Mt&TXsa3#h%35X-FrrJ91*(u_*Do$&%DGb8>c^fPj zbI;#b;(QSg0wNzbgcmf6*V<@-s_8)-B-s3Kv}7P;+Y91I()D-MV$1)&pHoK)`y3b0 zciV$PTfxQm^gGIepi!3W)&@4O*B~ZJjbs8m)sWUXJ#G>_xLg_(#-kH`#tWfg3hidr!`LhtiNNK&yNc%|FR;u9d3PW zzdNV5hdCDo=vw9J)s}gcqeP0RznP6+|2CF_&p8yl_gfQs$75DUOj4??5QYkFzu6Ne zVd1m1N&c^dEzkr9?P%NE;O=T=Luz( z!b~*Aq0f);<5ay}Iy0F7aTR17u+ZNoGp~WMi%fp`pB7j6C)VddNA0A+&`wQc>!lS>lVAnB1IcKf>1Taw+$h{-mNf-k!6B-DRpU4k4nmXs3QH z0fJ3#?=P*H8+k07+`Q!_OE$O1*Q8J21;73FbG665ym)$P#Yl?KT8VC^hb2tcx3Me9 zA}9RTp?IoK%gfZihG$p@mGR5|41NVy9L3CP<2otxB?LM<8*1f^K)Q;gtw7|k9D>`# zhTrH6qR`flulMQQr`c;`ZpYcC|Ins*D(aJ`c{9iCBYC(DqxR1GX7so`BJEe@Hi=Q1 zX%`9485GTb(U5622;xgQ4IJ{CfdYa`Z^GVGHVC71F5O?5Nr*kod@@t0S^r?PRx57d zCV6Q02}|CACovc5o}|H)c%0=mwzN9^Doo?OW%P7PZyq8T=hzg*5stiqof+i{ES69W zshp$H4FEyVQ|wuHWtRY#is3GlAovr!Y0;oqsM_kqCu|}*=S~vELSY5Ow;8Gw$bVb4 z#-eGmEB;|<{qx0I_9yDTeO_=Ewst4J-0WHUD_S*ax=iw3^U%1_5Aq0_G>|0%0ve-v zggg_jU4hmGsvLxCRPv$IxM?h)+W>gjb zcoa*EKeS@bTOhyvl_3Eu+&V*!^TM`4rx`~tG*JHtsMAjT)ew||wsPDg{9>K0`h#IU zzI~CzMHxAw^hp6f+9(@!kdFUC1mS#P@!oc#TMotY^;6w=7|z9I>@bwn45<;5+B{&# zU&~CfLGrM)sjxTkY>hqJ;fRvu$MP-X;P3KG9Oc9B$51mJ7_;6c(-u;Ly4r896Z6)# zr7Xd>QRKUnOH<_-oun9?0C{qylE|-rMoaRK@yONnY&kRGX`b-#2zgKc6NwNJ z*$;&OtYmSs9}Pjgj=|r-Ipz+!@-r@(Z)7@G-8RxSOqRN!iLro;Wpnc9Ga>R}RpjrN z-I`H0Jar=&^bq{H=tdy2wc1I_nM>t9S&YbOm!Z^eO?|w{AAyzqkda-{jL%(v4Qb!q z5OzrS<~gyjs-iXhIhtN)*RhO4-)(*C+-S`^S&@k>wnTB=)<7@q9;48SI9-!QW%kWD zs9dg4VxhlgnX&YZM8e#8<)_h1TifQ>H;EYli&fa%o`q9DdH7$vr5CUILWM6BgFB+T z%U4-RT|U^ZIr1@Es|^~E!b<<2fC;I*mSqs9b5MY;$xK}pp$zodv~R!_ALqafs@q?X z(%?nD^np%uUgj5i))z27Po?4mdyZ19p85(U##{A`b_pSrJPoDt104SZ3qpMe%e%Sp z-yy7O!!Rot0P+`*tez0Df&DWDr`yxdt7puGw1dU|#=m1Wf{&(Y;df^-I%NBFKRrs9 zU8>h)?bdoiKZpnWKXT+}*7r#YYo;ZrkGwX;KNgPM(|{TCgi7=~T=c-iLl ziV_z655W5I5PE6J{-qT=D8P6mG$p$dgGVvxpRiA~hAzE+g%+P{H||_O()N|J=2b}F z%PDr}$_omJ-qA=z?8$I`Hs_U)l3j?7|m@l zD+5Apa#D2M0bI1>Q66!!PWbBaer{^ZeUM5x4b-*c>k|;RTBPDJVzP=Gr@68Jfsz)a z)#srfj^a=F`GJ!S6woN|jX#cBs86-;*Iqy~1xUbU_6Ubr*-S5OD_N2S?50rZW4*H` zplSCA`BV@~SV@V^fx8bOzgz@Rh&gA)Y9(J$<0zR|!|39Y^6#WeycE^6 z%9z62LIuIuHWu`+4F7_T_?4UUI$iv_=MR2{E&L3t-q%}*yMlq%k%6^!DE3FQpuccJ z0D5M~C&RykkLHDfCJn9;P8i|hh{fC1+;;(cDqiR76jWbKr3<+Dc^Yj{!;~rf8relUUt=odeQ0zP~ z)r>QRR#((Jlkh8*{t|{h_MY4(!r-axQSTsjp~1`qO8k>0AF%u0e_g#-SrLoE)H-P) z4GC+F%DoQ}$tHMpCu1ppb^(uDqDrF8%#!z#j%ZLTp`|aOcV)-q4w;}d6IsQSF(MA>+w_fVa4&@F&{WC2 zUR9;v0M+lA{R?jb_+ZnNzJ?aRoJ>&Y39g{*MH58o#q9sr0hgh}g;-pQs38_p=VIvt;F+?!kKzjb07;qv~tZbSbz%pgL4b=#MUKg=2k zP#eaEMG9l)A9jaHipf;w1Uqjt&!UqGmmd7fznty;{^f>V9!xt&qs2%J82W~Dp^F-G z4yHsC4S#YQ2u-lPy^;WpLIaHLR{z67nTk+Dm``aw!tK5NlbYJN*!do^kPG?N8EVa4 ztv=?8FD?inkyk9Sb$Mu`YTm{M+buB^601XFppN5FE07@cKq1qmGTQs%9%i`2w_^V? z)YNNZAGn)gA7`~V@6M_|gu8ja(FLRDBQKuhH@g_I)SXpVdc_4WfJCidjpt8`#fY!X zgdfd)F5jxw8nhribaW9#QIMn$;2^FI;~2z@tB;fUdG+u4dXrafxZ)+KbRbh8!s?v8 z$-~*D|1e5!k>3t8k)MlFcWM=vpjck%M?%y8++sDwCbl+?R+gg>W2@IM4@~C%{CFhN z-fn%2v&>lM03F{=U8*=*cBJY0X3d+?t!en}|snZ0R=_wAJ9A}29G!(XP zUIr=qP~7*;!=P4jjsx&qCze7={EKi{*yfnh?eYNSZf)_v!NLmYb<{56uPin46@i=~ z`q@!*m^Dx`FQ*{iGt_$skvas{_AlEA4;yeD&*f z5*DvFJ)P&^38&CblO~3azZ;{C5YGxzxd&zV3H9zs{LJ>bYC+)rO;YOALkvlVh^O4= zNu~~Ka>39`t%in{hDVi**BCwF;4$2yXuaR0diSYA)0{*l=QbTPHjlNo zR!C;(K&^E7hPxH%w(kmJs+*wJFA6RG8O9LV?h9As$k13 zFkQ|achO|$sm-r=_|u5k6p{x1@!FTjy-woo6>8L84g4l7R%k3NPH0T#Dh)XZlhvHq z1d@R6+==TYb?F0hk%^O}h66w+zd1TcQLE#X3a#~l$fob#A7pMNw&0J`dNnaBZLmw*%8Fi6xktLd#x;ekA@pqKBf1a zgeKfs4W67u|2IPP*oJfA=g+d{&(_y&hP9p@iN5$zZy!%kTGP?e@^~*HV3EHkvt<5Z zfMFV*hQh$W=sUZ>()av4{>AuWX!R-SG0wmjWVbsOj$9+zL4=PF?~)k&+?IFShZ~JY zo~{8tio{bWcrf!?D!=bgfiWwQT{x*~`qQL7bb|iQC5&V>jV3G4pZoMCA$j1MYw0G6 zulc)U7s*SZLe6Jq+5N&kUfZo4o#uTpA>qf{U$5hZbd-%WS86cC=i#r&GM5ol{ET}q zz==YIYjcv(@L?&Tc)pGX0Gfyv;1aTT{#ZN*Ie}zMuoGGG&ShfzySUNfw5_*I>e-bP zrDZB#78V2^9tG``9ux#y8O|%4ngdQfKG`HePdqY?qy_r_wNMdkWjT9Rs~z(l#TB1q zZZ02O3Jr9h+y%3gul+2(fP$*P-RF3JZL(<<>PQpnVV6=kaiQ6zcbMpQ+(FR@ z+x0tnl1zoxva*zfjn1L6O*ofCVYuj*oJ{y{t!k5KnKKZ@5m>hDDEw#!uG@$#G;5S~ zpxqDRQy%83`PNd2mkkyZ?~PU|Uv~*K5u8%|dh=6RJ_iORSgqtz$O_GP8uftHb{LrX z8Em!O%q&Od;^ag~)sJ=>9BR`TtB45RP!@_ZF=Z|amZ*Pu^5Nr1Ufw-7ZElAUl;+!F zzjf?aM|XC-dft7oqu)^0KH{QeEPat6%V!d^sfj%WP6_HMf+;6<5t(6MjIL8m#6dL;1+O3LT}?E` z%G0RIvno$tU=0IhowaDcx#jrWi~aZhc!a*R%r)^ZjwP)7T)7keVlHzAsYcjCE}B)^ zTs8i7be*b#h?d*HMR6Dx%@hQCy~@}X@s*?}jm73$%~PCo?#uivG#3362)=TDTv>L9 zaGNqar`ehbfXtePb`?uJuSOcFc1K)y2*zD0lczv%Mv z#9s_}_^@H180}8I~p~ur{u48Tvj+_KX4vvQ?9F@F742T!Vum>{|gft(euc4nb zrA#toO`ph@=M#etrbxGK#OP1dL^OhN)zS|!TZ60DqxG^{ziTRFw7Vv1Y1g(J6^0DD zY@NFQS8%na=GJlTe8p2ji~yf!8*Kp5Aen{o5Pyax_i#>1BnSj?-p1|?y1%a;95`|g zXiRjEkE~#(rOLZO**)g4EFV=^`gYEL=frVqtx0@v;x&4(#Kw{lZNN|Ycvg)cgcNz6 z=iJ=Hy}-qTpF8{*Fa>kIqKjX^vaMN3#_M( zgm=f%Gf@q0dfchOcTh1R3mM%PcC8w({j;*DNO=);(cr~QX zdM!F~w1wYq-}%e^E_rep;ub+9|9rurtc@>|0dE_1aD%LrCJp;g>#%aM0_7vy#^{>X zXdtbfyqd!DLlp}2k{Ft+Zg|D_=FfJBZ$?&8aXD&7* z4#q*%g>v-wgItUA5HvS(?GHcy;ZBH%=t)P8m}XuXA$TA1;_q`0!7a1ge^iV}CfJAU zpg6wfbHYN$Bk6h%Tk!Wcu^%WxXK|Tu5w(}W#QaCpWraaun$nzJxf*hOc_bjS*4k1% zscdKfKypK`Z=bGQUIOT&>6 zDlBDBQ(nz%57ZS`>+Xp)t?P& z7ZqIJ7)n0g*{>>dDzu;Kl3C?f!X3;ae>PRY%C)}A=O}miOH#&8P9sB>j!f^-V9r+c z(+>L%>NiRr)HBDR2V|W@&Bk8P;4_uH?YZ`b>c1Ff2< zZ^Psu)=|0KYSkZhDTOaJ?X|Ws&q*Sc_6P;q%KmzhGw@*`|FI(+U#ir?YC-W0g5Rq< ziA}k&z#0-9ddla0V?bbVAZgj)4Qqq*A0Yb@n5fwk;p{j#au#FdJD4%CB2;?wK-jkk zn1;2NP|TxNyj9mOgN_3}Isc zjVgp*_^89lCW`3)5zl)~7Son4m$p>GZEJPG43V~2qStUK=`<}A}d z3cw9Pwy{uU)iQPKKHfopsg}e|pvdHhg$LV$Z&2{&)rLUI(xL;10VpYO>w2X|7^TiO z@KPCwZeBmC)JktRytl^pzGEU4{pvEwf~GULXEkNZoh02wDf?>_R!pWhNM+UnL)5^6 zAED)X=gh&0#i@^vZ^46)Q=1ZUi+yN!;fYF@H_Kgy-=L@{l)M+wPdsb9N#@LETBCJB zYyO>DW=~Y$IBS;#k4?c4UM3EJX(Y%KNQ$Z_HE}~F2$)nb^SoN4sP2LWH`8zwk0YT1 zgB^joLJsy*z$SVuOGKZ@LW1w>GG0Y+YC|L<;_eSEU0U|6deSu|@TJY|Vf~scqXVMK zqr?49FYxAP<`I&68T^&LUH`-?JlHo&KL@N?4cC08b8Hf6AD#G{BFfOdo*8P zS5Z0>Iqeg?eCYKbN&BOMvnKftk#{GJ!|6h;c=wu*`oR{f{FHEB% zf2Rao^3xJZZsR`KMvG-633%j+TWC;g6V4fZhVJGYY-5v9x={EflDh$2jwSc_Tzb{!0;pfv28bYnq*^hV;hZaCk-3hwr$(C*%*y&y!-plyq|VvXFoi%^W5h?=fb%x zV%DWSd@f*?yZ1L26#V&2f9BJ(yNmNn_cyTsz~e9d#J42JD|&h~*`lBy>eaCUC_XD>t4kjU1Vt*KYfjYFp zn=|I1d$Kco+e>2RggrnQynD09k_*8VVb-c73Qv$9(wC{k=q_X&y7!`ZLkoZmzJDbK zBhJj;JCz$7Amm1t+?puPg2@vKksPPw7BLea&0D%ao`U0|XD8=D3y2Z7u0fCi4~NPl zFF2R|UIWe~vfp>hYWv$Zzx~8n25(%Z`Du556K~}{Oq2MSC_FrznvU*?iZI6z6pGXF z`8}JWcpA`@Ta*8A<2vDET03ml`NpaI>tcnu1!k`Y4lVs+_Eix2#w>u%r-{Jnj}@sF zL)eElnpMOwx&V@4cQWB%I=W*mJ>mi(^K*?xe8!pb@4CEzt2S~A%{3h?eT~U1-xq2* z?kN#QP5AJ{4^R5Bs0SKAdH|8MQAL@l-S*1j5UUZ)OjYr(3a{*q0YHm{wa;Po6*J`7 zur)qoT^goi>zPy1Bpeq(BU@xy{1JsN!A8D=^`GIlmQw4rbvh-S9O;`;?yQSq5(~Ib z`ebAAQ3KFsW%WHF*VKTZ;DhEPMp}fi1;wl%$-|7w*WI;K!Xotxs?*g`r`Gm0$Eo<@;Yszj#^F%%_~x=JX@f|~^aWiU$x{g> zX1FN}c16;HXv8S)#hAj-W9T|?yj{{Hd>()m;HNeE)Qrz`sZkZ^{Vv6uj5_)U`VGu3 z$_)H#&_kr<8B>0jcb6~gXD^GZ{kt(-u~S)0Vi+~o(s#hzvC0R!AZq=xBE#`rpvx!= z;)0T9y}>}S4-jtuH}E6KG9ZdY!q7G61)_?cb=GqPz4Fn-AijlKtYDQRJ6Bd$BLo2# z#%gbKF8+}C*H)s{zpW}54Ws&d$>riZ{5U5Saho&46r3ycK(>%q3mQCEbrLgt^AUzg z{@gZUCyw5Q5{yvxm6_y0CTSl2QngMMrL>ftGDb&dhXC+WI``aQL)I5{@;Rj zCJ_v_afEoRS#C3+QEDfpnGXUxK3G*T+b!oQ$;qEWiQdG% z?vmE7Nq+j%SsuF}d|`?V7OfotSDCRH?LIP$XQ0s|T7G(8 zzZAGXpIkM9UdeNo0*4b@hH|+Dcx+Z1BEg)oa?pSNPXRY}ruR1Re#$ zCF8~SL{PjqL`=sNa4+>JuGmi`0lrK7f&4lmfUqz5>vfOQ_Xxx>Ly>y#$%jphW=(6! z?lpxzU%A{PUGvhuBC}zh_&O?5YB1Lh)@?URxvibyRsT>K??eZeQ3Sc?9xl7PH${5$ z)GY5K+zta}bnUA+wRGA*pEVxwdjL+Atc=~5=lq<{FdoTyvCYCkyxANMeM zn0J_x>u+HkkMOth_8V!H5HE~&?* zljRyluF->*>$eF3U&6frfc!%_ZoKSFb-tMy10RpooZr({ZMb4R?P{dS%`#z=^_Jqq zv8_t;=nIwg9h0q|P34E$o&b-GQ7f>C6)j#=xaphPjOvPIBtZyjDWihTjd?e%mt%O` zhyG*JLGmuRkk>ZUDOgtrBn?8KOk{_d(VfYFHz3X@;}lnQFq#}z=PiBRR31L8OR;>S zywtM}uY*3b>v#e291`_X2PLoHT981lRJ|rFvur%4i)^wS({_z>TW}kv=oEixRXwCm zAl94c@omZB(2GjwlY7;H0VKN`Qs4wc- zP@=h+^6lNamqw$rAEQ%J0+=pJlvm3kpk%%OAdN>*DE1Y~PpQ5xucyr0>C?3N>x~Y# z7>RBZD3W&}8e&kX_i_6*5d9nPY_6 zHbD2*psLd=RSz!xKo(nN+f)^rq!4G)QJN&o$rKtQi|F!-=)C*QXsv7`c}XN<%a5@H z8W}5fb^_k+>n+M`#72eblk=b=h#5ULrPq?0n?h0Xa?gV< z0N9o8YELUnY*1;4rg*W4n3gZ#Mokg@v|lydfW;d0=*`D7`Iamc@%Bakle{L&erl$D z<&~pBzM0Ie=0Yd z+xjjjt7XW!*4J{ai2tJsYH5-zPNW|%n%tEW7%|J|$SyJ(J(bH2b=c}%AWWPC#22(d z$8m}Z3J6wm*#b=x4Y;;6b77o}|FjDes4-5RNS?A6TL=GXMC^&?U5Dy})3P=f36_|O z&MT$zg|Lu?6(x}0Lc&({^XN%uUn0&2huCP{I^zUimwNF*wtfE-=0|dVG;jKN=kThi z23Yy(x`|_D&ZfbR<)Quz0XR@AKW+nY?#RO!|HU=+AfqMs!T`yFWu=8ncEiG1KeN|U zLh5Q10#iPfCIUB3dhmO6f`?JOYZ^1}pWD|0PSnWtABt%s$KsPwvod&krqd~&ezc=E zp0AXpkpl^4mMi!exy))pa~Jkd8+LI4b0XZ2L*c2~$_@fv#4ml%Ush>v0ybk^&DR*J z+w3OQH3dPUS_hyk$~^@&iwZYW`~iIZ#W{r$&gZ2Xj|o;j{Mf@L76S<2z+KOqTgqGd$QzeF{zeNB>9p`-jxOE&rK2OKI{8{8xwT` zX@v(z_Qw|kc?KRV21t+>U6u_)J$B)l*h~J{6sTr&mg991Cx)3L@N&0}PjTL!&BjnV zrrEMPaB;Gs#XKMXTyt5-trC=J(+k%UsrxIob5-!m27b>ap}ePTxSKz6)g-=?su*wz zcH~C#NEM4|n?^q>(pirx4j(o>>-3pHSiJKOD~m=@ckpP30}{F>7(P3J_sJn^aa#}s z$i2pNHt~x(2T#9yQM~l3Z}~_S@ffhPUTcD%zZdUx;w@EA;0v1U5J9)+Q8+xd)X0f1 znhsz5waq$^_j}kK2#Ilm#=RUN-u5-y0abcKW9tZM>5^=h=Ao|*@thp7Goy1bSxTot zWauY{;vdWi59&oEhZz_7i&WPvjor;+IPuG z$;r2eJvmc(AJES=$@|XQc;Zomr^~H_v6HY|&TdwEpDInHFD)AJ$jc?Gzu@d%pwE<4 zaOWqg2qWZ!F-aHpZQst^WA#V=;6TP}Sj0PHBK)iE(Y~XPwnNPG5P@G^eV0W+hZI zBajjVaCHdcr$}cAnG#>ULQ~`^hK%|}X;RnTvh{xe@=!wri3VSn2H{u*G9d989Bnc{ zdlOKBjgnMa`Ce=F;#xM?OwIzx6PebUbh)Sui!67TbykNK*@nw-=Goo`y!sc!xXn(t zCT9{#8s?%J#6fsoIcFTDN_b`n( zpQ>xv|I~wAX_Q`)&4(XbN1bc}g(+Z*(;^4Dm-C|PTqkeoBOeCc$>g0gPE0Xi4hYXZ za{pfoa4@U&2hTJox5bLpvtzt$N&^F*0?kUYs^`%hKShpvx>#B5bm$58ED z{TS;F{jXPz9AkWH$QK4H!^y?pNLQUK0bbpUoD+2C%QI15b~t}9t(*?M)$FLcWwW`~ zny_`Fv(?|C-gc8heYK?j+JX7s7HT|$!M@S{-56|yU++X%1AlV)d%vaQErJe@RcW+* zzhzFn$Bvvttc{?;WWCSI0Z`mu$4SXOk7fl74+&o618iY!OzR$*GxSe}*dXUhql3iR za*ZOTu!z0m^e3`H_3ol_p6bF@B%pNFGjTcM({)2QxqUhghAQHe5f4=UNW1!GygG-U zkP|XgUFMvqo~}$DBXTtUD8b)!s?B;Cacgk>m9l8D4vGdHuo z2l6Xguzt;u&xtn)^nQ~zN+YFl&9QjN9S8;naFK=t2<2jnP4dHsJ%BqsBTuA}FGz6P z?+D6eu{j;lV=?O7dmR?NxmNQ}t3I1-kF9*R(rIdIu zzS!lYie>z(e8XI6o0l9rqHbxadFnd$&b(p90$O58p=AX;-_cqnE1JJIkH<%DS{gl= z^WGT74%?NQ)Y*|+d`2)%Mg@Sd#hApY_eWx``s{6fCKg$tXL;*%br*y5fMrkt82ppi zX3V&QT8Av^BG002BH6vTDF*g@2rGI73MxsN(mf#!DH*PO1EB`BNM9fE(@%QyFD|^J zKGH^Qr2p#JKEJjAdA~zq_!P!=xl?`W2Go>M1keWY7IECw3MzYdhiC%6Cl3ofwfkT# zbv<2`Njt=mYA)p83n2ehaZy(@;Hya7`moPmg*K zTJY1lV*e103a?1I!%5GYxOVOVSc$hxdxDI0{V{#7Ehq53$zGiz6Y28 zFNzUxT}GcKLHc*|vb2eb)7Dtq)wxTC?w+sgcy<-an+&xIMCu8i{OFo`&{8|!{>qpK zlw-C3Di6ypM{?p+S%>KwP6EYQ@lrma@Jo`!?X$YjA$@8$pR{Ym4 z1(Pv~ks&ML$yX21F>JV^9Q#C#5*#H3$(?ee{w=sA#E@yjkH(jaQIo0VbZ`8yVm&x_ z#wbZ8HR|bc#iY}vJD7A$d!q58S)e37C^F)3ym$vpKC~S+xU_z!%dKP7kfv1$;pDw( zfI(iLWa#20TE*KT8$gZ>i6^ zi@l6pr4ALSYK8|f3-CEPldn@w7IykG#Zw-EraT(W#ZVc-NX0a@?Ma>hEGJdZYCP9J zG@Jql3hF8S&Z-UgGJQ`v@O#n-W3nzZ%NhO3V?IqRUVNa%qEtTs_~-%p-SLE_puN`J zr`c9MAp`2!bjO#;jMY{01~SPq9!U9bE|F+sJzJ^92NOt54>Zl`;h9^eaF%CE@7qg2 zZkay2eWB*G0PH=X(*Zz^&1L=q20=ZWQnI)Y82`fJ5IiGS1{)+$`Pz|JGKjRTt1aT! z=lW{G=RC7IQ5c)@~ z$wtm$Sq+8a%8IQJtvTl>qN1=n4k^JN{$ZHrk+2mewmke>OqZKT``4ry)yyuXYPfWqHGMB_-bDyzGAa#5LJl#UBK z_uap~YNgF%H1#+#$=FWamj~4ZfBZD`3bgvLA6FjL@>uHu^H(${x+KfSCTBZE!Iwds zTJdf=$DMoBcb=9VymvS~EkcJLqyzB`?3U{w;;C@K!q@MJFyJGb`Ed#LfLCnNQo?C$ z@xZ1c?r@y)QPdIOab|g-gXsqNyOe1OMN(rV81;;H9q3Z@K`%3AGbitE%PEO@-;K9yE_zh6M| zpk_Zi#NVB}ibf;pt@N-V!qpBWQlc)M=eK)hx8JcNJ zQi2cBvA@5;_YyE-NhBu6D*5l>q{As`+OfQkHE-h^%p-4HLHg1>R{o0UHu_kYuP-pC}26J%j?GCyhQ4 zx69)9+oExpP}7wtU@6fA$L%#WV%G8~Y{Wkvb|XmmwCh$2JUCe=TAvz-O`4L(@tn7S z!32}QaT~K7nv-TW5Yb*V)90;UO8)PW)fRqZ6RXa{QzSNjyZpD-9ipRYl+RcdYKFk8 z{}fh>egg7uT0;;$M-9(K(8MxE?`Mi%n3 zEf;)QAmOi{1u*ZowT3;zYbnKwEOc!c~ct#JO|#N%k(IE%T}P$ zP;IhQzf-OR_b2#%)4FMu_NF z0xP+DAyk^`rtVB1ZklAXyo{0r*oDco!k7Oph@o>0>;Ne%)v!NAq{PYy8(NvRq{z+D zW&Z`1tTn3r9eGTni*wR3Y~2_nKuP^xE|=K8+hyx<$gi670LceQFL>)+VUeLW(Ohj4 zN+d>!hZ(PsB+|)x5?62N8z5JaaA#KsieOU|R={!8=<&vsXtxBqEGbF)&2|E$dM6^L zpu4|zw7_n^*Vdm3-TEulpRTl-;pCPGtOVOG^^IzHj1etjOIQqi3?HIXumqp#ybZ_J#GIooUXf z9-F=Sdxv$#N>%7ZmEp<{f0zT2ml(XcoNzMN)b|7UZH2FypWn@f$r`(LIg=Vl6(D|m z8%&1i$kvWvAqkTQHGpWT3H3AYce1*RizTDbKKF%}vY!x#lx&A|_V*!p;yr`3i+^KN z5fQlpp$M~i35$4(Q9U`#u z3M&{Wv)L85O>Es~&f}epwpY%U3Ew&amR$@`Vwe0kDQW4l>S``3n~1NLC?0*Ww-D7& zY{tsmmX;N!FaBvMoCxwb|Nbt%(cyl9*za-8l zfW>kQCe&AkdKSb7W>uPRY7@)M@*<9kzig0JdqR_g z&q96=)rhyRENA>GDSK!lw-N5lA%h>u8R}juiWv_bkQW`0IY=9z@QV^1uYC|Mc;w*U zfN=@B<9`Wk-bP4)F8}k`fzxFqKt{kvvUmv12{WWeug?>2O?%9C_M>;{Nqtw|5K zxIFvSGAz(s{^jxHwejgLbkG z6B$5y_@F6LBXr=!H@xEc>3?B=mWL!fFwGgjUXUAw4b4ITJeQoG$V4P=fJNkqt+5Vf zg^R0u^CYj4PQ??6*U*o5H(>6VoC;&VYZ$Z~tn0Fw1UG@lVOWNZj4ha)vLnOc{|!saP6Y$WnMCEm=Zp+hBn{oDSge7@;j+Ix z{F?u24Sqs2Ni5$CwkRWf{}(%e-HkjWUtu!b=~CEk*>;J(q6ofk9RUxcfZ|7Sx2(w3 zGo?I_)xN=|vm*NK8)MHe!W8}4;os`Inh1sMDN5Y`Nc6vYw;-UtTWfbjjdb60hPnE; zjb#-AXkW~?v3x$;rOPifpFPaKV{u%1B?cb|%z0F@nr)r>lQX1;bEH!11HO9+r7lxE z-R&g~5q--bH9mCy?!dXraHWZM)TBwLxlvMYQlRYI=wqT!A5Br4A`#nwX#GQ&gjgIP z&@1`&-T2ePObRAkPz`65SP8=B+N1~~IVI$mJzO+VKP+QV{|{ycFtHyHIltrIe72-M z>J|fW>lTEOq!E(P-_Hr#TYTC`+j`m}K9Ywea%3D9I>$j~J0aADoY!1gudp5U8IQ9@H-}L?juh6~|=W?8|A|fL@J==%x?i$qCzKV>= zf^-2>po^M++U5E1Yq5{YbX!eGB~ZoUpNc-kGXT$}JN)rn48-7>PG=7N?ecoRz1r6e zVNq7%5D4C{7s#bE18~iQn_kGUHS&Vkd5k{3;gAWf;wmiXBMT${JN9OAq z(|Xf05yTFlbZ?nHsK=*fKrZ_*NRKn7kONGC8g^J8$JXgz&G1fLz4h$v3=eR=e~D5Q zmuxID1x83Q#!VNRGlaY3NF04}k>j^vFJOguF$>3I-&LKk!M0;gtpSi;_R1{vC9fP!A9%UjUz zdcr7hg-k?DLf4Q(Y?`A;En27`n1*I}o3_JTluc{vm(?kjZ^Cjb&(%!Xi7jqC;tPsW>nul=%#R*SC zlm?sVSvEX7zk{S}py|D~&`05L0(8!ojR;dA1KOR#kM?!BEHR8E=XqzvI+-QUH9#l= z?ZY`vJjb8cxWp8yvobyS`Y)%gP^BT$#M+zRMTLmSH0(Z&g6eB612kfIZ-eI+Hs8PT z)12+=)@1xFJQrP#zp@o@kE==cPKj+VMDp~jj${P41NY}IC#*!IXIy^an(%I2zRC4J| zXH6NmY|B%XVrMOmlx|{Bsz}~vdvB6@#VY*};N~Axt6D3S!!)p@CHO?&G8M;8c?!6W zzoyu?&EC$FR;9_#H$J{M`oKGkie5zulL%V+D@m_BHs0LdZfN?x@P&#{a-_%nygpUV zPH8BhgE#Vs^VcO7ijjD^71)v|A#Pr&RN=5PhC4tM*+s#0+lrcFBK0#f;l&~jTRkC# zMtq)3QThu=!%2CuLE=jm|2>}ZM11P0O#d8a+(!B$q;d?cm<7s?Z6Y0m{%p((;Q3L0 z?nqFS%2%q#(6h|q1sd1zSH3CZ5)ru)5>dK(j>?eTzRB}{&i?N#n>=$hlwcW!t$}~J zzWe-P0YN-`(#XVi$Z2n>xH_$S;YokJAFi&_R#BK9vXcZz_V=B8Q)$AMXe)NiLq6Xw zy!^@Q=vo@G++|U^#~wr1P9jcIcX@11LXvY%M1A)d-$JKC>@wx7Wf^9wH?kMzWUQz8 zY@d-bMhO9kzKS3UpRue%7`18cs(hbfz2PlTzz*F)VbIzT)Tl2?8qSf!D#yZ@nc3^B z{b*ygzN12HYiQpn+KCs4$3X^Kx=LGCR4~I~_&4>(g0Af-*s2<7H~ zYCb(ehsrIJg2nlylxF6mUp9o@ud&HYB@e95kuxMX=O@U0zQxwDLz$re^b8D#;dE;A8(#NQz8UgB{a@wV z5?Z-i_kd+gw^&a8w6|BSFv=K^b=gu%g$>HjTQjxzAKx#5%qlu) z2nGq~$;Mv;Sr;cYjk#2dZ39JsI3;|M1e|no`#WmB8g|r-1~}UpJ@tnz)ka^F?|j%2 z)I4lyqtOD#^&aJ(S>@%DlzB(iglozZ_iZ)@`>_0DZZQdpbNn~&wEUh+v_F-zenQxq z=A`J=6m?Z3_jG$=2KAD9(IEVx<}Xd%A=TL5l-Nk1+{gdV%y`Bn zF~c3zWIyH9&R6-!O@}Yh4fSqoH|3iXzHP=CYiwr$kt2fo_(R=_RV@Pf)eJA{ESH(h z*dKZ9ilVDF-lrmr(encQ|f73`x!%-ee|Wex#p6xo*bg@m|?w} z?d{75?)l~BT|BjGpSYjNUTt;ZZ?LJdxy{?qSI2zJXWVLuWwy}q?)fu#vj_kRn zBLTq|u6tIYuL}{=nxMfuU!NIgsm;+Vo=!gj;V(Go(suL}2`VY~=H>Q@-TP_}v{sgh zJBYeG_O&eC`3khT^@|SNF;m?7Ve;+sXRL?}LV5`#-f*CXpItY_*B>QFb0mPH4H{p$=GN)M#L!diz_CpUbMfadx zn8b-2gi2_{I9aoScZpO4BF3NY(SknvX9Rd`Z1SR`89t+~9mJR9)9Ta8a^xyIK_&xLM>GabGU4i#a3i=G}PD6!B1*3j^1DNO6^n#$5$S z6ZLZI4b=!d0{|OVCD~15FLnIjCpB=Qfjg`$LDT8x1A?(TXJT`lOQajA0A|_Dr_j-m zsi!{7szyhwyFEp>VdQz;DXQ>`TktRS zB>$DF*eRlLg_FSJJPbYL#}d}PdI32&SxFVC8P4e4B418uY7=&l(}ws^JCCAF(~o=O z34DG!Z!>4%3S%!Iju#NZf!Y5*(Y=(ygD5*O6Kz3rM^u-v*;FOodBjpfvJ)bx{ZCbN zKh-P$c}TyXo((<5W2Be1up&Cfy#82)%BdIZZ3WTMh#yXIU?s@H;d`bZN>EqUog02~ zzX{Maq90oh{Pou^@0f4ammNU|F_NZUHQ3l3%upXV&s-8Pn4y6yp#-3T%>l0R;w*X8 ziXCs%ks~*sRLa9tmpW|Nij*F6LY%8wY7*Na6$NT1a_r?LWOouSWat+G5N2R0c)dvM5g%og6$7+>KT%@(XYc%PK8hta}ZBn#gB zf?WiEbjz(-27Rp-zg#j-Rs{@#AVRze@;ptX8#7(6`H}`KovIk;Un;=KC{WNLXq<)d zU4NvH>9XPo(t6U&SlX5|Y=+;n3K-lMYL_3i&_zeC|BLban1dFbJ`O9gTH#Dh!ettn z>vt)m*c(oM%gB6dr3RYx>13rN*s3v{Cw&x8KR{nM>z?1t-V2nSATn=cK~T#kuc&Py zc?mKzH1iL|=m@*1jqdt&*nzq86CLEbxUSb`Pq>a40oSe-GnSy^Q-=)uCp8)*-P;<{ z9!wQowSO?w!LcDo9L3ff86ZeSk^(!aPrPlDb;pT3B5hc{@!l@uBrcXH4@Ue!U&qaW z3~=9d$M2jC6*<>XI-HLlD+szFx6{ElYU8D638t7M+v4f|S8g(e4znW&b}FG9D6aZw z+sNz&#%$zZ4artSiyH@`&w~@kK_X7FKoQ=Z4V;|mt6u-_(C@CXF|6G_+;eKTDoct< zNfYnZYi_9PsPJ_gqUS&7qBZtcx@_}nBIL|XDhZorb9jK_7m5?gV{(PbQ-bF}>L&VM zkFXD?*g9UNhz;^2$9TWbv0DrfEh`zNJr_P!WNS0WLCerOqG$O-sJQ>&5XbS>F-YE9WL*q_ zz%hg)y=Bqb%Bc(v)o`T=qAlf#>1g@y3jA(_m`)qiqFgsvts4|ii?^rQT40x7vu3lS zTDaKX&h%>zM>3XJJ|9mht20)Ht5>Q)5rMC6@C$Uf<&l4SjCXZ)eY*9IXhIq_4{~R3v^7VU&g@!Q@8Jie z@<2MUhSn*dMHmCM6b>pCNi|nka)1l8FE4iBdQ^=MR)jdx4^cky zq|q1>20!_M9}hI3^Znc)6lpS#-^juNwflJmq+z< z8Pp_#RTarotJv}`+v-UzaT0#=I!l8u%5GkP*5aBS_UpFY&MxRd5a#Wkn9v<5WN=7i zQabqi2Blk@!Fnh~YWgF}R#23k`YjK<1L?B9a*g)Wt-m$=?AMPzFV#M|ag}XC18!_W zm;Xj5R5vh1#?sb|bTh{nj81i8hoBKzWVGi-Z*M+(ch_B;26XI&eo($9Qycb#@ox8~ zp$VVM$7<=tWLAu>D14GI@xRQx{~nn6mXbIH+Oa;up$*jigk9&?5WG(M64vVm18+AR zX;QS*_lTQ~9q9WggT0z+caN<=7+Z`TV7``&m`-N-`17Tcb$}+~C{{qONX9JvxAThm zO)Z3}(E9Sz2Qml5RH@|T(;w8{nD{GFV3zTR*0b;<75d4dTp<~9`QV>T4F`k#EPo&U z-dFh-SGiA}k4oOIZ`A&qgWs9N39FMq z`*KkzGxlQZZ`lC(dG}@@SU5n=noM^<>l$OI0PbKtdw)(NELd_?V)IdI=epz{*^eoj z$t(DDvsO_%t=YxJp-nEN?Xc5I4oLQ3mGBKPkjC!4MY`LEF8Sck0}aUXTR(=ui>|(M zH>H8bcThWr!HbW4Yt1_fnm_7lrw~E*mMuFA=SWiXJ8*ju@9^kAveZXyJP;V6qn)!i zGABSVQHu`UD~}Ddx|go(SLP_ixNLe^?Dy!L7Z|Nb#*>MBAZLkyaEOy0AAZcy5rU`X z0f+>riv>Ivl7J*`?m)FIZr6-VZz_cet(SDACMb+BkY+tS#>K#L4>3&BNP*VH+JBvK z(`?~)CwzqmP}liZbCk!i z&9=p^s;Al>?CT0W#If%dI$#mGRoqlj!S+6cWF%0M)*kcnfN0UZ&JZr_G-Mp>IPgn_ zeIhl)#w$71W;iASI`Jqna9kLzIaJ>~UQjagC0Ec$l29g{fxT$I#60j>OD;|8JLJ1N z^n-I5zWwE?i3&hn?XjcL5+Wx1BH^69O_du!rekh_1N8j9y_z|7j<3n_Wz8zHL2r=` zrclck-zw5CxU(;5scfqG!SiB;aoO30&$ZB-h9OKa$v;soo&IgMg+{D;SMu~#IW>K! zX==OZPNQT6AlBfbY3 zC`FyiFVP1Aj@%{N91~euNf6$xtu*PwXvlh|wp23)FX-(Z4o>p9Pcl5j$dVy`I8Fri z2+ot|Akp?Ea!;8GGQ4u!9A}jm{ES9U^BkeF^v(oc|L1Mv203CuVsnsSLBI6@08*vf zF+bPa?~=KmOV)$B^Pb$SzVGlLOgl@+)KHi^>ru6y|1S%UGKJb}7Af{55j!=;HcR)N zZ8sycKK9~dO86>oxxpo>sBaZr(gnyLg?3+<;uvV@^E!!yM8GL{9sxXMl1KIB3jL44 zZWEmkLOaV1Zj;SoeOv(wA9MXRbE+U=8|dRM^$@jrSMMXJXc!%_5pGD@axhO8*+Qh5 zoTAD>wXKY0`x3(@-O9V6J50R@xGu4lQTM>NLqv=Er!jy>A9RAm-isLn%_7^E?jCzJ z7%xf&fK{&LCv~5v(8u3QJM4M(Jp@PJs zDk0pMGHQjy$Kv1|QoZqda1>%@{F`^QK@cA~P!>4_wKfg!dyU@CGVGp|A#q9}UU*JV zYkVakZG3TD7=Z&tSkS~$mF}M|4KCHk_0Fw2)~U)`%xD?&q$qW|P?-aB;xVkzjpv*3 zGcef`Pxky+<+G(zvG0$e^wv+7Vw%x5#$*y+j1ddJ)KEHw;ma`_Eqy6tfhEhw`*@>ztTB-7h=q>dO(d~=Ex|VbI zk|T*Li*I3!_3BMO9#yr-Dkvi!s-9+-JdvS^ylN}0U5t|DCto=6Yu?Cj#qsYXUN_ac z$SjKU;JBHz2N+sT5LWWKv}vaqYNGCPDu{1ngf4oXPs-xQ5-cmV?m>Pa?mA`uqn`A#{ZQ>WV7d8g!a85BKEdSK1#;za;0y>>9x#X#Dkq8@Dj;U` zU*(9pFG#@#f4#gNEWrRKtqQJAn??@-hO(a&J)PqdUx(;rzG-t`E4cr3D1DtC! zh!Sq6LpmcAdQ~JIQ#l1k8VDvXAK@vT{SRANm-%O}UK+k1e50xWl|SsRnaDPsG0FmO za3X08o6M~V^1if?1?hz|dfP}Y*BSUkh6CvOCIeCMYdke;HP_;!V&3w51bc17H`w~# zepD?z?(1S+dCJUZdjw8DxQf5${G+Cl*zaL_Ib-*3^yQc+2pM3iNc~XyDH}uAx@!u_ zA$08RO^!|(ZDgsQkGF#%X81^QO-A0F>MkL6O>tj;C(5e-;L*Z+o_U)c5D=#n4kM0>#QEGA-VkvK|l(+9`l2rhS_JBa}?<@INx31e3A|$&=uBE#P zwVa?WB6s^YJ@!GSxYZO%!;FH~ntl>apQPVw-sc$LC82R|va6alznJyQFRaE89tf7a`r3_k_m2hiRI(5@1|S6akf`Gnqo#8;@( zqQRou!To%ogH5R6q^xVL9w{`cAH&?7pGWAWm9Cq^w04DjqLKl41sth~Vb*%g-|(Lh z?^{KW4ZtQG^YwYX+kCxnQ<_O{l+9nQfHE!Bo2tUa@>>%qtM)X*&;fP94^GF+Ia_9z z%|+6!UfXI!xV)1MQJ)R2D)FfnSkVTE75&?`x`)lY1O|J!`LR?R-1)VR<+rZ`bM=#& zbS08RatSD=n#tC?trW}sRRwS@Y8ZE>C8IS_#3{<_lst&(_fy)qEzxB^4VUqhG1Kgd z4ukAFQv6+{;&_Xw3b_u6sqDOX72h|iXkQ2e4m8pSX&Pcp@OPRnupb_65oyVK&(IRa zmgiYiyQ9i0DvTb_x%!@;RfAvnpzB6N&YkHdi0&9HN@}?PzB@8ypruH!hd8J6%Vjfb z7nwKdixg_Rc6BxH?JCN3lfStY|1PsrpVuB3ajdt$OAOr}@NUgSJxFLiA<05*G(eqb zw1%Zd?jfZ#c0GhY_;oH1XFsvXmPdh8^|i~)xu|@7?F}O(`#2*m_*wTC&LyjSukL{I zyVSvNN<-Aa{8v0~SAXX^^m6nzG2?n2X0?o=(%=yQ`1UoZT%a9J!~N?)9B0iR22xpj3n>^Ww1HYNA@E5rT$ zD`(Xm{&{%?pZpSkUMj$9#_m$}b5TfoU&48j(dl(Q4|h8$O{HNqyU6IwCufG3g65e* z-sQ7f5$#`hzc%0Thv!l6{^m>ew+X4w%IB|SE zchok!7FK)o-G0Us%kE#I4lavLMDIGMwMwh_C(3?0;8~TCJ{Q1$6GcENyg*FMbSb=Wu|IA$woNKkHZFPyP0B5)2~hywBIGCs8_?cr$+2jB<*E|k-f9P}P{^SljLoGJC|66! z6r?x4v!w3U1dBW1QyrEkqtuRlvekLa^*exW+$@!#F;Oc~OqdO&_{9oz`_6dYESbXg zU=o(C#pI#hwBp#RIkGf70nid{%xUL_%1wUKCMj@pSPtw7sZez*6@#2alk)$g=__E` zV85?%cinJzch}*z;V#7;hP#d7KHP`96&Y4wxDG4s3>fZKzU@=u;7P1>|+(tDqC z&pr2C!=iW~ySP~}rB7;(pv2EYXlh-=M8(Tmt^gi0f^q02Slk`dQW@tzqoe*FL?twv z*IZKlDwM!q>=u5o$A3YLXc+->c#_2;`P38mq%1H09bV;P3Fe=qIvmdHp+2Itqr^c` zhJHm*U94fH9qWP5gb`ZPh}@~W21KM~O`1LDxdTwBaGcP&)g zZK1noQ&N?;R}!3m!Db&N-9v;5a3>0EYW*Wc+3embi1zQ?v;MZHNH9BQqa{jxy{It2 z)E{<##C(UrKjJdjPNiI*u%?`w@+bG7(i#MRp`4&sZ3mmfkgj8G0_tXE)PdserXT~% z!TNt}IIUi97bNe#{1sGu)ej~uKeb#Z!(Ops9vb^j2*sWt?U%ifO|2Eq?9X&B`fwhO zyYUx2A3UE{f_NWK!$p^aeH|t&J-T@5nbE2AhGF$FJzs$MOE{In=@&-EN+Pavbnbx4 zw2(kw{)?{Np6924q~JF$K2+8%JN#D%43fT=#E7RK!ASG(dKXJUUZfwK8%Zmli6&o( zg`R9GP0@4~J-0gIU)x)$*T*6DZ3O(5muVFJf0vk!%d>vOhkOE^m>94 zBLE(tOu8pV!|P#{NK*TnAW`dw#!36RI8I1&V-kNxP5WTX1tU!ufCEwkY%wVLS@0OZ zH+*6y{lyj4rIqY2UnuD3lhaCh{(Ftu^X*g`{)9*FojPJPkE{w)BuyY`vE9lZM6Yrj z!*#AJ{UVO%ST+#Q+Z?=mkyiWqqmaC7ab}H-D>_6 z%`}N>zM+Bs?Mn=KT50EiXW4*tDO>2N;L*&7Kt`R~EuD;?Lz?Srv)|apB1uL+M8>a% z#rGrcred$AGE!pRBwG@FwVPRLb8vHOG@sGQxkJvo4|w$a*lY^L?>K}GE2?#0md_{o zu8uvCoC>t3Ky3sQnGNRu%)cilXk-`=F(S`(&_l;O&dU7Ebk%Kpy^WVkJ#4YdT7$0W z(7RMy!-8Z|tCyadD<(1!FEOO6B~+{5ZVUfCx+_8P7fw?Fb)$x&vyl@4uf4eJAL<-5 zfx#lBm3{85*be12HlOHn8NZir3k_E>OK?hgdIyOts~!eHn|NQr6e+;8p{lzF(X!}d zT0*qFg)Cp4@WnlYT6Z}pbk<{!);^5Ro09}H>x`C6X_I;`Ag2cr(6b9GnG}zVY`AVR!dAq@@>?gTL$ypdJb@|(aXjD{ucx54Nmw${XzRR0q zOy%gpB3rDb3*T=oOs)HEyi8jrn;O&Ur2lbPvMbGPH_VTWUqPR>aw-UQ?(N8};XFUE z*&6Q107%riqg9XWT>pW2Fuq3o^eRmRK3lAY)_L!`8TT_*2Kt~(CA(rpEtZSM=rWgT7lp9PJRjem^nFLzlAE& zjby3}lT-IW9T;wc@Et2?_-O-&D-)r2u;Y87q{J$d9Y{QGvEG-D5bPpXV%Ls`h*A9U zRqL{nbXb%qxy6>(R$EW+!O?an2f8GPo9C&`9txJMiC(1x2)8qZ4 z!e{z9qi;kk1qzD|^z=r~H~#fezIjDc#oeEZ61LdRph_UantCjw)1MJrS&)f&9rU{e z#te3T-mwl5j<9hB^{sIN^RGg;i#N;Ipc5caWA4dnXV1+|1uGk@2951AT&u)KglQVN z{ctj7&iGdS*{1@DXKYd{EXP#v8hs-XD^CX3l#KEo~T)sm^L)BHpu{0zb5c}2R)8eG$_eRzwPPGXE6p?5b*RgV03g)sBv zJzQv(X_Ll?hHxe|yv<(IvTm*N)>IP1Ua*Z^#pP<4|Cje<&glw)Gd~K!xxjqtkSX1U zDLAM=f+mY2mk$(PYMM73talGxS}2-^E$QtnJsB*4bGy8gujte&BmU}j4#y`;~1 zhHoIo2a92zq%3ZKayThJ{PokY$0r%#)v*EQ=;V?hnm8@;<-7*0_ty6wQ`R_%qZ3uWK=u$%>unGNOW6-9o<9=s?_?$eoBfV z)X`TVFv;Bd{k=(GwYrl(*B?#@PH$o0_k{VHhoi3{(EZ=Ki$k$gBe=w;0g+-2_?<{A ztznUXuxYU`#L4(~`I~@C-crJs>&_fhl)qA#Q#QY)av5wK?*~2%g5}4^_}nxZs>m&P zqA(W3&}9iv7z;_wjxtr51lj`OsN*h70zUx~Si4DzTWmO8EKgFmV{R8gb!=YW4X?280Tvr&>`!mrSCGr%bnHKkTWI)@4HI>**fM{D@)Zdmr3;Nw%cC z{Y0+~Nin!WPTf2@bNw`gG02x?T+|U-7sAOZpNOt?oo$^YcFmW96V3$%s0D1trV^y? zJhM>X@uSsd{w!S01pf44J+UHb=nYIM_&D~37mM;ef@!H&}TH`$=_pMxwkH-4e z&|O)kg=tMdF~32v8dq+ggJwsN1gb|2&6|8om&W!>ADgl42~A|H{?55>N7ri*F>5NN z#$GvM6X&sXFQHC{eOQ-l@?%@fO=Uwtm$AhbvwJ)G`phFf9R8o1MYX{<0p*FcT#bOU zbE2@WA;~wi$deiel@^DI;|paSoB2imbd6}|h5Hd`$(;we^AbK$B@+)(xQ?^0t$FR# zDCjLPVjsE~p)Zk2Vm%U;m0$3v--gm@)J8n8PVO@x!eg+K+_hBB^3Y$u#=q#Xu|%m) zZ4P!vOfl$_XgX|CFO7pFxZkXLpoT)1X5G%IR94q+Nb{I(kl| zT9Gdck>AM?)h`bu;i$dFd8lN&ghMDW3=UwJ)DO>phne0q9l#1Po!{GvA`JVDKz3{GDS_$W?$uzURnSB>?-*k7?@bg4xx6 z^cB|Fr>u>08XB>E__^Ret-m7br^sK7L2Zjv=VaRc?b&_O^@Ax!Wm**2u{! zPVF|t66GHtAv4LHBKSnsf2+nR2ehiW`Of*zao+=Q6B3tcJXxnMSE$rB_~j-wIym#_ zeRw(8PL%TXf!@<>?t5nkoovUJ+@=++YxC3T5ANFd%_A}^;k*itraDoTfy5}RVQB6aIsrId!W2l;V_&)JG(6rX*Px}h+za8T1_5)!npHX$)WoY5#yHAcH9Rbgfalb>!6Pltw;(OYcp4`_fGrgN9D*3UcVgdJUoF&Ejs_JxB_P-{9O zrPG@)>%cz0g~4kN`;D{kL0X1s+98Nbk1=6z*BSztNA9{|j;_~YH?X8R*#9jct-g?d z7ETyF*|wCSCA=qV=zo0YKMHQ-dteAk&HwfR2EN>09Rv9?k7KPK#OfoUG3;n_@j+YNu|iLxnuS~N&jY0DE4%;c?rWPoly zVLz!POH)*7Z|3I|b9OO>lGRn;YoO~($6y^H;)%r)4&ov!V{7cf_`h1c&Ul{IGC;lotHA1#;q%ONIac(YgUc`}~bIV`2aF{cG zpnvLRf9@o`Np^UD_K^C4+dc8fyWucVt&{Q{Z++IsmD(%=)*NRU!5Dc`F3ny_VTxoq z;aq`LdWmI7f9$Eg>nkRsNk4`P;g4n{Xw+6BxbU}Dw~=Ip9UQAaTKlvg)f!wXt+*#g zWpMip3xJ*8kYJnv@K&$Ek02+SD@1%oXBs`i6OAdyzvq+B&E1cWS^JhX=d*V-CeR6Z zO?_&)H-?3E0C~fc5@V8T^-N-+ck@o)cbS8rp_X~PkyGZ7i$$@Z$+n=4Q)Ds=nuZul ziJAw;H)Hf`XbW?T_RRJ}oJ8idsOaZ7wmDwll>3btkjgdT_%N+Wu84?w%a8QZ zGHVl)4bjGup%*JO2+DIBtSmi=8$HAv2mJ(&5UTQhJ|YbuMPz@_IELhF3lZl*mrdmm z-bc~LG-L@qWV>thIWH85Ih33 z@b1%oeJ|k?5I`clQW-c|9T##nT3;4Qdxe-`oEpLtFyKy)u&w@`&?8{$jzCR?0V!L3 z$IKIFNXa3)AHs80OdiY653)Zf4Qu&5C`xza2Vq#{9NQ%)uu>;5D|Ax9&o1~)T1(~> zCDYh-z#uO#|F{vUfs>u`d*a81?UbHpZxuEJ)%|CJ8Acmk1&r0)7OTV$rTzo@=!9cQ zkKl>`#7!6JgT^qgDw@9zkmiM!-ux>(x$C4kDD=-N3-d(CQx~=!uI1W+_~Y7jlKsZ|I)7Fc-3i2@ zX%bP1Hf66@KZmamFuT)GtKCk5dr=-#5+T-)8C)NY1y! zKuh?EnesZc{`5LS;jR^Yj67TKVcTXvZhT4#uI?RZbZ~P+OjtzS#3aaIc$xn$23_tZ?k218Tv_4x&JNNI5N6V_5Y%e@1lb{K!XFHpj`BV$Zp*!qEzXY?C} zvz!=g)vDVcm=}_V6eMKih$flP8;YAl&P$I!A#Y7G{|0_`%f0W{g3K|#`j@^>&V+C5 z;JsOtl{FcYGrrn~6z2c6s_dps?EYQQ%=S8R0;Ffx-d`GTA53v=g&yvA9|uI}XdTK* zjh;sK7uI|KeU5n5Yz=g(d%xQJ#R?BAkKp$fjcsy#wv`*p42nloQSbA<&d;;GbSnD; zWNZi=;R3T$IrjO$rm)DboK6u60Rut-sxE<+M0?K{E!X4fL^B&w`loWAzAk(L($>Ro zuBsn5)b-LtXUl2I^p`Zs__F*uK+4UzJiNv6!YhMM z?NWbn@cmM~R)sLB(*i}7gg^{?Csu18?fjwSt#^Dfj3J-G&+c4cori;P4D{kWJ{x- zJG^sJrtXix)PXYosw%NPv6R3;Fnne0fFYgr}6C;ob4sFt2jE{R+={U*Z|dJ zR6f){e4}kK2Pk83BF^>K#=tIIUZfF z;`ohib1RUJlEU~(ZIhaA;iup8)x(^ z-S2E>*#*9%dh{-YgIkPETbwbkas)nct`(gIIPal@oigbw)LpqRH!o4|&jr{1UsalI z#r4eVG++7^=qluywI<iupy0?YH^08RC1ds)7|jA@B0+zvD|dT5AYVd{xKb zBlQOMrR1YMvf#(gAXHwKZc`bD8uhtPtlD%Ma zeg(r!X0NGX=EOS}iOIGh`TE?D5SgOLzFAyOL@B@Zx|<4ig_=;?<%Y&&X7nSVV8Q*t zHGpUI3RzV{&l?$EbMq*1rH?P7*WSd2_NB*Ahc;eK#Dp3_+odU$Jm^qA)ON!^;y}tT zX2DL7QabLb{hfBln!O``=S(re^UYS%2kvh%oy)r^8%fEMIYOW5z>8&dh!DWd2x=wL z4Qj<75PpF1f_2WMo*L1yA^Ku%9dPlE_t&1Ji>%3=X=j5O+Mq+jwO7E@Ch9o8?yh8tTDUF1QLuNsG>|g|gsS?J-1iJ{ZUV9lts}!gMntn~~ zdu|-qC?(ggtz^+R_aOU#h}8cP<=FyOeal9z?HGHt4hpvsm|myFo;%&O9(DG-Dzc_( ztZv5p%>M?2wwy)xQ0M@m8Q%QAmZdEedz07N$0|BwU35?Z_Ae7rd1#TU`nj$c##Seu zFB6ZQD}Gy*IZ;&g?1US7-<27x5?imh*-^J}7z`mg;D>Z9{5~P}^c2*ov_>CUCSu^- zXFVZ$G)RLWW>ZHzCZu{@sHFLGsE)Mfj*>B(Mzkwz_fWY#pzO9QfqN&+_}|0(*62sA zFn3*3eK}E}q(^st_<}|(>sZ}{wne}{0f>54`vucV@GqJt;$A@ex4g5bXNFqq*aa<% z?m9Tvnm)sNeF$<;#~Q-4tj*9j`2%`**SNk;&DlGt1_>KegEiXd_xiz35#eV})L@dk^| z9F*y@a=_?T!Z*AsNp(D&vW}X)Y)-pi#w`bdskAKr;JQ>ZwI_`+FE+dXO-lkCD{(gH z{$MuV8=)_t9$#oOS=o$r_LC9NX_&DsOa>;|r8|eTN<&@39gT6bM+p;M6IgVyZPCGF zk(LQnXl2faV-iqCUQ<3xHN98|Xlc;xAYDG*N1_F#+MI4*hsxz*7WNy}nPn=dwD|9M z*CjH_f{ZCE#53u&tO*p&9gSzbezvV}$K<2D$d>ghf^cJA; z#Q73}qb_52!z@7Ny2twN7t5Z@QmBPKG#%$k)#c>%5!NtP@;N%Hdzc}jU!2n$w}yF` zqLx7=(@QX@y;e?+4P!CMT@^&B9x*26n3sRky5Zn!TU`{3h@)B9u=h`0f?4qR%}6$D zv#T?CX?1;LZHUoqee{9h`#<0Aw2#PQ_ohG`uNc=tW9${3vr!}GNk+0kilob70zgtl zVT{P=R8n%6P`E=ARr|NmPxyd&bd0-t1ruI!8Nd4%6nPuTfi(jvYZbzllqX>*p$tx@ z0ZM^JP(yGlmuQc^`Zr~;ibzyI@~(cTdZ!Ql>Z8*V^`d0vH76KmubUt|Q)uom1Mjo_ zKBC&8HXnQsLg>-=ru#fmaQ5P0VzS{UnE69*0SgN&qt(cdIQk`v733OvW4n&SwvT}$ z6+$e-bkqfs>2@J(c^V^hmctbzgAESuHq{1}{Ti31@(DFl5JFZXqmnQJ%%lw7%e&u0 z;BQKPs5b0R^T6y0er zb%!8Mmw(-5=vCfz;&TrM=6 zOJ{KPL0^a3(B;zWYU4s=2pDygtbU0iG=Y+c7Mdf^))1RO2^q{buy|Tlb8Q@YT(Hwi zsu?T4#*zAeX zr}JMmUL89lvXh&eeVLi2?s$lEJWfqHA&DCD>^@{k8 z5g)1CS3ZgAb_0Gx<`XcAT7j;#qvGLsCqG=ZT5S`sfUEwx!BHDZIFtOeKF$;aV1C&Z zjxl0)tH=yV`nCA;5`SB7UQZ;KZ3+g~^um{&k+fp`X`&`IJRZbr*{s=C>(mp`&71h7 z_*Vju85d|ocC%LD7o_vI+&6!a!dT&Se#4W~DOZ!-QKCGFF=QU98EKlqhN1$e$q{lq zUbRzny7R_9a-zuw&T}6~L4f-MYAq=N(>9$arDKF#=SvI3wc>sHPG65n;sR8@sd*Zr z%qmd03GPo|JeSjt%_Qn$^8}y%o@s#H4m%XhLJFKS{Ed(!pNF;HC6~$A=4qZNGxEak zL}5Ivb0BE(L4>!nJD>y8qu+b*ZQNh+``r3h=hXAKHE2w}KtR*K(NT@JraNw)0pL1u z?xGVP<6Z4sI*l@=Z>ptbI#VnFYR#tWnMn_902swYK#83cDr^9~bFY&~%Vb5et%wP* z^?r2kljAq=6lk5h%2#*U+?cY3@D=AKI?4f`I&{@01V_GP8bp(G+>gR|ygTquv*ACz z30=brXv;o$IlF0*elTa~g%LwwlY#EUQ{aTTJVtDzjQLVo!FeoE2Kmt^lcXl5L6GN< zhn*WKL?k6T*=G;wgSmQ8uC+#+kwl_I1{W(Wlf2u))#XgVcA+Y+6xK8lu;pY|tBoi9 zx(-ha^ed_qmmJ3K4Q*?EE|lh3Ip0bK}q&wacd>f=~rEm{~~g|04q^ z-Vak2=o5ymG2JO3C{6sl?a*fn&zcAaz|qaw8B2$DFGW zGF9^AE_>*n?$C{>u^dNYBQUSk>X z-iyBCLhDU1QA-jj%AlC=-D~>vu7>qTC(JG)cGFU>raSAsZ?rhY!CnsVP99+z7vELC zedI#)>B9+eU{0GoDVMi(V+PYyc_JKV-#}1+0WT;m870N=-aaTEOxDHmM`kp;FTBt= zR{vMngpKR=aZRrVf1?}kzUtJNGpSPvQZggab(xV1vp%^X4DTPJ(MR zEDl+1@=w~7-@e$@91pK?EDOIPC6?6>=i*qYr^kyYLmOrJOSQ1uiG`aJl0A>?BGoyK ze;k(E;7L247u?sAx62scan~5Fd8y$Ut?=L&x*Lu}CORV5SDQOeA5bo8wZ)A}Vr$-y zKU6()k#ac8l3k)zo4EJU-`{TSOmh8u)hDhV+x1Nw8duxeX1vLux&I}X?vy0a7HeqL z;G!VM-sx($ml!3XvJ`b8fBH^Tg`Bb?jQ5aT+I#pw8Dazg$)>L2F!1WHhnR$roRre=TORi|wrb7> zJ7y%#@Y`n=VWOSPD@#%_&fX6(hLt>b$JnZBuDD$eg@Dg~PY$f>hhG00cnP$yUn3Nf z?tX))K-+MzhdA5a3MMAxH;00V=*(u+rh>66FUmflo11mgCB)l0{n{+6fe|k!_w>NP zC$vzhSKRHqP@Rg#3KcvBwc3BN`@4KGuq`wAkL}Fk_72(bt;73U4t8RZWPQQTh|(@u$Yqu%_NW>0HlEjnP58C z4OxSD$vf|!FibDK5}xLI$~&8Sow(ouyNk2;59bEMmKjxel*FZHk_2~L2nGSOv23eQ zDeWwy+sxSEQ|W++L6t}%W$Lnl(nKoYAWKy3&sV>j35t1V99wPFJgl)Wz8H&0-U&9K zNgPLavX6$K?{;JmS0vA|=SNeQ{Jy$4K!WyWE^mn#Cp3ng=cs9gk>}##cv|i; zOETJjWl7B4b6~zBg15!J0(z6q@k{=cpyZf7kk9my@*4p-%q2&1E4-Uw`puTIw9N3~ zYFCks09EzijZJzX2*FWi%l3r%Y#5f{M{BuY>#ex0~zk1qOe-q93e5;Cz2O)N#eo$DwDEalbcz5}ybn>aj{MRruV%N-NK@~s3vosT*Y?zJ27@z;TI zMDHA{W0zFd2Q?1t|Ec-NpC-?wq~GH9^5|`5bmCTE4uhi{n@vh}jb0qsRY*ul4SEBu zFa1#5)ceVC2TfxgngRMaYve=X5|NlkSmMjxNl#V^B{aXp)Bqp@=}D0;)%TmmqDJ3= zerTTo4La|6B8TSK_U4X^2qu#YjHJ7_LQPrbY&KUhxb(QRc9Z*WGx zCTVoDeeMX53;TiC$f2_gqIQ2kSr?xjXnU;lH#)s}Ym-B3A4C$q=cGrt1jspR+iMD1 z@1Ff>8`ag`DMy?xd27Ri>;+=g-C(AHt*g1l5Vs{b-3p2ICw@#92Q3e-vADek8n)|g zJ74L<7%4N9KxrDv+n6$BwOUrftF07$R>GJDUG<-Iy{BtBUE%+!mKErmB%^m-2=r?R z>I2RV-T(dYTPqzqW!hg3~p9**d20JMfSW*Y~*5 zqvqy&^w5&)zmg4J>4$lF^d}_YgBbX%72|ag>4Wz%E6fdDKNJZWOx2exYn%3Ovh;?Y zLHYl3PJtRq-Kc8SaDz7T6=J<*OEB46AK0{dQW?yt~qq? z;&n0e+-?CcLxn!dwG)I*)8o-Zj`}-Tg}vC$AeGcdSFI!+f5dKlwZVg1;n89xgV5jo zK5sLUGkj^q#Z)9G>1`%jxUFSpx_^i<{|nq3(!;#;rZ&S^O+7sYjhW%lZ0t+cGpE1K zDny*7nvHAzb%kS3H^f{4_j!GtLVdz9iq47q#%fu&*rcD=%}V}H3t+{-!Y;)t9HCm@ zARP!-O)6@)jur&U=#ksk7p~3b#}e9zS0?Hl@Q_rr4a!dbm`q z{1e~sk+S!CBd?9+uGQ>mXcUeSw`@*W3>u}?ow4`Qne2FFpS{SpmfA|eaB|n;&zsjz zEmx%URfhw<0f^ISas!OeY9UA`V-gqMHA%u|>HXj0(zDFpPlLyf&C9O$9y~ti&R#D> zW2@NrJ7;)S%}Cj@NMJlUh7+Sk3O+Xq?ik}AmS-0axWAYbj-%vQ8}{GTEJ0ekcW6Aw zm^_>x^(P3&u!69w&bg+Sroz*?rEL28)@T%8sh~mfD%c|S+`~2f3Ki<7*Fu~~TwDG? z?onhaif(3}M=?k`ND-^*xxg%PJUeTou3|n))v9&Un&mO^e=h?gt*zJ;AWdvl!(7>h z@F$;U!9oS;tDD}b`BzpamPL(b4hIu!4SsiUj-OJhxU-<@CUE1=-$AKAP+DFG-3%az zm*o=~a~oXvgauQ7pzb;uzb5@%(3X``s|3&t>WXw)(%SvL_eoGUeWlMBQGTaHOJ9Q+ z3d@~TvIL0R@jF2j+sv)=-nZ%qg}(n+bWkXrcxa55PZ^;<=zY{$#Q^O-bdC2_33?Ho z5h#AN(EQ$O=BSGMab|}vOUu+Kbg6!30V>6U$~B94;1HyYkTe*iW+JcjHg_NI97vhl z{0K{(ik-Ujq{lNd(hWakrk_;;xg>IV_C6zd^h7LIJ;cyLjq7Y@!qwJ2D$!l_xqxTF zgB;j3rYYH6M?&Clf*fcpD_v%%yJ0C6(b|9AMiARC3=?0Glw8CHUU#}+I$Y);C%eJ)$zeXi1=k9zui#5PE3A6+?f&e? zcyX5=If~Qf+j%_bcf~~dRt@@fsDFri1|bT z9eNPba&Bz-hqMqFCmQU_Ir7||T#dfBh^BdGF$mirh1MXEV!hGN7vdv}@r0CnZb!N+ zm$Z(EixTEe_j_us>*^Tc=L|c}1yoMq9RMw^dfpczp|5;DSxxqlL{4~5I1*Okn5!)# zUo5Kcigki?eF3KfU!gDzTdWx3qd9WnL>lWT*HOG*Y!#?0Ux1NUjqeZy=%1Oq zM>=qDhW9}Pni4|AUJz5-PiNZAXlZE|78i*D2-CJ}ZyuQciFRw_;SrdgTyiBtr2AyM z;eHr?EYuo2g$g{;1mqzP7ucI)Fd%_6gfe`DCozy-mu0$HDHjh9o)s&ykZsDxn;T^f zl+*qnEjp#6b6I}bz9SXuyQ?yKWP2cxO(HOpcMWsRnLplT7 zvI!phx<(q0Im!1Ts#ZZ`Dr;Dt5zKDbu$w#v%~V(Qd5WoBOac$vI=|TZhudAHo~bp? zMw-}3?ug0cu!o;icikbFg370YirvJmL)=m?3Jq{ z)ECSv*$h04Q4fJ*S2l-7FQ3dT0*;%wHa*_>jmy%L`~XDeceyRVcU>Z%66my2{Tfs* z*{YoKPjK2EKvZO6J+|-x5zuy1CLwYlumg3$jnK56P$&L0{I!<+bp98R{+Gdjn!wQa z-tJF-Cs3tXS|hLg#2iuf^cY90n&+i>@pT?sMke>%QoC zYe4Op_Za{F_}J`M3uQF0C(r-_eU4Et2>Q_L=YNTWQ~S{?-bQ%sO7Cqo>U&~_+SijA z$W!havV86= zCT$;rZ!k#YRkYJ(U`9Ol=%&0Da!Oc}BDmVivsgoA3KcXPn$O;DB*rcslF(Kn5*=vZ zMZf+%#6cFDEEKV-J`t+KB6^mAxgHj(RyxGmx|~zblTXXf+$?H`RonVk^q|o>+6IJg zED1sOaXs6$xRB%qoos)Ey9vlyp4zO9v2IA3|&+i@Nq#Q-EQDx$k z?!+B%PZnxE_nH|$wsQRBH@MPri16u5_%i!{L$iFx$H#U~c^`qe4KRns!%pT#WZTAl z`)r0iaIZ%-JUc1xst7CNu%_5f|_w=kfFoU&RY>&x_tlLJeDhEwzlumiv=Z3<9UwF3sJ)>Nwj%zII;s~Z~@by@X z{rta9#xkYW%+nd;kMO#iEkGBO-q32LH3!LQf_uj#x8{3)-rGoq{Ci`X#-3K)hAM;| zjY=C`(>gd&0AqIja4Q@1(XT25K1-!ellkGxTMF(zXsHi&a9rN51U|Wa8w}APwcWrj z-*bK2Tk9=Z$1)b1*NpbY6HNhd2_`qNKwKcfLX6LMX>*-2!U&VCJAbkoQnIF0# z<5gj+cwIMGYUlR0$@QI=>yH&8iqX|?`Gpz&X?akB=E~G!xYmgA$mthiyE?%tWxFX3 z<#l2E@U`v4I5U}W-&^P2>DD_<)6*9yhgtt?*P;61+~)1pZAZv2uA8|KzR>9}-Jp%! z#I@CiVe!QEOc)pIS1VWm@u#M*v5$>xYZ8Qbm?GFai%{nAh%Y1kG*}w41Qzr*w`r?8wi%@wJ zrs36>=7RzP%ICLi--B$*!kdRH|2DCV3yxKU-1onE8;+YgKrDgxiWmN;)77eG`4 zB3^T6Nn`95~wnt9fy3cfX~-o|2%#E}w>x`g9>n zhOuY91?h)afrF{;F7qfSGxpZMPVhNWqzWxn$f32M*W@?u_X&#-^~;J2^&4Rz8d2aJ zVMovyiHn#&r<#hkh0$hp2T|7D`%1vgrBJo##{0aXvT34qSAzTO@_@O8(+UEq4hlCN zN;6(^^9;En1NE3)Cy&bY1doR;k4FQW_!yg@#lfbP&CeVL*{pADXApr&GhZ;Pj;-%AW3yEul5BVl>yU>o7)oIGn2)|!+>d{3kXH?Kl}KdJg3jf z21Niox#a{|S!>3gniIP-=VI%Bx^m-*5ndW^H?GffHoB%a)Jzd2Qat4-4gvn&YaISg zgDESAzVmtld(KMJerLBMY|yi>3~#BaDaqW#Ctj;1!s#G&yMJRnWsx*>=rqu^it*rx zcyp(~=Cbb1n%{~!x;P{}z}oPHQ|R<8wzV}sHj8|Lp=5wkFN+m?>9hYZ`U2XD@Y~*a zYv@zIy*COKq)AXomS-Q(RhI+<^7rkNp1(jjd_C+K-Tng~C(WR5A~8KCL*@IQLArp= zquH0F>JUwBqeR6Ve2)j*(;gbvke87@$?9k#%QEc|$)66*_dT7@z4E@(paxviJomwD z=jF-3JG~mOkZ&lsroYZ)r^DC>Zbl{yxsB|M$X0;zzGbgcJvc0@*}9vvX@ID}T^|y_QN2MFS zl^I^mG%vYYQ*c?CzH~&7rAY)#A7)ZYH}m?_Nx=1?QXAVlx6J9attQxn!1IrowA4x$ zNl_PC7h`{b9C3FYiO?-fd7SpO6M$Fc5n(pPi^&UCB)W`8ee7d8Qn5*-q}#+6qovM@ zAFoY!D&%`KN-Wu^>1{5$zx8SDd#a)aH7OaXJn&V5)@$Vf*+~JKzfqB-HA7O0{~fbU zn|`^jy7ROpgZ>Ik%Ln|b+_>5OvNL0=);?$qy zKtT+THLxr-NHh64?!6TRtb(clreQmCx+C z$5VgkT5cUk$W1dfE2bOCOn-ePbcqzGDRGTQL_5G6bnv(6uEgw`6(3#LiFi4ES*0PI zlT^cMboB+6PPzL_i%q6X84yJkD&ZF!wjDu?WGq&XZ0)aG^l$DAZnSvt4e>BFb1|o@1rdC zetEP`4`-`Uyv%MDH_mPcoaw6`ZWmh7Jy=*WJ>`g|T6n*vi#(j+`QJBxIy^E<{~V~W z1|nG&>{rj6%bEhH?nPf#RvEcCk{cBXLHTKz#!xGI-KO;Kyx5KYa_ua!EmD{rgd|&! zr?44!BS!|LhyNJ?f#)xA3Az|y>E0*zx$CJiI}Ww1-5A%F?K~S z(Av-V>8k4e$dlf#DLaAyXhFHpZ|lA@b%7VWTku68jg%}@H@~Eqd$y!qcq(5ZHd5AT zwvtR1yPDP(#=;4KzimpdGPZT(Uh2(0uf4QC8G2}cKj&`3tW-=F0tR&|h}Rn8E`Ka> zicT<8a>eP_Jle;WW*~av`e3|8y^XOPfG}_Iax{ap)!~qa^&;POa&RLvq(Yh&^9H*7l zI!ogO%dWIA-m*58ZdW3P{*4!}Mas@650dM>D|eG)S~xW2AcVXKqj;>r`=K>8!*yx< zRBs-dC0s!yAO49~&0hWG$O~d|^=2^44d6Pan=W{HS$H4+ev>1!?V@t8Pr4FO+6|;!nm6SGv~iu>`MFwtnse_!x9w%h#?KYWK)o@{ z5493slR$5=_6RWw2vCfNShP8DKw8^1OYDVIps665Zpv#}1^2UhI+N0PMvhIq(j+g% z+Hkq=^@7xLBIeM{j`qeu3l`esWE6Cm@s_JhFs>VOsezza&8_&=O?~J%!(J}qcS10c zV}ZJ*x%H_w8p#Nua8A88WHhB&Dr+JGA}PE(E3jU2?TCJ_r}!-Jw33X0B)5Msx;^lB zUT1uBg?&j;6+%}YlvQrGfx;PF2&fOBk@>cCEMA=F;|)5NJW-t(U5D{8*%;P~Hz}pD zUc>FOP4k0BzAq)$m4x}vcST&+pA*vW#X6}!2m{ClC6H&WGxHP-;vXZVgO5Gkdw#wz zpuIC(b+BjjOK<;lFFGV0WC5IRv=TSX^h*IW&_y!5EI6)~LH_7I#=+ zn$9w)&2Edr1&UML-CEp=yA&-}+`SZcCrByo?(XjH?(QKt6et9j;BfQ(xXfgRNrpeX zlXLc7>)Cq^vq{7JD^vYG2jn8{o%y?hYM5_5_0NZ@#N8;5Ua4(`(UPBP*^9}DU zgQD-{!g+r+mg8YbEg<-c{(G!`3|Epvog<|3#;q!{QYHbzS?}2u2zrO=A>`7J+DQa zRx6~Xh((QCSYf?&v&U-)_SC^?jHhNFsBF*k z?qLKCoKDH|lkYC0czhou(ozPJXkY{McW^<(Y!G$=0AC?&`z7hg3C}eYM$xClFu6M} zYHXAvKZ>Hj#tInQaYgrfF4>`pkENXsNr9iuuj6G~!jX(Xv zVENWUEXi(7doE@r!FCsq7CtPZ6sHFkVqw>mC+0PG>Ii%RjqXD));r(t!hltWJw9br zRsWQJpVUwnu{8?8=Z|Fm>+lEk+-F-vDW<8iQzSy5cX_&3N78-l^05uSPp!3lg*^Cy zLtk@KYM0|)gp)sOCMkCgl%CxP6Q;`9Kl~t@K^MQq5Q>`onWpwEkxx^I0Lls;ewK5y zkbMxD8L;@Gii0B(jx4H{UDFkMTwFRKD0YliOpZJ&+Of%MY(gkZ>D~Ew zzdP>uBkzYCz(9i^5GoTnYwln2Q@WZ#*j8~$ZU-N$4kkUFc)IKqC`VzYYC1is_uL$P zyQ7YTofrU1^J4)5Jx_kJ(1Ux^gB{{mW&u&&E0*9m_%_COF+P!QW(d>c|5QRGhDFYP(7 zI_-vL7EZMOD--H`Tdds+1KdqptQ#j!`ksAp>eth`dn>!)F8tGWdo1#qr6C#85Vte6 zvoGT7nlPW91=d=g<0`n#gqw!FfkI8loQL%S>(kL5+Y>DYp+M(fqKd0O@d7kIsY?W| z$|*$7I~OD`yAE0ze*jUeTD{Hc*6=TlgW1Rm8XE#IjJ)k+$5IM$>xD~6Jn6^6xKo7s z4nJrAgW^4<8JkWO0WwP5mz8RtUT&UZRd`^`)qZ0bx(jcUJyAk#r3L7S%j$ZPYOzW_ zb}te`nsxvb?==(l-E%u5GkO;BtIo~h?k+gj5^&uv=)pJKU)ClwE^9dEDVi*^#+=t> z5#$%Iwu)r+KAbg8?!;$5UYx7k8Quc_Vdyp9cb3ID(7#&u3q4I%WJiAULViKzf#Y4g9FuFp*;nx0N8cHh{Z@B( z;V*WyoC=q?#Pja^<};0Rt7*CWEf69OL(FA2ZptNF1`9~dyAPVkRAj!XKc7!-Xi-<> zqi&y`o}#uOsU2H*QEndkJ+f-S!J0rDR2v47b2A`9K*;xPCGYqw|}#Z(iq_=H_L>5 zh^xBA-Q^%IV?}o6Ky=Mg325~ZW~!__J^>BW1)<*b3*c3CGHXMAIvojn*|Wcf#c&5U zHYlTJcr2MB7TH#a1lFtLA1svAj2T-MCt&;78gAL__2n(zIuZ1p2Vm_m zxEUzUb2{aAGJXUi-pA&w!?QQa3tbr~?>C-fI5e4Fym?2Ya-T-EsAL8ml}~A#35_jB z2OI;qP~DhUe8?;$2GV%JZPZUtR5@?vvn^-tr9L%+MFl>k*2*}%%LKV(oXL318CIKVfPwvk ze&em4gxuKRRDrvYAt0>@U)f_R)twg6SVa_YfO)&%O>JdR=wNyxP0{ee#E@dC*aN&| zgj;5AXY4!IJ0{G;mq!{;Ep$%|UByEwfW_v5D~+9GJ&EFCRp>4%5ro7x70%BY;63u<3TK`P>eH*wIXSWJ z=y2!c;gNn)$huAM!k!iy9VASA3tLaJ0m3v#>7o&a89yAm$p7XaXq+WLKiTHTS z6N>?L&ead!Lz2lG)ZwIoe}j#2RMa5JGZWvmav!I?vv>_A&f0%8CsW?>gk49K?Y*J3 z`y>qP{&U+SX1<<8RX;ZB1V4inAXs*7x!4KEw37XK$p?;jCD6MpMbQus?T=8=zANg2 z;2t4&!pN$*6RhegKdmD=eC~5nh*SR1Q?L^C`QlYD>qa8+im>;1R;gpJ_?scrmR)u^PCpBZ=Q}wVpZy?L61Zsaveh&K$4}ZnjW)uEsjrv-9cR;lh74o{k zLLvFrbb?PvJ-FJ9B`G~UJ!K&gnE4;v+(-&Th2?h+ti70xEGXSU{Wj4)O&F_Y$w5~-kGIKs{@F&pzj@mZROtMCi;PCC z&>+l44NQ&yvj81rJuUl2j@pv%$8S1d8#vazy1=(QJYAxrlZ>-MLC1-YfimvY-b-Cu zMBK3+cGzC|0bO%Q%k})pte6#M;>*_0tM=lg4f9IvVS!4QtI{=ULExU=jtJ#aQeDxG zfYL&DHN%KyQdschFa82Mi$(=+-j6z%R=7Bpg<)fN)EHW;t5HRg6_E7m0FfRl2Sw zS13o**^kDi{mvrzhuQ+5Av%@4P(aaf^!s3PHu~D!2;NSI)k65l`SyGLrGGnhgIzSH z2~R=R+EGkubh1;vos*=9lqXB!T+Gjd2@TsVTg=$e!e{CM8+@hy#p7;E+7ch~3SU$+ zGqV@-ci|?MlYXLEkA_6*u`uD{S!#2bh0;AL22|smqxiDx$kSLs9yb%_go!6lF5o#M zhQ*IK5&T^9fP*YtK00{F`0ov!9kZJIx@UN$UP_%KlNGNbj7r}&)j>Y31y7Td+eN1; zI@hc%<30u|j!zit8Y`n8MjjKE0Ljj?-dsPDdZ0Q44=;?R;X%CiY2p^%sBpE&x6xc^ z|3&G99yy2JKKI7QOPLV%%tfSg8u(|cN_rpMnE&d8KJHO*lhsJ#0)fWNExo7a-xq~s zF3XCNj;=AuzG{S&@R~Q$3Kj+8P29RIFsMUgfhY-$*vQo1uQh<^6Oc9pLm9}*kVBS2kIm< z4vEOEl6dBo0@H^1>N!iY(_LUX)f;$-0b026wdZ9_6Bq<}#0!jUQ1M0JRIAA`cw~s zs(5tAfV6#UO!n&GZwaktc{Z9cwhrmii$S1Vobq2r>Q(yf5%u-;vSgT00qD8lhXKy+ z+TFA>+&WwEK|Sy|sJ4CQ)ermPUeR2+OCGBRdQM#6OtiE>P^TMLuI@grwQ^JEFvfrD z?7Z!15+QgEji?iT8WeOgg@uz-W1jrQQ|~crh(`MiZn;cn>!B!AFdd>rNPx(Z*+|em zf03f}bGaWi))&r8)xHQssBYFf&e|3`DnMWr@=6ozO<&Ct*n}T`^_n{ofAE2Gag|3>;X9u-a3Bj`h58W{P(1#e;o|e;#y+tGE z%Po8A9QQo5z1UJLBE(k{#og`7d&}OTAY; zy)P(=-(Fn}mofCC5=c^E_DMTD*z|HlDq^_H$Z#Tkq4(W+E%%fLxqhta_-Ov)WHVvM zP}c}exA3+_x<=vQp5U*gAu|8v;A|{ti!JrWdMCF5PE0%cMoI`5@*@Q}ns?x-cv}d` z8nq?}?G1*y5@~Wvhq7x~NVL?}&|^R%Xd6F%_}*o7a$v#}dOqZLYu^^)Q%St_l+_qc zLCzjybZ3+*=R#!qh$SEGKZ0AEK&wWQr#Efl6^G%GHA@eR7My4SFw`@G>BDz8($rl2!pI4A+w9D z#f>sg_FW?_uQ%b*_hc1-gmG0It>C7&4jU0FKcz5 z&70wy3(=AMiPi*rse8#MXY_KtufR>%N;M1U%4sv%S0@Cs=plZ3bsk*frSDT<;nS$T zH{E_e)|832hir04fNoTC!jc7N)4RTw@*rZw+Rwt!MwznGzxN*(MRrX5`Ua70g@d@HV?8fau9s0T>(fijG4EZQ5odpmm zhmBp?3$u`(snW~*%?EVz{bE(O!iA=zBad0Tf^D#dJDZj&bY>DI zS2g@p<>g-YQgy5`aSoIyXaAnF4y*c=x9s(wVeGq7RdI*6(?67a(eBV^89E)n0*mfZ z)v6tW+=)60XnyeS?0bL#Lm5S?i~S;DDj`mQ288sP-fJ7W-LjNL(SUdHUN*)Xn0x|i zMjSeyI&0QC*4BtOg$&meQ#RN}V&DnKPWCGJ8PdAi z-^mdEW*|QdufRlNMj}3`tSeXgPTDCE-=dypox_nG0+$^YYkQb0(ka;-KMFtc8QVMH zU{19M@5vbanWgICm*9^LcL;MJ;s*W)d)X%E4g4w&TANSd2(~t>kB7gwdr7r_Ll^W9 zsbk-Dyh5G z%!y8|0=TOeV`k{ymD%?4qWyA%J-tUBedVz)s=sXMDf+#Gd8yFX(h|wt+xsehy#WUW9}|*Fp$=)k8QgO2k*j>`1|@$y5FwRFL(&a5aJ|${S^Z|{%6)*!8nVqTvXXqIDhe_ zaLudfb1c|L?&S5mUFTzECc7p+j@9&gJ_196!?pT|ZGWEZ$v#ok4egl+7>Ecz5}fc9 zsV=Sly!muWT1H8?vPIxi()=~ceiJWiQJ(f!qRg{_z_gM2v(js@K+hphGE|DFdl6%M z%Cw$@7GGTN7u%bC6Z%EWWl?L8gN}*R=v-kV_nQoCNgrsah9J($S28n&lnuHv1)zmI zLM`;l{2NYQ(t(knPsxrbl%chB*x3DNW4-HRv3m&P-BI{?!2JmJ zDOYv16 z>MknE{Vk3dYJAhhO62)NOFq&>3wgD=y=bO!7xb}zpJnG>mR`}4RZX?{mu3CCn;y10 zp=CHxPrOU}@BQ8^+9s7fjA zb`dYhHfVnr-DRf^WmhHiUGi`i?}1&GI3r0F7ze?RLfWryd;4>(I{((0|DNm#8DH4R zb+sa*97BGALWMLpR%3d892}h7>zsPlX0WZ2j7_3--DgmWz55A1-LpJ|cdR%E!Vt?A ziqQUo5vT?Isf+z^Azp5-3=6w^ItbNw43m3*Nkkll2Xk63*D zfpE6HV)Zt%W&<#jG);{_C7Q+QY)4dB`&1=uu#J4za34|dW)gI?@QeAEBRla=e-`LB zQs61revw)-?DE8xlUhi$%TjZMe|_)dWSCUgo3_CMTDgyObMW!;S&Uq-HCWPg{zj_R z{I5cTmih-f{b-{Ip^hp%n#ad{(Re!M=i@a97F}DC*feN&x@GN4lq0yxtuF@*+l!0X?Sq&P56G2j``qEB zB^E$)h1Zq+lv&zh!pmbl{kns-UaY|a2yHSiQ*`)Z>`qwSZ1Gg``BdZ`$BI_r4_tRQ@Bgg zu#Q77K8W}TGqc1}*ISRY^bbuZdoK1U~q4R(JH~z&SH_nSJ~|3ZQ`TJ$||<# zsCm$&IsIcN=gN`<=`?ndJBmYY^r}Y3ee6T%my$JJu8Gzsg!YmPOajdm4(GMx{N$CX z(#FJZTg-x{X8NX4@(VY6Qj1ma0!qbsZgrt0^QX+FD}<><2!Vin)gZ`dyIrx8IeTbw zLHk@n8+$3w%NAnGuzh-i$_xv^ZgKF$>;~SlG#2$#St+&61pz{^HK@Nopn$n|Lu}ch zQUF^SL8l-S&017&Jw@BFB#h_1OHy`#@pF~8)u_eKadMCOUc2Nh0(BG1(anVR7U#kM zk4EZ;z5DH8;DPZFZELbc-Q3!nsEE|j2*O|Kz=syDcc*J{kT02quCaPq77%sYKWv3X zkH6P83!zu7zJjJt)tI=(_lBo~pjz4$??R84mI-YfUPrsBh$LXoL7?=r{j zUR7MgtOXYMnns!b%*A|MBn~bzX~6N}^K%v^9`t$cL4iI@rp#>svm1JY{Wv&(n?xJQ zLc_i?GK9N&KhOHZm8)a-3gMD&V{Iz5see~JSUMNt3{%UuM&>O!`Fz$C>E|DJ2k__M zIPVq?*Eic?lcz)%fL~O6@r3=IanZVC`6uSy4}Bssxp(h3b-1r^zLIuv2Kjaga~x-D zNt_;9S(>!a6^XSjXvrJ0f5J(WifExuQ+icq^>|g~-F#*sObCs$AW{_m;4Mbqx!b1v zEG!Tuz6fGI{~fZ(>2bE?`9*#)-Bx9!s$O>ivPHhJs4F|eV>dRCumiwFeS-`dAnx&* zsn|h$)}za&!$3^~SEB^$6YmH7?j$-yGGXjE&<;D`gA3(Jps0M;Kh2T$($!dUVQlVm z=)-Q~byltu%^dMP!~w-e@C;PGZjG&((2fdEA;%t8=$3tGTnLo2q*$(>xc)2OFfmvb zr)~CVRX&{l!`vnt1!+u*d?qdLQI-Yb=oH%h+EydGmM;dwNPFl-9)k;1HD*qroxQI^ zgion7%SFMBs1&NA5m*r?0~`AR+R;D~OSv>0t6tgwx8fv&+NF=vy=B7?Sn!URPUd7m zGaUAcJN)>Qg-9qr>ffK;GS7wH91NLpK$(wcvH!GtQPiusv2UznA)#(nb^;^t(53!) z{CL__6xh2>5`>kX?`&uf1!3{_y9FR`JDmEYz>%#$RXW_hC${Xr03p?P&TluOOCc$v zAIjN2T7!D4ho5GTO8B@!K9|!FWoRwWsMeIABd&MnrTpaK+j`iD0B+-tFZPS1{3E2n z<^&!cf)-L%UCQ+=wn&1{0yr4UDU!A2f7ODs4mfEMyAmq2JFU@4b~wU0G<6lNSr(is zhN`?=?3h|N4Ea&6kz&n9ANO7GRWIaKwG8oEYDK3KhekBTd|0Y6!hPC22@Eol@ICY_%z#*6M?zg ztf?l&cuhdgc?0lIO&NV6Tgl>Y?dEH*0cgXElIJ9B7U0_ zF7p>brfKSQNy&76vJ+NG{sBNQ*=6ijBIdl|+ukgFVjZ>sFW28xBQ#P8EUU;56uP{2 z#hmjWD1J;fdsb^>R6?|QX%ED#JAz9+9QFez^>ps`-D`NeS%GIB*w57l zB88e{Ol&-t_G3(dJ9Jb=@%M6gvVgDd z*#TY5{?XkSbji9YV!?KARO}I3ek2`t6vq8AXR9ByK4?|U8egE>e0S+9?A9F>8ZGSB z8g&ZlXn`}nmGd-!c-XRa3F>%Vy#AqcQ`z^xW)naKW<3cLI+y|p6fkoz|Y^|WD! z`?Do^WiS?dX?KBJW~j9lIpdgUbrNCn@JfBV0_cg6D4}6|7@jDB&h?ZkfJ2lLPdNJ! zt{M21(q$&;2WQPSyOtN>@}uu(wo6&V9TT#-di0Ob0bJuufLjJdPP~7oen^q6bD+!# z2yLW2pxU{X(yLtNq#C9^t!CKS70tl(pYx1MdeuEUSeTHmNld9*@Y~5IQB)8VdHg}t zG`(Fu?5$1r_$78Jlrthsn6?fBIbqeaNTi}9c(hA5;mH$WB>&OKrv99TT*&H8mu1?h z^0QaB%!wLN6ll+kd;9nRaRO!T%`6*20R{q+;6V^U596v-i`T8cOC=E4fNrrLqN<>; zK;5?m?McuL{PfYPgwED4zAh!5*rZH;umz_wfV9>?wDKlXZD9s#$t4$cp^d{hKp-Qu zhj|1uoYH?eDg5I&Y|y=m8XnEKea0bMWJ|M6mN5*U&(@4t=DxwYUSEp)EdsjA48S&R z@qwwm;Y>4n95$N}_~Dcx&UZwq75u}&!=!4?*!;LDH!kkDG(9%{(|F>vXHb!ng>1Iw zvt0Ig9O+d7#Z~Hu_Ozt3S}dx8Qvgi|n<4RE^6&nq^+v&~c{TQCK#NJN)>(utx`dx^ zpNC^)T4~sLe@(CUnom<(cE`fwk5TXr-tTtl{qdsUls{*?QD*3h%@~`ET0m5fpRI2$ zanqQDIWrevd2df9>G5Y8zs?&8lT+12xPgrg$x&)~{ioYv4^8yxuV#;G$c85j4ORyI z6IF+FvlucRE|ZT}3PanNw!S!54DQR@A8>hLz}9qf^ApE3<($yx-ch}Wi7R|Au}lPj z#}5iLdR6zzZ3$cF3>wr4%lGyeHzOyzv`3!^viBCU_LkeDS)VV%F|`gBo1ek#ro}e& z7f-ZXcjNrER)@-Jo)=ld+pGjW7i!zXfY9*!m<4cTpu38lnHCbXI5y-GezAAe9&Qhq;$!-6*I^6Fpm_SwRsG-OlWCtw?^DDRiP$PKaM9 zZQ7-H*l6Cl>?dYUsQ0RpHFP6&8>bhfx*e{1rt9X$t!3CA3_V5XJ%0uv)$V58w=Xqg zp-j{eOib`uh?o1d#Y#IL{zptkbK9_%)YirZB0~2pz%ppjYG|?jf&z3$O+itZy9ZGc zdKc+|VfG3%2Jx*dZl&B=X_RDPh8@K#x+l;^V!N(45cf99S^{u#RnI1Dkz{qkME^~WU~cv+ zHlx5NtfW29lSY$ezN#mmx|kHMW}aAB-;e0(p4o2^o!TMAZY#Yxx^DS(r?-0Dov{a( zr8%+oBv0Gw%M;jWw3D;s2+iJFoO`M#KYfLT+B2^|ptMamK$XU8VQ|Vj|Fh$Dlg#=! zd6w6N058X`S=5+LO8<-mmM*Da@z=^(s|Tp7{sgdkz;4ygC*PWd zR@knZEWegVCI?#V?0WTz3bNa!+BgHBlj0l1?sgr3~LL z_Zf9C#&A%{DLkIMwiQ`1>lNiG{s-4!m#WU`)$FENX`?1bJ9jXWzozwmbknH$_Mcvo z?zTKEh0!79X~oXNqsdj4twy%IY=^eqvf=z0D>A-2ANh9%TT7Du&(Uw|Fqnc_1-;IV z;%B81EN(ZGz};ukzvc*Q9u>ZJ$Lq5@G1-lfzWQZ}crG-9rN3DAOL7jI8iPGRnzWs0wEBq65Wb$FbUt`Yk38uupSGcLInS8}* zHaIe)fqAi`{c%HcBK#`erBxLH3710;uj@1)ft;UCC8d1opwwL1Ih}2>(NNJ`x@kY~=|Qrke-E|< zidsMO_4zOOMDglA>Yi6KIA5ou*5@H8v8gs|JY;*yj%qWQU`L4~YyEj`qO2d#`grzX z!;LS76SqB0sJDft!6y3hbiEnslokM+q3tybaiWmTI{qdJ7Ihcn4-E||x4S+1mRp^I zxrql4r72AVyfbVLOB(EEC^D$qrd^ZZ^6q`uWifA-@45KCO$TK30 zOtZ-LWZ?H0F?O37Naw~fdlB}iX-toz_KJPglTSx#=?j$lOOd;Kj|*8OVD<X#eMfF<_>Sq|sBalDZmg9R*Re37>l7U@oPF5h+TdX1JZhB+B^GFwBN1T)^4oILmMIDTh-7@s+`yPNMUkUTe27~ylnLnnmOXx^aX6ois z0=>m#PK8qow2f4|ncr-Tl;_3f8v{5JL`%{iTlu9-!H5{xQ zp~4%^(a;Rpb-W3CJ_9_A*vWEr6rKM-y+x-Dp5h z;QM~Vs9Rz);IrJ)KrSG1>m|Tum*-*zN1#M@c(@CQq^)+Z-KkK%D7>qv=4!*Jdy?dx zc4vX=H`*tQkQH)hYyZ5mInM8ZXt$EDre;u~GAC?J{mX5leTuk8J&}Gp+nYe%L1Se(Xoy`;PeG zUvHXSC^H)mX8PX#^;YqiY5NN0n|8)qfS*0L{m=Je2gy@6OaL6UU+wf!?!P=2mq6;_ zN%5YU9bf-@{A1B|8o4!il(0;;XY;6vntQ7>rSo>s&-A0oXS z0M%b5Fx#y{=A8XM0ed^5{?7u8^8yG-KD$fLU1t+#mBQbJ6rF7fr=g%Zw5 zgvl77%G2IASeC@MFTr3*$AzXCa) zO>5O%78-Q8pQZAVnI3HRrT;{es99Qn!9ATic472dQtuiY1B&sK8tufCxv4qK%(;rE z+?q&@b*R#`_wToWzw-G~(;B<{^E4t*gsOnb@F*q*3s(WGq{`*Lvdv)kh2)?*pi(X6 zCLY};9=#2_dY4) z(LJ{0iCL*cTg3*7R)bfayq~!@Y{k;f2>71ikBx@qdL{?EwgR2&&KKk`M!%`@gi3s! zpYo>t;)9*|<{&jQL+dkmF<0>50tFNVygQ(7+h~KT1;fIhLQLUp54Y{V5eG23 zAn=2^>8>&q{~jP*#kkH36)HG`&nXs#3?l^%^vyOru6wOKD-wN`&-V$oEVUgRazQW$ zb92jbRjNAf8*l!iC231u^!zqx38{YJug!WN+8i(0KUoM^d3A-f*Z|mF<(?A-a^GkW z+voc>oU`<7{Gv>}J(+Nk1t}g9X+j^i%B%G`E?}f{PAvkdu==}DjMoCJCc>^#8k7jX zAq%;semVT&s?sBAWZdf}m$z=Ox$ zDL$3;I!ZW*wA`yDG|muNyXR#i>>>;^|05K}B!UinJsr%#_PUt5mvGy-LS+g19#Q9_ zMfv&PGK?T3w)O&%7jteL%`k26Vq*(>Zv zUbGWF3;Xbz{mBU}QZW1i_(H<9a;irkt%XDhamy08BA92=kmPjCdWN#+l2my}Fm5by zG(-*`$st4mYH^A-%qfJ+*p*Nxc|U&6r>fMgN`ZsnFiV|h6fzErw+l<*p*?ua2Ha}L z-q)Aw5EO|_`=rs_e>(zV4q=tEz^%8*qLbT<>*s?Sc3493_MU{u<+gDiOsXqJ8#F|ybH*J#AlW@X3 zl9gFRM}8j4JAe?MzRn8GCDgX~Qe0*cse(<@Q zuar>dj!syVyv3ni$uC9-`km&-1!2!hIs*&s%1UK5^gM0L7l|^Y8>L2Zc8kRgHW8kn zLtFjv|7lAUBs9&ZOqiV2RPs9H7rn7!DmTAk6e=u;6yMPJ(sXV;zQrN&OwfkI_fT74xH?Y`dKf?dk&Lbd zE;#Q{Zftl^aF}wriuQdHeL-OXSUZMtSJAme9VEEaU)AD%sdkr!Vm7Y(2YAR1})wh;dgAf_8Ri~St|ZB6D7nN zY8ZZ|RpOtmT+|T3$2SG99{i0fH*-ZrW_%FCWaOs?2lXTA$&QUCu!y~2;;s#WzS7G) z*VAnEA2YSd@NS-@;W1mqUEjH)r-fA~&jafxaRsw<^u%w)r6)(W zI$T}yDzBCMAv>8sKOn5QEsE~B8rYuK!}tQ*kqT;poe-x}w7L8A4Z(NI@kL{%mGzduo2w zCs9-oed+woU^C?M?ZGad#$Y22K@Im{zD4OSu8+v=H?L!Rv>7|v$0xvDEC=|8j1x@tUb7pO?U^S+u#7V<;4oCa|}A@Yh}gEwws zaoUH8+K2n3p6<$hf;Vu@V4naEW`8DU9%$`lnsfaNt13EBCu8QP6MoW{fW&}59$%aU zIhk59p&i1GrsYdRErmr-o)x|PB>#yJNnt|E+m4_IzG(~e9o?aNxC4iLU5_u18ES~U zpDg6qex$etYYvTblDB57>om=vHQTCsr+p(oe!OD$UnWd;`8D+gwJOd9OwyzNecg#a z64OqHYu}J%mdOw>$=wpIRPSNws!1oxag3vfjj`VLw=R_b6mJcC_Gv5W$5;u%S4R03 zeKq_!c*ro8A@Tnix=(~u1ElvdHHWd66VfK{cDA-rgRMUQz0laK5`g}{Z|J@Z@XXjK z?Y+i_-^+a2LpJwfCPlm&+PAd7sImhyNbT`^_+*q^Gp`iIU?t|m^4zdRwBfDW4Y`N@ zOb^vLpBE`NQ#}4z>oD}(HbF03_fA4v;Zv;53|EqO^=fn&z{};>2%tC%b&L9b7e^*G z*rP<;A=qxBOh$I`Z(w7`1 zgd;DA?5Xy}DB8)F<-D}Sj%RL0WiE6MJzMX*<17Yv|Z`e(Ly^s?#_ z!H3JOOxoweFMpq4hmXIZH0$@f z93<-vSV233Ip{R7pE%;D>Iu`YW$i+_96u>J%*f9cVUTr8atvEbB39)zy$KHzprB0^ zX8^oo@DLPD0GvChlDkVAh6@hs#bml4#EPo&jh_{LcMBaZt`_c`*bHUu>oRp zFX}9izBNSp1RJ5KwjqHu(V3;>2+FOO8^y<2j~H4vjgUhb>v~k&=5m{*hG~o?)B6MH zCW7ZSZ-;x7gxVW+wj0ZyR{TlynfWgmHla#4$~Gnxw84l3(7YZAgeVhaEpMneIW0=h zxB3m+EP3c5C`hKyo3<`Vn0`mmdX5#bQM3*H{@;=jZMhLk{afclMw-KYo~jP%`fNg0 zGaR0E1s$K(yC~p-oI=J8=esvoJI z__3koFO9tJW{&90sVr0VPdHZI*^8UC*y{Ei{>H|m>&)$o)+)bi0g)4GWk%D;0yXkl z6D!|wWSSU7L-e)Emj(sRkt;jd-Byqc(w+h9iULljZd{h{iERz=#d6;3XKq2gvZ9ri ztrqerW9?RqMI94-{hErRWQg>Q`I%gp9DkXywo#)Rx07JH))Uk=0{{Ij;cgKJ7oly3 z+o_6qLG)Sm?7O(W*ESA^?%UNU+tS+IbM8?g>MyfpXxVP3f7EB2z@{eIq4Yq0+oruZ zz32Ri{uCzIfFWW9-t+lM8@@Cc8oiO^C++vVzWovJiaao9=p44MDM8ZEXP#oz&BH@Q zr4@;Qy*FNxuaKyy!il@WskwD~WFAtp5&X>SC_b3I(e2x4e?R$^HdL_+EAgq4*zqDN z7UCu?sgm0+Ht~f~@D2ekj+853Sy03F>96ny=2Pq@5X5=@yl-{8G~n`1Zvhf~ z|0K5=Z&PKd@LK13_jEoeXdRF@r<?6T~w zID(#!yl;|+D4@(d>N7BqCF(V*_@6FdyW|}H7>LbZn&eymHV3VpHbmcktu>kDH{hG8#7wpB7hmTU$dgQA%CPtP19ED|`Z<+O`8{;~ zkij>8T5mxe3X0E#8oo59or;G&&-u0=Bz(&%3tdI-a84_T6~Ll>e-uu9>Ae`(1G#(G zrkrfpg7OZQ&wvC-4>XQ`yU`3WNN4W*ux@crp3>VzN?~^1zH7A&T2uhMXdC$PBgL$$ zJf|Ls84W0(c1>K|t48zm=1l)kjfAv7lobV?%#SsHmvm%}RZAcm0jRSa`(~2LqdBwY0L*U^-mU zIt@C0Uvdy3tCJIh6?hsZ-UTXdFZpEg!x+PJ zU7c}7^GNnSL@pQUIYnm;2Ch`gn2hY(xq_CrYNd=N*eqXGij(iVF~Az+IV3gnL%TMk zN4Mp-E04b91io>%<_tcdNh;zWKtEMhC{brT9%JmTJ~X$J-fGn0RA zQBC$%+iYLdL;m99fH`muzuipRjoskR1ekW3h4lNW#Jw4$Jy3Lvm2Dk1Vf`61_LJZ_ z1BU0SR;(Aa2 z2Rb%Im*i{|4V{7#pNJQ@3lEgFY~;6XgLj#XN7r#;r$ZIBg5|VA<0z?hT6cd(INgnY4Z3P1299Yo*GX-&WEo`KK`C>GP`9UZrn>F}oA6 zD*YnTki+uF#~_G%M$=YuJ~9eS4(c;E7uNTGUkyV$43Cy<{>1)gcJeW6^$|snRcBDm zs0&@Ev?=4Ntn~&-|6WVE-hWu5%FCQ-pkA&u)CnE=FRau_AW@8OS@`I=7w+%%w_8NC zd}L6EYz|Q$uX2@zp5G^Ps#=ZICGjGD;Rp-t97*gnAeuv=4@p-?WADQR674V z>do16$x{ZqZ?>f4CqgUT=p*sA<9B55kNgrrmi{lh38U<}brEkYCobqrA-q;nmB6Ei z2%yBwsdDT+m7%K-tUI&wg^~QBzx_}-u72CIPS*E;$8X&R`Ca9LZyAcYU5L%9)b4_R zr;#3mvFttnfj6!tec6R;4OFqQiN~_So*BA^NuPE{2eb_|T^veY$Kh z?W*>N{;0fp_dnLwo#_ROagb2?xr8JqUvi?WYRRFcwc1xhRyA*dQ z?ry~$3dMrEyA<~pcXumN+}+)wSVEBE#S6jp=KE)ECX<;kkV(k<9NDvb_V{QK&Jscq zngc;DCW$$OtiP}t=vM<9TH+PHQdIbRx>NT7W#_a7jo=s=TV}6VW!qfh=xa0O0U99T zad=SbclGr#4o^F0+hL(!_lX=H$sXy2`T#1MJr={96L&hF9C1y6qz;K5ScRt5H>ci# z7Hoz699n_dH#0h!kRb$i!VWHstl!1wWtJ=(RI74)?!oe?9{@o-Ag9iVXhyq!j&yM(+hJyYf8Bl zC<3~c%rXk0W%SdZI>a38t;v3eJoTinA9hr6=>CooT*)uiZ+$%F&$C?u`>ic(ZqA<2 z)^l%ohY%g*Njo{QE&e20&~#qF;Xl5(U;sE%A!!%I1R|9d7bmZ-8V#CqNQNk`W1j=@ zDkrz6Z8u*8AETTrB9?X&*Y396dB`c>U>FbQ7_N6=4}Vc)u=h%~|9r;MfUNk(f+0Ae zDe-46Jt=I}^#{}MFG9FxnF&(E!Jq~&h;>>TZ}OgjKZ}|I)uQ(}^&ir!e(S9vUs1<) zi^RA)tPD>I8OQd{opF;g)$;Cj>dscLKy$BSdI$}SBNRLp$<^YC)M zPNCOh+B^k}iQ2D1EH53c4^H++73u$eaW3CsH#uJ=HxA5*4@u_*^`5DBIzKRfrlnrh zb_@-g@G6`hR@eDAO+MT~nOLf$xco`gIN^uCN8U@A!lV~MRPWs~ovD5$U1PV-wAAsmetB9QjeU0_@5HJb z?d2P6Q-7sDO2ha!kscfZ+_o~UN+pF=6eXvV9H2x}g@b^!myyUE67}zZ!l+EyzWJvl~Ht#Ck-0#UbuWirSL-+J4 zr}bmB!zn})bwN`N6}+PS?Av#h145q~5>fXJWg#d0`-YLN?OAatkek~Ye`l_%boRL& zxAA*?4DSl6Hs7=~Rm1Xg>--w3AmC^=yMo~kZq;n+)*eoVSIqJ(iRzTN1q~51O}_7! zdaDK#LQA5Pjmn$526gAU*Wo;!-+n?ZbFfnOa^Djy5cT(#Q$>@d6942zWU(t5;c*S1Z5-6rXKD)57qQh-LXzFB=Q2v&uZtwipo|ZeUu%ULQnpqKimGr1t zvdlFC-wF-BKdyo4LyX@=rZ94zJY;=aB42<*13?ez9|R$U&n_m@u%nmiEH)QTNz13Q|$(5|hcx};_N{LW%-z%6Q z&{zyXHG_(=54al!yKNZVhBUh26c3=p@2*&u5uQws4Bm-oPGvs)r_{=_N@0sCZXJQSR z7(O+_z05m!jU_8mEy7vbt=Qe zON}PDGS-LC$BFD1uRBs&)!aQN;oQ3<)8XfJTVW1)?`Em}p`JD_9ov#NdWk`9;epdj z2Lzo)*ey1XjJ@b}X#K@BRl(NcWrGU)UnXAudwF@EM-*mb`6%bhP;N+@7OXi*0g|qIY1lcd=-}&;D=fJPTT!xCtYy zLKx;8;J~z2c=Codz6_0*L`RCC^Dv-K3Gf`QQz7|D=KDSm!=x&MT5nPEVhrp4@cNNI z$h!X~W1M>eLh#ZX3oT`RziJ)yJgt#Y^!9!Eq}^?hch`9SQEE8ywuKCsFk>B+k4L|f zP2EOyLRrzUtzG80)3Y~EE^(p8RB@(NCd@rTC>Ptt0i^h#ff()FK0)}{Qjq_7>`YPj zXkd=L&cmTgC^>>$gAUV$k)P!Rj8~E1@7oW#^%1Hw#GRsNo+&xgGv&2dC7#V{ji}-= zVTpyJyu@SziT$P88W}`iY*H$m`dbbav+HD-v zQd*QYHcb3UAI7X5yY(GT;4K^F)HCP|MyZbCT-&cd*ZF11G5MC&BhlOd>xpBlt-W7q z^YGoWUWlk$cOj|j{=OT$r84x!;IL=%bJH)&dwv%vXKF@6_Jg$VijP0=j$+0|Z$!GQ zFuBrG5i{F!jQ6?zQoB!0)M9w<6MMZ z_Elaj7C)Eksi)0Fi;nh_E~Dl^G`7qide28DqXi6{lq$PH!dzWOtgz`h9jt|5m-8LS=JzTU2J=W(qI_h%Ax*X+`2AppuM6NeWAO>3!o@C@R7D zCx_&toGJHuIVVD{rtl|@)|wpNZpd=+q;mnA7vo4zpk(_Y;~?hHUY$VXFEdNE5$+26 zaX{8tk`1Nd9t{h@se7#3)7ZhdcjV%BYWn|k0TiKwp)ECC;fgkSmv&!S7S$cH1YAo9 zqWgCmujGmpG3o%)y>IydOMgSjli%pk^z3SDf7{&KXjUo{lY?fpAjSp7rE8{608HO6 zJ1T4A>))&ppOZ}UwO%s1mzZ15-H>y(x8-E^6)BNZ#mthP6uzIqeW(WCq?cUDWyU-3 z2xx|#Szs0o3<2|35ly>Fj+o9Yx#AJ|J%bE0A@WpTA`m<1;z2@&ZK`$n0`ADwT*{c>#wVzp% zMNda0rQE9OXs3JWBz-ZhFb-YEE~KBq1Om6}Ell3%JE=|F^|lxGv~ItDGMn_Af5&r@ zwKob5R;P~jNpS4kNgY47+dR@-7@Vp=iCo(fAPC8M7xOw90S4LTN58uD-n+86IrqzS1xe6}UEv5vix+_M z<-MvlU-7FK0WC*=n9L%XJ#Dn2FmLR}`e`885=qLEZa$v8yTb>J1w1;li1tr9Y~pva zAqzW;3guxHOc4vK(G+dC;?Y2utchOXTGz38>yNKoF*xq@T5ngBF{;TF{e8{jwlPol z?JmW?qr;p9GKERApfiT3fv{0tKqC@B@qSN`o0WkCCX^X6khOCm+Gw_Hp36Rm`*~<4 zX7yyD+X#mC85+oY3o?Awz;n}}@togN#4SxaE$gx|poggG-dc$P6qF`n*0xpEzIS)U z2VHd)jhUEU%tI`;)w8WB=-Y4cSIQ3c*UFoDiZ^~|h_G#qU2ZH=)W2VaKQUMIIaQ(H&%;*32|2z>@uO!jPBVxrjs~w1MZv z>XyClZHS_&8Dq7#A?VcI)5^ePS+ zU3Lu`^=xa==&0t2Mqzcny+n{{@?w56@6|jjcC()xbeobI*2*kceovftZB)wwK5{)a z@)+d>g?d#!^fbmXP&n}=@QQO;ZwqIR(A007k3NIPBj2ww$?@n+xL+shAAE%qGwg|c zWs>tm{Nnb-@y46QDC%pR@=B8+_><=hs|mXh2Fz|cf0Z*X%gTHLAbElNb!m=eG6&Py zIh=n2)#Bfi_N^aOZ$X(Omz{J1ITPNIqE!tJ@Kxa3pvivTMs}X)dN;=X#i!egb4Ym~ zmQbe59KE+1{^tc?MU3{ZJKo}zrsChviC=&7=K)Mw0wANAX1cK{{e=kW)kbVgKZ~y6lwUSqyxDmw;oWwSjKG?|#)GoSsMJY|6YLU>H>YzjzK40(NRac+PXrrY6DnR zXLcr5RSnR-8G~ZMx}0{mgl+U*Ua@dT1u(GXlBQz5-b1PzQh~!rFa43tg#^Rp`Z|G_`<=#%_X|CdiNUI-@udDlSXW2(Wm;$Ao zjXc*X#JoX1(bGVCL^GoUzkPb8ds=x(<07C&Zvop_YYp?Z(&nXcN$+bU%DB#Le3a20 zX&2JrJ?qS+>e)|yYE|5};CHhUQPIaYi3ZLJjj3M*xK~4jxUcLOt+#L73-+5&m;7;C z@2kJp8pc3F<-pAjpKqT)#~Sx8CVQpQj15R#N%PL;vzPphZxEAxJf9J}Gc8XB=aD+x z%CT6W`z^9-olgs_X%@nyv<6nAiA=JYtmsL~h64?eUxGLXnrenH!*6Z9Zq>5}zs=j+ ziOvSHefLNY8B7%L_U1P8it&Qrj`{!=R%>WCUOVJ?yc1%<_>NIh-g;tnVKM8LR0l?<(- z318)shyBc{`F8b7G3|%gDcqBp%meWV@*4N{qBx}qlAW3ilCus{M4iq3W7f4tM1oeE zdFwPsj=DzHOL&2!Iz~F((MxO%%1qX^x}w*&WVMy8>d3o7M2|T`!brQZMz}{EBL(s1 zJ}6Kw`h#ZX$lLkINr~RGs=?d0ZuV)OpH7MSHIj3>Wp&fo{-2c27&Ui)7ztvb){SIX zn8W_ohSsTyZ>tgRRMjZj6>@{>RNmY%uQ?&^4Pf|HGrS752Y81wfaXW_PqoVx55;aU8-U07PKR06H_>)y?$8c>>{@yQ1C>Q&%w4Rjk$ z@iQ<6C7fxc;x+E|JD`i3gwI|7;>BIBaPw`PTzU>pkB^~AWUtx`ZTz*~@p24v|3k`Mt#t7`v^)u! zd^Q}MMzbMOIR(&XqWL3n#x>mLCDdr}X0X%*;Vt=L3j~4b#{CE0-`j&891Jwi>f;~m z4Fud6VTi=9jbKs^7$SHdZE0Qie6BiW;$~MR77GGY3+3K^Eq}LxOnD1)+d_Y zLyMiucFxN+vE7k$_QuW9Kp_ZhY_(5N{&cDrvdiwtScLKzp&<=HBE9O{xDn~YcHrrQ z`K{l?2WhDG6ZTbKLY?JnX8u`(Zo68C_kF6{hB||*L^jpa`v^7%eroPTt=k3|Hw%lA zi!xiGsH=U%%|+2vJZB`J{I_rZoza zhS3}iTZHu2V()_Y?~;NM%0A6vkCu{))-v4$Wa?e7GWMhw@okuTEq>VSAc2%;dZhmlkv z%YZ+5Do!i(CM)Aq#bxZ{<72w?k!rwhCVzQ_4K*)74Nq2QOkMoZV;xGd>2wQ$NmU7e zX0-R32KFG@{M;~dLa65leCmqLkw=LlX!CNtjm{~;t$dT_occUe>t zW4w)>;YHKp#Gg1@0LOxF3(oaOSBd2hbjwH@5yvEQ-i9ufJTBiBC{hEG8g3Ui7U7X! znjxE0l=2>+65qDk^Ciinc=c)9rgHA0Q_1wK0}AWRY48?q%awgne^MX@RZr;H`vWSb zo4v)#?m+>vEXfcE9ac`6&52bs#K<c5`?*ylZ7CGCl1k@ut+CT zr#O%#+oq{_k#hRdXdhcp{9C;?E%`@}v(2FJPJqa6V-%&A-G$?DHbcPl!51by{0doO zP`&M3>yCE(I&6hagx$#`4#|vq1NqjAy~83G%$u_TJxD2Bj2y `ovey@N9SnLcA$ zeDv^6XPe!3$V(gT_tLP-14s{?yEINBU&G+HL6iGuh~M3`#JufMCf8V8ZqT3sPfZ<- zh%MEZZ>J;DODA66Qu;-w$n=tbmC)h%H(CHv^bkMnoT2}2;7@{MkPpDTGy>meqVn^ZpbzI!^~ z+!==M!+x^K`7Ff#7L@aW$V7U6rc+cz6->`@EHbyW{lWm#F0Afe3*l{2ky4QN&_G-Z zJRow^_hM6}`Qb{|6kh7oZlBiTycJjT)$+Mo&;7b_@k3a4^@iI z$A68}K3AbJY%`8-9bL{6#ZtWef>8{1-Bi3}VbodRCF$ow6OS_ghKDYWqLUE_tt$WhIH7sElCIU5886-CXV| zn!*vIA%?#}oX3vPB2#LYCR0J5Vv6cZD&yS}6Nn|JH zYLFI~-el?5CSBot7c&NCZkGb2w;eQO8QOBs*e;kK^cXhq5U$^hRLE%HO*af`we8J&%yBIaZ<;QieloO^rsGwWY#cj$U9X-B)`ZM1M(B@}=prV%wT8dh#lH zsc_Hx#ObDqSw-SZ`m1R zW(E$=WKFpnTE`0oMG^9;jcle>j(OyYnk56I)_R+LYR+mJF#XO#O2Z*-V6hP-Cas zGR2pQwY2axv1Z|we&SvmN9#b8{tF4&o=|-Z~u(>1E2amUfVC|R{+ZK~_;$0>7kztk*>z8E%#=?H2oC&kQG2C$8Tx4JKIN}XWyyF`C5J!B zo$BD@WVJMYxp=;LPf=d%x7=HnL|U!GZyw~+lBqY5$VW-?^(w{)^N_ZS)jM(^eeF8S z#>g>nng-&+Ji<@f`05*IblDtr-@)3w|GCZBn_jV7@|xx1Z6!6}ZO6a2KM^MVt#hsC zLG*ZARNB!d?OS|oUTst>@-9(l*{UUPFgW(mm4zy(Px%B+*3kyvKQY9j;{Daz-g74U zwPYa%lvlJ#b321kiosK#I0axou|A9f`4arnWHLeQJo`6IQ~<4*Isqz zx*l7E(LiQyN;YOpHfDscOZ;Qsm-nYjqk5W^g24iYs1;eh9p4RlYq@#i#_W@YyYa?I z&5gg;DIfX-JU66CEcPfof)>u&_YF&nNHRGrl3Ta4g+j_s{$=@U|M19wV#4k;iw2BYPP+wsr(s+<=!$eNMfb@_;v zj-hEWQ++rv1t)!&S0bdo#bI~@ia>0AsEwoW>dOuF`cl7Ki^`0dm&9KFJM3xyg>j&$ zcvU)AhygQBH)DpX5i5?!t-DaAEty8Z1ra$+R6hS=e}d{67?WuOyyw_;N-=^-3fbo4 zLX&*N)<(Br(2^{$$}AYqV1a&A5u7`3(-4_U2bK2wtK04BaaF@2mXwc@Zo{Shf1bwg z!WcW$JUe+=>(&C_9k?|Rynj%&(JLvxdNY0SmxLmNKMxMh>1?v~n$_!FK1!UV2+q@! z@Hb-SjLdr}vbr_4Bkw;diLiDj1%O6=@rF}I6kQTf4FJNh0{;%Tv|SYZ!?okwLc=!2 zhr&cR#yVKv(!M+l5%ocjztPyAKccdNHr*R<+0?ntWtbB*Hz?4q zIiGq|(g#)O`P1lnCOG~KhgfW7rT;fJ&Z@m^>(&%h7ih zhq*5N34L4G*DCso{0xBCeU+=}F66vxt#T?N3pI~Sgi z9%=H3IBQ*=g8|e_m+geCsp&P0AG-nfd_8YxhdVkSyN!QdfpaH}zloawAMvX(`)7&| zbeHVde<(qhimv?(I?uOxjyU~~CPN0Dr34f!YYF~1$Z<5@oO)h$LHzt;VnwR=Q8-F6 z_w3?I0c7)i_20t33fOP|Mr@*HrcUEP;-=Vbb9%!W>wIK!tIZG7c(pN`^CNB&sgiu( zbcVrkx{8kiX*~!vF-P6y#c_B z%Ey!lzEV6x9qj9U=ESt(!nAq~gdQ@>iRN&Ra-$YzEB1K5ermcT5UV}i3cCuf#uZl$7I)sE(!Zte#V>9iqA~&s%wW-@OA2fj*Z zz78Q|BTuD+iGw7^!Lv8d4Y1I(K?XUTt!VXX=MW|#J<_3a2=APOu@Qli%fdSonK@Ud zI#??cU|`35l=v3$^@s|6TiW{#Zmi!4bPd0z%@Y0DjFi+g{-_fPl@zJtPDn)(a7Ra$ z$j0b90O^Dr%@hAxG1E%-4Bf7cV`O#|zqdi)L^uLOy7X+)^p5`0MR?87WyGs#%rGQo z0T~gh+R&l*>$0H>9Nr#{L`aO}YGuj!IUd||guJX};@$PwM5tR*XK_AthjdF4==|FBt+gM-Gc?hAF@0 zTm&95Hgdnsl|6SxtN-m&hy*O(d+xPAP%G^C+aJyfTZSN9OiJuK22b^DHJx|}Q z&YF37BYo(9CNTjO(0lVvNd#W7Z27*|Sb{4oKY#&2;iUa|`ah$rN=AsffaCCp*c^a) zzGAi>TeR;BpEst=>PUe@3NBF_Dz>H&_87!8aG-7|xj}8{$1jFIctoE!#8QhPi+TPR!U;apL}W6KejQXl?$!^Sn=PI-ji7D>l*6T2k9tUSD5fLHJYy%$zP;FOqDeFd?h6iW?*2ICIW% zXJ!%202V80Q_I-#CLfn~gt-PuV0VZAIER9E2b9}xqj&GbP5Mqj&mjlw#-6Jy3B(&_ zKROG@R*)?K7z3xq0_0L#2uwY@0%%ueaxzRH$CMH!`KF)nm9NKrAM_B`j6}ovM1o}7 zZm~VQ&zbF?VW8S-sWijcH|6?2t^V)fa>biQ_8gN-UVM)G$^kiy`q-0Nn1&N9X|TF= zIuTE1%Fx9w8Aj7N1-0v5?L>ko$sk{Y1jDJmxsQI7el3=-B+i5oShU4m(+-g0seZN9 zc}k4FSCx#>C$9c<)~cMZnF`DFDKBBjvHiw1>tBhK-Gdk4B_AdkW3-#iE5d=t|1zD} z4Bu<(_q36ltPoGWD4x>h!YbU7nJSJ;^|@^mHT+UV7l;M!G@LiTW8Bxl+qW`=ZAv62 zC$h?5dPB~nO)QSgMw92%;?7t${&6VQy=Ojm?wC+mkA?P%n!d7CU%qnzGEHQ}-EoQG z-3MGAff9Y6&HJYDtjvPrG?q;+cw7@u_&FRRaTrF*dnkBKHW3;6Jm%MZg~SdQc8$Ja z6c8itVJ9`)z$s@MOZq=o4|a%4hAa`+tMKbESI(hX^j%!ALo-RBe9>nx(TqRhxBAll z{%sdsIF%8-QAb$~a#%Qg8%xAbpmxGYff-bnWFxoHuTq5PB4p5F4ZR?JDa44nfdyVI zvLfbun(7DsUDCiW{@1hFF*Ag4Q(ZrByk)~R17T?@$z2hZH_eI7BL7EJyZ<=w=OBu4 zn~sT3kx+)?tCsqg5fgVaVR2s(iq+!XX#8ouMneUotVKdA@ZiVak0w6DlDrcNXtQEpbWOjPKqPX4pNSGyg&!t zN5hmX;P{vxg+Rvw)*PXf=&t#}*fL;tUI_b9n_caTpdIzX!L8Dxl4gJ8fhWo+acT!y%$4w5O zJxWN1QG}hCTF-`T2D4>$Npng5{vTUXBdGuM%zkM{G(hf|#5ln*0BGg0+YIB_#gag# zVY*o@7Re%60(4#5ta(2ZtJ!|wBc!7oqreuF4*Qm_ybE}jY+5TTUn?W;czb|27Ih){@R5RBZipOd~6_#i_)f9+uWMbZ9Qsm>p{$s;oJKKy4 zpiy!~T`ij1M~;{VSD7=uB;`m1_}!6a0uss7hO z5^JcSKHtZCMg6fiZ3%x;5gGJtZZw;rp(4L4IA_B$rP8z2VnNgu6FCbD9d`4HB9WX0 z;Tr@wsszdleBt4{>x9m^f3|ru{0Bc<^bhqzsl4rd?*@FN0qqrXMOhfwDz3|H*N_>w z^fU0b9g23#r6GP(=Dg1CpLi;#h`>lkc?Fv==vd#9N!>3e)4_njb;>g#Qzm(UJ~k8& zcVya-Kf}gV4!%vmm$2T|47o-;)w8gol1*1njNv-z)0Z?j!N9PV>ucM{Sl+a`uoJ#U zoDm!QgOhb>A^tWS*K)gbyOTWh!e3K`k5kk#t+Xey`L5326XBHv1kN4rQ-`Q$BK12%(+qj?F#oP6{- zUd^%$a&TKnfoNu6ObfEQM*mpiX&1-O7&cZGsAo@&*m0HnIJ5O@-o_G@)!z6f3hJ(6 z|1{qY3Mx>Nz~36&*Qm7KT=mK#$Vn!cgwlr%6-2;AcBB`%kQEh05!_vri0bEaJ#(cQ zCP2>v6MQskCQvfXWyE|xr_Sp1Wcu5qJou%LKE&1A%pmc}9@I)J#EacA1i}f&DD3?aUN17^3wo1UM}!G zA<07x^|#5J>36!Bw)M2+>aR*4Fc8a^os{EUM154q(v00r9Y9`3>&gqTM9isTw^?58 zK%{*}-SIqHew}JiZU%kdq-{vRzc;a}zqqtviA%xc-D|x1h0dg>+n3e4LpDp)YM0Pq zNW=`XLbM0*2#(eN`h|Kp1P3oT>o!fAkH*4ek3}hN$a|M7;1ZNv($?S<0&{7NPZkt* zc`Xz7bp~<7F{ByV(0JOV{rdIEz@QC5g7A_G%6~^o)rdTR-Re8Cg7Pp2(a>GsK-}Ri zIAdJ!t2euoF^&qU0EEx{8+^+|Vjy4GjY{A}`8pX$3Mz&&M5(C& zcBbjMP;uoInqdxy-LUwlC^2%`IbGiVdJO%a4MA2-ZPY*hYxa*%rwcfdXCuz45xrZf zdO1|?BBXi-N8QxL%(SRVc9vHM>um-QbJF4|eeA^7b!0M#=2ik^)HNo9^3g;xcoQgn z_^yOe>`t^%Y79J-zT9gk1#T(BRZv-ffV-=8cxG^T-< zArMBfS=<>;aCXWxA9HR1+0GfYi20v5VvX*HN=?sX z+x%8^Zb$wrMke(c(Kpjzg?lgS4nscosG~&8e}8TTXy@w9r7!gF?p60j_tv<21DMk# zd7oJ+^P96j6}iLLJge+0oeMS}{?%Fa;gyzPJr0ufh&FO9djFWvzdQsfTpKyFwAU9P zl;=~rPDYlKCv2?E3h=s&E7einChWi$I(^fJUhmF%o`I)6{Ch!iM*}hE^s5qGBwsnW zghgVI*Jq#-Gct=(R&T*5a?G8=1l(SPFN9Ptd%Vss%}gMLx4cMV^7Du#iLsV1S*zhs z#CP5iy&udj={`Cje%@#fM)Q8>6~B2k!OdPB9zPp^!yBEZ{W{RW=fh`k^QNW54A*P_1FdxyWHzF z2vKyi4*-@PmwlVM!(hQAl2E@9%Xod6xpKdjFRc7xF=B`3E)KvE5)BQZuHc&By!^AG zg+gknp7~K@x+JDCbqSEK)R`^52#3P0RYP^_fm_q`$O*TZ+SMJ@`D)&x5Fh9S2P%o; z@PNX2iWJ<6q7}6@#InFEUHuG>{A0&boV)W&8_E+w@uNvP2$$ml#Yznr>AUI zcGj&qBOIP?38*REDrA6x&ZLf!l~bRSr&yDdl#XS3IehTlS&>AF6ub66+^2OVs-R{1 zWRK_-*~SW#FZm>vg*0tczv_=wML8^jOKbF>UiK30bkRO$*ot&47tfTTu6@fCk>Vr0 zygo5K%x!jUw$9cYq}B<(OCRpJO|wgo^VQU2XQd;hDd1`cdYl42lEi0#=W z_8o=Fshi5_)vowBwB7KBK8H~`eeROLxqiZQ^JB)!mDJ{2BoX3ue9QCg&Urq91(3v%g~aeMOX_@)e2yTC;CN;@{D^1dZD>h3apw(#XOOlA{d?(&w=4 zjzVbP@Ba;B?igL->x?j0@4vrZw+UvErgr$ybM_0NbUxeUcz(se9lNd3?#;V?>+~6s zZzr|MCVQ$&p0V%D-i<)jd&Ej(qK zGZo9i0IPJLo4cx8(_P%bd%dRrR_+fSKrdn+nRB>$gWVK~JQz~Qo5#}{?`H4(-7+)! zOpEu9xgYDr4_o47$dIbKKa-8f`JR1(c1t7y*b5pItjd^Qi}Ebu#26p$e#B29Q+vO&sT36jiQ(0wshs zuKJpHb{0p3klu)pAt*r^@|*wnk0GevAjUK}YI#3edtcFquyAP-g>3$$qf^SIeNJCx zWG1ysSo*Ar={Vf1N$knsvt-*iRp3CggYiL15VMLF0P`^}jQ&sB#725As(%iZ(P_Fb zXFWlCh1sdd9kB&l665rnhnmz)dBqP#$31N{8fjk%jy44+aD9OPK8%h0^S!b5Z>XT8 zq`zMx%McnNcndQJh6D$`F?Hq{F7d&z8Ve|$bY3xVlS*KPxZc4od?`n%tBtSLbSH6W z6XMNmHA_U^#?_fjXX?b|c{GYxGVrWh*7y#-2u^x+=ZjX#l=pdyx^d0&8jf|te)*#u zJWKSpww=o40d2^4zblu~B+9s@`-hOIp#`do&d#+JEcU4x|Jg@SvLE7j8BxcX!xV4e zAEy8;d|RPDjG_(rEDAqhWlyPl>$o?-ves~$O+S;bh0^P4aZmI(Wc99Oi~RRT=O$w@ z<(oaEhRe&HambEYKhZpwM~WE`vY5QGeb<>gUbQ0{3_Brz2sb>@vpa0| z?S=B~qmxlj(kq5?4}}*AbWJuA(Q=7c`1C^DUy8f)n%#-wlga0iuQ6vu0&{{njEe_- z)aE*OpKvj9^4NgX(@M~Z@8>oo^Ki{3cr|vLra+;92Mx|uDA9oTpU!%70{MpoN~DCZ z%ZP!)Fqbm;_{}y-W^cxy{}-WU2D>_--&@0sKN0OjN#JP%G!(u2qPQM%7NjA#eu7W9 z&+wO@pd#f~(EWbQBruUdYKiedgiawd9@kBEzvZ@3Ae%4;QT3}3bTTnZ?xawxuxuN< z*SHUz1S^-ULnVKGn{JkV1?31rxZ{R@$J$Ahm%E?@l)Rp{XD@qrwZagyzr@^8Gt;RQ z=&7@$f?}omEwk37jVkzHz+oP?AS1kYyH9*CqN;~`4Y)nav7d|jlo#w^d+lvd-~}ea z%g(6ypM<##Jj6TqHR5x_P6|Kq>WRTZnd1b#&ale&G`xAB$&$r4-Cg9aQ&r?ie}32VR$ zgK_sIku1l79k;h>*se|jQwCqb^kTx^S!VU)iIE#kv1oEYfhSX3N;PzHw=mw|)3_EC zso+~M!b?Q*WrBNDRpN!DvwT}#P=u@LM@#}o9yu|&eq4fDoFn7(&s}vqb^=@R3ztV! z>LR}fIsxrhY!B#8yHy?YeyVS`m2|If>M6C^;~7HzIG4z>s1;dhJsmFfl|eU{Ezm5bPWxEsaZeQ&rwbaVgewe{ZJe&Xr= zMKOo<2SWtCELA>?(K3QQ83t8}CTA>c5vlO~qt2X``crV=U zTzKFizU{Kt+rPih2KZZ9Wwi%Rk;I@0i1B%UfaNdfCnnxKybQ`*VS{j$oH6}Fry(=F zY0FXM*gn_UaDTCeW3xMVC_}x=`80gYmJieuRI3=u{i)!hxFEbdas6E_&sbIK)pQU; z6|3d9URI^OFND?bTh93KH#2HMs=qeu;536|^~!o`k58-;Q#(IOGR`%Wx3(p(uKym4 z*ZGK6!kYEcGFXX1jAyQ~l6{VHFRm*ChhJpQFF5%;o-k7ahNROI1Y zsXyA3lX8kDy`w)nubG>9%E~jUiXho-t}7g-ki`v5@u3x=I=jWCu4Y%EnDAf%?mcDy z)zEbtVaq+*RC^DjZcg^j3+Q;xUSK(AewzFM*0ibfkyU5BEEJ19!yjxWC#QebelmW3 z^{;IGpq{aInK!=2Q}Vu9A^Sd#wXN1kkjxLSf-_E+D9DVMYb{Uh6g)?({)%3&gdlQAu_#A z!I902-0=41vedczMdprV&dx8?S{~xa^!Fr+tKTlEYf;mgtPg7WJcCL&duh73fvFZ- zZ?)(WH0l8Uq2Ksy*Tr8jcGc)KQ~go;=A2hk@7J%thHmsQXgY7wk?ty``Pzea!kT$2 zYN!W+DRTtV$%C~7m$DbD=;7l6uyTTIAc=#9Hz*aNkwwr$;C=HG|NADJ)hXj)LZll~ zz3p_PJX^*0vFpUHOml zk9YPt1bP6*0L(Llsq<+0muQ&i=rTh!$5@Av>o0AD(*UW!SNy}7YzMC_6d+l1hQ;@9 zqQ}CUATZ*AzxN1od%(s&if;Sk;{6d~m1lV167=jIb z&KWvhDkH`1@W7wrRRs@u4^<${g?x|v!=l)ry34L1$iq8mt;nghtFqQ$^CA+_9pTG| z`f@}MQiBMD^c$xHDkUZ4_0G9{yu4vjU-$UEKWJ2=Ady4W%caTnq0G`hD)maIREi2gS0nL=rcrm!6DeXWso;*)NVzm42bY}Dro?$=@re9UZXA*g zw2*5Zd~qTUjux>J??2n3kI0skp@0uzT+!-Pt_)42V-i0|l~%33d$39zg>M|al6>7N z52)ag9z3j%+bv~WIiBl5(Wf373mR^chgcQc5cv>fiXYE@TMvdI|QIo$J z_)<7`fg>20Q%)aFMGa<~xWM(iNu2*x?}xx$pYQ_*^9MXAKWtUEqW>z-@-qnbqC$ZqpaD3}>GEdbRi`-`-yEKw3sTolM|*<T!uT)b}#rU1acPvJO>B z$$rfDk|z5TSZnMj%7rk|W_Yj#BDSx;V?ZVQw;cGGk*~-5Hku=@a`wk`C=XzZgCz0b z46(&R(E^566Ap*U#S75km6Sre{JI7`tHfaXJcXt`%_ulRke$~ttCS&RgvNL7aKcYx zRgiH^iYhRosVDWuel0~us(O{Z?b@xGt|4QC3Uz~u64OLZQeUew$%IY?nHf2`&8YYm ziN?37!{N1&7d_^}{U2EWG+G?C<*8HLTQ_4sWCg2RN}lW7HVoq?3kH%c{(il6vfC@ z2ZuRdd=3gv{R%lQ3-Y+@o`7z(!? zH5(oh!FD)c*_pAe_+4zhdb4Ios1YjD&r_TvJib0LaB*;$2wM?M28eLul4B7}O1iba z;jeK*mScx?!9a(M1=lDS+}MWGV=Cz=6U#p^7h`_d=PWQL3%H;79MhNYnLY-->JIGW0!?$n%n0qy?gOhVAK}4jMg(il@Ud*B6xZn>KO<9 zZV#0WNshaC!RwB{Jb*mz`pl#K%fA7OM5s~JdVu#Rv3@eolSa9>{5%|#C*~NqlObV5 z_{+HWmntP6KRfGUB%<(;>N}ZMTC>jmTXwxSgykjVma?)7#>)G&yrc5Ic&KlO4^ zd|x{~B0_UZ({faPnchYETd`Wj2Dt4HiX8`g9MO787sg)*9Puk2$8O?!MBLbqe5j}5LsC|p4%eG@e}vR2$31*BL#fawExqJ;IF3vZV`YHl1?h96ClcOUd`uM)SOGMm0RV9Ck zgOx8vuUbmpQiyQ1i#ZBMdmk55Bm~i3d2(Z_Zp)T^1#n2 z0bJs33Q2Nc7ZTpT1~4GTE@r$uprrv78J6!fdG2cVAn_ty!m5e12EDM`RAC?u^wsn) ziUNVHgTG2rqf^e8xAt9|D1lZ_R9{!9P}pO^H5YM5r-ObP$O{odb?uSY9!jni+h+A$ z@9yU7RvG^0M8~mPqjNJ~(mXlm11lXci8m6_F04_pG%{N>zXuw7uiJ1$8r!$1Z=pbG zLBkOfm2!-$v|qwTs9n4y_0RsR`mkz)Q;f7s`$j2q1aVyzlmz*O91B0vLM=p6`F+{R za~fKWJ=(-@-&w1D#dPYuqDV!+H(_c^+#J=O%^#oG4$O9Gq}tFt7(p+T4pX5Gz0^7* zbpil#X|FC^tg_`?;>DIdrJ6To1>Mtq!>RTKgK7b`5$<0V>VXRSYKVJUrnI-MUW#*- z7eo5Pc#6x!njG~T6u3R=tW9Wb>z;8Q!Yes@`{`0i_7)Mw|49*?&t~Y zvR#on#hLkkUH~x^H0lA~xwWn1ZW6Fj5a>`U@Ik$DeyNIZwistpjKM0}1)MEE#)3?AxEvI%c*$gj-HicL4b3c9@kHRo~Urr${!F!$35T|@s` zU6trup;ZCn_XxN`1sgo9I&WR~N8NlCXO`=vKck1a2J?R(!$1|ODZ(bwQl&$-M$Y>| z0{WuE;9?)QlIvFk->RML$gw-hwH{~A@BI}OO1V1%7w>Nb+)QOe08-}&;tUtVfeQ)G zUv1nle;Cge;>YoeXt-J1oH~glClw-Bf_)2*D6vZ%i8lCDA-JY#?tJ>}D1|qZ3&}S6pjTax$+(->QY50n z_vvL`f>_J#y3|9Km(Xjrsy2fP<@lvuQsUR24*tIDy;N_;G!251kA9}@XcrQ~$dUpS z1cHKP@YWio`3uSK-HgugTsCw?Jl8RT+b>W$Pj^txvb)RUCCK3tsR5YSza*YLU9kh< z62BbkkIwyuuPT4jG+kfM+%#`GW}13|^1BNmeUv{b^#eOnf_I$_U{&rjjWT`x=R9B4 zR-Y`d$StnOp(qjyBsfCn0jJc%p4(*hdOcZjIuy_DO`pE&}k{+uCF;p_Veh@zu}beA{9r-e_`h+5{mCU6^Tv`HZjy9Y=i6MuQEGF^ zS-q^!a~qNVS(nnRBGIzL`z0}Qo~fbBUWX`(wPb1mwQM}`D3gAFI*N792=M~YwW##N zLek)mxksgjol5k3+5H1@-ix(5V=NF-UM6q9h@#OCF*Pqs<*8kO0T`9q720e+H0TGp zSGQzdms<6i360E?Rc`23RVw6d(=a)*^xabgrhqlVOPB6jPb2E3Dfdy zHVKZq!6AkqUC+b z-qGXBWN>3>Z~}BE1#I_($+lt+{cAy?%v@#6Ogo|(E4cDG+vpu?*Qg@(J3 zse7_&)XR7H^CWh10Be0b2d~T z;*hyIY34u?$d-rN3Jvb@HYaEYij19%vpO7%$o4$9U&@(fe12gwhEhbUSBy`M5u1Wy zT{}Cz>?&!0H&(#HK*{q_y2|-*_J>R_NaPFEYG@nSahMxaOk-$aJCiS*xh0C|0q$WficUc$E*%sCk{OXl0& z-OBWt>v#vkWJ$SkHqJ6o^@1zy0rVZ>65c$B|B&3zKHakg4xgnPz1>o8VOb~~tWAaE zlw-RgmTW^NeueR*a#L7BK?)ctmlY9T4yd? zw-v7#8P;+aWu5EzK=YPe^77!wxc2K-m_^!qS$g~Kh4C`9kLuhJdXmDIXU&cfOF|gk z=EyIuL=>;v%8aaW9jmxrq9TIFD3M06Rl{pKw!yU9O9Ci0eyZ&APkd3{QM~jjq^ZV% zQ+LQ+GppCZ7!5FUUFU^3N!l|n>ao1U;9IfEkUe2lFVWcx>X6m2tsNfH0ahk`wWaF_ z*;y{-^{ET8ejd4>GN}VyA$qh!9p*7b@;C`d1K7dB3fX=?rDir<#tu3>q?=v;I!*Rh zB^7Y9O;{ZsTy@gT2*oq3|Ff14*|ajDKf@M4Uu$#nL=M@UKk(jE$HRGwBSQ=B)y26W zu$bZ5eawSaf)e2VCWi#}LuxURe%hG@O2>ISem%uFzcW?a$8-w4sRfc{c?y z%DPY$^81?1KfeY-_vJ9a*TnX~4PuGWx+pJbu*SI!-S?+^1`=L=ffucF^y0LB*q%O7 zpV?1_$9NFgHU{|-zuJ7QIP>z}G-0<;+i!NR zO-`(9x@6~SuxRz*^U_p&8&nf;o9b2wk zIFeoRFOp6d&PXvEY2pn_x$*oc)bMEKA5ZM?wN>_G;0I%N0vRJNe|hFbipk#OryG?f zb6EVkfogEnK!iy%nS25PVNL#&i6B-Or|AGOrtM0pix1DPMliS40D0sB+*Z~&HvZzo z0F*ueLmPK)zCTFPT-wYWROHYgA;Mqar7rMw(~1jFnZyia+afr~UxV+FUzbbzi=>MP zLuznZ^|P_YIO8EdKX_@T=%x%}lR!LiF1@AJ=RpFv^Y%D&duJ9N2@AFD)@%s`Z)1@zNeogbOjomB*!+qt!btz{l;m2Mxtnjm5SiXK`M zF14gR=D@LQw4eL&WOI~uEYb^WBo%f_i+eN?H=X{gOD)Asc`rb})^JS6+!NnW6c zaBz)-0huk^njeLgaCW~N6;ioe1E=X13jUDw8kc*UkX5z!73hTq7inInTCNb=ji{z! zZ~Z~FVD(bhJ(5q<$Ov@GH6!+_VS~W1c(@A1{V@*tW*WaIiSa!6vOk{<`T=4XJ{b&{|fMhZ7$|Zo7sKz+BO(OTg}% zmn|5w%+F+VFN2y`0T^K?d8f7*iz?w)Mw76YM*WH3iH&@28!n&)>~cSsMiL&ElAym+|$Aeq)~Iqh1@b-AVa zVIK0e<=uHEAWL}E=`dE)*qjI9kGU!@lEz?zs7gb{rNnEPd;3lk12yWc#A%20SJ&x? z)LHY@5eA*^T&cODu)5@Nr^JKTcPo7vu^ z3z@?2=Ii#~@<1r+p_ggr+bMpC6Wz$kj=3&M{CJxx`v>Vg*ilmVwou>fK2CHJfDL1B zdyShOsGhKfCk!J%R`p}AE^+4pe+fJZ}zT6VoL^`DA?B8;t zVYF&Y_@?V~1OUU&b4Sdu6raANpCESKp6yt$>Q>ERFGz#HR9$Bwn8%bxJ1k{SewYy| z?n<%t1*wrKm6qvaT-4gqG6t_zi?C+W-$`Qa^E#kverYS6h=aci;+De2Kz$XH`_1ke ziNB>GCGY{MGmh$Hh-d3tcrOEr?FRFer+nAnpDv<*SCKbZV~XtkTsY4N;PgK@DekiJ zesS|r-}5NU_d7B%d)J8_=JJjtH8C*>A{TDyb!sz@9sa6!xpFjgEseG6O5KuT&zIQ_ zjolMB<|G})PU!eT6a5WJL&eA8FC>TZ*I#gZ#5^cfnN`v|6FTXsm0cn|J52`P0XZPn zg+NQp$fa;~TUTQ*W7-|kzFglSG;H@(1HF$apW1=nG;XjN=E!22QXsOTC4Uf+@`-vX z=!Rf=|14p9kY4BhQRZpFHS=oF*yEyk>U-ew_fwQ7-B97l<@V*`uG6IV^Rb=#iI>i0 z!Y}lMn0%xAu6vuC0;I-_?h6Ur8vSxFbH_Qo#@}YwQFddMyxHPg+G*F0PHdD^ZpDbm zef{w|yr3445Ti^D8ceKooe*1S2DFp=`|Tk@{y9@KWV>YIb{aD1QUC6{z&mCLqn!@o zIxHEj)!RCir2E`K^Nfn%yHc?1=#pUikEbbXF?V-h*e*FaxybWzX^SLFBtD=N{y#=r zOQ(S>0$+h&7<5+D*%|x%{4xAD89mEy{TE->nM;0v$92vC7bVvaR-dd*#q=n{n8M9D z#G6PZ662wk%jI!$>$I8`;nt2K{UC4V%rhjB?#m?*G>!al5i~%`k+5{D1JkOY1|Oz5 zAYh3IuUup0?av_I>N?ZGjjz-kDj>|eMIpsUe_R=#e2(38VF$-?1QWtGe!ZH%0g_HQ zqYxi8sXkl%c!6Y5k!224+RL?`P<&1ss#xZyrxlXt?SmBoO#r~L9#uA}>ryi#HyqpX zj5@P2BQFazns~z%($0$qDbp;~cS;Vy>jXlq0V$b)=EZHihvo%_>ycMOyxN?Q{7>0= z(S{=h)MSB&3-j7!zk(?Itbur11geELL`3Re2gDfM$wb z64}%8B`lVyLp!lnC$QU^8u89qq@F!BHl&5E35?Ribiqc6*Ha1>h15&+-E~et*vBuk z9$`Xmbz2;~!^@S}2~S47L}n)WjRq(A4MVTRV#a;}AFVka(;O0N!T-Wi+Y8Z3^JJyz z%+MJHk?048qFn?r5jo_Lzp=GopRQ26IZCb^GDEPz-H1`t1FU4rw^TXaSy&@a+Pro6 z-j|?q3(N$L_4_ZvN`s+1n&|W5aS8QATR{VbG|1(0LUs1DCdT8-Q+JsoTzwkniABL!w2)(n3vX9Ff4PpsffOuD*)E z->Re$O`#Gjg>O~ay|r&h#$C=em0bH42vcFaKmC;+(ed)}>`8GWj059Y5y`Sb8TTHw z!5uCS{hKNWi~xF0oeI_vow!Aj>@aWKm!JJzk)nqid}-f@uSXaQ&@`qjb`u=Om}1Lr zpXvp(S)B>;?U>xBCi)b+w6}y&3Q^aE8Sur9@|&^?$V}s@vS`#Ugw?jVzW0(4i-d4j zBik$a{-ApT>Q-WXu0Se%R@r#lESSXszRS(Ie}pB2;Zavl*Y+Mb#~LuiB04$*elmO4 zOw6AO!1?M0T-cs6RDOCpvgm_XGx^kcdoWk+$w5kgC@oAcolO}ykg9&&w>{a>l1xGe zqh0)PxfqVRT8*(}3>9V;vP1=^`6K+jTz|vb<+hwm^OX38Ze36JXe#%%Qh$6f0J5$$ z#A-jbyn>DTLIlhBu-34D$OWmm%9jMOay{D4J&3|%_sFuj!=5`9CX$S)SGsk~O^vQ- zRG59CzSnT!4=u4?B2K7gF#pw^8KJm*uRp=E;F>8Zdj=kzE%||!Q_Syh==3sH0cvC<-UnC$+hG7 zQX{OsJFWRxD;KgnGDwO@4&VrLzDAD7UM07{&GyIx!DgKVzP*2sV#o?w-Q7 zx38_#E}j@KVbVOIS;qtO>p(=7E|ogO`Z;92*BXyDjNt#?Qu+ z3kn#c8Yf8Vn;9L)x!x-Xi$ir^&5TO42?cKW(hEKiLdkxI zI75DZ$^ABp$ z12n#=Tx@a(hJ_0vO(#LVo?aWlIZtW6)pv;cH^3~GJxl%OTk0zuGBY(A#!JBkKg@T} zfvWCeayG)WCJkE}Rd*Ql%D2fDzFa0dtCV!IU`1ms`u&LB1%W4f*$qyeZoHh}g^F^o zCAY?xgURn?jyXJcFX_!49wO^~!xBra*)!jCBr$^Nw@lK+^EF^q30L8fCSteSKW( zX0`s3TTxPgca#a(5Gn|%RbxY@LiuwTJE?2479P31$2jO6PtIcIhn41?(uP4Gt^vj>`vI<&9geEMrl~)}j4L z%3GVZ;dI>coxbDp(sTnpSG%>U>2c$}X-!|D|N z9nH36TM^rWRFb;JRfoNr>V?2G&l)r}ZMJF*Sh7+42`7uK%_uno*{^Ng9gMH90s|Bi z+=Z?3|99`~Oa@})GfLb4xzrgnEm=AVru;KcshbI7o5Ub#t>&*ZArUAQoG*x4M1VIyi-^9D3kJB=@0b&vSvAJdWF4AV%Gd%n7dKi(T?%SjWgq5S zsRsy0AJE9UgwlB~dqa* z+9i|zudYO@0gtgAWyvU~pCLcvbufMhD+{W&1lTfF7b zc~Ugkp|FVb&SQZ)J4V+_ji*PKDfN3XLlLHW^a+*ez^`K7*GoqE=PKS7f=6y2jeN3 zEz&3&0*I`d70AzYf63_&T$##E;l8f(PK7I~V+3X%yxU6c##&3PFjq6$*PqF}xfcm{ z;7YCS`OJfUvdXOAn5(PkV0;kz6LwAZosuTBuFe1<@UyUz@22*1Z*7}MW;;fZGImcG8U=kdj(~((OblndvHFLd2=)>-zGNMg04+rcO`Ot6x7kR+h&wHF@l2M{^+L z$CsIIsn*(ZVZUECf&21&W-LVboh17S@TuwqisB&HT25ZPDGamwVj=mD7!Y7rSY&XA z{YSbu5vo;v1vV*91=xrG+mt$Sn;TO-htS>Ww*Lh*zqd063+jwC@GKvs0crf!Zk`+0 zBEpU1PuOo*ml2+=tPpBh8R~}y?r_~D#2FUc0)gYimf8g`b-aLzFecga-;e0HlDbqY zACb?_8+7iYB{)A;wy`w<$H&Gm;_SP|WU!?7%=c5b><8E++3ipyVU$VBDlAfu{6wc|ZZ>P;whtjopFs`p;F;6`cN1)8o zE_^_)iN4jwlA<{jkVrM^L<16>T(1>E43he!r{sR~_0`!h5{bVk9~XO{{(maP#4gKJ3Q#v<8T zAW*EMKEqAG!3^(j_oFp+ZUnprIGguR^<+zMu5vygGsr_Oz1*xK))Ml(2l9Sc6jBx3 zdsY~bHxhPy=Y=TzBk{lg4+`Hco4kAW}`hNMY9Ks@(P_Trx@N4x;f zX8I)q$76u2Rc7~&af2cpqzv=fJ1``4gqY81mC9}EWHI_!0}PpE9fxQhX59T!8<|=~ zuR0N%n2x6`J2}VfX9Pg-Go1_HnJ!PRuh7@(bta{NRn|TtxV1cOgonA5TddW1{8_`U zt`tVV3#_*FV&nXx(&X+lY_6CwxJ2eo&N_~nEL)p*@H(q_(t^KQk=#!n{(E?s@lt|r zS%=I{_xY1d*evJs74C-neO!rswYac%#TieWn;81vR#^Y8u~nN2imZXQP!Pj>hh^e3 zC=b{fGW&y3l^g#Fv&N~XBV$?jo0I_y6JRJXreRB5Y+ZuxB(*c#OkrS&$CEA#{t6*s z&Ge{)pcc|;i9!9JklQ9W(}M($W^C;RbmR?FDLaiMa^7DXNpKfQ1EdWZ8)iV&5bN^@t4YEQXy# zBbVG~%F`Qv1hQ9m-S~#-E6_IDFa#^-hamB5Jr>N)r6{T}btrGN;IvO|!z9T<+;!RX z!2wWUf2h9@G@_6Cg_EzBHrs(Lljc<$Rdd+@uve_ z@5QSj2dKX}W$t;1r3QsNO>hrk);I}lu$XRFZN)QXq zs#sCWbuLYOV7JC2YaX7_iv@o+CvVJ<5W+H*AOwuaOP?zbN|fl;)sAJEC-f3nuS-~h zxGfAC;zAZ`T@iS*^947YXjiOW;NIT!qMr?^m|I4{$A*&VKi(S|U$ezN^SeW|!I z09aufSv>`$?6Z!)=YN6>g`_Uc3^kJ_4DGwFV>Xa!q-lE(=+dcah1CN3A12PkNhJFdWP3QHL?*$A+jt`TFLarylYVjcE$KE# z77IPX68kKRb%0HutGUtLn2b*&p$wdBUGN8p{Y*6st2x(VQjN^ct7u?{n7?+98> zdjDo&B7vsI0xbRtZLQ|POU4uD^5J0_U2={C<;`?vW4sq{g2$8|#yFJZdvRmqAZx~3 zZIhz83G%;3w3E}*XrMV;fN-6)Ac5R0m)XyC`|BwLbvh(V`e)ee88WEgG&tGM;;hv< z?wq%S>FWhU+2#KpWCz3nTQ@Bk4xIly!LQ*4!fVI&!RCu`&+;2JhMe3?f{gX-nT$a& zaf2-*3u3HU=Gl9R`i(qU<7yVwLbiE2bQY#}Jh zxkbd&N0mg?y+P8|N ze)Vw62~k9Fwzk4GAJkV^`m}nq_b5<8#ofDcQb9UZoRls73EU;+V%R&SqSGpZuFGOZ z!DXW?gwsOxxsz~Lq3MG*KHSkYV)JE5V(ALv$y{`((T$X61znA*L z*Lev8p9*!B?$K^~o=6AO)V`gOMayQ@gkd}J7w0d~<6EZt!cTMp$|z0pdn?Lm?e|3w zy@{TfM({F7h(iO(RYbSV5^MyGMmV&eabQf~HXd^Y-{fwWHu!+;mYpc+8(-A5A1v+m zodemYLi$oQ_HdChALmZ=yy#{w26@(Y{quio-m6HzSP=Lg-ZHZ>+v6i5Mw`QEaY_rk z<-s`F2}SR;tMAHAPzOh&r<1_6V4DaMjAO!-S0o-4p@$6-FNP=iJg|#of(P?O=IYUZ z!oNoiopQ73Au6pf1I37PJUusWa*gc{!^v+R{}{oa6c?A3pb06=o_j&LBIcB>n= zWc%osA^sQQ04^}!>UPIkt%-86ANTp27~5Q+_4q}4)Ib@3vi;t?budRXXk5JW+W5kB zQjvBE0e%0R9w3|088ZU!XG?AjqsDqdkR}5mLLM+Qe&a~L{`64^FxcoJI-CD-ny$4f z7}vctQo!#cI@@T;ayM?v)zmhcJvrpo-Sng1ex7h<$_Q7^4?}XdoQ!vQxswamcc0dl zUU$l~c+->u`vpGvczVx0FEw~f=m+0kvg-5Ck>_GoRd3+Kw^n1v*D|hMK&ScYrZsvl zwuOaae>;%`z|jc$dici!wIU2!rbHM{MVo!Gk(I&YLHEfLl@*bT|2UfZG<5^^!&60$ z{l;N`MSW+jlhXAubnpLI{+$B}LPFtJpuB%i_GCDBG?Q?Zpz8Gx*qPOO&oGbPBWr>( zRZJ?#E_(hRUOk`tWOk$~J~WMiLIh>4xIc^+(EFh>rA?Eb$8AZ-iZufVNGOsthsmra zJq5D%r%IFk7o@ta)nJp7{C3$u)(L$*`UyL0wh3WaqA$<0X;BSa92k1%WX3ufB0ccd zs+lbM{{1uuIV@1whJt?7?U(GC#a-^n@2O){EKv=Med*g?QFYP)DrAmnnCM0VXJ_^t z85e6~1I?}&Y+sEPv}QU&XJdtrg}F~29E{^^djz~VRH$CyN1c_UfV+_XZbx4K`q|dwg1&WK>8Hx8dBik- z>{MVcPCv=Kobt_LGU*f644bJ|up#UeICdgcBnS%*kOUjEk1rv8;SoKLjCM5+<=!FprzyfGPUg{ofnN#3JWc@w2)h$IMtPh{ zZ8Aya8&6CP>`EXE^?D8K&iRVB457I4N$!p%to#0*E0*D*{I~mCMpUT-s z;`Q$f?B)zYtIn3de#sf>DTgkw=3HV`fs+~9NaY!kboU6;MP?n;(7Zd+frz{*ic@V2 zA=q*P^ka*;y$i6&`gIxR_kuz>KY(?Y(u?&^V3DC2!AG4Cg(Y@iWFg!I;rxx{_!q)_ z?x{7t{bbMp)jkD22s#~Ly;8)SDH{JoiWGfY$aDUa!ZK{bPAy8cWW&AGyf6~2pxR}L z8X%XGH)GsOBgEs(K`jx~$MJa$fwPhAuIob2c10f_Sn5G8KY6R(ZwEQx>=bE2WfT%v z1_*8C0-(?H8kVn9-fQo_W?Ui^(LJ?KoNi8HuaeRD^*H2@i76;FG+zq>7OL4F`3t{) zgwqY2d0pu2&;0oje!xXB55ebp#OIJ#xW2JDT4d}!8>biHDcX<%ghisLp|yRE;yB-r z1ddh5<^}9ntIu!0_+wvcTP{Sp>O*&cgmb;bp^F#OrJ7sIorqt&Bs4o(4>$>ec&?bh z{Y^S7FET(O080Y1(P6_n3Y4ix7o%}Hq)U>5cBeQ3rE4s)WR1I7-k#Dt)cde$PR%sJ z^eCsS8KrlELIe`EddW*}90hbQo%Li)-+Q6K=`ju7X`MvpQ}oFJc-R+tb=xF26j`1l zRKik4`QG7d(`soC%A_0a=t<5KW29BC{M?eLLr&)`q!$t=-N*pl{m-zM-B0Ps~^5D7m`Et zbPM&E(@Vg=|C5aeJSki!6|}67|7uR+ESXF%t|KaTOoR~|!jX&VeU>Qy-wWGkYumTy z=9a-Y0Kqt42sSvfP8Lfd0LF!L%gJVL((@_4LiNVU@KqD^2}cB~M$t&_qJPO@yL>=N zCDCq88(N{1`$N`G(+Tz52vsxi2{;6Z*u}Qm?fx-Ta6}(ja&L3qJ`K>Apb>Fg?rQa? zvh2Cybanf{)}HB2Jz;L3&qDJXedIi0(wVBQD+Z}yqa_3qTjFx=%#a}9nQ)UGy zUJb_4F4AT$np|M8dm*!cRr*7L+=J$YZ>i%JDL8f-|J+kbgC0|H#lCVU3rHgXtw<2g zfdFQW-C~D{_&oztL+WZA-|H#zspa(;Qa zLd?asdX_}5PkUu=5zUC2cEE-@3imfT4BwJfh8K`uR~o?h!e0Dx)~ic}8E-!_9by2Q zmOfJu^Y0PXs43C2FOgpCSw4AKSsSTrSH`#oC=z)7j2s_*g+2`^(ZJ+&nKtIX@1Kf(^2@d(-p* zvON~Ar>t;Yt9Ic_1MO*+?fB(6nS=C@{_NrJm*c&EzV5neVjHui`Kg>{Ke5xw3VZLd zO#oL`*e#`uFwXfR>_RYG3m3WoGLZ>iO#ULY|7Z5*8RkX!3bL#1J&R(}SO!7zs;4_( zp@+>@GkdH9Qq+6i^V;5J-xHod{q=GG1+`5QHSpw6TsRgCC92>YzW-keky&rNl_n|w z3)o$$m8?`Sdc|>gWb;gw0Bvb87h29*BU8wxhS6SdqL5DbuM^~C){kK|rYR$OHsy^~ z2ZI-Ac|V?(31mos~y!SGvIZ;xV{<^@igwGr!hr+f=xF->wnkl)4HV$#Up z<;MlOxS;D4-)^IGve~yw-LO%^5msRsAuyDbxMTmA zxPzeyA_P0~#EK9qOHq_~X@>?vw|iCiX5^C*#E;zFR-d_nhepmp!%GUI9Dweoc+c`5{HytlAlSr>OPm&Y zq`775yXq_|y|XUb|53jw-dK;nse4}8$0l8s0$0{U=M}+N>`fVwst)h`<{sermiLh1TENdYfkBDiW;!>m4 zg7?i(ALc!&2Ie8dG=9;NkNF{=g|W}OdVDq7Gf7+lTZH6u3-U{$JX@;tbFZ|8F$-$u z#@0OqKTM1Gwd0t=kRbieiwGVABIda;MygIMd1NU z4aD+`V4un6H-gFBQUSEbUA{+0!=?<{dMBp$^B%R3h=1Z^0RJ^phwMtGh5D)|*HXSH zg|(!!Tn#?1&aF=RwsWFdM{{0pz`y$9=*|3lMzM)IKF^&#`gS48#naSK;hGR$=3Fw( zmt;a8?laAs0F7Twoif5{Nz(A2wobf$mIbTp{gj1FWhr6zU`S!NXJX%c_IPy=GIExiE%okKJrJtpg9Av|S4+RB?DKlJ$^!#P#aB%WjmD#ouY9P!BHE=b<7VYNW5L}C`j>CSo!c)UC*OaC zMZ`#oZiYbxKlIzWFSML`G0Kg4Q2mOaU#r7gRf_N5*5gVXOpJBxx~O`Je{$GAv17-- zX~Vp5u|Ud*?_G7BRtc*dmYZyk3?LwM2LX%w6)YNn}fNHB; zAo7t=5^Jk3h!JOXWIUCD@U_qFS$*P(NBwJ_p$_9z2BUs_>D_erwmLe2%xTW#ntHre zzbP}4La+|YOpm`WF)3+kEN3jNMXJ+Ji9MV6VR}~|WWv~gcQtwMLDJUBzzP5PFiT@!{^YFn3v^%Cq~Iupu|r|sBL5JFJj zmZHGFJKNLlsOyVCdHmrm?f0`xcbI?TFut&Vo&DktOJP;D5fxp=9UsifFkHtSr4PFg@S>9sYl>|MouQ8prF89tQs|)Tbm^C47A(# zK{q!yciV(BUAnlNnP`*K`Mv-9waXp&6jUz1v09eIWTFcDJ!H4Op0lHqe<^S2wxzW@ z9-WkrLr^fA8G!~#lY?e{DWp-wX%B8UezQx8W__jA`LZOZda~2EB@nY|HT2a4;s8@-2?C zi0)i@YVK5(yKefOG7#rcE_-TFd!^7bMI+~`XYGII2iyXxTnAwUta$^f!msaPbZz>Y zc!S($He_^v?6;p&j$W&1oOx;=h%Wj+fj0s_o&`zsK!au_ z2G6uVJ(?G=I`86XtrZ7(&I8xR)SEY^&pw~v6^l|isU)zBgO#0N={bL`K-0YULRkl? z6RBJyag30BGEuTKRY5+4U-N${_&9k|@Bb1nNu!VYF$rEA>+sT7ZsTZRk1RH0WKPy1 zH%^WaDrG_^%k?WY9?H06KGl?2px)U>nlgf#I@RX|gZIKlz@j{ts=&G^8;Ik%{W>!D z_W=P%AyX?bWmdIq1@0f%rh*hqA?+=La>;zTdh?{%JG*NqF0E*V)LnCP6-on7o?ojLG+Ej-yk`G_;hA241 z-c6=B!a?9)jX@3=4fvy5;qKt!ih3l{89H6z6GD@_(namOUL!r{t=Nl@qTN10oPG-> z(P0=mb#3r)8f>}VYLK5aN^}`_YT-IAoH&++h~Bdg=OiK;1_r^&{?gC;4+*-(dl9TS ztMZI^IGNQ{Q!vS6THI7dCU+LwHdKIYuiu)!j<`v2MKzBxyLIl)Y%9;tErb2WpZt+LIwjeY9oA&=uK3 zJ0RO|JrFx^iiTH>X2M5I>x5(CX4Y3U?d37f(Z9R*Q)!i!HzrQ}+qTY+%&L~mo==8e ztopy?^?%T|_~jxhEOGN%G`r*acLzEEv%iVQ%${mZo@Am%dScut2j$7Xw5uE}O$w*Z zraRbkJ*;DKAcX~i;#50%M!vt?pQr2iP<(i6q(TaDDXzzx;8vfq6shq*>=3XDk3kOi zf4QGf%BAYs?N_O!&-)*mzB(%E@A;c82MkIm$TP`tRlkpz)zQAZ4FP^`Q*lW{@FY#dBC*@y8zwB5Ho=;j3|j>L?$G zK0g-^5#6Y`WcJ>4T{m3?07+%hI5KHMI{{E&CQ)dhkF8kR5uSU)* zpoJn?o@3vvr$a6>2b(v3YkeH5*u2~<6>q(-!aNBIaudi3D_|yTV$FrQfR}*mer9*T z#qD8%-2+5sR?6fz)8hOP--{m|oCNNg=wCzaw^X#&Lc31TcZJ@KkCInR4V)%u{J5J9 z3|+d+{ugWLHQVeNaY}dD2H0?>6IzA}wKUk{>#@oF444L&QDA@n=JF0^U3wP?n-xq-OztwabJ!3ZwMM!e?y#CfmH-Y>DwfURvX z=(o7-#@^rr5BQM?1qO4Mkq>;nlLrosHR0UAn{Ul>3WAo#AXVDig?6uKdm;;UQ(l~Z zU98HY%-#YX5mG<+)*79s{_#~=>i_Qh)avcehVx2gxWJ=b#8j(t3bb~1#Ov$)4m zd_V24k-GU-I>g0j&D#&azE4{jwG%eD&D#Z2=S**LGG^<0v-6XRu=`*`)+ZI;w^o zQhZHMwYA3J_t-~w8LJ~p`pvixd(Hn|beY2eu(|}v5r5Zv^P8?=Ry6{@b2r2iiz1?%z zqBR;pQR~Lddfhlc>TfEi8r(cd#Q5ars+D=k^t!pVQUnNhOO&60d2+h0?Us{>Y~Ah_ zqRZ)Y&5!Q10kOab2}m6hMV2TKTL0Lxt{dIQF7wv-GPMFSduaIR=z}&UtZjK<^x`No zp{A)(u-8nk{Gk0p zPnPRo@h#i1vbDJ!`%2awtyn7UQ1aqQ7Sw%R#qd#}u+}X_yC$ zB&X2F#kL6Ax(w@_It@A51iZ;ZKFpQx12Td^@i?iyZ(Fs9fg%)%n^ZcvO>O3+J_56K z@{r={amIgRd{?LM<%`?nOcLvyCUe1w3^r-#aVoez{&fBVh$Sm2W);%}Z-YRZ)F*as zmUv3gM?_MdPwN{Uayj-{BDjnFOhJ3$t1q;FXzA^3*)s|kGl0MWRAg5#Q*yadc{W(* zuwI;*x>;i_P2AS|6z6Q$ZIRnym#hKOSt^U+Am$E9;62a@Uq~UU3Y=nvL@~ zsk?{dIv4Wh4*Ub>m#qOh%gY}x&tmKKcMS(bK>FTa-j89{+Sr{*HX@`B(N5*93{5r0_tUFfP`Vd++ z^?ed959hx_eO|_Md5h8r9KEw%PNGj}mY3FPSg+LL3`iVUt46)Mc0W0B591DCB#0I8 z+8gDXV9QxF>o>g6B7q+mmgVoZg>@|6ehR?;z6qb;ZOk+v9uv2VA@AYxYm;Llx9BIP;?*$M@1Ijpm*V}+= z2Y-{1t}ScVN=D%D5yd*A6YA&_+PZvV7Rg$%{{&3L@jnO3jHT;sT3|J=%lFuZ;)}D* zvkXI4Zq5B$q*7qJZ3m&p%RIJhm74_mi_Z-4D~^#Jd5^+N&9Z}|V=mk2)iM#y759|ho+R@-eLm()O}tqPMDEWP zOG%GTpsVbc7yDVhp9*Su__534-K?(=9zfz%skzs+SxD?VRAg_qEY^GrTv(HA zP<5$o3!M}8db!>EVa{0<5F`pblQWCo8nh@Ue0j!s7pw~uIF$WpJ7+FhaNzSW7hor# z;+pSSe-=enRYZDE=k(;hLvKrq3BI-=E$%Bs{Nh{dnu9yiYKF$rqL`hN^uff*5XfDciHfDnF+0yIL(el6LDpjXeU?KLIskMOnG&QHOT?KKKN@g%xb zP?|G%>DQ;~R6MHZqIKnrvN|i9=}(KX z-U3moPmy!>I2`rwCR@c@9ge0-q`p=2X2bn0>dxN@fr8@QN3QTOIV@$Ef^&|4mJUpxnS7tz`2(&TO7oOPZY<;ZRTBi5$Sk&SCYN?l8madqvXaai9n3d$; zqW_`^_OU2qE(8j+Y1iji`2u6-ktF;kw=SLay}iHSiR#GKZdW{a<8votc8LO2P10GN zWh2*zdCQ6^!<(jl)Xy)ee-r=89%-|S+e3#0tX&-)1QVAGOLj!xBEe6NiGnX@rs38l zht6Xs!m*?LKk$de04s8YS799+G3fpJ-ydg`EnM^$9d( z1yiAqqTK9>V4!8aIBj5ZCZZ1od{c*B*qU zv-wVSpN!ya99;eL;BC=7_o6?u`21JoC2&UVnO2p}*of24!)j0qqte)p@I8&x-6rYy z(OVzO-FIU1I~d)s@z?JtJKS-?ht^y>`?XNAv2i6;Zr51cF*1jF=pGvsqgCcUm3OT0Ojw`0JTtO?k@T|Q8I?8mzsRB}Mb5D*FORUl&_}lv#T0&1>c_|*L@Yr( z$5uv3A;C0=)3bQNbA}Wr)y~v@d5yy~F*;QZkWYi+YMHwCv9nvY@ggd<>+qf+ALo zrP7yjOL)r=1REbx2RigIgClyY#!R9iGlh!)3iO>jF)EW!4an?%W_c6A!Z*v0yuFN# zdK6A@!dSC@he_x*&n$3LW50xx7nuZ>}yLnFcjbQw$$>>O>I-vPX@$ z>*eE`XuwYXXtIO(Rvd&(#3|>IE{{2h=As&*f!-t)MFvRJI@=SP38_rnbnM$&fGU7y zvr>oU+O}O<)A2qr*1%eR9oo?^b#si>Q;GL9w~+nC)JL)V_7y6rj73>$+6GsOs|E-? z?QhItk2{|zx&GltiPOexr^?X^ta>#xqC_-HS3=C&p68n%;{c+9=l|+?x>OBQd-8Qw z2w8GdottVG@fHnCrW-2NWwdgz7kPDyvbY)IJQF}ud;Ev0 z)syXq_awT_Z(EhoG@kucfSqb)LUou=C4bHr(YW%`WkY84aq1r#_+!&Jm!VKUv79?} z-;WnjSM%w)!o@n#BS|jkzCJcJGf;(ABkry@nbQL!tq&h`T-y{f(QDrHmv@?f^t{q* zr+}AxEr=3y8j#po5+n3{rZ}r95EsPoz3;S>M1{5NobwaXM;Ht_ElCW^Q69a^$)G$v z*4cBGu%%c8)E2sw8z2^;3SRtt7eIE*?f&rvTV`P*B&7BIx47SdFo%)NOQY7~elGUNO^@DFw~e6C4Rt?6^+W(U_>X7JG_-MdE)w5zH+uSPZAfxzF&MX|gEa;OiCQ zt?axKVWisHU2n~R`kS3O9V; zF65SYrkg`EmVeyAnqLBDs^tkJR0fHN8E9l7NhP{3n)Hhis|92Ny79L5Wm14O+P-Ql2OOUt2ZdHxc6h($XM)j z9&bQPo%CqUl@#uH3voAK&h z`FW+1cncZDL66G6L<;LPQf>j4?Uw+tQH##+-SD#zH+r}Kbl!(7s9_H zU;4^j`3k{)6!GVAeyj@yc7j(af}V3+z3mmifSkaqah(p28hmHBQ8X8yZHGR+j;|U> zS)6~C^P5K;<)jfgV8)H30%V%X(+=IO<{Z@L7K?Cds=gvmy$hVCt{)7rRR)k3Xu;N1 z%`5_PT6pTg{iJy4U%_LReVwJSYlV>3tGh%STry`H-9ooT&@n7|nI10b&>=YE!J_dV z!=flD7P6Rf&yn%*CJ&m&Uli^a#?;=V_7`Zs64d{9l|_E8t{N#6XlvxwW7Ws`ddf|d z_zTv%SSU6%(7ToekKSK_cK_9WJ*T6cjHwyAiR;9RAO z+P@zTsKgHEy(x+KYG^#bdh)608=s@N2Wfh#1QX%EI5+I4M?Hn}FP~BAK)Acz8f#Qg z^MdN0{q8|y(f^%bX0Qt=xzsGv_+iq&-e`8xNTef^vMuy*T9#Q}lm>^Ut^hRzag z(9FJ*+S)IkF4^X>ht>^lx-N()86RN^QhPS(l?RW7<>uj|NdS2!QvOnNkq{5DEf>Or zgY+}}AG^l={h9*DdumD|jvw~>cbsylR3i_T*PpH;{j&)LAe@;0669fwV$)XV!e)R* z=94(+At3lgY{R-D1-W2{ZcqzHyCidXTf)b;9Z{!!NWSU%?K6cn*;1tvdCoSa^|9Tq zEa`wP+Vj;0j{%1d782siY#xd7UmN1xPA{%cQ6=01Ueq9(Pk*seXs53Y93VlqT>87T z7Q165SrrNobKPcr-`}N|hN?lMhk}v59)+pbWTo-2hb8O>w$1`;B39|^U+vtt4Pmbz z2uT9V5YF0XU$KiJ3xRCY?xf~h>l9Ma|BULjdf(YC1~-!S+2)ccTCcFyl()WR2U2TE zZa*gqFq*>iu~xnv7g3ChayHUY+8S=)3-8K$a9-WG)M`y~a$p_0c#M;>1XC_}kW(U~ zlw>lfp^kK?zW<{1+)iz&fo&O*BQ}%uwomYoIC9R`{n*(uSd}nx?#R4E+23W@DTW^w zLpc75aO;^z!R%-#a7rmkL;iP4H(~0AuWFml143%!8rH>$$vLHUcj~$h%8+&kiUnQe zK>3UN@p~bzW0tNGO9Z+WNti{(+>l9qd#$|b7RD%Py5sRHSDS4LsNMEZ()n%%dp(^qeqzn>ZP{%b3_8@4 zjqY3~C|tCweN)Pbw%Bc^M0f-YP@@2pW;*CHgr_3KXMjAZ68FF)3{u5F4a;~x=3TL2 zG*MA9{z1q1npq~%W6T!*j^37}RN}X1ywfEqzdVU`#SigR_M!!Df8HsL|LS*Kn(_B! z-kyD?0`W4Q!eoYFy(eNZMHdF%`8cw!f54~puldc9h`gbFEySPJ(3z=H>YRc5?Pp!; z>`+BhN_u9COLfYEnQ{aB(p%xAX7wLFz_X-?<7VpGepD;Y*PgE^BHtb~cwC5l6{i>O zscWBI}FqyV43BiyYO7J!3oE)z@_K3 zY|n4ZwbbRFkBxVJMIQJ^E&I9qIsRGA1W=3qWD?(Cn_D2+Rr+i0(CJ1`zs~JDjUJpw zfdNZPA|bp#U*o?uUBPP302Dp7G<{}guA|=FJ+|sWmyO-;>#l9vTY%GMY%9@0Z`$RH zWJ76r&Q(}X>*5e3o-mtYag1n<3C$~0X~oq?sQx&TNV07Da9?-;mv=Oq;Wm7co*MZa&a47pF5 zgn79?L>Csh*4JpC?2@YM5ZWMHCFpEqp%>N)-1^gKo3*M;jG|p@kk6M{i{<{3(uK}| z&3NYzeC?5T0U0L&1CA5?RmnYw#An~sh|uh8(+SQwD}M30b-vL|6VK$xJ~#po8hkBb zoELsVps-EKk1YGE=yu8PMnqluR9YPMabW$ja>^(*Ti%bItLmi%pX`x$-92)+FK94` zZiqh9LjuwH_9E!O#LT4Rqj-7ywr79s_wV4D(>tz6!=WSK(Q(||#WziwZT(Z|&)Dhy z6U1-*%nOsYTO+#TptO`iH5&Yxj^&gh|lWrJ$uF+LiM zM*?(6TZw>J8Kc}&7~gzzSEKzc;?+Cw+Cvnn*BLK!D<&a14#YH6R*#hX%-croWY4o| zc9Zl|aWzF@ZJR=X6wRLp@YnNNB4DLWJNLj^PRx8&O+RK$mwVicpSnGXF+e7LEjPWTR$CvJ4%AnmyG~c8;?>L^1*x0esFckQ{@wu-0d&& zD%dTrD+meg`0^#YdexGHkzvHOU_(8|K?Nf<2QlC#eF?u)MaHes z)Kf#NoPQ_v)9?OL<1!(xo_!P+K1$^EaKcE5UF$d1M&CZP*xUVAlU!pJn?BmJaEHk^ z$5!HM6p@Lw)e!DD@RxnGp8JblU4K@d^^;`igyv)Tp)p^a8BOL5-62J9#unSnR=x2xwW|(<9a8Qd)UJcHgNMNy1W`=7-w* zNi>L^W$X4%Nits0rCwlGxo`CY#}maY^2X-g5H;A#jDsFo*`7fSmqhqF{e50m&e2~E z8d!RwM|tn!gn>LDN)T>g0zKv;ekztSa6Ds3Ok1>nDc#-PW&TscnuFBo$cfU4fvDxm z6!2i-BKw^7m?jODZ`3Ez^`7pv!peRDPgpb+wf0gq`-G5elqqmu&mFXWCzCGYUvZ0?v&7uhX! zv-<$+(?@UO%c*Ls?P9Q}Ifna{fpKYW97Z+r5Pg+@m3;g2gNokMXl!<~oTfvf<3vJu z0o4pXA~C=^ioZNpZCG^Cz_xuftfO%AHpg#z3{g_FRge=P0&RoS+GUL|^S6{h_USM7 z*CZy2c1jkcf6EeLV#+9dq<4RgwD8xC@40g!G(s4)v?bEIJ>27&mVhS7AEq8>js6*f zxYnDy!Fxl4#fE=0#={g_l%TvOcOQcWBDh6!_CWL3L%vf+qeQ`mxT#T3!ZM<9`P+6B7WE3}Tw=!Gw{mti*GJtE>6y z4cKm2K&FgWx5e$bU*sG7siaV;tx?3|eLmdV^1>XfPe@L!Dom&3(PYP&G2c=p*m#l% zO>!^Q{o)TF#rXBayQ*S@3!+&SGrmqxUObShpX&Z5vPPUS9L%caIG2PC-$<;UsD1fckLv+g}4LS0?Wge zY|S=Y^rGhM_Z{AQ;t!Uqdsn0=H%uoo<@grt>VV6_z86-Vnmq&n;Kk*zt=(iRbLkzX z^GD466H?IUEE!l_{|-tQ1p@qclhyDM5XX~FpAo}zIj$Jy=MOrB*z8t`c@NEVo3NEEHBCJ({JlUe7oQ$ZT-d5Z|I^G z3VJe|-&6e;*>V93nMdvmKYb!wKEaz<=Q0vDEH4rMWK8b199&m%Jqpag$o(Y0l6;Q$3yQ_hB-BWD3LB3m9v2})$5%l# zNHy#z_ZV?`-7&3QX9MMHPL+!t?Jf8|U)Jr0K0aFn<>^Q@w@)Q!D}gRJeCl=u97~IV zHnFdDMUNZx@$1){;-j2Cx4-LsPMTh;f1-_UmSL1xq4`AVjX&riz*p=6yf5M5$LfEqWF6EuB4Dq+r8PCHEO}fsg@tV3INh4W%`P8pkTfow?>7~ z>npb})HN{Kx!32}tapYbtE#$cmrZ=oO|MenSnZZSRk^okbYDID|7hY43RTTRw{o(8 z|LxO6itWlWBGRCmwccO$W%r4)A^IY$xV$A9;~10YxYSJ=v=JQPOEYiekZ763k84qk zQG1`fyEm`2=E=6E58C?<*nmUQYo6ZD1sr(_U%@^~yPnj~9hhs#u@A18dsfDSE@c<4 zUh)Ng5=#ptRDow04q;xucs}6oS_9oi;ycbMhp(O2e+ZHqaI~V`09PQ7dSbtn>n6n) zws@l&4QP_-+j3j$$X^{@jaB`)rw{~-kPM^dzapww|eGN(cOk~Us6~@k)V;E;w?lMkv2$}pr_>>*wyj5 zdLbK*9mp)+lRzTJ?0hE%hujLwwjlbYUQ#3#b2-6xH$5AygL`6wxw~#RB+mL+MfsDTf})yc`n^E8O0;l6hZ;qLB`P?Mrr zjd!%lMR+@=Em+VtOxC8>=F9-5W4dF&j2ErjGO zgK~~qx*BGk{pxw`b&vUxO?MQ12G&P?M?AwsM3NqvO=CSCf^Lk*K(kYZM~={3e_Dd( z7kDJNM8cLwHgjAF9K5{eHG6L##o<(ikY7gFYhD|TB8PS4blIVjM+9;ud$F(!DOx9G zuWY!p&mt@P2PIES^{}>9+FU;~Kq5IG{{m*h6-H&Zw@g*t-9cglE*`JvJ(*Y~&^sRc zmyy}EVbz~SPPLLo-Z1{J2Sd6#+#$MKp`LB`OJr~nhUF* z{*`0!(s(>d7ZqNOwPPl}E>W-PQA$ zf32TO`Xr#hfF4N+9yuyl9LJ9~PRTMAE8^UATHf6?Z-orb`;V<7nR;mZWL zPY}ZpeM(3^!cE}C^L*Q*=X?;;PRD=Z!yj~Mj{m$>e!u`xv9mL&C4}y`mW7%NzkKF` ze2mmR1NS>y&v9UlM)f}d;$HifA({cpjr(!SytIFHx_tJPAC;wQVQ%4quHO)D7bb)p z(NvhLa|mBB%_OQ5LWapq4&;UyMtk;$DRXz#zUwGkFE?oIatFHm<cSx==%%X#cpsyY-H&il+XUZ7htrxHC(*Ej9slOca7CJ zl#KyZY6xvaU2xPhJ_#b%CYLZ8`=0xoM1SDm#)QW^84R^SYoHce*7i2eDM!vpJdEj* zetd@lCfsVO2E4y4N-Z@UnKJV2nR#^N|3G1Nb*v#^sG^TBs5a98%*RSF25v~IQ$cRN zdMdi7)!w_P-#cPP`*SNecwch?H_eR0-ZU~*Pi)ioop^80&)s?5uSJgMLL^3cBC>vV zdv*50s$JLi$lGJ(DKXhXt!+E3-NN{Msu9iN-L3}7mz53+B0DjSlOIkwb&0@bMBK7M z8{U631@QAu<5P~A6Spv{te|#8zp`Wc@^aUx^AthlwQsg<;g_!gKS7Y;qkEcDUDLZ2 zm1_ZX$^~JFT%JxlV0XaR(lxk!F!_9y_O7(ZkC{i?Iy@G zd*nX;^?k|<_0Pz=VaX1&+Jxj*c%v`}RzxjuN%?h$f6M-nhgdOUsJ5*(%+A1D=kdV;*rrd(sxa8RIxw(e#a@Z1~!oeUKj8G zaNW~Qq@UN*Vk6WoaXn$Y!STShbpOrKbZQ_6EGqP~HS+JCsj7vTUIRJ=caTSG@AjqE z397-#OQ6wyZeNhW#R*TNJ`;b1V~}6p*dfpbQp#_<4r($#FkC^Mp$L> ze5rvY^(yp1MNH3Bn82*h{-Yf_N1ea$XG4*Q!!8p5d&-E0S)4X-oK(xSS%NeShd1fh z2MAtM%>SzS*Z6e>Y5d3Nbm|*}0ba~3rq++2RWae(i{F*UI5PMf3Q z-B_)MKLfW-?MxTUS4^JKV*sZ|3J6-7@LJF3cLmdhWdAPYk&GY|Spk41M{YvB(>ptf zKyEDL1TkPK$B$U;{z`}0dV3-r;N>sA{xSYq1ofw0b6Gn%LtL68M?lxrEBd3SNj3Px zjx9snidC3h?ew#jnP=w8wk^O+op79W2Jd&S?WwR zkJ*!GY5*mdh*=|k9lF5mYqF#}8Q?(P0YVr0f=pBsO&H$T9S_XxEl5of`MQt~Q-IfkKdyEbMang{DcI8W0oz?&Rtv z?iJOZH@1vZ{}-k!v(w|Xm!9-5u+IL>@}A4oy{95_h>8lACR?3NgE9T5NVQY^isq2y zw1X>)uBMOc04l&IyPFY?W@+|6>0eWTaVko{1qY6hww++O;~{qo@r{%gYqGpi8W%kP zo48@-Oo6Xg5i)$5Q}xysXvS;rKzJ1qqq;SFrcQGYX1I?(N!Jujl@1o{ozZfg75(PU zOpFr~59FNC`Gs`nI>*EHr$ZC^2#Y zk9_O*t7dFffOK*PW~tMl3ng?swSCuV+VEdFWh9`*?zz8gp50KVNY-zmgzF-olp$4j za& z6)uuW-Tk6Y#nu1bVHFS-l(+=NYq@YTT2uk3RVIl-j|I|zrtBTYgB(Ot7gev50ide} z*GHYs>zIKC7!!ovBX!LQ7COgy?Cfr~E?x>b*P^oV?|2&kLm%~itVlmA-8W=^{z$0V zVYHyEFpCK;O%%HH{H~{r@9gmL{nA2BGiMv0IePQws8cY8p9PRUBWv*STDg z$U1_3e6K~3E^AiXi2yR-S3M;oM6SG_ou@;b+AP(NQx)xH2bt8V#RD#s1#v$g7!HEq zMC(x!1%{nQ%UHu+bFa!xPp57&itjOkIx4A7y}`|s^ONZ%3D6lXrnu$JBLZLCI$1hP zNz-jx*Djg^^@ZCE0}~TFN-}-_Mx=9wOfg>sn8HC;WFe09lT&1p7Y~v8Fy}S?I)nr* z)-Ak-bihv1|9o7d=c5%2*4oEyN&Fhg2tIO@dR#_Ij%>vMej zM`%nB)g()LRID9p@cShW2a79q6^Z*14cjHrdRMdS1|fO*)B}m!zDD3(?1c}IQP2B0 zU`%#*GjUrq?Z6zQoSEy(5^)iuYSZ5CfxAoMBS6+&+VsNX%bU z&PN`q=3A&jP(;l+8a|?p!vQzAcB3gsX}kLLjs)6UP$d13^J6$kL>~*E{=la5a0)-rTzVt)XgG zV*|puroOS?%~e3-_9)Blgn%jeE-028~F74vXyV zU0t1H&6aFGxu`NMM{$u!`!4Mc9WN2#_@f(s` zf%ob3%pVjO6$+jKX;)0$0mr&pUSLVsnDe)$N?K9V1r3jXxbWqQ(RD)kci!rh2m5W( zP8c!z^$2;DUgyKY%DCz^%&EL0cTG3meI4v%e?awa8bKp55S%FTbCz9UzhQpOBz+-| zCeo{$)SWyyl^>-9Qm1I0_9D7+ie=pJA%6Q?ino2~GlZsoO#T*iJg{@NVoGuP;?Dmi zhYubzj@I#b(Ux`M7OZL=`o{E|FJK(k+N;Pd%s1v7#W+bM?&u{byBWDE@v!Rq?;^Kxa(PYW`nLPKBd*SK2c?t+LiE8wA^0R;np^v%ve>B_F z8>H#;^bSiJ-|&zP{oOQT7&35J@68i_*}ZzqX@3+g0B_~a2zQOQYK1de(7N87QdYVC zdadWvj&Y(oA-%!TOoY(WG)}zf?(4bhAZDCA?GGFH?mDNI zvSIJ@4ZtaPc#Dj|z2lQI83l_131 z-!nD-GEk6q-G|-Fbq;AGQyTv z*q;l!onrJ2${CsDISg|H4hWN++Nn2{LSR`6WM1=TI{=R0%DV~>th0L8G7P&xhe{!- zKcX0hT}`UUv;SlGlDvS?SFE1<^VTTA^da1aB$?Y+j0rb@XOcM9+4OwFcJ0D)7TwMH zVPJRfie2O(vBZwsl+d1WyTn^hufL*9BOtP{va#WS6qxm!^b?{gtW8+VQL6(}RBTN& z-WkcD>tjGFO>CPa6a^AaIQY@}Wi4|G=c&s4>BbHB;$7#Mj8et)PFyW0&=-K_CwVv? z#f8v~!>G$wH#~!f zbF}=pYmETBYgzNwv_8SBajkeYACN{-QZ?*>vg;Eg2cQwq-(kQ*e+GwB0!BRO!#;AW zTsXg$M-?pK>mnHF!LMLZ@a@;R4bu~xgFk5+<+XySecr5Tyzt-oskG*?=GuS#PA*W8 zLCSYy#0VT z6A8m|+kZpS)RdsvW|ZnDu;qjH8LV7K7hmYmfZeOdMG!C?K5q<@{^FIcNvJ7ob))1l zd0HCN$2N#If9k#WM-z44fg$Jj=-+R-X3$Hjm33)s8voIdk%mcSVPH>wNCInrIzj*x z3Ca4SNiq({N|#j?7FDpA71{*{l8&&^R5gf%B(B?xjw?zh2n(pDb8o$o*#Y}b%1k<~ zBZo|6=S2dzb_>SdAn;hQL70`KI_i{%KQrTR^dtf16tC( zDU-iuS2DNq$x{Q_wgg4D)rcsCTav%+3ND7s}WFiJEc?Z9`H5zcR3>nb2QrBqbO(_U6cNzH70 zEiF;zQ6e0B%OAWnoTyT*gHTKRJZzt%uKDSXQ+xwCRXH8y0k%}qT(y_so>%rE1mqR47WIe$g zO~S>6Hs8+RRGjraFQm;5YsgL6FRiCaQ*$#hh?q++36TM^OZY14Wv1d{F>8H80ms*LdJ8ndS9&LpJT?2r>5tbov3+$>qvN}_C_OWhq0Az#w2A@3S;zdifghiBH(^?}(J9#hX>=e}W z;Kk={;pMt@f4-|C+vL^_M)b!U9ryUFmeQbcR zaVgG81$E5jd~KR=ak|k3rYr%>OxJ#DL&y4S>3taLIPp~lWUv=;{xr4>Q&I7p@mZ#C zJba^}=5;o;7=PdpQEJEk8P=UR!V@Njh7~E!f(92GP-rmCMysF8c{kuUhVgl1V8~UJ zFMB~%?6oMj8Wu~1m%yh_7TuKbF5kZhG}+$lN;Wk(;Ly^FpJmOskd3?8py8eM!mOL1$>4h~Pa=-xS^7{*My`6$Gs zx%tqzcqA*%k0_;PwS3->*Xp!cyZOxs`jgk=^sILl$K%rN2nCC_0nC+C3p#@srFyf6 zAKdU}*W&a$CeAZ{NdCC@R~sCq7cYDs8{E`0hGudRQedbDdeN@uZD@ zxJL;^2f{@7k%!N{*Es4BzGorG8aNwy)K$D2h$80l$+d-C==@^#RZ0#%n$Ak@&r#sj z^(Y1k|a#YphVmRiF9AOM;rOy{0#@j?1Z*k zpuBk=uZQ{j(Is0HV}*uKh__nF2MhOyp8p&Y`k;bKp5#xylBNsMEx1X&jUCe&+;}Hg zM#&RNXk}zPbB8vgo1b7(C-<|sg}5+zoTZU4Vf=8jkj%>FHfz@or}k37jky^V+mM~K zAD;xG`S`6s9Q?{~)A*o{1FYdTx>dNxM{I-4`!0yLO@@AC?pOe}pLuY}J@F6}FM(ml zN%*ouG>+LWQLsk3m*NN~560$p)?#;J$=9ob8GYUL)4zoIQNC>+%Kjwlyy$bwk6(Rd zXX%`HGp6+ejc`|`m5pZW$5>v!4<8c6-#yuyO(9A<$GJT#GGd!B$WEuwwJY`tPcrr2 zo>OwIklxtZxXZEO4cHmHwS>CoVE^-c{SObjnlmA_yeETx6kG8xM?FmLzq9b*e#iBe zxkf%8e6~kVW?i{nHV|(H=6y{;BN-m=;T94WP$qFhm3dBg_q8D4rt%>u@OO$Xr2ayL zb$Etgs8}j-z5WdyF5|E1gb);KMBg~E@$SxgRk0jRvGz1tJ)x7DWYDV@Kcft-&GxOZ zTJ57+<})dZ_9zr8T!t6aYgL&Jwit-5zxMCH<(O!itF7)zz4-Dz2(r14NLpz0g$dcL zBL6l!^(etZT|i0Z6SBEBFF?XQ=IUOFL^-GieIR;bV77C!+IzGX4nZ{}`zf4luS1>Pkfz|X^E5UHu$atdVy zHX%dtCpf@S*A4dn5C6a`7Tx9G3TGdRbJl zde6jQS_13uiA}m0I_f>xI0RHc8^fpp9j?m+?fn;it=88gVWc76U!LmWEi5V0ZDV4u z;u9Aee!$yRJdCjzMJ0GHAPP>5e>kJQ6YdFEy!zgkN4VGh8Z?C{BwHVRRZ0+5zCJxm zYQDB>e1%!a<1@M)2d=gcdoOG@!+l-I9|C~+q%RScv)d%B zKk?~>X+81WuItto@}gQDGVdxZ&4kc3ptZ$e!1DWK2iu}R*-(!oFTC~h@ssz#$)_7Uzg?Z6Ns4AO;c&qD}@RzsO|x;jAn%5 zygzH4R$gz9F+_&cEZaH9FJiVq+|(n)hkmr8%x{>dKzr8AFl(zNRY1K>W&tz3qGK~qH*?!3OP2eKqm*mj>w*TZ&p@+g^)i)Ek?TWBNEMCKm#p&i zSrhB0SJ$STwIcynaf|g^m zyp3<52t?yLObO-6Io517fjg!q>3d>@m6@Pwt@wA`+OYNal0m)$qKuJ*$i3@-KfGRp z+DFQH@546`7Vj5an)y5@%w7N^UaATT4HLw6`8F~}EC8UZCFhk>CxMjE8MyM-Z!dLMuP&wInoTyV~L_E|gD z+WR;f^k1Fr=vn*dR;TVdfNLliiVuogdAeq6<@lqEm9I*+p+B6}fr-wHk zOKEoC_r7f1mvU~LUSEv9EzzlZcZdppN^Evpa=8>`X=gM?S)y`YPTi8AP8U|vb6DNR z7Af|=;t8b@1zxZPpU+oKO-qi!hv%-mF_>D*tvSbiiKrtjBf@Ixt*oq`4Ka47Vw-~+vUnU&u9m>qIdp)#S=r=k zTe{)Z^}@oAXuc}qauyNnO}fN{8uGH*YJ|Wt+9VMt*9~DTj$5V>m`wbWOm?vm*akmZ zaeiSb3R>_)+C7^;c^hl<@4Fp_%DRK!(1&lqk!_DMzNh>r+UubpBlH!qV}N)BRzjHd zt#NDdZNMqO9*a+LQ2VO6KS#ALBM7TUf3eknh%gTLv!nEyL7+?eEjbBWUi{zUKFA{yKL@opW=YG4Ov4&i$}bz`A`D+n^m>w^sN&c{xi zRS!Ci$GBSmXJ<22gMFi1EHYKUzEzZN{QGU05ZT}GnfA+Rtp>e|Q;?f8iP>IzG?@%@ z)RHvb#YKl>%fsYQ8*UAt6Ng+r1O3E@)HV%bG*OS4Y17^wske#?wCuq&*%$D~iS zec(J<(AhWBb|RbodtJA7(&3c*x#iARSW@c?e`|#(ZOgrrNoo*6rt1}mvxym~V14-5 zP1NAlFF2SQJ*Wyg{@V9V2&2CdHnTT*E&fkWqYVe-cKqH+7M$7qrnc zHNjSvDdpI|ticj|UVF|zv&jL%%v}ov#LdJ#n6fRmOe~@_=2ANGl7@UGL@;Hml-Q0M zR@wnGBwl17q>eCVeHbdHPbcJ6trwDINpE*UmmEJW@wda)+6ZqJ`Bv_mnckl&9e0N< zOI6se)D0UEwogo7Wnmddlur*!KEHg9RUG!s((jGMT4VpzVl}bzhJPhAb>O+ur~KS} zWQl_XV0chuMeE}iGVxjD$Rjt>klylTGm5{TAfFdSe5Yl5nOfp+-!t-V6OY`=eM2xt`p$hApmFo+DrnpWz*XSg5?&x;l{Cdwh6O~yfFC1!JM{q zP~A-vXP{9|;7YL7|JMSTbp(&1Qc1=h4cm|s4YSFtBps2$=0v~bB@4q{Oc^_?A=`vZ z@QEAEMVsH~c40=Wp-egTzZ*V?HO9a|%DYP1yJNNGKT9~@mc>vwR_7BI1U;;_{K3Qg z*(!y${Lp^YIH~;S!i~@3;m{u1;NdvnEt%pl^VET7-tzKSMZm_i|> z?FrZ@B!@nl0{p58)-&Cfms)o6nF5>-yMHz?X(BXR>-yrS?&p=2EwPuJUGxYR;#bMk z;M-XXNNMWVSi_=QBG&OcdfQC%GBkfU@-H22-(kug)5rkFqoG=RX$c4WmcDyZE!zORP)Vz;T=y7BBFusfF z5)+45Wpzs#^tDyP>Lf>pW95?aJ~Upm*)AjNsB6dvOl>NZmR8k2DajG1hi#eR@n|V+ z)xY2)$&N|2NY6z_|LjA!{m+P1i+|3L^=llQ4}yG61;kma%`W+plM>-V3_mNd`*=#V zGU>oeEw}D#gmBeQ*qSj!x#t&(iLr)G$?`?IMa1x6;kPH?0|-)i7PI-gJO7LfKS{3j z(ve0pwg@{zoI^6;k9-3!z))bbC) zw^p%(L(&rP*^{-s+A&mIYjnWgrtL|78fSW1A;a{MNn8NUf!{j| z7x;P$sLNfrv8omKwI3*an)_6UA%DmT%ud=fw$n)!+s%>mr%*eGS37yZd+wm`UZ9J& z^6jumUMa=iBOHmoyl4Q=pg?TFD04oYS64R8zbk{!{FVDzmvoN;|GLRjwy^Vdf~VZ5 z15b>bls8w>EAt;>oH9EeAI`XEUggY}@Mpdt3h#TZL-U;nvTfNOmL?|ui8hkE+T^Cg z)iiKVpz~=+&lkkLO5T3%TV*jTO=F;T)tW&gqAMeGrh?bhWM%jnInpX)aS=_(JdR?FOqghm zvRRJqUcdTP_~?ttb_0M|0r|3iVvoJgQs~wrlAuWg>~9?{}&{`gWGYajUm`s@XM5HV~&{2wshaw3Nv3~ zRd<}nz29-QJY<_c;h@_#1+~!tk!PEyjXnJu6qU?W^Z1F9(S)}QRc4uD6E_12MNB0|6uVek*8W1LrV@ zZ=h`$jb?~;jXYcVrNXyc51a${zjLT*#pL@#sX^J>6ZcN&-#*jpol6-AdH!647xMLh zW8d6>(ak}PNiGXXnP2QA{pyla&#@7;{g&3 zpW9c*n5S2@;t7oApgd#%&CeK!;hznY{l1w2tU1V#{k*V-OysMgom8~>i|MZktv22+ z*Hu&Fl56ntIc^TPfn9=>jR=L!X^H?$YTt~@Ft>5HW=<##erz`UhekdmTOoOY=**u+ z&+lDcX_4PBHTY-Gd8yAko`CMCV1CdO#um8O)^P{y)?YpgFZP3mvq|V^ zskSiHH%P=xoYg#0u=h9x|AF=Hm}$gAjh^JJS|}-5cF$jF_~{%iQFZXS+2uRO0qDCD zWfMC3KylfeHepBV*_}OYt4t!0D+5+DYy~~U(SrMoh!KHr=S`}4sFN-Wdnp&oj(V+X-iqbB^*UC=Bl(44V{|Ts1g>Mq^ z;@3D-vD6g=Ok5O()GE);e%Qi(R5kJ;F-^42Lmr2pr>VeK!p>XTH>ky{xH6TcNR#+Y z_tfuKGD(f@1e=Xj@<-S(Kbi_p(ppSt5MxiM{pFg=CF1=hS}jxu+W?B)M0JC)P#9~b zNzh2E5|sdZx)FwEhf$S@nN{>!4|!aR%;kM9H_a>Sr3;)wNk;0&EkF5O(UaCjZ@ix_ zHiX-gMi?R~Fg5x=YqLe}1!NM`$H(O5JSwP>!ft(Jb2&GZG^Z2OQC{ zaZ$vhHv}>6qcJruQ2^Nf!40R_o5%OcaW#APr$^7OiY}80{N3;6vr>*e>^g&vQc=g_ z^iNX~wxmqu!yn?@q`o22AoekkQ04YKqSUgYIm}S$u#9<*HjcI=K7pj)Ig1v?Wq{OJ z#n;Z~aus$APh&|r;kaD8=p+!JZ(56e(eJ53ye6rGND#AVdfta?G?>PUu`nfe(~ zzj%DLaK?V%mnY0{QJ9u|4tNOU7Bu^T&&FZ=P4W;)+UzYOUU@yPm-N8@A9{awPXSnd z^wKEXjwRz_e#9TeXt6?LMlwONn=a-()y2J98+hS*!)<7bK(~x{$1y*Q&!5h8xQA!Ec#`S5!OWNHm+5;qpPK&ATMf?>YCDA?=Gvu*0-{!M5-5L&pNHxAUaDGR%ZCgV)bGls z4_A+3d#*dDmkhCkL3?9{O392~K|PDX%%L#)3LpiUnpD5fu={xXw1tMx#^S}^TBB{4 z6mkKPg4{iIOkbNNKkDHHdH+FX*>?{S6o0N=c>F_D{vJtkd3c%`a_zT&BQQHuZMEg| zz;eq6+PrrP`tlcazMsbSz--GTRZj1jY;4!uaFXPh>X_V|XD3B0=0|7eupV!Ur*K!p zTi%pD$gv%>T+B-EhbqP~iCv#+eO~BtTRc52F&tK1>r?5mB}Ph4E-~)cdR|jueYDs- zFgTc4G?f&WDVV6_%1>bZFD#e>H5?%4`uY4Krk$Q8z527$>CQsq4OzW- z@fD&w$bvKC9pBRjprS9`tt9=k-IM{@8Td{ynCV>nB)%6o(TZ%p;NY(zeiOLXQN^L zKhB*Wl$Wsf!DJ$B@uPfKf9v!>V9wN_eKVHq9w~4?OxI?4nBydGv`UC&nMPGU_9mC0{Bj5N<3c zu2_a{(6DY2BD$S!@D@*AHFmPu{mDd}>&>lm?f{W2qA4>@^R9DUx>Es%Q79g~Ee$5E z(DG?AS@TUUmt1m4%KF<|BM@DQ^&U~P?aHT-5ODg*&7vDRD;k-WsmasBG5hFHlp*Qv z(!(zU$*$%{dO7-7&kXXEO9yw4ZJ(Z?;)QI2+;Lx2=;`qR&N37B!zbycL6l;Dh-%GW zmd(}aqX1`-eb+KQWifz>Ymm=xd*jf=na8&|{na)RYya-&mLX41`oJ{X%H#*qo+q7> zkXSSL=+Pqx%nDS>bd9r2SUHFGi?sY$PCbo15I{pT4CZy+D_{w?`%T9j-_6(m&|Vfe z1|o6AteJ+_){H+j_)}hIN($>s@Q|U2=+Lrp6hV}Hh5bm-R<5e9e7H2ext zkjwR9jl?4}3iK@Frwz>f-!m%hrzV;7Q|>{Vq3{uF`iZYh!R7H1cjuyvOQLvf6jJ27BQMBK!Wru1mV9zn3WRe4eONBNqU__|g>v)E z%XC6+kfO>YBM;BAeaWu97sxr>Ttr52<2qZ(nGm(ipWbOyb4FC3RbQoS@v^Sys{)XdVX`5qjD-v3!beb7h;6EfD&n&&KLGVP_t|6%Z%P-hQx zcZ)tub$&;@5S#s!BtdkOu0dAGXS>T8?>(OEF5UYBlQ>@*=kj5?mo#>vHkQ0xFAYH| zoR8o-tG>@U6KLMqn+b$ZJ3-+B;WM5X3Wd%e1^+4ViEqY(ia!go?qYqeD$)LV&DpTX zYr?WRn+MLLK#$TSFa>DPDuSLQsU=Lnn-Wo*^#!zCJ({#2fyj@GWBgWRv-Y1vo$0Uz zHl3I+5B~&VX}Cb0XMAjeeYxbc$5c7KR%JQiW{_ z-i#LZqoxdnCFXDM3<=>xJ?lClxP$g7irqg;Vsy2fR$ z*X|b+bN!lffbRRoOqwk($7NPMssKGJ}t4hReT% z<=tuVo?vN#n5hjV{~!*hd%19Dj|QPvqbDFi3);lj1?G(rcFo$Lz7(w(^IHcMbPUhP ze#xuf^@4nR^!|eM2i-88zhiVZts()G2lBPfrj`oyd&XMAiKBDnTJ_rOHzw?oUSx$1 zx#=WOC*PYn2w0pu=~oE%qiFcS3b}eR^$Fmy(AwRRu#FVO*!gP3=zdgpPnl?=OUHi4 zy2l#HOG-Nxc0}TA9tA@_|LbIPa)1X+afSj#1G1!EmFRex-&();V@l{Vj4sOPgGN(C zZI3B)ue~OhyT<`m8(q&?`d9`h&WI@HTB&feICZ?eBDj9op7!_5hr@^*?;zrwO7#Wn zx~T8(`P-~mgda3v)8TV2(=tCGofo0HAyXi_yWk?FDKJAI)4v`E+TiOBpdMJG{#$2`A?dZGd($E8%1nav2f%Dt`+(Xa zj*Z`)ii7HjJ84_e-0$z~zy^*PiJNtwPwKk_TM#A*t*-%W*# zxE+2v-fI%G2kFQQNS$yXVWC^5U6FxhOXSg~!=1B+tU_orwrwNv#OiaT*Zz-?%6dkpnktZ*Q8?;5L};>B3!Hxtp*v%P3F(gIQ^F6Uyhr(qalo zXtbjQhP0(4$wig<+~yJ69;B`4-&s`GEin71tWponuw#ySxTf#9YTL4z>p02dl$JV2 zlHqhEtRSQfX?Stcn(>e(i4cQ}D-4<XZE$-{`B5GK7o6D)d<906jft_|5TshS zD(h~c9B@Y_U^~#q4QTE^n|xi3Yjg#O_5eMv8y-}0w;tc7X_}MD!R)V~43qRl z;9_JlFn09KIQ7m|V>e!3+x274B34U#=bYMYd8ur-Lbn{uL;)Htw%AOa3H>x5-tZ43 z{JG$>t`t(L5(rU2`b(9tRpgwDMe?q3bPby+Q#l^C;<#EsGWT4au$-wK(se1g8%;LO z{0~tR&Wl=p8I$Do&J#Qh{GQn%pCxYw+l&8C{EWjSCwUK5-k=>>?3eRvn#yM^ zwgz>jBuuaiBSp#`2L!r$_J_HWmU1{GD2_vbBWZku zAM8FVF0RA*c`$iGCE7nB(IEj`R_wX(JSItewSg{C7=U;)Zeywv<$-3C9J%sgs<7#_ z6VT!=hLO*>NrXyFCiDed)$W0d_!sUDW8-P`mC|v*X#3s6MY)F>ZIFka5gi*5^u;j& z<~i`pLH#(s8vebpLrgW!H!$v>f;iR{%(Kw6)B}%xv)Jf!YuvR_b~XFqnQE%lG1hm& z*M`J3DaEn>BjxC3OUjk7Q}Jw+rjDB+cAON}tSt{KDPHCn6vsvQvO>_?!ZCY56Q-CA zEtnm>#vodA`HK*dQmiYsV@EL(VXF6a}H@NXk8M*qebl9t0yTbM)x^_G)orU5-PXF9|s_-)1pC?L0myf2l zBs!;Ru%fs^V@KqOqFM=`LcedMF9$8%`h-3hQY!DYp;glGrx_E*hWMmDteZnSPJYMZ zHt%tkF@gllDa543<<|GW^N9c|FKMMd#ViL#H(Hx-DV!wiseh2cqON1cGoob^#HqAW z!|y7(MdyEgoeBjAkvu6|(LKy_KbowS;HN1!$ci-M`z2e#)0npefilzEY!Af2uP` zBsMO>Zxy&XkzKMOO54%RbnIVX)F7>>)q)d{{FVt2E-;4JyG37jLXcQT++i1AA`o-O z1KyWgoyXyLWo;o>dX}Ke-kMqCC!NMaJ>wL#wT;1VkHk3*pgxo2xO4O_vwyb+W&jvi zWGr}`&2J1BbFk%OteIGKdRB)Vm%M;i(ztFoKCltN7nM|28xokxj(3<>EuY(QTbc}` z(lp62#NKjIOa0hDZAWm^RHn)WCdyREZ=g^t9Z8k*j{^r-ey*%QxX1H{ z`C-Hmm%I2-b-N>3c$+@ALiW(i&4u7~pdabq1(LiaKE>SQM7prE5(UcCXH>QsR;YKR zT!qWmr*7>Zjj}#QT_|DZ+HglmBTQnMT)5wFI=wdNu+xr+mJLeT@t@-hpKv%q7I(nu zx%$MV3ikEmA>vdTy{T1g^ulX&rm}p#rIapQ5ZF{oZCXD;>#)JZ4`*VFrxW=Hq!kyV z)(&&TqtRL{tn~aywcAnd4QR7XAB7^QKxc2DJX(nFft?q=Kc!vw1lv{v1$v5;qtE5= z5+LAae^7w0#EYQ`cI)r}s--D+$_qhw*XYbF=+Gj91uh`-v(*e+^Pu7?zHE!SVI>%S4^reE`*cNuY74vr5G4H<6$eH zuy^NInVD6JggV+Ma=SUIC(Y95Kw&RdwN&&vFJdO*Ge4069}^)^-K}}WDz2N6jP>K6 z(aTX-`{_i|vhMyfg_wBCC94gU+5Keg7H50sF`ePnKyIqd1{!3@s_Q3I63Xg(Ud#SN z)JT$W=FrTUbfnUgPVK0NLjfc-wYEV5Quqwpc#9^_ik`|m*pJ)_v-OT3$iREut_@pm z4q)o+re}lL_EdJFrKs2bL;$aZ4TwzT;??PQn#@YoEl*~}KnFM-B(3@E->b4@dEHtD zOu*l$0q@q4?EdDIjZHiD7?6sb3|p=N*!Qoc+6aicf=P0`{5Ohkd#%8;TV0s$i=xfI z^#W&C*Ft?>`$YqQ_b~Ii7fc`5J?NVt#|BIwh3$blVa=;i-xH?wJo7hsAVI}w%;yw` zBrtpT#WwUOIMBNfm37YZ{GIP0N#1hqTf0D6Plrt@4C?u3TCazi2CodRjVSn#c^T< zRN&@lhaolPRi_Qb(rq0=xO~ttOMu;4S6>OGO$w)1P>UIG9PU5HqN?92MoTN^mDc^a zd_VI!Io2CJ_p`i=0zJVAKwt((Pv=Bzb-iIDsL$q&ylAVFgHCF;O#xIT`{N(H zEyf%!hehgEH$6*H^E9#V$(b)emt;9KmV)iiMy1*w+`O+FA(@gRxTlP%dV#4p{whdW zRQGsU(|Enn$;B%{MCt7mGTq!HCsr!sNwlU1sihP?LgQeDTjj)f;KWug7T5A?@!0Gp z=6L|k55@uE0}?vObe0`Mvwik$2Aj*PKd|j#aS1iO%j^$omgk=M^8SIj$jSH zPNx3Gng&G2ggUm$Z2NFX!Z%1DAUb+=1Bm*po199e5&VMtogDoV3}o3;u5MgmhWfQ{ zCVXk~TE1}ey?2TusJAo9H{UfS)(N>au6YGF0SBI4Dy{{35d&82b}vZ4w#070wvmA! z#U0W5!m!5Ks7ELnA@#0u`hvRi^N+#L&zeAc9*^7CM>1L-EG@ZnRWx0>49Et`KCoZT zaW#<~dUuFJdb7N7{7LS(I9O8oi)tMnc%cdlxd)Mr^$_mZK6hdvy^xMPnwryHd-ead z0P0>%0dCQwnVKH)d*ciRA}x|%zzvaYGVj)|u9^nT;@4DRQ=EXr;&o=cE>)87Kokl# z4^_a*Q4w+^SV`jnIYJ3}*_(*6HQb1Cv*MbCd3p#Iv)+m$&EljMrOQkqC> z23r|Egkcz_Uwx-`uOQLMInd23^@R(|`zOa59_U8L&kKm@a8PYoT!Kr(4yk5dFs-)R z#H#TskC^8^Mlf-&@4LsWy?)sE^7T?vZRLSt`znBRf(`QB<1bYuhk7~b?1_;f-xSpM zv4T%r2{Wragf3Ss0|eWzVZM`;-(2dO8|7)`98J_fZT0ku*7_kxK&HsqQ$K6Ef)9Ia zy+tzl*JXAe7|U6l8kAv7Vamr7TS>hoC-EhZ2hzurIM*@dSuZ~vRk1_*)D;>8qoUcx zCD9=nydWI)h05<9sX|*C$XUXTcZ_F@V^ho3Q#A|8AE@6Hk7YFD&JOl=JVVU>1bl@6 z$6a(v!s%$J)~9+})#MYEnfKvEt*L(d(~t%V@EGc9`{Xqwh;vW$h~A|;Il{ztwyk#g zBy&)$W%aa#9CPMsK|x}Xh?d&N3}AIy%`PbAruu14ZqcLMCJ}aya)gaA2x0iN9PP>$ ztmE4SHoorC1I{py!iNMq{Cxeu@PC_n<6scR+w|K=rYSY41Fpg)C8Z z2EpeSibduzgEHTfV$UOLHO<*scM;|e&|HcdNKo15IovRIt%wn&Nw`gIXa3Y_K`zCDX83;dJF`I7cE)D(V$P6j3!ph9~B2eOnVnUNC+?rFFM|7sigIZ~|E~ zS3pBYtYh)JTc9hY8?zg1Lv=*n>X6M}E89`a8$M)K7(YeyB=B#Rctm+O*n(tvV_&5> z;Xx!}CVVWrd%Pv930=0ddD=*ZU&)Mgdq^kmVSc%)BN-?dCM1LR{`9ZFa1!;Amxyap z95nNA5VKFRPzi~+TuULQ*>V?O6GLiKgH%1llf;l*p}Iphc|GTbsAR650x(id(UA>8 zGf|}ZVSw!sjb*u|Fp!WveBoFEvGXFGs+a%P@n#CUn(~LUJeQ848Eg7CYVcYQrVk$U ze;UlL6ja}bszR%w+MkmOPeyP(J}u32jJSXRZfobv>Q*qKNc34>jQ^A0y(*2>&JIF+ z%5vxS0pkJ@buqr=UxFtD{*!yT+keESIv5*h8h<5w4%~kDaz|a8=akD{L)~;BF zxqr$)BW<`Oea{faVx(Fi?)~h`PuC4EB*_hkqNgGc2Sp9?K5*`>)yY>7sNQ~h zw!gN|`|=HenZ(0d>IWqIr3bm2KKeZ?etN4?D8u*?IKtH2=a6ZNjM_5DKv|nG&eAm~SR+Tv0_S0Dc zX;>CJ6YJzS>m~K)wX6o6)tQ)A>zvb0tWxI5LkfGIDw@gpdSpC3j zff8K7HKh=>Fu_V$_flD^1U;nbDAwr~^ zEiy`Y5LL&23V-_V8ykO4CC@;qFc7^k9eAc3gw%|e39plWze@Lh4>N$hRH~KRxF<=l zcyG{h>{yEx&@Z<8rvk%?l4ttiA+u)kAy%F?m?^jieRZ1|zlM=KJuXHNT;-PK{BR^5 zs%eM4@^z7^mdBHjQ~f@vg+t5wtrF+Li7fl~98l6uX1KZWNRjk+Ps98Q%02a*M)-QC zO&#=Mrpps7I!_t^@LwPcZn03xJRrieH0B*bVj;34iv3%3Z{?tU2%Nx?)zkdjE6{ybG4Y;MaG0eB75WDbe4>4E3ESu^2x<{3!qoc|NP+{!t;B7PFIst@ddvUm(8pb%SIM!@>9a zFM}^pt%LVhkPJnJFqs;hKn8(*lCIv27NX1toZp24HWXK{Mt;iZvt}N;kxE$KreB{K zMrS2V6)}*w?Iq?v>zpzb)1_DQGDCfP^g^xEqlCtq9aUnG(n0rqf#{AlpL%O*1-Hg2 zX~h;H5;>DO=z^-`*MMYt4&<3OO4tM~y03H38FF(VrhU0n;1uXr&Evu4jC*PqF#yxx z*Hlp-3^$qE@&^G!7pu1|YU&d|A(>?s|HmRz5$Z$%hr+;f*!eNmo4xc`ynGV4kODm; zKOr9B3(e#;o~Mn8p6OM%>Gzp#64*PHp4uYF?k*-Ct=Rf$t3It{c7M0F{{F&Lz|-W} zp)bjlywmXoQ{fCfr**vB$^J|4gInp^`@e+jqQ@E}W*-&)j%J~$VY9lB175@E%Fz=I zJ2owa2LW4d=s?liqvHGO-QFG#%pcYGpQ8` zPgYTwQAqM%$zLiJ$tcC~r<67-S3RIG@7vGit-HNIh^*|z$3B%y!C*b|ubv2S?AB1^ zBS;9F0_O);3=DVd1h{mtZc-`tA z185Tg#bK&I zNMG*iwFy;5&>B!U zc9ED>Y3pY?_MvBVSiNCpJyNp_lkUzD>1f;952OSHQIbz%@}a9`8>#NZ>kgyh?tff- zf`Fm)_7_p$qv9}qzt&w-q#zR`cpfoLb9lP0-~bGV@7h3pe+>bJ8`lemoYB?WfAZUA zuD9=wjL${G!cE}&WR3p+8A|L-yxh@=DB7}YVd-m1-GIoZMv)Uwe!@!oBIJ+NENH{xk_=I6$lJ% zVE6IMc?-3!A)N&lG+@#1R6UBNq^`sfJ%R=kGMZQyoBQe4^FZ|3pm-x=P+7NZ0<=xE zgnSvk?ZjhVwDH)+k*BqAXAEtbT=NXPWmzEaoT*ss-H)(pK{OL?4V7PR(f7@f8bp7u znXi&z)T43!_Sm+fA7e)QzJ$xeyEI>XhYtCH^c6~oz|(es(n_4ts3Z&dIJ^7e`g%GW zO2D{CP^qPjX?c#aIbgPE;m^$p3L>IS2TY*qrZ5NM_-Nd5SL*>aO1i2Yeg!0WpW3Y zix+7&3R1Z~O@Q_*zO@j~)6E1ZOt|^e7l8?Y;U=;KNZXEKi|wteI{A>2lL63N(~~bp z6>Hii7;c<%5|aG4u4+8DXDKhSr62v?*07_r?iYh+IPPo-1mH_I{Cz0{!;4TaE0s-H zS20-V)jUnkB==RKQLG^I8Xea6vaY?DrU|s)AH?Oin^kAmUlbG%syHvN`|RiK};YqsF&RRgEJmG*UHAv}`l#}dYd`ot4TOr(UMf5Z5ys{K9+fC!A50+LY8!q`pg>C#e*Jfe zud()a^5SQUfUE{m+=HiB3R+5lTHK-TUhB#cYU{^>a`Wf0X53pt;4FkFodJ* zGHVHIRC6)a@d2*af4$ia@@hl~u!>9HMtcnIthLU+_&W#-1ayJX&XOBD(mG2AaR-tE zA7%H^L@*85+MczD|GJx3SlInfFstpih?zU{pr$>WoOeXHvl77*$GQJ$2geScHM;%*+SV(0-#S$5ix`7MXL=OG( zl3)Jg<_o9Dvr5b`eBN{6nfyV-q;^T^->!<7lV5!|*GP8PNzzvw_mN2fK2P5nj$yw_ zi7~J8?c&V%?N8iKac5zcyz``ou*{^KP!Kd3{au$sw6V$em2Z z@@5w53h-~ulc-k=TAa%bs8Eydgmm9=bMBACuhRNsvmFn9M0}Uuo1iedK!e+PUsz;C zN>V!866&(3u{nhp8=b3fe<{<-Z<71xEonbjN<`lGA3R~VGBopc`XyXUfquhYcQWZA zkM$8`G%*)$oZxL*aZ-I%-gt;nXG>fjNE4k8xxd9Ee5StoLtszl-zTv$IG-EWmA$fJ zg~!Ue+mr<)PT&p913>o}i~j-Zr|!=4K89}95Xn8sE+Jv&5Qp(DeKJLKtQc6V8Y)7m`3dH$-C%TgwD9$Wh; zV$|7^yj|&tjlwP`>cvjg6RENDkJk@UJg`%O!csCB1J1LZvEVK<`jcCeFUT<@TO{9T z6}X10SC$a*y<4-XrI@Cm6=-(vjO^nUqYB9M?fEH|?8%B_SR1R14*V#-Tze{;hjXYp zWq766?VhWmZG}%a!TOM`~EnmD5#JjHm$)C}NabJywQE8h+bRrrAzi4n8jlX)w7jg2s z!M=5J3FT$dx*xr;N$0}ExC+Qn)N{SlSEC%p(*fHAn$8j5lTqO2))4f*(>EbL!>mEx z5mg**O)Vmw)_?0hxW*n;*pCL|8!3cAZxtU&C}_yLHS7S-T=LX``8w zdY|=v(4OYn*6D-5dB;7nOn{50>DrQ^@*Sx30l{X9ziPDf)8l`Jd5aG=+RcmCRW8mV z)@fB{18PG6INqls(jFX^Q_>v`U~ZE4P8)^G2kxmRu+idDqyb1+C1qrI1Zu3NPN zi135CRL-5{5igpT1>~;jB~Ko^E&D82Fjt38!A3T&8K5X$QoXU zxl=$h0<5a9!8I<}Bd}r@-N=qAHNIdtRE3VHDh}I}{^V0;NB(c^+9BVoIvMNj=H_I$ zQ#d!;9_I~xHapn82W%Z^NWb!o_v}78I9eMjZS8t>EjPUC)^lu8l39K98`EaE>GRaq zn|Qt!m^^Ug79>gjZdh?D$!(dz64@r0`R-{LREq21b-fMXDDTIYYLx@=d_`ELJgQ|M3;D6 z*g=H?f_T_W7GmUV|7H2${NVD@oDj~AeCJ{i{;9|`nrWF-=wS}VFeo}{hjh{um3d+5LN~%0+1@2pi~UMg3Hc+D^e<(egQeB#0aB64dB&wHsRo3s z%Fe6v)hV|h`_x!JwyfKkXMYPf(fKAZt@_9=-@ocLf?N5P+>N7;c$7}RP^E027K<Uob*oGYy$sc1|4L&KZSjS@dDIQdqInZg!LEXkDYnLvG~;e_d2^1m*49*3DY#N%+nj$QO zBa?&0*-1O3bQmChg@|8y*qo_ea-C$S|J;UJF}ft*e+cVKhG8X{ES*gyMgSIMP(%MO@R4=XR38%GJDoO`xYBcF5aXGhI03Z zr55Ef0qZmQ>&WT#B=M(pkdLv~31isL<3oMM!CNw)Jb%lne5dAq00E})r;6#XDbK#H zjXN~ROYEuG?FX8gVz~r1pdx9dGQgwI8NpzY89kpZ4lBdw<78gVc(dEh9DfN%={}kM zpUuRt?oB*IveA~|n<$oQ<{0zDMHtJOhH7s*$(tC=oo!XgV?Cu;=bzc4wmO(Ox*Y{W z(QhXC{E}{8r4Qk79K($30!V3nl#YbI6VZ|Xp$*V8?6hcnohUBwGZ#aU*K*w@hk*fW z;zg73qC_Tcarpl(ZZCyl-pC06D`MQ^7*W+?)>I@KCB*sPf+!QO54)?UOa)9eU5Mb) z2L^<2=_bLwQ~9Z_kj+&+;`=6sXv9R`!C5MU)v4+2L@vw(k$;QL&zPFbG zX$gH4_xlRNxUzkA%k};fb6@K319B+=NiYB)rYQI)>`qrY5Ny!$X$`@3bc=2F@~~PR;NrD zdd|Qzr~mVM2HWUkDX%wp`{g2&tFkU()-y4A#_k}Un4jW~pE?c9&G-o4QF`YO%3 zRpmPbY6lUELDMrTHieElHNJ8#vnJ#Ht@^?N{Ow|VBoyc9EJ0r;4o+DIjI{ zd*o32e~knkZXdnzX=2;K>%CSeLIn^18P)9l?}ziNZ~w2T_l~FXf8)n*n}}p@m2rA= zjARp$kTM#^krA24Asjo7NXiaL*?Vt}y^_7>v6Y#foq2vQpYQkk`2BzG`*odbKCkC> z-S^Fl*Gd>_a7z#;bRmSGKl!w}fXlS)XV0eFZH*U;W3aObQPTWwdBc|R#i_h`-{V4J zImLU|x(JWW3(L|FFC7`-5#geg(Vgx0YWVPJVVttK`WHJo>Wz!CMhWGS`|hTlF6QS? z*D5+YZ=e5~x=jW)` z;ay2mXyP?iP7`O4scG76&Q1*ed}H>VL(hd#^xrqGj1fsBf+>O#!lP>;V>saubdM7w zyx1)&>e(%>GR47ag$Q)LXK>2$+#THE@I-0)GRXF1FwGGWh?nk1}R91gx@p@|w zMGft$1Rwc?AJLQB5I{EZSFh%bKAA!?X$`Ar6!>Zqm%(Pty42>-6)4##$smI1e25RY z0^hpT^C1<=ea_0Wb0YuB{UjWZday~H{b}7PQAy0b?{yLw&%*UnpI0_dy5D7Zwo9~? z(O{G?wSyLU4jQaq_v6v$n?wI3(@V0_+sEJ}lH`^&&je!2mb01Oj8~xOQGXvo(m%Xm z8x^_{k?g5^;#8QPN!JX=UXJsBys;`a{HhBa+wNca`1s0ePNbr4Mx+G@T-s^*?63|! zGpIsY9`?^vlEt*xmWw(Lk0~DFh(6(3pJAx|)#k*8xAL1fn)9yR^4eXOsr_~qzoS3& zU>7r0$v?+q+Z6o&b^$66BGCJd>dhMOOV4X671e@U3LI8zhsP}=ul;ibMyn&xVbc}(Z{BFkzZ^aJ-88hFFo4`Ohh=jqD zlYr@P!y0QHEaF?EgQ-+qVJ>q+C#lP^(T9Z>X80t~?3L>FMYu3B* zo<}!6%I)E9-}@m+p8A{BS!S!KPF%=2Hr>2#+drR4W?S~!kXfaR5QYiT?(@9i9iD-8mf@%`O)aKqSSqendxBdsrqo5+!k^od{P0A}D#|!0$M=kmYfGQ~ie)v6UW6f@Z-- zx*L;THTNGYQoeTBxDN8lvk!Z>S5sAV+J!JJO@BvxWS*bnYLtfpCiG_mmEaftoHM0d z)C_M&BiqtX+7p(?<-HDdMlW=S)bm0ga-RmJ8}b^(>^txneVOjm@5Y(;edBQIH64?{ z8riG|-AIQYAtW`dW(lCuXJWA@ebY#_#x~DQ)5o}t>~$fao80jkhhk+#%0=f5!j86a z__KBnqjFdf$X+!T?{4ItqhUomm_3EThA$;YxX7^a0Lk_%7uoWP2R?irs2wgX$@W4D zx4LkiA`%nZxBW5cQ#|s?Jn84rCV}gMVU{j;=!E=f?gyY*KtT z@Hk^|x>BC`ifJ=70bC@Pk{8%S&vGNi<@W<7`0h)|y~-<8;YU#^XC~|Q8O8YEF!b|W z{LvO}WlsDnx;GOm6_%=2(Ma1>B)ePq9&y&oQ!anhua{1tj^jB`O#hnR>hNT5*$TP= zhoEtXnF!9i#|%xz9@1FEUjo{?K(xKFyfEVQ~xgQ;lZU@V{za- zRE@8?iBhZ47^+Hd=Qa9zwk>7%D*k?LKzUDZtI<*EEXl5{&pW{x=ZFzq**DuMZuMUR zoGsh`y-4oJ9c58pJDqR^%KAQ4n{dyYk50<~QW3DHuz2@&vfE(G!bl{e@Ft0*44XeUlbh;tyT=5N?m$?et zf0wP|b29o8z00eKI#-9So)`3KE703-8vdT7Ty#oYwzGb{o#>y#(Nj-Wwj_F>eDsgw zz@Gt3&XNNPw`F8}8bQFvwB&xELXi>Y(9B(n~Pr3Wds&? zh1^mHR-l}DutuF!Dq?9+o=Iv(zlDW!s;YXgI z=I+z3lYNSiz#xBJL7G5K+TRkSLX5?UJ=%Ubwh3OjRqs8Y%^$We?KHY(S4K(Dq)GWy z$$)zsXDTCqYN8z5N-IuGD(}-f$LaeU;jTP=Abr$a<#A{yyyD{mRy`X?aTkwZ+rqq7 zJ!6>B&$ToECg>s?xNS6?<~Rl1{lX?v$7nJ?h^*g!rmU?BLB8iB*T6X`>mOl3ucy9z zP88E<7rX)ztPZ`(H`!sKnfq~xKdW{~$}i#3!)&oC)*o-vgBkrfTk`T&JZ|~kaKt~3 zNB{Ksp>r-aV^nf5=Su(Fd{klL9I+`JV6@7rp>^$d(zB zNJf9qQ;k)jbs;_x{}7cXSw%|JQYymHeOfZhQBraA9&y5tL~)e#;%2$JytKv-zk75w z9yV*wo+=$T&Szi5h5kJV$ou71e>wKSJvT>{i`%NR=b_h*Y}CWmo8|3Z zJ?6O2j~cVJfuLP|)mX3V>QaWC7I0b>HaiQd4ZU@_3Gm!Fak(k&BN*kPQH4ym3-UGP z$L!<%+?-E6p)Y*+$F<~p=O{&9R&Y@))yqcX4O9>ME6B<#8n1Poe%21g+asD0ZXa3W zE9uWZjZ#?*o4fCrXypNobT=lxO{!(lDEhkppL!OL_p_mvr<)J5m-wTS{GD#4_x|`^ zb!QhvPXI~v$bZ_O92&Wizs-}iBWfwjjphMU=0c&V>*@^BX^u|7edwvYcvyd;_w$M*YdiC^+AzO` znC0z+;UP9$`eqwbgXR@Jc(p^wQiJH&**tqA`F=hxxlLgBfe4hGUGbnoX6gWOSlFVD z+kh3e6PI-`I49Z-+TY9|n%uwnk>py?2jD0Q&IR+VUn)pQjLOI7q?We{nF}Xtl{^&a zZFka!uO!;g7$Y(FCS2VwxLgA>D{$|f=Hl#Lu*=zqx4$VH-eQZK#qB(yQ7h$r5gjjl z3UVA%Sj=|nGsfDvI1w({b&9pdi=t2iI-+A^Olav8b%!$i6(@JUle}o|-YkXX=Quxc zgSQU@jLFd#4htXt3z7)COzvsjLM8{qKp-3TXC{PcWq&8D1Y*DNY^y4%KRu_B=}Y#G zN`KOcPYPRWob!YS-5m81j6PaO@k^>m=g*jQhiyB-@W`-fnxCC4Wo(hBW`gz4a`D&} zVTi0o;l7&e#{0PNAn4}$0(ESobgGit+V~9Cqz}^np2!xS* zf86IXm1{=jYGPAKgnx9Ws9$g)1HP_E=q-jz_x6usS%0toyCCeFoMPoDQJ6}*b(oM+ z=N7Q5u!0UK-CAE*#wSr*@bhQw?dS;BY?EAo;PQn#Emd~`8-0Ow(*ufRwc7S#<`1S`Px7# zIVjWfFQcNeSXkOU3UB{OwP4>nCH2fh1@79vcd9gphdt@8r*-oVt@JK7)s3vHlx#TC z*qmFh7ob2@Oq|P876mWWi;c`YhA(TxT()XkhYTKdZzfnPm#4Codhurk>DP)+MlzO zTw?cW2W|>eYAP8dGvgLhx%joQtu#jEOYH6FZbDhZduE+_0(Y;5>3>(4oc&$nj`o~W zs5~6gp8ckM!IV&_J?8Bqh~Mj6Su^?LzFFaD*ly=3NVd*I-(%p!^^xJs2WhyN(TyBB zU#8?msol5BxyVjCvHHhhUVQW)AAc68{i>=^%!cZZi<25(y#cy09F{z&VAheNawmJRdYjPXxL8gq~ z%=(Jb1gspQo(?oncFWewkVamOp zwns?8LR{I{l-Y&k#%ABTMPVlZ8TEx~MW~G54j$7EASRx_dKBUOm!yAjkzP`#S)X)3 zuk)EdsAZ49oAc(wEI5my4-UT@^tWi*uJ{ZO?Yet$*X&1yhK;M%)auuZrJO0eDL>=L zJJR>@Pd`#SX<6LcbL+KP-TlrO_R}dVstM<UzXbwZ$slAuQKcvXn_r<) z`bAXsCjnG!QeR^eMb;xgR^vviqEmLuE%vAc<9|Jdo<&J)P zs7GX89r7m?EU)x#Q!!uNhKIu63(H)2+H6;2h`q4(5;62b?#gfFnU6MZphK4?r=kiz zpDUot&mQlJA@!6<+66s|u4HU$oP;f6CI+h;D^q{*YBakE_TtN=eQtC-Mt$~ydeGHx z3IJC^mIEI;C@sg^Pr@ddPZ|?U8E@gPSa=|cxyY?W{{zUd1aRNn$~9P#JvpQDW43PK z`DrEl=E$M1JfXLxPsPtCy>N?w5O5kV3D`-xx>U~_jVDp<#!S}Mj(VwHpFRnfx{_G3 zXy3M5_+jY9?O5 zO?kVNsQ9!#814OeHpe{6i&=;M>iK0i8uI*q%^$f1*gM~vYDQxj!l12|&ddcmbLJ!SX1IHFIql3Fg zH7x@HUS^=fEI)gBglw+KIL6<_Im^kaCPv6IbSDIf+2KpKXD=p4Ey#Tnwn6?qeEXMDrWR`w7Fa6Juv-eOT%kO?&UzufVNY88ArL) z8@O8-i1_C^eNew*E07C+Z#W-J^KNpwZo58Y;SLVxGQju~^+#ym{qPx;sDQ>@Lps`a7`#%BS1Bv8@BK zWgS3}Eb`utA0K=f$xI#tF;!|GmdUf9)EB1&yOx`O2eN(j0&hQEiGoJ(AJTrAxiPQF zkC0pGvBNbV3ovUnWFEeO712%$`PkO1pI-d^ggVCe>zqrg?j7~y_~cfIJHGiDIV)5x zR^s;}@7Q7BeR^6XW^7fah_RzgF0dSg85A*dViwC$7B3o{lC5h+uksnlw9?!0C-sAv zbxBeyPl}*6`zl$M@BI;$<;iA)@)ow?y2_@%@Oqagk@PRipPQf*hAR#;wP*cP&K#t2 zlibqHb8z-FOU7CTvvXvUr6Ro}A5%ac2c=q@B*$ zm(^K(eOc#`(8a^`14R7Wt@S7?^xRI71|9+WT;z`X`dkIt;z{$t;!6W>tw`Qg+o6&? z*>q=xn$*_0gk`4Sr#M!F_4K9Rw*m7<+heAPn7VoW*P_P_b4JnCEDeJP(R9F;a{q?{ z7ReO7(@B@3V_5&nPh~CCe{`#Lk#Ji?mK%BYqF2+f-Vk**i z6mPEDd{l$ksy-^{xXdi)hq&qWlG%ML%|8W|fu8^Rgf;Nb5obliLykGFx1(!0G%&hO z819(FsQt~w(=*_+TqWfq--uf@6aWE^)ZErIN`7!8(WB~IWc&OE>avWDLQur$_gDJ0 zU7%^-mdY!1r@Kyos-^|;Tc_*X1C=5i)KY^FeHUcvy>I!RPiesf)G5E{&*mu~_sf7% zee105$!_DS^>M&f()#R|_gS-XO1=24ms7~#O09J<1g2e%wv?p;7>w08Q4*+10A$Rbdvgre~wX}?+zaY&l? zyP3+zD+!5n>$4o|!-Fi|ujjuWFyXbltYtAP@iE4=d~Ra8e>pUoonz2Xog6}6U{rRO zS*QNP&&S)A-IytD5)xOfxySih4LOBPwf2|fgk9T;B4}kB287+qGBVi)3d_Mt!lu#|^5F%#AMXR~Wv$oWqgeDVWzlS(prP2ehub7nw6x3@(bGLexEmo=UNx*LA zkHoo^S;orq6=Oqoe4ZQUaF&oPw&dfY&$ajNnO!+x+*&k&`b@yju0idZ{U{!2* zo>$g0++orC>fVsb6tIEmzv*Wsb*DA{xPV@LjjvYUj`bU8}gHZ9O$gP$_N)rKZG-$+j7Wwunf!kvnwNTdTWS$KUhL zglDT<08*m0-jeQh3d|+&SXRPC)c{G;CN9FNQDhiZm|b9qT@{a%;KeJs!3=8^qVWZb z&cWToMhb4f5A_Q<*5{Y~oqSd(s&UU|Di$J7l^vZ5^V3_mwfL<%6C>{O^(MtdVP-!I zNi>CNaC`BLH|KTW)JmTa_lLAsv$YtoRnO-RIyQVK23rUVu5Ap5g5lQw{ z&Cb#9b&>(OKveEh`Uf#FCfv~^C!5?iHhpT51W*&K=zuLWL5S216K~3RYBq%hz0P+P zSTP;pRV5ce^N@h(vb25#}sC*g2X3oZ(nBg_Hm>9Iw_$&Lu%&lr|CIQ`Y(l48< zFz4u+&(JN;!f(}Qyy1=#(A@-NZY4*(#ffqK-Z!iLrq;dhl~IL=ZChBq`jCGl-a_@@ zs_Ke;z8Ws$xIh{%U&VJMUgEbRIGSX4zA;Jk3de$lPLNpdaA0}Jx(ejgC0rgIZz#}wPu-8#8=_WN!nevgk1Q|s_7g{RUE^$v94Y) zycWl5c8&5xREb|z3GYtp*0xcN+Y=dH5-=qjX_ZCKWgt(cAFQu4W@Wx`R;mulkmW(C zU3^|Vm^4b6P78$xCza8^?H{VHW+0IitUlsP;*Tf!aEoIob3Gh3Iq>r*g*^Vuxeh#8 zy7;;PRk-92SQ>d7l)u^=e}64&8{+Z_MHnUh>0~c8Q}PAOm-QkmcsJurZ!h+laCG?|34ZDYMo%Z-(yCQRRiR`?~+h;zIbN98*^tiDMr; zi|T<@WIv9rd87Ip!>V*AW=QAUMz!$E`;z5bzWF0uV5BJ4i=wUmK-Ai-yQHYoerVeN z4dAIlsW@tX{bU}m3O#ab)t7RYps(IFYvm=>x|*60A3wCV=HZi~m<05AT)9teG_#{m zNmo+$ECp1iQQ-=V(I#lB3sTB&!|&m4xub}&ku`k@fK8cQ^g8Ef_dY4)ihk<+8QGdU z!`0O|KyEIKM$gZVk(+FPUb`G(l<+E`7iVdaJKe))PVYiSxR(DBI7i{oL)V80k1hLB zh_%a0IIf;ub{5nBud@KF5QP=JGz6P(E-PFs(Tk?urRw0ZGudiaqH{X-GJ5v1MdR(Q zJ4P~J(0QbKaJY#BjqZ$jNlX!9s35XI0A9zgp*lK!y;_%IX(HupVD-dU-O1t8lF4K6 zZXP}M7qa$eg43+s@(cnW1>ucD=5b4?PRz*QZcZ33Ok*pd#I}g~1tta+@-AQGNO4H~ z;{%W!6AEgFNz(9_VL#y&C2nVq(Y zg18t)VHdX~p@~rV2NT!D2IlT5s-?Mkn3Sc>YM8i<;6d55nbNHX`M+{AGEUj1_=|cw zv8V~xjAQK=n_JqmGwPL_yWP5bA(L4A1zFTKPBPtt*AP})SsEZ3(Rv~mB;h&6y=*?~ z2EKZp{PE~Yqx?*5QV^Y%2hc{HK52?3wL=c-i}Wpbm-$LLVDG&>z?s<2uX0jbF=lKrTnyZ*xg zCHe;ix=jYM*SlmB-=|)@P(4^Lz^#Qk+cLG89hamnA?2~ciPq?Hd;WydEx4m|NSyt@ zNmR<&%9Qe`^G?v&LfBe6$0*33Gjz5)J3Mza$;y^jY@+4_B35L6zU4_LflTkF!Xi<6 zq^_6i5Z|kQ`wI%Gkz1eo0}|&#e7YwNI?)S^4Nu!j%`jwSj?d6zHN2jLUi>enjTh6c z<6X-TRwHQ!4{63NE(Ephn^DhsW~0bI300}x~UQQIamv*hkYK*o)& z7$Z#=EQlrG08WzT-ky7|B&r3kDHqMv$=5NB3{|9nIxdhNAW#u&Z1 zyiid0sEjxpHrBjja4)R57VWn8KB*QEX-gWoSd(Qj+oO(c0q)wiI;m z;tY$eBMMP5rPN9NBAndn-JQ`}SQMQ#kI*CpF@92iaR2!bAv9p6Q+{I#OSW4^VW|<) zMCxJu{@TEuHUb`5Tcee{3^K-1GFQNjkVBzp^7vfw16+P)*tv9Y9cIU(}r}4Af(}e-s z7$XI*_Mr0HB!;?r0JP7dLY+}2PS5Am8X8@1*_~E5TWDywwK;9Znlg5LOs6$7PsVes z%DjtUgnTbVS9+)ko9#XYw=BvT5V9>Y5p4DWfZ_DAdt!&MwWfIZ7 zho_#JB8Ex@+A({tb*SnI0k;K1ajU~9qZbhN%L>p$zB&&_u2700W5)+mITs1LTlrri z!wig~-bxQKtWJMnIOYc(k%r&2v!TFlCC4#PhHE-<#{7&wtRXwl#OLWn=$7`FJZqk- zM((g{+AVZ~^;sM%p7V$~p%j`#M()3jqPFRN+erK;>%QwSK}XnPojZVGO8*yz>5K;i zRfjR(bPz7ndDxmGE1;o= zqi3&3ckFzT-@3V4xLw3SAujIv_{c{x1~a2`?&+3XgU$u1l5%)R|ETfRE4i_=0BHb6 zb`M+^*3)cAaBv@WMN-fT+qfLOwOqTt=K#jzaY>f}{%aYhz4yySfwm{+Jq5C=*}wF0 z?CK`57yMz6T;FA@BDTP;c(Hcf#=)pu?k&Nh^11c;OT;idFE6r|1$pr=K1Qe@C$rdN zCBtX>vzL5~BrW(}Y0_Z7&r*1LpR-Lnn^9>fJkq~63>VI?&@ao<#YV~S68l{C_VHJC z4}N7Z>@+XMN=UkVLQR!!Ub&={YndNdfoUB@?3>}IGv#?n$K+L2Zx&ZFJX(0_e&m1hCqOR}_3_!tP|c%; zepyzK8nYWlXVnd5IlE+MuXwtsTxk>ZP>ob{75%=P2piFD=CQiE3y_j-~f5PEYm$Ke~?e=zdyk zal6Vg$EWvmEd%oR13^4udozL{#3{kJv-c$aGS+_IjD;8L!n!?5eGRnf;mKeGSCvWB z;f6B1cS&WwBg=F-SbI@p`OYsp>G6*t#e&TM{5eM%qIT28(|w5!(677v@nhBHs_BSSM2Zl%vPm8$?*ZTM-j8ZIP^3LRLv@TE!XtTIeBTn2|wT{^eVKH zZ{Bh64W|;9FK<|1!gRZ-O_!k)k_42Ucime#7op7(>CwW# zA<-Py0@{xM9%E%WH5wXOx*j2|za%6I{C#MPvuYhnP@x*h*{xG$Zm+YA!?&o~ z87Y&)B@qg9ww0liN~v9}^6^yIT3nc|Ud!@f$L#0DIs@QmUXcYM!NY=s)!l)Yhzb_? zzae3xs9dq3-BY+(ANc;Z zQ}*$*OGajSW!+pIwr)hpz+M8Xv%*$(L$5>|^dT6SOk3iA`TP`1%^wRNAQYDN3e#qk z+L-^*VXLSClF`cKEYhA(yJyFzY_m(&!53`1(d(Tvsva1!S`CL)DovFC`tT)Qosv5$ zlC6?0@RJahTA^~>@`GH}I0T8r_|%8wr%PcLu!21TY_x6_ccF7rQe zPha(g6lqE2Y7N|=d<~+|@wl*4HlTd9p9qRjUA__Gb0fA_nr`UL0weQu>JMg@|HD^RbxQ%-#ua4&KH1QStLxw#g=eiwJ` zg1muhu@6}n_e580!sg-AJT){BZ`UG;`_iWD*toc5oBsQ*1EA?x zs%g`h4uQJvE|W>muBMWd2CU0!Q@^x2k`x|Nr-V9&U4p|VuFLeWJcmeYBVyy@*SyH! zDS}PnoQjU^XT^ov=t05>=Dm0hnrMHNURA?kim|9_)!^l&lP(Qhe`0$-*}6Q8ta?TH z+MRZ=|9^5nR!NW_i6CvV{w5Tm6XH>0{cbSCqi_c*ZuGQpIoMg2XQUgtJe)ZL7IXr@ zAV(RC)f6^&)Sxep$f?{{%I;DEZK354a8-I}iFGfnQ15a{=UsErYIPe?hzEP2rKmW4 zLOJAnlRLIoWRHh=rIYaZr5roYWrpZ-E3oPz0+$(h{kmgRre-?^=gS6_1#9$bMZi}y z{NAYG>h~bvt0F;2oyZA}ErgaxoK8X6GAQD8T4P>UtwH+VHCnHJ2SqzfTOGu!UmhLe z(MAJN721nBqfWBPIfYt^CtL#>rJ++Lk+{KD!|PqU?>V&7Ra$xpf#rOW^1k!or*$t^ zfW}WGx5`dLNPRCfu%ffSLYZ}D00CfEn`-NVJ@&9=qGH9EC?2=fq4cQFoyjf5+TM#z zXOjfgo2rqOFH^Bz=G`705~xdTd5?KuK!uXsewuCoT2jJITVG~uoy&~vUps5Ze)8DE zZ=#3Z0Vr~!CqbITRHR2A(=I!k@#zxrK zXq*#n$Q@3!F~gXqu+@x~1NJxIjbc#KMWKLt`^KwlJ(i{=G4Z0RAnMguzLl;D(K{32 z-U7EOJPtu7$D2218-5*Dq1=$$Vj)vJ<}n0Qf8Cf2T z)nOWgq|xeDu(*ecl=Mg6wN|LK`$|kc6m$dqdWL&LOOE4xEFld(pD(rH@oz*fdrIwEIXLcm&Jkivy@4Fm-} zYl#g{aCv;<63u4#jmU!IluQBW-}Pg#*c8?vnSd8P4$jtzptkNcJ`^PN-7r3-u=I5b z!xZ+`uQTs`7D9*|640a0oYCslYs{Y_7z>>F2%=FNs(~_At|66g{$6h5&9@0^5A7&? z{Dt;D_q*Jilio?X=e?{w#Si@vc21PT`6R!6EYi|jT|at6}d4cq2@&P{uL~ z@xhZ6DrS?hB&&m&Qz|Fdkur3-3Xu+tvtH}y`j@oy$s;*^ylvmK0`OL_HhJGGG!_II z?5F=Dg#8d7G!YPN;tVs8N#!>|z-R%oBmsr?(-v|IFE}w3*jOxIz=+OofNvl6LfRJbxCnfLqyiMH5N5B9YOHOHaf+wh{X54 zA|+K3sp;ika)xjd%_DcwgEwgw6oMq&Mc81sfkO+u!g*#o&!~ZtdCa837JBRIVI?(p z?B*@HjyKATup{<}48QNbjLg)|g>p2O1WT`#3<`_<F$Hkk;S$c3uj@Z}W1Pa4pVJX1{ee;+10xP(??(`9WYgt(y6)#OWv$LT~6Q+_*X zWu83xd1CDnh4s6O5yFIEYiOxiVtFDT$rI+#^ae?A(dT;yN64^6VaDwenj?<-zu5~U zjgA=qc(6X=^|AFUQ1E+#NBJDfZDX20x|;wtTmSC7r#)WO3j*^X9>-gZuwyyxa_0Dvi2fJI@Wma6HfK5{e>(NvB4m~YO05}%O9?6moi`Mp= zA)TCZ-@KyoJ-=-RoAMA%0k=eP##+3Dc&)(@Z{-8Y8KA1pKmtD z)HS?`pq3)CL;tV|`NopVTmUlhVi0Fn=HPwGeapVcG)^d%Y+OcY?%=98^@%7A1QV{Y z_)JnSV*`Lenyt$RRx;?rU79#&%cCH05230ax}E8_1YLQLQ|wqd$`!qyn6{DlI`xyF zJC_<8M7cmFgV=xi^hXhq!e`WxV};-|AU26A8lgncgkt-KP!H!hm@+>qA&J&EP@cFe zV}1Wg#0asVCBZV`^1JylDJ<&Qif=UpX@5Lv8usgyV6tu@f5L@l*k^FDSs^Z(h4WsfuiIh@$*I}~2 z=tWR<*)x9l5gPjS2B|hxxN*F`8oT*lt{r#;1MN$|9X(^EGiUH~uOS8Y_*%={-KLjK ztSRv>VFvubQFM)po0VB1-yb8=2?^yRGEgx_r@Ulk<}SIVETg_Oi;RVt|DbpAls0&`b^Jqmb$Uovx#HE?kFpkLjav;Cu zZ}8H&j08&A_#Ny)h@j7q;QmNpx=d7P{wE&@W0sN&+Xikuxib5k?O(dfiKwfE2xbOL4OG zoR89$34H4vP{xy{V^|bWn_MrI;`Nk`;w%5qib$cSbt@gLoRfr2Z+-oRf3Bv&cjbwv z3X6vsecR%-b?8O8lIw^BefbL3uVd9F79`wHS7HrlF^{(YKJb#2-@Fqd} z3Ncos?UgMjn8~FA`oB>U>h<7Ibn7)=vjXvLkw_D@v9nC$@I@$AoQcf77>XdbD0^C^ z0rsyRhANU1am(|+d7`8+pkf#={f?Eu_jQehr28#jPEd)p`8RyPzxOksYbrjt=DQ!S zs1uuzYIHNX75LL#s0oWwVx}tJN(q+0h!Zw)K{gvrWE=HcqPQWn8k-7R$So+KfW}qU z3QOOdUtOXE5jAl~_qsLxKRxE5o8Lmz?DcpeOH3k6~k1?Vp+rxVuv-uEYy9YtjEWJeR(nA4XO>k)R7W23G_<2&^ld3oKRO-+S zk{m0p8nea)t`-&kTTJS^&uS)YNKZJPG@~>rh*QYtfY5yuSflDyTnNJs#=S!3mil|Z zwJeh;O`I8;G!9S=YJwJI+WxxKc%4Xhs4j&16Qaz>bg+8TjvjnUbk#xAR6_-_LAMgL z6kvM3pYN}Vfvz_D9hjYPPDP-mWE+gL!wiOxmHrWOhiYTpdxj&?1M?z#ghr0g5Lo{S zJZaDOT21BPv?YO{hh7|-TnF5|Hwrx71hJAU>aG;V$@jd74Fj(IqM*;onNyKXX~Hbc zpOLIt`6cApONm8^33E#Zzpb$jl#~<^hSbaj%uUff-guC&Q6D%!@6xgSy?~gb3~Yq; z@7)#f(;wmV?IVKJZ(xc06sWIDxf0GQ4Y?tJeGw9EI`3vu_RE*@#m?rrfI2j0}x}t zK&&`aG$LFkyDTaOL9Q6HSZXc-X79g96eX8Q(Tt1e0j1Pi)J?rBq{$y;YOQ;TkR!^q zWt&%=iF`R$bfM#jt#ol9w@8n)byhW>TeBS~+)mC6icCrd(;G@^iiXC^N4?Wfva>xH zB}~}f*gNWb(mAt2woD38;tR^FchZ;0iJ|(H53?&h%m2lS(=CCDm#9rN0Jed>;6Ev> zyIbQ``oRsn-u;~RbsAFw^M7Mm5lMiCTulYclik5%S5*-)9t4Wp)i-R%XcC;9+dxcp zu?Rylv|aPbD()v#h&>PbK-5$`2Zd>S1xW=_cA(Ik3sz_Y>8+zf?`U!zhLC@K?i7Qv$o8QK diff --git a/ifm3d_ros_driver/doc/figures/rviz_ref_frame.png b/ifm3d_ros_driver/doc/figures/rviz_ref_frame.png deleted file mode 100644 index befe4de790dc333c02f9e0583f440f42e943ba35..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 57878 zcmafaWmKF^(v-4-} znbT5TeO1*})qRJ_$%w(j;J|=^fx(Oa6j1;J12+Z(`xFZW`SFjTkNN7y*B3`2aV4ma zj~A3t=*MqtrypuginbD%=?kg%u(**pDH-gIcm zFTi!sqVDgR%|Iku5vwu+T+Pxl1YszmH^-jd@3mZk?@+AEwv)c9s5T_d8mM^q85=_j zP(*=9@8T^WGMn7@5ocGp!KRbN3W;06CJYyJQq zEH}BHoW%x-o1Y~tYDJp5b43DUNO2pg9VhA7Dz*FOHumk^#_!u>4I~o;Yg5=Bs3Bb{ zqbe`pt%&o`s9{{w2LR=oK*JufJ;u=!zl~T#=gv>-;mye;CjW@}{gfg~8H?%E)1uYf zEioXa3HW=KD=M_ny|iRWAzNSb1Z_O5aozm@?k%YHsj<#l8yTmL(!VtUa-_b%rUPAz zCnhHHl;UaGp`g*O*UkaQnooPA-Iuqk1+vmZ7<;A!X?ZQZy0)P!kRz8^sL6Ntd*Oq% z{{0F53#!Q%nqn3Mh|R?Yv4BiTNA832gS}xD=TGdF%06;;vSDx}S0d$Biizlx=V*<-6k+{Z>gKcZ%5FltZG z>EckJx2v7pTEj*QCNO8_YDK=-JPACBY0h8Cn|v>v)A*7fBi$zfLq@m>Kj! zwYdDkmpr^4T__bP_8SO6;C~m5ZsUsRrpBJK`Yg69pjt#2ZrVtcHqceC%a^me7XGJ@ zR&;kQ;rOc$bf#;2KsbLM9eqK9JhBYZC|_wJaYk+SF|z`@Ii?Gv^JZ8kpx z*?`5R%e%}$*A&s}y1{NOL1pPGd!S!t!Cz-mIZkpY7Lmr9&W7%|YhehOn8TCFysaEqg6jFoAfi7+4v52Y3^-u8)&Z7!ls}Q)3sC8r*9Bw9qLhpXWp3(i$qQ%$Q zYK)bA$d5GO5{gqwpID=A{lB{1;lPWC&WC!KLV#PS=J+ICzj!mlwChAO?y*RAnEi+> ziNwZD#)e)VotyGpi;h6l5dT?5l)9_wa@7TuO>8<}0wjCzoZC`trt;wuh}@l7DA)2F zFB>T`5gOg(7BF?Q%Op*!k9Po=3=Zp6-H)9l{}T`TTBYo>J)&iys;2#L`tQ%ffsVdN z1v>lYD-9@|QgH>M7-*Ml$tIlR@)0@dI*cKtUxn?8*TOE~9Sjpn(c4qY@)vV8=@Gsl zyQcPUzKn#afhCY95zBviP0*%McT1>B6XXeF&`YZ1%iyC6Pn*beh%DLZ03lu&-(27b zKQh|hNmO8g>T3~y;JW6tNO}Rxy}Tk%p|xcUWvvZX z&rQ72g~QoQSxZ2)TO*|4X0Jsmyd9^xIIfA~nzrpMP(MW-TLPj7L0?n7cxImE8VBY(cHug|hEKR0DNZL&* zhUnNVHob{N3*Gp?vNR>y2)+t6Om>pPGHk3)X5mg2@U7$kbr~ zf|H%lR~=W5)?H+N%~(jYV7<8-&3F9W3OVmp=O;0@4R7Vy4=wrV(|PEW-M=u5VyR4e z38w>?EP_b~PA`qS!wPyZ!m9;$9sdu`lt`((}V>JUFs^i<@@a7@*x z7QF27mW3VdaxC3>o6gUX9ht!D>q=D;V@ihLbiM0j`Iok5nOGHi;zjoIU8TV_H0H$} z<#IC6;VXE3Nt`w;mhf_`4SDozZ3fH32Wr5%Q|l{!_(l59cfJf4Czm0J{}adB=vm0f z%!u%N=S#8jdfm|89Ekn4hZW(Dn;2ECMwqWcu379Bvx`IxdIF$*O1f7l-7yUNk~wk% z*@lrWuy0?Uy%MB6RHR9rHaGDiiUgE#9RVs8KT|x>?PmRO908rKYm#}MInbP%zCSh{ z9?a&j=;*P#1J5a)#3MY1@<*ZLTv%ne%OhPWQpIMqN%V>4!6tZboPTRnijWqjMfA`;Bph>z?OYtc!8px|Ub zDC_E2HYs!-Z8fOwK!D4AIrc11+ucr zp{F~-D5Vf1WX+f|h8J-A9A(c<Y>rwmc!CXo7tVa ztcz=ESI!?}L3sVk6>Xl1B{1?xW>&suI4u@G|5M-cT_Y}>KqlYLO~HIpl_~!E*VD;9TzrQYq)dE1j}- z+zJ8p0o2RhdCQDXm{EUr542cuP;ro1mY&h`fAaA@W}Vp8%kUXeB+;$)%8lTbi_3F) zErU1ch+Xc=-l)sxK}UxQ_oMZb_(ea}?@a%4#%ltFrZo~XKyqX=(u+U)TTh?+MiiG) zZ~J%FPMU)`7P1a1!p4Mo@OqeQmNG5tgB&Wg#p%zkhEw9_7Je|!fcol@L` z{}kRH=OkD)$tNLnXq2t5fyw1X)mohI*L^*9BY)(+&F9$Z{OdxC6?&JMEm6{7BeP}L z6whE;b5wK4ipOvVCQ?wB;%&b;*QOaHHDa9KE_l4PyrFc%`tA=U)Dcq5X01$2WOK3D z&2Fg}gT9|lW1o>SX&X;X@tv`g z`T8Q|s}z02CJ?!r9`n$tBp2kh28m3_J9Y>gpreKQ&jsG9_Fw{E6LfoJD-JTB+| zqZK#Lxe#t(ho$VmOGm~mJK-(Mf*%nZU@ALJi>D#2vmtAL*;S}ikQ-~goO_dgZDbg? zTcqz~dNAh%O$Lk??^xXKm_BS}B|{qd9Kkgn-@tWW!d)Ms z*>De6THQzd{+ae9D46JeGZrLF^pV~)OwJBZ;ru zi-#i1<#9Y6QqdJuw+*b}&AK`v#Vx^xC)a|ALmO{aTFFs`|7;ae_GZj!YLHROMfNv}1OoNUW-@>Ln@aYjeHTyp z3o9WbBJq)b^X2cb;tFK{KC4skQO4!`O%wx>zDxd;{GSf}gNu^N%IL~L$wycL91S9s(f0O2#-*g~C0)F>cbo>7b^Yu9Y&lxZbRUJ9x zUzxmq|9Q^+|H*e6TT@u5_Ovbl`RV}aod|Iqr9f!Ebyx}73{B8tH*#ipPmJMSEnuvB z=VKex1-srn#y-nv8quQ`xVEUfhCh{1J#tucuZ% zn-2b0k9^ULcGkB%2ej*>k;#ufrhnBlJil z?OF)cJszBVm-`yq_C@@CC4cDfJgPLDdjo=M=BX523m{RWcPD?~^Mve7g+?0P_|;~D zuIU+4uJ+W(WleemTY>a$?-K5{=rgFMbvKika9_i#duMjr+zD36-NA|P-BJs{v%F^K z{77b7ymF`Ml2L{S+lN$_#R;A&$0f_Qw(d=#l+U|a(JpmIoy6o|I&0R_SR`Kj(&5(9 zymgR}7VF%~WOD!G`ybyw{{RH&XQUvhZW6ZNlio1*?m(X^1aG!JhA;H&i zEgvp2ZN6_>MD{8u!%Bk_z?PJ|)MSj+kMblWNfA8Rl8otA>GPCoFom0NS7&UXp?0uY*rH8z|_<|NYk_{zK^kP zwud!R&FafgK5BnKyVM;Gul2LJe7bAhn_8`T7rD7)F~2?sjY=vkfrl2~&^X65z><`4}c(7FgVn$_4wsHi6df-vG+2;Jy4~&kkILXQ|h-51cIa zvtU%Or`|I27_iBV?^x#@v@tv4VSGULR^hSY+gXVNmRcWSF@gQzOm#SrSHEOf=Jv|5 z5v>CwUJ6@$(4xbXbN^;UxlzdHqIRkq@qU}K)Q2ia3Js{u8@sAB zJ5S-EoxZ&jhhjA0q>vwj*dOD)2rkyk9C0)S(C*`^^t*R|pU7wpsV+f0Nw_cLEgo!_ zHUwZ_I6f{TJSFA_?$Vd>c|<%9pt$8%ab=WJN2Ov#RlLR3vU1CJ9Z2(BnvlGVaUEod zpWl-N)b-(;&aYVhE~JO|CT@0RXW9-Dil?{gIq?qRyheMmn(1_oG=zXev>ush7*(sj zfdhyA(q<{${4XF{q*@N=WAhe0qS_3yqwBDnobMq$46#n16ZBpsD=qCj?>KHdW~Czc zX9fsCV$<2o^?eiLX>Ip>`?pcNpr#ttouTk*c6MfSpc#e@_h>*N0RKVQRYjxi(c9DX0C$5gm1sA#vkvcuRv`i&w7>`|PZPy_ zV^fbiGg)W;Ql%ECj;Ogw!?}?tpid15M3|{_xZ(}|lw8b0!^0ZnmvzN428I1|1dIj- zlep3bI)qM_6yx7u*XO&*?L1jZ0b{mi#$doicqp@RDc#NDnd2LCN2;5_O6$`)*7j71 zmCJuY61U=P)We^tboqp@n{?M5MUI!uo}MB$Qw?2?Q2x2vLg=ADUT$i8(}ib~^~S3> zJbQqPd_&_WXZ|BxSn)IPK8)7FP<&*`59KAeD95KhBI6^DdJ&X%4;n zoy$)0vQe@=TaWVlC|sBQ+irF|wKFmCq=n-Lkx2_f<5;Fta}^oWq9k2tjVR?<3b~}- zUug?;N8ic_I8&_4O%xx;c`cHdVCfy2%ozC;>?;-0Zc^^<9qm==?UgG@(_|mUB)k5W z!relQ=exYK=W~Vk&DGq5Gy%UH=egopqV+GMcb6Zo#u5Fq$TAS{sj6l3e)3hlo=!b2 z=Bm)q65$pyo!c!@2X`&z%>Keb7IgzKQ>yKo%iPwm6~!Pzj{q3=qyY+riC@=r2Kqpl zI-FlRWC|fz)2EVL$WlXxNNCON7uDGeAsUBe#PcY&MEF&9 zAF)GQWl=<15t&Pb2)s5x0Ws!O!wYiBB2{>2UR0sryB$><4nN&l*n6qy?WmE)CeGY2 zeYI{0#@JCT?^i_PuG*{V8mc*%i!#`6MQv^%0XHn?*P!?e{Hgw>JKMc9hLWL-{B z9t4j-r-N3ihC&z~Q6bk|G2>dcnVdC@dQfdLN%(?h(l^!}&O@5IU8MR6qN-q_it-Nb zDT@DXqd(#D303b{Fe(|pEVVt6oDqj6y`6FfNL}DHo786e+SNDP#BT6pq6&!28v51Q zPy-YoQR9js*5w4O@K|ap*;#S|uEii3^v@w5)(M0g6`<+O9p#E`Y=k~1UEc<%(eT2~ z7#-<#TnzLImsryCH~41WsjAyHILQxd)^Ts={Uph|DaH0A;$E7$aDLgg3IMb zds*n;E>J{#Kj}%0-`?K-PhzVhF%ltasM7Z@OGY9jaWDAa+*nRX!6d5LeF5_C@PSB# z-|>^M?}>z327u%Pkt^P~L`tXwpe@Y}gJtJi32Z*O+km-wHlg8HU0du`5)e9bz1 z>uY}hMqjVK{YI1MJ57pqoQ;jLqfHMF zmq92(ZJH`&YTfszi`Nei1wX@<;5^-eG9Bx8m zHZU+KQYpt_WMovw2Yf6*duB~9#Y9mhgh&LylC(2L13P)but7~TVUaBVAiMKL0 zho-8!*k^uy@u5~2X446ygRvB_yNmU-jdsu7!^5Qhm@wD=2yEse`3p3&-lDb|`4>V~ zb7@>b-pJ@^Su#r>KAMX{)5o?-r2>hm+W##47)s6$irpQ$6m*Y+Qg>E;1@SN=)r;|Oqo`n@0OI+@Bo)@U1 zC*%O1wcd4_B9Xg6F}XE5_Y9Mu1aHoP49|OSlM?3+gUCW(o0oQc25(|~B&D8r9GTiE zX3iVJlF@i5^temmsv&3CxaMsUeG;1xOq|obNOs!_uaoHL>?UCujTf)5y%4sCOPxKt zqP{);z=Er@Sx?R2cHKER z7|7)HL^%WjccY8ds=s?b-RUn?>C>R%VF6UgwvG7{^=5ft_8awGg0dP*k@sm~ih~@|ode2;_3D1X(%6S477HPrqTG_> z6#nx1;>pirQ`sE0qs5AaO+K$&v>J7KCv(L-J}=3T@HkaIuO8_c8ONKQ{G*Aq!j+4P zReIfMi#eakg7}TQ`wE)KGWj4BA79Ki^KUBo^cNT5L1s_NZ6~hVwZr*W4fCj8APP^q zAOk5?5YlX+^ufqHZe@L$u8i%|Jz?_I>a+adyJ~Tf6eB2dn5+|}r0;Wek^OX8M6$5V zC?5Tysw^U-;gyz+^2Kmq$6NCHMo(P~>d{nhg79g}Zn=CIH1tk&4xI2}M0SZf%{F4C zz1J#=&xKA3NOG|1Wsv}_&WjUccXp5mt~UGONZCt8Ld;4H>HSQzFTN7zdhz(j*;@`> zlx;P6eaUA4`28TAiNG}p`#S)Axt+DLY*exQmer^39b~)0?@4=`CsWip7iewz1i3+n zE>#d{z{Ckh%7Vi{Dl?B%Jp(hEj$vExRYIlb)m0!kj=fbAM2OQu-oRBHR`?9BwM!h$ zod3g66t6x{V^AjoHx@N*No=jzE4E84CONkHw(Ju%K&ec~CGMw9##+`%L3_mcI0mi3PG1;}R@3hwSWGgR_ovg!N&=9q_gEBkhPg&9 zUO&t}scc72eEDMJwWduwFwAz$1QP9LaC0+D>&Mq>-fdK15%nqdY&*2F1X`|Mm_;4_ z!`H*_C{b!-<`@W8Vy^&Fiez?r2+28sQE)|*6O-+U*tJZ!IrYPh0@y=#tvOuc3D9+<0*SpkQ`QE7R+2sS?P&u(zHhhBoG5)fAo z_I=}(H0K3pzB!}4)VoSqRhC}d7HE?}g|*-aHk`$54-`*z2E#&zgHaH>(oAa#1=l;_ z^c_E6lzn~J{SnX2m@Ei%U93bhH15r(ohjlv&3~B+(Wd4&!U@o@vqcto-+u=-amLa5 zDz`|jirLM`E_|Q79-P96zjo~%UIy>nDNpg_%jv@*Wax|`URYRATSYfG@^{U9{i&?{ z864bvrH=B0wB*X?iH1$Of3S1Ao ziEuWe!|4?q%};V=+wW?2JZC}7_>R`#d3+TjI z&9}0KmF-4Y{j{sWsPx4SXYxD*+tTsu9>%1H8~E)RgJhA2U3|nYv6CnnoOoL?qH|T# zMCVF3BM@FYO*h6W_GUlZf5lQPW$3VpTH^NjUDz`iu?cGH*YrIg=USwa_OWG8KRdU- zrjxm?^xY}6TE_sXrWZa%wWB7l%ahK&Li}{Y$m0hwBO28%lRNwvG$7>GC$L3YomrIKtNkep`iTZiaXvnS9Wj)5{8c62@$$ygSTO z)3(`Vps9Za4Wf#;D*koU@%`erjyG#GA|fIIni8VmV#E-I{u-$fShYmcy$!>%jH$Fl zXUo~5RSq(zYvO|;J{hv|85Ws6I_<=oeQL#0aq^DjYfR51r!IrjB&Q6obR}*Yih?Fg z3hCn+<6^a1M(qwzMwX|WjJ+c0C zh*tys-N=vWpXSo+IIcHnd+$380Ge+z;wN<QwnwKOp?2?O`zNmEfq_w;<8Q!Nv9I3E(MXnxe| zVb8B-ro!n9~<%w&T*F#k%TvbZPKKjUDCcT-;Lq7|n=Y9EtAIg1bLJGQt!md%x$oy_sV1r1KD~xIdb}#;oTlR!vvHCk(F!jrwyA23CYA-1NrG-CAVbfQ7*Q(e%xU`!y8$F<~kvuIA zI;Rkm(ZGz~!yVmp)zp1zV14Tgxke`kyF#nu{#9u>rBycaNR z8@A0joxL>E@$dqn8orD{w}a3w&orPuv&gVyR43--OA9de4iD~Gy2y@W^3ZHgea<490zE?|$ z0IiA&21PJM?#?%dcc|35^pKe|OB49X=!2|;i1!9~_+N?Do)Yj@6=V6XoyJEV(x%eP z{8B;{_JcfPFU}tx(T8U~TkO3}LHMKgY7t*|nsGM=`s)MrR1)Mh2joXTqm}b6OV8TF zOHLlUjZ&>qg|;dHNKY_Ubgn~`(BGs=;5VoW)j91;lCuxFcW7zqv#7;W1gGL*BX=__aGOovcJK5wXG znxR?VupAL?dQW57XN;OhXrxR}W1gR%+dDh|kVm7T-Cf0zmXf-mudSfLlaeNl!y7pHrO(7UVf}<6 zS~{~dnAz=sX;ez!0^z3BI7&1LcZppI2KAO?QeWkU4nE^*zVug9LzZCr^yoTbIuh&h zFUXz*U&0>J@MWoveV~-uwS}I_cIAUxsI|J#y12M})GUHOL%>Ycn#!i9r=uKFDi**+ z6Yv`J1JKjCU89EM$Wig|q&}Dl7N3_}j}{~W1pjAG)e$FLk=bVL<}5s3CPxXa1LQ zE|%Ot1d8%1+hwt{RYz>${$E%K6YkFG`Cw>cj>>;@=5LZsC=$!AZCmO2@~%(1?%Xj! zMqOYdhglzoS?9-dAj1=M7oo3x1OSJN#IRiw{A(3|~GS*o+de%V4MQadTWWSZlst`qfB7X8HK|F%SUD-H`koB} zaZ0UO^oWJ~n2NLm4Hfg#xx4dInT!tzxMa)w&Ns=c&%~VzY|>;rAODESl9H5XF!JmP zRsj@iOOz5#jRkI?2pfjh~DI$c3 z5Qz$+R>^6Lh8%ITb3a!x*{hU2B%5ahA6d>Y`7xe<##vry-oM2%8qEx*QIljY5DBv& z{!3hpM!iVhIvVcPYuR${IwmdUdeiUEo@X<{UEj7UP+l8C{wYf0`XXSbPm4MOe|y*8%c&1f~sq%o?vc3i2 zD^sZyTKVC_{Gdpw+Ne8yMZ4&ULgIl^Y@1shy zrOLdA8M3C$wA)g;&{zeXO5XnQi8@g(kwqU>w%TyWn7nfKG;2D)A5t6*LHPa`Kf% z+vxIgS^>c9D_Ocgzl@nkfFUyufKQk(4J4Wb3({T7rJ3Aw{ku!g8e zlz{t*^@V1%P)h&0!g0+5FQ7Ow$}WI&x|-^U-u_04MrVBF_b$Hmz)v3;)e5bYB_U3O zKB$Rw&fYfnTaFJ&J{aJat|lG`Y*p zET$_pZA!*oV!R1mcaQ3vlN;Xx*p}-*-Wv#Fj&`?_tM2rQN7a9bFURv!H^{R7N~J{m z%Vd{PCfLku^$#V8Y{Jl6kHp#HWVzY~GZ55+ zDC|O>A;IMbqZ}kPBS!YEbv#tImalz@U&nP7qwqL6JRfL~k&)LrywhGlx3wQ7A1`lj z)YG8^YSo?X?e2QZ#j5)H{SSV#*6jEd7ZmIHmd}N?9;0{PyO<(=?Dt~Py@Tk z_l2XezQ0I;Xt=tX=EuCk!HdTW2m5_Khcgh)!oRZkD7KBy-Dhl$WKy!t&PR%RcDJ^s z4o5vCHbi5lSP_$pg)Z3g#*-!wIZqzqhx`65p2ZTh4=yJlt1*2?!w${Fg)9)8CKSNd zVTUkpT5Y~Id{9BebVMXy0-(%pYTE8WB?!Tqk@rzb*C_#?!5n=)*_^*7=S0OA?mDL9eT1z-I*n74(9gEyL=p-9T4YDdeI`9C9BgtNeO~VNND3Upz^Ca^& z#Oo(yeY7X8>UDp(8)sy1??1&pmUxv6=2n}%fLTLn)%%3H)MK&|YyK`TlU+!f3|y?D z8@zHC=2Y`U^7f${$i<`Q69$%e;I^LB6`7BdpRzmD+7j02u5|@d>#(Hi;Kdm&lK$t# zt${;!i<-q;HZO^=Ndm^BOVT>u*ah#(m>z`arT1O-JJLe+*3pDzLD?cs=? zcJFpFi?>t1uZV2zXWJhBlNoWC>AF}JrCQZD2v`iG$xL2o?|>Z5MjNFvwd;K2TI11& z7fjX&@*KT$^B_okPzzl4McG>fp;Ppz>1Uvm4JnO$bwhpd6nS9j?>*k6v0KCZ@%4zr zA7l)M^90`|MQa?=Vk}TkcXGR|l_BD4;8s~8gB!##7xi{Q4)2htg!~Q^zV=UJ!V$&_ zHnhxIZ!vV|!kURlbOs;}Ov_t_pvK3?iMD7!N}F2nqA3i8UdI@Sj_hkioz zN)~`-<_!(E-*W7K?%0&w9yf}|)7Zc6j83O>I-0FDF(M!!C>6>1cXbJTWF=QuSJ@w# zM_@?E?&alVBCY1pbe>qrsZv>ue6|^5P3ILE14_z4kdpMzL5nn?;`5u~1 zErI4HPeb3*$P_ zvzUbu)AfSqcU*A#v>s58V(YOY&lkm>Mlj=Q`*yF7pr_C1JaF=|t3Kq&U$%dd(i%*6 zdHdtjFD~Rgc1^6x(2_u|YC-r+P9hi}p{{3g?q~X7wUkCWhMP9>l@f+T2Po}0YksX? z0#Tv&c9sHH%pWj(epqX7vA)=9LPf>_`YKnZCc%rRBOm4V%Jn|K_*QokICm+#8FEuR zhB#=^Wf)Ns!`yta-BOLDa>2&2o#|iS)_s!_sNT&t_GW{r+++YHq=}h?4Ij^E60&AYl6X;bXkd519|CRy4$FO6sC#W@#iib9@Y%cN}O_3 z+ZB?*AejlRSfIsI7P7pWoyxe}{4|4q0ZBY>lhe|2L<9SE%Qob{BH(?aql;23l#$O7 zg81gs#~v#Cad;xWpJQN1k)yAtZ;b70csl3jgDl|@#}6M0FK_ZHf!K*jRrR-BUgWG$oNQq;ACEUBh&MY%eLd*k>Dd~30R zfZZ|C8eU$VfV0|3Ht8>+o{KO66*B8Dh`6w%iQJS%UiCKmvdefDI|PeLDy<^AS?tNa}G*)jRIhfZsbTh zqc&xAAvX{9WO9kA5c8SG0dO=z-QH%@7}I7meQCCnBjHo^r~iC+u1ADJF~nuk*kGC{tW5Jf5!6u z9a%yQBtD%MN*Z@}{@6LDK5aRF9W-Q%K3ok;3wm1&jxEN|3M45q6M(T~9Tuw=;=;IG?}Zm; ze5nHyy|`E&CzTdlLHnszY#<&5bB-;a!;0@?_VXCIR{h`bZK{We&|lJ|9Vmym@0DO|QKD+y2nuWp}Q; z_llk_M)IjRa(!jwgkecg}u=o zN`B~!2k%P%QF58vxklrsxSGY|4yd*{t_QZ{13Ce^g4^eKViGbBpjv*09*H z94(}S)(fX^YdJhvX#pX_iWfng^35*#FE9uFM#nHFG-H#4?&uf%bvZ%-u^gSmlS!X= zJnll_aoMImkk&_3p9Mb^`{FsQlP!uukYiwO9%FYVMY&=~5+MArwO%VDM5qZNX-N%* zNIC|lw)jVP6U-v=RDwMO*@@D;KVy6rXi}cY#mp~$R9o7eCr*CivlywrS>oohDv%IZ zW24c)?L9)LztpwB!FMFR{#k}Xw!)r`%`bBt_Ik!sSv9mn5wa$K*lk6neVCkALxCuX zxn)VO0v~ZtCnpDPRMC%T1TsM-JOIT$?zK}|udq8@X8*NH>UPQ8 z&dEijy&(X7RbyLwH2T1Mm7)CJi0`6|smPntK~2Q|eMdVT$LUW=2;^)H?~$errS8KU zzvm-9!H;GLJ0SaNtd++l#8084A0Cx65D;IeslGh`AX;?rtv=!!IOpj!c%whft;zFJ{0v*q#eX%>7C%h ztr)-+bfiYkSTrp=*K*)(-j+|VWgDjnH{uvp&u`vG`^Bk;FC0Zi8N6c)_>cn~9~b_< zr~lM`WOP);!A9Ewn=Tw`i4WJo>BMQwk}wA^Ba}2$OfqcSMIuODiQOJmw|4#ST>!_+ zeYRE8WTtFv83=JaZvE`Z_-z))u)*p73LgZi1 z-LKk1-23kZA-`ZVo^$!UJvLD}zedr=K?fhd7yw~etADG;5p0EBd0J)`Gg!#C^;zBkj4o6z7A)xK^T!|7(E96@Tzvh9O+8&x;F}G$)^M$ z8WMJfxU-KROoUjwza^@eTB@ zq0qP~#hT^#_3c2`ySalj!vFjj%PlyobSa7@QyK5})CG#S5@Ya7n##F(H_gHOq2w=H zXfk>({C8Y2_LK8j1|ou9dNP!Gv{;>bqL;7>XUii8+pJUpo0MCwQjg8SlGyK=^_(`V zPTLc!#6YVFr(CD@6y_Xr^dAcmcbV68if?U^%XwcNoK{!{oZ!2aO?S>ZtCJ}SF64LJ zD-#{dQw`Os+TMcc3-a@0Qd0qqjjra5(W5_B?_6};pOEOsd^0?KKPQoayVcz4tpr9K zoZHs5y+0Isfo7;s99TF&Y^FzdL=nYQl)e7`%m+71mbTZgwXRI;V*PrT0MA*MFP!M` zUJe(ppLMcyTA_P0u;M`@d`5Z%Nip_Rj1*Gtaz_%<7SWCYr4{kRWqAQD@?EeKjOS zSzk_n|M5N1RP%lRMSl+Y1&`-7HB`9p_1UX06rG*iM8nwl*HpK9%PE_0Zwj-Udg^bi z+Siay9GZ-UW%e>Ejzlzo+-xdYoIcbyVAenjk66HL8A!^vF_RU7LO1SbL0L$7F7 zK~jXd@qp|kolomLXfl1z-h7NvMX!%6jlPM(9rK~UzoXCNT%}e!3p+>yWWD?l3X;st z%hPz3(^~h~C(16~KOW;0EWJG&-m%iT7=-)|s`8d}7Dg?tAP};7xV&FryfoG$lb>-b zr#NoFlhzUhz)kp$Pr?EZIPPs!efCF2fSo4&M0T+`%iAm7Ff(2o5`KE$aQl5WULr2) z)gb4QCEjV){RazSy!%n6_P|O$<}btcN~Hu|29`E*mSxl>E&83ah3PghXw z=!-SX7VE+EI30vinjNV7T@A<{Ca@DXl{-Z$1bu-MzEn+jylrs+~>|d4X@?m7}qY2XZvko^z%<-AZ%VZl?*R(kCIaF zZSFnO#dFo~^p`JL{4NA%`<6^CkmzcF)4ux3jf>rjdWy*4!Vx9f(l5JlDo=`_9hF#@_yltWCs@a>6gf%g$P) zzN`iwwO!8$;>N%y=)|C88zJsuC-myoxffm(vRU}e7c8Xe#}&OFO%+?@(A8)nnE7<< zBE~H;Ht;MdATP6rMP;JxxCsXs~DM6GCk zvCR_BawFO8Iw*;_D0y(NY(fK9)E_mSwsX^|-}2nGCr3ya^^H*lR`$YA4@_0P@K&)bkwQvTJc zMG^6;?sI)d2gnZGo~+=pu7@_l{2Lqv1Lh3Yc< z63gc$G?sL0mIXF7pz2$fHTUgE6e9n>n$7a^d9-L8H3o?6zp`}mHhcvG*Z;({O}9V( zU;i4)|A|J;zx|&R?QNVe$pXy(eY<>FY47+r0%Qnf=rn;E3J97NIN>0FAkazVe|p+t zv5G7uRRRVEhVSCym>3xTvSxFIAkkWNI_UdtFnD@0=O2mid(u*axzVpsf)HAlv_D>C zo}QVhSgLFKF+M)t)YSBmn0WpFbL7ow`QBK%R;$GSuH8~12kpPt=HGD1O|%-UEkge% zhXtqQTj5N>BM>AW*BQ$aN9V|837`g#roxh? zKg2q55n%DDYBcq`6cie&DlJ}(IL@cpnfB?ZTC4qSWiTQZ2}yK%Izev;TGh;x)qFXW zdlkZ9CAE|{QpCZ-8{%wSbM=J>L~U1Chkl@a&?=gN;%==A7Fc7I4hKIl_W9_Z^axKvsJhF*Af}Zv8xS{Oc?4dIYl5A{BmA_EQj6c%f z_6Ys6ySvM5y~w1jQZe(?8;oMq?GL9KB^g>K7nDDmGyH)a9|igZK~pMps|NJtB{7*Q zRKvUVzs(&twY=C>M%sYfKBXLmb?+{F;>pZ4 z6+cZ+{(fBdNzO@v`9ere`cFtlG2`FnBsWgt!z}5v{%kSj=y*%~u4}Q9BC~NdbYv3N z+}ei0oQ#X>z7|B+msl*lm*34??XioQC{gFkL*y9%+uq?Vm#SOEC^IbiQpV4pvmj?` ziRN=in-q~(4mp<*Sb8F5v?NTuvnE-^f`Q}Rc&|BY;qY%%5J+C7o{br}lN$QEA&epL zjN{~riq)A3x#MuW{T}CaOumk`s*{%THB9>(ZZ3zjh}Yd`Qd$xMGe5e*SxKttqnq70 z7N{s(w<-xr0K>m6?Y5udH&L153SxD9kTM<+?7{V8*cnh*OPODWNn(Av?_5OCs2xGX%8}KW)xGK1YYsLkQp`zQP==g}=z&Uuz-D1UL}z*O7|gfWz`GkZonZf0y!aBdp#b zSLKQA)~9}!t6DIkCh9S#zIzRO)nV~rBI|eVmyO&%6O5KuKl~2)?hC<99%$eaWEnUyUeoiEU=y2kI=2r-I~Bvc;X3McPaV+Jk&qU05u#o+cljjJ zV*i|S5kaz+zUd!Oo_dGj#95G=OIGeAu02P7d%_*m>@0wE5gSVm7E5>SHplSW?qu{H zw5vgN{=^)+LK%^7#>#7r5;e$9{`aA0Q>BndEiENy)QsY8r6xu4*!Iv4LFsZa_Y+?C zhK2t1y<=-doGNP0=#ROkEm^8nJ+ejm!;%yN-0?$qI$R1S{3h@Lnw4s!*^Ga_(t2er z6(}(U*MI);$T?tW_(N@FQ`Z6G>Z|K%s0d0&s+nHqcOZ?Rs`wQ_=H^8=s;EQ^_iw*- zzhI3{`kn3iwG{U0vf-V<+m=@M0_ib~n|_=&t{a~Qn^g(b4I!?E17Y!f_NN*f0*6Kp zQu(*V8icEU7{D3?q8^u&1{*WEBov)20BFYNgu$l%pHW+z(j>m@xE(<#$Uh$o!%tnJ z3v&i0i1o}*bJ;2hc$ZCXB&*K^oFD4BU5g>c1!gh( zpM;PE>GyWX6;-+#_@7%^4FoP2wI(#f3hB9eUV0&m4TsWJT9eH!;QSpYEiDdN;KE*3##P1@^&(7!`jV~SY|ZB(*U9kh>LhNt@fP= zpa7veY4C;`ZtZc9*CN(bJZYY-v2m8Yw$*zP2V{y-@!ket5w{gITFUOYHm1c6FUz+h zj(z}Rh+bL9EC81EUHVtaZfoYx2ipsenHUk=lmR{&n)X z?Rf-&ug(pQ2myINcuM48$BwG^AOHB2d7?~Z#EE9y&4laqsjYhy2`KeW5H37y;9kMl zW?2s^cgbzH zx=MIev+I2^atO{Wr%3^GVcUrv?S{J*=xbk-%a}Oucn@u(xi*iQSe#k;?424~N8Pyhe-Ppc%kO6Nn;sD928fd@& zGl^c(N{kZ1-*g*Y(wiSgVv!dmbm+xsC&V;w@S_h1`4}JMe#9;5M@@4*S$0@MVw^3x zfC9#O3jr9X2Ln|>NU4Ba*wPn;lvYXR+`2~eWq}BH*iL0yHO6{hPZP(p^>JsTeJl2XkO?+LCza|%p$O=sA8779OsO6g3ENoGm}iIaeK}e%zV+-Q zjO&Ren8z0@D&XO#kRDGvG|eQ_&^mW-q%y&Fw$890HFYQ9pO)KgwHMl zBxf^*Uk6E_S0%oXMaNoCZ_nN6X8N`1VGp6`|27#Ku>&qt&~FLI9v~`m*SNe@Fg1g( zLlHs(fdmnk1Yd=S7pEc{U|o0mjyKPA98v;ojW3J4av4M-sk(oO%^Dp+4s6sYH+X+V zowQCZ+fu#yaskx7v|{cVgwJR6Rg$wdC8CKs9QQY&cRxYaB)}(LPHu9I)8ylIyFQuf zX)+^8LQN||<4e!h53~e6@eOs(NrC_Pv?7&2x{RRypEIFCT#?03t5wH!P;jfji|a!> z(;a}IQE!Po5Jg1mV>1*-alFx)1vRQ*;NZ9_oZxA<+vQ57Gu^E~ zpq^kN?->*$KE{?d}k z-l(52WyOb^o%c1G+CubEIT17<#JvB2zL5hc?ajr*Gu`RuhqVhH&sJ91z1#4k;^if< zv$KO~fj)mE25%-i{a!t-v_cyvv*|iPBg& zv~-T=E3l?!>t;c(YC^qII_X`M4Fo`fW}NL}(c{wCK3ey|hKa*j`){*-RNdU(e)|n7 zu)^oUAg$D`C+?vB2kG|}#B7BNE6Ym$&vf|x?f->y;Kz`g2!~pl7#p)WzyIfF)aoUX ze30>2b{q$w-7g<*+aR7i-DJ6Up-A0-CKHdqwcE=j&M9tVPoO7qt@qruR@AO~ zfWDaB$IdsywH3UcvmguvSKd7J}Aq8aMa?8M^VKDqenSY!GEIM;g?fIp6|)`F>(B$2c^ujmB^^e1GN(d3>lho0KAusO$}u{`usjKqwF|)D3rK z^})v-Z-v9o=;VrshH>}5NYrB03y(VCqE`OuA@lo}TpMwv3)gxR!>pgv3oYVJGyLGE zN8ExJNZcKd`Mp`3z9>N<#ZJ_>BU7*^}4fW;j7DqBOu155qW<(#R{uC39!4%y*cC7u9-n65<^lNC z5Y zh~IB!6Nw1kC-2^c7{D;`4?U83UEX^|Gwmk<+U9e}Nfqr|E|5?en&CL%zERlBID6{7 zGO%VnCh@Au^vk`)@BH1?=?#WNe@&4r(8aRVo0lJYJD`c!`@Ip{Atmda0w9K?i zA5gK)c-*Xh+b-Fn5=#o7Y->FvZFk{$Lzdo$%}4#tL!zAaTSnu1xR%j=eRf}!T2?-` z;5~IHMB_-Xdgy_z!foy7GU#HZyU*u>X9u{Txf(B0A>AKO;2!WT2Cw?fpL>-O<#lL{ zEMQutSN`kMb}*Tw=0SlatsjPwOe8lwJw4sk?Mw(n*1w&me&N?nIKWOpTC%53ckw&h zO@LL5py${oLNsXvZI@&SX@16RC)J8-+@({zFctigKwo zCNnJ<4h1#pb`A|P1Mj3G&X@o_MPx}Yk(R2u9=;q2A3F}q3`;dku)qY1n!0;#Grh$edG@*_ui1$rE1WjY%9>hM&f{);Sjyt?#T z4kSPAak+3o@Gpj_Sw}1jX1F38`VZ4Mj_yaOrN@hktcx|fAA>YWG#k!~w^*^DMq5P0 zVGx`Vdzfm7Dr~rBhN!6cWvvD?@9W<`)_!C;Kme088e5Kx9pN zAv+rdCHLK(pKmUiWwq}FmVZySR|6|usn$_(?&TNtnIV0?cOAmir*b)=toQtc!6~Q4aeX_6$5*OU>)nlDx zYyN$qV|jqB63^{O4jWFIQus?$l>Zu@zZkN!zhDTbY2>3a{L`*+#bbA+;`@ni*O-8r zI%JjLDa~gJ<==d;sbce|w-Xz3uBVHjd85Y44bxk*+v(!z+B*snJgH#1mm0y}OHz53 zoX+SlC_-)m18XwavOdf~D;rCajwpa%JOG?oMb3Q<_qsA|1BBX#uJO*zNbU4RP;<<&q+X#M(R$|ixkCk6}NZOP@vD5 z0zVZl?`&QtVzo^SKb zB2U;V@5d>Wj?CwI-mLVvjHWv>GB~}A1n_GgUXDKU)p@cxksQhnup51vRNlQ0-Yw_X z{+51t#@a3dSuYwDTsQp_(7A0yN6zfXPwUJ3y>KGZ`(e+W59_n@r@ZC1;Sr>>e7lG5 z!S%O2szzV_RADKn0ixIH;pm^)pBfC|F*8*>-1gLk>y@*+&ypZ?zh#Y9N06H8PbAk5 zW|C2Vi8;!h8C>o8^zFA!Z9_!8J-t8(;$_Bk?cu6AzWU!MJ|chM)u?}xlU;J&ztM2p z)Z?q^Sosm`Nxze>Ve|=|Ka9h*giv6!o6Ksx@C?psbuV{8O~z4mUA&6h;`(3-Ll9w* ztL8UIYP#BDC7PHRg{}X;{CnD|Lu~4Imxhi%hRPfsMoMq_4dEk3R1` zUGR?S`2@Yv>+}>6bhUdh5cAU*nmC=|~035DHHxJ(oX#^;o14Q3bY~0Z)3F z9v24i@3732TU_~Ctv~D)>Fpn(WHEbL!1Cl_+Ug29<4pogDaa&m_}%y7ak*~$sH}Bc zqemA8R6Bl#(eh_$^=88AU7fC0-FsZw(XFS1tkZ|i_Y&`d#50W@JAXx9!T^rA#^d9-k~Xnsy!{>UGrnHNn&I5GJ1N2X>TkP)xm>EYKXykL zI}HY7NKuHAi_I*DaU-rnSN{e#244^UHIE6SH1ua5k(w z5I#qb@pAIA)nyjQW?3S~qocjGJ4*Qfp{Yqx{RY{bf{k4-etK85#=L&p;j#)SrR9 zJw4C^WutCLY!VX_HFmwk^7y&AUA*+m$y;zs*}fhz?Qe__g?!A7y<{qi$>(4B=S)pK z?Mp4bD}oN-dr_IQ-QBSy`qx<{w&bkV){wasXIIzCOMYlt&GE^Jm9!rF zm(Hry9_{YRD9=t!-?FQ|VkuDF+E%W*12}bv@Ohw%UShR<--2$z$#|_QCyMi2;=c75 zWGE!3_Gn#&f&Z+NWA7()e7pF&UT>rD`D?S~gyvARpRaVckO| zp#g_)#<;h-l9~nItawAMX{B^-MLc-r<9%T62Fft`Z50Vkm z#ib{6IGQxjT65DK<-Ity*oBZ%=G>|1e0@A0LB-n))(Xcy#$S%WMsqQCl@bZ?A;Cvb zgGZny&-!6tCiE6=D)ex5tr^&ka3aY_tXz{d7v`__6QMV4X}h33tig-4d~jssG51Um zb9acRjqUW57@UHIlZJ+EWV{UpKtqN)@Gt73T{;A(~z14O_-Qa(NCqa_YDm+nbPbR&uFa>yUGCy8@atVQjm2(k2l5@ z48e`RE=k#mnkH}X?fHJNzIcxg3fIwRUe*A}2-=lS93uW(9Ugd=f=Jp5Ks}b}e)Y+@ zhQM-K-vtYAOaFSRgwNaNuYJTM1cO84+Xu1gnd=FXe?-geqG3pgkGEt$e@v!-dC0E zD5U!|KNv;9o!joo^4h@CMwuq@qAs_#I=P_<2E*fB%$7juaG=GAgDKJQTQfA>PsHCC z-3YXAVv+$Pm1GWWcXAk1QkPPIx0ncUOnoaqV&aLZ0K&eu3@c=ES4$u0-|~7gf9?vc zLdh@42R==h3vgS|G_K9=rJN8SjMSmpI$tw`?Phb?aX(^u__zAXQ8aQm%nt=U;vF0; z*MEplTfzhzcCCp8%v2g6MQeCy(&_!GnZR3>%BWHj227gEZmjWQ;Ie*3hCQthET~`7Mh1 ztd#UH7C%7ik!g`NYi%HYF~LO0%Iq^U@L+&vA~z0@Fg&~+l)~n@9O%L1Di3v3dwJ~H zD|qvmnN^~>kiS~9Sjl0<6iv;vq!M5TH<K zTFDGEw|8OL+|m~xNP1b_)fw#U%rX&A1xi|-s)eopLSOKh=H?8S5uXWV{RPZRZL-G3 zdK(bZU}}o=7H?lsy}byA01X%3^+O&o>z9SpHkbB$YS&e69{&(Nq(z4Vx-u5!W5N@2 z(+2I?7^(f3j{-y|A~D>_6$&5vunx>I4#ect;A$=LfJ#d^DyaSW@$*yhs4orX<2y;2 zgS_{=m^sWq3LZ?%`qgABuD$HVNx@ZE9o08S+v7#Z@Qi}%BqY)Z6~EU8FqcwLWXBs) z#y|r~tSOGQOP`X3(=-D7vUvk|gD^@NH}`HtdsVRkMEqph7KwoFDunRDDJsTIO853;{$L(S@|G>cDzJtaHy&f-E)m#~h`z(pjxM@qgon_OAIllY4KYjAm}tL#Tef0_m|u_zM0TEsW}8wldx@sfhNihkZA?cY^oEC2 zByqp&W`u3upnyiorFMSvLT`}{2BWV}#29F%8N^|>#H1D+ymB#?L`YXJV4D0cp;zuG z8v9N?(E;5-GdwM^=XE|)Z{ZYu>xpYMvZf;9>3kvR4#hKsbGN-?+?Xf={M(OZS3uff zEKZl@C?+R7xw7^PiM>oxpPD(wpAjO!)9^EApO%ygC_qJt=XE8fOGBJdH*GPa#Mjh! zStpfETau7?>7AbACW}~0vqbJMXtDv6u7L{BxI`C zINdU}l$yiYPEX*LxAH1C?^!fKK$VSa`LKFq#Mmw^Y`puMi%RmCg@v`0+7!<+Sf>S) zvP2XgBr%1#qgZ#!R%wfTsrn;SmQqov4z-O4WwFSlmQk&HVF6aIWYT-A?BrItlqrC5 z;rqoOk|K2srEmI=d*1A$Z?oclm)Gdcg#|~A>0HPIAr4ZK4#KKfkH3f$P4n76BypLq$m^=L!!bjcuZ#+a<(0XewO(#&X4`dFT0wSv7Qs zoh#)o*i%0ua&PKp$fQAow32>W%9N;<_-KKBQOR^K8JpL=GEA661z=|UeSqbzm;gv- z{gullt{K#e4m-Jmp- zjTYm7I1&Rh^9D3>?uXl&Oy?ZEXx5}>y>G=SYDm;OjtJ8$?M7DTyH^QPd#t9CriICp z>-6S=bEyVJ5ek)~RJ~Qjd{M=xmEl_!(Tjg^DIt>BNf*w2V_a_=N%WE>zuc|_K6&$W z&bOOtifegeC#LLZL$`8c+&L?Db`${|5|kV5<_J3rR9@T5FSXWFFVziqlrQ3-=!`}% zayly<8IsHAVWg)hvAwIt@T5{JyhhsT|42sc38#!i3H0~(FAOH+05l$(>B}SEy}3Q~W8$5F6ty3``X|36+*gTx ze{Tu;9d(9mg>YH)1pLb)&uoW_y-4P6=fR21qE0y=S;0qO_aI99n*)V#2tDXma`=jN z&Z0je4GnWFmB*d=3!ErF9mL~@s5NZ;Y9@`!VA3Ggc*AXu&QGG{1M5+?RbLfV$b{-| z0sDlDnsH>iv)(?A4nC5--V=loH5CA{2Vzn7yRM5u*7GG1D% zPg-e6(awtN33RPTxB%(7Es{uMdeiI=#MytWs)t zvMmP0y?kxi@(vEX7pWpTOF&hd_(`_~5(h49M!5sSo%Gd6TbG8%J`309=ZE!{Mey1qY8XkTuS7*PB!8hX( z1e+5#Q9;%MDTTXR;$MR|iD^=ZYWlzcGZ-UQSHU1y`foR_^|_2;bA z06J98H5h=nR1$@|*87JCWaflt$Mg8=SrG;bN!zB@V706o7{8OLL7_Of?;;p=H*6nT z3-N48nCwu7#?zM7U4Ho?r!jUdD}8wM+e?yA?qoRUBbV3bGzk6jrE&7deq!#vTsEYY z#=dGE@`zX;Eg(5tBK-wq$I|)U{gcEx@z8NRPFK&14VA_$xxbcIy{W_xM8C|Df&4ji z4C8SBl64$1e##&n2*WkeV%pu45?6{zcP{hfSdF*EiIm~c-jU$=v|R*A{6J&T(Gc5h z5p+WMrev3>A{AZJQb;N!jHPtU@9}sFqdjhF&($8|9hv#j&y1(pLW0}XAFd$ziE+a> zk;o_PmDtr(HJqu#=|n274Ye5K`lo%Ntr9vz$5C_ZlY^-q zJiu4L$wmEfsl1cM)1$>hBog>GeR=BQJ5B2h^bqTV%@X?(6X~l7@@kr;^pY{{YU2ze z$Pf#PF1VxI!NsT=x9_CG{@_azVaGFB6f7r%)kc`Ng-CAuTOnNgRMO@sknd6sKON(3 zQ>P1c))M)Zn<6ZvR9OBeyIY@1%mR$_xOw#c(hA4akV?yWZfK{pdGlY7MirMn>B8H5s&_2)k+i)lIQ)DM8#W40c2*bz;nC<} zl`(;IL;+e4EVE+W8G7GFo8PU!>|@a~7@Cdny9Fb3j2J1p=>@;@U}9DdD9Dc4iIC<1 z8Qb3~2Ip$jYIHEh^CECz5TtfhBK8U#buiKf1~y|Brl?~jikbv{0m=L&_wq2eM znu_BWd!}Tpl}-g&RZ(tVjykjxS@zFQT9mGv=>tE!eTJN@sNYI$p*cWvT3L=_p`bFP z)@Ee`8V*8stlbz9G}6d&2CVY9{i!tOgh*QXfp`xquFe*PD7ZD2_6BMe$Jsk)4&! zI+D98x0~%8{WAPLIi2~S^<^|HO;?K{vxOyPrL`X>3nZSCffPfx{D;>aBU`?Zb?E)7x+<)IuSFL%AKdO<&P^($p^Tb zv>4dpLT3RjpM{4~_5(3=D+U z>7XU`N_(i|qGI8;AbIows-(Q(;^K1L8$G1iSZKdHZG}2!3^{P2`6=ropVIynDb16% z8_!dS;8u*7v#Dw^i8h)|5F;XuK~-*1B!aT;P00HHF<>}6S|Rysn^gd0l2iJ10wcoBdu-Go3WaFg#1yd4oa5XLa#e-C+uAcY2|$R5JE0ln}^ej>`$3S4yWzniCKb)o$t8KDu|D zs=6jr3`Lw%_H9Mfh`ZmtvEXxXXR#q}%8*D+-7XW{45&&&f0z!}HnMuIwcP0N0qm~< z&7!f%pjvr{ivM*Ly}9V)=0C-KjP22~W8Mzzf2J(!4r~DDmdn3>H45}TbxtTOPLk@* zjFO){Bqg5_eoz0#83E5P*7!~HF1_nIn!|yzGiMtUg~IKO7x{WJ_og{{gT@+RDa3cP z*#Ypup}x2OKz7C!)7=AfA?1Alr7k-N#j|At)*?4zRkqeVA<`q=oC)~>c6Vl^&wtgX&kzooaK9+d=3&$@EZd8I!lc~3k9`PCdWWLtezvLUZsWOw_L zm!;W@r~UqDJ|rE!Sy+?pv7yrNl#VlaeGd0E7*$Ezb#GBr8t;nEk6cT>jke7V%xZhe z8@Z7nyXv?hRo4)1w7rmZl~tn^s?ib@3T@pQ^%)0cD zmEPpjjV@ifj;fU8@yA#(Xxq*SjO|8Nreoc^Y^Oo$sM`+$k ze!b9Yc01Z;rO$Xg6rvmrE7%BVv_Hrz*xleD*$wCH+>h8;D_?#3+N*>0ZTHtpyanf; z)%vTUV7x9gV`mcTT~Uuj)~RD~bBorLDLS0WgU;s94h>&F(?XQ_L*_nx<vtdB-BTOlYf9N4aLX%ceX|o&L^D_ z>hQZo4R%KD9ausQ=q8Rf?M?N{Hul$!s`8H1@(KnU*oC)?f8w`$L@Sd`AW}CmT%t!c zKkl!kZnajgY1>$U*EuJ%rlIy6@;;X${xlOEW#HSiw35BB1SVXJWoAu6cj;EI5FWSn zO#b>zcJ5jY8fQ-#=WHKLn@I}8Oj4^(_F(juiD)2W^}Ww1F@ai4Bgtfhea5q#aWb~< zxRpLl_7EUw@oJ0ku)6kt`NC?&8Y4wv^yfYkiuV!bJd3ju|Tv2{zZh7QOpGXl& zyVn3<{8gQ>qi`H*xG*h;uc~!ipn{wxttlKv{8bE$&$X>rFX-CaA9j4l54p!o_fpM* zG9V{T`%&#$7QWmNNQ>5XJzU*MHDYU}RLTM!J&8Aoaa(sHfmq$)Wz5X!oK?1dR@G-b z7fRw)pL57QIka=Wo{~DOgbEw0fv|Cy2VaTz{n9iaYAxgN>o@DItA;&9KIn z>u}!34=TeXA<_g8;SICp`j^r3@qzkHIKvmL$w?PGk?)7`h zZb4LPjM=PiPe1VThi3u=m5v?@0uu-a#x3R?pqrD{g?AK`vD{+aCzOkY<9}7~w{vu# z;dx2P3KQ#OBMZlwH50%00UNsV>=tPPB=c)HFYXIb)@|`W`-ih0o$D0Q^WD(NjwPu$ zxLECqyr5DDzl^$BUu?WHt$0hoDZb#6W^9)eWh=LUh00787(1bsmBN?Y1SRx z)>=LjS#sKoy!~W%YOp|oX)6;JuYmBezxf%Vi3n>n^BFhvejOnkt^dvY{p+TAWNxj{ zsSwY&UdI9PhTmXjvPygVGj{*eHIs=$ea}6|2X~3QLwqORTT}70j$`6WB3Cm(Mi zW9m$*0arsXyV~+3HvljD(tbi#mf-lS?w5rSA=$s&xgOD4!&<9uW1k$c^t%m6^holU zLga*p^UbFtN>tN%7k-LmBzq#p_})M2zbHYE~`29u2Y`W-7vb4hd z$8~G((cp#!B`}Tmd!~8^*LYWM5MF~ZPP%wPQBJ^{;CSg{_V{p|g8SVr$`&(^)ClB# zJQX^GXTfHeG7RrqWHl6?TCCyd8QeXbr~Pj&jLj0I!BX5!)eOX%KR@!I(uock1ROHA zGOV=bKi{+e>X#Zl;D`u7hx^p#Mez1gtYf(UMao>g7!RoxrBDH)_ca|n#z5i)5PjqB zkP-{<+l}2I?4NTGxe_Wvfg$o}K`xl86{EAfA!2;N`?jD+sd|0T>wA|(N1zOE1yg=O zP!ng-Tp8D_&@9)H9E>z`z;a3G5kg#G<4NT0{EIehfQ?qN69hcx+mej*%zAH}($wCB z@a*O}Z8L$kQxD#b3}&;iU~a;6DwEAN8wz{k%*LG~a-Ht%wHz&-FqGCYJEW(9?tD4^ z3 zjf4+Gqo+`thS%(L#Ua+^>_S9~8U$7cqOA!M40hQYVcV2BZ^?x}JT>?t7ZB-XO5(}Z zI?lmK6G!6Bo~V2dzl{gSzDhR0X~>s)b#fZzZ7QFNx8SgDUu4lP;(tOITA@K;f1b|s zd0{MK5Kp?oW3)BB@*o?p_nc%HfmXEfwT>0NPZJaj;TAG!3Y zIa;Cu`^Sc}da~|%qQgho{CqTf5w=*hWcrf~pO4z<|GGGzz_=2(^s27d=E5u4rs8Fu zSx89a*;tT2K&2Ws$4hs@n?ZKi!kXg~JfWL~U2kOhL*?4b)1^|nMXr3cR7eW~DUw-i zz!%SY%F-fLt!8BZIdoE+yShGdU8zE?<41=;b~%}^^#Abn)=_me&6hBQKoT^;o#5{7 z3GVLh?(PuWCAbsZ-QAswy9Rf6ox}4!?{C(8-@`|U#PA5uC9V&9i?J;SI_XWKa5D=_XL}tsSS{Ra zBBGUJP41ALFHW_LGuoYWd;6QW4JN;|S%a9124i~QB=-$L+F@bl*-VX%Os`KFKXSEdAKXYA}~dAE#Fxv74XJrF8 z#C1tjcZSfWnG3i&%UznuK;?^QGIqgsiRB-Gl4YJX?SG8V-@E-`8b%A;n;sCqwaI$Y zm;}w`3Z!rjXUe2w=T_0Vu4v&wrXv$e^Jq%xcYbP>vZ4dNs{AHYc|{yztMi^o7gDf zDx{%kXl;X#MEO%_aeS34=}A7EhixP z^Q;TM@tJDz2-8j}Wpoqse+=@bky!GDU`Gc(?1_g(Z^g>nMfbAIh(T65MJ{|}ENPI; zO6zkqg4Z6Ed?5J=v>9XD*oqRfZba%!NrAY$U!O;?d>!N>b2rksNwt=kHJa`5kp3KN zHw1h#GE8pL#kG_Z%qPBiB}Bbe2bF+UmY8^QCovlx4z)A3MhalinH!%Z4Rq&c6fUtu zGu2K+YrJ{tR+)8nA`5b$dh%*Cn0~aQw-KtfGT!T0t#lPlBgn!ux6jJG(iBLq_ZcLI zg`3v;d};H;?Q;q8X%U(*=Vi14sF+!}dDIBeUU@|64km>4wQIP%6fToSE4;@Hy8585 z2k%4Ber$<7Iyl+fGm*YA%CTRix|Vbqv)yEZYtDsx6eotvkwUbqL7+*ek$luX)_Uvj z3_vn=`NI~?(^~;}Q+{vViJ+X_c*7CUVEgwYNB>jT! z36vqh+lEBrF-Ez30W+xd#_qgjp~|6K#IwAp!eFpapU9j&8aQ(X8`NLsRwC*RQ)1L zRT;DRe-=#pKBgIuE8h3cN-bS07AD*nducKLwiOnqr|UQ|E)SEdq-F81gZV%v=lrcK zb%*dMq1=FBT)3~AJh{mQe@oeU_s;D!W+c&!?e90)h)>W`C`WQi9Rbu^K{aJ_2E*)v zERQZ5yy2qmgf^vGnb7diIzsgx08;3PRigYVewS(2+Z+=x*T7MC37>toqzk(!8>%hl zUEI_qtP-E=euhYO+8p~6t~thNR>kb8-BX?c;#UKn?rBEoren$9dK+-Y!1C_-Mbfd6*y+K$GxA^3gxdUN(vFAQcp_)aIq2TC*t~mD;S+&J;usuH z+6v?KGnBYnkFwu{k@t?{Zbn|$a`3rcBq5aLz^KECpVJnn7j;IC&5T6YF!S( z)7EMdeb$mit{BcRtj~1sAPJi-OfN!T?kM;^Uq}KZn;v_6*9VNf2luj?7s17a8KuIC zGBPsZcXjnrzl3sJNf*QlB~^y#;@URO9(X66Gf`*Jho{|@+3T!HgDL`aGODZq$)!#%-A(AIdM?o#T=vNalW!B92<{(^&RE!WlYyHsiF}Nv?1{{BzZG^8MZ5z~dr<)GC%`YBLZBUz3 z*71E~!1hA#+Ds2iZXXIxjv%yJ>nl`hM$e#U8xoJ{;C=nXNbfW#kYK6ZJyZ9`q!hkdtq6p)s07o(I#hLYM_7>muv4)st-p zcW`16ONEOOopIhG?oAh+|B3bc(b12hjk$fad~CCU3EsKty8v^U9urA29uJ*b<4q%ZDyLj8r5A&Wt5i4pez5x(|oi_8=K!L)Jb^z_lq zn|H`&`kcI{V`g>b1RW~XeL6JC@4s-lu_?w+`^gQ+)2k#ly6(nJMgl}Bz_$5&a`Mu( z6`CDQsa%d8<$k$6gw7NcLIXkiX&3*^1WV|(B}(f6aRcx70g3!bZqCz*)$x-v6J+e9 zvNm9m*a7)DWGWT9wSHQ~VujX-7wVB1LNt8*uBmOpNOpGit-pUUc2G3fHAOyTSYwI! zX7LWe&+Yqy^N}MLK)=5s zO*zsZM9U=XGc`U&==iM%_htltUB``}3{bz#vH5^2XFDqRvPMsP^bUa|hDJnKwgNvL zQ*lzJ4lcW<1-%9MoA0MI5KtG~QLA>*0|r@UM1%ORDyxVQa3{aAv9k+5p@RMIKLQFZ zThD761ac0kz*PPf7yX^SpD-VCPyFX!K~w_)F|;jZ2_<~uxc{`=#Dq6C=Kh}Qb3u+( z95g^4me5GO#z77By{vkp5~IJ#C$A#K;HPj-Wa*mkf=(Cm%bwJ;vWzl+^iZ&15AGYl z(+xk34wMfsNy5E@mT$VKYo{W>E#%^E2$Z#?jNyzRoI_36U#*dQe9~U9T|V!c%NPEX zywv;=BTZh%aPMdN;miHjRG2_g!~2ZCSAT*0o);!6aoHlBtS2SZQLk`4+y2x@gTrpw zF}KWA;=k7M^GEa-?GBK_h+e=WLG;tSbhZ71ObSiL_+wLx$`ldx5^dy-+2D`z%$8w7 zYf*zu%WoQ*>}iwgwQ*$2NpiPPrx`25j}N>uI|6j>@NguVeIt_m(sadUkWkol-<9i( zYUkbtGAV`RJB}q2a5O}4?hLNeqk+N22mnqHxn{U94^R8#Y3t`9`Z(R6Yf2q-Re^np ztS^Tu(G{~Q{p~j^8JQT;b%<@MvscC`3feyumj%)??xB)mYtC@3UQ8lxN;+^4313Zq zN4QZYR9$X^U82l@lUUI{gwO}UZ9lmpv_NflL&rbOszq0T^d2KEh2y{URY{B%y!Y%8 z@zc;0H98#V=}B*;qQ+v`jVRBa(b-z>xp2%qMp_i5i|FbG2CStYYqDG-(`jl-q-H0d zS2lF7j3T;MXegZ2#o1d2=x!}OI26kIt{kk|R@QfpazWB0k4zeNfk&32OVr4z+RUr# zWe}jKQaBke229-TW+A$G(5x13_x6AgDce3RQaT#G4iyyAy9muKE>Ac8#yQOKJLZ0> zZXLBrDRR7w1t~`5C9}^-nUc#mf5oZ@@UHZ}&v=UwdaCY~*B9QZ)4gDjzCfY(ri=zB zb82i^&dTDy<0xD;z6wp}l9c^LgJZ9U(u7Z=*gVCQ(_P1_WV7EBmHNItHe-PBm=`NG zsmzC{C%$@|-p=rnYV&f%3yuIRErK5Owt#Q z^oSmJPz`6R+oRew7z|e=riZjynx~20as;nCXVbd-45;5TU(^k|nyHWn_5DoyM5R_3 zWaW5Bfh7^}jhX7Z2aMR*!8B=3n>GWip>A5zdZO0TT6?otkaPr(1DO%hLkGxlU)X`kKI^l;uWj&|g5f_4AMvKQubDrXj0ASj0{;YnC3KDj$4 zg4#w7%(rNohckYUN`Em%7x@(g8@>lfXuy&lV^v-c5*#)Q1{UEJJCkVlC5OM?KV8TZ7wS@V$6TG>B^e38_0mTQY`8MSeA{%PLY zQ^qM2Ekp8tFwoHw6|gxRzE>6C^AJ3wvzGi#Q)i8_KjSiyvaPtS^+p+PAMC6dkp5hA zo-gxDfvmvFmQnB?zuJmriQ zdHp$^;zM2+`ryxA5?Ng-D}wg=^tMRg&fy*h`nusaTz$&YvA-#LP`6xON%rn4^wy?y z707P=d7Y&5vuk`YF~tg@Lz{?E&t7UOD{H}S=xO=#CKTVV1u}ZeANbjzp&|DE3foH< z!%*r7C0?BiVJuGp52yKab1aNC`|tM8()N4F-Ng2$PpikzeJ?s z>9dUeQKz40wZ6Top?WDo>+xD23JCgxKB;GDC`1MwNOld10%pb937xs=cuo#qdmz>_ zT(eH@)7eO(!Se7q_vIeb{$#BMSF3xEqDYon1nn0+(reETi#x#lD~z&&Vkq}&+6^72nZ5sa4#f{#Bp9`BIZ zMz>!I_qsQnx-?iN>&J!-bu@R4Fec0oFA*JXDcPU3hKN!C!{MMVq~&vYZITl#!@@0B z3s01`;UMw?MnXcuml4?7vN-|+0ww?Q4o1!F4zQUA3x$b4O6WdaRLTdjNp45rDd1Y9 zbZ5g*tkoULPCOI#yb})+XaOknb4`7H^OFwLn7L3$7L>y9u5TVm zxcC!p&L$S?r^%h{f!^}c5|)f_c{NpI6$AmTH(xzcYrKz4b~}7Xq$Zo-h5g+9Y=O*Z z`fZpyW38boNy4CH9mSeNGDjq4p0!+s0~Gey-@YOw|F#-)Gm872-1T2OwY0{1^UhZO z>s+EbA&XR}=<|RHg4i&uHb{Fkf={%l>o) zN`U5?+d8%Vw6h;?J@2*d<Yc$7cwa7aZO7xLjQv$up^b$PFrQk+E z5h&LnY{{lpIp;*7PzY|pfW~h(13Er?mX|pJa||?NQtq9dNdugcTb9pqd18Ib3)+l$ znS-I_lmLLUo$Rr!_rx(WKl|?T0yt}qhK8KzcX2Qlmimv7kbN%RU;ZVa@$dtpl_u{u zEj?*M)nLh3g#VcS_ixefZf|2B(G&ga(_X*<4z2&6`6K-{0`mWQzSiM!G+vtjeFR?s zwy%EZlL*w#Bgh5K^j>f{^HV{FSN=}uBNlKgS~NBjWkeC6mHxT<D~a#5Mc@#oK<+n{vL{-;bfTLO4vLSU&r$20;mbgr+@uB8K_LOWsqr7^?yVsz+m%AZLSL9R>$L38m6UBaa`AEQykIOVGD zf?SWFD=JBeJQ6zERNuYkpfE>zMBj&4n+ENdOfve;}+bpd89%xx|!VO#HqoKrW<0kpbGULM6Ij$Hc4X zg2VzH5694`K{S#644!X(;NjC z7j*u&r^)dMRXT%9^!VWY-3|o;aavmGN^qgAt!Q7KIGR2;s3GRNp6F3rW+aRfW1$aw zgYxTO(#s#~7bW8JdyQtrp^%_-VkI|(YURV>=U8diw$2=(uiyUYwLZfHjG-V4{*)aZ z;(VqO0*vFKWRZmyTRz>uXg6vD)y_WM75cA=PoMQ2`LURk>Qrx!%lK2R=$iZ?o0&8h zaV`Q#b(=>@FHvcu%5*ZUKkkLodkPY;EpT#kTy;O&J)HdPZftjiT~7r0mXtvnp|Y^$ zfyBObpoTBK`Z%Muh9@Skw}SD2$mv)c`l!_*n?byN(|5{!n+|IPMM=EgJb?6G=h#>T zi{%p0tpl*8!3I4`OKQLiRf;at zD+=Z7k+pNWT=&kO%p0hH?qP&$n%Lj-mfSOYAF;Ua%bjGgXO^*-8h;g)QP>P@ejLGS zZhK()zP3k=xKyIZ;M4B;1b8m-gN*MD=ZLit+W)Nu`27j6Zz{I4+Ym%?ZGv4i+W6J` zO7_p|-mW?nzk=K{OjieNy4%6Uqo}gWQ=w!Y{;0f0@)wXgvtU$4QJRFEY*`(S*X{rTT;gZo1 z%nQ6Oos~x0a2!rl`zzM7bzpYN%F3$5@3svwI*x{k zwJ}g}0IpHFl;3O1^23J@pFcMWR$9|TvlnUbzPq+2*qz8?8-77t_EaLe+Bn}DAR4jK zUyve(k={`5Kc&c)4typxl_Tw5#siQv-WXY2l zmgnTVZ)_jm8tUbdA?b8PvVZmI(D~{GCe!5CC1BPr4PHtss%>~9rLb5I1Hz&2(tasujvZkJkr;CGRO;fe+RH$-?($2vxu1Jf!d5!XlQg@x9|EsxNbqsaC<)U7txx z>Y_T5@_@WtgLn#ox48xig!+oTPDb}bnuX5ml=>J1EJhpMDY|EE+F0^^oNKav&W|h1 zzC3O_zl?T`vI3ECakWi_{Zb3CFt_MInl7O!>-177vAu7tf*w;QOcKcq0f4Y+rB2s} zTD6lS#cF^fllb-;IQc}3K#ERwjip>FH}-cU?B~sq&Fc4S6Qc8cgN~7dMQ?u+;9Nz> zk+u~FtHpRZA7S#>Jrbhd)xiivofGB^H*w@Zp6$Fc)-7D{((`7l-Wds)tyorRyVP!e zi}RCSt5z-G4;rq?DnJLbN48j9sgn0)x4&e7>L|T9&o{H7RsW^2+wx#OtPnYmDWU}w zdL(uCgvfL;Ea{W<0%IRZq{S;!tJ4FT$VbyT(R}c{?td!1vq})LAs~#CS*P-N2C{Kl zX{09&1n&Fyph*kXqx z)0OrQq=NB2CddMYSu(4m@kbDGVSNYY1D9MD^U7ug7-3`EB8_1g4HHg%e6pXo{Dujf zSbmK#mQ(7>9^4rbZXZ6QDi@Q5=6uwnry>b#MTGSq3I&Jcfipt04d*h7#j*^WS3Kip zD_rph={({d_Jr%B?x8zSdRvEMzkNqQjQeVE{ z)&h2M*Dxp}uH2PemW%P0)>-))C26ArHV99s(q&IC-f>-jqa*6DA7QMlO=x^>a14kC$ahfQfq?vt1>)Yljm;%&@2)%a+1j(rs7S4)_#&kFA0n8lGIerU%#Y* zyjytedGWoqT0tO%5kTH~el{d;Fc=*GjY8q!DveL~jjjM%bvZLX=FR(AZ8ughag!1_ zjm)iWZQu*-o}7S`ddP)J)v7iiDKI|*D8~Cj!t^iS=ZSf4i|-h0C=O-Uc1x=OzxH?H z4}>jCM!Dvm6tL;_b_7$x+4mFi#na$u+VO!ZCe!6GoF%44fbn3CYj5qL&0^)6RqXGi z!=uy(RlALijZQ#ALBFo!AK)$WKlz`eh3T(V*Ub&S2M>}UyjIu~bK+eO0XajrNc?B= zw`0xj$K_xCW^&O}oSc0vV|xSbl7mJG3rNUc@TD`7G`QcnI)m@ei-}|~?TD!G@YdN* zT0c*D$_m7*N-fbYi9Ypa1ik+|e=vfIs^3^bq>+tQ9G9;z(SY54_rSEl0g%UzT9u%( zsw(1&{=W$JMSRFnDq2|Kdmwp5NA+KSzd}M|y;X&X=6}KmLjX0m?VX3t^RISJYJAv3 zZ?3}_&HrR}?HtwEl@Sn&(eTLC-CefMQl!DRf;E4qo%2fsUvng z^ga&0UKJ0AHzZjkZOS-pLo%2zFuGUC)GO|8yph5zm+SdO5}J)+C4VLn49(8rg&I!! zgW=x#M1$r0;A?E2spir=e0qZy80^f?PLx{j+ryv-(*T7D11#uQBw%wt_AmOOzO& zr)6~aBE3k94yWk2w6fN=pHrH6DO_W0u>i3ZnC#~ZOCXx+)z{Y-2eQLyQ6)z=9dF;v zCUo|G2S#^d*?Rdj*1m2-HPfDn)}<+;%R4K?-7!Ly?s?CqTpoq!P_5X>w#s>~jQKX% zzc3iHNE-S}s;VVO`U!G@xZ9JgsPkMe@=IG&KdkE+7AY@cSc-rdBfRykIOZKJ7Jby& zoQ(Hw`nE3`o)d~Wcw?{Zx}DC1sM;I9Q(G~Y;%cm|6Ppi4T!K0v>N=X|*OD~9p4oSW z$)LZ*m10OIeO&Ypw_h&?;LmBy&COld)mUl%A`lD?rqf}*-^&|ry%2X$P>Xz86O!jg8S_|nZRqBfEZ${W8S-RG3Py;A7HK?& zV-Fp*Fn-&@`h>9eJ*n)L|zM;Jq`1@a1XM9%5~6Xu52vomWs5rM!)SB~N6 zr6JbRY&vLT@-ZO0Dhnva1MJ3(=z-p5@c8mqlYGg{vG8Ph^cQ@cEw>t>}Kev=VAf9jy&HxOv#lhg3?rBpbKPV`9v5tYA`в9_)V;LQkc z=R!Ckqx)6$M-cR)O-)^=*qLZK#cHxM!+E+Q#q?}nEqTfp1b52OF{-M&VZm7~adxz_ zyT!p1A5L^;@*#D$t<)b-St@_`@3k<$XiD;9LB8{V;+VFa5q{|WzaafKz31F-gb}wp z=$M?C6>t#UDytJv5sH=xZJM~I&0X7wsQXh6hR(euXnW8{P%|Xnn4hS|s47L16IM`y zs_tC3uh@Cp7&30xW-{D&kme_gR#Z9sMGFYdO&G$6J=dWPz?R~W58C_}sau2D7~{J- zK6yO4aox}_w-^qH?MaQf+S=n}y&DSwkM})`l-YnkakAD12MB;Deh%ZaT?Pa;FaUNs zK(zgFn?*`W>iTFN!Pt0DMcU@H-4#}aGgzV=14Bb!=GsXqbECrnCJNcQ*|EaU9acGF zhIDyfwU{Foq#83;fqODl{M_KlJiQdJcb6A&jH`**cIjrG@zNGK)fd6>zPe#%~;^wIm7V8Ib= zm-fZ*P1qWXDL?4F%+B);bU>4U-D8&&wMd0zAyN^&A zs?|^)S}9x^sJLL%*v-7s)rn2yTjY7Um^CC9;A!iAfO)f-1hYD$3dH=PG8=i==Jdz9 z+Mn4kOy{o3hV%2!(b0h5z`MLK&sJGZ@yBq#<&#YJaVUe!;#S-02C zU@LIVBj=KYu9%pkJ`^uQ2l0fDNQ(R}nAzD29GmA=SI*4Q@>rfXXhxF(Tb7rp1U*#JS^oe7ouiMZUq8g zyo-$xzSHccD!Mh24XLyhTk7Ba7_4ZF;mU6Y7q?(MRFNOAn0EFjTBwP+dA>EyeD%#N zGC9Tuitg;G%5a4_A>~Er@XuP`~~{#avaw)=H_AuHUm(bXC@_a`c1#)K@zi!*%|QDR7zIcPJH zuRrldQ1equu@+L!T4=YA3sBwp-nKR+35`_kVouunNW)5-220;7Vt2+HW|Y&0l7=89 z?;Xom!qY_V>mp!_(?20#iCd&=*wowS4qH3Z>Gqp%u!NOUD4x2ok&&zI4lMYi}OvG+m^XXUa|(gyqp%+KED}tKTPVP&76;OOH(PveEP0qv3#2pQt{s008Lz5 zwy5AvieME{TuCAX-3KG1_W&F9buH|_*_#%Gkwmxx``9Ig3fZV#6vj5R;ZZtP2xhLd zyC5*g|5lo6YpG2y80Ol|4_Q3i5qRHF`&`@;J&rg1h(p~$CLNxq2q?Sw5SDNCU~(ru zLu!#;A8jv$B{o+kQQV-d(D!Q-f~Dppks%2WOY$YZrU^Ygp5xs&4Hf_@DAwzV9GNA5 zW_~cZ8ie|x6jiD)bZ}<}Ns`Z$YjsOV?TKs!vX+d!2y(p+VDwIxf;p7`klD_)%sL{O zzJwuDPHS*~3}Zcv%sG~-brx$Ex{xxxuL!?_PPAPPwM%P@vFjQp(<=ViSG`1_RKY8!~Nh=yY z*V~GDj$==cV%Wvy7pb7uH}QYKf%v~nKw0P0gB-}&$v#h@=Fng&xzYO$oaFoSqxR^% zAxn#u=OG4VBQtvMn_bGc%0f6e;j_K2n?qeV`}!jQcnJiERW>^JqU z;nT&>ODhq9{88T<{%JZDkR#3u3mNb4Psqy3a>3#qas+>CH-R}WyACgBL{x4wFCCCS z9%gXcVY5;=>dRm26JgDvBZe{V9)sdL&Cp*bhS=A(EbC!aC!vD#rq6R!KOT7DDaovi+`)H=zH_{xacmKuYBr!W{=uxPi4t*(mA`->F3>0Wp%{v zt7*>QuArHQ@?Dd-*a&Yl%XN(G+l-IcqDJM6zpd%IzJka4=<5Fm6_9LhNL4S4Qkl=8 z8+)xLm9FA55I^zHqmMTCKGPW(ayMag$P&g;Mn<-~SL}8_7Vxsv$RMqQ**HIj9w-_} zQJpPR>Psb;ACS$tmOP9H`Q)&-vN>+9+T@8!LUyEGb5^F^?noRzf+EgSNxx9hr}p7^ zivHiqDl4qBjJO796;rFH%ZMI4(&!Lc28!Uq?w6B(_Y>Fr*XL7gP*=~<2W~dqG zN?c_o-KcwuaR{GgT~SC>DcrHyyU;GzpY7b=eCD!C=&O*Uv5Th?4y-ImZE`5w1|+tpCv`1w$#fKLhAb+C_{bD`Rh5R2t?D3TxTvlF>k*f)C&^>r+9 zK|ecdypp>B*<49!%w4B@1NMSBdaT)$S^Nr~xKGMbwkB`jk?AddUCem1oRNC3E8ub7 z1%5dpJ{|e=XO+x`oSxF(gyHrz$Ygp$SMAYi9(}}`5)3b%FFku>(>ptV0PLzr?wEjo z)NTjpDdJ^hWL&Vk0TZnko0}JZlvEyOP~{ zk<1^yRvekn7miI%Czxw%Ya!fl?`Q%$AYKBEN`-E{l}MpTvDPmo!NU`ys9?vfx@l`? z*Wc3<3n-TMFVp{?Vg5G*`8g);Kb7!XH|YOUcbA=eq<8uKzo-L|NHYxy98jgTS$9S7 z-|QlRC;;+G9+L+rZr1!Cf32@inCcS%l9!`bdl%lq>i@+mi0FZgJrj|@|ITp={00(~ zLt*~a)+u7=O=F`NyndDqk|Ep}?>7JQH^KMk7Zw)!-QT}*D~hj+Z^2U&;4XbOFyxY7 za#gsq^CLep)wQ&LC|Xu$`!E#mV8WQg9q-=}-eUrp_$l4@TF8IkXJMRnJO4mNteT@| ztJ2Z3_R6{t^Vs$tK3N%_+e|_7{52+BH=AEI&VG%yr@R>?Dr8}yUlV3(AMaOCAZv~x z*iA)_*+YpA77baV&LnPp4@3-&1M(sm*IX$kjke7|Ug!AU4`%}Z6oZ|;QXFGx6DKt;D|d^ypjTJB8!gA zFGH>QrZF9S?}K9`CEfd|{_prU%48C{mBNAqFS(zT{(ndUyDy}x`b&2&CTiw=8*zqf z=qAQ;NI#k;$st1e4|6o)Dr17*%@aAWWvjlfdpB`d?E!*qVSg_VX+ti+KlL-`fTF}r zm0961;3Kjo3Q$vLg^%~;ewXdJDcuZ9hWfj~149x(%$q;TbD+l%YbQVEuK1uD zkL^YO*+4s=CnG8|52_#`^)m$D?JZGB0DP1XWz${r6lI*g-=&UWLc&}s?$x30R$H5d zm3jhIIg5%Kdo+nP_2Y|e%*0*fHz!9Vek`=E`5{agbK@x#%h3hys9?vsT+H6d#nmEh z4m4BwB|TH4UzWuZOj-^|NE8SxH~9)IwAk`V`bN58>IrrZNv`3Y4e%CRoSE>1M;yV+aSsEv9G<=BSrz=4(e2pmnoSq>2yWRNRD{;+$RI^a|1H@KY=)5Q!$JVIjq5kM9)AysE!vJ+0!p z{RXX z;zb2Bm-8zVOX-_4TeTPSv>LKuN`GK&ABB9Lt7>Ca>MR!NWNSXVX=GG>rQtR*A3S`v z#>3yVDq4v)mbMG%x1gJ_{K?{DLxM=FTuHSDFZ`c{Q47s(pSqS{9S$`x3Zfv%`+h;= zq{f(b**KN0jJC~L+Pb@QGAHTlAIVz|e#6EbHNL7fYaCgAkHt2&w_)GQbp`kmVo083 z>aU(@`YkZRlIOy|!1ZtCJBR%h`JZCMe2M=QBi>fY7>I{-$(yzmAu_hWW&QjUnRd(+ z+JS>rWhbGS7C%Uj5OLanJhJ9+$vc=kbsO`uOx+Z7+oJcf3I;=_4DFz9e3Ab7lhUe~ z=*dHn$`aGf2$lre zE{@{I)2;g_kVO5E1QdgAcRP_q^-z1GkH|07nb2$$vDpGa*|6E>+Rdq*qEMKn(9qD@ zxf5ArWdWE_RKXt~RTVz|8f-Vje_|Q&d==^Zia5wHG)j~?&z`{_= zR){1Wf#;2P7WsB@)Hz0&v|tV;uBAFWNm*W638AMy;V8{;R-9n?({dLgjd4SYCBikW z?o3nj6`VI}X#U2q+gI7u@uV#r9Ru>UjO*bkXklU#T1)kbAhE6rjKur?K?3US8Uxqs zQ2cf8kM5(c6>K|>M@`*FY(Mn1g2%JQvUwY*7T9{Lr@%AMiQW70@I>k>8pBP}l8}yT z)dU{acpBMR8bShssnSBnss}TcOnu4e?W^>Xq>JvGYl~GsRx6iue)gb7>mdufu&ev! zKJT4T_?N?rk9i(`ky^&U~DF? z`YRFaSBy0%wY}a~?HW~Cx~X5U)%(1;yY=U|_Cue6@vgokc7Lz})(FD!mJAqTnIfLm z5laF+`CX;g8N%_E-!jz3b{ai@NctPivh%i1qy)kFi#pZgu<&vT31hFfkLS}cnh1B$ z-_rtD%M&&DkAai2E!1%1qofs`y}u_Am6^{d!IaQK<{R|T{#y(11?pECz>Rf(LHRco zrR4lmHhYg%-o1lOILGVEA=hKnSTXA#l$C^6I*OAbr^4pU^BeSrNg^$goehFKrTU{e-n`jls-;J)fxNJl( zqrl6*N2Gsxx%YC3o=nH%dbr-FVzB?vY30RsJit z0ZpSn4UCjl|E?%0r4OH~J{>mO7TgDn#qIlFhfYl&*s;f$tJu=mq+GPIH6HJeu04-f zpKk(6*v~q36Ixv<{jlM*n}dTz*f?3dG|R%qX?Qswq>U`tjXnQ%g$$nPpfD z0Spxa0&BIx%QuMD(s{}OGpq(nQ>xCKuuK0)EHi`tJoComqAV&5O7W%R>v{sMN}@g@ zb0xwmC61mXPgKjAy5RVccYplbGak3iAoDm1#{X49uN?ANlYDOQA$wD#s@^-n$nqozeX#>Ikq$p2(&yG;0>=w z-LVBEDZ;9^+b|w`&UClcUx<`vTg;CJ^Tw$La5*EzGh35G-ll&`1HJjA0p{PnndWn4 z7yu;+D2EKWX{%PoSGy4rw;lsINtETT9+;R33~@Xsk6;rmn$|RI_5^|7LRD8tRL|aG zu(XE_1~sKGp1#aq_8w;3d%PVcJ{o=_=RravBzP?)|I&|!936=O}Nevls4lN)c z&@Cw@MiCGY@P~$Gqns z_Vxru!_}i?TgV3v%@^lWSJSTzTrP~`8n5`QPIdOLt5FP=2MSt^j%=Q5?LM{;%SdM< zM&t9Trk+pGyHdfBdgxvQTcgh#dblm-M4mj2!6E#dUzJn(=5~0$X30aeeTKM83S*mZ zigPxO+{_-Q)w5}FDQ$o8XdFjy#4%7!F5_)@-g0iWpUheD_QK-KL{JVcwVU*P1i^wQPikyA+F7mQNv; za_H;_1c9!Y`Mk4Ju28fzG~1ExyEWT=!Y&;Pd>VW(YIV51h4$lFf-*dsShZ|#y01^B z+NW>JNK}v8#2KR(NT~}kjDgy}md$;6`dN#CS>Nxa{E|qy`z+mYi(j&)DsA;WW4oL` z`8LtK=_G&X+IIGw+cslNJ2SO!VDCBkVSat6PkT(?LUJ4hH~=4Jn$flRY&|nC`cGa) ziNd=2uMtP(@VE=OyY4Txq`mWlnP6I+PO|OyK){9qjQ$FMGGMS+sQ8ufx?S%>skh+g z<>qeMuwmUi60_IE#VLSIO*yeF*{l7gb8!}=$=r=+S&9t}20kJfbu@u!K|P{C;wgux z;N($I6*&of)UUF-(SNUi`S2?2{V67OGfh}tr6l;@`P4b>)h6i6#viCfq{vph}fDZmqw2tA1tNrR?qh?ABVBwedE95Gg^rySp433F(yXRyu^CLy#Q0yHg42&Y@H3K|&-{8ithm4&wWM_x|qu1t)f_ zz3O@PIcK^2oX8%_5==C3>PQy#Ih*myo;q>c_cVY0qCFry_M9M5kF1;WNnEN<-~1}& zTDpfv9a|F$y51hf_FJgAgeC;}Pm`v20iU=)X6389j?;b$f7eM|f`FFu3k#qhjk#7L zoB0HORID&wrq>)h1;)7v){{Bo6?%1Y3LgW+tz?Rei^tM=!|++PxqxTzYU}D+wleI9 zUO1AySn;FG<_{l^l{xFUay@j&w+ib;8p${q3K#lFNR>++_b#ujA}Ru0L_M6) zO>2BSw~_+~V_C-0k)zIf{KtB%_||^gfi>{jDjp#re8uO08@#IznD%mywoUg*@ILi+r@_Uv4?9EAWOXg{;)!-4@4-uHgE{o^^v;)-_)|1Vt_y- z<_k(SbVUP7>x#KE!SQSP3)vX-$k3w7z)Z4Q7>g(NgAE-PPw-OW64RW0U+hUU_{{BZ z6+;n~pj0&$JkzMc;iHr5*^^jx+-?Vza=}7zTHQfbtK4?S5(O+6a8RS-oI;x=pmvOE zJLVUzEru`KYTS*G_eQS9#*_%ybi2ttmefn(jH)?fKz-sg;MsJKB^Okuj#GkfjSd!z z^){evl^pMF=FaP5#S-Pr0ifov&2$Ooi&bAZ^E{v84PKIy5iyvQoh5|j;LJ!#FF_d% z#b|Q7Co8{(@!HQdGHeue@D_yGf1-UvXRPfwUfPFD+xocankPgtTcTUOCxzCYO%uJ4 zPZV+5ayu(_Au&gFCk0$ZzKUMft~jUocj)*avWYnV!_-6kdbKTZTe_H^clMdcTBe1*&=N*XS<;=M;9NY6ao5Y(kS|D9pKh}&6 zn}4V*&}Z`08kCLV;ozXLg4?pkGhc+ZVw4B{0};EI!LCTuP2b4t%_wyYT^>US*b8K1 zDX!PB1MZ9cZSFO#0%ly5Z!s9tezs`G4?GMZ-JhT@)+iR2J4zTv;yFJ;nHSl?7tdfb z70!VnCtvWnZxHI_C}NgsKcL#6$N;#Gczr^sNf`sDT3*ko#h-Ms6h z=sAM(wDJpXv)&Jj?3NKfuXAdy;c_^)64acWuu0V_Th#;8nA)bkFXhGWXgTKhl$t z3d6GcJyo1m5@9w&|BL8Ev`y5ab8({9cj(Ftd-^thym`n*=j*>< z?C%Y|z1}I936)I0&voSD%H6rIL#8d2luhiP z`WjE25q{p2qn4q-P85Q1k#sys>}@v(ld%+lYUrhwqfOrPwY%@k&3?j!Zn|=N9)73N zrlX<3&G|2ep_BaJ&ctg?h-f+yiS9z5oF+Es*B<>%oV9zU@cBDVRfbuTR#)Gv^LIDb zNV{l6C%JJ${nSsaiVZw?{)EtOWDrcW*>g!PBia zFTPK1o+b;Du^@H|4qg59YOYacpX2hgzi<^lD8fGup6{LB;IN%QfD^w(Z@BMAUuxa-4c6{uQ8tROO+3QG!y~7l z@Kl?f5p4iV&mW9~ijH(K+J%Mu2#+A?b79^G^0qqNdZBo6<%1rpN?V+d6<`$i`lA&v zt5iBo3O9;VvfRx$`Ai2#BRZdKl*APuxwuL2v1c<-09~r*TQViN;*1iQDZr8 zGrn>Do-D#KB57s;^!G4-PNuxl+m9|s)JFga)=w3rS%a&);O1Y;#VTX*>)R&utPr80c$ckQ@F-3fn$ zvS0urUJ=Y`tYJtezVvNq``~|rE6)d_06`(iF~i(_#9p4y4P1}%Qru#hH>b5wFX(tB zj(VVMORyY&(R#=fo|hkDj^Qz8SS|W6GaIJ6AP_5~8R+S?Dj_&jOZrMX_#-^Lyul=6 zwuNViMH% z)+&QpK&)4Q1k$BIab@_v$`NibOrXY95Q$e-X!w7Ai%YzoIQ+n=YNeN{{ z-t>|##ic6S*}Yk#iE`V?a;3){qY+0kQHE*q@xRx*)hQXiww_g>>DRMFBk4W%G;}fK zuC*&01x(6D6978_YjfuM2U|6!kLzCV#c7E#5V5(a)4>op(^e$((9QBboEu+-3cpDG zE;{G>lXdHpvJb48J(DzG8L}g!`Qj^-&dx)qIv_i?y0@^i*IXc=BR2Ca<#=JNDyqE4 zUGsfA+lngO;t|0c+<^A)eG(|9(a{B)HiRE1cgkaiJ5N`6_r}?HkT$WsAV4W3P7(~# z;0Yy>wWYD8soH~BGg?@&8I|(a8Y7;-9sjw^g|cTVJ@*5*v^7da53=;bg5S{-;!Zo5}-kBdi<#0Ys}{- z)imOQk2JN_K=9;1}riJ{E%&yv< z1+_9#_|0i+$=J#9VwW~te{&F%^bMwy3}IoCj0rjYATl(iJGyIoAUOghP2P=Vv0It6 z!xOs%zVaS?-MMU&1Jq{x6dNW_j&YrhWPd&AC~%2nzibj7OH{y0K}tTFzO3(T9Wwr5 z3RnE`W|&j?c1FpB2RvF`!4K&a-GT9FDK1|lj9tuzHx zp0n)8$XjGN62U86h@yWDhQr^_x(=Ii6oC zrp}OK2TJHbVA4hHiEYZEl=WU?N(H;Qjlr!E2m7&lVm#`rq-2Yly1Z@!hcAM~DBhx% zvWg(vN1-oc&yE;T#%%E@Ktl(&mq@Ix%AfmP*EV>Y*<~sr@nhyhOP()H5VkmOGiU{^ z?i^Y76O@Tz>`C+hW56dA%a~qYpAGO1Dzrfk>JW7f^~jmRUiH1O*X^-@MtSK6n=Qw|2l@Os zuK@k7$y}IpipTR}JbLNwli8rhu=Ta(eTqHRUQ|@%x-qn-mP*b4%uz~=>WQ#b4~At! zhe`!l*p9&a%x=(W!U3ApBOkS^$sDKm<5z~IDZ={-!#Q$xY_gKr>ZzwAVXyn9`pG}s zkV7Tyy~qS0?UtGuHck$(pm(C14I9PqF9~c|+BrUyhw*;)OJ*Snk%~xG#1$#kgTy*w z5!`AcE4$m!6k6^SX>?PRg%iIsv~wz9`MmJdm4*ID-{)*!qcUe8KKMf!7!TPhH-@K$ z7Kuk!``Q0bR&mP9z4wwH`-JVLZ3pRfR51&a(?-Hk8#lg^r(0gRdR-UqZD1=?35W*& z6!1YqP#<<2Xux{K1SzQd7HXB6DxprG$|)%KGBP@djFSASX>Au-I5k#bV>Tq+G7S;z z-;#{(LFcSZD4g?_X^7Q)v`Rz)@o*S>GyM!PxI5A4k8?d zflAY(Q&u)bTWxY|Bb&~}`vYZIjsuOLK8PMedgfFbj@H-)$Jfu*7e#YpQ%0y>{;DuM z`8R{wS(FAtk?i7*_@p&17(2MK?SF`9wO1z`ImAm@(Z#>@?68h5@>@sEa{zf5pLj+q zksuisk_|KNrhEg&1GD_h$C;=q(0`L#vSXPQr0>A6CrqUY^p zDv`LqZ`sZxl4c`yXSB?K44jC@3zt{sC6 z#5F^IpWn~ufv_$Esa8bv?_okw%U8@oT1DW{f3Sd%`c45d{dX>z^ z;iFk*_Y8>AI1xgLF4A$?_h_E&)F7}P^H6KDemu%|6B}&*9~V76g-4VmfM*&+M2woZXVi5 z^!KbY!Nl|HB5!b;sC}5PL`eLFpbyrwPNS5+1Iyn8Ga{}D_o#j(*arZ#Boq9n<=axF zzp^CZNL9R_*ix8p;6Ex@gBFlWsH;el-j6+9DZP7UH(V|a0A?Fc&jBb*oz&mps2GGZ zqH*7VbZ??QA+1g`_GRFDK3n7p)Z1L=L85{YgNYSBiSofU2+db2R#S%?YV&`GgA1lH z^Ul>|*Vt!$a|O+%EcR)#EVvQF+O$XX4ryh0m@N+4^c7t#4CUN5Y~DcnPmHP;e6#GVm*U%FJ92cur*CB=DF0 zYA3s86Hl2kk=8%Wd_{*55qGGWDPd#NEp&f}G);;l5jhOlNbEq#;$!#+h!toyOQ0H} zZOatg^FJO4`Ea?!A7DnAnbW|hR)0mGT;|SQ+hSN1-b$hNulGj{910e%AG(TXpic<( z4SX=9AvC~RFKKLsQ2(*?WTk)x>SSgLgrPrliDScK$f48s*zVs5TmijNQ+sIYWhF#e zrU>&tCW>PtN#pR}mJomozo`GcFy2}fxH9-#wzQdZCGpu@n}s(A*(D??PF(_e!X`yG--iGMY{&;^u*13PBWg47Q~ z)Xcuf<^it{>vR#1{M7J~Vus5|ubySNeSG;9(3ALkXCYeWSP z^d7zUtv%b@*l{}NzPnVvakzrt)fCXTb;`l-gNEfs#E}l&DaVsEmB+g6YsT40p8Ck_Qhw9y*w)q`x=;qAT HH0b{Uiy6aG diff --git a/ifm3d_ros_driver/doc/noetic.md b/ifm3d_ros_driver/doc/noetic.md deleted file mode 100644 index 8c4a341..0000000 --- a/ifm3d_ros_driver/doc/noetic.md +++ /dev/null @@ -1,64 +0,0 @@ -# ifm3d_ros on Ubuntu 20.04 and ROS Noetic - - -Our package `ìfm3d-ros`, more precisely the `ifm3d_ros_driver`, depends on the underling C++ API `ifm3d`. This needs to be installed first. - ->NOTE: The instructions below apply if you plan to build and install `ifm3d` from source. ->NOTE: For older versions of the `ifm3d` (`0.12.0 TODO: add link to installation instructions for ifm3d on ifm3d.com once available - -You are now in position to install the `ifm3d-ros` wrapper. Please switch to the instructions [here](building.md). diff --git a/ifm3d_ros_driver/doc/rpc_error_codes.md b/ifm3d_ros_driver/doc/rpc_error_codes.md deleted file mode 100644 index 41615b8..0000000 --- a/ifm3d_ros_driver/doc/rpc_error_codes.md +++ /dev/null @@ -1,9 +0,0 @@ -# XML-RPC error codes - -The underlying C++ API `ifm3d` supports these error codes. They are only sent asynchronously, e.g. when configuring the camera. - -| error code | description | typical solutions | -| ----- | ------- | ----- | -| 104010 | JSON syntax validation failed | Internally the sent JSON string gets checked against a JSON schema. This error happens when the parses fails to complete. | -| 104011 | JSON does not match current schema | Internally the sent JSON string gets checked against a JSON schema. If the JSON string does not match, it will be discarded. No changes will be applied. The configuration state will be the same before trying to reconfigure. | -| 104014 | Invalid configuration | add | \ No newline at end of file diff --git a/ifm3d_ros_driver/doc/troubleshooting.md b/ifm3d_ros_driver/doc/troubleshooting.md deleted file mode 100644 index 0399b45..0000000 --- a/ifm3d_ros_driver/doc/troubleshooting.md +++ /dev/null @@ -1,50 +0,0 @@ -# ifm3d-ros Troubleshooting Guide - -You can use this guide to help you identify and resolve problems you may experience in using the ifm3d-ros package. - -# List of contents: - -- [ifm3d-ros services provide no response.](#ifm3d-ros-services-provide-no-response) - -## ifm3d-ros services provide no response -On systems utilizing a single core processor, you may find that the Dump, Config and Trigger services of ifm3d-ros package do not provide any response when invoked. - -This issue can be resolved by setting the "num_worker_threads" parameter for your ROS nodelet manager to use a value > 1. You can read more about this parameter [here](http://wiki.ros.org/nodelet). - -The snippet below show's how to set this parameter using the [nodelet.launch](https://github.com/ifm/ifm3d-ros/blob/master/launch/nodelet.launch) file of the ifm3d-ros package. - -``` - - - -``` - -Alternatively if a virtual machine is being used, configuring it to utilize more than one core should resolve this issue without any changes to the launch file. - -## ifm3d-ros nodelet can not connect to O3R camera head -If the user forgets to set the PCIC port (our standard communication port for data broadcasting) the default PCIC port argument will be used `default_pcic_port = 50010`. This TCP-IP port (`50010`) corresponds with the physical `port 0` on the VPU. The 2D RGB imager or 3D ToF imager of choice therefore needs to be connected to exactly this port. - -When these two port arguments don't match you will likely see something along these lines, being repeatedly posted to your shell: -``` -[ INFO] [1628860557.703261704]: Running dtors... -[ INFO] [1628860557.704592043]: Initializing camera... -[ INFO] [1628860558.705489893]: Initializing framegrabber... -[ INFO] [1628860558.706352595]: Initializing image buffer... -[ WARN] [1628860559.207288723]: Timeout waiting for camera! -[ WARN] [1628860559.708197339]: Timeout waiting for camera! -[ WARN] [1628860560.209029697]: Timeout waiting for camera! -[ WARN] [1628860560.709553855]: Timeout waiting for camera! -[ WARN] [1628860561.210310005]: Timeout waiting for camera! -[ WARN] [1628860561.710739497]: Timeout waiting for camera! -[ WARN] [1628860562.211714793]: Timeout waiting for camera! -[ WARN] [1628860562.712752207]: Timeout waiting for camera! -[ WARN] [1628860563.213765790]: Timeout waiting for camera! -[ WARN] [1628860563.714424040]: Timeout waiting for camera! -[ WARN] [1628860563.714658175]: Attempting to restart framegrabber... -``` - -The fix for this is easy: just remember the first 4 digits of the PCIC port argument will stay the same, the last one corresponds to the physical port as marked on the VPU. diff --git a/ifm3d_ros_driver/doc/visualization.md b/ifm3d_ros_driver/doc/visualization.md deleted file mode 100644 index 23a70b0..0000000 --- a/ifm3d_ros_driver/doc/visualization.md +++ /dev/null @@ -1,28 +0,0 @@ -## HOW to visualize the point cloud with RVIZ -The included launch file `camera.launch` will publish and remap all topics and services to `/ifm3d_ros_driver/xxx`, for example the point cloud topic will be remapped to `/ifm3d_ros_driver/camera/cloud`. - -When you open RVIZ for the first time and subscribe the point cloud topic to it, it will not be displayed as the transformation chain between the different reference frames is not complete. - -The first option is to use a "dummy" a static transform publisher to fix the missing link in the pose transformation chain: - -Open a new shell and run this simple `static_transform_publisher` to map the `ifm3d/camera_link` to the `map` frame. -``` -rosrun tf2_ros static_transform_publisher 1 0 0 0 0 0 map ifm3d/camera_link -``` - -The second option is to pick a different reference frame in the Rviz options: - -![Choose reference frame in the global options of Rviz](figures/rviz_ref_frame.png) - -### Change axis directions to suit your interpretation of a robot coordinate reference system -We have removed the rotation parameter which have been part of the `nodelet.launch` launch file which move the axis directions around. This decision was reached because we believe there should be only one place to change the extrinsic parameters to keep things unambiguous. -We suggest changing the extrinsic parameters via our JSON interface (see ifm3d) and the mapped dump and config ROS services for this. The extrinsic parameters are applied to every measurement (distance image, and point cloud). - -If you would still like to add a `tf publisher` which switches the X-, and Z-axis please see the example below. Afterwards the Z-axis will measure positive values in the direction of the center optical ray of each camera. -``` - -``` diff --git a/ifm3d_ros_driver/include/ifm3d_ros_driver/camera_nodelet.h b/ifm3d_ros_driver/include/ifm3d_ros_driver/camera_nodelet.h deleted file mode 100644 index d048909..0000000 --- a/ifm3d_ros_driver/include/ifm3d_ros_driver/camera_nodelet.h +++ /dev/null @@ -1,122 +0,0 @@ -// -*- c++ -*- - -// SPDX-License-Identifier: Apache-2.0 -// Copyright (C) 2021 ifm electronic, gmbh - -#ifndef __IFM3D_ROS_CAMERA_NODELET_H__ -#define __IFM3D_ROS_CAMERA_NODELET_H__ - -#include -#include -#include -#include - -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -namespace ifm3d_ros -{ -/** - * This class implements the ROS nodelet interface to allow for running - * in-process data transport between ifm3d image data and ROS consumers. This - * class is used to manage, configure, and acquire data from a single ifm3d - * camera. - */ -class CameraNodelet : public nodelet::Nodelet -{ -private: - // - // Nodelet lifecycle functions - // - virtual void onInit() override; - - // - // ROS services - // - bool Dump(ifm3d_ros_msgs::Dump::Request& req, ifm3d_ros_msgs::Dump::Response& res); - bool Config(ifm3d_ros_msgs::Config::Request& req, ifm3d_ros_msgs::Config::Response& res); - bool Trigger(ifm3d_ros_msgs::Trigger::Request& req, ifm3d_ros_msgs::Trigger::Response& res); - bool SoftOff(ifm3d_ros_msgs::SoftOff::Request& req, ifm3d_ros_msgs::SoftOff::Response& res); - bool SoftOn(ifm3d_ros_msgs::SoftOn::Request& req, ifm3d_ros_msgs::SoftOn::Response& res); - - // - // This is our main publishing loop and its helper functions - // - void Run(); - bool InitStructures(std::uint16_t mask, std::uint16_t pcic_port); - bool AcquireFrame(); - - // - // state - // - std::string camera_ip_; - std::uint16_t xmlrpc_port_; - std::uint16_t pcic_port_; - std::string password_; - std::uint16_t schema_mask_; - int timeout_millis_; - double timeout_tolerance_secs_; - bool assume_sw_triggered_; - int soft_on_timeout_millis_; - double soft_on_timeout_tolerance_secs_; - int soft_off_timeout_millis_; - double soft_off_timeout_tolerance_secs_; - float frame_latency_thresh_; - - std::string frame_id_; - std::string optical_frame_id_; - - ifm3d::CameraBase::Ptr cam_; - ifm3d::FrameGrabber::Ptr fg_; - ifm3d::ImageBuffer::Ptr im_; - std::mutex mutex_; - - ros::NodeHandle np_; - std::unique_ptr it_; - - // - // Topics we publish - // - ros::Publisher cloud_pub_; - ros::Publisher uvec_pub_; - ros::Publisher extrinsics_pub_; - image_transport::Publisher distance_pub_; - // image_transport::Publisher distance_noise_pub_; - image_transport::Publisher amplitude_pub_; - image_transport::Publisher raw_amplitude_pub_; - image_transport::Publisher conf_pub_; - image_transport::Publisher good_bad_pub_; - image_transport::Publisher xyz_image_pub_; - image_transport::Publisher gray_image_pub_; - image_transport::Publisher rgb_image_pub_; - - // - // Services we advertise - // - ros::ServiceServer dump_srv_; - ros::ServiceServer config_srv_; - ros::ServiceServer trigger_srv_; - ros::ServiceServer soft_off_srv_; - ros::ServiceServer soft_on_srv_; - - // - // We use a ROS one-shot timer to kick off our publishing loop. - // - ros::Timer publoop_timer_; - -}; // end: class CameraNodelet - -} // namespace ifm3d_ros - -#endif // __IFM3D_ROS_CAMERA_NODELET_H__ diff --git a/ifm3d_ros_driver/launch/camera.launch b/ifm3d_ros_driver/launch/camera.launch deleted file mode 100644 index a64cff0..0000000 --- a/ifm3d_ros_driver/launch/camera.launch +++ /dev/null @@ -1,31 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/ifm3d_ros_driver/launch/nodelet.launch b/ifm3d_ros_driver/launch/nodelet.launch deleted file mode 100644 index c48f03f..0000000 --- a/ifm3d_ros_driver/launch/nodelet.launch +++ /dev/null @@ -1,117 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - # - # The IP address of the camera to connect to - # - ip: "$(arg ip)" - - # - # The on-camera TCP port that the XMLRPC server is listening to - # - xmlrpc_port: $(arg xmlrpc_port) - - # - # The on-camera TCP port that the PCIC server is listening to - # - pcic_port: $(arg pcic_port) - - # - # The password needed to establish an edit session with the camera - # - password: "$(arg password)" - - # - # The PCIC schema mask to apply to the framegrabber - # - schema_mask: $(arg schema_mask) - - # - # The number of milliseconds to wait for a frame before declaring a - # framegrabber timeout - # - timeout_millis: $(arg timeout_millis) - - # - # The number of seconds to endure timeouts before restarting the framegrabber - # - timeout_tolerance_secs: $(arg timeout_tolerance_secs) - - # - # Flag indicating whether or not the nodelet should assume the camera is - # being software triggered - # - assume_sw_triggered: $(arg assume_sw_triggered) - - # - # If using the `SoftOff`/`SoftOn` functionality, these parameters - # control the `timeout_millis` and `timeout_tolerance_secs` - # - soft_on_timeout_millis: $(arg timeout_millis) - soft_on_timeout_tolerance_secs: $(arg timeout_tolerance_secs) - soft_off_timeout_millis: 500 - soft_off_timeout_tolerance_secs: 600.0 - - # - # Time (seconds) used to determine that timestamps from the camera - # cannot be trusted. When this threshold is exceeded, when compared to - # system time, we use the reception time of the frame and not the capture - # time of the frame. - # - frame_latency_thresh: 60.0 - - # - # Get rid of the errors when running `rosbag -a' - # - distance/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] - amplitude/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] - raw_amplitude/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] - confidence/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] - good_bad_pixels/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] - xyz_image/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] - - - - - - - - - - - - - diff --git a/ifm3d_ros_driver/nodelets.xml b/ifm3d_ros_driver/nodelets.xml deleted file mode 100644 index 15ecf95..0000000 --- a/ifm3d_ros_driver/nodelets.xml +++ /dev/null @@ -1,10 +0,0 @@ - - - - - Interface to the underlying ifm3d camera - - - diff --git a/ifm3d_ros_driver/package.xml b/ifm3d_ros_driver/package.xml deleted file mode 100644 index f2e8d8e..0000000 --- a/ifm3d_ros_driver/package.xml +++ /dev/null @@ -1,31 +0,0 @@ - - - - ifm3d_ros_driver - 0.7.0 - ifm 3D ToF Camera ROS main driver package - ifm CSR group - Apache 2 - CSR ifm sytron - https://github.com/ifm/ifm3d-ros/ - - catkin - - rostest - - rospy - image_transport - pcl_ros - cv_bridge - nodelet - roscpp - sensor_msgs - std_msgs - ifm3d_ros_msgs - - - - - - - diff --git a/ifm3d_ros_driver/src/camera_nodelet.cpp b/ifm3d_ros_driver/src/camera_nodelet.cpp deleted file mode 100644 index bd4d7e6..0000000 --- a/ifm3d_ros_driver/src/camera_nodelet.cpp +++ /dev/null @@ -1,628 +0,0 @@ -/* - * SPDX-License-Identifier: Apache-2.0 - * Copyright (C) 2021 ifm electronic, gmbh - */ - -#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 -#include -#include -#include - -#include - -using json = nlohmann::json; -namespace enc = sensor_msgs::image_encodings; - -void ifm3d_ros::CameraNodelet::onInit() -{ - std::string nn = this->getName(); - NODELET_DEBUG_STREAM("onInit(): " << nn); - - this->np_ = getMTPrivateNodeHandle(); - this->it_.reset(new image_transport::ImageTransport(this->np_)); - - // - // parse data out of the parameter server - // - // NOTE: AFAIK, there is no way to get an unsigned int type out of the ROS - // parameter server. - // - int schema_mask; - int xmlrpc_port; - int pcic_port; - std::string frame_id_base; - - if ((nn.size() > 0) && (nn.at(0) == '/')) - { - frame_id_base = nn.substr(1); - } - else - { - frame_id_base = nn; - } - - this->np_.param("ip", this->camera_ip_, ifm3d::DEFAULT_IP); - NODELET_INFO("IP default: %s, current %s", ifm3d::DEFAULT_IP.c_str(), this->camera_ip_.c_str()); - - this->np_.param("xmlrpc_port", xmlrpc_port, (int)ifm3d::DEFAULT_XMLRPC_PORT); - this->np_.param("pcic_port", pcic_port, (int)ifm3d::DEFAULT_PCIC_PORT); - NODELET_INFO("pcic port check: current %d, default %d", pcic_port, ifm3d::DEFAULT_PCIC_PORT); - - this->np_.param("password", this->password_, ifm3d::DEFAULT_PASSWORD); - this->np_.param("schema_mask", schema_mask, (int)ifm3d::DEFAULT_SCHEMA_MASK); - this->np_.param("timeout_millis", this->timeout_millis_, 500); - this->np_.param("timeout_tolerance_secs", this->timeout_tolerance_secs_, 5.0); - this->np_.param("assume_sw_triggered", this->assume_sw_triggered_, false); - this->np_.param("soft_on_timeout_millis", this->soft_on_timeout_millis_, 500); - this->np_.param("soft_on_timeout_tolerance_secs", this->soft_on_timeout_tolerance_secs_, 5.0); - this->np_.param("soft_off_timeout_millis", this->soft_off_timeout_millis_, 500); - this->np_.param("soft_off_timeout_tolerance_secs", this->soft_off_timeout_tolerance_secs_, 600.0); - this->np_.param("frame_latency_thresh", this->frame_latency_thresh_, 60.0f); - this->np_.param("frame_id_base", frame_id_base, frame_id_base); - - this->xmlrpc_port_ = static_cast(xmlrpc_port); - this->schema_mask_ = static_cast(schema_mask); - this->pcic_port_ = static_cast(pcic_port); - - NODELET_DEBUG_STREAM("setup ros node parameters finished"); - - this->frame_id_ = frame_id_base + "_link"; - this->optical_frame_id_ = frame_id_base + "_optical_link"; - - //------------------- - // Published topics - //------------------- - this->cloud_pub_ = this->np_.advertise>("cloud", 1); - this->distance_pub_ = this->it_->advertise("distance", 1); - // this->distance_noise_pub_ = this->it_->advertise("distance_noise", 1); - this->amplitude_pub_ = this->it_->advertise("amplitude", 1); - this->raw_amplitude_pub_ = this->it_->advertise("raw_amplitude", 1); - this->conf_pub_ = this->it_->advertise("confidence", 1); - this->good_bad_pub_ = this->it_->advertise("good_bad_pixels", 1); - this->xyz_image_pub_ = this->it_->advertise("xyz_image", 1); - this->gray_image_pub_ = this->it_->advertise("gray_image", 1); - this->rgb_image_pub_ = this->it_->advertise("rgb_image", 1); - - // we latch the unit vectors - this->uvec_pub_ = this->np_.advertise("unit_vectors", 1, true); - - this->extrinsics_pub_ = this->np_.advertise("extrinsics", 1); - NODELET_DEBUG_STREAM("after advertising the publishers"); - //--------------------- - // Advertised Services - //--------------------- - this->dump_srv_ = this->np_.advertiseService( - "Dump", std::bind(&CameraNodelet::Dump, this, std::placeholders::_1, std::placeholders::_2)); - - this->config_srv_ = this->np_.advertiseService( - "Config", std::bind(&CameraNodelet::Config, this, std::placeholders::_1, std::placeholders::_2)); - - this->trigger_srv_ = this->np_.advertiseService( - "Trigger", std::bind(&CameraNodelet::Trigger, this, std::placeholders::_1, std::placeholders::_2)); - - this->soft_off_srv_ = this->np_.advertiseService( - "SoftOff", std::bind(&CameraNodelet::SoftOff, this, std::placeholders::_1, std::placeholders::_2)); - - this->soft_on_srv_ = this->np_.advertiseService( - "SoftOn", std::bind(&CameraNodelet::SoftOn, this, std::placeholders::_1, std::placeholders::_2)); - - NODELET_DEBUG_STREAM("after advertise service"); - //---------------------------------- - // Fire off our main publishing loop - //---------------------------------- - this->publoop_timer_ = this->np_.createTimer( - ros::Duration(.001), [this](const ros::TimerEvent& t) { this->Run(); }, - true); // oneshot timer -} - -bool ifm3d_ros::CameraNodelet::Dump(ifm3d_ros_msgs::Dump::Request& req, ifm3d_ros_msgs::Dump::Response& res) -{ - std::lock_guard lock(this->mutex_); - res.status = 0; - - try - { - json j = this->cam_->ToJSON(); - res.config = j.dump(); - } - catch (const ifm3d::error_t& ex) - { - res.status = ex.code(); - NODELET_WARN_STREAM(ex.what()); - } - catch (const std::exception& std_ex) - { - res.status = -1; - NODELET_WARN_STREAM(std_ex.what()); - } - catch (...) - { - res.status = -2; - } - - if (res.status != 0) - { - NODELET_WARN_STREAM("Dump: " << res.status); - } - - return true; -} - -bool ifm3d_ros::CameraNodelet::Config(ifm3d_ros_msgs::Config::Request& req, ifm3d_ros_msgs::Config::Response& res) -{ - std::lock_guard lock(this->mutex_); - res.status = 0; - res.msg = "OK"; - - try - { - this->cam_->FromJSON(json::parse(req.json)); - } - catch (const ifm3d::error_t& ex) - { - res.status = ex.code(); - res.msg = ex.what(); - } - catch (const std::exception& std_ex) - { - res.status = -1; - res.msg = std_ex.what(); - } - catch (...) - { - res.status = -2; - res.msg = "Unknown error in `Config'"; - } - - if (res.status != 0) - { - NODELET_WARN_STREAM("Config: " << res.status << " - " << res.msg); - } - - return true; -} - -bool ifm3d_ros::CameraNodelet::Trigger(ifm3d_ros_msgs::Trigger::Request& req, ifm3d_ros_msgs::Trigger::Response& res) -{ - std::lock_guard lock(this->mutex_); - res.status = 0; - res.msg = "Software trigger is currently not implemented"; - - try - { - this->fg_->SWTrigger(); - } - catch (const ifm3d::error_t& ex) - { - res.status = ex.code(); - } - - NODELET_WARN_STREAM("Triggering a camera head is currently not implemented - will follow"); - return true; -} - -// this is a dummy method for the moment: the idea of applications is not supported for the O3RCamera -// we keep this in to possibly keep it comparable / interoperable with the ROS wrappers for other ifm cameras -bool ifm3d_ros::CameraNodelet::SoftOff(ifm3d_ros_msgs::SoftOff::Request& req, ifm3d_ros_msgs::SoftOff::Response& res) -{ - std::lock_guard lock(this->mutex_); - res.status = 0; - - int port_arg = -1; - - try - { - port_arg = static_cast(this->pcic_port_) % 50010; - - // Configure the device from a json string - this->cam_->FromJSONStr("{\"ports\":{\"port" + std::to_string(port_arg) + "\": {\"state\": \"IDLE\"}}}"); - - this->assume_sw_triggered_ = false; - this->timeout_millis_ = this->soft_on_timeout_millis_; - this->timeout_tolerance_secs_ = this->soft_on_timeout_tolerance_secs_; - } - catch (const ifm3d::error_t& ex) - { - res.status = ex.code(); - res.msg = ex.what(); - return false; - } - - NODELET_WARN_STREAM("The concept of applications is not available for the O3R - we use IDLE and RUN states instead"); - res.msg = "{\"ports\":{\"port" + std::to_string(port_arg) + "\": {\"state\": \"IDLE\"}}}"; - - return true; -} - -// this is a dummy method for the moment: the idea of applications is not supported for the O3RCamera -// we keep this in to possibly keep it comparable / interoperable with the ROS wrappers for other ifm cameras -bool ifm3d_ros::CameraNodelet::SoftOn(ifm3d_ros_msgs::SoftOn::Request& req, ifm3d_ros_msgs::SoftOn::Response& res) -{ - std::lock_guard lock(this->mutex_); - res.status = 0; - int port_arg = -1; - - try - { - port_arg = static_cast(this->pcic_port_) % 50010; - - // try getting a current configuration as an ifm3d dump - // this way a a-priori test before setting the state can be tested - // try - // { - // json j = this->cam_->ToJSON(); - // } - // catch (const ifm3d::error_t& ex) - // { - // NODELET_WARN_STREAM(ex.code()); - // NODELET_WARN_STREAM(ex.what()); - // } - // catch (const std::exception& std_ex) - // { - // NODELET_WARN_STREAM(std_ex.what()); - // } - - // Configure the device from a json string - this->cam_->FromJSONStr("{\"ports\":{\"port" + std::to_string(port_arg) + "\": {\"state\": \"RUN\"}}}"); - - this->assume_sw_triggered_ = false; - this->timeout_millis_ = this->soft_on_timeout_millis_; - this->timeout_tolerance_secs_ = this->soft_on_timeout_tolerance_secs_; - } - catch (const ifm3d::error_t& ex) - { - res.status = ex.code(); - res.msg = ex.what(); - return false; - } - - NODELET_WARN_STREAM("The concept of applications is not available for the O3R - we use IDLE and RUN states instead"); - res.msg = "{\"ports\":{\"port" + std::to_string(port_arg) + "\": {\"state\": \"RUN\"}}}"; - - return true; -} - -bool ifm3d_ros::CameraNodelet::InitStructures(std::uint16_t mask, std::uint16_t pcic_port) -{ - std::lock_guard lock(this->mutex_); - bool retval = false; - - try - { - NODELET_INFO_STREAM("Running dtors..."); - this->im_.reset(); - this->fg_.reset(); - this->cam_.reset(); - - NODELET_INFO_STREAM("Initializing camera..."); - this->cam_ = ifm3d::CameraBase::MakeShared(); - // this->cam_ = ifm3d::CameraBase::MakeShared(this->camera_ip_, this->xmlrpc_port_); - // this->cam_ = std::make_shared(this->camera_ip_, this->xmlrpc_port_); - ros::Duration(1.0).sleep(); - - NODELET_INFO_STREAM("Initializing framegrabber..."); - this->fg_ = std::make_shared(this->cam_, mask, this->pcic_port_); - NODELET_INFO("Nodelet arguments: %d, %d", (int)mask, (int)this->pcic_port_); - - NODELET_INFO_STREAM("Initializing image buffer..."); - this->im_ = std::make_shared(); - - retval = true; - } - catch (const ifm3d::error_t& ex) - { - NODELET_WARN_STREAM(ex.code() << ": " << ex.what()); - this->im_.reset(); - this->fg_.reset(); - this->cam_.reset(); - retval = false; - } - - return retval; -} - -// this is the helper function for retrieving complete pcic frames -bool ifm3d_ros::CameraNodelet::AcquireFrame() -{ - std::lock_guard lock(this->mutex_); - bool retval = false; - NODELET_DEBUG_STREAM("try receiving data via fg WaitForFrame"); - try - { - retval = this->fg_->WaitForFrame(this->im_.get(), this->timeout_millis_); - } - catch (const ifm3d::error_t& ex) - { - NODELET_WARN_STREAM(ex.code() << ": " << ex.what()); - retval = false; - } - - return retval; -} - -void ifm3d_ros::CameraNodelet::Run() -{ - std::unique_lock lock(this->mutex_, std::defer_lock); - - NODELET_DEBUG_STREAM("in Run"); - - // We need to account for the case of when the nodelet is being started prior - // to the camera being plugged in. - - while (ros::ok() && (!this->InitStructures(ifm3d::IMG_UVEC, this->pcic_port_))) - { - NODELET_WARN_STREAM("Could not initialize pixel stream!"); - ros::Duration(1.0).sleep(); - } - - pcl::PointCloud::Ptr cloud(new pcl::PointCloud()); - - cv::Mat confidence_img; - cv::Mat distance_img; - // cv::Mat distance_noise_img; - cv::Mat amplitude_img; - cv::Mat xyz_img; - cv::Mat raw_amplitude_img; - cv::Mat good_bad_pixels_img; - cv::Mat gray_img; - cv::Mat rgb_img; - - NODELET_DEBUG_STREAM("after initializing the opencv buffers"); - std::vector extrinsics(6); - - // XXX: need to implement a nice strategy for getting the actual times - // from the camera which are registered to the frame data in the image - // buffer. - ros::Time last_frame = ros::Time::now(); - bool got_uvec = false; - - while (ros::ok()) - { - if (!this->AcquireFrame()) - { - if (!this->assume_sw_triggered_) - { - NODELET_WARN_STREAM("Timeout waiting for camera!"); - } - else - { - ros::Duration(.001).sleep(); - } - - if ((ros::Time::now() - last_frame).toSec() > this->timeout_tolerance_secs_) - { - NODELET_WARN_STREAM("Attempting to restart framegrabber..."); - while (!this->InitStructures(got_uvec ? this->schema_mask_ : ifm3d::IMG_UVEC, this->pcic_port_)) - { - NODELET_WARN_STREAM("Could not re-initialize pixel stream!"); - ros::Duration(1.0).sleep(); - } - - last_frame = ros::Time::now(); - } - - continue; - } - - last_frame = ros::Time::now(); - - NODELET_DEBUG_STREAM("prepare header"); - std_msgs::Header head = std_msgs::Header(); - head.frame_id = this->frame_id_; - head.stamp = ros::Time(std::chrono::duration_cast>>( - this->im_->TimeStamp().time_since_epoch()) - .count()); - if ((ros::Time::now() - head.stamp) > ros::Duration(this->frame_latency_thresh_)) - { - NODELET_INFO_ONCE("Camera's time and client's time are not synced"); - head.stamp = ros::Time::now(); - } - NODELET_DEBUG_STREAM("in header, before setting header to msgs"); - std_msgs::Header optical_head = std_msgs::Header(); - optical_head.stamp = head.stamp; - optical_head.frame_id = this->optical_frame_id_; - - // currently the unit vector calculation seems to be missing in the ifm3d state: therefore we don't publish anything - // to the uvec pubisher publish unit vectors once on a latched topic, then re-initialize the framegrabber with the - // user's requested schema mask - if (!got_uvec) - { - lock.lock(); - sensor_msgs::ImagePtr uvec_msg = - cv_bridge::CvImage(optical_head, enc::TYPE_32FC3, this->im_->UnitVectors()).toImageMsg(); - NODELET_INFO_STREAM("uvec image size: " << this->im_->UnitVectors().size()); - lock.unlock(); - this->uvec_pub_.publish(uvec_msg); - got_uvec = true; - NODELET_INFO("Got unit vectors, restarting framegrabber with mask: %d", (int)this->schema_mask_); - - while (!this->InitStructures(this->schema_mask_, this->pcic_port_)) - { - NODELET_WARN("Could not re-initialize pixel stream!"); - ros::Duration(1.0).sleep(); - } - - NODELET_INFO_STREAM("Start streaming data"); - continue; - } - - // - // Pull out all the wrapped images so that we can release the "GIL" - // while publishing - // - lock.lock(); - - NODELET_DEBUG_STREAM("start getting data"); - try - { - // boost::shared_ptr vs std::shared_ptr forces this copy - pcl::copyPointCloud(*(this->im_->Cloud().get()), *cloud); - xyz_img = this->im_->XYZImage(); - confidence_img = this->im_->ConfidenceImage(); - distance_img = this->im_->DistanceImage(); - amplitude_img = this->im_->AmplitudeImage(); - raw_amplitude_img = this->im_->RawAmplitudeImage(); - gray_img = this->im_->GrayImage(); - extrinsics = this->im_->Extrinsics(); - rgb_img = this->im_->JPEGImage(); - } - catch (const ifm3d::error_t& ex) - { - NODELET_WARN_STREAM(ex.what()); - } - catch (const std::exception& std_ex) - { - NODELET_WARN_STREAM(std_ex.what()); - } - NODELET_DEBUG_STREAM("finished getting data"); - - lock.unlock(); - - // - // Now, do the publishing - // - - NODELET_DEBUG_STREAM("start publishing"); - // Confidence image is invariant - no need to check the mask - sensor_msgs::ImagePtr confidence_msg = cv_bridge::CvImage(optical_head, "mono16", confidence_img).toImageMsg(); - this->conf_pub_.publish(confidence_msg); - NODELET_DEBUG_STREAM("after publishing confidence image"); - - if ((this->schema_mask_ & ifm3d::IMG_CART) == ifm3d::IMG_CART) - { - cloud->header = pcl_conversions::toPCL(head); - this->cloud_pub_.publish(cloud); - - sensor_msgs::ImagePtr xyz_image_msg = - cv_bridge::CvImage(head, xyz_img.type() == CV_32FC3 ? enc::TYPE_32FC3 : enc::TYPE_16SC3, xyz_img) - .toImageMsg(); - this->xyz_image_pub_.publish(xyz_image_msg); - NODELET_DEBUG_STREAM("after publishing xyz image"); - } - - if ((this->schema_mask_ & ifm3d::IMG_RDIS) == ifm3d::IMG_RDIS) - { - sensor_msgs::ImagePtr distance_msg = - cv_bridge::CvImage(optical_head, distance_img.type() == CV_32FC1 ? enc::TYPE_32FC1 : enc::TYPE_16UC1, - distance_img) - .toImageMsg(); - this->distance_pub_.publish(distance_msg); - NODELET_DEBUG_STREAM("after publishing distance image"); - } - - // this image is currently not available via the ifm3d - // if ((this->schema_mask_ & ifm3d::IMG_DIS_NOISE) == ifm3d::IMG_DIS_NOISE) - // { - // sensor_msgs::ImagePtr distance_noise_msg = - // cv_bridge::CvImage(optical_head, - // distance_noise_img.type() == CV_32FC1 ? - // enc::TYPE_32FC1 : enc::TYPE_16UC1, - // distance_noise_img).toImageMsg(); - // this->distance_noise_pub_.publish(distance_noise_msg); - // } - - if ((this->schema_mask_ & ifm3d::IMG_AMP) == ifm3d::IMG_AMP) - { - sensor_msgs::ImagePtr amplitude_msg = - cv_bridge::CvImage(optical_head, amplitude_img.type() == CV_32FC1 ? enc::TYPE_32FC1 : enc::TYPE_16UC1, - amplitude_img) - .toImageMsg(); - this->amplitude_pub_.publish(amplitude_msg); - NODELET_DEBUG_STREAM("after publishing amplitude image"); - } - - if ((this->schema_mask_ & ifm3d::IMG_RAMP) == ifm3d::IMG_RAMP) - { - sensor_msgs::ImagePtr raw_amplitude_msg = - cv_bridge::CvImage(optical_head, raw_amplitude_img.type() == CV_32FC1 ? enc::TYPE_32FC1 : enc::TYPE_16UC1, - raw_amplitude_img) - .toImageMsg(); - this->raw_amplitude_pub_.publish(raw_amplitude_msg); - NODELET_DEBUG_STREAM("Raw amplitude image publisher is a dummy publisher - data will be added soon"); - NODELET_DEBUG_STREAM("after publishing raw amplitude image"); - } - - if ((this->schema_mask_ & ifm3d::IMG_GRAY) == ifm3d::IMG_GRAY) - { - sensor_msgs::ImagePtr gray_image_msg = - cv_bridge::CvImage(optical_head, gray_img.type() == CV_32FC1 ? enc::TYPE_32FC1 : enc::TYPE_16UC1, gray_img) - .toImageMsg(); - this->gray_image_pub_.publish(gray_image_msg); - NODELET_DEBUG_STREAM("Gray image publisher is a dummy publisher - data will be added soon"); - NODELET_DEBUG_STREAM("after publishing gray image"); - } - - // TODO: this casting of the confidence image to a boolean value image needs to be tested: - // inv cast might be reqiured depending on the interpretation of the binary image - - int const min_binary_value = 0; - int const max_binary_value = 100; - cv::threshold(confidence_img, good_bad_pixels_img, min_binary_value, max_binary_value, cv::THRESH_BINARY); - good_bad_pixels_img.convertTo(good_bad_pixels_img, CV_8U); - - sensor_msgs::ImagePtr good_bad_msg = cv_bridge::CvImage(optical_head, "mono8", good_bad_pixels_img).toImageMsg(); - this->good_bad_pub_.publish(good_bad_msg); - NODELET_DEBUG_STREAM("after publishing good/bad pixel image image"); - - // The 2D is not yet settable in the schema mask: publish all the time - - if (!rgb_img.empty()) - { - cv::Mat im_decode = cv::imdecode(rgb_img, cv::IMREAD_UNCHANGED); - sensor_msgs::ImagePtr rgb_image_msg = cv_bridge::CvImage(optical_head, "bgr8", im_decode).toImageMsg(); - this->rgb_image_pub_.publish(rgb_image_msg); - NODELET_DEBUG_STREAM("after publishing rgb image"); - } - - // - // publish extrinsics - // - NODELET_DEBUG_STREAM("start publishing extrinsics"); - ifm3d_ros_msgs::Extrinsics extrinsics_msg; - extrinsics_msg.header = optical_head; - try - { - extrinsics_msg.tx = extrinsics.at(0); - extrinsics_msg.ty = extrinsics.at(1); - extrinsics_msg.tz = extrinsics.at(2); - extrinsics_msg.rot_x = extrinsics.at(3); - extrinsics_msg.rot_y = extrinsics.at(4); - extrinsics_msg.rot_z = extrinsics.at(5); - } - catch (const std::out_of_range& ex) - { - NODELET_WARN("out-of-range error fetching extrinsics"); - } - this->extrinsics_pub_.publish(extrinsics_msg); - - } // end: while (ros::ok()) { ... } -} // end: Run() - -PLUGINLIB_EXPORT_CLASS(ifm3d_ros::CameraNodelet, nodelet::Nodelet) diff --git a/ifm3d_ros_driver/test/gradient.jpg b/ifm3d_ros_driver/test/gradient.jpg deleted file mode 100644 index e2d788b633a7ea0e3fe6450e3d191f13ccb3067e..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1363 zcmeH`K}_0E7{^~*XrWpGL55(kxS}{1nUjc1x(udsbjBEW8aER-NaEb$smm@9)R{#V zEQtpX#uzTUO%6*;c0jif$u5Qyn`Xg`-FE19*l7vtdrgX-mfiQ-{L*}V?|uL8egD_0 zw;I6wU`m(*7zO~QJfL+7R)CSD3>4X8pbRu^)H94;ufW78pSB*my~kp;I{JL9!|8Qd zt)3B&ci0~c2Cwvwj*kYyzUx6hM$@#irb~JKz1Cj;KaW-!SPbAbc8$OW0B*qu3)cDo z9Ewb3fc7ACxPems*v*&Y$_yN?uw9ys*1@Rd;vQ=BGw38RB^6--cYyqR=~1O=^ll1C z<6yp8?0{f~(n5ow($R(qf%fpeH1AuH_pnJfMy2Oq)D~@+MdDCHw0I*$RFe!Nzr$YHx~PD=RP{lG8|0H)p|pjBt%g*^4P8>?|gD- z)l8vE+Vb&r9yb9|!$N3{VV?zFPP1_Y?v=oP8LNzSxhvl`mLd{NE2TQOBPEEMsM`T2 znml>WdbCcUO3>*e`D#me*cXJ5bArtCTlc*A0D^R%%Rg}?T$CxXTnV!ROe=)eX4p7H zipOWcf+kO#GoDXks1kJgs(jQEH|z_7lksF@?&$&P*p47vm15!CelGiB{~+PYb1*Hp zJu#RMK!kR%p>#--hin8;B^TtQmZ)Zf-eSo7VbKIl*@3`qRykLtUO9YUKikh8cf+*Z zGoC`s4&j^yg|btVr`iZrazQ?7iE1|JEixOMuTjvHdKIyz#C%;$%%6Y%e - - - - - diff --git a/ifm3d_ros_driver/test/test_camera.py b/ifm3d_ros_driver/test/test_camera.py deleted file mode 100755 index 3f11705..0000000 --- a/ifm3d_ros_driver/test/test_camera.py +++ /dev/null @@ -1,240 +0,0 @@ -#!/usr/bin/env python -# -*- python -*- - -# SPDX-License-Identifier: Apache-2.0 -# Copyright (C) 2021 ifm electronic, gmbh - - -import sys -import time -import unittest -import rospy -import rostest -import numpy as np -import tf2_ros -import tf2_geometry_msgs -from sensor_msgs.msg import Image -from geometry_msgs.msg import PointStamped -from cv_bridge import CvBridge, CvBridgeError -from ifm3d.msg import Extrinsics - -# XXX: TP debugging -#np.set_printoptions(threshold=np.nan) - -class TestCamera(unittest.TestCase): - """ - TP: 14 May 2018 - heavily adapted from my old o3d3xx-ros test of the same - name. - - This class tests the following: - - Getting data from the camera - - Computing the Cartesian data and comparing it to ground truth - - To do the comparison to ground truth, the computed cartesian data - must be transformed, to do that we use the tf2 API. It follows that - this indirectly is testing our tf2 static publisher which is publishing - the transform between the optical and camera frames - - NOTE: The camera h/w is needed to run this test. - """ - - def __init__(self, *args): - super(TestCamera, self).__init__(*args) - self.success_ = False - - self.cloud_ = None # ground truth for cartesian computation - self.rdis_ = None - self.uvec_ = None - self.extrinsics_ = None - self.conf_ = None - - def test_camera(self): - time.sleep(5.0) # <-- wait for rosmaster and ifm3d nodelet - rospy.init_node('test_camera') - - self.bridge_ = CvBridge() - self.rdis_sub_ = \ - rospy.Subscriber("/ifm3d/camera/distance", Image, self.image_cb, - queue_size=None, callback_args="rdis") - self.cloud_sub_ = \ - rospy.Subscriber("/ifm3d/camera/xyz_image", Image, self.image_cb, - queue_size=None, callback_args="cloud") - self.uvec_sub_ = \ - rospy.Subscriber("/ifm3d/camera/unit_vectors", Image, self.image_cb, - queue_size=None, callback_args="uvec") - self.extrinsics_sub_ = \ - rospy.Subscriber("/ifm3d/camera/extrinsics", Extrinsics, - self.extrinsics_cb, queue_size=None) - self.conf_sub_ = \ - rospy.Subscriber("/ifm3d/camera/confidence", Image, self.image_cb, - queue_size=None, callback_args="conf") - - # If it takes more than 10 secs to run our test, something is wrong. - timeout_t = time.time() + 10.0 - rate = rospy.Rate(10.0) - while ((not rospy.is_shutdown()) and - (not self.success_) and - (time.time() < timeout_t)): - # Make sure we have all the data we need to compute - if ((self.rdis_ is not None) and - (self.cloud_ is not None) and - (self.uvec_ is not None) and - (self.extrinsics_ is not None) and - (self.conf_ is not None)): - - # Make sure the cloud, conf, and rdis are from the same image - # acquisition. - d = self.rdis_.header.stamp - self.cloud_.header.stamp - if d.to_sec() == 0: - d2 = self.rdis_.header.stamp - self.conf_.header.stamp - if d2.to_sec() == 0: - self.success_ = self.compute_cartesian() - break - else: - # get new data - self.rdis_ = None - self.cloud_ = None - self.conf_ = None - else: - # get new data - self.rdis_ = None - self.cloud_ = None - self.conf_ = None - - rate.sleep() - - self.assertTrue(self.success_) - - def extrinsics_cb(self, data, *args): - if self.extrinsics_ is None: - self.extrinsics_ = data - - def image_cb(self, data, *args): - im_type = args[0] - if im_type == "rdis": - if self.rdis_ is None: - self.rdis_ = data - elif im_type == "cloud": - if self.cloud_ is None: - self.cloud_ = data - elif im_type == "uvec": - if self.uvec_ is None: - self.uvec_ = data - elif im_type == "conf": - if self.conf_ is None: - self.conf_ = data - - def compute_cartesian(self): - """ - Computes the Cartesian data from the radial distance image, unit - vectors, and extrinsics. Then transforms it to the camera frame using - the tf2 api. Once transformed, it will do a pixel-by-pixel comparision - to ground truth. - - Returns a bool indicating the the success of the computation. - """ - rdis = np.array(self.bridge_.imgmsg_to_cv2(self.rdis_)) - uvec = np.array(self.bridge_.imgmsg_to_cv2(self.uvec_)) - cloud = np.array(self.bridge_.imgmsg_to_cv2(self.cloud_)) - conf = np.array(self.bridge_.imgmsg_to_cv2(self.conf_)) - - # split out the camera-computed image planes - x_cam = cloud[:,:,0] - y_cam = cloud[:,:,1] - z_cam = cloud[:,:,2] - if ((cloud.dtype == np.float32) or - (cloud.dtype == np.float64)): - # convert to mm - x_cam *= 1000. - y_cam *= 1000. - z_cam *= 1000. - - # cast to int16_t - x_cam = x_cam.astype(np.int16) - y_cam = y_cam.astype(np.int16) - z_cam = z_cam.astype(np.int16) - else: - # camera data are already in mm - pass - - # Get the unit vectors - ex = uvec[:,:,0] - ey = uvec[:,:,1] - ez = uvec[:,:,2] - - # translation vector from extrinsics - tx = self.extrinsics_.tx - ty = self.extrinsics_.ty - tz = self.extrinsics_.tz - - # Cast the radial distance image to float - rdis_f = rdis.astype(np.float32) - if (rdis.dtype == np.float32): - # assume rdis was in meters, convert to mm - rdis_f *= 1000. - - # Compute Cartesian - x_ = ex * rdis_f + tx - y_ = ey * rdis_f + ty - z_ = ez * rdis_f + tz - - # mask out bad pixels from our computed cartesian values - bad_mask = (np.bitwise_and(conf, 0x1) == 0x1) - x_[bad_mask] = 0. - y_[bad_mask] = 0. - z_[bad_mask] = 0. - - # Transform to target frame - # - # NOTE: This could obviously be vectorized if we exploit our apriori - # knowledge of the transform, but we want to test the transform we are - # broadcasting via tf and the tf2 api for doing the transformation. - # - # I agree, this loop is slow and ugly :-( -- mostly b/c using the tf2 - # interface with our data structures here is kind of wonky - # - tf_buffer = tf2_ros.Buffer() - tf_listener = tf2_ros.TransformListener(tf_buffer) - n_rows = x_.shape[0] - n_cols = x_.shape[1] - x_f = np.zeros((n_rows, n_cols), dtype=np.float32) - y_f = np.zeros((n_rows, n_cols), dtype=np.float32) - z_f = np.zeros((n_rows, n_cols), dtype=np.float32) - for i in range(n_rows): - for j in range(n_cols): - p = PointStamped() - p.header = self.rdis_.header - p.point.x = x_[i,j] - p.point.y = y_[i,j] - p.point.z = z_[i,j] - pt = tf_buffer.transform(p, self.cloud_.header.frame_id, - rospy.Duration(2.0)) - x_f[i,j] = pt.point.x - y_f[i,j] = pt.point.y - z_f[i,j] = pt.point.z - - # cast to the data type of the point cloud - x_i = x_f.astype(np.int16) - y_i = y_f.astype(np.int16) - z_i = z_f.astype(np.int16) - - tol = 10 # milli-meters - x_mask = np.fabs(x_i - x_cam) > tol - y_mask = np.fabs(y_i - y_cam) > tol - z_mask = np.fabs(z_i - z_cam) > tol - - # we are asserting that no pixels are out-of-tolerance - # per the computation of the x_,y_,z_mask variables above. - self.assertTrue(x_mask.sum() == 0) - self.assertTrue(y_mask.sum() == 0) - self.assertTrue(z_mask.sum() == 0) - - # if any of the above asserts fail, the test will error out, - # so, we return True here carte blanche - return True - -def main(): - rostest.rosrun('ifm3d', 'test_camera', TestCamera, sys.argv) - return 0 - -if __name__ == '__main__': - sys.exit(main()) diff --git a/ifm3d_ros_driver/test/test_threshold.py b/ifm3d_ros_driver/test/test_threshold.py deleted file mode 100644 index 7d1d7ba..0000000 --- a/ifm3d_ros_driver/test/test_threshold.py +++ /dev/null @@ -1,41 +0,0 @@ -import cv2 as cv -import numpy as np -from matplotlib import pyplot as plt - -def test_random(): - min = 50 - max = 200 - img = np.random.randint(0,200, size=(172,224), dtype=np.uint16) - ret,thresh1 = cv.threshold(img,min,max,cv.THRESH_BINARY) - ret,thresh2 = cv.threshold(img,min,max,cv.THRESH_BINARY_INV) - ret,thresh3 = cv.threshold(img,min,max,cv.THRESH_TRUNC) - ret,thresh4 = cv.threshold(img,min,max,cv.THRESH_TOZERO) - ret,thresh5 = cv.threshold(img,min,max,cv.THRESH_TOZERO_INV) - - titles = ['Original Image','BINARY','BINARY_INV','TRUNC','TOZERO','TOZERO_INV'] - images = [img, thresh1, thresh2, thresh3, thresh4, thresh5] - for i in range(6): - plt.subplot(2,3,i+1),plt.imshow(images[i],'gray',vmin=0,vmax=255) - plt.title(titles[i]) - plt.xticks([]),plt.yticks([]) - plt.show() - - -def test_image(): - img = cv.imread('gradient.jpg',0) - ret,thresh1 = cv.threshold(img,127,255,cv.THRESH_BINARY) - ret,thresh2 = cv.threshold(img,127,255,cv.THRESH_BINARY_INV) - ret,thresh3 = cv.threshold(img,127,255,cv.THRESH_TRUNC) - ret,thresh4 = cv.threshold(img,127,255,cv.THRESH_TOZERO) - ret,thresh5 = cv.threshold(img,127,255,cv.THRESH_TOZERO_INV) - - titles = ['Original Image','BINARY','BINARY_INV','TRUNC','TOZERO','TOZERO_INV'] - images = [img, thresh1, thresh2, thresh3, thresh4, thresh5] - for i in range(6): - plt.subplot(2,3,i+1),plt.imshow(images[i],'gray',vmin=0,vmax=255) - plt.title(titles[i]) - plt.xticks([]),plt.yticks([]) - plt.show() - -if __name__ == '__main__': - test_random() diff --git a/ifm3d_ros_examples/CMakeLists.txt b/ifm3d_ros_examples/CMakeLists.txt deleted file mode 100644 index bfd7203..0000000 --- a/ifm3d_ros_examples/CMakeLists.txt +++ /dev/null @@ -1,19 +0,0 @@ -cmake_minimum_required(VERSION 3.0.2) -project(ifm3d_ros_examples) - -find_package(catkin REQUIRED COMPONENTS - tf2_ros - nodelet - ifm3d_ros_driver - ifm3d_ros_msgs -) - - -catkin_package() - -########### -## Build ## -########### -include_directories( - ${catkin_INCLUDE_DIRS} -) diff --git a/ifm3d_ros_examples/LICENSE b/ifm3d_ros_examples/LICENSE deleted file mode 100644 index 7a4a3ea..0000000 --- a/ifm3d_ros_examples/LICENSE +++ /dev/null @@ -1,202 +0,0 @@ - - Apache License - Version 2.0, January 2004 - http://www.apache.org/licenses/ - - TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION - - 1. Definitions. - - "License" shall mean the terms and conditions for use, reproduction, - and distribution as defined by Sections 1 through 9 of this document. - - "Licensor" shall mean the copyright owner or entity authorized by - the copyright owner that is granting the License. - - "Legal Entity" shall mean the union of the acting entity and all - other entities that control, are controlled by, or are under common - control with that entity. For the purposes of this definition, - "control" means (i) the power, direct or indirect, to cause the - direction or management of such entity, whether by contract or - otherwise, or (ii) ownership of fifty percent (50%) or more of the - outstanding shares, or (iii) beneficial ownership of such entity. - - "You" (or "Your") shall mean an individual or Legal Entity - exercising permissions granted by this License. - - "Source" form shall mean the preferred form for making modifications, - including but not limited to software source code, documentation - source, and configuration files. - - "Object" form shall mean any form resulting from mechanical - transformation or translation of a Source form, including but - not limited to compiled object code, generated documentation, - and conversions to other media types. - - "Work" shall mean the work of authorship, whether in Source or - Object form, made available under the License, as indicated by a - copyright notice that is included in or attached to the work - (an example is provided in the Appendix below). - - "Derivative Works" shall mean any work, whether in Source or Object - form, that is based on (or derived from) the Work and for which the - editorial revisions, annotations, elaborations, or other modifications - represent, as a whole, an original work of authorship. For the purposes - of this License, Derivative Works shall not include works that remain - separable from, or merely link (or bind by name) to the interfaces of, - the Work and Derivative Works thereof. - - "Contribution" shall mean any work of authorship, including - the original version of the Work and any modifications or additions - to that Work or Derivative Works thereof, that is intentionally - submitted to Licensor for inclusion in the Work by the copyright owner - or by an individual or Legal Entity authorized to submit on behalf of - the copyright owner. For the purposes of this definition, "submitted" - means any form of electronic, verbal, or written communication sent - to the Licensor or its representatives, including but not limited to - communication on electronic mailing lists, source code control systems, - and issue tracking systems that are managed by, or on behalf of, the - Licensor for the purpose of discussing and improving the Work, but - excluding communication that is conspicuously marked or otherwise - designated in writing by the copyright owner as "Not a Contribution." - - "Contributor" shall mean Licensor and any individual or Legal Entity - on behalf of whom a Contribution has been received by Licensor and - subsequently incorporated within the Work. - - 2. Grant of Copyright License. Subject to the terms and conditions of - this License, each Contributor hereby grants to You a perpetual, - worldwide, non-exclusive, no-charge, royalty-free, irrevocable - copyright license to reproduce, prepare Derivative Works of, - publicly display, publicly perform, sublicense, and distribute the - Work and such Derivative Works in Source or Object form. - - 3. Grant of Patent License. Subject to the terms and conditions of - this License, each Contributor hereby grants to You a perpetual, - worldwide, non-exclusive, no-charge, royalty-free, irrevocable - (except as stated in this section) patent license to make, have made, - use, offer to sell, sell, import, and otherwise transfer the Work, - where such license applies only to those patent claims licensable - by such Contributor that are necessarily infringed by their - Contribution(s) alone or by combination of their Contribution(s) - with the Work to which such Contribution(s) was submitted. If You - institute patent litigation against any entity (including a - cross-claim or counterclaim in a lawsuit) alleging that the Work - or a Contribution incorporated within the Work constitutes direct - or contributory patent infringement, then any patent licenses - granted to You under this License for that Work shall terminate - as of the date such litigation is filed. - - 4. Redistribution. You may reproduce and distribute copies of the - Work or Derivative Works thereof in any medium, with or without - modifications, and in Source or Object form, provided that You - meet the following conditions: - - (a) You must give any other recipients of the Work or - Derivative Works a copy of this License; and - - (b) You must cause any modified files to carry prominent notices - stating that You changed the files; and - - (c) You must retain, in the Source form of any Derivative Works - that You distribute, all copyright, patent, trademark, and - attribution notices from the Source form of the Work, - excluding those notices that do not pertain to any part of - the Derivative Works; and - - (d) If the Work includes a "NOTICE" text file as part of its - distribution, then any Derivative Works that You distribute must - include a readable copy of the attribution notices contained - within such NOTICE file, excluding those notices that do not - pertain to any part of the Derivative Works, in at least one - of the following places: within a NOTICE text file distributed - as part of the Derivative Works; within the Source form or - documentation, if provided along with the Derivative Works; or, - within a display generated by the Derivative Works, if and - wherever such third-party notices normally appear. The contents - of the NOTICE file are for informational purposes only and - do not modify the License. You may add Your own attribution - notices within Derivative Works that You distribute, alongside - or as an addendum to the NOTICE text from the Work, provided - that such additional attribution notices cannot be construed - as modifying the License. - - You may add Your own copyright statement to Your modifications and - may provide additional or different license terms and conditions - for use, reproduction, or distribution of Your modifications, or - for any such Derivative Works as a whole, provided Your use, - reproduction, and distribution of the Work otherwise complies with - the conditions stated in this License. - - 5. Submission of Contributions. Unless You explicitly state otherwise, - any Contribution intentionally submitted for inclusion in the Work - by You to the Licensor shall be under the terms and conditions of - this License, without any additional terms or conditions. - Notwithstanding the above, nothing herein shall supersede or modify - the terms of any separate license agreement you may have executed - with Licensor regarding such Contributions. - - 6. Trademarks. This License does not grant permission to use the trade - names, trademarks, service marks, or product names of the Licensor, - except as required for reasonable and customary use in describing the - origin of the Work and reproducing the content of the NOTICE file. - - 7. Disclaimer of Warranty. Unless required by applicable law or - agreed to in writing, Licensor provides the Work (and each - Contributor provides its Contributions) on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or - implied, including, without limitation, any warranties or conditions - of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A - PARTICULAR PURPOSE. You are solely responsible for determining the - appropriateness of using or redistributing the Work and assume any - risks associated with Your exercise of permissions under this License. - - 8. Limitation of Liability. In no event and under no legal theory, - whether in tort (including negligence), contract, or otherwise, - unless required by applicable law (such as deliberate and grossly - negligent acts) or agreed to in writing, shall any Contributor be - liable to You for damages, including any direct, indirect, special, - incidental, or consequential damages of any character arising as a - result of this License or out of the use or inability to use the - Work (including but not limited to damages for loss of goodwill, - work stoppage, computer failure or malfunction, or any and all - other commercial damages or losses), even if such Contributor - has been advised of the possibility of such damages. - - 9. Accepting Warranty or Additional Liability. While redistributing - the Work or Derivative Works thereof, You may choose to offer, - and charge a fee for, acceptance of support, warranty, indemnity, - or other liability obligations and/or rights consistent with this - License. However, in accepting such obligations, You may act only - on Your own behalf and on Your sole responsibility, not on behalf - of any other Contributor, and only if You agree to indemnify, - defend, and hold each Contributor harmless for any liability - incurred by, or claims asserted against, such Contributor by reason - of your accepting any such warranty or additional liability. - - END OF TERMS AND CONDITIONS - - APPENDIX: How to apply the Apache License to your work. - - To apply the Apache License to your work, attach the following - boilerplate notice, with the fields enclosed by brackets "[]" - replaced with your own identifying information. (Don't include - the brackets!) The text should be enclosed in the appropriate - comment syntax for the file format. We also recommend that a - file or class name and description of purpose be included on the - same "printed page" as the copyright notice for easier - identification within third-party archives. - - Copyright [yyyy] [name of copyright owner] - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - http://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. \ No newline at end of file diff --git a/ifm3d_ros_examples/README.md b/ifm3d_ros_examples/README.md deleted file mode 100644 index 7a455dd..0000000 --- a/ifm3d_ros_examples/README.md +++ /dev/null @@ -1,41 +0,0 @@ -# The `ifm3d_ros_examples` package -This package provides examples and helper scripts for using the ifm O3R camera platform. - - -## Launchfiles - -Please see the list below for launch files shipped with the examples package: - -| Name | Description | -| ---- | ----------- | -| `six_cameras.launch` | Launches six nodes, reading data streams on ports 0, 1, 2, 3, 4 and 5. Provide coordinate frame transforms for each node. Note: you can use this example for less than six heads, but you will get a `timeout` error where no heads are connected. This does not disrupt the proper functioning of the connected heads.| -| `nodelet.launch` | This is handling the nodelet manager which makes it possible to launch a nodelet similarly as you would a simple node.| -| `head.launch` | Launches two data streams for both the 2D RGB imager and 3D TOF imager on a camera head. Default ports are 0 (pcic_port:=50010) and 2 (pcic_port:=50012). For different port numbers input port as a parameter when launching. | -| `camera.launch` | Launches a single camera stream - so only 3D data or 2D RGB data. This launch file is comparable to a single camera setup (O3Ds and O3Xs) | - -### Nodelet launch structure - ->Note: The O3R platform can handle multiple data streams.* -The `camera.launch` file only launches a node for one data stream, on the default pcic port 50010. To launch a node for a different port, use: -``` -$ roslaunch ifm3d_ros_driver camera.launch pcic_port:= -``` - - -The launch file(s) encapsulate several features: -1. It (partially) exposes the `camera_nodelet` parameters as command-line arguments for ease of runtime configuration. -2. It instantiates a nodelet manager which the `camera_nodelet` will be loaded into. -3. It launches the camera nodelet itself. -4. It publishes the static transform from the camera's optical frame to a traditional ROS sensor frame as a tf2 `static_transform_publisher`. - -You can either use [this launch file](launch/camera.launch) directly, or, use it as a basis for integrating `ifm3d_ros` into your own robot software system. - -> Note: the O3R camera heads carry two imagers, a 3D time-of-flight and a RGB imager. - -We provide the `head.launch` launchfile to handle a whole O3R camera head, that starts two nodes, one for the RGB image (we assume it is plugged in port 0), and one for the 3D imager (we assume it is plugged in port 2). - -## Building launch files distributed systems ->Note: This is WIR. We are currently working on Docker images which will allow you an easy deployment of our ROS node to the VPU. - -# LICENSE -Please see the file called [LICENSE](LICENSE). \ No newline at end of file diff --git a/ifm3d_ros_examples/config/rviz_config.rviz b/ifm3d_ros_examples/config/rviz_config.rviz deleted file mode 100644 index e4054c7..0000000 --- a/ifm3d_ros_examples/config/rviz_config.rviz +++ /dev/null @@ -1,184 +0,0 @@ -Panels: - - Class: rviz/Displays - Help Height: 70 - Name: Displays - Property Tree Widget: - Expanded: ~ - Splitter Ratio: 0.747222245 - Tree Height: 900 - - Class: rviz/Selection - Name: Selection - - Class: rviz/Tool Properties - Expanded: - - /2D Pose Estimate1 - - /2D Nav Goal1 - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 - - Class: rviz/Time - Experimental: false - Name: Time - SyncMode: 0 - SyncSource: PointCloud2 -Preferences: - PromptSaveOnExit: true -Toolbars: - toolButtonStyle: 2 -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 1 - Class: rviz/Grid - Color: 160; 160; 164 - Enabled: true - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 10 - Reference Frame: - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Min Color: 0; 0; 0 - Name: PointCloud2 - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.009999999776482582 - Style: Flat Squares - Topic: /ifm3d/camera1/cloud - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Class: rviz/Image - Enabled: true - Image Topic: /ifm3d/camera1/amplitude - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Image - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Class: rviz/Image - Enabled: true - Image Topic: /ifm3d/camera1/distance - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Image - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Class: rviz/Image - Enabled: true - Image Topic: /ifm3d/camera2/rgb_image - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Image - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Default Light: true - Fixed Frame: map - Frame Rate: 30 - Name: root - Tools: - - Class: rviz/Interact - Hide Inactive Objects: true - - Class: rviz/MoveCamera - - Class: rviz/Select - - Class: rviz/FocusCamera - - Class: rviz/Measure - - Class: rviz/SetInitialPose - Theta std deviation: 0.2617993950843811 - Topic: /initialpose - X std deviation: 0.5 - Y std deviation: 0.5 - - Class: rviz/SetGoal - Topic: /move_base_simple/goal - - Class: rviz/PublishPoint - Single click: true - Topic: /clicked_point - Value: true - Views: - Current: - Class: rviz/Orbit - Distance: 10 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Field of View: 0.7853981852531433 - Focal Point: - X: 0 - Y: 0 - Z: 0 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: 0.45539799332618713 - Target Frame: - Yaw: 0.6153985261917114 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - Height: 1016 - Hide Left Dock: false - Hide Right Dock: true - Image: - collapsed: false - QMainWindow State: 000000ff00000000fd0000000400000000000002670000035afc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000003d000000c9000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d006100670065010000003d000000e20000001600fffffffb0000000a0049006d00610067006503000000000000013800000267000000a3fb0000000a0049006d0061006700650100000125000002720000001600ffffff000000010000010f0000035afc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d0000035a000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000003efc0100000002fb0000000800540069006d0065010000000000000780000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000005130000035a00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Selection: - collapsed: false - Time: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: true - Width: 1920 - X: 0 - Y: 27 diff --git a/ifm3d_ros_examples/examples/README_pointcloud_merge.md b/ifm3d_ros_examples/examples/README_pointcloud_merge.md deleted file mode 100644 index cf5623a..0000000 --- a/ifm3d_ros_examples/examples/README_pointcloud_merge.md +++ /dev/null @@ -1,6 +0,0 @@ -# merging point clouds with `merge_pc.launch` - -Three parts: -1. one node per imager publishing data under it's own namespace -2. set all 3D imagers to run mode using a rosservice call to `SoftOn` -3. link ifm3d optical frame to map frame via a dummy transform publisher: `tf2_ros` with pose parameters = 0 \ No newline at end of file diff --git a/ifm3d_ros_examples/examples/dump.json b/ifm3d_ros_examples/examples/dump.json deleted file mode 100644 index 6ab7a91..0000000 --- a/ifm3d_ros_examples/examples/dump.json +++ /dev/null @@ -1,338 +0,0 @@ -{ - "device": { - "clock": { - "currentTime": 1581092244602229792 - }, - "diagnostic": { - "temperatures": [], - "upTime": 1599000000000 - }, - "info": { - "device": "0301", - "deviceTreeBinaryBlob": "tegra186-quill-p3310-1000-c03-00-base.dtb", - "features": {}, - "name": "", - "partNumber": "M03903", - "productionState": "AA", - "serialNumber": "000201233338", - "vendor": "0001" - }, - "network": { - "authorized_keys": "", - "ipAddressConfig": 0, - "macEth0": "00:04:4B:E4:DA:9E", - "macEth1": "00:02:01:23:33:38", - "networkSpeed": 1000, - "staticIPv4Address": "192.168.0.69", - "staticIPv4Gateway": "192.168.0.201", - "staticIPv4SubNetMask": "255.255.255.0", - "useDHCP": false - }, - "state": { - "errorMessage": "", - "errorNumber": "" - }, - "swVersion": { - "kernel": "4.9.140-l4t-r32.4+g231628d3fa15", - "l4t": "r32.4.3", - "os": "0.13.3-188", - "schema": "feature/O3R-4949", - "swu": "0.15.3" - } - }, - "ports": { - "port0": { - "acquisition": { - "exposureLong": 5000, - "exposureShort": 400, - "framerate": 10.0, - "offset": 0.0, - "version": { - "major": 0, - "minor": 0, - "patch": 0 - } - }, - "data": { - "algoDebugConfig": {}, - "availablePCICOutput": [ - "AMPLITUDE_COMPRESSED", - "CONFIDENCE", - "RADIAL_DISTANCE_COMPRESSED", - "RADIAL_DISTANCE_NOISE", - "REFLECTIVITY", - "TOF_INFO" - ], - "pcicTCPPort": 50010 - }, - "info": { - "device": "3101", - "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", - "features": { - "fov": { - "horizontal": 78, - "vertical": 105 - }, - "resolution": { - "height": 172, - "width": 224 - }, - "type": "3D" - }, - "name": "", - "partNumber": "M03957", - "productionState": "AA", - "sensor": "IRS2381C", - "sensorID": "IRS2381C_105x78_4x2W_110x90_Csample", - "serialNumber": "000000000186", - "vendor": "0001" - }, - "mode": "experimental_high_4m", - "processing": { - "diParam": { - "anfFilterSizeDiv2": 2, - "enableDynamicSymmetry": true, - "enableStraylight": true, - "enableTemporalFilter": true, - "excessiveCorrectionThreshAmp": 0.3, - "excessiveCorrectionThreshDist": 0.08, - "maxDistNoise": 0.02, - "maxSymmetry": 0.4, - "medianSizeDiv2": 0, - "minAmplitude": 20.0, - "minReflectivity": 0.0, - "mixedPixelFilterMode": 1, - "mixedPixelThresholdRad": 0.15 - }, - "extrinsicHeadToUser": { - "rotX": 0.0, - "rotY": 0.0, - "rotZ": 0.0, - "transX": 0.0, - "transY": 0.0, - "transZ": 0.0 - }, - "version": { - "major": 0, - "minor": 0, - "patch": 0 - } - }, - "state": "RUN" - }, - "port1": { - "acquisition": { - "exposureLong": 5000, - "exposureShort": 400, - "framerate": 10.0, - "offset": 0.0, - "version": { - "major": 0, - "minor": 0, - "patch": 0 - } - }, - "data": { - "algoDebugConfig": {}, - "availablePCICOutput": [ - "AMPLITUDE_COMPRESSED", - "CONFIDENCE", - "RADIAL_DISTANCE_COMPRESSED", - "RADIAL_DISTANCE_NOISE", - "REFLECTIVITY", - "TOF_INFO" - ], - "pcicTCPPort": 50011 - }, - "info": { - "device": "3101", - "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", - "features": { - "fov": { - "horizontal": 78, - "vertical": 105 - }, - "resolution": { - "height": 172, - "width": 224 - }, - "type": "3D" - }, - "name": "", - "partNumber": "M03957", - "productionState": "AA", - "sensor": "IRS2381C", - "sensorID": "IRS2381C_105x78_4x2W_110x90_Csample", - "serialNumber": "000000000192", - "vendor": "0001" - }, - "mode": "experimental_high_4m", - "processing": { - "diParam": { - "anfFilterSizeDiv2": 2, - "enableDynamicSymmetry": true, - "enableStraylight": true, - "enableTemporalFilter": true, - "excessiveCorrectionThreshAmp": 0.3, - "excessiveCorrectionThreshDist": 0.08, - "maxDistNoise": 0.02, - "maxSymmetry": 0.4, - "medianSizeDiv2": 0, - "minAmplitude": 20.0, - "minReflectivity": 0.0, - "mixedPixelFilterMode": 1, - "mixedPixelThresholdRad": 0.15 - }, - "extrinsicHeadToUser": { - "rotX": 0.0, - "rotY": 0.0, - "rotZ": 0.0, - "transX": 0.0, - "transY": 0.0, - "transZ": 0.0 - }, - "version": { - "major": 0, - "minor": 0, - "patch": 0 - } - }, - "state": "RUN" - }, - "port2": { - "acquisition": { - "exposureLong": 5000, - "exposureShort": 400, - "framerate": 10.0, - "offset": 0.0, - "version": { - "major": 0, - "minor": 0, - "patch": 0 - } - }, - "data": { - "algoDebugConfig": {}, - "availablePCICOutput": [ - "AMPLITUDE_COMPRESSED", - "CONFIDENCE", - "RADIAL_DISTANCE_COMPRESSED", - "RADIAL_DISTANCE_NOISE", - "REFLECTIVITY", - "TOF_INFO" - ], - "pcicTCPPort": 50012 - }, - "info": { - "device": "2301", - "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", - "features": { - "fov": { - "horizontal": 80, - "vertical": 127 - }, - "resolution": { - "height": 800, - "width": 1280 - }, - "type": "2D" - }, - "name": "", - "partNumber": "M03934", - "productionState": "AA", - "sensor": "OV9782", - "sensorID": "OV9782_127x80_noIllu_Csample", - "serialNumber": "000000000094", - "vendor": "0001" - }, - "mode": "experimental_high_4m", - "processing": { - "diParam": { - "anfFilterSizeDiv2": 2, - "enableDynamicSymmetry": true, - "enableStraylight": true, - "enableTemporalFilter": true, - "excessiveCorrectionThreshAmp": 0.3, - "excessiveCorrectionThreshDist": 0.08, - "maxDistNoise": 0.02, - "maxSymmetry": 0.4, - "medianSizeDiv2": 0, - "minAmplitude": 20.0, - "minReflectivity": 0.0, - "mixedPixelFilterMode": 1, - "mixedPixelThresholdRad": 0.15 - }, - "extrinsicHeadToUser": { - "rotX": 0.0, - "rotY": 0.0, - "rotZ": 0.0, - "transX": 0.0, - "transY": 0.0, - "transZ": 0.0 - }, - "version": { - "major": 0, - "minor": 0, - "patch": 0 - } - }, - "state": "CONF" - }, - "port5": { - "acquisition": { - "framerate": 10.0, - "version": { - "major": 0, - "minor": 0, - "patch": 0 - } - }, - "data": { - "algoDebugConfig": {}, - "availablePCICOutput": [ - "RGB_INFO" - ], - "pcicTCPPort": 50015 - }, - "info": { - "device": "2301", - "deviceTreeBinaryBlobOverlay": "001-ov9782.dtbo", - "features": { - "fov": { - "horizontal": 80, - "vertical": 127 - }, - "resolution": { - "height": 800, - "width": 1280 - }, - "type": "2D" - }, - "name": "", - "partNumber": "M03934", - "productionState": "AA", - "sensor": "OV9782", - "sensorID": "OV9782_127x80_noIllu_Csample", - "serialNumber": "000000000094", - "vendor": "0001" - }, - "mode": "experimental_autoexposure2D", - "processing": { - "extrinsicHeadToUser": { - "rotX": 0.0, - "rotY": 0.0, - "rotZ": 0.0, - "transX": 0.0, - "transY": 0.0, - "transZ": 0.0 - }, - "version": { - "major": 0, - "minor": 0, - "patch": 0 - } - }, - "state": "CONF" - } - } - } \ No newline at end of file diff --git a/ifm3d_ros_examples/launch/camera.launch b/ifm3d_ros_examples/launch/camera.launch deleted file mode 100644 index 78ae71e..0000000 --- a/ifm3d_ros_examples/launch/camera.launch +++ /dev/null @@ -1,31 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/ifm3d_ros_examples/launch/dump_merge_pc.json b/ifm3d_ros_examples/launch/dump_merge_pc.json deleted file mode 100644 index 2e8fa74..0000000 --- a/ifm3d_ros_examples/launch/dump_merge_pc.json +++ /dev/null @@ -1,338 +0,0 @@ -{ - "device": { - "clock": { - "currentTime": 1581090835576664320 - }, - "diagnostic": { - "temperatures": [], - "upTime": 190000000000 - }, - "info": { - "device": "0301", - "deviceTreeBinaryBlob": "tegra186-quill-p3310-1000-c03-00-base.dtb", - "features": {}, - "name": "", - "partNumber": "M03903", - "productionState": "AA", - "serialNumber": "000201233338", - "vendor": "0001" - }, - "network": { - "authorized_keys": "", - "ipAddressConfig": 0, - "macEth0": "00:04:4B:E4:DA:9E", - "macEth1": "00:02:01:23:33:38", - "networkSpeed": 1000, - "staticIPv4Address": "192.168.0.69", - "staticIPv4Gateway": "192.168.0.201", - "staticIPv4SubNetMask": "255.255.255.0", - "useDHCP": false - }, - "state": { - "errorMessage": "", - "errorNumber": "" - }, - "swVersion": { - "kernel": "4.9.140-l4t-r32.4+g231628d3fa15", - "l4t": "r32.4.3", - "os": "0.13.3-188", - "schema": "feature/O3R-4949", - "swu": "0.15.3" - } - }, - "ports": { - "port0": { - "acquisition": { - "exposureLong": 5000, - "exposureShort": 400, - "framerate": 10.0, - "offset": 0.0, - "version": { - "major": 0, - "minor": 0, - "patch": 0 - } - }, - "data": { - "algoDebugConfig": {}, - "availablePCICOutput": [ - "AMPLITUDE_COMPRESSED", - "CONFIDENCE", - "RADIAL_DISTANCE_COMPRESSED", - "RADIAL_DISTANCE_NOISE", - "REFLECTIVITY", - "TOF_INFO" - ], - "pcicTCPPort": 50010 - }, - "info": { - "device": "3101", - "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", - "features": { - "fov": { - "horizontal": 78, - "vertical": 105 - }, - "resolution": { - "height": 172, - "width": 224 - }, - "type": "3D" - }, - "name": "", - "partNumber": "M03957", - "productionState": "AA", - "sensor": "IRS2381C", - "sensorID": "IRS2381C_105x78_4x2W_110x90_Csample", - "serialNumber": "000000000186", - "vendor": "0001" - }, - "mode": "experimental_high_4m", - "processing": { - "diParam": { - "anfFilterSizeDiv2": 2, - "enableDynamicSymmetry": true, - "enableStraylight": true, - "enableTemporalFilter": true, - "excessiveCorrectionThreshAmp": 0.3, - "excessiveCorrectionThreshDist": 0.08, - "maxDistNoise": 0.02, - "maxSymmetry": 0.4, - "medianSizeDiv2": 0, - "minAmplitude": 20.0, - "minReflectivity": 0.0, - "mixedPixelFilterMode": 1, - "mixedPixelThresholdRad": 0.15 - }, - "extrinsicHeadToUser": { - "rotX": 0.0, - "rotY": -1.5708, - "rotZ": 0.0, - "transX": 0.015, - "transY": -0.18, - "transZ": -0.055 - }, - "version": { - "major": 0, - "minor": 0, - "patch": 0 - } - }, - "state": "RUN" - }, - "port1": { - "acquisition": { - "exposureLong": 5000, - "exposureShort": 400, - "framerate": 10.0, - "offset": 0.0, - "version": { - "major": 0, - "minor": 0, - "patch": 0 - } - }, - "data": { - "algoDebugConfig": {}, - "availablePCICOutput": [ - "AMPLITUDE_COMPRESSED", - "CONFIDENCE", - "RADIAL_DISTANCE_COMPRESSED", - "RADIAL_DISTANCE_NOISE", - "REFLECTIVITY", - "TOF_INFO" - ], - "pcicTCPPort": 50011 - }, - "info": { - "device": "3101", - "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", - "features": { - "fov": { - "horizontal": 78, - "vertical": 105 - }, - "resolution": { - "height": 172, - "width": 224 - }, - "type": "3D" - }, - "name": "", - "partNumber": "M03957", - "productionState": "AA", - "sensor": "IRS2381C", - "sensorID": "IRS2381C_105x78_4x2W_110x90_Csample", - "serialNumber": "000000000192", - "vendor": "0001" - }, - "mode": "experimental_high_4m", - "processing": { - "diParam": { - "anfFilterSizeDiv2": 2, - "enableDynamicSymmetry": true, - "enableStraylight": true, - "enableTemporalFilter": true, - "excessiveCorrectionThreshAmp": 0.3, - "excessiveCorrectionThreshDist": 0.08, - "maxDistNoise": 0.02, - "maxSymmetry": 0.4, - "medianSizeDiv2": 0, - "minAmplitude": 20.0, - "minReflectivity": 0.0, - "mixedPixelFilterMode": 1, - "mixedPixelThresholdRad": 0.15 - }, - "extrinsicHeadToUser": { - "rotX": 0.0, - "rotY": 0.0, - "rotZ": 0.0, - "transX": -0.13, - "transY": -0.1, - "transZ": 0.2 - }, - "version": { - "major": 0, - "minor": 0, - "patch": 0 - } - }, - "state": "RUN" - }, - "port2": { - "acquisition": { - "exposureLong": 5000, - "exposureShort": 400, - "framerate": 10.0, - "offset": 0.0, - "version": { - "major": 0, - "minor": 0, - "patch": 0 - } - }, - "data": { - "algoDebugConfig": {}, - "availablePCICOutput": [ - "AMPLITUDE_COMPRESSED", - "CONFIDENCE", - "RADIAL_DISTANCE_COMPRESSED", - "RADIAL_DISTANCE_NOISE", - "REFLECTIVITY", - "TOF_INFO" - ], - "pcicTCPPort": 50012 - }, - "info": { - "device": "2301", - "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", - "features": { - "fov": { - "horizontal": 80, - "vertical": 127 - }, - "resolution": { - "height": 800, - "width": 1280 - }, - "type": "2D" - }, - "name": "", - "partNumber": "M03934", - "productionState": "AA", - "sensor": "OV9782", - "sensorID": "OV9782_127x80_noIllu_Csample", - "serialNumber": "000000000094", - "vendor": "0001" - }, - "mode": "experimental_high_4m", - "processing": { - "diParam": { - "anfFilterSizeDiv2": 2, - "enableDynamicSymmetry": true, - "enableStraylight": true, - "enableTemporalFilter": true, - "excessiveCorrectionThreshAmp": 0.3, - "excessiveCorrectionThreshDist": 0.08, - "maxDistNoise": 0.02, - "maxSymmetry": 0.4, - "medianSizeDiv2": 0, - "minAmplitude": 20.0, - "minReflectivity": 0.0, - "mixedPixelFilterMode": 1, - "mixedPixelThresholdRad": 0.15 - }, - "extrinsicHeadToUser": { - "rotX": 0.0, - "rotY": 3.1416, - "rotZ": 0.0, - "transX": -0.015, - "transY": -0.3, - "transZ": 0.05 - }, - "version": { - "major": 0, - "minor": 0, - "patch": 0 - } - }, - "state": "RUN" - }, - "port5": { - "acquisition": { - "framerate": 10.0, - "version": { - "major": 0, - "minor": 0, - "patch": 0 - } - }, - "data": { - "algoDebugConfig": {}, - "availablePCICOutput": [ - "RGB_INFO" - ], - "pcicTCPPort": 50015 - }, - "info": { - "device": "2301", - "deviceTreeBinaryBlobOverlay": "001-ov9782.dtbo", - "features": { - "fov": { - "horizontal": 80, - "vertical": 127 - }, - "resolution": { - "height": 800, - "width": 1280 - }, - "type": "2D" - }, - "name": "", - "partNumber": "M03934", - "productionState": "AA", - "sensor": "OV9782", - "sensorID": "OV9782_127x80_noIllu_Csample", - "serialNumber": "000000000094", - "vendor": "0001" - }, - "mode": "experimental_autoexposure2D", - "processing": { - "extrinsicHeadToUser": { - "rotX": 0.0, - "rotY": 0.0, - "rotZ": 0.0, - "transX": 0.0, - "transY": 0.0, - "transZ": 0.0 - }, - "version": { - "major": 0, - "minor": 0, - "patch": 0 - } - }, - "state": "CONF" - } - } -} diff --git a/ifm3d_ros_examples/launch/four_cameras.launch b/ifm3d_ros_examples/launch/four_cameras.launch deleted file mode 100644 index 6ee2d6f..0000000 --- a/ifm3d_ros_examples/launch/four_cameras.launch +++ /dev/null @@ -1,110 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/ifm3d_ros_examples/launch/head.launch b/ifm3d_ros_examples/launch/head.launch deleted file mode 100644 index fc45542..0000000 --- a/ifm3d_ros_examples/launch/head.launch +++ /dev/null @@ -1,60 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/ifm3d_ros_examples/launch/merge_pc.launch b/ifm3d_ros_examples/launch/merge_pc.launch deleted file mode 100644 index 13bf287..0000000 --- a/ifm3d_ros_examples/launch/merge_pc.launch +++ /dev/null @@ -1,147 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/ifm3d_ros_examples/launch/nodelet.launch b/ifm3d_ros_examples/launch/nodelet.launch deleted file mode 100644 index 8259ed6..0000000 --- a/ifm3d_ros_examples/launch/nodelet.launch +++ /dev/null @@ -1,117 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - # - # The IP address of the camera to connect to - # - ip: "$(arg ip)" - - # - # The on-camera TCP port that the XMLRPC server is listening to - # - xmlrpc_port: $(arg xmlrpc_port) - - # - # The on-camera TCP port that the PCIC server is listening to - # - pcic_port: $(arg pcic_port) - - # - # The password needed to establish an edit session with the camera - # - password: "$(arg password)" - - # - # The PCIC schema mask to apply to the framegrabber - # - schema_mask: $(arg schema_mask) - - # - # The number of milliseconds to wait for a frame before declaring a - # framegrabber timeout - # - timeout_millis: $(arg timeout_millis) - - # - # The number of seconds to endure timeouts before restarting the framegrabber - # - timeout_tolerance_secs: $(arg timeout_tolerance_secs) - - # - # Flag indicating whether or not the nodelet should assume the camera is - # being software triggered - # - assume_sw_triggered: $(arg assume_sw_triggered) - - # - # If using the `SoftOff`/`SoftOn` functionality, these parameters - # control the `timeout_millis` and `timeout_tolerance_secs` - # - soft_on_timeout_millis: $(arg timeout_millis) - soft_on_timeout_tolerance_secs: $(arg timeout_tolerance_secs) - soft_off_timeout_millis: 500 - soft_off_timeout_tolerance_secs: 600.0 - - # - # Time (seconds) used to determine that timestamps from the camera - # cannot be trusted. When this threshold is exceeded, when compared to - # system time, we use the reception time of the frame and not the capture - # time of the frame. - # - frame_latency_thresh: 60.0 - - # - # Get rid of the errors when running `rosbag -a' - # - distance/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] - amplitude/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] - raw_amplitude/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] - confidence/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] - good_bad_pixels/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] - xyz_image/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] - - - - - - - - - - - - - diff --git a/ifm3d_ros_examples/launch/rviz.launch b/ifm3d_ros_examples/launch/rviz.launch deleted file mode 100644 index fcf2c23..0000000 --- a/ifm3d_ros_examples/launch/rviz.launch +++ /dev/null @@ -1,12 +0,0 @@ - - - - - - - - - diff --git a/ifm3d_ros_examples/launch/six_cameras.launch b/ifm3d_ros_examples/launch/six_cameras.launch deleted file mode 100644 index b8a2807..0000000 --- a/ifm3d_ros_examples/launch/six_cameras.launch +++ /dev/null @@ -1,156 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/ifm3d_ros_examples/package.xml b/ifm3d_ros_examples/package.xml deleted file mode 100644 index f8db7eb..0000000 --- a/ifm3d_ros_examples/package.xml +++ /dev/null @@ -1,21 +0,0 @@ - - - - ifm3d_ros_examples - 0.1.0 - ifm3d_ros examples subpackage - ifm CSR group - Apache 2 - CSR ifm sytron - - https://github.com/ifm/ifm3d_ros/ - - catkin - tf - ifm3d_ros_driver - ifm3d_ros_msgs - - - - - diff --git a/ifm3d_ros_msgs/CMakeLists.txt b/ifm3d_ros_msgs/CMakeLists.txt deleted file mode 100644 index df3e3f0..0000000 --- a/ifm3d_ros_msgs/CMakeLists.txt +++ /dev/null @@ -1,55 +0,0 @@ -cmake_minimum_required(VERSION 3.0.2) -project(ifm3d_ros_msgs) - -find_package(catkin REQUIRED COMPONENTS - message_generation - std_msgs - tf2_ros -) - -####################################### -## Declare ROS messages and services ## -####################################### -catkin_python_setup() - -add_message_files( - DIRECTORY msg - FILES - Extrinsics.msg - ) - -add_service_files( - DIRECTORY srv - FILES - Dump.srv - Config.srv - Trigger.srv - SoftOff.srv - SoftOn.srv - SyncClocks.srv - ) - -generate_messages( - DEPENDENCIES - std_msgs - ) - - -################################### -## catkin specific configuration ## -################################### -catkin_package( - CATKIN_DEPENDS message_runtime std_msgs -) - - -############# -## Install ## -############# - -catkin_install_python( - PROGRAMS - bin/dump - bin/config - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} - ) diff --git a/ifm3d_ros_msgs/README.md b/ifm3d_ros_msgs/README.md deleted file mode 100644 index 6f5c311..0000000 --- a/ifm3d_ros_msgs/README.md +++ /dev/null @@ -1,24 +0,0 @@ -# The `ifm3d_ros_msgs` package - -This package provides the messages and services interfaces for the `ifm3d_ros_driver` package. It can be installed independently of the driver package `ifm3d_ros_driver` and examples package `ìfm3d_ros_examples`. - -## Standalone Installation of the messages packages -If you plan on installing only one subpackage please see the instructions below. - -``` -catkin_make --only-pkg-with-deps -``` -Please replace the tag `` with the name of the package you want to compile: -+ `ifm3d_ros_driver` -+ `ifm3d_ros_msgs` -+ `ifm3d_ros_examples` - -Some of our subpackages have dependencies to other packages and therefore will trigger a compiling of more subpackages, namely the packages `ifm3d_ros_examples` and `ifm3d_ros_driver`. These subpackges can not be used standalone. - -Don't forget to switch back to building all packages afterwards: -``` -catkin_make -DCATKIN_WHITELIST_PACKAGES="" -``` - -# LICENSE -Please see the file called [LICENSE](LICENSE). \ No newline at end of file diff --git a/ifm3d_ros_msgs/bin/config b/ifm3d_ros_msgs/bin/config deleted file mode 100755 index 470fb17..0000000 --- a/ifm3d_ros_msgs/bin/config +++ /dev/null @@ -1,12 +0,0 @@ -#!/usr/bin/env python -# -*- python -*- - -# SPDX-License-Identifier: Apache-2.0 -# Copyright (C) 2021 ifm electronic, gmbh - - -import sys -from ifm3d_ros_utils import ConfigClient - -if __name__ == '__main__': - sys.exit(ConfigClient().run()) diff --git a/ifm3d_ros_msgs/bin/dump b/ifm3d_ros_msgs/bin/dump deleted file mode 100755 index 396285c..0000000 --- a/ifm3d_ros_msgs/bin/dump +++ /dev/null @@ -1,12 +0,0 @@ -#!/usr/bin/env python -# -*- python -*- - -# SPDX-License-Identifier: Apache-2.0 -# Copyright (C) 2021 ifm electronic, gmbh - - -import sys -from ifm3d_ros_utils import DumpClient - -if __name__ == '__main__': - sys.exit(DumpClient().run()) diff --git a/ifm3d_ros_msgs/msg/Extrinsics.msg b/ifm3d_ros_msgs/msg/Extrinsics.msg deleted file mode 100644 index 7fe7168..0000000 --- a/ifm3d_ros_msgs/msg/Extrinsics.msg +++ /dev/null @@ -1,11 +0,0 @@ -# -# Extrinsic parameters are SI units: please be aware of scaling between any extrinsic messages returned by older versions of the native C++ API - ifm3d -# Translation uints are NOW m, rotation units are radian -# -std_msgs/Header header -float32 tx -float32 ty -float32 tz -float32 rot_x -float32 rot_y -float32 rot_z diff --git a/ifm3d_ros_msgs/package.xml b/ifm3d_ros_msgs/package.xml deleted file mode 100644 index 39f5fce..0000000 --- a/ifm3d_ros_msgs/package.xml +++ /dev/null @@ -1,26 +0,0 @@ - - - - ifm3d_ros_msgs - 0.1.0 - ifm3d_ros messages subpackage - ifm CSR group - Apache 2 - CSR ifm sytron - https://github.com/ifm/ifm3d-ros/ - - - catkin - message_generation - std_msgs - std_msgs - message_generation - std_msgs - message_runtime - tf2_ros - - - - - - diff --git a/ifm3d_ros_msgs/setup.py b/ifm3d_ros_msgs/setup.py deleted file mode 100644 index 412b54b..0000000 --- a/ifm3d_ros_msgs/setup.py +++ /dev/null @@ -1,10 +0,0 @@ -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup - -# reads package.xml -setup_args = generate_distutils_setup( - packages=['ifm3d_ros_utils'], - package_dir={'': 'utils'}, - ) - -setup(**setup_args) diff --git a/ifm3d_ros_msgs/srv/Config.srv b/ifm3d_ros_msgs/srv/Config.srv deleted file mode 100644 index 81c8381..0000000 --- a/ifm3d_ros_msgs/srv/Config.srv +++ /dev/null @@ -1,4 +0,0 @@ -string json ---- -int32 status -string msg diff --git a/ifm3d_ros_msgs/srv/Dump.srv b/ifm3d_ros_msgs/srv/Dump.srv deleted file mode 100644 index 1399d5b..0000000 --- a/ifm3d_ros_msgs/srv/Dump.srv +++ /dev/null @@ -1,3 +0,0 @@ ---- -int32 status -string config diff --git a/ifm3d_ros_msgs/srv/SoftOff.srv b/ifm3d_ros_msgs/srv/SoftOff.srv deleted file mode 100644 index f8f830e..0000000 --- a/ifm3d_ros_msgs/srv/SoftOff.srv +++ /dev/null @@ -1,3 +0,0 @@ ---- -int32 status -string msg \ No newline at end of file diff --git a/ifm3d_ros_msgs/srv/SoftOn.srv b/ifm3d_ros_msgs/srv/SoftOn.srv deleted file mode 100644 index f60f193..0000000 --- a/ifm3d_ros_msgs/srv/SoftOn.srv +++ /dev/null @@ -1,3 +0,0 @@ ---- -int32 status -string msg diff --git a/ifm3d_ros_msgs/srv/SyncClocks.srv b/ifm3d_ros_msgs/srv/SyncClocks.srv deleted file mode 100644 index f60f193..0000000 --- a/ifm3d_ros_msgs/srv/SyncClocks.srv +++ /dev/null @@ -1,3 +0,0 @@ ---- -int32 status -string msg diff --git a/ifm3d_ros_msgs/srv/Trigger.srv b/ifm3d_ros_msgs/srv/Trigger.srv deleted file mode 100644 index f8f830e..0000000 --- a/ifm3d_ros_msgs/srv/Trigger.srv +++ /dev/null @@ -1,3 +0,0 @@ ---- -int32 status -string msg \ No newline at end of file diff --git a/ifm3d_ros_msgs/utils/ifm3d_ros_utils/_ConfigClient.py b/ifm3d_ros_msgs/utils/ifm3d_ros_utils/_ConfigClient.py deleted file mode 100644 index 1f5fbe1..0000000 --- a/ifm3d_ros_msgs/utils/ifm3d_ros_utils/_ConfigClient.py +++ /dev/null @@ -1,30 +0,0 @@ -# SPDX-License-Identifier: Apache-2.0 -# Copyright (C) 2021 ifm electronic, gmbh - -""" -Mimics (mostly) the `ifm3d config` command but communicates through the ROS -graph -""" - -import json -import rospy -import sys -from ifm3d_ros_msgs.srv import Config - -SRV_TIMEOUT = 2.0 # seconds -SRV_NAME = "/ifm3d_ros_examples/camera/Config" - -class ConfigClient(object): - - def __init__(self): - rospy.init_node('ifm3d_config_client') - - def run(self): - j = json.load(sys.stdin) - rospy.wait_for_service(SRV_NAME, timeout=SRV_TIMEOUT) - proxy = rospy.ServiceProxy(SRV_NAME, Config) - resp = proxy(json.dumps(j)) - if resp.status != 0: - print("Error: %s - %s" % (str(resp.status), resp.msg)) - - return resp.status diff --git a/ifm3d_ros_msgs/utils/ifm3d_ros_utils/_DumpClient.py b/ifm3d_ros_msgs/utils/ifm3d_ros_utils/_DumpClient.py deleted file mode 100644 index 3b45a8f..0000000 --- a/ifm3d_ros_msgs/utils/ifm3d_ros_utils/_DumpClient.py +++ /dev/null @@ -1,33 +0,0 @@ -# SPDX-License-Identifier: Apache-2.0 -# Copyright (C) 2021 ifm electronic, gmbh - -""" -Mimics the `ifm3d dump` command but communicates through the ROS graph -""" - -import json -import rospy -import sys -from ifm3d_ros_msgs.srv import Dump - -SRV_TIMEOUT = 2.0 # seconds -SRV_NAME = "/ifm3d_ros_examples/camera/Dump" - -class DumpClient(object): - - def __init__(self): - rospy.init_node('ifm3d_dump_client') - - def run(self): - rospy.wait_for_service(SRV_NAME, timeout=SRV_TIMEOUT) - proxy = rospy.ServiceProxy(SRV_NAME, Dump) - resp = proxy() - if resp.status == 0: - print(json.dumps(json.loads(resp.config), - sort_keys=True, indent=4, separators=(',', ': '))) - else: - sys.stderr.write("Dump failed with error: %s - %s\n" % - (str(resp.status), - "Check the `ifm3d' logs for more detail")) - - return resp.status diff --git a/ifm3d_ros_msgs/utils/ifm3d_ros_utils/__init__.py b/ifm3d_ros_msgs/utils/ifm3d_ros_utils/__init__.py deleted file mode 100644 index c928a3e..0000000 --- a/ifm3d_ros_msgs/utils/ifm3d_ros_utils/__init__.py +++ /dev/null @@ -1,5 +0,0 @@ -# SPDX-License-Identifier: Apache-2.0 -# Copyright (C) 2021 ifm electronic, gmbh - -from ._DumpClient import DumpClient -from ._ConfigClient import ConfigClient From d2e63e6f5e10a93d6b5cf86ca827ddbee974109f Mon Sep 17 00:00:00 2001 From: ifm-csr Date: Tue, 23 Nov 2021 16:34:48 +0000 Subject: [PATCH 6/6] add latest dev changes and fixes --- CHANGELOG.rst | 106 +++ README.md | 46 ++ ifm3d-ros/CMakeLists.txt | 5 + ifm3d-ros/LICENSE | 202 ++++++ ifm3d-ros/package.xml | 22 + ifm3d_ros_driver/.clang-format | 65 ++ ifm3d_ros_driver/CMakeLists.txt | 84 +++ ifm3d_ros_driver/LICENSE | 202 ++++++ ifm3d_ros_driver/README.md | 72 ++ ifm3d_ros_driver/doc/building.md | 93 +++ ifm3d_ros_driver/doc/distributed_build.md | 47 ++ ifm3d_ros_driver/doc/dump_and_config.md | 286 ++++++++ .../doc/figures/O3R_merged_point_cloud.png | Bin 0 -> 763340 bytes .../doc/figures/rviz_ref_frame.png | Bin 0 -> 57878 bytes ifm3d_ros_driver/doc/noetic.md | 64 ++ ifm3d_ros_driver/doc/rpc_error_codes.md | 9 + ifm3d_ros_driver/doc/troubleshooting.md | 50 ++ ifm3d_ros_driver/doc/visualization.md | 28 + .../include/ifm3d_ros_driver/camera_nodelet.h | 122 ++++ ifm3d_ros_driver/launch/camera.launch | 31 + ifm3d_ros_driver/launch/nodelet.launch | 117 ++++ ifm3d_ros_driver/nodelets.xml | 10 + ifm3d_ros_driver/package.xml | 31 + ifm3d_ros_driver/src/camera_nodelet.cpp | 628 ++++++++++++++++++ ifm3d_ros_driver/test/gradient.jpg | Bin 0 -> 1363 bytes ifm3d_ros_driver/test/ifm3d.test | 6 + ifm3d_ros_driver/test/test_camera.py | 240 +++++++ ifm3d_ros_driver/test/test_threshold.py | 41 ++ ifm3d_ros_examples/CMakeLists.txt | 19 + ifm3d_ros_examples/LICENSE | 202 ++++++ ifm3d_ros_examples/README.md | 41 ++ ifm3d_ros_examples/config/rviz_config.rviz | 184 +++++ .../examples/README_pointcloud_merge.md | 6 + ifm3d_ros_examples/examples/dump.json | 338 ++++++++++ ifm3d_ros_examples/launch/camera.launch | 31 + ifm3d_ros_examples/launch/dump_merge_pc.json | 338 ++++++++++ ifm3d_ros_examples/launch/four_cameras.launch | 110 +++ ifm3d_ros_examples/launch/head.launch | 60 ++ ifm3d_ros_examples/launch/merge_pc.launch | 147 ++++ ifm3d_ros_examples/launch/nodelet.launch | 117 ++++ ifm3d_ros_examples/launch/rviz.launch | 12 + ifm3d_ros_examples/launch/six_cameras.launch | 156 +++++ ifm3d_ros_examples/package.xml | 21 + ifm3d_ros_msgs/CMakeLists.txt | 55 ++ ifm3d_ros_msgs/README.md | 24 + ifm3d_ros_msgs/bin/config | 12 + ifm3d_ros_msgs/bin/dump | 12 + ifm3d_ros_msgs/msg/Extrinsics.msg | 11 + ifm3d_ros_msgs/package.xml | 26 + ifm3d_ros_msgs/setup.py | 10 + ifm3d_ros_msgs/srv/Config.srv | 4 + ifm3d_ros_msgs/srv/Dump.srv | 3 + ifm3d_ros_msgs/srv/SoftOff.srv | 3 + ifm3d_ros_msgs/srv/SoftOn.srv | 3 + ifm3d_ros_msgs/srv/SyncClocks.srv | 3 + ifm3d_ros_msgs/srv/Trigger.srv | 3 + .../utils/ifm3d_ros_utils/_ConfigClient.py | 30 + .../utils/ifm3d_ros_utils/_DumpClient.py | 33 + .../utils/ifm3d_ros_utils/__init__.py | 5 + 59 files changed, 4626 insertions(+) create mode 100644 CHANGELOG.rst create mode 100644 README.md create mode 100644 ifm3d-ros/CMakeLists.txt create mode 100644 ifm3d-ros/LICENSE create mode 100644 ifm3d-ros/package.xml create mode 100644 ifm3d_ros_driver/.clang-format create mode 100644 ifm3d_ros_driver/CMakeLists.txt create mode 100644 ifm3d_ros_driver/LICENSE create mode 100644 ifm3d_ros_driver/README.md create mode 100644 ifm3d_ros_driver/doc/building.md create mode 100644 ifm3d_ros_driver/doc/distributed_build.md create mode 100644 ifm3d_ros_driver/doc/dump_and_config.md create mode 100644 ifm3d_ros_driver/doc/figures/O3R_merged_point_cloud.png create mode 100644 ifm3d_ros_driver/doc/figures/rviz_ref_frame.png create mode 100644 ifm3d_ros_driver/doc/noetic.md create mode 100644 ifm3d_ros_driver/doc/rpc_error_codes.md create mode 100644 ifm3d_ros_driver/doc/troubleshooting.md create mode 100644 ifm3d_ros_driver/doc/visualization.md create mode 100644 ifm3d_ros_driver/include/ifm3d_ros_driver/camera_nodelet.h create mode 100644 ifm3d_ros_driver/launch/camera.launch create mode 100644 ifm3d_ros_driver/launch/nodelet.launch create mode 100644 ifm3d_ros_driver/nodelets.xml create mode 100644 ifm3d_ros_driver/package.xml create mode 100644 ifm3d_ros_driver/src/camera_nodelet.cpp create mode 100644 ifm3d_ros_driver/test/gradient.jpg create mode 100644 ifm3d_ros_driver/test/ifm3d.test create mode 100755 ifm3d_ros_driver/test/test_camera.py create mode 100644 ifm3d_ros_driver/test/test_threshold.py create mode 100644 ifm3d_ros_examples/CMakeLists.txt create mode 100644 ifm3d_ros_examples/LICENSE create mode 100644 ifm3d_ros_examples/README.md create mode 100644 ifm3d_ros_examples/config/rviz_config.rviz create mode 100644 ifm3d_ros_examples/examples/README_pointcloud_merge.md create mode 100644 ifm3d_ros_examples/examples/dump.json create mode 100644 ifm3d_ros_examples/launch/camera.launch create mode 100644 ifm3d_ros_examples/launch/dump_merge_pc.json create mode 100644 ifm3d_ros_examples/launch/four_cameras.launch create mode 100644 ifm3d_ros_examples/launch/head.launch create mode 100644 ifm3d_ros_examples/launch/merge_pc.launch create mode 100644 ifm3d_ros_examples/launch/nodelet.launch create mode 100644 ifm3d_ros_examples/launch/rviz.launch create mode 100644 ifm3d_ros_examples/launch/six_cameras.launch create mode 100644 ifm3d_ros_examples/package.xml create mode 100644 ifm3d_ros_msgs/CMakeLists.txt create mode 100644 ifm3d_ros_msgs/README.md create mode 100755 ifm3d_ros_msgs/bin/config create mode 100755 ifm3d_ros_msgs/bin/dump create mode 100644 ifm3d_ros_msgs/msg/Extrinsics.msg create mode 100644 ifm3d_ros_msgs/package.xml create mode 100644 ifm3d_ros_msgs/setup.py create mode 100644 ifm3d_ros_msgs/srv/Config.srv create mode 100644 ifm3d_ros_msgs/srv/Dump.srv create mode 100644 ifm3d_ros_msgs/srv/SoftOff.srv create mode 100644 ifm3d_ros_msgs/srv/SoftOn.srv create mode 100644 ifm3d_ros_msgs/srv/SyncClocks.srv create mode 100644 ifm3d_ros_msgs/srv/Trigger.srv create mode 100644 ifm3d_ros_msgs/utils/ifm3d_ros_utils/_ConfigClient.py create mode 100644 ifm3d_ros_msgs/utils/ifm3d_ros_utils/_DumpClient.py create mode 100644 ifm3d_ros_msgs/utils/ifm3d_ros_utils/__init__.py diff --git a/CHANGELOG.rst b/CHANGELOG.rst new file mode 100644 index 0000000..cd57f27 --- /dev/null +++ b/CHANGELOG.rst @@ -0,0 +1,106 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package ifm3d-ros +^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.0 +=== + +1.0.0 +------ + +Braking changes: ++ Restructure the ifm3d-ros package into independent subpackages. Please check your path declarations again, especially for the launch files and messages and services. + +Changes between ifm3d_ros 0.6.x and 1.0.0: ++ Order of axis changed in 3D (cloud topic and extrinsic calibration parameters): This wrapper keeps the axis orientation as defined by the underlying API, ifm3d. Therefore, you may see a different axis order for the cloud message compared to older versions of the ifm3d and ifm cameras. ++ Extrinsic calibration parameters: now conistent with SI units, e.g. translation are scaled in `m` and rotation parameters are scaled in `rad`. ++ Added publisher for 2D RGB data ++ Use CameraBase for compatibility with other O3 devices ++ Comment out methods / publisher which are not available for the O3RCamera (at the moment) ++ Comment out the unit vector publishing ++ Changed services trigger and softon, softoff to be compatible with new JSON methods and schema. ++ Changed service trigger to a dummy method until triggers are implemented for the O3R platform. It only has a status message at the moment. ++ Changed service dump: coverts from json to str for displaying the message + +added: ++ Added pcic_port to the list of framegrabber arguments + +known limitations: ++ This version of the ifm3d-ros package only works with the O3R camera platform. + + +0.6 +=== + +0.6.2 +----- +Changes between ifm3d_ros 0.6.1 and 0.6.2 + +* Updated maintainer email address +* Added ifm3d-core dependency in preparation for submission to the ROS index + +0.6.1 +----- + +* Added support syncing the system and camera clocks at startup. Side-effect, + is we can now stamp the images with the camera-side capture time and not the + host-side reception time. +* Added the `SyncClocks` Service + +0.6.0. +------ + +* Added a image transport plugin _blacklist_ to the nodlet launch file. This + prevents many of the errors seen in the terminal when running `rosbag -a` to + capture camera data +* Added the `SoftOn` and `SoftOff` service calls + +0.5 +=== + + +0.5.1 +----- + +* Added support for Ubuntu 18.04 and ROS Melodic + +0.5.0 +----- + +* Converted primary data publisher to a nodelet architecture +* Provide the `dump` and `config` scripts to call into the exposed ROS services + of the nodelet. Removed the older "config node". +* Added unit tests + +0.4 +=== + +0.4.2 +----- + +* Now requires ifm3d 0.9.0 and by association the more modernized tooling + (C++14, cmake 3.5, dropped support for 14.04/Indigo, etc.) + +0.4.1 +----- + +* Now publishing extrinsics on a topic + +0.3 +=== + +* Added `Dump` Service +* Added `Config` Service +* Added `Trigger` Service + +0.2 +=== + +* Updates to CMakeLists.txt to support Ubuntu 14.04 and ROS Indigo + +0.1 +=== + +This file has started tracking ifm3d_ros at 0.1.0 + +* Initial (alpha) release diff --git a/README.md b/README.md new file mode 100644 index 0000000..9dfbc46 --- /dev/null +++ b/README.md @@ -0,0 +1,46 @@ +# ifm3d-ros wrapper around the ifm3d library + +# Release versions + +:warning: Note that the `v1.0.x` branch is generally in a work in progress state, and you probably want to use a tagged [release version](https://github.com/ifm/ifm3d-ros/releases) for production. + +## ifm3d-ros for the O3R + +**NOTE: The ifm3d-ros package has had major changes recently. Please be aware that this might cause problems on your system for building pipelines based on our old build instructions.** +We tried to ensure backward compatibility where ever possible. If you find any major breaks, please let us know. + + +ifm3d-ros is a wrapper around [ifm3d](https://github.com/ifm/ifm3d/) enabling the usage of the O3R camera platform (ifm ToF cameras) from within [ROS](http://ros.org) software systems. + +![rviz1](ifm3d_ros_driver/doc/figures/O3R_merged_point_cloud.png) + +## Software Compatibility Matrix + +|**ifm3d-ros version**|**ifm3d version**|**ROS distribution(s)**| +| ------------ | ------------ | ------------ | +| 1.0.0 | in development - latest version checked 0.91.0 | Noetic | + +### Internal ifm3d-ros subpackage version structure +Please see the internal subpackage version structure for a known `ifm3d-ros version`. + +|**ifm3d-ros version**|**ifm3d_ros_driver**|**ifm3d_ros_msgs**|**ifm3d_ros_examples**| +| ------------ | ------------ | ------------ | ------------ | +| 1.0.0 | 0.7.0 | 0.1.0 | 0.1.0 | + +## Organization of the software + +The `ifm3d-ros` meta package provides three subpackages: +- `ifm3d_ros_driver` provides the core interface for receiving data for ifm 3d (O3R) cameras. +- `ifm3d_ros_msgs` gathers the ifm-specific messages types and the services for configuring and triggering the camera. +- `ifm3d_ros_examples` provides additional helper scripts and examples. + +The name `ifm3d-ros` was kept even tough this is not consistent with ROS package naming conventions. +This ROS package has been split into three sub packages in an effort to facilitate dependency handling on distributed systems and simplify deployment on embedded platforms. For instance, the package `ifm3d_ros_msgs` can be installed independently of the other packages to control the camera from a separate computing platform. The `ifm3d_ros_examples` holds our launch files and examples. + +## Building and installing the software + +1. Preparing your system: [Noetic](ifm3d_ros_driver/doc/noetic.md) +2. [Installing the ifm3d-ros node](ifm3d_ros_driver/doc/building.md) + +# LICENSE +Please see the file called [LICENSE](LICENSE). \ No newline at end of file diff --git a/ifm3d-ros/CMakeLists.txt b/ifm3d-ros/CMakeLists.txt new file mode 100644 index 0000000..5a82652 --- /dev/null +++ b/ifm3d-ros/CMakeLists.txt @@ -0,0 +1,5 @@ +cmake_minimum_required(VERSION 2.8.3) +project(ifm3d-ros) +find_package(catkin REQUIRED) +catkin_metapackage() + diff --git a/ifm3d-ros/LICENSE b/ifm3d-ros/LICENSE new file mode 100644 index 0000000..7a4a3ea --- /dev/null +++ b/ifm3d-ros/LICENSE @@ -0,0 +1,202 @@ + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. \ No newline at end of file diff --git a/ifm3d-ros/package.xml b/ifm3d-ros/package.xml new file mode 100644 index 0000000..49527c2 --- /dev/null +++ b/ifm3d-ros/package.xml @@ -0,0 +1,22 @@ + + + + ifm3d-ros + 1.0.0 + metapackage for the ifm3d-ros package group which interacts with the ifm 3D ToF Camera ROS package + ifm CSR group + Apache 2 + CSR ifm sytron + + https://github.com/ifm/ifm3d-ros/ + + catkin + ifm3d_ros_driver + ifm3d_ros_examples + ifm3d_ros_msgs + + + + + + diff --git a/ifm3d_ros_driver/.clang-format b/ifm3d_ros_driver/.clang-format new file mode 100644 index 0000000..817fd6d --- /dev/null +++ b/ifm3d_ros_driver/.clang-format @@ -0,0 +1,65 @@ +--- +BasedOnStyle: Google +AccessModifierOffset: -2 +ConstructorInitializerIndentWidth: 2 +AlignEscapedNewlinesLeft: false +AlignTrailingComments: true +AllowAllParametersOfDeclarationOnNextLine: false +AllowShortIfStatementsOnASingleLine: false +AllowShortLoopsOnASingleLine: false +AllowShortFunctionsOnASingleLine: None +AlwaysBreakTemplateDeclarations: true +AlwaysBreakBeforeMultilineStrings: true +BreakBeforeBinaryOperators: false +BreakBeforeTernaryOperators: false +BreakConstructorInitializersBeforeComma: true +BinPackParameters: true +ColumnLimit: 120 +ConstructorInitializerAllOnOneLineOrOnePerLine: true +DerivePointerBinding: false +PointerBindsToType: true +ExperimentalAutoDetectBinPacking: false +IndentCaseLabels: true +MaxEmptyLinesToKeep: 1 +NamespaceIndentation: None +ObjCSpaceBeforeProtocolList: true +PenaltyBreakBeforeFirstCallParameter: 19 +PenaltyBreakComment: 60 +PenaltyBreakString: 1 +PenaltyBreakFirstLessLess: 1000 +PenaltyExcessCharacter: 1000 +PenaltyReturnTypeOnItsOwnLine: 90 +SpacesBeforeTrailingComments: 2 +Cpp11BracedListStyle: false +Standard: Auto +IndentWidth: 2 +TabWidth: 2 +UseTab: Never +IndentFunctionDeclarationAfterType: false +SpacesInParentheses: false +SpacesInAngles: false +SpaceInEmptyParentheses: false +SpacesInCStyleCastParentheses: false +SpaceAfterControlStatementKeyword: true +SpaceBeforeAssignmentOperators: true +ContinuationIndentWidth: 4 +SortIncludes: false +SpaceAfterCStyleCast: false + +# Configure each individual brace in BraceWrapping +BreakBeforeBraces: Custom + +# Control of individual brace wrapping cases +BraceWrapping: { + AfterClass: 'true' + AfterControlStatement: 'true' + AfterEnum : 'true' + AfterFunction : 'true' + AfterNamespace : 'true' + AfterStruct : 'true' + AfterUnion : 'true' + BeforeCatch : 'true' + BeforeElse : 'true' + IndentBraces : 'false' +} +... diff --git a/ifm3d_ros_driver/CMakeLists.txt b/ifm3d_ros_driver/CMakeLists.txt new file mode 100644 index 0000000..634c40c --- /dev/null +++ b/ifm3d_ros_driver/CMakeLists.txt @@ -0,0 +1,84 @@ +cmake_minimum_required(VERSION 3.5) +project(ifm3d_ros_driver) + +find_package(ifm3d REQUIRED COMPONENTS + camera + framegrabber + image + ) + +find_package(catkin REQUIRED COMPONENTS + rospy + image_transport + pcl_ros + cv_bridge + nodelet + roscpp + sensor_msgs + std_msgs + message_runtime + rostest + ifm3d_ros_msgs + ) + +# catkin_python_setup() + +option(CATKIN_ENABLE_TESTING "Build tests" OFF) + +################################### +## catkin specific configuration ## +################################### +catkin_package( + INCLUDE_DIRS include + LIBRARIES ifm3d_ros + CATKIN_DEPENDS roscpp nodelet + ) + +############# +## Build ## +############# +set(CMAKE_CXX_EXTENSIONS OFF) +set(CMAKE_CXX_STANDARD 14) +set(CMAKE_CXX_STANDARD_REQUIRED true) + +include_directories( + include + ${catkin_INCLUDE_DIRS} + ) + +add_library(ifm3d_ros src/camera_nodelet.cpp) +target_link_libraries(ifm3d_ros + ${catkin_LIBRARIES} + ifm3d::camera + ifm3d::framegrabber + ifm3d::image + ) + +############# +## Install ## +############# + +install(TARGETS + ifm3d_ros + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ) + +install(DIRECTORY + include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + ) + +install(FILES nodelets.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + ) + +###################### +## Node-level tests ## +###################### + +if (CATKIN_ENABLE_TESTING) + add_rostest(test/ifm3d.test) + catkin_add_nosetests(test) +endif() diff --git a/ifm3d_ros_driver/LICENSE b/ifm3d_ros_driver/LICENSE new file mode 100644 index 0000000..7a4a3ea --- /dev/null +++ b/ifm3d_ros_driver/LICENSE @@ -0,0 +1,202 @@ + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. \ No newline at end of file diff --git a/ifm3d_ros_driver/README.md b/ifm3d_ros_driver/README.md new file mode 100644 index 0000000..bf05705 --- /dev/null +++ b/ifm3d_ros_driver/README.md @@ -0,0 +1,72 @@ +# The `ifm3d_ros_driver` package + +## ROS Interface + +The core `ifm3d-ros` sensor interface is implemented as a ROS nodelet. This allows for lower-latency data processing vs. the traditional out-of-process node-based ROS interface for applications that require it. However, we ship a launch file with this package that allows for using the core `ifm3d-ros` driver as a standard node. To launch the node, the following command can be used: + +``` +$ roslaunch ifm3d_ros_examples camera.launch +``` +>Note: Please notice the use of the subpackage `ifm3d_ros_examples`. + +For further information about the internal ROS nodelet infrastructure and how to apply this to your application, please see our exemplary launch files and a short run down on the nodelet structure in the [ifm3d_ros_examples/README](../ifm3d_ros_examples/README.md). + +### Nodelet - parameters + +| Name | Data Type | Default Value | Description | +| ---- | ---- | ---- | ---- | +| ~assume_sw_triggered | bool | false | This provides a hint to the driver that the camera is configured for software triggering (as opposed to free running). In this mode, certain default values are applied to lessen the noise in terms of timeouts from the frame grabber.| +| ~frame_id_base |string |ifm3d/camera | This string provides a prefix into the `tf` tree for `ifm3d_ros` coordinate frames. | +| ~frame_latency_thresh | float | 60.0 | Time (seconds) used to determine that timestamps from the camera cannot be trusted. When this threshold is exceeded, when compared to system time, we use the reception time of the frame and not the capture time of the frame. | +| ~ip | string | 192.168.0.69 | The IP address of the VPU. | +| ~password | string | "" | The password required to establish an edit session on the VPU | +| ~schema_mask | uint16 | 0xf | The pcic schema mask to apply to the active session with the frame grabber. This determines which images are available for publication from the camera. More about pcic schemas can be gleaned from the [ifm3d projects documentation](https://www.ifm3d.com). | +| ~timeout_millis | int | 500 | The number of milliseconds to wait for the framegrabber to return new frame data before declaring a "timeout" and to stop blocking on new data. | +| ~timeout_tolerance_secs |float | 5.0 | The wall time to wait with no new data from the camera before trying to establish a new connection to the camera. This helps to providerobustness against camera cables becoming unplugged or other in-field pathologies which would cause the connection between the ROS node and the camera to be broken. | +| ~sync_clocks DEPRECATED | bool | false | Attempt to sync the camera clock to the system clock at start-up. The side-effect is that timestamps on the image should reflect the capture time as opposed to the receipt time. | +| ~xmlrpc_port | unint16 | 80 | The TCP port the camera's xmlrpc server is listening on for requests. | +| ~pcic_port | unint16 | 50010 | The TCP (data) port the camera's pcic server is listening on for requests. | + + +### Nodelet - published Topics + +| Name | Data Type | Description | +| --- | --- | --- | +| amplitude | sensor_msgs/Image | The normalized amplitude image. | +| confidence | sensor_msgs/Image | The confidence image. | +| cloud | sensor_msgs/PointCloud2 | The point cloud data, i.e. X-, Y-, Z-coordinates. | +| distance | sensor_msgs/Image | The radial distance image. | +| raw_amplitude | sensor_msgs/Image | The raw (non normalized) amplitude image. | +| good_bad_pixels | sensor_msgs/Image | The binary image representation of the confidence image. | +| xyz_imaege | sensor_msgs/Image | A 3-channel image encoding of the point cloud. Each of the three image channels represents a spatial data plane encoding the x, y, z Cartesian values respectively. | +| unit_vectors | sensor_msgs/Image | The rotated unit vectors. | +| extrinsics | ifm3d/Extrinsics | The extrinsic calibration of the camera with respect to the camera optical frame. This 3D pose is encoded in mm and rad. | + +>Note: Some topics may have empty data fields. We are working on publishing data on all available topics, but have kept all previous topics active for the moment for legacy reasons. + +### Nodelet - subscribed Topics +None. + +### Nodelet - advertised Services +> Note: the services are provided by the `ifm3d_ros_msgs` package. + +| Name | Service Definition | Description | +| ---- | ---- | ---- | +| Dump | ifm3d/Dump | Dumps the state of the camera system as a JSON (formatted as a string) | +| Config | ifm3d/Config | Provides a means to configure the VPU and Heads (imager settings), declaratively from a JSON (string) encoding of the desired settings. | +| SoftOff | ifm3d/SoftOff | Sets the active application of the camera into software triggered mode which will turn off the active illumination reducing both power and heat. | +| SoftOn | ifm3d/SoftOn | Sets the active application of the camera into free-running mode. Its intention is to act as the inverse of `SoftOff`. | +| Trigger | ifm3d/Trigger | Requests the driver to software trigger the imager for data acquisition. | + +### Known limitations +[![O3R](https://img.shields.io/badge/O3R-lightgrey.svg)]() +[![O3D](https://img.shields.io/badge/O3D-green.svg)]() +[![O3X](https://img.shields.io/badge/O3X-green.svg)]() + + +# Additional Documentation +* [Inspecting and configuring the camera / imager settings](doc/dump_and_config.md) +* [Troubleshooting](doc/troubleshooting.md) + +# LICENSE +Please see the file called [LICENSE](LICENSE). diff --git a/ifm3d_ros_driver/doc/building.md b/ifm3d_ros_driver/doc/building.md new file mode 100644 index 0000000..4421c9a --- /dev/null +++ b/ifm3d_ros_driver/doc/building.md @@ -0,0 +1,93 @@ +# Building and Installing the ifm3d-ros package + +## TOC +* [Prerequisites](#prerequisites) +* [Step-by-Step build instructions for the ROS node `ifm3d-ros`](#step-by-step-build-instructions-for-the-ros-node--ifm3d-ros-) + + [1. Installation directory of ROS node](#1-installation-directory-of-ros-node) + + [2. create and initialize your catkin workspace](#2-create-and-initialize-your-catkin-workspace) + + [3. Get the `ìfm3d-ros` wrapper code from GitHub](#3-get-the---fm3d-ros--wrapper-code-from-github) + + [4. build the ROS node code](#4-build-the-ros-node-code) +* [Building subpackages for distributed systems](#building-subpackages) + + +## Prerequisites + +We suggest to build the `ifm3d-ros` node on top of Ubuntu 20.04 and ROS noetic. +If you have reached this document via the [noetic ifm3d building instructions](noetic.md) and followed all the major steps in there you can skip the three steps listed below. They are just a short repetition. +1. [Ubuntu 20.04 LTS](http://www.ubuntu.com) +2. [ROS Noetic](http://wiki.ros.org/noetic/Installation/) - we recommend `ros-noetic-desktop-full`. +3. [ifm3d](https://github.com/ifm/ifm3d/tree/o3r/dev) + + +> Note: Some users may require older ROS distributions for legacy reasons. The supplied ROS package may very well work with limited changes on older ROS distributions. At least previous version could be run as far back as Indigo and Kinetic. However, we didn't test this ourselves. Please be aware that if you chose to go this route no guarantee is given. + +## Step-by-Step build instructions for the ROS node `ifm3d-ros` + +Building and installing ifm3d-ros is accomplished by utilizing the ROS [catkin](http://wiki.ros.org/catkin) tool. There are many tutorials and other pieces of advice available online advising how to most effectively utilize catkin. The instructions that now follow represent how we choose to use catkin to build and _permanently install_ a ROS package from source. + +**Alternatively: If you are looking for indenpendent subpackage build - please see [distributed build instructions](distributed_build.md)** + +### 1. Installation directory of ROS node +First, we need to decide where we want our software to be installed. For purposes of this document, we will assume that we will install our ROS packages at `~/catkin_ws/src`. + +>NOTE: Below we assume `noetic`. Adapting to other ROS distributions is left as an exercise for the reader. + +### 2. create and initialize your catkin workspace +Next, we want to create a _catkin workspace_ that we can use to build and install that code from. +For further information about setting up you _catkin workspace_ please see this documentation: [create a catkin workspace](http://wiki.ros.org/catkin/Tutorials/create_a_workspace). +``` +$ mkdir -p ~/catkin_ws/src && cd ~/catkin_ws/src +$ catkin_init_workspace +``` + +### 3. Get the `ifm3d-ros` wrapper code from GitHub +Next, we need to get the code from GitHub. Please adapt the commands when not following the suggested directory structure: `~/catkin_ws/src/` + +``` +$ cd ~/catkin_ws/src +$ git clone --branch o3r/dev https://github.com/ifm/ifm3d-ros.git +``` + +So, you should have a catkin workspace set up to build the ifm3d-ros code that looks similar to this: +``` +[ ~/catkin_ws/src ] +rosuser@tuna: $ pwd +/home/rosuser/catkin_ws/src + +[ ~/catkin_ws/src/ifm3d-ros ] +rosuser@tuna: $ ls -l +total 0 +lrwxrwxrwx 1 rosuser rosuser 50 Mar 26 15:16 CMakeLists.txt -> /opt/ros/noetic/share/catkin_ws/cmake/toplevel.cmake +lrwxrwxrwx 1 rosuser rosuser 31 Mar 26 15:16 ifm3d-ros +``` + +### 4. build the ROS node code +Now we are ready to build the code. The following code block shows you how to simply run catkin_make without anything else happening further. +``` +$ cd ~/catkin_ws/ +$ catkin_make +``` +This will create a `devel` and `build` folder in your catkin workspace, which contains the required code for running the ROS node. To test this you can easily set-up your current shell and run: `source ~/catkin_ws/devel/setup.bash && roslaunch ifm3d_ros_examples camera.launch`. + + +The ROS package should now be installed in `~/ros/ifm3d-ros`. To test everything out you should open a fresh bash shell, and start up a ROS core: +(Please don't forget to source the ifm3d-ros package first if you haven't done it yet.) +``` +$ roscore & +$ roslaunch ifm3d_ros_examples camera.launch +``` + +Open another shell and start the rviz node to visualize the data coming from the camera: +``` +$ roslaunch ifm3d_ros_examples rviz.launch +``` +> Note: `rviz.launch` does not include the camera node itself, but subscribes to published topics (distance, amplitude, etc). A camera node need to be running in parallel to rviz (you can use `camera.launch`). + +At this point, you should see an rviz window that looks something like the image below (note that this is the view from 3 camera heads): +![rviz1](figures/O3R_merged_point_cloud.png) + +Congratulations! You can now have complete control over the O3R perception platform from inside ROS. + + +## Building subpackages +Please see [this documentation](distributed_build.md) for how to build some of the subpackages for distributed systems. \ No newline at end of file diff --git a/ifm3d_ros_driver/doc/distributed_build.md b/ifm3d_ros_driver/doc/distributed_build.md new file mode 100644 index 0000000..007f38b --- /dev/null +++ b/ifm3d_ros_driver/doc/distributed_build.md @@ -0,0 +1,47 @@ +# Building and installing for distributed systems + +We have structured the ROS node into separate subpackages. This allows us to build only a subset of packages from the metapackage `ifm3d-ros`. + +## Building only one package from your catkin workspace +The command below allows you to selectively build only one of the existing packages in your joined catkin workspace. All the following commands can only be called on a device which already has ROS installed. + + +``` +$ catkin_make --only-pkg-with-deps +``` +To apply this to one of the ifm3d-ros subpackages, please replace `` with either one item of the following list: +- `ifm3d_ros_driver` provides the core interface for receiving data for ifm 3d (O3R) cameras. +- `ifm3d_ros_msgs` gathers the ifm-specific messages types and the services for configuring and triggering the camera. +- `ifm3d_ros_examples` provides additional helper scripts and examples. + +### Building the driver package +Let's say you want to run the `ìfm3d_ros_driver` on an embedded system like the VPU itself. To make it as lightweight as possible we suggest to only build the subpackage `ifm3d_ros_driver` and its dependencies on / for the desired architecture. This will look something like the following: +``` +$ catkin_make --only-pkg-with-deps ifm3d_ros_driver + +traversing 2 packages in topological order: +-- ~~ - ifm3d_ros_msgs +-- ~~ - ifm3d_ros_driver +``` + +### Building the messages package +Typically a secondary ROS client would only subscribe to topics of a shared ROS master for receiving data and configure the main driver. Both jobs can be achieved without having the main driver package `ifm3d_ros_driver` installed on the client system. Therefor only compile the package `ifm3d_ros_msgs`. + +``` +$ catkin_make --only-pkg-with-deps ifm3d_ros_msgs + +traversing 1 packages in topological order: +-- ~~ - ifm3d_ros_msgs +``` + +### Building the examples package +Building the examples package by itself (with dependencies) will result in having all packages build as it requires all three. +``` +$ catkin_make --only-pkg-with-deps ifm3d_ros_examples + +traversing 3 packages in topological order: +-- ~~ - ifm3d_ros_msgs +-- ~~ - ifm3d_ros_driver +-- ~~ - ifm3d_ros_examples + +``` \ No newline at end of file diff --git a/ifm3d_ros_driver/doc/dump_and_config.md b/ifm3d_ros_driver/doc/dump_and_config.md new file mode 100644 index 0000000..5ca1094 --- /dev/null +++ b/ifm3d_ros_driver/doc/dump_and_config.md @@ -0,0 +1,286 @@ +# ifm3d_ros_msgs: Dump and Config + +The ifm3d_ros_msgs package allows us to configure the O3R camera platform via two separate ways: +1. Use ROS native service calls +2. Use dump and config service proxies + + +## 1. ROS native service calls +Per camera head connected to the visual processing unit (VPU) of the O3R platform these services are available: + +| Name | Service Definition | Description | +| ---- | ---- | ---- | +| Dump | ifm3d/Dump | Dumps the state of the camera system as a JSON (formatted as a string) | +| Config | ifm3d/Config | Provides a means to configure the VPU and Heads (imager settings), declaratively from a JSON (string) encoding of the desired settings. | +| SoftOff | ifm3d/SoftOff | Sets the active application of the camera into software triggered mode which will turn off the active illumination reducing both power and heat. | +| SoftOn | ifm3d/SoftOn | Sets the active application of the camera into free-running mode. Its intention is to act as the inverse of `SoftOff`. | +| Trigger | ifm3d/Trigger | Requests the driver to software trigger the imager for data acquisition. | + +As you can see the two services `Dump` and `Config` are also part of this list. +### Dump +Calling the native rosservice `/ifm3d_ros_examples/camera/Dump` for a certain `camera` will return a string containing with the camera configuration as a JSON string. Please notice the use of backslashes (`\` before each `"`) to esacpe each upper quotation mark. This is necessary to allow us to keep the JSON syntax native to the underlying API (ifm3d). + +>Note: We have mapped some camera configurations to native rosservice calls to make their handling easier, e.g. `rosservice call /ifm3d_ros_examples/camera/SoftOn`. If you think you will benefit from similar rosservices, please let us know so we can add more comfort handling. + +Call this service via, e.g. for camera: +``` +$ rosservice call /ifm3d_ros_examples/camera/Dump +status: 0 +config: "{\"device\":{\"clock\":{\"currentTime\":1581287336449588512},\"diagnostic\":{\"temperatures\"\ + :[],\"upTime\":196692000000000},\"info\":{\"device\":\"0301\",\"deviceTreeBinaryBlob\"\ + :\"tegra186-quill-p3310-1000-c03-00-base.dtb\",\"features\":{},\"name\":\"test\"\ + ,\"partNumber\":\"M03975\",\"productionState\":\"AA\",\"serialNumber\":\"000201234160\"\ + ,\"vendor\":\"0001\"},\"network\":{\"authorized_keys\":\"\",\"ipAddressConfig\"\ + :0,\"macEth0\":\"00:04:4B:EA:9F:0E\",\"macEth1\":\"00:02:01:23:41:60\",\"networkSpeed\"\ + :1000,\"staticIPv4Address\":\"192.168.0.69\",\"staticIPv4Gateway\":\"192.168.0.201\"\ + ,\"staticIPv4SubNetMask\":\"255.255.255.0\",\"useDHCP\":false},\"state\":{\"errorMessage\"\ + :\"\",\"errorNumber\":\"\"},\"swVersion\":{\"kernel\":\"4.9.140-l4t-r32.4+gc35f5eb9d1d9\"\ + ,\"l4t\":\"r32.4.3\",\"os\":\"0.13.13-221\",\"schema\":\"v0.1.0\",\"swu\":\"0.15.12\"\ + }},\"ports\":{\"port0\":{\"acquisition\":{\"framerate\":10.0,\"version\":{\"major\"\ + :0,\"minor\":0,\"patch\":0}},\"data\":{\"algoDebugConfig\":{},\"availablePCICOutput\"\ + :[],\"pcicTCPPort\":50010},\"info\":{\"device\":\"2301\",\"deviceTreeBinaryBlobOverlay\"\ + :\"001-ov9782.dtbo\",\"features\":{\"fov\":{\"horizontal\":127,\"vertical\":80},\"\ + resolution\":{\"height\":800,\"width\":1280},\"type\":\"2D\"},\"name\":\"\",\"partNumber\"\ + :\"M03969\",\"productionState\":\"AA\",\"sensor\":\"OV9782\",\"sensorID\":\"OV9782_127x80_noIllu_Csample\"\ + ,\"serialNumber\":\"000000000382\",\"vendor\":\"0001\"},\"mode\":\"experimental_autoexposure2D\"\ + ,\"processing\":{\"extrinsicHeadToUser\":{\"rotX\":0.0,\"rotY\":0.0,\"rotZ\":0.0,\"\ + transX\":0.0,\"transY\":0.0,\"transZ\":0.0},\"version\":{\"major\":0,\"minor\":0,\"\ + patch\":0}},\"state\":\"RUN\"},\"port2\":{\"acquisition\":{\"exposureLong\":5000,\"\ + exposureShort\":400,\"framerate\":10.0,\"offset\":0.0,\"version\":{\"major\":0,\"\ + minor\":0,\"patch\":0}},\"data\":{\"algoDebugConfig\":{},\"availablePCICOutput\"\ + :[],\"pcicTCPPort\":50012},\"info\":{\"device\":\"3101\",\"deviceTreeBinaryBlobOverlay\"\ + :\"001-irs2381c.dtbo\",\"features\":{\"fov\":{\"horizontal\":105,\"vertical\":78},\"\ + resolution\":{\"height\":172,\"width\":224},\"type\":\"3D\"},\"name\":\"\",\"partNumber\"\ + :\"M03969\",\"productionState\":\"AA\",\"sensor\":\"IRS2381C\",\"sensorID\":\"IRS2381C_105x78_4x2W_110x90_C7\"\ + ,\"serialNumber\":\"000000000382\",\"vendor\":\"0001\"},\"mode\":\"standard_range2m\"\ + ,\"processing\":{\"diParam\":{\"anfFilterSizeDiv2\":2,\"enableDynamicSymmetry\"\ + :true,\"enableStraylight\":true,\"enableTemporalFilter\":true,\"excessiveCorrectionThreshAmp\"\ + :0.3,\"excessiveCorrectionThreshDist\":0.08,\"maxDistNoise\":0.02,\"maxSymmetry\"\ + :0.4,\"medianSizeDiv2\":0,\"minAmplitude\":20.0,\"minReflectivity\":0.0,\"mixedPixelFilterMode\"\ + :1,\"mixedPixelThresholdRad\":0.15},\"extrinsicHeadToUser\":{\"rotX\":0.0,\"rotY\"\ + :0.0,\"rotZ\":0.0,\"transX\":0.0,\"transY\":0.0,\"transZ\":0.0},\"version\":{\"\ + major\":0,\"minor\":0,\"patch\":0}},\"state\":\"RUN\"}}}" +``` +## Config +Below you can see an example on how to configure your camera via a rosservice call. The JSON string can be a partial JSON string. It only needs to follow basic JSON syntax. + +``` +$ rosservice call /ifm3d_ros_examples/camera/Config "json: '{\"ports\":{\"port2\":{\"mode\":\"standard_range2m\"}}}'" +status: 0 +msg: "OK" +``` + +This is equivalent to: +``` +$ rosservice call /ifm3d_ros_examples/camera/Config '"{\"ports\":{\"port2\":{\"mode\":\"standard_range2m\"}}}"' +status: 0 +msg: "OK" + +``` + +## 2. dump and config service proxies +`ifm3d-ros` provides access to each camera parameter via the `Dump` and `Config` services exposed by the `camera_nodelet`. + +Additionally, command-line scripts called `dump` and `config` are provided as wrapper interfaces to the native API `ifm3d`. This gives a feel similar to using the underlying C++ API's command-line tool, from the ROS-independent driver except proxying the calls through the ROS network. +They are part of the `ifm3d_ros_msgs` subpackage, so if you can't access them please make sure it is installed on your client. + +For example, to dump the state of the camera: +(exemplary output from an O3R perception platform with one camera head connected is shown) + +>Note: The service proxying only works on the `/ifm3d_ros_examples/camera/` namespace at the moment. + +``` +$ roslaunch ifm3d_ros_examples camera.launch & +$ rosrun ifm3d_ros_msgs dump +{ + "device": { + "clock": { + "currentTime": 1581193835185485800 + }, + "diagnostic": { + "temperatures": [], + "upTime": 103190000000000 + }, + "info": { + "device": "0301", + "deviceTreeBinaryBlob": "tegra186-quill-p3310-1000-c03-00-base.dtb", + "features": {}, + "name": "", + " partNumber": "M03975", + "productionState": "AA", + "serialNumber": "000201234160", + "vendor": "0001" + }, + "network": { + "authorized_keys": "", + "ipAddressConfig": 0, + "macEth0": "00:04:4B:EA:9F:0E", + "macEth1": "00:02:01:23:41:60", + "networkSpeed": 1000, + "staticIPv4Address": "192.168.0.69", + "staticIPv4Gateway": "192.168.0.201", + "staticIPv4SubNetMask": "255.255.255.0", + "useDHCP": false + }, + "state": { + "errorMessage": "", + "errorNumber": "" + }, + "swVersion": { + "kernel": "4.9.140-l4t-r32.4+gc35f5eb9d1d9", + "l4t": "r32.4.3", + "os": "0.13.13-221", + "schema": "v0.1.0", + "swu": "0.15.12" + } + }, + "ports": { + "port0": { + "acquisition": { + "framerate": 10, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "data": { + "algoDebugConfig": {}, + "availablePCICOutput": [], + "pcicTCPPort": 50010 + }, + "info": { + "device": "2301", + "deviceTreeBinaryBlobOverlay": "001-ov9782.dtbo", + "features": { + "fov": { + "horizontal": 127, + "vertical": 80 + }, + " resolution": { + "height": 800, + "width": 1280 + }, + "type": "2D" + }, + "name": "", + "partNumber": "M03969", + "productionState": "AA", + "sensor": "OV9782", + "sensorID": "OV9782_127x80_noIllu_Csample", + "serialNumber": "000000000382", + "vendor": "0001" + }, + "mode": "experimental_autoexposure2D", + "processing": { + "extrinsicHeadToUser": { + "rotX": 0, + "rotY": 0, + "rotZ": 0, + " transX": 0, + "transY": 0, + "transZ": 0 + }, + "version": { + "major": 0, + "minor": 0, + " patch": 0 + } + }, + "state": "RUN" + }, + "port2": { + "acquisition": { + "exposureLong": 5000, + " exposureShort": 400, + "framerate": 10, + "offset": 0, + "version": { + "major": 0, + " minor": 0, + "patch": 0 + } + }, + "data": { + "algoDebugConfig": {}, + "availablePCICOutput": [], + "pcicTCPPort": 50012 + }, + "info": { + "device": "3101", + "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", + "features": { + "fov": { + "horizontal": 105, + "vertical": 78 + }, + " resolution": { + "height": 172, + "width": 224 + }, + "type": "3D" + }, + "name": "", + "partNumber": "M03969", + "productionState": "AA", + "sensor": "IRS2381C", + "sensorID": "IRS2381C_105x78_4x2W_110x90_C7", + "serialNumber": "000000000382", + "vendor": "0001" + }, + "mode": "standard_range4m", + "processing": { + "diParam": { + "anfFilterSizeDiv2": 2, + "enableDynamicSymmetry": true, + "enableStraylight": true, + "enableTemporalFilter": true, + "excessiveCorrectionThreshAmp": 0.3, + "excessiveCorrectionThreshDist": 0.08, + "maxDistNoise": 0.02, + "maxSymmetry": 0.4, + "medianSizeDiv2": 0, + "minAmplitude": 20, + "minReflectivity": 0, + "mixedPixelFilterMode": 1, + "mixedPixelThresholdRad": 0.15 + }, + "extrinsicHeadToUser": { + "rotX": 1, + "rotY": 0, + "rotZ": 0, + "transX": 100, + "transY": 0, + "transZ": 0 + }, + "version": { + " major": 0, + "minor": 0, + "patch": 0 + } + }, + "state": "RUN" + } + } +} +``` + +Chaining together Linux pipelines works just as it does in `ifm3d`. For example, using a combination of `dump` and `config` to set a new name on the camera would look like: + +``` +$ rosrun ifm3d dump | jq '.ports.port0.mode="standard_range2m"' | rosrun ifm3d config +$ rosrun ifm3d dump | jq .ports.port0.mode +"experimental_high_2m" +``` + +>**NOTE:** If you do not have `jq` on your system, it can be installed with: `$ sudo apt-get install jq` + +For the `config` command, one difference between our ROS implementation and the `ifm3d` implementation is that we only accept input on `stdin`. So, if you had a file with JSON you wish to configure your camera with, you would simply use the file I/O redirection facilities of your shell (or something like `cat`) to feed the data to `stdin`. For example, in `bash`: + +``` +$ rosrun ifm3d dump > dump.json +$ cat dump.json | jq '.ports.port0.mode="experimental_high_2m"' > config.json +$ rosrun ifm3d config < config.json +``` + +Beyond the requirement of prefacing your command-line with `rosrun` to invoke the ROS version of these tools, they operate the same. To learn more about the functionality and concepts, you can read the docs [here](https://github.com/ifm/ifm3d/blob/master/doc/configuring.md). diff --git a/ifm3d_ros_driver/doc/figures/O3R_merged_point_cloud.png b/ifm3d_ros_driver/doc/figures/O3R_merged_point_cloud.png new file mode 100644 index 0000000000000000000000000000000000000000..a0c2163bc2b46405cf049c3e20fc3f75e98ab3b0 GIT binary patch literal 763340 zcmeFYXIPWl)-_BK(WtNi14z{%9YH{PQITGP3P>@4^j<y%!0+_aen_vCrP;Jl~J^$MfU;@m|;Q@)DDK-77aMbImp87-NP$hO1nIFhNL2 zNUo`=Dn2D4p|mC;A^&>mB6w%Y%u^oxc>hw@z~iZz_f1zf7i&95tD7Fau2wg#eC)tT zpHaPtiEBZ3FTI^gY@j*hk45(PH(g^f9c4mIk+ZyIp@0(kk%)ex_FIdd#LANy(T;F= z(_aVAnU74SFP<{pdF(Y>E=fWHxnu{P%0Np~+QP+2(9F`s+)B{L$rU^<35o1|A6GLA z2P==8=2kX#&T_Dg>N?m>J4-p3zL?fsE!Rg@wsxv7-K=z8!gVcPI#@_q!tTpMWPPN; z1Wr~SW;cDD9G%^zedJ(&%_|N5fBv=*?B-uXJRIa;23n7AK5}uhx_M9Vp5Wa(N~cg@nAly#>8R1zp^1goLG}q=fE@2#JW?0VD3X z`#O7=`P^}K=Qy9@Uvns0xm&o|xq8^SINv;<)6Cq((?bph1J`fKG?+X3T;U0F@|A*n{SN=2n{ATILc0N{)28wo0R?hC=5#(UPl2Z5nn(aTA z4gbewDKW{vuAWaNt>$EAW2J9r>0$dn?)%RbRVzCiTkyO5|L)Otv$F!LaQ^#(n_xoc zYbo^iVuJ5R=-*$?`3n8t|MTAu`CqN^f0ygO%k{rnf&bOu|3=q;m+ODE0{^SQ|BbHy zx0Va?A9!cw3^1KH0B<_aP{jcFU2s=W)4c@#_+PRNAtAX*qNeyz*JpG!#W$HnuXevK z=55OyUQAk*t04A+&0*yn5!2ku3OPm-?>hz7DS@n zaw$6~yO3G0^MhqER4~0_;q8N!fppcRxzqGOz5de6%YKE0Aq&Sxo!rL8dYCRLJ>zSq z{W~Y4UwB4^%^EJS`K=1a3mU&~HpdwV(1$f|7pkI>q>K6wf0|&BN1C%cc!*?$0eq@X zWP60FlvL^kziXiNY5Qn;9>0GN)~&d}HCJa&80wb1k1sWt|Ji24e76xlKBGGV@qeIy zXp7S{^mC+4C5@L7yQo*6PJSwT#gWpBgh)!B=bFn}$5n#dV6-kCnB`yQRuM7ub;|x*=zGJTVa zX#(69qdcuij)-~t$T;{NxihKgZob4f?JZWtyqU-45iZ3@DTJTD^1Q_dq!jn|k#^$7 z;9d-hK=mR9l3?3|KaAu?Jm}iuTDk}`d$Pde>4X#Ps^2y_zsmf7Qhf+ z*6klw=@9R(AuVv74@b%C#RSs?;-zG^ed!PVtsQL?<#UtysHMfggzg@}D;XO$%JNCN z^%tSrea5>Zf5*-FkN6biRx^WpJt<|8=gPB|k)@))LdqOhGwkE@DJ_>H%@9_;{vJ+r z`*=yb)h?1ayXQFK@_>S6c%-?qSp;JzG~uO6k@t)gM8)__zrlL{VNhP!!4<5O9{mzT zh?I-OL8-G+dV7h1W`_WeE90}wVkzv4UDPM-LlJzYOQN;4XLnSl#W5XD@VIMyFH#`* z41+8JzGeguLZfB?@5n(PZ^Mk9$P{|S_aYy{s7uNz)%9#z8Po9%9>?0$ur?M>u;EBs zfu)&2Hw9cj7DSOxS|XlZ+wHqxLZRysyjAZBkHftFGyJhwgn|F5=By|cegvEKt50|g ze}dV^YbzQCiHR^ozUR5JsXkp+PiY13=8HdaRX)5pta0}3eX)+ng5P_j)KmQgOZ6o` zr=|wZdR?N3seVF~oqG;ahm;;X^Dx!*OjPA4alFmOZC%4JoA zM7Do*8DP5tOS{H*VH(XhYX{u~VWSM))PTCayMzjLJ$afqg(~jec#Yyy4Ibc7%$Cz^ z8NTRWWdM(4zk;)%=w3D8y5ZgF&-z(zRD>v{;Fsr?v$U-Y&G@oP5#6lS z&;&Jh;>5F~zOc9yht$M`YgFt@3T^iVYKyO@ecLe`C6=}=cqSfvD9>V)NU3;BWp|*w zH043uzLHp>Ry@_O`CKN*Aatu3EFA zW3j_i_~dLkdb>z|j<_&*(v~@EOp6h8^BHkQMz8Bm{1G*c&`@@i11ya>h3~7* zTo@d+lFW3=%5*8d5zsDH~T>P#!jQ;5S08j&5u9zr4)VQ_t%^)OGzN(M)F@U3M| zuYQ3e%|R(7<$-|hy<`=b)!<=x=&-rts3D$_OKXiQ` z{OlRrzW-RoP6+C?;1C(9B)>plyh%^V9m@FAi0Ib*;68ht{MpmsRf=S^Amz!^V2_m! z#)obN1sR1BIYD2;NfIRl38L=zs6uq>C1z_mlvD!??zn_+);yuW$}oOe{j_`NzE2%rKTTJ ziSJlR$S@rQOBNd?d5ntu1dQ##>StoOgQs=g5R`C2b7+a{{4r_~1Ci8FJpF={65UR; zSJ#XZo)lU*J!xA|HU6>MW|La58El@ImJ<|!BK&#h)bDfg)Xt@L_tMrIi4K+#`z@Wv zH)fc$d5oTn{wE!ssc07Iy!a=oa8Z)ll+Cw3T9rZYMa`a4pUA#W*QK_Qv^CpmZ@baG^**~fg#6Mj9c?f#QnXcc)YcShpG-y(F!ml^;S+i86J|J<8n^|H_ zrm3f6MTFpT;mlV3M13*|HfF9nPn>jz7}IgcJ7e9O#ApgPP27t4#cz zM&|$u1mM|{LAKobZ^C9-$W}?BJk1dcF6?7^uJ;pWH~tK`x{u&T?>~^0uAfpxRqlGfpO&4#citn#Fc6Y6GBX}Z&wPHwF9z?9aHbrtezg^81kMz?j75m6*e4iTeni8C6iUL=)(R0|AOxtnc_3ykbR^F^( z$T8KX`NLDk&MjS?FV`0Da#|RP zddm|@w{>r6K@SFtw;nN)ZnF#?04@&{R?6mHYhYbUJsDBm{dLpQhfq-qRdq!~` zMQ}6>EGgLJz;s+Ex`h{Ps+b=fN+k2e%+?l4>s4_M`jCCnyXh2+W%hjo8G+L-8PAw3 z2wka=$;BL3MD?q$yW3ya3QfaC0l>$PyK;u+n_g|xW=8<{iu9V@3DU8O8PDyyZnNsy zEOMMkyP(RtDk@rF9<&l>HUD12_tE@WxhOo+9|p~c*fH18#s4Q(Px#G)4gZc^!hNV{ zI6=YK3?&I;u#3Er)8vL}v4^fcjjc7Bk?tm3@(e3&1(zRFSWIdg@Q`(B5=FH2@vT@S z&e6MOzm2pcoZzUV-uyjpOq}ou;^Sh&z-=G-A;jl0IiG4u841Q-d%V1RZ;9j1>5kIs z;yuBN(vbTgtUe(7s`4DXd(+P7pUll@9;-PGiO$vbm9`c^4nIQ-z^;#zu9OKOqK@_2 z#IgF-kM)NkhwwNMjklni7ik9Jv7XiK2^D0K*eC)l?OW5#yd#~8pbJ+4a;#865c;HK zpjMsWCLZte5qU(1+pIKc>H^{IaO0iDOtDgVk~L!eTS#q6i`GQ8T2koUYRPRovIA+H z&P%mfcRO5X5sSkgNZ*Ti?!HNJbN$WA=x(-pcB@meH5@2v-s~$OFxra3%0*A}iLe^=(4ooTZHk1tK5V&UzEdY8-u zilB(WI9*MDDc90VxjLEjo41L@Zw&CVM*4?zuCWEbVS^?@DfTZn6)fgAIj=0anMB4@ z(t4p!Bij%{V?OH-Be$B&EoVwiFbZ6ugk5Ghinac>j(I`BCiu0h%2X;OgNDLZyw59< z3&+>^W-o)o1<#TtHyFCIHwH(69kuji)ivNd7OAx*HM9$E)oV#Kj__Z1&yk(&A0EQ% z!qR>{B^?U&`}KfkHSO^&O1sE(%Nn)3g8(>UM`B$Y5#ud`dvo{@qs)veO2da!$E>)R z61OYOrBdFkG;s!GD{4%+P$2%DiMNFwJio3a!=;%}ZxJci(wnKV7XA;^G}#nD`NzwM z4Tji$lr*zpLTf9^vpZmgF5`kAuF3no0XB^28(B^E&~@D!fBBiV0a{Z(HkEM>^3!A; z0Sx^6+w;n0U($hr=2J@V(Cd`lB_o;y@A3^h*kY=lKuI04wTYQ~4|%Nj0FA5^+?Faa z$TDTYVeBH4Qkck#UySOaO=$2i2)0%|Rqfe6js~74 zs!^gxFroP<=@OPZ#Pz&5fkN?sATUeTu`ID_1=6||mAroN@E4(Sj0wAr0B)n9&VeqEjJ>MGQ zpZa1AKJnkPiZD@M{p3XUNW`X3WMMR}yOB9uBTdKZbBKNSZ$tVicIqs=3bRF}5{CP} z3KX3~(D>^F%@}u4!wc(8PQKxisY9x|J5)2606LpJ@x;hAH>wI68SRRWDPwrtNbyu4 z?5)ewTPhBbQ@;&SO=``&;l6=RoZ(90I|Ue38d{_!zp>I3_dM1jGDd3hBFks~RVu_S zn%=(KT}RvIiNw;@tCe1@?F$w%MV;7QI|I$uIv-|kBy^Z`CAxD($OvY20gZAMXE*DsF&d2neBnH^Gk zUO*4Ay$f+o-rd*($JY|~_T=r*2Z8liWXL|FP#XDcGN{99o^%<)e&68V`K5(vNsR6W zxjiOx(Dex$-ys&lTOLxSG{QyW$z9eYR3Z5MZ@3{qPq_bkn9$b*aw^H7{O1)SXPu(m z2wCTG$>lxispH9m)zyFRfV&=y=sT4!f4+E3!j>V!a%a|n93gE z4RXh>ff0dYu9dXT0mJl$UB=5G#XB|TGV0z+dOpaxIwG*yr7WR6r|fIbFxJ${s#K9T zR4Gk8d+b#i*)@b)yV+dZR1)C?Svudv>IkQspdNa5^d?_XT|?jiIX{p@`s6XKvx z1@F~l8BRx^sI#>nkU9zULie5N@qO5>e1B8ESrdVopLZH_dv^{zoMU%XUXDBzVA8gy z2j_H6Mb9^{Y0qzD3=zA<*Ag)NHMGMRLx3&7uTumyz$m143?vGEnRG72N$D@hp(<if$J(@~8gJn2PS!Q&*D(GvHr zfZ6V5keQ4LxCZTlN@F-VcW2c4^?`U*OVvwFsAPIihQ$jDCe)=CmZX;uAI|(o;lYoyWZ*5 zv%*mpp264nrd#&e;4DjXfyjqb#QxzAxjQ=0VtBB>#8j*IcEAajM8`dyna}?0_uCGT z6PtWrlT6!d0d)5W2Ekd^HqcI}*`p`Sex#WEE)c~*FO)_am_v3ZqrWh;?ORuDU|kdL zkPbO~>PL-2q+EXRX#S||8yVf~PAqvK7j=TBn4q89aVUpRr1fjCq?3b-Sv)HT&h)mk z%Qg8u-y~-!H3QMPJM+pCDvOY7l`88!0(VF7CwJ>Uq~%1#sKghkl+VDMh5&m2x+92j7r{0Y%&Z`=m#Xww{CpvqelRb+Ur(2KYCr1+qKdKr& zS1DvDFjY!}3d1nEJF9a$ltbfiYiHc=&cA94u;=GC{;Zzd6WkxMVJ~-?a!wEb=aSG> zBZp?Lt)d;#o~AI4G>Q~syMU3m{IE2uncpcSANnB-#w#^)Jf{YU3ag4IfNlN0Bbg5( zP5XMAc!z3iP~16?ZD9jDN-orB3e4H^S5pPsC9X?141O*{R4 zH^ad^6ZGi^X{=00^Ufpb>Zj;kknKJBEK!#wAKJg|0t5M$2qjHj?SeWpmTQ?bC50E9 z>1~KwGjC56XLqi;z7u$rXJDPfD-6CTO^U18K{A~0%PkRrTAqNT&>fyK*<|85cRgt* zf9M+KDooN>+D%MyHjAW%`@^Gn*8Gy0!tQ~T;q0ArHRrcXi|94M#DyCznG)NTjo585 zOiOQ@%}3;oXI226B!A)0gC5Lw>qfO)1(9oz{ey()7TV7YAO57!LSCX7N`<`Zr5ezi zYMwZf)daXBFPdlCz0h)+EBW5mKg+oCDOifDBMwq-b#$zZWy4R@C^)$6Z5Ucr758dstz@fcnRuoT;vFP2hILq~cUIFyp{Y<3$v!;d#!)hw z24&5NrUEq!`%S2=(ZQ+Z><$#u0m>fDBhtV<(=84^hutl1j2-%07qx` z+f4S#z|0@XoTqOk<@a;iZ1|BEwpig%eftP;E8k$mBebG?>-rayEmMsZG50vd)bT~X>{OrTBY5Uh)+F`n8@3p52pnJh--SD= z;WU|%vEua~%oCSdGP$=6VNb@cl(zbhc)x)d+;lH~RPZE(7@S5buO}dC`t~~^bIsRI zYl81UU26gh8!pf>GjjLFh97}yC?(_<8s_F=L6SHNh36+)Slsw^(_8<|byZUl`r zs7uJ1-F+peTB9IKaYjk(OiOd8DCa?JkXT~dBxjFSUfkjjD&n@u2!Im4sx!PXAv13Q zoX}{@1q^X$cYrh1jOy@Rs5!Uz6-`HaP+i0O*|?V>Qy&7l;&`TSK}867mhl8a)b5(% z8uF?2SS~CLeE3wyL0QwSicCVNZIbbshqdpHsc(cl^HHar$IgSVLY|{ktG9n20gz-^ z)rGIfDU>r?tbE!RId~70t@8lcqbihMDP18c29C~0nWxN(v2xW0^T<%)NdSa? zk2c}@ElkMN!`@$RN~KPbtFYr>>kw{%{^eD?Ba&=aviCAjatduCk>u`K-ey|7A%baX zq}4cH^JkX{s!nE_YDYW*!cY3I#EiL^dV_9w!D$5;I@;T*K)`j@t1xUEh0Ct?yLgRZ%07kfZx5 z@vatr)QzzHbpZOGQRt5O8PHBNK``pz*u(~HxlPFO^t4sC%TDrtS@zH|2Q|X^Ljo-A zEjC{apsxw0rLVF__qT$wgS!*4o60W@F=X-dgw+9o&8;>Yje;(Yqqq}si4OWubC($5 z4c?)-m(cHR1IXDu3pX|ZYP1QapABEgB4f7>IMrXiOi!|#iJeqOyxF(mn@x}Irrzcs z$yV66r$4myprZ?VKI)h7A=D65NI3lxAUBG9%-wk#QaVx9U|Z0oy&Z7RE#3b`2HL-b zqzTuh6Ha)}Jn)&a633z%m)AU#++$*(jWS`s!Z{f zUvKjs`~=}>6E5(hURfe?_Bg=|(Zyoe(0C-zC4Plve38w4RTLmerR5r~JrfKw8sp|E zFMH}bm>mVEpRkbojeMG{*sm`m{_z5ofr@Mid46wy0%1AjQcx&KIjfK2TP#29{+fyx z+sx^hkBGiaJW>YFeXSq=zx#%m(C(Z5b z$xGGga2D^IU^?azDHfSsE1^}e2CsT44vpS-3`XqcAXn|%(n|(pNCX(bj=#4mto1NY zG%?Zm03eUY8^9?htzh+Q69VUf?V#Ic1l`Uaf0Wue;0yLjwUS~T0h?)lGTK=#>?Hef zBOOQsVclg1=SSRGH0SDNEa7Yu)Uxx-c~Iot<4-MbtzYXM$y#N1R+qusc(Z5m|E-absBn4@KT%I zsoZD#8ncnEGxN&DcH>8nKfBbZ0Z-ScU&b%AavhvH0|Z#H38Oh%9FG#=L$pFkBoT z$qR-$e;J%?)K6iW>OR;4HQ|bG8v}@LP*DOxE(KMoDIus&Psnq#ulZs)&5Cjc^^?sT zAb#K4DQo@Jez2uma9$vy#(6NPT{2w#SQ~14Us-}bQ+YGGs-dq^IslHEnpKv%zl~j3 z*1YFzG=*1NT}-h<1jcR<(}AF^#yW?r2ipsLg6ti!H&bA>N)ZK>(XmME>ydiJ%{HU?_!Qd4X*YM)21!+=h#X#-45_{48fP&T1mg z*jC@#mOAxao-#VKDQ$7sSlz*kb6me>Rj@Ud!q>VC@s<<=WM#aLMU}tvhwh;$$c=b| zskf0(Lg#n3jWB;U`=eC_0o#@`BXWBC$a91>TV={4{Ac&xUZqzBDc}k-n?-7ygNUUP z^LVtSybNm#s}7ySj|*!!^2kUH*}J{-M$n>X<`I#?f;+cA?x(&ET=&QspX*<|D~MK- zN2}g*rFE&HM53kuR=nKOEPQK2oReNvYt$0qklC_^93>ir-e!At>)`5c$s7DvXRnDF z^F)g>m3RH$jWG%laoz5{LyogMWTBoW>12X2VUWo7`r^7 z_@m$^xKMxGJumz<$)_zf4=FUoI9Z5p%Cp;8^F+Wq)U?^eKq`&K^K>*rbDw|ND*WIy zq;YM5H>)WM;+xL9rEYkZ(z!xrZ1%qYw@BUkC!-e3MQXvC;(|%KZQZ){(X>`Iz1ZS7 z$#|)!x7=^{-k8SlO*>YyJOB31cmHGgKYW@%d>#G2b-$A^oN_RN<|wZnKb0Cez;`Ih zZ4VRK4SDd=PFbLH&`0a6*vYEWz}|}M_?w7e?ziE957J+_9RS0=$4-aiqSwtG2gFLk zu30>?(r7tEkekL=&N}hwXqr`5TBI-yPO$CL<9C+J*Ql^TSB#nlk%_{bWU8ybU+eR= zB`=8oSqVHXsuZ2#oJT`e<-EvTope!-2(DvKCiHV(IO6La4ijV6qj7+Vyg<1e1OZ+I zHjb*vW!)RPq!NnqrnE?2EJaey*{6cKXAbC8; z)Ruo-^7HN}E3Q$xRNII}g-ZRgaACyw4!0~;A$2@h^e+FWuHRk@(J+v%d)U9?$|-n8 z$^b$(Y9-(gq>{kZKIuZ45cW+2o*C;&nJC{(ZxUrvs3+OIw#9-l{Sq zNCf?n2cty3pI>Fa_t!o^{0fKz)@)_YJvH1L*J<_+d4qmyM`Xk+SVwDxc_Yft_MKz3 zK}+rJ?U5n8z_6Ouz)^H}p>BO-Q|1Z%bVc#H?HaPQz*Xrlg12;EQr*7Fgm>pvT@el%|b& zsry!`WM}$)6bp`~$nG<|J}{i_Z(Dc=k4wvq>f=bOSi;9|T*uz`dxYz}u4A4v-st_n zXoq1YVHU{QQ=~%VUzhraEjK*>!vy`JVYYJo+qeg_DMw1ZvQ%TrKL#|N8)jc$89u7B^Sg)g)XLg zn-upHtKHkF*a-lVM%sISfaLHK*mFXa1*>-KgiVvVO*JU>RKs00Sb*K6S(B)4Jkle) zXY1*F4jQF$c-BOyrZp|guRWyZ2wgDV@%}9=FfDiIxNc_LdgUkAp0oF! z;VA5sLej$Wa^$T3c1SZ|?!3&Vg_k{N?QqKGD%#)K*!eGxulJuhjw#Wq_&S6gJC{L@43?eW#N3`| zd=bx!I-;IH-XXS0yJ>eS-ZmBZLV&HU^*>>0aea7Fo*Qm@X z*MlIy4T#M7<9V{tazem6$%U^xf{iI=tT-XW;7LqsQr?Oe3L+^@oIdd(R7EnpF^&j$ zOd;@{O~W$jw)v4HvXV=|(PcI=RO{^d&vNC_v*ic(y+d@o{=g&A6^g>#3l=Cz&zQCu zDjg=e+(3+u#pnIr#f3cLAuY1mMDPg#9TFyq94XKvZ4G%-wxc2BIg(gePf59%&mzL;Ps6+hFW|M;iMO*<-e4?|uKVo^JAcoR@ehC6dK)PlT zz%;o;Al5x|P9h}drnR1&)b@YouX#E-){4K7m`yaz3A#pGxyppb+%9H(K}{4H!25s0 zZUwGwsVp4_z~iRKxfdY-Jp%8Pv+0%h5p zZ1(^gsNs~MMGu2d=zSvhefqJuC&Akcu34RwOwIzMeqa7=U^p6Mw87N>U5zz2dYlup z?4548IvN!9j#`66rA-ZkPjd97HR!u}Wb4uFJ9QsuHlF1MHA+{5V zoPxV15fn(pO|>errY~#cwA42l z>+8IuL?$~K-}_ijndd(#k+R#oRSjye(o`J*_uS++fl$}5@O;w?IS-+(ANOrJ=-AEYZAxd4)8Jj?qQLHz< zeUN4$T@6GuBobJmw|`1jdLw#8CLJ?8v}YqLTf2wAX)I@JK(TbtDhH1PpmN7*48#^+ zZ&x4m>#VL}A=&&2go3!Ohv~Qo{cfgya#0dn61K-Td#7bCu3lfM$vGy_@i8fN7}4kB zrGh%jh#qKG=p(N;kf%dyeSA?o$FxF}^1wy+FqkEszm(K${`k&Q(mGwz11UXuPV+qq zk(P`>;7m=MY^+v_N-;+$>(whG+XTNut(nm6Sxw4zzktG8r$fZ>y~siG%6EJIyPz-- zkZFXJ{C!*s!TxAQ#-41-H{y4d< zu~BE(43*WWs(mGwe=`>O`~K6w*s1KYin_N`c@Bu#K6snlX~o(#IQL z=*c?-ss+{hDw7Vo_>IQ)QKGJ~+C*uI=#G1sj)u~}NXr}(&6S%4dmqC;_r>-ym87)H z>8=T9D727bth)3?DoB8v=5)@p4j57&8tLzcnG4e22ECRDD3CYcyCk--{7=gE0W-6E-8dQ$Vd;+Wv1X?}z5 zbrjlrLV2ZXpm#_>?N_{1SwE)?0gqrk!jkyw&ARJ_xeDt9D&BwMhq%)<4z~0|oUC%2 zoZ%>A?BaBj@5?Y9E7fGTH?-8rtV4O>bY3+qE{|c+h2j37L_M&&FiveNgyLnp{^Z47 zoehy6jQbgPp1RlF}q&g%#@Vl>U0LQuB} zshQww4CZec)|pU@3*g!S2~h+Yc18rkEYbvp2~PF?#y=QC&Ce8ZorSs~90#4AeAD`T z)6hh}MQ^?O1Eovy>iRxOz)g1~m~4%ZXFAdp78D{C1k&Nh&HxXYyDIv_-Btgv2*4UK z^?&pOozUHVexdoTM)Qvn#bn*074`!eT81^jx36!sXdR^3jW0l-0OB1mJzra_fbk_1 zb^&p6|2nCS>YX9QdnUJOJ~0pu3qt%sW6BL`V59t4uhc9u#jG&-S z2S|mZW|5NHB8N4a_iaKS?NuI5zvw)cAtsTZjssBk4U7D+FRAuds|+*pwp(4u*OKP; za-(1mb;T{v6fyK(GP(a_faRw&_xDy8b?dz^{*-!d!d+(O-QrF8vvLIMR)V)HMEQ4p zI290LF)5S_jHa14aY6*{$S&AEo87sBX?gYQm1LwJBO0@|x2^pRH>%+LOlz6B3 z^cBH-`jy(ZZ2;cc6g~=J$;LuC5@YtW)F(z`WU3{NA`X~{BGGv3L-}pv&8Mk!UNIrS z?|I%-a|(JO_DgnZI(yiZh;EPOkIQ+Y`~E3{2z3w!Q-5Jf7FUwz70zW5e;XU)Ux`~Y zqqUU+`F>Y8d9>w7RIhCqhWgpfV)jTkm=|q6*T84)m3&$43@2jB&Q`X-s^qPQ!->UD zX9CbNWx`bB{2af!mxsAn3gzT0!@OiN<5$8p>qbRRHS8O@#5tu!XSP6>37|#>_+D&w zFL$0*(upDQT_VoQ1#9;>;oo+B7YjWudEY=I6W4}9c&^~cyf%paD=`mRMJ?z|NZvvQ6{Qf1e_FBW3yUb#` zepIJ0@h5}7_RD+)i;#-!AkfI5ofE`+yKCULR{XA_JlN9CJn@D%8*FoVWbzcY>t$vq z56GdL@@qXDRAcD(A<2q-60@m(p&>;QQhHfQv}qCkf!To8q4W;C0(6EODko9hm+q3~ zfnFRfUX-3QIgobhcRYfDFLFxN?cu&ljpNX*DV$U9pl@_{or*l=`ix8$EgjZ1{E}bD z{&08fuztZePy_dI-1lVTR&ahktr=`zFbo%y*BOC$3_D!x&C~SC)|0U*LzMo~JN5ScX61)1(;wRw)v70&-Jq*EQ2E58AhqjH z@*{a^VC3LPBZYo(_Y`C_Y)Dr29)-sbS`n_q)H1n`)EZ8EyVagO3zkii^8PhZd{U=z za;aW)-^lmLPAeh>I9R-A*{V79wT;W#S6X)hPJ|^oN`OCX1)RMLqkhBHhA#li&1$!> z8_iks)v$hc+0lvKCk#1KXb4)Xe1Psmwzfq%O<0pFr5P$aP0W)4wXY&^Tba1+4lVL7 z335QNeJh*=#5gB$TQv0feDTXq1dE<6?7z*(mv_ZJXSzt6`VK zm3wZUR0FB_&__VLQUZ+zxhIwwwe{=4fC{seY4~JwPy)s{~{8PY<>V&S?dbq4c{y< zLyet_f_?0L+Wk=Rh2^|>_BV7ro8Wy1Mcw3Kfp8l5EqeV5a$o{$4XJ3gj|4_5nG_}v zI1xi}y2-!|BG3;7n*e9@Gv;m|{#;0+8huK-Z$`tP)``l3Ic-bxzi(-9OgV?JFQlK3 zXPZWU1unqN{P0UDbIWZDr@+w_w?VWFWq>R8YOBZt`SlOoHnpk-5b4<5{pCe2@Kk_E zWc=;5HxQVbfV8W4=`226l*Xejaih_W9!Lw)5*>gOztcOp{X@?}aa4TfCk{Lye1HvH z_ym#E()YQ^(ckr#jvT3IsoFIBI@~AeQq8lsrwc!zEpyiZr(sm^c?x?MYDE`|w3F|a z3TQSpsN*-WKtNEHC*ZKqEO1sDdG(~2dhT{%+P4AVg6ngn?|nx~E9|`y%_*B|+D>eD zE2#%AvpiS()p+K)J1tg7U@LGEi12rI+%SvNu?Q=b%2W75kLL-26nM=NdC43>8-~%_ z?>e5r%wv9xT_`ut*>hnhScg~*wv%RPEg&`kUnB=dQH(auE??Cs-NaRWQ0A#11z~&A zswxyYe|#SKbt@1*AnVTQ`re4*E=U0h)nsZh>jh%c86iJ4+34~b=;Zcma_3gcTALkd&^ut%6W2hF)Nzc3h0~u zCH2pl-A8t{`9|R)g1`dT*i4ZUPRv{63QWm$KT#EmhDcduptbm-+Ge7F=BdT^;sf#s zsGh3($DYoypo>rbjz^_Zi4S6V$zr*{8QdG-+<>Bi4Z!O1yy=(`dZPE+@8h=~JK~W{U zhJ2^POsD2=V8cKVL1Oc94cw|8uHtNX&{2C=kdVTp;^}p2Xgum!Tw@e$VgD_HBcd+_ z7sgZ?<`GO4`ojsOY?4oAt(v#-m{5gmD!Y6u;sX53AMZqPO`taS#}YrfYH^KL67Y8Y z8=oM3Yk)<{r>#tuGilIIwy$z3cX1M#97tsEjR{Q2J9j5otJPSQ*BUtb2+nL@Ke|mhEMW>eQ3j|5uKGy@tYf_3InTC5D%EY&3&@NeO$;1pw)Tscsc z*EWlQ1PK}!MPX@nS+VcynROpf`9P6tBTjDGQ=iDhvx8JAfSu8cBjP^%tg5UP@ZaEk z2D%?&4e31V?lmi_#!^AzZW@GZQ=8(tfp(v*348|2FJxY%oEB{s0UnsWW|3%!!JO_$ zh61>*w*5jcLjgn*RUg|syGYgGWL~27mk8>(t*MQEpYPbLJwNIgqo&_fShYnsa{vv~ zwomCmE#!X6mREa^PwGQ#^c$zy(!Wc!If~z*{~&o25(Ml%50E~_MDPF3O;gJXgq(f> z*2fR|W(xw?kb*Q1=>!Gh4dZFpiTiJKA5h?7+kG!ffD{T&bxj&mblI*$J|rP=M1qEY z475DF3cm=b>CC<7KPpFyLm$-Gf4ZOlD5>943oo*rSVl)9fxRrl&mo?|)35+QIHk82 zX(;1!i}GDST_+2SUCW7be;$F(do%0{>b|QvFFL*6@L76=Z6@um5pMjbxYiQVpvF3q zLACm6btko}K-fGFiufgUgn}GtDc8Juv%lDhIH=Pht@BHDmmwYgP#HLxEoYK)=FEr7r;z?R%9%aGBC}qP_OOO(|V#%@4A&9x2&e_6h4Zz zAC_IGUW_HlMU&XAScFC0vs->l5~uR^L(p=|g1RBwNEypYs&VdLWV?XX8m@j8JbqKm zc}P8A914$v!coo9+VA!clP?v3&=V(u{)AG}E2S#$c##$38dHhy%gg%9t{_v!CNeHM zzvC5tEy?;t#eUg@`^zdP&>4Ys1DNtFyX$o4orQcK+k3wNjhu?0V`r5^%vK^h>i%y- zpIKE9NnXGETYHncHJRHyt?MVig-1iuc9=!JHL`FBP7ccJ`&IRoo9&M_-{QrkRM z!jT5r>~BPCKWQ2kJzDafJf=7Td;qN0LHUT0uM)hq5< z)@qIQiQ4r!ehV1&b9trN>hy@r@S|yYy5!{+#s)S<3X3G7lVj(Fd(!*3nt(r*FCL!> zvtLdL)lwC_{C4qFHjwd~>c%`|E>j7^uxv0Zwu9 zedb%OcFnui>~Gxs!{IC~K!1N_dDQse|6}U98?>>0)&f!>x zW79E?y`ng_>`f}lcI;!7nPX-hnH?lKb{V05@9w?ddw=KQ59d6Nk25~c_v`f>ulGkX zg-fQ%e0&zxDGKEz1E{j`h9-MBw@qU zr*NTFKdOJgMeP0k95H?6)FcQO8&1VNf~$z7h$+(at27ghC_0l1r($1Qb9(6F7NX`H zA?LZ?@=$b0JBPG2p3!BUd$PYFdpp>gdOD7BsgC%nF>(W$*v+eG}J#Pkk^7Is<3cuoE0#q|@qz9fGtZyTg-f}s6OmQmKE8ax=e2*t zLo8_qLR~dup#D5tQ7UZ+6FHCa+hloL#t`;sAO&5Chkw{4?H~fkmV*F-Mv;`!`9U{dj!)zS|32VAzf+@myo>1#Hdn`;e5n@k&|z%)&|EY1OMgT&>p+BC|CXs zqavT-JrobO;TI^}P|AJBa=}zhw$|n?e1&fh$}aNZSDzz!4Qq*<@KzO@qn2C42u;$<*Q-7w4$`V8IPWtW3 zH_E!K&52bX=^?L++R@gJk%eCKtpCNC$dBxjZyDnM1=_P4e5l~F1Hbi(dK$Z|=lHC8 za4%&-M$1OZSq@-oQ<^+%y%GtT$lo4F6!ngmsxC9qA{n5Gp0t4wN2G7ct0X; z-whjZ3?U&XboSyW?b3$hl6nignk8Zb8u@lj(Jy}T?EtzFa;-^t}OH`r!fQ10n( z(n}EPkubA^3*EJgpAey}6VkLRND&Ws)LVPmwBJpZegD_y!dU#^RCAA0_t`-;G@5kq zf|OvtOr859Ba=NGt8q$mgymHA^OJ7uH&N{L{RupqCWvCX@*=vI9~zu49^ z-3t~?H(dW*+HhANLTo#=!h$+B5qv0!xI|oeaNCuNL4eSY2AR?wvYIjN?&Itf^%>q0 zm##xZeJCf4C>V5Z;>!>p7Z&Ve69dYFwL_=Mwz+ZIE)h_5*CwcSx!0(^E|+}Ypf)&B zVAvsOHJ-7SyME6mT~)J>)(U)c1rx)%<-RvNHqiV6X`T@~m`>et2(9@=T#o1}J;0vq znJS($Y9nP*YA9a-AZZk6TN*9v|D+mZCfrDSNbyET$W83Yk6WerrB@ToaQ=Rl*bnmj z%QbyV;34pgs!@7^)g&g4)v#;O-;Go=N^k090`BrUjuRZHUF6nDGO*e4k{u0P|8$M` zJ@T12)-8AA!?!`Qmg#N_o{03}!RDt)P5g(!_|-s;1x;Bi3zA2kuH|LFfp~bH{Q8OM z;%QD}q&PBEFw{30y2^-OEhDUC!&}9$rE*>8Ps=MT9+PAwPz1Ny?Jn^g^ule-U5dV$ z+=g~~w_=CxH|aaL$+JP{SpEUxsdWh%7Sz3e->GfI$Ks1SkSfHRk(E#^-8!(_dO|QvG(+{ z2cFI0*Gp#kO66|Xte%JS<0OPN$s-&7`VK}5)A_6#PnTI~SKA2Lw0^cC>rmVHcDmPt zW2rYgb>MBY6q;Pde*Gz7&>ZVy8ocj2LQ6F?gb#J5OEbyzrjBDhN8~ZiBp1{Utc5Zj znhpQXemXw>MaiM|(AG`NPsjzs@_iOV*+)g7K@rA z)yWDF8#hwUKPM+VSe`Wac0uQ!b9WLZIc&6LpMy^$EuXx4-&1@)i+q^(>($f4l7Wam zL^_vc@=KW|&oO1?NgrL(ORAIGGaHAxn~)s#RP35-n)*QZXT{tpPtA;5(9k*L2)VHi zSJCQ9o@lkQ&t9*atd)t|uUCEeoVI5cP!0@b2ewAC$Duoze_4^=Hi1LRSd@f(W?!>Z zAxFPS85`42+BiJ*Ao7qgJhXAbCMXWlDR;dOYB4U+6wl@XYdR+23^9$6PWk(x4UWTh zu}*Z?S7~*hCmF(#!ClOxed)&$S%QCl-XA{M5$)8%nTT>j09ZmvF+^MbdX+Q;tyg9GK zpRl3X$A)7Y6Ti6+P@+YAKIaypV)fHA%a|)05=#+?>rZ5?>7=E~ngr#_|LO&uj!l56 zGJ>7JMuq4?g@@g8wSm85$n_9DE1^f8*56Si2NzlI1NC1-B{crpD&I zpYd9lvj2ThON zM*Qy#6~#Z`Len>3w~M0b*;2CLGE4ur^NjVe?*S_FYtmj z^roUcmv|=eRCU90PP+ZwWPj|iA0oQGfQBV|^h4Uz^D}vE3cKv-;gw)5Taa^dk%hT1 zXEecVo=3*AV(V<4HR_s}s^zi`L6L~&|%G*|+=-ePM zzR!)U*CcM&u3%MZ_CcFVjg;gt^*41mcImb6e^83#CDWjAp;_*EC64T1&s?2B-|!sR z_m)Ivj}qZYy`j)m)Y`d_9@;f+F71v{OgK4M{|8?Do`{p#6up|T#1#1)y84o^avmnF zh%yyQ90%JGm?0D>8)fTk!lA3=s5uMn)TXKL_B9Zt{GuT2m=adMyfodf8ovhH2_mls z>-nQ&B&&jGSvo3~Y+hvaqvO^F0KwhE`A-vg`tolLrDY0~pqP!gn@mfziwZ8@!mln7 z{i)a`Q9~DCYVI*An^mP;5%izq$s}S_dag0-WwSJQHyziG5O#2^UJB3DUiU@(sb|dErz;q_pY+Ocm+|q6#JDJ@TCf{;0hFlqY zTeMG)xo^Sl=ORz3rdIX%Why1>T|4a*f-N=alF+6wOj>fY(5%h#S#tfq37g2{Z$C>Z z2L90QfQCLJ zHo~v76|`Stb5<9wNS{D<9KYJSA#+4KMDP+d{dYqoI;5bSEtO)j#*r|j|z0S=iJhJSp zvg>!|tA4guPp1!t)EetLj^7V$MRttBP-VvL=lL z*iZ|=e4b4V1BT6wBfaL%SD_&2%%nDrmSHF94`(#vT$#jkKFnT_7d;uNsDbA+xTj~w zq-nQrD9K(7<=j=p^?MJ}QExYGc7r3cYVw@!4|1H*ol-TJ3<1^XmK#@g21NHh7ejy3 zr#t113*T2i5LUuw)%0<;3z7&kcj|#p(J_ehfU@9u9zPYUg#nGUVJ{Tn_lL4Q2GlDz zDN1mTjb33OF!f$z;9PlAlOX5hrPEH5!9=SGiO6Qv<9tEka(n!BBdJ$Yw!nIlBO9W^ zw|W6*%lT#mofB9=aM%IFiwrL)2+HJ&HQqjkVDaK6_?|Npkl_|jS7oU7c&WL z>8zuPF!_|c=&akqz-`6+tZS=2Z%35)5k`*en%JzzFa-Kn<+X&bS8?Z((3BxlxfHt zsb%@5ay-#kmNu~>0dDt_V3+#i07 zaLB=ODpCjj*qFE!-fq`Ej@wReR@u{zeUgFjPT-)YY@iW7AHy^6cEr{9Gh|bmQd3Z0 zevTulWo|c8)gIIg3ub=XbdD!L5izmas61z9c+ch6At6WEx1F&@L1AA%ZcyCp+k~>( zy>q%Z_!C;whL=kQ8VTL8@cL;ZE|eqheXhK^z&8p`DNK=UU4^u+z1UlrvCB8E;`(Kg z9m|dOro&I{E1y_6c1hP3k~rcnE3Y&u+_8%vi>6G;xOiaYnCdO=&eFRffVzCGo#^W? z;uDxK7A=j@5L;I&H9)vm;N&No;yz2UxvB9q877#vdHwj1tQnJRJ0FtcO{HEJ2t4bKV{G_!KJ(olq0U6vNvhZsM7iN&^Gn%LY=7{K3na7BCN1!_W71WE*}C7 zB+Zyhe6A8Si>3StTm1_Gl?MW4sA?g@T63_z!5!lZ#f zb~O~0n`79bx+_yG-r+B6mCLc6*SCbi4(XHU3i_QUWV5t6n!LrU-Op{Lxe^efu>1V| z?2O>^!=OPr&Vf*a-9QWz5Mx4S%c9onRO1ag=#E;1&W``KFp=aO3{9>j?joO6dPyRS zpsNDq*A<-P217wNxZ1VxD}uE87B>2t#pnJo30kdVTg!gd%elKV?LoRRN&C3Dj;P^L z(fE;`U>)HiL#aPBh}8-W{MBepeP-7$ea48V`ov{=5ZRG!lden>3G4W+hwMNq7Q-(2 zfoIQ8lbC&vUv}1uN%srq0FWu(EhV+G-my~~HaJe# z(%ZcKy--dVbyz&xT$#`^5SCq`9CvSX7VTMUbE_g?Uj|iGA+tU(5v@gGO0M>~%*uZ3 zHT_|Q3?-_$-st*{kcP9z{J@F>=3O zg&y|4qC7ODNOrF-4ZQm`Ay&$Bf>q>)w)21vS^p6GbTw?}Iar`QT;fNg&l)Jk$n%u4 z6w`~{%_f&*=VN{;!^|%k-g(cl+q7K9_g72D*uot!Ev1ir(Y?q6v_nqZv}sSDj}-SG zPR_crQm-=OoKGb?13IBIx7&lb%UR$CnWvaePh{?$oTz(F-31d5t}4)xY6J5ILxW@3 zm?D!fo$_H-_Z+%CHDd_7)2@>oNstz+TJ~IsqSVaq>@@xS&n4V4HU2;t9it~?o|ZfL zjBLuR=dk;Mp5`OqX@jBFn9f)vuK;WZ=iw}N3k2*+*%Os56^ zKmiHM6dCAN)bmh+$1iqZ>MhVT?BiIELr3VpeTrV^ype^>Z zYrUwb#?v1CY4*>|fV9Z&9x9N(1OVH4sXv1*{o=lPcF3h4rULLzBO%>M>#JpG4!K#Dw7<@lMOu*>Q$w) z&PVhd;+udjz3|&gr(N*TW(V>)u)O}C#v7bP#Bp+K2T=ezJH>`VUH;JWPWEgMQ($bh6PFj=L4 z7Klh0Z&()UO3P9++5(ns2=}#5jIb}lrU4BT{Df~dGOyV~D8w*IkWbySm?T$*a>pqrmd2I`X1TNglm)0*wfP0KG2ctm`X4Ii{g0+g-^wlf@e znZ`k5Nm9;f_R45yxMs{sT0$vg;n-8uL5g?0I>*<0(td%Y1pW0l^5Z7h0jCltIjPF3Uxt~Xgj8lO^}A!jUC6a4)<-n z59YTmg%3{N;1iMMo60r&mYU9zitYRI7{e%Id!&LmqOj}M5+5RIaED_UUu4{pSMNxI z?K~YNLZ{n%Zyfth(m(&n;*LFu&--HhHBVJq#M5TkuAp9aACfzdJi3!MtS`IBfgMug zxAh`!-!YNocTm2zK@fcLbHH`nSAs3+ldE!SWNq=s^UBHt|H85ck4$*k*gpMQ zto~dr&_Ks(i8-K7;aB^>>5Bbu8P_ktzpO=WI}@7-*Nk~{=Q{-uJAQydQ5#s{Jns9M z_Gopp8yHG}c>&Eb*a_f`FXVICwjp$wvDTSMO`y6F;1KkfUmd$8V-t%UrbNIqrur1| zqnJ)0$?&HQ7jxc_NKmP#r9H92Cj7a?-ZDwwIJK*&j?R3`a?p>~gExd+g_91TY5>+8 zutG=(h6zi*Ari#_L)j9ydkEce@X2!yL58H7yB*); z$|3rqOp4S2R}&B`NU6}*=u{M@llLxg1Fce_*Sj|2eT>nSd&X=&)D#8`Z z&1AdEo(i?8oH`lrCZyOlW*Z|F9J*PqZ|Mt?^lD&Wuo`=K0t11Gg#VcxI~>^UX!BFFUg6M|iRqw!bzlEXDCoc_(+MH_nMEh6XxmDEt zwDF#mi|~3BRZSkDQk!k&DPct#x*C_1-pw7N)$!!B&~aNI;&teRjvaRcVZu6o3JAMJ zUW0EIAul%k1Mb;+6yC0^{rqI_?#1J>QJYtJy}?KE3A$YIeR@9c#;lty-PC+< z$2S6}Z?~UMt#Ko?Ft7=$)=&467p16D$cv;K1>h*c|DQ31d#|wW`poFMPO(0jw}J zWrn>|JPr|JeblMsTC5YfVTkN-<6q`j^PLmf`*8rV_$LcM>KDi1X(RO%2CrnRNuYcm zy}{KI2l|$Hk?{BOs5PfWArDHz0uc5GX^#M{1iTHb*)YF$&@_^-6`sb!S9tKN+ymKu}Yz|eTKAtD{X_-9h@ z!OGS_(4)O4D3XjC%2cx8Fgfn>ziqq(Mi1N_?gyav);5vEc5|N_VfM3%c#LDC6x1Jy z=I&4`%?FJ!$6`)jkzlB|7xBq0(r)Ekj4Z*wsbgB5DRK)1W6UD|BUP2+2pj#EkfQ+J z#u)8UHQWwZgu8u9hh5fL#w~Xzr=Mqd|9)^_vzA#tmI{e|wb7x6csdr;JWX$kG!gvJ zICKpoGLML0YBzsrCMuuhZ46aA_fm%cx-@(k(FC_UvvEj_Lw10L;Q;54Em`K|1QU7j z`An_~t}YQ=ukJJ%6qzmVvC7^ARr;!wUoj(-soEUS79c4J54d^+88kFway6r(15DZd zbSI*d>ud@;*7P1tR5uzdos}(+NCNX$lm};J`_#5hN(R89^8kChDC*&VO?stQ|Ld9k z2SvSoEBrD?os*e_!rzT-D&@Xm;bmo8r^EA3o;FX=9yP;Pz!K4Lmj^71g`-5da?|To zo+V2k9{H2+JuewB#;{P=#Jrxd{Uw*FZ~2ENEY;DT6hbdHm{T|My#Mb(3ngF6KiObh z{M>I7HRk%n5c|PNc2OVo{!L{unS8DSJopi@3T8zL=;pwQDa7Ae%hpT%Fspw(TglDP z2k#{N*MtI;)kx+Kpr62S)@^oM5ZeBM#t#>W)hhetc70(*tw}JayM52nJGP?nT#xdQ z?h}sHyS ztj0abP~Q927|G8R85DWwl8a~cU-{X>$io!bT328RRsvi3Tuf zC6VM7`pCUt*~L&uvt=6{;t9;XJ3Jb1nay(A5eOf`4%G(3iZmu%FvLEurZhGt z0CFEQ2Q=E65p>|{T&?Hj8~ZEfEpOw;zT4g9*WeuAl)sJUfZ>Q)%Z!-br> zH)orbiVauzT))=_F%r{icqSyuGuUw_cet8(Q=*8$YuTp{u^&{4Wx0tEF5R4g)8nJf zZgcUSPn?7PlQaR9D|-rYmw^PyVywPrXEt={einKlxVbvwcv@@USL-xDJSf9D z+3xZroO`S;iOyuk33O0ZS464IbK%TIF7D+JRk{83+x8=Hun#;}YF{ej-mB?7Jlv zzJFgiD{F;?+81`Q7e7QtGBU*=d@M-23-DICfza>{71ZJz*u_-nMZZkELJ)&?=M}dv zjsF<*t$F{i29{PR!gi{Wmei+8VJlr-Un;X$7`AOxws1u?i|4yn z2BsL+5#2D=bkv)Zip^!yA46=PqZUGFOk@SlW-9H*5*9PfsnMkfvP3D!bm?$`%==PwDAAim0 z`r;_Nc&9vr<6!%T_2kT2?V!3_7P%fr12s6;(HwlvgQ51e&37>8Y|<$)oeje`8O%7ZdpxD$`OPcXp)yKA(2;)RY6966;Cle)n{tp&y|0^2{Yu3wusTAy0#?s< zQDs~^t+ibH4mK@g&xb${NQYftBAL8Z;7age3|y=uX{w%6eEt$nK(kM*{BXF!0{lKJ z_^?q32+|QM4nGlOtNr^q6)bG`>8qG=F0$*hB4oP)ep>)7YcP}s_9=)P*|rFNmLSYf zWl;RZtIRquA%NJNSJd?ub>UvW+JY@`kNd@#N`gUKN(ai-xaY#hXH6AT+#V_}NlUiT zIa3n&AffsUax;%Tch)P}5?HO-%A+X+|G?tbB~&L+V^#PHre9dhaTELX(pA+^8R;?F z`n|S-3_g7s`lHc43Zk7#-o*~jrb_JgUhTEMDA@m0qPui(a?ti4x8uk0|1&!*yk8r9 z7^8A{}3~dM)?Qn_#HZX&tf{ey2!ON5ffTmUwb7MYD&v4 zN@ae)lQ+@+97R4$>S)*yp>edFot4;m@ALZ;)f!Xr%FXrY__isWfcD|za>6yno@Azf z1!p!V*7+}(nOFP3fR3aJr6KK_Z#i2CKg=y>`7>T(Cndj8+$zqNt8zVlcF21$EyKn( zKs**+5vO8|L7)vtHbM*ypN%&A!e(yq+ZI9`KV2stXj)8i;;x_-4V4fyajeOn+?D5E z%kDGa?K4-f+P{#zvg?60)4j+1k}q1BuJI+Z?0j=F{88KAMs5 zZp3;PxPP}R^Kt+$5Zb96=H$C~muL7Z(elqluUE#g+Bs7{?0HflT->;C3rm|bqp&Y> zPNW-@AZQaG7eL59=G^wMJ`OW+R2KvhoN)%ITEOzP=S6ik`yG!odnAsRn+jblQ+?l+ zrt{&!mTF=i?^YRhegVoD$x&rEbdJ;*xm4Gm(_kNkm%rd!+^Y)2kWQ#c)eP-S?hx^1 z5NtMMV>H!NbY1ZpDuV?#{bM5TazLyxwb$Orep$%?25{ZT7!7Kfj#`jL1A1z%ay)qN zWmTmou86Z|w;LImGQEFSR7VU0>GEb8C~4;0eiWAL91);I0U5!#MZvAWcBgOtk2q+9NokM8$QMx34fvay)50EVpfu2Qr*!Qu#zSaak;X4 z_!hcK#lPI&x76P3uV|9f+y=J`ByRskQUPf(Ugb~3sEynPyX``Sj3(J{K=C;E5=>9K zH2bKV7>CI;Z?ZN77KU0{TKxpJ@&-DU_p=d@aYRb<*{*~qgd=l3ZPGysCsHh*KlIFD z)5I{a3Q-sh+lU-a+`ve5Yt2?e2DyE&s;iX<Smosi+F6m`Ba(hMej&P569)dUi~z^%)xg*gUmOf3&0+skP_M~^o!aX z=BBVyF7{#P6LRj(zv0xPNE5QBKjnwIplquy7OldQw0H1KCeJHYaPddZipbt3@)?kF-BTPkshBcP*y03RZi&wG{ZX%4v+J1DDUwOQ%cH*5h$;H75$W^# z{|Q8>LB_+TUxGG>2V>E|DIti&51w{(e_C(89lG+W>*JMWy0ApBo&wdzo4kDL9*<`& zQ64Aa_L&J-`WXOFz%q5^u9&*y_9m!w9b8uh7>r}P*ckLpYLh+fW1C7$f6ldS_RkFS z(@ksO_>BT+s>OO`qp@!bKNcou@6PDkOVCGFgM*p!>l2us0kBVa?dzv(sl?5%7fns!PT`l8wW9E<;rpXL<@EQ_JWTqDtJ z44x;Knbv%_y}d{PX6&gDDDS4T!7%5Sts5zN>YWy{R{7A?sID&=1iORM!%R)5?vlnx z%F2%52eFB1a2AFACk^Yt7+PLo#@1c{s-$}-qH4#|FzMIR>E833>))`0y?hD!IWE5- zAupRp&D!>)#*C~K+11~ z)7J;}R_rF;oOvKR*`ybt*NW8xFA>6Jwj=DP)c zxI@&Vf?7)dmjket|Eljyk)Ss7`uvp95Vg_f5`9Z?V5WAVZ_vVQP>IG7XXM(Hxjska z3VKn$gqGXjT$^7g1LoV&!dy&d1q%p&u@|v0hk|98Bw`{b+M-pzN-b*@Ykczfg~4RD zH;_!-maFIKYb0iYK+}G664XPVdowp%PSYreYAc$q}{;^i(ur@ z$-pi^H9OzT5@VCSPu8-{-32xx$>2+J(JWcij99mQh)E9&X9O##dy61Famtj_1B)@h;7GNB{g(&f?B=Gf?aC*YG$&T^65B z@D73>znL|Cp_sx+@lJi*^n+Y^V+E9h+6iYj4LLXsQk0mvt4QPdU-R`%0 z*6=a+V9%4Rf!SAL>q*nR@D)fU=xAjrGz=lf3BWZY{30&No43A&e$nNaaawzvUCJ^O z%WAp#eQ>tatUE6I`@^BxagOYG_c)FxgU48VB#O_S(X%eeg#_v?iY0c_EnMfWT=Q)sl%OKb z$@Gsc!B#3QOE==gdE{W`mvLn&-oT*=aT`B;2e*qSgFAH2+qJKfy&hRN0j5S0>cTMo zpmj{Jd13d$IlClF=0$HR~ex(T^X0jq1b4Z!uyz zO9(4RCQrDIGQJ{S$_!`T`g)0n69;5|E?yj|{?}-Yda=BdfTpPDrz}_!JKsIJ*w3dj z`vGd7d>_qre(SPMS5YW7SYqd2K3fW|F*Iyjp22!B;?J=@7(Suza9qn_Tgl6h&@29T zHB`Q=Ba^-fHOORoO;5}FZbAN84H;JO`=Nc)L0eO4dVpAdsh|jCqLoQD&~f35-R_3u1Q9jl~$R`(8Y}uvU=!mSufFNw$`F$Ewd^Ck#m?i=qughasf>gXs|;uaDce0P?Pon&t_u~odLl#`f>-;Qx%7!#-v_ZV(kR6V~%P7 zC{tM=^fV4^8A0e*a(wS(v>|^&5=D%?Lw8d(9(b1FQ2SCJTSYhnf9 ze|HTO!{graBn8=P<;b*rIh$j%rqrC(?>dHC%~EaZ z&h$Yx@H*>=w0%7wSJwoVxL0?06$ENv-4YLgH2X2Yjg_qBZeBQA45b?WaU)}OiOJrS z-s5{-(D<%jgG)GL2RAxZNPwbQBDAhmHwJ5y{+#0p2y;WNel&J{VZ;yj$UH?yx`~Z` z1pntPY^Q2sn6vJKvzX&T7oki_0#&nhw-}H9!be5|%Ia$-=&AomnZ|4Z>_5(?zuo_b z<{QI08yhe#kW(10*$46(ya%)?Vkp1`VOFbjnA4zyMm-R86BWx(kUy@u{u$_%K)8k1 zINsTsOmBQRvgv+aMk-Upd#%EkgALQbVf{5&Pf}Y~m+P9KK6RQ&AE7c%rHyY1Cx?b2 zkBIu>fVtY4mPxdHi=a9z>zKbZ@EcK-*5p&T;RYAipFXO_|7=>z&I;;OL$n>&-I>{G zR+>^c*B9()xAS3*@M)F$H4bEd=ACL~7PD?o|Cuh?DdE_z%fatUW3q#FXJtSc4@&9< zj3NfkJ^APJnlD@+J`Uu)%|OTnz0vjYm-W~xPrz9=G|*Y8;(&Y^3(q?~Z#{mCKM;Ov zdVwZR8%U)?>l6dOjT1IX258G6z8M={9rO@~+M1<<0>-wN59#e*o){XD)N*n$gMV$s6Y~XBXUOI}NBtwbLBu}pWkP`LRce;kZ z2U=tyhB2G;xZP<<_wfQ3i9oR(ewsCZ)ntalCp z=;ia29SLT?r8;Wm4-U(#@v3RVAha+e_|-QzbgU@U8`%MbPmUaJ8E|2n85I4K{Mo+! z`o5)O^o{k5R!N_{-J*(l($SBelv*EjE5{Q|;Vc_B;2lu1Duo)m?&)5*I;?{#n6Im9kCak3b^d`a)Qgxy>=X% zte)unB|jCHpRzj5HkDB-*L3o?syUv*n!Ut5_DU zi5o-gS>uJ$^5&eop?N+d`l)JPyfT4JsqQQWN}yz1|A`;sY}_onMNG4j$X+4x86cd) z|IQVRxZnL>jHlHmD+3bv#$d^-yoxyzWXde%j!iG(0^v#zO|r=ovc2`0qkwiIj5+oK zV-_HotryB$Tlj5Ga__??NdG>-JhX6~1j?aT;1)(@lIz-LgW*i<6GAT0xvMVQ1oMbm zXX}!XGo4Ta-H#Uj2Ho!wdi;@w1e_692Z$b|N6&m&N2iW?R*VCANRg>iC4>C?q|~;(nJ|m(`R!f=9LK%@C0!(4-|Qo8GA-wtll#BM7* zuX$#{t(qV1`^-XHkm0hpFJ|G(!ipXh&2?*eQIZ1X3-gxh`asQx{Yu_@tyl~rj|}k; zIC{59$kw{}JJH2>ZgGj3mLb=D@~Zb0H3kJ@q4FQ-`)|+eWIhF3lwC-!>$gzn7qL%7 z*BH0dO)I!ertITgz2R>i+e4UGR9#jH4iGCcsZE`{f zBj0g)0F(;}hKb4(y1HGzbv%t``mce&BU)VRw&LaIQ$M@`t>iGJb&g}Gvd;Q6|1wGkd^T&^0Ztn zh0re!eY3UM14{S}5$9L85k*k@xD`+?TW+9_lHlFiTtg$#LW4@`^`%{(G)}mWk+)Ge zH4yX{*ljela=aXq6KvV48F!990a0g@yRx?y_8Qpq#a$9OAfi$A=NGVicF>aB2D=>` z5RBxtTz03yDefj_ZCIgxByNzITuXdAyCY{%ulFul;MZ|=?X{(g`eS;?#9PzCOnfb3 z4e^7>n;O4!c~hYR@$+7)fb_|!Cb*T$96V{B*XX8OU2T#Q+0!gQ<54`zfh%3dLJ3Q+fIjQ{*>V>9E(w}Yp{~Lft(*^zDZ3ui=@;62hM7Mv z{499#Pw2E=aOFKI%Et4bDZ*gpQ(#mEyp#cG`duG@q9!A6vo<-hJ+LX*c*!MPHKk4;j?ADB4Kvv5i0KJ|5 zdrfL0_LU(O21}kY7NH%E=)-GcNVBmIkdYQRf>(LUVU*7b|GuC&%R zHsP~Tu)r3=xtpV@J@=+OZwHOBTE8uHi^Cuj?}^AbaXzt7Ni|zFMCRsuLlz(RD!%{n z1CHy5K}`lLK1n9*G0fB^pi7~{FJs8tBnv$KAAenVo$U3-IB>W^#zM5mxqG#l&0gw< zXHA@T$0;(m)HZf~P|4&jkI7v-zjwK7@-P4?HlpNcjtlDPmjjwxihkm(J;W@L~F7#y~xG=gg8?$J5u&K!ghvA z1|Do=3*Vw9Z+Bl90Gf*)GFO?Dtw`rri(tO!hL(6p;?8;6LBV72DA z?v&Rwl72L~f_!h&l4G-ZMdi%6sDE(gPpci@Rs(CM206r7S15=V~`?+wdns#bQ zs#DZuh8AC?gM%M`^`A~(+gJK?vG)g+L1w$z(KkNC^N_%(KR#rK<7@U+=3oC*2YF5w z=6sKcm;T*VvFqNnkTkRLz3Kqh*_H_+??UL*BZJJpFYH-UHTY-6EzgIjsH69O{M%&z z=HuD=KX6s%>EpX++QvOACrx*qG$sV0fm?#r_&b=xIb_6a+Ir9+PT$>W9~HEW%7)vO zjuMCB?-OUbjE=Ko4>||iG%B#=OnaWF_eU!d@d2j%L-XrhdNc8S&kycLY{~Q6w$0wi zS2B={hgZb3l=apNxJ|4?ev97VdZ46gCMtmm0GbP!shBOpTN3qu$zAoUFrF2eQQ8uK zU&OU2?3&t9&pMfafO{qx4V8N$ft|OtoYjexpCUt#b9@J*#J;5NK;XygG zT?l?_fG0jT6x!I3*8ZL;mc$_i6_s!w zj~XCzjmTk41=k9$@e^`RZSql`m=0NY=)OBhSIAMdI(2yJ*F%dPRym-KsNz61Ck2(0l%v^1OhjUoe$Uoxg1hgQIP9fvbMFR z*XQ2J{!jsAP1CWv6`ktbovB#D0<;#(t?$74+nwxNqAx!TgRhvQF0>c0c;otk%SY_B)?4=138A5qd0D3IH_ z@Ns|6idsbg)qGxdF}iOF2>Pv=8kh?P9s{W4U(M;ak(gh4#bGXUz(4<+$rc$Jd)%HFZ|2Z@{=#KGvjL?9 zGqn)asuW?^PHTll7P3QfK*_L{25FQ?j3Y)2m@;l63Awo#+kn}YuR zhP#n0|FUV8>+0jZ*Ro3OdJmGKzK1}MzB#KgHT_4^^m1S^==o0<>3nl5zTcb+H#;#J z`D@yIc|-KIVV(a+(|2RFMBdAFmeI$98oJl*uCVrjLJ_Y&U5|9`7Qo0`NJzPro&+?3 z>w@b|DO+}Y1?asj+eb{=`|K1k>v%LU8J&G*5e(wig}nyCg*(A$^TkwUvMF)pQ*r$u zt)Kauy{aD)VQ=?d+l%q$=6oPb!*-4|R%@Y44kytvS-^I8WhL$gKbZ zZb$Fn-TGW^oThY%-7F!G7D>iU5dXybV{ZeJ2NVoEt=NyPEy?|EWbOfJ)yR_5v=HCx z=TZg=LTf;EqvMwPV11?DkYAv=-7|0Q)2(x^2c+t1JQ(LHGbSm(BF|tYUw6@J#U}2+ zq@&SO8`YRj=Com8Ah-~vv`XpCn<;f<9RgsFk?7@9ZHII8;kAAa*=layUCg`;pDjjB zUyv_4qAtW6yCfbgAR@*$zE@J&S!%Dp3cqC48alS6Lqnp;X5p!G{~C-M2AdVW3QsG; z?FW{#OD=l%IY`T*4yQJ|Q$qKyCWKd?)9mwRayNfDxATkAZ}@_oDAW?n!=^YOAaoh8 zSyp=`0P;3LHn$4;u>f`XZOg0D^oF}UpUXUPUc`!I2$9)Wno04@P|{x6v3Ne{Cz*}a z4|EbXLMMhnGz(h;pTe8c3@U*%HZUB(6a*+rj#=IoWWf$5)0Edyx|?sh>;~y5jnz4+ zzMmQu^=Oi#su^XBMZrABW{o?tzT^F^MS9c<&zZkoIgg**vS*3|rH&{H7;ZV-xD;?y zXLesz<-hX_u?2TrA_fwEO9pK5T)PJ?J`GU{qxe91J5t~-r9ra(?Y=O~UPZg6$c)RAy& znVqfrz<4FILCrn7`31tuz*H;#bk$fqrDpJ8&$lg&wobz!<{G`JvQjO?>Uy=aV#8Im}D_}oerpS&WP z(o46(`*8CBZorlvQ{?q*m!S_9$1!#N$=pq!7vXfIz3S=Qb%Ccy{hq^?l9&*7 zbxC2q*~-8+1g^{_fL5;4p-ot^UgxeZx0d1T?D(~weNo9HbynvE{-GJhtU=MW@F({=tQTRR)x1 zAhIBPrQg0f3Y*XU4Ovau%lXpt~fE4> z*bl_#_aaxYa5eQYw?_`miV8vpkDF}gO^f_|9=f7F^UPeQ7af126@!RmaveKr2>*LD zOQD%p>grlePFpO6$*=7Dyd)U4+TFo`y8dAKS5l- zqWK4y`?!hA%Nqt~FH`BqY3GP;5=;wDG0SavoT-f_U0~c<`h_az!2!2NCHhfO$32?n zBh>HU9yz)eot*O0J6`eJ&C<>(!!t!pX5~r`zB=EGSLgVKjN4UI7D4Gheu>0s<>w7d z`99-h5W%8-qT3_Kj>?;S8-Pw3sdA>S8Fs`{=glcj7oqvOIRX{i(O zopYHc)v+)T{cYR+J;e}4`;KvL>+<1tN1$eLji0Q{ziz<+wjW$H|K57slbmUqnH5%x zG*qttA5U)q)%5@UkJ}(92qGPdbV@fU!j$gr&e4npQ4tXa(p`=Q>6DaaqY;S_3XBdJ z5+nalKkx7Fzq7-6ZLsaI^St*y?&I;e&!>_5gNE()uZI28kWhyDCg*t_LW5Mpz2%$p z5nBS6A^DPWpXO^O;H%@6oe0f1;a6Jvkzqr&GHI4`>KDq*4k8BLr->t`uiq~RV?3uG zq^det;<=n%25Y>>yu#MqR3ve&zT;Q;vB^l2Xik4Hy08MDbMS$kvoVJ#{bKlmQ2C?K zV;;1PL)*`#qp$+XvuwuR-kHh`=rsI>nMy>d1E28amF)o4*|$amt5~llYzhz04_dL^ zN|ROO&F@1$ADhw1@VeI@ac0vtk^e@!kTt%b{n~)$31W8_BL9*+0CQ_m~ z+fUj*Xw;(ZZivcGuC)>&n6qu3Yju1ALv(zFF8Qy180x3|FdF(JK!K-77S;;V*la)5 zeO)?~y(;DUsywDft>9neNqzj))K|j#h3oUj>VPtFM3ilyx=ra^UpM2<^R`~yrd~4! z@9Scwl$JCOxrctG!?p&jmlEXAMGje4uGuylbLsX3X%&jX1t${d(3793RN~J5iLygX z>=mb-rRO9+X3Ju91Y9+v(kXES1k4!xZG!NyJ4`!nIemFE)a4D6(Z9HR zSC3*s#Pj!o^0F#D>XqGlBj-BUHjE}=#0Wt;5w(i9v`Tk95TUOsH>bczzD9F<_(7p9 z*IyGVt`5}V$QXYCZybV58yCBS%@FE`IeoUGzFmH|MEO~ojYn|1n3u0v>Og)z2-zyvat&NyTF|=*QkH5xi_znd5voZVOPl}S}$8Mh*!>#Px zttZ(93C{g0ACm! zN;YjfIrF&Byjf?B`Ip7aqSs=@J@P-UJ^T_Y{%3dt%dOTq>96G77N49oK4m^H*P~x# zOA4iBxL*PywuPCaY8vK;81wq{{9^6;{q(_PT7@A@njaL%Nx2_XpKzQ{8De z6G!e%3`li-EVZJ!E&U|5F#YR`)5N|$<_Rd~i6Wm`a>itUCazlKwob3&#$^=i zXCvrpITQO5bGwuW0_L43ad8RK!P<(fGW^y@&hg>$Q5OjbG|VrBcr+v>IQT$e zw%$fasF=pxW{qF}LKR|6jk3-b z8MxVIgIwMm{e2qh;_~qOasA7WTU1n3>`^X{Y-z%hHlm`U%)SdHoeoM^noGZuW2UZ0 z(PIv(@l9F#FJ2>dP6JHV-DLHD9*R;(x;5X!euq-{fyV2F_#I}Kodvo z5mb|Gv`O}<0@@(~w-h5tfMwOpQ2*-Ur_KrcRHb6PVaO>LD6LdEPwC_5;y! zlx=$eVucU+N_o5V? z??gM0oxH)Xa=l-|Rd4dIOe*?0-{B#n*lw*yopmZQc4ToL7a39C9=0bVrPu>CwyCI_ z)cyE|b9@lxBHJJRHVC`d$#SU6Zi7iVA^EeP_S==6YS3hmJD|FmcW=(Gglcq*?~#_Nn!A9!{j6XM}@?Ay`rZ>{}fcdAu! zKfbDy5@EK-QMD|osNti8jp?x6CZQz*C@AfRzL&VVJZ`fkc(^nY2ww^Rd zs&M}>b}#SNPg*hEH7C4;AHhd&4ur!OVdXB`!Hmc(3UNWrgWL_;`JBM4noVc2efM|R zeXJ1q4A00%P9bs@hLI^>$dO$u))4t5o0n+!aiXi!z|jr&>F6))OTA516%-a1i}G{P zGwc^1(f+U2{|r}l#(Zd++KoS28t=ZgNGB6RxAgP2Z^g%hc5P{z6$U|*equCFFaWkg znHm(=o`!}yCm*t}9j7CBco^2DbC|sU7o?Ehis;&B5{xv_VBvw=BG&~J^L9d6APx5- z(SfnIM_DATov@@#+jJ=qzGg-(9*Bk+oZHS-_N)~uV?}}`?BVB37)gG| zksPLqJ;mg9sk{(s3Z20-PTgE4!0=7jm*dmz*3Vm)flPrZhRw$GJhEV(IU>Ng=PNHV zLkC|g(gn;p9KRkgCrx(z)+(_>Umkb3R|!g_m6y)CTlh}3GHzf?rSNN?kOi}QwW%Ig zL+x2&4iY2>4~H{HgCk+IO)6Ftd`?_YGl!S{+!SF46h@4aw{M+?#YfG6h}Ye?TEx?F z=v&)+$6-f3uQ}^G^I~`sd{IyA1Fq1?QojcKPbMt{pT2d}%1|+}dPOz#8sU&9T~q%E zwN1Tr8lZr4R-E6XorE#O+4_{U+I_OAR|vq3{-#9CDAXuF>qr2nRBTEkN-L7b#*gd~ z@$JODwwNmZ$+cGi6ZZe5Y#LD%&|U4p#7-Rar$G2T6 zm*_cH9nd!6WeqR=Bn`M&C-z$eS@TX8@aCRYROr$l&q^r^XSQ^Cc{rKzf^X6hvmewP zUJUX4Ha4ftRb%MaVwO>J?F!mlrb(|h(4P8S#lu;KK|3PhRi5P00F0r=BukTivBpF< z^4;H{+^%D2ve43|$ydprY`pBP88_<(q>iZFvE}t9^fdvZ;D~zMll%mw+^(B2VmlfY z`{PP^KLyw>M{~Fuk9wm-pCYqytHeeskpQ&GcDURXO zMLy{xgWLM+D-6S9P&k37UcN;539oV_Z9jfAQ~oN!;a%p@f&U9SKJ1Ut5KI$MG)tbA zQjYV^)}?=_wIf+7IczUc!CG&^s;Zt(sx4-)IzmKeTR2>IARB(rNg&f;63jD&yoE^R z?mWrW&ql&C+4@+x^UAd^uM?}N38l%`qvJ%-!#P;obA1P@hTN0b9S`)gsU>2q9X#Z+ z*(VzS*Mo~CSKkvwLX&&yQHx%KOJf$N{H$Jvy?-sxHt)bdS(&am5*m zNG)FTJE(#H%Wgne%coO(UYQuPP*o0*HoxooCTAtGAp`Q))1@yhd`0!vjlpbQC+hmY z!^eB)*Dk6ee$Xk*U(g>SP{RG z;=N|MQ z_@{4^)bQ@!X zT%-1DBuS=e^PKGL7ITVR7UFRa^j?1kK%J=BvcS!QRGP%Nz!{La4XWoysaI-1Hn&e= zSg@XKvdA&Iq|fVGw+`m&uV3r^zxG_!d~&8R@bz84voi4jfZZ{g5i5<>@jx%t*(n$KC_m)nyJ(=&uW1i!gpw<@rZEgB=X!2Sf@5qXiWc=y&T*0|q zcLp=&Qv-YUKyKGcWhcY{R{eKJo#zKPQf;pKf!%a{(yM5?n)Jl%mHB9)v<4zC)*E|Q zA4Fc8nK^H5-Gz9bJ{M`19E9dgg^ZQdJgqb1HT3TMAzCnBKRWm!lkvv3aOv=|O?tCD z8=US#0QGHQju?hQtV;+P!x|*lfK-eg0SVoU$?jWw%dtnyImZbVUy=({Jf)DZvRd1H zYncjqT7VtfcxB#1o{2&ff0pY?J0&a*_T{rrXWeqH*_`7|ZK%no#TLE;JCrhC*67=& z>)2I~opYHjhpe=@fd>*|3l9?YGuyN4kZapTkv0FCW1biV-5qg^K()rNTTN;v_RTF% zHZ7~i0`;(pYK~;SHDhI3^doH9HF?|aHz^(NdsygOWMajHINT-O1poN9^@<|=T=gwl zSK1*S#;Syzb4FYOZ)q6_ONPcLk!l{cQ=Hkvw+QX^y(OuRJ!Qiqy9j7BFSpDpwyI*SQkW4Ku8- zirNo+y^tv-ukPRdeN{j7PSvh(yRnqXhRF`MEYw-c82wF!5qMQz zwFBDNFrsDnYHIy4A_C%>nvw2c=Q^>|95N%8+m%t-*`S4Mye45CnAJZ;x_{{4zJCX~ z26ivR4QLDVbR3qF^MlR$aGiD_25EJDAD>+}{14|^#EaSf*OUeil_}bMs~4DDU!gd^ z#(+=P_Sr+cdn-uP>!k90DIg4cvSpe22nt=WYTmwHfaD$4W2>-9{TJFlE}zV0`pigi zi&b(GBUV=D>(k2wo?_&77;NXM3gW3CHL`wxBfAcIe_X1Hr19RK%**zfWeoZf&NbHyL#DFp))xm2?dFM6MDHW?<0Jb|a0dRI$FsFi z(uG&mU}2<9($QhuO=&GI0hGNosW_Jw{nR6r!p4%V-_nK4v|4^}es+_U0Dth|won>m zQ_9k3y;9(iJ}%b1=ztXge)fVx;n1A z?K=4~h>wB(wzH}ErQhGyJ9xXlKf}2Ok}qu}u@kC|#6PO3S4Z@@zfzIx%oTW2`;b-(o-beY+-rAnOy$^DC3 zQMPZ-TOocc34PQKd#&R?FP1t?5R#5CwWYL7XRoD{+oZ3y$uU*PT?JDopFvgOG=+lr z#ClZ2Cye!_A{uk+m+Z#KyXpn2@oa@^)Ak)wwit$Ksar@Z@PAsx84y+~_?0DJ;H?wT z4L?gmuh5IA(@(($m!33-t1M+nnH>o^dk(_hKiaJfi1YYHm)m8V#`Du1A|T;)qG-nZ z4r!N5n>?L*4s)3J*Ij0|uzRiF<5d29B$79riqKk9wObz*>-Ii;zvBVUp=__u?7RBG z7im^|H%6u*fG7p;j~R5UpgksttBAj%BH8K8Urgup3(v?Y>C@4-@u}+TO(&_zg38wzBw-PJ-<2A`?MYf?h>-$?YmpdpREFJ z{h@&FkxW{qeo64ZQwd*Pc+zHM^FNZ+nwCD*O8Du&+wxQgdFe25IL;de_ys%4%yZ3< zNTGhMxKN=X`%BOj$s|NgKPr}-*?=^NDl@Ea*?br~Uq10WH*?sEjGOo-OAiUMG!Kpw zYnH`Hj{hvYtmm4}J(cRR?-e45*g6EP>{F(*Lr|wuA;3-HlCt`H)e$i`WO^l>JuJ=SLSSz@9bBSst5NdRNXv>^!W!h5 zV5yb|+EfcqYKQ?P5t=ZO~^;87LY33I#HEyBJQZy`Xqm*a8U2=dCqb(`2B#jr!01NjS0V%;RZrUr^6I~9 zd7KEXk6qUGgXYequf6eJ^2oFnq=?`YCiU6n#nv%}9LWx(z{`NS=v!W`yQgG1?Ye3~ zA>|NYgaD}@tFvbHA~6v08NV%7sQ=+oOW*?a3bzKkd(CC6^;U1WGTL64Ek+$@TcoD@c=vfP#+a@+0^VO_!Gm5Ft=nJV2zyqGTnc1^E@_>Hzire=edM+ZP z3@2V`bjy*TLZ>u@KMKxj&%Ta{btS`381V&sxqhx87wgu@eL5bRbz5SUaObosnxPoy z)7hIfyRmM&Jyqjg7IQY?TS_#xRCbW1%8#6{7?|@4bxr%^#KsHTI!fPB<9KaN?=^8Y2==l zK!L_DV??o$x2iMQwDWy_K<(5*LTjQ{?+s*aYSE{E73b7E3z+XXXVN17^}TIDZZOk9 zu;JEZ-jBa8anud@^d*C_?)q~uXIttamQtS1<3LdTk_xeAA_H9wG4CHGv1g;5lbt#V zJQ12oXa8Wk!4XI*DZ-s4g>nXz4wC{J!dCjG!f7NP!BLf)scdJ|R1Si#?hmfnP_@TG z1iomPXX~uJMucJg+=cTH;x)`u&xOiV|2(hcy3qv+uM@d z**&b3L9f4)6OlouW?drfn^kZv=95%VK|8$3?yvxuI;OTL;bZ;UEge|oYmr%d)yQv# zv-8kNvpTl3*?}r0oS^lU4|{fU*>~&Hgvz&*Y_<4R`ySUG=H2s>402q5#==pBc`yZO zc54=>Yv(oazU+g=+X!=H$A`*1eDe1;B9(^Ae&9^%h2<+)KQViD9{afLgg4rCa)ymL zibL^i@BeuL7D*CGMJjG2P4ln{5e$A(biU@C#)HmYaVpc02J#Cae6uvALl}=soaFw_ zO|hBFGebCHH1%_Bn_GnRJCu+J+hzb>y}}-4Rc&&`YxW}GEDX9GB?1H|er>%5xm}OJ1;5VEOgchh1Dd*WLOErF-S9XqdJgmZJ@aF5ar%xFFwxK))nnR5aH7%<)uk#i; z^VXJ%WEIWwfMy-LvN7e4-_)zO?_ee#_uVNS9?^t4t4sG(b^-=y4TD$NcP*?)j*o+6 z#c7a;4g_)Z=o86q@81|FPSuk#V?aHAV9#rGLoCWu!%_~8tc8vyQObW zFt?T1*HwHz4=`=Z$2tkQmP|(G(&Zh|7m4xKssCegqM~jNC{o$|Ct*fEoAknduk6Ho z87@OWr^^vT3>#GBx4q&i@^DyZ%8#;py@5_G(5lu*XPm$JKia0L4~FY}kYBr7Z?a3j z6nP?uz^NN4Q~)5VKG%4mx#aVStAUX{WG+78_w5tsl6!6dlt^im~+9;I`52_y4d&i-4=HE04YpT~*MLt|~Z05#9{41mf`ZL5& z`Au)~(!d9h##hMc^wTmr3vsF^%z%lX&zsxV$n7F24*2wxNK@QDdB>w=Oc}oSv_W6>{d6HTnH5uW0@#E{+F~zegI}&c=3XfGW+pG+ApPI( z>pl8`CP`Jy-*=71IeBvFujITJDSOOW-h20G+kqve6;mO+sN3Y;gO*>h@zvd-3H;G0 zs)~620lqcLp^-=%MiQTjyCqRXoMkt8ROj)`m_jPF=&$s-YF^5jya{1Tx@#|9L!oeW zP1TX6kM^1Du$X;P|Ga`$%WYAaGPkzvtK#P`lhW-4L6J(@RQq;sPxM!d*S$AbQ2`xD zK*o7%H_RYTT&DNFdqxO{P2vO>N76=(iETJhO&3AEb$7uAKApH`(8mVAuol!o*OqdS z;cq#J6&zOMF^8Zt6q(#z6SsALAEl%$fY-pj(CadDh^rejF#{JZpT!vLVhKG!Q*jD(8JEH(})XnylAuNC^fo`jwJziM|T#z^z_ zzo=QH2TYh`exNkdmu*2rs*5|xarX!z!$4FZLVu(6e$g>tvDnb#m@o72`} zRiLub2uAfH%lo4A4tk9JG9HV;`83q!XIx-BbUcuE*lEry%cFaq?WBZNyqqylqgJPL zkOw{d;5rsNyHH;xb7xwgYeL<0X_xksD1~=8)>qKmcq0Fe)mS|^Iy@Xp`n_IH`fBlk zcm(CNs(2yH$cSNr5qhxqQ+R+45dizh~8gK1Cgs!pO<8HfT(STTKqV*sGVnx`z zzlWl!rbb*0wb`YZx=G}6fo1BXrvFi^#qDi+UCtN~8SD_x8d}5zb2hAQzKh7N$E+*LE;ZogcaoYyRTP5aOXDa7y^&AV=~R>_Cx;<7xmBt(v^zh4QOX)-qi}d zI@%ByTVtVAVJ@of-c{&5*dG0zQ5n|=rq#o+6hf1Z)?j6R7(AK;Fd%#=idIYjk z!XIjjk^1)UD#-nw$?dv@FnYh}dl|PK4*g&FToK16@(=%~^F2EFJ^H)LBA*%Wu>I6O z)z&L+@$_=^cg5S=fg`YZ<0&2F+A;uzKH5v@`bcgn9Un9gr`($sMz0TKa_9psE6b@J zj71n#F=-#4QJMH+tn?fkN@)ITFk{CJ$+QaQ&b8leT9t29#*cl|%?L`I>+i&u%~s?o zGVwxDQqV<;W)1Ur9lH++WNj0$8Rz>q{yAJYz&6P2{Cfxk z7M!)gRRSbbX{3>jJ@b6zMdBzmQ|;y)Aex&r%o)VW8P;u$5ucs6zz3n39v)4^$pkd- zREwG+y6lq_dbgo3t@ifRNpKc^66FwEPMBU zAnKzYI;d{pPm6ewxTY241p4DP;WBXuE`m*hy~slw@g`PS)dlrkYS{iLRW&MsyG_lw ze3ZR_rOTH;Iu<>2YR*kd3Flt*ay<_Uo)TU~7sBZd&*GKF*Ml(j`&4 z&vNIiJJ&aRhedU^ad1Bc657X91EO7i)dyQ&l#uXJx>(~E6f}*T*{`4??$@ul%#^Af zT>;q)XvRVz0#xeJjH#NhCBOArR2Xp z=n#qxfD>+=T3Ef@-rgR(%PEN`SsHjLsQ)=ZaUmy=g>onYF016Qcvmw^M9TG@^|W+s z#eT{THu?M8JTr$`)OBJa_seqB6s4UYYnrMmUz$i*qFf8S&sBBZ?cSed?Es+Km*RbE zGQt`+7WnO~17L_Vm{qo=q{I9(K|Dw3%z_{}D8 zS#nO4^%w+s;J_B#(_@M~o1))c_eT%TBCO^MX{ZqCjF1vD!-gk3XUh?X@ZWAcss4iqB5uKliuwgP@cUjMf;q6r1_3$tz8RzLHItZg;M8B>WHi;NC= zU?y0JQ^@hh8RE}-(U)ZQ`5C`RR(Mas9#Ti&l`Gh4=sOKu)0@dPTOg|=n9 zPN5zy5SEi}0I3l*v(jiw`dE#!Y1WH85QYr}bL)3_48#s~PXqN73NbvCOMn-GK5*HM zGO?oWV`UOnK;y_wBe?W|)8Ffz&cpT)Ig@RgRe$BR;R1OyN!&pbYo>vdc!YEET0);Y zlvml>^&7LhptY-2~0 zpQ`z~c3w75r)7m0s@tUh4M-S^A}-n14X!??clu0M%>Z0I<0WB|+5SOgA7iT?1eD=N z?t68W9JFAKXlq^`3P}YeSkDT_1+1)^cyRrQj{as?pawv;05u{I809h{KvCS!eD*AR zl5zA>?r1FtFg}b+ZSuQYIUCe~Hsv*V=iEOv%^oDf?d6*}Ch5}bT({XWY~KrE7GBv? zd%qYj7ezP0_UEXmn>cYKA=HKCdJM+tT+r+(UdxlRKZIzTuh=F~Y8g4)KaEA*tT*sJ zq8!RA>Q==tZ)La$0#}YONi1MufcNJE?bIEepX}KY8Wf44F5sdcc$enhc|-xGC*x6~ zFLT*vyAZN|aSSUn+$z?k6}w+14t^yH65b#GI8oa@3KD*puS>&bL`w2au#LPg(R4}R zc_4fqeuEV>sMRJ(vpizvB_HcTBu9rpuumY>_&r?p>mJyDs+y1u_W`k07MP_&kNztD zFsk4|qA$PMvfs?ef!uRr7QY5Q0om}O;^Rd9qM)miFlSBrpn6memQOdcl!DB*#L zVA}m9?dXU#zv|svh%pVl$p2?+4S)WBw$^h%@vYyKYjc1QvzPUX6)0($(HBw;>AM%J z3ZxN-KN2=N)WeY7p0>P?E&5oQO}lPeqqBxyQoMblzV7Cr|C@KXu?RN`5-;zaZ=mx1 zlG3g+f#qqM7Prlcl@mVtn?O!M;kGR$E8&m$6i zk;oKWR#Ae-pVbr#LE^~ARL52pX1qW|1V|DX1C$X4X%$spRLt7|SQ((U2Fy{SMOctv z*f<8c)@2dK2fyKi-o5^I&$d)GeC)k$CNMfmQ|tP&g@i0sUc9&rCdWAaWzTkp-=KpW z&86uetY4sm18~{u;gAZ${sH)nHf($p8VyZu?a;9Z zBSJK3MqjWvRWhd^DaL-nA|%Fe9lMM%%F^LGB)LbR z`sRzP)}N)t^alq^6=4rWlU4izTl80T z(HIySBSlwpqPqk+Y#f3W&w^e^{1VX23~xEENVRc#4tAo_I$Q_E^+CIz=VlsZt}KrK zFw~>?2lC+~b%4b++M#zzyqse}1#%Z*g=TgqbGuRt;%$&l?wAE0)IW&sQZ40GRJb5x z3IIA$oJ?vg9~m#@P!0E*1}kr^jihah|Iq;Dt`>d3@`xLPibOkoi3_0eZmDa60(NHg z0ivX$9NzH48l|mzB@^i_ANH8ZV&@4j9_SMRb&Uiyday_N2R82Y1aTT8CXQt*iBT&<4y2(JarqV!rwOmK9&(KCK@9 z7&H&~nudD#r@RI&c}Ek!*)ik?iiaAV`N!|!OQ28BqvpHbha|3yjgjr~Y?f`oc zmMsjN$~+{FsauIQrPS@e9vby(`_~}N&}o7jO*{G8{OV)(kLAhdGt(Mk5?-RxLU-KB zpb_0(aV--%px$>u*_7b zamEmX{IQwRV~cUOGIJfzPC3x*^Nq*qFVxSgAeZaww^y59Bnm9=i7iF77F19e%@QT_ z)zQ_g1O7-h{1CbP1dWNOtI@Y^Ru)VXv&hGU?xo9y0}vhVEHcn~n=M6^rOxK`hF3l2 z=1n~7;oe)w<%e`Nq*bt1EO5eC^37s$P%G&``@f~*@mW-!LSf_U2pI}AwZ@Ocjk$?$o+k7)fVcU4 zZziRkxWwyqyGxx(xe6VM_*0`aZNn^25Old2&-V+|l#3i>QJK4RE_X}LYb%mN9Gsff z{Ctti0Jke6aBAp$y;;ZA;ayi?YsD}7X9^&4`InZ6UvXwX)S7Z>&LIy|jr^4aBB_rp zCU7>)x|udH(L<8!h<>FF+O3{lid;^#q*@x;@-^%~JY@O84SBi#rv*E$&Q*hkz3`(A zN%`Vu_(LhOwmD&>rnrrcmDwYgeY{t8#~l(manylX+UUa6j#|u?2J(JVA|+-W-o3nk z>9)O+gB&Xk&Y%>}NTE(ggl{bWTpVppq_#cV@HAIJ`vxt-{1kD4EJge?_Pccf)2|Nj zG8PphYC)+2zEez&E-4?%>WdP!t>{x+k>YtF8ROT6qcXgZ>y2 zwirC;2F&;0vH;S4Y}`55s>=A-$QJ{6nkQ2~@qfwAml`X=V~ zq+DR>Juq3K`+f+J+gNCy`Iimr;`y#SGe2)l4ESm4`ilZ(F@!hCs2i>CHh*3DE}d}y zagP4;sIb|H;^VLb*|j%Np*1nQ`OB9*9!ohU*2fRnVt{%6&$IHnn7@Zu$v+#>2Irnt z%Adsx);>JC%&ka%JUJW#O|BqAaTCqP+|uzfYL|E!K0KQ1ma-=j>8w}JJ2R|VE;`ir zmctX>%P8GO^I>|5WR&r-tGaaLPS#C1%zwS$B3^X=hsXcZ?1{r_-Hw?_grz%?HKDHKFkzXL4HuO&S zsDQhDovD0=3L-EeD8Jt9hErVXhnC0Rv_%R_to$AnoEXR-hk&Y5FyHlPiEB4rT55U< zl?hXetT}R9*Q3v-mc7?5+xvXrFQH%$+BJU`C_Y6(C>?XBAt?nicT7bP%ectNt|{8-iG=Y;LlC z@L_R4ogI4NWwc1zH|MK_(cfa2DkUsbjkqM@SHP#a=I$*9J1-Or#*v*_p}D>IRWeHq z%ruLt5|p&$Ny6@Xn!ysrxR450`JxWFz1O544LZPE_1k zIZ?f2#IESNAHiQW=o`pTWg7IrmpSo5h(ubi59}h5gfj-S17#1B6{J~;Jhb|_T(-6_ zaibR1V^P;!bfx2!?IOF}>aa~}!!>nF-{1zNk_9Ql)(d1!(JZJ|UtrO89J8w4P(Bql zkejZHIQcolINMupxDr6LJ%W$|BMf|L4AVTJSOAyY4Ae2ZmZ?4L6fRt|y=PV3yB3!E z-?gM!$H}ls(^6bjCO4YH4;^0FuIF?Sn3l8#Dn1U3$*_8A@BPa~-8AwU<=Wg48A_SB zq%8L66QoAq{Znn$fIQ_t6UB!~vo1=in?FV^9QA(}Ylo=Dxi6#{y2fKgpL*%rG)I^_ zCX8f^I=E*X^(@ZIhCjmkG{2!CM5xX3jDX&O{kJHrjHn>#>L3UC`j?sJqS~sW!OG+t zi9sLaOOku;D$>@+wfKF&(#8xM`8-n{32m@hT1`c4Y$Op}`er0TJN8y41x~%3P0rUY`$25&OvRz`Zt6^`&AK% zk$VqcyGRsu<|U?cAxa}AEKja#Hm>&L-ArMY-MSQ>AX=ef)CcoMDA{l##D<6p>y9#@ zcab9nKO>b+do3}qtmk8tveTf#Jv)tM9_?5*@Mrc(MbXC>W&meB*`3r^j&|642_o!+ z^O;rkj{fUt*Cf->n{(wrxdWYCO%H#z!$bXK_UzP|cYmXz?i~?2Pt=5mQH6I8p(#xQ^3>M)%cKtVj;&oxUjXp13XVzPc`@&;*dcl&?$3QL*!ZFBn5LIwNY z6E#PziedKS0(T1q)PUof<}F7%*^`63QHKE?DMW>c-;Q}+&ktL%72PT5mJ{ZtoawJ? zW8}Y@rhIu?$@R8*&?@hBnUB*TyI-UE)8gN97)9Cu8ya|{lpG{^Dt+`0^tc+0mP6;t z&A`4NPxY{%Z5~$4r_vC90YFPnJ`cLq`=csE(a(62kJEi)!Rfft5ZCe+b@noR1W)G@ zPxO&KBJk+?6rRp*O+ces?~XKkMaF`(pgdatwMi-Pi4hlm04LoqpDa{%8e%+462yX^ z&o+yeRnh|TWIKVs&%`1O_@d==yYSO2cWez$&q9}1M6k2>i_2jum+lb5teo+ zW2wm^Obw`wko8gCtt+Fd!M=Bnk)OYr;sT#yf-`Bvl@l^%ySz(z6irI2l#X)ix0>t) zL$O4qL*RAcnm2r+(l34q{jb0rVG&*f9r|Z7T%GjIeEd({?iHJ`7dAMY zYPlqL`mBSrQ!0TET}2)h&N<* zL5eObc_%_Z^D7>O*ho0i7kEeNJUZ0tfyL;3K^_$eAwu^3c zj0dXJ|D21-$5E$$J-xmRhMs^Y4QPa59v4gqio71)Bz3SVvXXk)JK#cANpqVVRUL^H zYO`r}uHWQJ47z?2ZhqZIF~aH%;TO{MGI3O*n*C%dJF(!Mui^lRX#J!0rL^RZf-$T? zsX!7Be*}zE^a;?u3xfhl+gB!Y&qh_u95Ywj?o~6H(TtM-hO>srOu{^*;vQWaDc9@M zEHL;S9%C~pri;_RiX173l2MKt8}PG;V!#->mQNV^yvyM(cU^Os|evAfbh=PKdFgOFm`O+^?Uxyt0^>mD;OROn4p|bG zL6hhkqHj@$^)u3DjGI~@_x@)$v+^iU>LdV;?W{_ZQ=0_>r_aC&`mMG}x7uaVLGVf_ zn0}PZQP0r(^gswOljW72!llE-@Ea06cbj!_VD>JulfWCZUxxK_(q6j#i^}PbJcu0;!pKn&?XVNQdD;xuJ1M@9Rkx=3Cc2Ru#e(_l~D!N+)7Z_@wD z&+&imvI9fgH1BvYxmoHfDDHHAuTh!66&Mj=5oOZ~G|eu3ug|Px!>0;8gkH6N3Rs1) ze)YS*w4wnaZVE{nqxDV+;;T<@w29|)*+M(H*JV*^iwS$vM$;|PU(G}tbR}tBzQnL& z+$**ZTI)GoW^GwE&zK{RID7byXQUJgcC-=k8M7w=Nam%FnU;byJM>vv^vqPtK-_=~ zq{AaJE8MA8*rEBg43z=C9WVg>p3T_vBwevaXnBPHb!Sqs+o4Qj{Ke$J3v(zqP>;mU zY64;)(q@4FFn((7L*h-^l&hpu`ke57=^cl&tY;F54dN1BDN=*S!}kGqvExyOO%YIz z-T`#N?2of^J8@fu=(0ur=xaUNGruR^WTRc;G>nvY&TKJ!;ANaw^#8~zE3#(wE6w^Q z1;4@jbZrY$D1S_q0$3i(LNQ-x(+Oq6sdBqSXG|Y|@t=Jmar~gE)dASth-ak+E-(Dl zF>mYnGVKLDKZwFcy=H?E%oGjr2VDdqi&N=b2etV1G}QqW|Ld0)HTe7fZ(%1+t27Q! z)BaQtlh{LDCt(&=Z=i9&-8C#zqf!t5?B~>_G)kV0k{!g#OU7tx{A9uoAJ-}I} zg2{5d_khy(CSeTPB`sv{_~+9cnIamr`!H6fF1<{B8x*gImnZaSmD8#L>TdEisN~-F zHd9;5Opj4v6pa~`ZsP>Zp!{4eYTkM>T(aOF!-fLG{LDKmz9HI6Ek)g&f?=rRk6J!q z*oTE!U?FQ6uqR)0dS48)V=7;{%5D`Qjz@gkYn71_;DGksq5k}dMc4TU=?$nr>H$kt zrtkH4-Td$!5s`X*<=xheLh&m2{X0=r59K{NxP;wXn6w)HuBPeynmbM_;{M$69P8hz znrK&RsB{+{pI6AF9*N1x&rkKcTGz_oOrw8ty?0tHd+oPH$>tBSLRFoH;SJZIkaiaL z;91^b!(o@5%?s5w#hAGBhN8|5_zfxXtDiae>$-92A9Sk~P9m0t+b*Z~shizv-fk9t z(5-wu(0xB+w@Z%a&$NQmGs@r^bw$m^sqoi9$%XTu@4O^Ol{}IA{GNyYSa~P;efyuH zQc_F9H$nrFN)M~-whUP!->8=MK4GSEAX`TU9uaX4J77MXFe zXVq^B5;e<@EI=H5)Uo;$H+Zj=iDFaXVWZM@)o5CxO{gRSEeAG9cuB~N z?hIBDTC?>S0;L3?4)_{mSPT1n#hRgS4;wvN+Q^$@>=N72n@&FuVdI#!v( zt%SA4T?YP{%WI_(U4L(68VSJ&U6m&flV_#S9OtWsbLGozYVsZQLEN4REAqeo`royg z^c4^b&Zyvjd}Fxexa!rd!Lb`I+c%=mGF-`K>opo2-_KS_7=@QhOOOP;V>;fc>aAGl zjcDP-<|Ae|F%zuQB+$2() zS5NMdaDj0QA7O%Z=qBa`I$y1Qqgh?Sg|O9qc-ZK$EuGaZK-#`pG6gwPqrS#7&veej zyDc|I>hDY*tVA^RwbRaqZwI1s+-|UYy;wmOqvZ}>njHOt6g_U~m-$nX zU2h1>YWrY|-uH%boqBD_U$VLBty_$F$(iMEf#1ICv{OHM&Abuy>)~meO-25ET^-@8 zz{%AFb=oZXga!r1MXIbKYK^rNcd9^BB zOXyThkAA7hZ*W4Z+e)j;pBgTd&@CSA=PW=0?OFyjQ2#9nJ7%4HjQ|kZn{hj|gc-Ud!KKtyw z?|trbpXa{Q*7~dij7ff*LT(h{;V^9Tv<8 zvzl<%Ie|)bycY`Smx?ytGY?Iv+~;?|9?M6}V9PrYWKnL#Yv#c_qS{@*49{>&x%?TZ4+m8tI9lc$H&Pdcs??+F|BWd1yMi z7G^c(J4GlB@yFzbRV$>LE&YokZ7xE>gV4#QMpRsGxpkH4Dv$!#Qs>oKikO_-c>|8Rk4}ui$ zWEQWVdxla^+Jm^V+iU_#d7baz`7=G|j*ho1hJxir|gaJt`->$~-{i0HF_ zSp#P9#&3(En_9@`JCed7{(N%{o}m~^u2=tj8WHQ4&+{Qx%i8~jb6X`5(m78EIY;{Y zzEj4;jVO|XBBQ5d{^lWR+ZZp^*qKO%+MJOg`bkZ3y94=y!Q+3l2x*|5qm^y>=Pl$> z_NKAPU4AZLs&LcrXWcIoaJMe^-{=bM z5nO2Do8&W)p1S_c&OKMyQ(D=zz?dTm;(thI5HovlAH)}9pYg~+&N397C3-WxV?c8} zCx9NG_STCvW--~Xiv`Lqzw)a>s^tskDR(uO3ZUdT(N*0?-w7U+*(8&TDyi{1O{(-Q zswhVzCbp=ag;fa8P+eWs^&Bc`mfO>hnGI$!(S^%|sZ%7H+QuQ_#nYVD?i(QlBFTMc z7&cxQ?u#NCLj``x1LUS_lKg8o2B`>-(U4HpcT*C!qwm4w5v|Ax3A$CwB!c&Ti>mZ` zT_9aGrInPUX)Hzym+Z)Ja)b$8Z_pi*&h~4w+h{K~<7mI2=o|epXTai z<2%MSP->G5A3oG!>eE6xuJ=cLd7PX@SCu13xIr!z2|S;`LlTqeFgl)Rh-}v8 zDeFV9KknK_D<)5}l`0z#i-zO6e0vK_HArMbj*+RYFEL8CMIRPiV~Zn%NV)W={fv!y zE4|Y|P|KS?hefNhc0McUXnle6d$)2&R2N?VJo1xP_|stR8O4ay0Y>~DdvemU9g9sp zAN7ou=FF-3W__MrcdSvX6v;c2MP7Zlvlw<$O40}=dqaWW(uz5K)7j*4+`3my@shu0 zMym5cYCe zbQx`;KB>{5bxJuaOr+Fw>AK`u=WUzEOIxVCDU6saRtz5v4%VWli@amCoXEA?Y{BK& z#i0+8Os%ky$XoYHLLQ8q{f=4?-A^&O4p=nFLcGv}ySLj4EL2at+qR@1sU4}L$h*SV zh{u}8!q6&nmv@{CRDLaMq>k{cBxlAUfCNU{?DB_>gah(alS z!@Lehkq{?u*%OI0ry4qmi2J3{upIW~L{YSDYg-FS}klrHDKP-ArxiDo>0GOfa;zWY7&I-7{5Pl=0(OOfhb$(c-- z*gj1p9e{zzhu*-ufyT#Q$y|-SsNQt8)|e;3WZf4{&ZDaUQIfOMHP3td+{>FQ{cQ?j z=`v}PpD_mi&~;8e&l2l|S^AMH^Xx>z4h6rQ%yHYoNW6QtvTHqkg$?MJc0VplFD4BxB&X~P2W`Im`1?^FzBgm^ z#=P=CIS-w$2%?4Z@Skf0vQSa6WhVN6VCL2&o>r=L3tr$L*ks%#5h_Hnc< z_gRu2d3do(xThlxil2+OV`^3dr3LA}r-=rw)XAMp<;&G@0^bk-TVz3^eaKI;_xtwz zH=RqS`x`^as;H$-eF4^+7AFC}VBe0uCkJ5|l4g3_Igj~t)BBk?I8A+lFXB004t0j+ z*G7SZ_Xf>Bz2z3)X==>pk3>@5s0pO6SrwKtBPw)Qm}62! z3(4*|{{k=j#f&|XOk8U5P+RbQpg)02Q{NmiymxD7g-H53Z>CLF?AJeBx; zy7IKIB;48HmNrsjG4+VH0!#fh(NH;Et0vyl%iLD|*Xuu^U#V~$KfJZqsyaKZp6*8& z_CvUuj3`BuilDEHrKwHWP zcg}}`liw{+=Y}?tg8GNm-|~pkeylC+Dj9aRA%D-mwaSyG&#(-fg%$b=9*kQYS8!E1 zS}(r)fJ{yndqUq|c@ts1$kaC;>(}NgvRZfpRoq+UEpebjBf9WMD)zDd9my>ks1=E$ z*`w)RgN49<32(;AZlQoaK{`|z5$?s{d0H4;I_ZPeoy5Ku+gM*#j0^UWk zkwli^=gnFf?90tTqHNmNqH-S=5R=?t&{AvB?frlF#m&Dt7o`d@O5&!{32MWm`stAe#-1M3x5v%C_3GFOMzu;@XS6=`Hv&V zi)CQZIG()d@=?OZgin_n-<1>wy=t@J43`>*`;AlfCP0mP{h8g?gif7`cjw64a5;>~&g*Fp=oi&{uKV@Eqx4uelPCb7Xr(RGT0PFIQh%{@XqGM4zZO^1*I) zPZc*+cy=Yb<(+1^N@Yg|T(M2xj@QzAuU?lkFFFWN6?HQ)d$_FZ%9Nd#_f2wI4!r(`rS2gN=u|MM4tXD3UgVU6JY7=}S(xOv#x4tN1z^ttQ=@au&ka%*OJ-uVST>dfg%OhCVVyEAOcw;OSqM=)OGshi(EW)FK4xl?EN z?jeZAaer@#bWv)zw1yiaYi7)B02v2|X);y#yzf8N%i= z($Pb~peT6Fb)G$4uIyCrwnh5czr-TBhyh(^Q6c)aS@@^eDo27rl~d!ye)HrDiPQqa zO1{M6W(EqJiIYGMO z&DqC>U%@at@9L)ZCjJAR1kZ)5rGQbexRUrkPFeE*-Jp`;af+;F-2B`qc`#W|50+@K zoADD%%B)`1X6369?0NWDwK44_t0qs zk>an;!Bt7$Q|q8FH+AVWANh({vXIO*&`lOXXFru&_nR6U5DpJ3e;Nj^q7!Dz?VRYA zwbpAsNlSJa0OM}S-O&%wYvYNtPw*mfEFqJcEkBFiq-(`OFTMa$2r^fZ4i2Xb20yrn zYSUoOo4g23LI67Gby*KxJHPD#_RyQzquH0GPm8}xo0c$5v8wjH)8ad84Qr=&9TDhN zy^Rz+gC8z+TcppzUW#iU^B_#Fw?Ssyjo&{bprEF#aFZNxH8qO&P?^p1JdH-LGDckLuEueVX&hSUfD&-WM;G&=oV!DX&vKG2i7a3H}+yC+#4@^Iq# z>n6W(c)wG<>S1*+32jXo{AB8wa3;t&mq}Yz1=)EtoadX9Qr-;Wy_Iv?|sEiT_MU+M$HxGFiJF+bojnVMf430{Yaew4_aj+3GfDA^>jMV%swEZ zSIpD<)Is_!89hxf&Dmy|XH5^;?*C%hAiaK98Jl8QVpx1^eY|U*jwY8>cUWwnRHG%D za9`h-x2qM6Im7zWrHb^LGOubW2XD$SpGN5fbtuBU_!WtiW#(nC^mit8 z*E-L|cdBqgPkPs<@NB}gPwo8b{wi-gSDapApKPi+w@Tz#=WIl2q>fcuVPc%e=t-p1 z8H2f*J=AKXg`7p+q=DOZDvWKgI&Ow_Zs?#!APTK`>Z%ux(~=wHIN|~Q=4yd;Vg~l|cp6dC&x}2?$=`$)-PY zoRxb{S$4RP{-n z1!X=>@DN1<`tojxKnmKxrPtWa)m61%^kmDu+4jXR@Wk0jA<_S90q&BOtHPy3D?hRV zI$5Xc*M|g)NKLbJB%mC<3iZmjA7PZMudLtsCx8*TDOC+iQ{Vv_QuJ1RZHjC@)H{ZC zZ?w8o#gV+0KfhG}*z3o?v>xpVPF&}Kp}5-f<+xS-dOO6%-;0_6dO-3>B$SkQ(m3P^ z==&MW(%XvERj&tW?KF9YZZ8%*&*1sB_`23Wwe2^Z>H^u zE7b5d`VNjida{esGwA0sfy)4G+IVn5D7R(@s9u*tLC5X+{S@yQ@#j3&j1aB{zy~qt zMUBMKrL`;UF>~FzT#RJ4FU~-%VpX*2$cg_z#=K!xNZo&2Hh)WBZ zb=dSPoYn;Z@wNel`j|x{j54&*tB}U{k3{fwO0!WVhMQ&jk4~Hy6CHc#q_lNa|NP1# zUG=$C>G!%ZWpp7;bcC78X|}hJW-+^)(x^+Qv7KSJ2FU=kw{tkIVXLJ^Sow|UnqqSe zyf3;!V&9n1Y`od)YpVRGXD=-r`16k=^@Jc{4@vAFb&`XoWZQ z&Ayk#b7k*3NT(1yfaWT8W%h+yg^>A;b;#b>TUN7`NF%n5ne!(iE#ioCNjWjwp#;|;HWbpU6IQlGSWhF*l@Chgh2=imjj zmI-F*TaoQ)AK+~Iv_UZndJ25%B}Cj2kI#9VgXmyyatK89;cHsqbg;S2L#Y`xp0dF$ zOP8iUW8N_-u7k1YFH<%p#duU`}Aa3Q1)Effnp(sQ+xyaoG%l`j566 z?2T_m3+Ts7|ItnuWE;Tgu^}grdunLxGMx_?9WttI(iGvPw0+z6YTNoWqJMIw-u910i*M%pd;2hMiuYew&@T2Kj!6?wFy5LF4o^M6R*49-jJx}o&^{7`_}O6 zU5McHPpxpjDnp2#(B^02_nl)^p!Lzu9I^P+xSzMmJ7!kB(IE3I7Qtd!LiTW$O|{16 zTxS;hqv^?})pC*>t3)b`0|z&4@Y`bjwyq{3#$f4t+EpaxNymrjJ(G?Rl(7{{R}Y=v zYirB{E2=TU{&wYm?F7kfPc%wozej+Yj!x)*(7n>KiSn#E1W~Nz(c_(+=98dmTCjQP zWb!e6b-73EoiP_kDcu=_KGTwTtqiQ=Rg8#3i?i~7cr#rY~QQhX$B7fo3LmL29sHQ2{kMV`}VeMZHYdG@#xhL!myY{2aIwn zne_Lxxc7yW>n^7FTQBBoL>$bXxqsS;PHq6Wic^dKPC|p)$PIxQ*agzjE(fx(hg$=3o7billr#=avrID|}}nt1`J=avED^Xg15WVe&FOc^bsB`Wg0|5C#N**pHqBDPFnn0IuHVYS! zbs9ySqJH9xOAkZD|*jhJfJq(C_)bxiYM!V_R4fjCrxm z=l)kjX%0(##_+LBnbnT@FBRNn{SUQUb$149l|F^14ms9!r298Z*q(M1=75C>k}NChyAt|tH%|$b z35xX29?&aXrVoRPS^#dgEXdO@yuvhQVR@JD4#@3*b_&(Tx8SLfz}tAxae&~ANAS$Whu_r z$Z*(PnRm>zRya=(J=K`vUH!HxN>6Xuu#8A-L605ziW)M!6}#rb1BX^4GQK7=xM(hx zW*YqstB8$ejBDs^(hx_O{X9~f&(BPy4bplSg;<%1CN=wzxpko9#?d7Y3(h(ur5aT% z?AH!0q$&81)UWMC)L{_n7k|oL!V%#0X3Nu@R7|dmaAuv9D#}i?F&yjU@*uKD5_2YQ zcg@`5vCA>vjgSG-`}c=$au&R(?8I@_(F$)1$Cc@)b(e>rG6+2+$%1HT!$=F;F;iOkZX<3vtZEFVmF5tZK`SF*vBXPzYpW3;**76&< znu=59x@db9lQn%A|62yf4)g4tI;b za|pT9xUwFcD*{zvBTMiOz-0pH%sJUQ*QJ$*&x}aOo0Vw;=V9Z*+ z#rT3f(0n9rO>QrtOO;Q~O~9y-c>z*szklZp%LU(l5PB8SNdMMOD0ut#T}lR%W65!u z0L0i~^f!*JeOyW__IRCHW}eldUsc?BT`OF^@+npD{Y&Zk9*k?>$hZ&S>_JWv2pGymb+O*i;rDaSr1dCcPH^ce3V z9f!P%T&B}6-6ubCTO;>vI}W{C{RHF&V5*&)XL4^jhYn^b2er#tmcJB)Te z0CT;Q1K65CTboKIl4r#y%+*+!FpVQap`4CKVVgj5i$GF}RFt!CsvEF>zNoab*N&u) zN^+PgjvS&N44V8FGrkbE=??I>+Vb@E< zkruf{AV1r<3~U=;>rbJ!pN| z>zNg@D%D;SgAuc^%wE1TEcexpgL#6&lTFe%6vlcgE)}sO`sR3;-J6q{TC(rdX7Z6& zE{e4)MvUd-;x>eN^<~u)cF=HwFeiMoDahz;5M`*n`N7)hQnFkH&@@0b{dwl zLm5m@w-vSXOH)YgYw&==*kc^{*0|{e<%XJaTfx>0w!6(%tX<>Q??Knz4v4=0t04NU z+}5o6v^ZG^Ahws++}aI%9D3TL+6+d;x9~^C2X#k%dOw$1lT@s7ZekC5#=Q$s!6g*k z5+f?R&g&NF0aj`_2Jxh`;zJ!Nao3+q~%ChFmu9@B}dn6 z0R42n`&2ECccad76RZ7lSDk220dqF%nj6F2qGfU^v2YfM~ zkv+t~1hi@5-Oh=C#gH@;~rsNFG7eRCw8FRWc&eX`^xpE{dreBz@IB71vi-Y*w zRsL|eCLFfN_Yx07tS31AU2eq7F0KGTx6sFWrHA?flf(&Lvv)10W?|Kk&;BIS5MGsm z={Jy^Grs0EqOqcv2@YFSN%B^HIK3i7TD+r^NNzp35;_>OeR7Kd*TYdJ>A>8oS zNY$|FVY@hi&*s_LGSrbTAdKwut{Wn^az&<`&X4CuB=~(eXM!?d_MCl)7m$>^Qysm^ zO;u!Zk3o?MN>Jr#p(Ipvg8};H?MK_Sb7m1oP|Pka5Hz2^Ua1PHz>j=HO6yw(rIhN= z{#6H8h#)h41!<%#Lkw};AM?wX#%K6V;8+&oo-y6uoK?MGh6(Hk_NXUPM}u4R2*R}P z9}2L!EpjQ_1*+Q*?^xdLHK=xp$>bS5Vg!;xODtPn8_O{Z=AA}J1DkVv0TaOM2TE73 zBB6bwbs2-}jf!pwX+#Vhnuu&l?qOU@_r)DzR2rM6gSAGwcs|ptnH+QUz#o{v(dtfT z*?@;V%hZk-X2~|;T^ob_zVjbXjJ*?Hr-Tj4o4MlZhp@~xcv20>AUlF=$L>sA;b^9rFpZQRGg&E?87<&pBM*PcQ#naiyz%(#!h4Qd5BD762Xaabx#& zJpfZAVoJ*8@Zc+p@qkmD@nq1SJU$pu)`V4O>`qX6m z&+qx5^cXQarx;=}jXhIlk2mX+iw%dTHn8tA8FW?PfR`8l5{rl2+F{!c1+f7%$hnf16!v?ELRbF)Fakdo1wQi;{e;2#V&dXB0DVQo;LjU4upt)txziF>hsx z%#vZe{?{q95l=umD2$j#jGe8hBBQkVEZ4|!=wMb(&DGGPhn3i-fsA3AY?qG<{f#}l zZ3@*;uSW+fR_ZfDXoM^ra<}O1=PsPnpf@A=d^W^20n;;%D6aH~eSNgE4jz|zxzcN7 z-eFVhJ}2|(v&LU9Fy_DV`CfG~74F`~nCBtArJI8Qq`9}|V@D-rd*I@vm(jv7qS$pL zzQ*kP)wu26o@OzTc3FS^ZW~jNQz*j{nkhYkq0A5v9q~E)qeedh$4*YHf#O1laHGlw zP)^#!MI+qWlB@$)#sapYJfZ$=dF!dgO#S2B!9_Ib1Sfo@ui!9}ch4FluN5|%uWM`? z6yeJjGAw>92DcQ-RRG;TPBsDJZRee4gU-HjQsO601T>pM1Fn6sd(-=*og z9)MBlAz=zEkAf;5g{*7Y8~pxjS7)~AXf*t;{AwXxews!_hU2CL7p{suxri}*>wzBp zAue~`@or#xjBIPC1GzsmN|RBcDBXQsXdP50P-c%B&=Uai;kgs8$E&u&>4yu?IYdf~ zOv4D`2ie~FHb(L}pI?ks8R+ov0qy~wLPRkc2K2NNQ6(&`PU^`;bPJQfG3)}&IvF1w z!foBQ##kfvgNsi*wJ;7t%S%yhAmqu?g%RiAWRe5Z@`QVC8T6mz6!!AIJvhrtkGXbn zK#K6@6f0sY)J{Mp!NC{|iV08{u>ROc`4_%SGUvqg(vQiR6lctV97v9q{jVdBP!bS8 zpyD{x>j})L(?!KF4T;($VN2k@Mw$ohi_zH1Zn#$*WdIsmz&R*$aC>t+a5N8N|4MZAUa->@g2+Mo?-ecH=RJH-rz~#wgv8YB*bYRMEF?oM5F*J#6Pg^GoY$!+ zmbMvB&=Fd_yQ@a>g~~i8fUGB4Bk%j#@ptWIM$3qZyW?Uhk3rze-q{y4x3X6j zfPRQaE++HbgxN#tAU^i-tO>CIJ0rwBtE0FrpIYsRxMQVT!ZKK{#l+`TjvRzFus|)_#V(DG};1D(KiopN-p& zl6G!pO`4pAY_d2^KoUJn@97J1kM*HbU~l{Y_~*fek(3&r^bE>uG>Qe=MnFLk5}BQP ztoVcQ6FbQX0BqZ%ir%YJimGCf8#gOr$v*q1d&f}8J*`<=GMj(g#EQGTCX`gPpI;0{ zsE0uNAlkb*o<6aZZvdoP2eSyNu-3$KElp(SzM*mxKad8QoljCSp7iab`f0KU*mhjz zo~s2uJyF8tE{>~Zj+sR~En#%m7rHIi0!sKK+FL;Z{a)+LKzAWI#@nwW)K?OB0?L}m zHE21ADc`0)+$1{yRzCG5zINT~2wegi?vHjj+yA6=;UpHsluKI*L|tc7w^y4 z2Nv4Yvf3xWfna57cndQ7QZXeFWbT;I9Nnk`8m?a*_7Y~q`x;Gu0Ne^qrvT!&U5dsV zUIU0|=c`gTE&MbE>yWHMtv&KsTSp!ePW_t-&lY=GP>o&9}>sTIok1}MQnz@LEG z^VE6)%3)PALO-CB0u{e66*z6ecX3sgG?} zs17LuhoU(YjFE1gL;xM~5x9v6{VLf-zzzjH5&I#)%l)#A!<4NCH_U{wujz$szvg{) z++P~aa^Hxrrk^Vjm$Hnio-ynDRa2g6q_`ZlydM;nk5DVwv3c->>09!0f4 z=$k6)PX|(pcsekvJVq~x&D70G8>K(rwkvxq=bwaEzQd4PM-o=;?#A(RW8%z`xX(&` zI{;FVo^XKuO3h#b^0tWr8A7ai_K(4~@9o)wRxskT z|7(qTT2IL%cCL{QnXN3fKu|f$pFTzh6aXv+z`V(Y{ky{f1?QGX*V8b@;8y_!<9R8C zAiubL%XApAP*7pz6T)1BGTAXC7d}-XcQuLmo zWKZNH)C+0aCM9W!a-FseMAmS@)q>uJ@xCTtb0-w`{6>LlENMV8Da&D0#}dUQ>RB?t z^Dr3p-C{I%xnS}4u0X+ytHLD-WXayWe~C>rp2>r3ydc?taL6_KOIzI?xvx1k!3_`; z=qw7vytT<_S<~%4WyLIgrOX&^P{t+zssR7+!gIzOpZXfP3BkB}5DD|w8ns#I^7@ng znub<`B>jN?=ZGtjXU-o$PeSV6BsW9E19v-4_5LTUCxck6lm%CHr@xm%&+$?4)bZZd zS9^8E)rMLN)%FWO+#=T_G1)vLtE7SjLt|ZrJHY=?fHCk&)OWpN=&778#I7`%N43c? zPvm35T;@C63ah7`M6Jz+&Zr)DQAD*}RD(9J^WV>nkMm2_@TP20Q%N@N8GQ^WK9{Qn z?=nD!hNXAjo?lNcm+v<$%|A@zo@U>4k3t&coHgjcw+I`59nu7| zZ)qV>*2^)Cm@P|HhJGBN5(OF^zaQ;$DEqjd8VuL>0ZkDoJ8;e&_D)q4?o?=ZyW^cw zkH8*HWR9e-M7vkIiMr3ohh+mbg0v?@X(}WGS)S47`S^^% zB+LoLSQ&iAoFXp)*7Mk}Eh%~YDbbb0MErQjXv(P9jD%9Rt7 zv)-C0ORHt!d(-|g#i%wQw^>c_j=qtT{M2x)yJxk$lQm@yy7LvOB)s2&PJyIUxC$QL zUHmOM$EgIt*BLRu~?e zp@7O7F7-fDL>pdBkS49{16j_SVXCw@xPtg>skz&^oF#72|HH?BfD;Q8W24h;K&(ua z;~d`yU#bhQ6F$(fJ!U=o+fe0XgaO@5FsTGUmzR$%Ia|2rYZki=X+#%A60Z5nOwMBJuJ;1;B5+I%U>QJBZJ|;Us!iVQEqEXTs9_3E zV5tDzLc|@0Cx<>q0`vO;)BPl1_EumTVH%_GNRRuM|M~#yb>FCQ0fIW|o!?LI1Z2@> z%-+{cmews9X5H_Gl?vCa8Aq-W&o-onJaupA$egEeQxn z^zcUG!MyeJkE_ox_Ny*EHkhU5o=62{{H+tQA)l`5iv-hz{1#`SzfCsh zo^}h((s)i4Uxn#rGKFb4mX}VkojbMKCLWZ@DU>_B^9P)&wwwy=_Y7v4{#SZ9PBBL; zEBT8g+~T*NcCM#1%j#MY)?wX`zhqO zinfpAmegJ)#fd&_SPMZy6+*clABgRXslmWh3h4?Mm^S5z1!D z0Al+%Z>EC>gZsOD%+&B+=18N((B6`43^!}q_js?T@U=X*pE%5-U+cGSl70Cp3)Mhk z)eq@jBPA1Ty@U_m&ubR@-7QH??sG|2oL)#qa$#;5MtvIHI`yV5{QXm`@9g|lb@yhT ze^ z-zmdG5?k@>QJ7im3y2)E{$#}Qt=1g*!#$%-i_851v!^HL&)n}_y+Lt?LXAdjkJWs( z&NWa#9HE=Dje*SX*G~5@*pIaXtFbM5^y5 z)s=N0HwmL@(Ii9-+OiOBIf|{SGhKTW=j&^+*4W{yX@c^p`W+OtH?rVUsN?2;yrz3h)+AB~$Y~5{KBwqE}^c5zMCUKUIA$6kqk0%2ZD3|HR z_Z>368h!ZfnEvT%%%5i0P=xu5CzwsP8E_6&{r|X@x=%LoIo#+MpL#PV5PXt@n&)?5h z>d++2`fKpvsEIVhn2JJG44E%%CEKv3B$mvrg#I_dgELq#d#h!Bv8C~%zjF5xd!EP1 zyA`L;oBT@;HZ7*hED=fDlg76)sGr#?oj|!`$vW)-++hrkQmSLDRty$Hg#69>bQ20@ zo%m3!2W%#|FsK}6u#eDBOUVcG_oX%)o}6pod5huEld}E47U1B7aT8ZkM!@EN3%;Ax zER-o?vg==Sez9NiS{4~;lp|^$eH{dnV=$;r^(N0UoAK?>e3AZ={h7RcCdA zhcE&`x|*z9Btb>mh|H$EdRmmCYrMI?wOFvd9-dJ?<^j(i;go7X0-Jo1E?(z(+yxyK z@5901aAC?Gp!yJ}k%En*dyP*r%K4K4m?_^?k>3kct@Kd~d$*>zsDQo4-@S5?S@%DmMGV zdkwFfgL=@9V#=Y81Pd-2Jfd^WvJe0=q%A0E{HQ%$aWd+Qg84gv=*&1c74hRXSY@F% zsDpP6rgAEzu-tp(aZj=zGJ)PwS-t zz)2f438rH8F!vF@lXj;5D5&HMR5;YA{!qy7w}|Pmsoe(K4BI(V&&UNCCyZ*feyb}0 z^|?-gsH3dyh%qXojjXeH%%XPQ;$$JC)t0jo?9m3{ZB^~g``fugTBX;hdX{{HZ$BgD z=gtcmIzRxuC!aOw@O1%0;J?Ig)P$6;eZ}MI$q$m%DRTM7*h18=m<|2#T>aw$VM-Fj znv;m@RgdR0{u~!P(|dAjS=9Z~mOd{cZKVAbPsiPB9#(dC}>(XaVd- z81zVvqR)mgWLdzRC}CYCtP=RAzK!@Kz<`QN7$vED!eX~e8}IsHfp6aB?MEtWv!A2a zB3KtQ2e?4PVM!qxu6edlW%@hG!jczHN?Rt%G;!I0O)Y;otwJgg1MVH4$H@ zP_BMbs2r{yf5$ADIHAG##IEveB0e8$$|bl>`b^PkNoT`{N%Lw#p8GC6yiGlo2Tw>QQPEvL)94lb#~aj8ZW8vy45$VM|@fHbCK{j*hO1N1%ssdqKq zQgAkEERlPgQo_Ulv@-!5GgD((v`m{f4a6%y9*-(61WW|#72=(2V~vKK`{)Zgo>zC< zV3hmLMg|lR`a(?-wxVDOdli}hl2zgj>OaL#J|J`6=xV@=!SslQ22XbDeh2dLqR#IV z+S0mTjHN3{!5O@O6KZ~`|N3Xev3a0<7qqp^2;zZU_@rjwJykT*6h@V^p8lN07}YOd9UL|$y@>mlWUGkM6Ixo z#`Lv+yx?W9E1#&&v^O%s zaZ_ONrQR4ZSL5ur#rF9G@i1JLMj*Z((J%yZB1eT@&5BNAb}zVUs__UcnJ>JLc?| zbAO0U8iGAQf2T%rpUgvS5Dc7$R@o(^*h% z=FEZ%Ke5%u+s-okmAKr~X_{<@QP(CPJVE)TW9D@j{X%h79d7%%ns*OI*k-R|qg z*SzLVv3p~fK)*!v;Go)n&9Jr-hHD`M8DT})cPas6IAHVvHX&N`fsfC}h)HZ-l^asp zbgrwPJ_h{GC9|=4iI5Vcqs}~?JwFwYFEP5^U~tO5Y}2H0vu&beLR0EBo1$S-aos8a zqBjOqkqO8Zr1Sh7tsUrVlOz{xfP37ZwelT}@zvRyPpHU0pk*7T4UD5GdlKruo$31k zM66!*f{*nFQAE3Mu}%kY8;)+aFF7y%#yMW)^EQYa7Vxy&u9;?H-GEJRD~r9|-~4w8 z>hgDKn|tq@CXuv=8lj$r)5m~uL3*;Y@9Q)rh7?-Ij-1tk3ilaN(SU2Ck+bO2O_gm-EErM6R@&noiyMz!RVWwOUSSMg;*39WFCL(=FE+f^h7evd!CE%J=des^w<$@(;|1}zl? z{XLiQ)DbpS;LEzNxwEf%v?_IJfG0uGeBX>%pvK6QlotfYk5ePQ>vU7lLU1kM-??qk zgly0zirjqPk-yuo_q4a1)A?j^K%scd5etUb><40Bc|B@F`%I3HlxiG z-hJiSJ3!bsd{)t8MP6%wt%QgD(4~AU`&UqTo;0;b+XFPhfS>`SA&@opMnU*+esnV3 z1~TS_-}Atk3z>_4&T)#-?be^X?wN5^k{yblKHdh+jomxYj#(P$n-53{TjGkRht+N? z)u^LacZ=q_ykkJd6QI3y1oR|NDv>f7Ew3dzz{;iqYaS#UH9RgDw&%qMpaZH7$ptc_ zInZ+h(E_+b=-iJfkNqMyoreb$#(<6`ViKhcp$B&{jojAmfob zxhPbNbUltOfSviy^Lyfyg5Tb1+lYULenS#W2NznQ^ur2wn55z7HUVH%EfF|TQXhlOvKx;>qRT*vhyd>+2-yo);@^0@-EpgeWHAvUNyG3_P zfh$-mqow_jG)b;yd;PZ#riuWij+dOl1R8AT{kq+COwR8u8-Ga^#D&5v6JN6tA$%(1AhkP78hpp;pEK?7ZXRs?C$#WA$8bv*ALmNkL6K^xjPd z8a+7vPOomahu+Eg@xX$pZ9Mk%#kKtxv&Q`5163i-)voP7{twqR#>|7vzzK)|^g38N z{yvXt3;sd4@1`=SFB5so)5*0Md2YVqR6NrpbWp2_qD*H;MBoNn)eF{qe%K}MCCl@) z!*ya*Y^wj2s|vc1;NNu(oV6#z6$Tx%dL+7(hl6CcXZ?bgjR4m*9sk+fC}T&w4~i1f|_3M@?P(?O9YyQnH;%1$5sm`B-VD(6f$gL#&As!xxr4qX&=v$|FY%xhim(VvF9 za*o%RQHCvrhl`Lx-NsGJ8oYDwL|RESWwUd0EO1AZX#V=>|F@jq^qIHsTBz@Vte@EI z+&*SdUT1~U@OdesN-a&B{)`{}=M0v{H+&Qy zyNX3juJ`q2L5f^H27bJc1uH9)H&k|{-kCnpP?o%{=dYt>21gFLNOHeKk z8N3E%#hGH})KkeORS$z)3Fnpo58++2Gkvo%9nM&fUoU#}I4QdeLS$Q{=ElakK2~P0 zezy3)5dW>AIpcBiDCaw;j9*}qQfsEr%=*a0`iLlc#Qv0l<4N{lRr8=ur=y^P9e3<- z?l{xo&<^Kc(#hd_o$TLS2Kd_FMaE9?HH6c14JQ^3i2gY0vG~xf8E8V1$sT;1=-S;? zX&m8Q%pXesW~fg@&b3ut++^N~)w#u;5b7 z(P+Ze2`%BT31^#}&BV6;c8C=VMb+)@ITt<|Iv9Ep`s)8^`s%PK*Y0aU6b`63r1T*M zsR8MRgS3=145f5;w+hlAHApKUIKa@|DxJ~{E#2Mu-S~dLzwqJ$f#+V&zV}{h?Y&8R zrbpu*3Krp~?vcg&dlqwdKh%^EbYr(msL4^~LMCl8<@Lh}-(J7=|5sgjY%Ho$hm9nn z?ZBELWDVEJnTqZ$_h6~9M5xXuq~H{lc@E0d8q>eD_etaBrUeg`_#j)3YW2Wp*R}|$&cp6SFHQLlQ3pg~?`gw9H2J&D z&`&#yHHN9M2TndCo28vqv{DmXnVVzqkB8^)5P!_*Y{L)_eq%>xkn7rX?d|ae;jHoo zmwiigf_c#%=zbC`dcw@1^y{&!qDk5{JETN@X*&U-$oGnh-rA*jpQ+8Q+aw+GX}i+o zwjG60iy*J=iWmtnTe6E2s+CpvDBXgs8SFHF1OTy&?dg%-D&SPHMt_ctCYq6G(w!%2 zu_KwFea}-?Wu(AvpK#{yABbOos~&jI{u#QrnE#c27R$8N(4*Vcb|HUV1t89)gq2-? z$j46I+fv*o-2$O$&H|Qn*xxosY^eqYN%Nm-jg}|Kymz zn@Q$r58$d1MM89d3Zy+#Zf!+t90{?^r^{M8NK3i(Ug-nMR%vU41J?crg!%y zB&bB%E@a6t6Q|0fh8WWK#Pa$}aJ-TbM^;?|C6ZV$w>PJP+4@6F-^%#BUbw-_TS{t? zzotug(p2lhq-U&Qwf?5+EX-5#QkHqH&GJOB)*)UeBs~V-CHEUQ@FBPxf ziy?tuoni+wik=0H(Sn&1H;#GSGS_^xM!QJ{Qby})?7+_ zD5qlG4&uI-5fwAZ^2}+S6T2zP7+XYdBXat3x!qHPH8$G$7ym>a*L!$U*q67!Vd%w? zbB)qoCHho>0^RuyJh4EoV=wp6z#eiab+>q@$H9Hy=kzA1PXN-0 zx-iSh5f74{o~ZbOJT)yP?=|MI&SaiC^|I`eU@NPF=M00inTf{q#=4=YF~xf23vOXJ z!#Mrd`7fgdP&>ojCe8VdWwi+5@5_bjZd2dvewJPRXD%?#b@M>e3Tfo?UDepiKadmV zr#mqi6_C%%(v<<43AId#sW^El0X_zT+6u6o2aR zxcl^}y3Ul4U;{c^`H(c14cBF(OkOl0neYpRTag)eF(@*I@I=^+nwU0VeaurMNQC|6 zj!tc?taN8K-TZ)(RyH-^amq;Zwc(8fW1r|gfOxaJO(EZMbb|V-0sKH6vWI_;!ET%I zyJbMS#or=fIQ0R74-drAo7L_p5xXJUB#q!(j@y65iQlG_=I@N?VqU$teRDNsX1LPC zsxEsHKS;#}g$$NxDS)*FpveeX*w{M~aGiAZ0r|aA!|O^wyu~lMid~bsI@;F!HI`K_ zlFIyoL)xR{siz_qQQt{=HgrJXxWaI|o_zDnVUP-$pmYaf=9fhgzSR1)vETYI9R}kv z!va0{UNy{*sPZM2wi%b|7-DMujpZW4*-#5|jER00Zg#!7qwH=Ibyw_q=?OZ?Q=x1b ze`Rq+O9z)si2Z2|FSVo1mEY9kEr4-e#%{ha8NW&7VH$TzuJU`G*%^DO`CsQ4TA%Am zeIj|bE2wsPD;>%!O&p?pi+E!5<)bFpv{_<@B4_J^anv(& zWsy=xjMtwk;-hN%!Z!hC>l(J4wQahz6@}+|@PFG#t)OBD9@D4RPDu3?X(uAq#)_rI ze9{IrLW{=YC?d~-bPB6ve}ix?Y9B@1hq;-U)I9+{0#th(-uLx3RlhhlRzKy1G}`pm z%?Ok+qiB7S^ipZfE-RMeWWtJ3({h=}^268ufguO?tzIo)f2=O;Kpu`JQjihR&UNAI zklBC>u;V|DI4O&>(9#!(@>FHZuek`O*FIXvU0ZBF+18k2r*95yG?&fTUs@O6Pd^FCM)Cl9;HqCVZ&&9|g|Hi{%FCy=- z&OY3k4yn%S8FKMn{5t^qf2Nr~9HiRf)=kd67qBd&>_8%5q;T^SwV$cTuuj&8na7XE z_7JxZla%k3{sdEL_ed##sg7Sgf(;rya@}!tFMzKhYPk>dIWL~?%6t40$sm0sO9DBR zTsd84#qdnKV(ERa-(J0D@a_uDQmA@f1Z9!cYC8PjIU{b>cc^xZZSJ2DbydBQxWvAf z7y2fR`L9RfPQT+`!w+r?r#r3sFq=o2oB{=eP8?=fZsTaaG?zv{m+ri!n)&g|KJmF! zr*!vXvy8_cH{>8veRZZgyI6HWH?JS7^m~Ra$(lWh=LiZNsv7~2-@s7#`7VBWtu#it z`5K#Yw>(1XQp~m|_hH6Vgmwvt+8-dS2*{>b@c#J1EE*)Hl%Ma{D+Em^dEGy9z^*>L zkqPse8ba?7(R$QZ@+`Q?1tELwz(g~?{aKkX_W6t0K4gP!jP3T(zig>-0)H0iQ-`+y-6q-^{~_jdv%NEs5>~5^eD81-{CviB6oP9KOr6f%fXxA zB$+(JrqZ-PFFkhXGyvaW5fgUKA+sjxoj?(I$}_fqNuR2RCM-mO%1+^6unL) z^ZTqMkrp~}$~X2+wJx153dDVO>jZPQ>PCOtvS_1lUv{em_yrRhzd*@g)KFcPuV_)I zTdNw8t3SIKc~FAn5T2>dUT?0sv1tJz+yT7vqKx6k?XgNAlL8@J#CAm~%eLGqBA!1g z{-_;|gZBBjm|zcHL5;JWrxJ|s`IPO_Kkz{JvGzdF9v?ei3sQu>=W=-+c z`1N<-_LLubrpJaLl)dRZ;te4a4WEzZyROtT0`WaC%n4l7mNk^I$ z%ac3yM=^?E`&iejTjppuE?0hk%Fw~Bs;=-ixo$m=i$P{onO{*UJ5{C>n(-wF-p$hU z`LRkaui_u=Mds(YIj)9#Pi`_99e+KWY#Oe)lE07CcOw~tDEu7z^X;un)5_2vsY&w= zVZ2S*#Ilx1OL$Mg2m8EPH5-6ol2vT@5Op=)mm*sMK6jt?s-jy`_pZ$yu`cYCwvbI8^h8 z9m$#aIrgy6o{>Z0qCV{01G48AeL__)`X$uW3ww7cO=rbnr$I1ng*$ zkIQr$}3G(%Uhb4u+O6POftE{ElJMg{R6@8C21eU>o)exiS_&wF7mv+> zHGWN{?za`q?)&oyGU^;3ws0w_~W?XwaE ztZDtN2LIDkIJe8&YMiyfI6X!0uO`QRr1Y7zki9^P(_a=-D|#q1_%I0A`d?X&*1mk> z@Cf@iYDH;feK-#6o?ds|_7gW9Bb@J%+3>H@F;BvQTmSZNi=2XDew6+sQ_naDz5F^* zFo?Gxu&b#+nd%$ucx=iYEt1Wa=ZOF7ltssNuA-h zG}})x0N+dwt4&RbEx!ie0HSkc{?9zlipj%14lAyY~wc3_kje$1up1*|geQsa0Lu`LK25NDx`iU|e=6 zm?EbeXl%dY_DP3wK0{ZU?Fmx`wm`llINf&`jk}y?X-2UerI1(8 zv=~2F4fXeD!Sq*BD0)p?_YP&Bc-hxhp%f|I; z!KwHhcJ0D_i#szA-;&%Saj3tD^IDDg$^F$0f6y5ay|YRQJAZEN89VTHq1W`@lf6%R z%l|+eu`Hj;{&Sm~|NDMqXrOxK63v!q*~3b!??2cU3cHx^ya7MN0wbQra5c2 zkHP{kXILZ|%^c#YypnLv^g}380aB;zFbU_amrG?7cCvZ%Ju9D>+s=_jSsL6!{x@T$ z#tHSU`c<~;VMBGv68n`O>`W_wYO}`p%#fefjB2bInv5OWSGVWII3HFSdL3DJMYSC~ z8uUp;f3z=uEYGktPM@hl+=C2lY^TICcw@?{Z-Z$5mBT%oeD41t-%+wO?bV6|Wbbi# zAOxpyC0&Mc?giufBNZ%9u`;p3#QL7idrP zBDo6NW2PdJra6w|_aQ^X;dzM=o4o&tE2f0d-koNWj{ngy<>XLFpH%@SHZdEnN#=@ z_B6S0xS6-BxFnrv)Xu5_W8wiCREbp0kyn&o-r+OF*x5%ZXa*CvynT~hdpg#_-7+B6 z5}-xQ7#4iMHP5x|RD=+DZ0k~R^)jfz;Pg-nRx8)G9+^o%s{$%GW_%<|T0Ru}o!^NV z8bFfmFcOp?5pB+C`b8q_+Qeeh)d*S$rMg-_iNQsn-hFG|Q7Qd)E9d(=P6gaqmV^Yg z$)RXkNXcmDfV(?YN8c~otny(Y@s?7D25qY@mYK|^$9Th#f{vaCa4vL}0l$Z(O=azm zRAZsw1HTbP)XbP$^e|b+Hf2;!qZHGrIhF%KY+7QKuym)l=2vZOkS&3*Hp6ZuWlLvZ zf+p|%RHl1TVH%;QlqWwq@rGejMXE)^e6s$#QxbX%NPO5IrpS08m0eeUb(xzQ!4i-c zI%&~W>D?6$cVy$DB;_MDW?|8*gPYt9`!Hvb@Q}hsRSleSIc$LfabcdL!>j*QOv^@M z*M!&{QQ0Pn82`i(qqmFSuhXMrgbx_`z5Yq}x(|0pir53~I-}uNA|6H8hpWZ!@>pLa z@6Zd)+^xli=Qsmrb94)s?AL$5uBf0F`fV#dc3>)Ec@a@gHD0UqJ$I_U;iC>wRp&U{ zpuc!x73^08=Fw*<{!8^R;Y~4*yh~NKCxr=q4+KV0xoTB}=~Ae0Uu7p7wyIO|Vv3ug ztvT7LlXatK5N};;ZWQu5;qpdvlDgjNpH~>b`Ar(Ev7eV zFtn_@1mR_B3QZOWw_HSI=wiV6>>WZ7wZ?6QAbe3im!w;AHa@TM$zUHVRwZ^%#_8~h zIcVQsH4i)S<@D|9>_XYw^$)ogO?lTIDBiXXmT5EXN~2bj=rfrY68h^WhbSzPi>N4E z6_e6BcMC%syN|r`wr`x5%G(>h`Gk4t)$q)oqmG#jfNgoRE3GZU2&ncm0C&W}}$+Gce}pWJ{zp0VhceYtwJt zP{!D@d&XQ}JO$`o;yWk9?#;jkXRd2lZKUvgTU{`$E8YtTr$PQCj~R-}2+f*Eqr-c9 z5Ep@1*4$V{TnDVNRj<6tai`7b1nilGDZCX4wolhtU87BVU!mQ*QWDG7_p;FA%oNPR zHb!vf%d%l=GT|gSbQ_)Ax2?A@3!KScD{bRjry-T5il;7RHoNME5h7z%G0kdh17}a> z>AM#_dht3|Q&}f8&>d@YQ)Y5(jNXMuVK$+5GCTl`Q9?a!CYsF1Y7m zpBO+$3oZ&84dNT^m8LUNx;M>hs|1>VzBW~g&|=;g1U1NdrG16Qk9Z~>blP+YI7TC` zT4WpmIT^8x_2%!+Ex1r2d@n$Uty~Yw*OQu~e+~%^`SX1+ z-sP*Tg7;*W1}#aaXk8}uG(62+usm%PUY0l+5pHU?n#~w@re~jMzu@{(UTKmVR{QeD zYD7nKnj!3bp7TN&iCu4l==|fOgqjF)_o}yZ6c&`*Jff!c_u;QsDI4tFjM7oE?q@_s z=7r8JDPe8pDQ&zB9sb8d0?q-Z>Nj3FNQpJV8KHwZ*_TnFiAU@HRW+3wE3;tYtmM>1 z$58d0RBs9nocs3SGAGl|nvaD~A|wCaP`+773KeS|R8avY*&Y`)*}ScI9GL=^F$X?M zCnkFNIuXmCJFZPb#iZK>IWa1ye+6swGk*U@z4K#|%}!Be%Hz!nuf{~|rl zNLiea4r9?`!)3}iS;#t=qPNl;dd7hp&0=L?FyIuXV;R6F<+|d|KVl`wf`L_`JR9NVp1jzA?@z(>qv-f;}bBnN0S(Vi5+Uh zBetNmj#;EZOmfeoRkU=t8griHL+vt39qSks!-{S zxnAC9lD%>mf0%hwsnQFh0+ElAp?yQt`zazkQ?!_3nvaIatDfem)s3T^JVzZ+hDV38&_U~VxLsf_K z))G)@m6U*gp;PsWS>RYmDQ(N+j{U5nViaMPZBhQ+j5>>quKk1Sgy@SyAvHxTrzKlu zx?D_+q>%cY@;6a!1@cx6407MtS_dogAu5E|bnG^&BK4GcFU3a03o7h%lLT?}?|DeO zeQeRZ6q)8;IWf+lj{i<75?&rUgvQFx_!PSHX6!BR${%*`eGY7yfy){NYhPUIut4~9{ZbBMBil<%a6Mrz@2Mjo$qCWML%;W zCvo1JmJy6=uy1u`;cCQslR;QJ+0C;B)u$k|bU6c$Si4eNDu*lVxD|-piG!HVFKn(S zgE*46In3-seO$%0E9B=)>$R-9N^oj<56~N0wat>I_QlAk)WmEj9|>~l)T2QbSnVXv z(xpKS+-rKXUo@Xz-YPA0ax|A@tLVvKT|uQOt)oZk)4rhsXk%TbPw!bX(3zFv+Xaw< zsW~kDaZ-JN0^W`lHzBjBSlWyoFtB%%!P?^Q6`NQXn}~}omB+FrIQB+`Wi?KXJXaoK zaCl7&hB*&>p1b?ApFiAx`J2upzEih{Cv4h!y}IZg?;i|aDQ(A>-wJ<9t}?VS>xG>1 z1~gIOJ`K5u5j3dynOBn+`3%oI3NeZY^?u8^a709N`X4N@%3JZLsqa<(KCZPxa8tRW z=wxnMWv(^fH>drrbrW{hx5r=okKV=?oqduLT~uXj9nSw4qC-H<&Fd^|KXqIv#%wM0OY)!`Ts-JWXMbK%eQYU@z>H5)*nZ&(J^Oo*F!F*NW8gRneeiY?A!Mt@%~AC2 z*F|U!6Bn-;=|k9H>5iIS^rG4IHD6`85BF&ZcEwU)hFH}JQ_OuJ(4xMnPGVQ2CGkum z_(_^U-RZ)8I+ldQjfn^Zyf7?wpn8U7)w1i^zT`HjN=RUW|D`Q&M8pnU+egJ<^t{sx zH)GeL248Q`0yJa?@Uz8fF=z9kc%jhU<{I9cHq;-Mm}(@h3VLz;@1qUfi3zw`3>X<5 zm2Na#l@-5;-G%^Bv~JaUd4D~&Zz=V`iIAIf3;x0V^|Lwagqr^pfFN_3cELHN_YHb$ z<4I9(k=!J!(Dd{?4b8SEXD(>Lho@h}vgNj66||;6i}Xq@$M1%wrKmw0Dp(R61~@4=lyX_z;w%5-Yk?A{S)a zCz5mFymZ(k6LvXGUN6;oCpqw!8xeR{n#QQFs?(=>24uG?Lk^N-l?p9MUMr_J_A^z> zih=*Y-l#S>bYr`5V|Huw0(EW0Fu z&}5Y`G;ohU%68%F)x9LXu~G@mXGF9XymmvW|Dh?wn-tVG)jE*E&U}nF8 ze!xCUQ1w4HTvZOw((eXD#Yy(vu61nvKZW{#p81qAFf{wVxww3gy)JO92u+va70J4w zLXIfqz*+}u`sjmQo7R|VEdIC(gKs!jf4H(rDOU2h^xxL?lv;!H;QQ;R%Gy*Os&?&; z@2$1qlY_FRJ&spi6=s6QZ!PgJw4Zh$2SOv=(uAV9!%cR0otK`{*~XTMb91D!3-|lX z_;m~Kc(E08oLKC<9T<-5kZKWM#y+dkyYCG2K4lw{PJX`fB=-cg6=p}+N-A{c z3(eojN(Va20F9RWiPP96%_{cUJH5r{=NRv=?mf0hI3$P8W%-1;|${tPBH>_l5+_AM>t{0*m3a?z*!uY7w@2hUmgs{lbmvx0r5P|f$88Lwmj zS>D|+n2ht28g_mit0WQ^n-Ej+PmiBW=Z)V@n<$$u3VMf5fD7)F2Yj+(+TU@t3vjiO zxPaU(R#zF`eaU9iY-|51Pue0ng8Z9?@e?yFJH(d9_7Gn!*}#+g)8yy+BTS_OWXpi) z^&PO?yd;MbN>FgHT5$+Bj3YtRZpx$q`uvbk5xD8^$Y3X#T79pEYE|RvHsWa3g? zEAWK?<6XYu-J{(mm5@|Y{#Qu0M%aOFX835$_AdF`x^bk7NogAH0MHxOSEX8Zh~8e@ zQqw!Rm`^HzU#gc;jgP|V5{PV~{Y(I|woW!ReVF6P6^eS(l)Aq2$af z^f>L{D;f)5B8zF9zG2bUA7?3p$uCwHjJx(yt7)Hv2*_@%wGph!t(r(gTA03O4{>oM zVtli#bM;1yRqs#%8xAU0J2!QZ^*bd|#O8|zx!86kbZP`%9lXbNa(Cce2A!1Zn9;NeFqtClB+g*eGW|W>cvBkbV7@9Zkk9DKFdML48W?T&T3& z=3cTrjJVJzp<^IR7>>1TNNARtSb|+?>T1euQNu?!NpPrgjzK*@Nv|U81~lm#PVpAw zg+eu8s+RA=lnoSe^e%6CwwG)E?(U4cZ(iK~>o82vxepXCQLySQw&b2{;5YaIBMi-o znL&s#fKI{!Wk4I3ifNlIdw3S|0UpU-@$E(NwD%^e$^$%AiuZ?=OM`@;5sYDR*B^|% z42OuGGw?ckgav}oxZG(Gf+V|CT?U!m(T2Zwg{cnK78fM7ypl7M0U0l@&6a03XU*V9 zT3XQ{$h~7Z_1ShVi7xX&>#;TmFS1+Ek{|I)1B7 zvFh$m>)Adta2E3bc?EZK>sD}c+r2Q^xno|(GUQ*@cU@Pl>Z z+HZ5s_D#1MdKBP#r!c1h#ldirJo>1wb5*&zn*^u{(*6D8d6#I~pBn9d#jHf>OghMb z@-3sRpIDnjDqppUky~59ZtK!kz^|j6ib``>hZq9!s`ba0MaQ1iHUcMs8_M)$`X>)+ z2F89zKnHcj{KWNyO@sp1KH{A3*xrt{+T zcu0=tx`y!^DuoLf=CWUs5f?fgG1q@`F2e#_ zi<)%FK)wOWn@JQ9oTlGo&|jhSmN_8@$W9B)Gra0e$n z)m6^Ym&gr-Ai+)G$`161b`9#=|`hZctlXhZD3Mz7d(5nfr$}ykaj6Ar$`Y*zBW;GIXZ%)a3!9*Sn()wc{d1`b! zwQhZw-W(gU12!^wc18 z+zl|2GFJYw4rIAZ56=ZJng&St)D{T}=O@H>Xg*lXD;Cc3WxV~V-_#lmN%<}P&h zYg^YeGrla3Gl4$UG;`6Y1f>`X?m|F!R-e_Vbd0|OB2xqPf0R##cjM*YfqxRGo`&Rx zEUxvdrYK|ZYDv(1vf@FC(Fx}s+v#TR2%SUkuUq8#xC#*;xG)lz5oT3{3?;fw+9qt< zTE)f$Q^!Awv6p0f;zZKxcZ05ySMmy-?scj9QFrFsUdXZ1hR40#Il`Di^tASAR1Rk) zJ5^pDgA(rgc~Kq%y?ScrDqKCS9?yE62k5P9xTplboI|1ntWUa%l9uCyw_(a=^iZ7j%y8RghoOq-qQ)A@WqiQY1)9v=(sN(XEXw zkmWlxB8T2sFUw>Q(M}@E^%Z#b3ULH1?=bW?cF>#G->EYQe)5>`z-HHiN11_mTQMv# zeX#>9Fuj~DZMw{YK8nw}-W5x)4zF2Y=k(kTFA1npM%YAEdJs5Wpfpf0Kr0`aPWo`_ z{}l@>(r4&C)21~)JJ&C2AX_+owd|A#d|oB#I(8Rdv=uHUb1(HvdmHWTWJVnFsz4wC z!ikpV8m8FqYQFRx*4WIOANAuXr%XMwB%HO;>q2c}@2QLLqCzKt{3f5lZ&f=v>9lA( zxHFrH}wd!K{U2wVnQG@BkTD}+oJ2u47+Vlskg?sYaq;i~FA_DAVIIZLDAHIh1 z>U%^4Mzx`76z{MBSS|$_YWJ)>C5C{(qtVp}Gs5dB7L)qb-=w1OvQboN;$)#(m9|3B zi}j%RgtknpDVngFnT@d_q7L*40E+d@fS-L7CG`io`KBuWrg7A}aPeYJF84f~+748* zP}y*7A;_B~>E56q`K9{Xt8h*EY{OmW0;|3$o2bafA2}R`sj&^hN(p;UAOIIY8GPKm zXp;Z)%ejAqLY+Ne8Qi)TmHGXLNsT3hnJ~qY*GXB;?%tE3f86pz1c)j^bG3zy>7*1V zurm?0i}~xD|H6!s&kb>2KfrI)SMwEVGJiGvj04P^zpnAISuYXzeNNexA-wSVUi?$k z-a3VDgw9h?)v@6)vGX#AJC zG%!3|09%jAhR~cIvFxm`h@|Bmbt3rLyL$E<#^WSgUM_r}@L-M!aI@JW#*nm6bg5k8 zm}Z%|6X(9QFzgx8XUa~qs9=V?dyk03VATxHd-q*uB~Yo{?(VH24Ei5=AQ6K&s+N{E z{E|oW#g>om0N?0+PGd`GLvRZaK9wOQ!*au!p@Dc6io=x8ZQX1XF=jf~jPdsPH9S1)`N+XrB6g~P09@i^$K#IU|^P5?Z8k)7*7q8!@PHxn{qFBx1Ge zxs+KN&Vw$Rr{7cW;GJiWhkJTwd;)uOBPe=COlQW)|733E@z!PX+Htu@=+Spncv2Bz z_+@2oCUktk0qEEy(g%#wPUP$AO4B^89-Pnc-Z=u3PL-#RdTPErv|7RBtxqfs3q9BWnF^DDiAgSp9gRX;Tl)`UEqOP6ZN z?O631?#L5k3X|~-XYE0z0rIM~>~}Z3Ck;(>&eK;O_guO~cg64q+3RF9#96HwoHss!}M7`tNwyJW95luw~c*%mlb;$dBt3s;iuO*f51t zcWOjM9m_=Jw`Z8k#l2&OivOwayMRK<8_fg!VF!Ax_B%{|(*?kUKCkz~R%)rA|MLP!vHzz6b<>FP??Xf-L_OH)Wtx(js8c5PP<_n1 zLQ4{a{N9JF5B^p6O9PkYu_*iCA_1boH4It5RA{WJ2!7P)48aVHmfk$VWO#h0PLKN7 zEV6UoDQ0BIY&}hCHP{<I^KYMAFlm3=X zUY(P^YFO5XL0aFt#|cnODCPf*38cXY1yu$Y5*p$5KYc+*8Rw2hMvN1$QjnclPPLVr zu-EKnO56JPpa!$^)c>iL_3}qc1^V+5B5Mab2Rfwwi$RF6U;;lWQopZE59{g=8*@mA zv>ZQb{ar}pr|m(IgYq^JoF7>y=eGMHk3JK1%S+ikA54*IL~vEYEvg9fAj%9!#NFA? z;}HVmeAk-!KkW%iy<_xvv(6{*;og;45BN#%+xHjR5NxLu&h;CA%8gQPhtheV!mj#W z4S;gurlQFvs#vD9BqQ20D%$|8?*c|o;0@hL{HMI7+)CEN%EGJXR9^dDT zn1Eo`o`HptTpm&Bq-HD*8fP|r7@lHh)T6g))A(;+4h&v_pDec#k1it0KB(B`dA9G5 z^1Ba|T#j;iF!pk%y+@=KK(Rx)qpl}V&P4}jO52C4RNaDp!y*c230_S@53W!+XS^`4 zjG8BQ)rhMco!lPx@;hQl`QQH?{^M1fE?DdUFinp|Vi|mc((p1{`)hk`ZTu@&%=3~H zl6YGE&o97_X}g8C>zf7Hf`*S>EekpH$s}sKkdN+sC2~(`B1JbOHDWniW~=J(+(fFP zJ+@3%#RaUNNg`fI_@Rw_6_M67lmnTCzAWPO^Ni7hV#6Rc_cD75hXEsz^tmx(np|C* z4}Fq4S+!aq6F#>%rc>OY@&7AJWr(8*Cvuk}Pux&0&G;iJB zemaUdtRid9PS2`h!8R2ex>7oz&Ix%fl7@^CMhl5dmBEVl&drC+SnZ7y9t*(}4iyUHaDN?9@1la#9HK{{BzB)NeWl zTIG(YOx93R{F8eWqU2e_K*&HXy(6ldox-kV9uEzWT$Okd$jh&Gk|c@&&yf zuhEH?o0Q5a8oP#FBT)3hrfS3vAnhRdQMlQl9zI-Lto7zCnmWKugIP57GjO<(dz8H1^-WXd^czzKb0LWO=&=2`_z%oK3Ly z5QORViU7)U-(IO-H(GO(JO{jF<9X14m9ZhY$)(IYEVCU3Kf`0%VQyxx`X->Y^DNz> zbnWV>(vD9}ON1gvO)HabFz*@U!uNByj$fQqrif@jMYn7wgD^)PTBYK5$geL+-8|v- zi?tS}1)UF$+)#GsVq|%_4Ln0yN?ua&!{hbV))(F)kQytB@{tTT(or>4R+0)_{d=O! zDpyU841-9q$*`nv2(RyE$#%LERWQ53iVpAnm$3cU3S8T;PbXNOkLNQqY$%GTHM=)B z>y2P8tMuI_7<)B1XAXWg=i<3dwh{`;!`DoZvR$TA^sW{);fml7!4|TXkjkap&Q+)C z?q@p8cUE=;q4H^m_|3lf#>PgLVew%$&2{HVC`jo04#YoJ4?egv7?RRu-dSI}@Ev8! zTOPm@SKIs<`@EyP+4!2t>PyjN1DUgQJEcx@ki|z@^JoRHVffd+A zSoQ?8sB|pd{;x?U43P2Te?Vs!tHy(B-TBLN3{Wx>(x*;rjMWUFDy8ZeuMtvxv#Vp~ zGYCVNSAYo>xR8LK+T3r!YMeEO7tSRetrBg^h^_DO1N+P{cUO$JEDTVpOM!qLI05CX zlg-vsTEM?k=h@S}WnBsk>1)`GlAGBaskJiY20Vg+c~gDw<8gA>dG2~%F`)KIsy}jV zx@(oUfQ}bO@TYd;?*VpF0`euTF1D1o3HWmF0rP*(;kDC}i*9ynx_wk7<14=8fxqP; zVKDdpoi;-1;ins=xN;DZMP; zU>eK6bt~>-VO@^OQzJJ%^zFZRjQJoH#v)Q2k>Biuw&cho#%bGsxlV5FCc>@zZ}&@< zMMxHD`%S4D|096$Z}GV%@=up2I^9$(ztEV4?>`#DYgBCLxfy_a+-cQxKah-GAQJv{g zDlxVT3o>C~@M*r?ltaYM7Zrsj8>x%$>JC<$?u1U>ps$jeUY({NzoY}{GTh1dSAza5 zQ^mOWVyYDIKL+*tW$3s;hwKPG$h<)jSf0w)KBa3 zW^pw<@ehay@wN%R%E0h>+RxqpRVWKWM=pbv!6=Li-?t6*9K&f*hxY&J?|A3wf8puU zE&~}zT^r-~;hEKV&u*EfyYPPPzKnj#J|3%pdbWVNTb8u{g|3JEM^Zb52RnsRu?2Z? zV_l=_AcMu>R;@}Tc}JmiZbiOqIn?o%homOA->xd%_p~JqDB=Va!{=EDFQ>YN{eC;M z<@{&(!|Q2XLObu^Len}8?CB5RoE_Qi3tF$JWZ9JWKxA_V-ddDJ`_!0!+v+(M9^>J7 z;OZvOoc0tr4D&9}{Egg(w-zHmyOE4IspRW2+az-XQk-3#_}&xDfF@`9kk0)E^;K7x z*BEm6DTYbEr7Y)Vq57&g5*Ku;1kt@I)V=pce2=mOc=`DOy~XTs`|-{bW9Hu#uB&GP zuI&cv^O6IgGd2Mu4CjF$nP)xX%0`CHU&`w$I)5+NI5{&s5cC2_YkGPZ*-+)=7;gTi zRPQh>0&aKWn=d+yvie5HV%6;oC4vWN80Jlhz^TSNQTR~yW$j$f(6#rHOOl=vJzukF z7O%KR0-rTT6{4p!5YRC^KU`jB{|G zQY=?Qog3kL^*r3nhv2Vmh*+BP5d?d#hCnis#;7Y$!b7-C#!LB_E2eIG^(R8;JHl(W zn2fn#_K)f`4Zdvi2K@tufG?z9Bw+Z8I0T;?y|e?ObG5b=jHuxofdB#FIAHgdyW*!qU5I<;Xnz1xxFnvGT*4QC&eJO>>}+odDlcy9RxoY4(O{TL=HatcZm2o&*1FYP z*Cb~fjDq-pyq|is&QF&KELK1`0W;7jxDFYuBAOxR)34d8M?PJfFC8iorl*c1DMjby zeBAni1BR)tC|Ap5B77CSe0y^gZlp@n#_sw)fiEOchVs$tJg;J;+gOBAE&RhFtr=~R zo3$5N^zJoATR=urJL`>$U}D)t#rop+-Fh3yz_WMfiUp>Trn&u_Q=&&m#;o1idox?I z%OVwP&%Hy$vkk55sN>T&bHls7NO#Lb1;fKOwVIkY-bc<9w`k@tx=; zpXvflnYHQZ0VpT+@9Kc%M_F-ury7J>)$hW-L0ih#XNFwG;QJUkgA-UC71QL7<)qFn-&X z_F6&zhPlBRQ#1uFF0$%*H?{@ zKLIORdRfM|t)Y`DL_Jr@e%XJErDC<#AL9rH5$aOzUBA(^=B6QsIH~5%sr!x@gBEf} zWG*!)H;9%|n*YYeVsQr`xta zNz7kO21!lyPc&uYOuNhb@VqOi6VW)mlIunH%Qi}7B~?VbWFm7R<*Gk2Id3et^VQ+w z+K~^4P7x536X_6bOx|UPQhP_%=14S)_3(A`cZ5uj47T6M1n1IrY;s44&=TiauY3J{ zw(1`QTOV2wO_f`ldm?6G2$9tD8_|{E^VN6!_f;@Hw4!T)x3BOipF!Q< z5?Q3G{SGo{IqUM1FO&q*>fV05nsy}vwoTRg}5AXNu#h9&AjAQ{JB#a2VssRsd_KZ$3ow1cdT_t=QK zAAgnMr&a4tzWYFhsNIJjy{;MGy;fbP%sJnzMCI~)h_Y*N zYd(|_?0Qx{x#Q(BE8HI&^>p4acgj9qB9WwfB1o4YG@M1A`5yzju%KBQCweX}*7E#{ zcR{n{6ABu{VaX8^~*?=+&mhMUg`O zmxcT?rL!+iv1Q{nd@jDHZ_x3be-Dm}RVixsVs8qGX5askec#3+bYhF%HOz$9$QZ3lwKkPfNIJxm`rhh(OZZrBw{tdCyN!#jdnhoodvk3<(eKBL6 z4#_P$B8HK!xE2_l`z2wKsEtu*W405Gv5MdIq#}QMv2yI=P1!>c7Ch|*TUgE|vVW&T zD{87|WgLF_>z@t_ffUz&g?tO6Nyy5dpM?@K?ndb3jE<}KNp2@S-u&(t_ePuTim?YH zl+dp=%)iH0?*qpChf)8PQGI{%_yLtX}36CGOY!1SLT znsE^Y*S!oRZWi}RG1*H{lLO1Iob4(zGs*t9P&gWs@osJ|rBfYO^e-umdL8*2lh;c` zZ%9h;JS7rpHIjS{_`}|KhV`2&y?XfE>)YkKiY`W8% zSyCdenl1yc_cy8GkF$EyYn>Iwx4XY|UM4PKfmZ2z_`(Hiw%sDv8$4Wc!ilEI8)oTy zwM^x$t0F+@b_P|UQkKwDH&at&Z?Wz6 zp0#hHt-gumEVv->&rK{lmq<+IgD?ie_8wsN^8diIs@TbA?bKbGP0Z(_x3)#y(q&}ygv4JdG7A1s~jRjh{6498BCemRUBDb z5!oQHDs^9u0&SR%QtPKiV2&R8_1kWf5QznkI%E2QMZ;QjRhV)T(!GT4Rr(Ej^>*t? zlVOATZvTqc2q-rS9kh_p`$Fdf&I`z>&|}z?P0CNMj+L0}7*2kW7rT83yht>DdH6>} z&De>qguWx?t} zh1R@DlmFX9sJLilGKdA`(rKpMExLfpWuAK&E-a8};BxNPD9x4XuQL=8z&tP1-%>w? zq|CzWDj9a0tzaWvH>-#9z00Ak4wDhAeB1og%U7y41L-cseDg0aR?L zcE7N?(D{0mJ{!ynPcZC5O+D_ISA*&Y@A+9wZ;ra^5IlB1 z4%=m7EapL^0e_APNj3+*OwDT8JT+y-IJ|Z8Al@7pcB39Zh1A>+&IyT76_?Cigi%IP(HB&UsZE#a&u;}5FNntazS=!FccL$d9Z-ePZti9rEB{t9Q%n^oPntp+p zXsm_~a?p)p21Jb+oGPgBmQRV*txoiU8&0FU~*uHaSOmj??e+Z zBAHzH{9xTo`Z=y&)Z_1B$*EWGVJ%#|)a`rwBoK0Rdu0dTe{3yr^W$a$fB%rd4gDsj zBaY0t%DO|>_O+0|I_OF+tA@{Pjl0}r>a*3VT^f(ituuK~qPL31cR@e!&zj)j_F4V! zK|_7^%|d!5%=x!)fdP1+`wsYBa!E<8k{YWU-Ag<{j3O+mLH|Xr6`1@BiZ!`C**^rM zC~I}xph27aLj~&5Al0XO$kLzrTO_CVPEo~uT^4B})WLHjX~0u3G>A8ECM+7ml8#mz zXwM9qh&<1kJ(-Yp;OX&h%9_eZ4{%8xpy`E0S+m-V;NSmu1pQi0Qq5D#5f6?Y?*;Yl z@d2nXSm;5(H_WN__M%ZauJQcLq4=>&Zu$*G>$9O{Um2yOjy7(61Q);vcSwZ(&|?si zzhn4u+cItNtKT1xH7{EI(2Nvox0tT#Vi{Z6Vaw-$c3=rB`AHvHl4qcZp2$7oSx`&k zN%;XsZfn-hs>^GmvYCNTykk_!NN)ANibDspVR(D4AmE7h=9k?{zPzgBxF{HKBla<+ zwBrPNH#w5jkFr|_(N<+8z^%_YSfuA3I@euSyks~aiKj+gt8?(({&e4swQ1@NATz#`kZK%q0%>7N2o?E*to)0Bocf)DmmIi;$z7^XlC?51zQ-qSywcPd=tbe zh!gghOhBoF^jPhWm#<%A1ve`r)%G8(PDjJV4woQT*HvjXw}x*Mxfi86ZR2ApmVRtd zjDI!aX87Re`=Lq|eg7p*pPSKHNIO%d_~^s! z8ML$Fl8QDLpP!^rUVHSR^+Sz!MMns?2~mCmNK}9IlWsS^piJ_N!jfg#-}t&pe98fo zpYaUjk_P@*4l&PV^q19fjYVPRo?7;$N?O4`bqUju4z?Q=rQT z!`F@JJ2bSIm7u!6)-7F2*it&)a7;URcxmx6T7Xz>yhb=$Ic^yhgS>GfAjA?K^R<`O zN*(}oBY~qZ|#Hl^#Js{91OKXU=8 zCl0Qwrj~vBd)OSO$0N48Y8A+{df--U9Kyf(FEOX>FM)fMY#J)!(DNSZnL?$JdJJTS zbS^0V=iNHSnRbcLCchUm$h}S(=kzsVrxiH~IvW`CDco0d`*G6#e$Yd`3?laFHqZZ6!kQoYh8t*ke`5w4ivgp3x>c6~S$>v%FZ4~bDR2U~Bf(1_S;vOv; zPOc2!vcyxrqb^+B%4;?T3^k7xLK}9QQ*Uz%kK{>m#i!9Wwr_K%Al-IgB;|||-Omg+P zJ=q-(TKtY(vcDi?3CfpYJW^ZnRbAyt$x%&CoP5zMzFJ}`A91Lfm!eF;ilS{*9lj;B z;iXu&R>FqKHRq_8S}sw-vatMUAtf_Nc#VIi_FkoP>OMa>A~T&A2-sZmJ3g3a&J80S zKE_G&rX`A7_EJzk4#}2wYYNr3=*?~_#+@zEwGGIjo}!qAYlJi7tj&F7^J_rX>>rX0 zozA4DwBX(v@QqXBP|n_>&SO`n5CVt>ccb4Zq;i*8Z(o2IjF$z9F3?JxHDX2~*S*W* ziOUlnO1@_nZuk|RIP6<)U$`l2NAA;G$oA+bb>Fx$!_e`2R^*ae8duorlTqZAbb_3N zK&hJO*=eFSILPFna=EQi#d=XhH8(6JUp*Ez3wpEceV5XrTB^a?2R`7lHvFfMTvJ0( z)Ow@x&&Ky2To&$4G%=V^;k(8aRde3WTa8tyRiJVZV+w+;!4*2RgO#IWC5fn{4vY;{ zZ4DaaxXxxf^!zOQ-$>AC-~U?m^Q+4R=THxcY7$Bz2%qOlZzz|YB(SM(lq`OdyJMIG z7dJCOh?ka(V6&dnvuW-}7Lyp|ohL2XV)PILmFE*ddUc@l|v68TY* zi(svA=c(=Sw>iWOtd3Hdd~ZkX!X}2Vn+(!8!YI6!jqMuqyH^+gEMRryo9Lp{Il3)6 zb=|9F8%=k3o>02y$u{N%j}ci}&b5%eJh~IOr0!d4|I|9e$}gHKZI^g}`o(FAxT!+Y znt6BAPseBKJzv5o*8J>8-lA{w_)SL{ewa&`(0VD9=jsr<1?HZ|SBo)>Q`llB9oPpZ zBezLKVdW>BHs}wu)n+w>yLV=9`Ipy- z7%0xVX(!45Z+;5t`6ck|I`Ex~469}CZ!KhglG*Mcu799 z`XozwrE&?%D+`r-XM}6Gr&b9YFUW&QMTt@=$D5lB*eCUP10$6h%jEB1y{MCcsvpdOo{_3mI1`NBX zBv?soz4}B3DP2-QFytsX}TRbse2)Xfz45S1)M7Kv~x@#NL%J`rX{8)y%;JE-x3k zzQ=m|;n9eu>qb!-&87mP{R4=V$;8q)ZLN=A$yK&4?(OaTcOQ?;iiO9kIWC^N#BLk0bj-HX z8w~3ibG0_}Ivb#8pTZ>IL;ITTE`!DQN}7_krnmh$nxl@oGVViH6lQCl?}yA)G=6+U z-J$2>%ATgS3WQy<8SWCXqd0TQ_rzdP8xRIBlX=s{OLXmX26-iX!1GO=4Sf_e^jMmIJIqt0`dsc#M@ zJwETjw4lh;+tDJy zqvt6SC*}=6{WHYO$S6b{+Jf{NjT6b$QY$7&kb0r+iBMljlwgmWppc*#h{SVCbYT#crJ%N2k_H!5Zxth5w8~lD2i=;@mFDRI760^Q*=**-v{a zOpT8;ussRUbJbUvV?TMU7a^+jsX?Dx`L;+I#&C-*7H7Yess#t@^L;GftDCb-4YOCu z=WyP;%1KZ$RA^kJKN1|BMEZ-Me-}fNeYR*U(X^b#JnBw;YHNuVvpl`=cdw3di?UVr zb;ir2hVNCBSF1VGQn>NBJmPzrNTNk7wHW-22cUPcqo>rVS}JMPus}?n`DwaKpS7g{ zo~42BtfJy_2+X~=?O4Z2!})EY$#3Z|5?hd`o>#pqKW7ib96Fj~;unO6-{AFHnUQP2*{J^hGhwOEFG_ z_!%YGLXHj|#E8MfF;>Uta6W&77sKXydrv*9pJd*7UUps%)$tF{_(IJar5Ch71aamB z;@7s&K(Q%bXF=yZ*_T>a%QfnHLN!dzvKLg?j3@K32|{4-~iGqXdV zoIv8SBdVMXS*nqsgY!~qP=Y@h>7gm9`G8-SH8m9Svc_Q%N?RjOjaE0T4Evev4y#_8 z{oQ>`g*~Vh=+y$=^I1ym=M13xkpg1CW%A$DT+;*S)AymVF-eCgd`O7~Bj@rU08HuN zs3;`IKjM<`E~i2Jt_>Y`l9qgczs{tE>w%GMq5JPwaw?tfhKKuE(TI;?bJZaeD>XMw zxs`TLZBNn z9IJn%{oy$+OiLqWlf+2yjeUAV)51jaePWDXN41#(mxi)=Uv>5D11(njBWd+S@e`QG z_d?+m@iH+Bv8S1!2rh{%<@*%@21-cidr2Ebo?)*$vM0CH3Igu3g=&UYCv&6rg)+CR zihmGuN!R zn{5+fjD30&fEXCkJS@Uf-!cuxT_d5xcaS*-v6n=rKNZl?bia6txpcdREid{DnQRlm zPHZht75V&9-%I2YffZ#-k89th!fzp{KnN;_c31S*SD@g=fJNJI=icWpnev(GOHQ=z zc#u4T(+VW|2_y=Y{G`?H2IaRJ*f*Prz^9O=EX1wr0*M;))|}=kvWxxhNcZ!Va2u&ZTL*nQ&wc{xjs{utAYB?` zUDx9!`F)pug1XX5K61QR_xiYH4v7o~6bW(ACJ-F&vDTZGEVewxS(dig-^v9dz6p2?J@8Jca=oqe<8 zo{xh3tAVK4oT`1#Z;YS*0@>4BBr{5t@{Xs2y-KOceHD9J8Wg4qC0ed^c~k1>@-#%g}xWYL~+ zB;3efpF-riIPu++LH4{w2PY3+?xe@0%1jYPlBTCeoky$U!14STNO5n%-CZ8WBL54f zpYtP(gS+k&>t1vKOd<9on&)Td*?lH&gJCZ^Q(M1`;krl^uv}rK*Fk|rC`$T#3JV3v zs(O<6u-C%}#PgcxBAq1GN@OGM zNf+#a89^735o~{;=J-Q==kIM}#y|FClIpfFn3iH$!AUM??D!8BLv_mC8b8+jT3wKH zFiMX>$40|tn_=!XQm-_E?~hA0?M6~rmyd?v9!CbdD6;ET&xKd$nVP0dbN zF=9rP=tqf#7a{}Ls?~utxz3(_vt8V1~^sX4iGRBXCed5ezRAQXAkkfas z&k^kFoT4R3+s#xHoK*Z7S9Htqn_F-K$2MtQ(H)$ zym2>{8dSblV#I*Z+K>|Mwn!5-VIcoRs(~&F{(wEzF!~$aR5$u!;$Zr$=OFo_?_p#14kXU}sZDjR>)hhXm`JAqX)QIlXuO zWSVov+hjuI)??y|;PqZNF9CH;iEPkf9B4<%^35lDy`IPh+7tuj=7)qQG7J-`@vGX%q?G*M8_m-vfce(+9z8vzqKse zZX2Q`czw3vqPxe%vF06RXsm!<)K*jd-91_@^MRMl=am_#D>vXUd(|k%glyVS@*MweYJNE@&4|H1-%31H@=3pmsbwk_a4`sMC znrZ$txU#MZ-Q93L_-uih(f@pvZhWGA;k(qY8+||Z_DoSCorFce8rhk`%ub^Fsgvt6 zFSBnfJy5-8-3uJTo=H}XSN}fyL=2|ScWSZjW}4x_0#>S09Qdr|Nes?`Zok3vT0(J> zL?bfV>}-RgwRoY4?7 zx|zF$w z5IYIA;?Uh?9ahDT*{=OeuCPjP>JG!e1v#1J>Q#f)sppSx0kP*d#AK6%TligHj{&;# zb3SzI_6eRr>c?AKwijildheHSvm_DO-Mgl%mA<*LoM+1FSIp{{61|6-_>a9Sn)W-L zG4x)~-NMui30n|`cs>HCMF4%ZbbGmu@(6SPW2t)v%*;Gn83$EHi>%zeM;<&ev|J^1q%@rw5sjn!1be?6klI)A=4~LGB|(SPP3f2+ zxjS}GCDqqGhN@jP)oP6-o$k|4|3)HXsVKMXt$P;uGRD;~2yQGAc_E8B0TzF+4ZZpV zOIgVYKYAIeN`u<`J~toNR6nI&1GRp*R9oeoDka9{TaVCvv=_<33ADL8MUM|^js6tY zP16uo)ULXe50*AnPep6FQjK7uOEml)5}!{afUj%M!DN}Wn7I9#AzrpxxtRDGe(N#O z)$N7yb^<0;fkI#hErwwKTYw6r@{J7DQpw?ff9dy$#r(cTqw}hPTn*O#40^G;%3P>z ze(f7%j!44E*>ahvfP$rt!>NWVbNuNO(`dveR_~iz=%``uhtp3!zqDqbdFUs(nxAEN zq(QW=l!9BJqLrn8*6L+(z!N-XYHf&^JoyrxBRJGKg`Rl1vE}{59!U zh&WT(xF_TYN_jltP%v#V3^z)_^vPQK$YLLVj*eg4Ldp4Q)pvA0X#t3hf&9|JXd}b` zI0jxe^`)-aS_B#Y^TVLA*ZV(q4bax@GH%2h65lF7k7Bk>5C%HapoihQh3_iR7&(Y8rIx16n{Lymy=V;=@?!$}+}!*rB;I^S za-ZO$W=Df92$9@pVM(4{CoYzDn?G*(F3aTHhlks7$$je=4Ny`%gSd0Qffew)`@B0Y z|GRwLzof`^%o{YXSo`bHHYZ=WilS1xj4wCaL5t z4Ee=7YN~8WO}`$UD5e(A5riLc^hBqA6kjCMjNx{!s?O5dZK2f)s}z!@o9m}p%5-sj zziiBXBv7+p$)vt(`+}T@K5e;H5aOa-v&F}9Zuq*DkA;=|U;ArF?`8LNMUfWKa}aCK zBT_Er;ZT7oeree7&VV~sI2W%BP;;E*orjSMI**i%gC=r@r0Bh-pAr7e1;&a4 z@h!5mCgP)dx2W>F`_IB`CWJ?`vjQ8E7C^Q;N z$zv0P&+uRBRU>7%%XR}e^6lykb@OmHJ4u(ql*(DgyF@tm0}1Fn&&K!%x4KYo_1*6) z-%>XE3S6h6LuKRcIbGKU9uC2@#C46oleX^juXrJ}&|bNJU#X26CSB8CpS{0&Rv*6J z_z*W%rVGnf0dm9Jm&}dbLJ~#o$F?p+SCxet=$t-3|x>Zlrf2H>o4ObT+1fW3z>{Vn8@>_BrzQ!t2 z?Q08M*{o>XLpwwj_?5)C~@Qd!!GCEAGriWfcO zZ7e&WANdb)D19OJan-Ka{omssT)q0)*ZjV7Y4I5er6`NdcCn{aeOj#C{s1-L4ALh% z^~zbN%u#=pY|WhAf5k{ zpxm}91!17L1C)O*Uq(*5?w_=9`Ey$%QC!4@4Em=rsPe5tlz6kgUeC}rNw#+P9o6%H z;fGEo+2%yr&rIYPv|mq+;1zqb2#n{h)_y2omwBvyZLGV!DRbr@;nzg8K%_y{c*pkj z9|ELiehGOL(^U@S^7hWq-0=InV%TiqHfd)*0ppA zwlvSu%@9^Bl{nrv+kQxl+3+fXHHZ!B5!P=~l?{u~*_7F>YYwaqPNgUp$_Q@Os?tT! zu8e{=zXw-il3X5FIcLaIdO6oE4)|j>`I_(raqBMVvZt^f1-mlrEfg_NETq~rc5c2* zHMM5jxVXcjg<(kBZa>oO#HvZCA1eE(@pb#N&u3YgA?w<*`91}D2M`el!Vsq}nh&H1%U)tN^h& zX`)>!!=}(O-W-{i_2ip!Lvr>LA37}Eh{_TV_s?gB{LIMAG@-fsV+ zj+Oe{OGE|K>c=cT55fZg6%P1TtVLJR=`mw372dlB(_krQT5Jo#U&4*xhBnafI^n49 z_ZOnN%bES^Uh1P8V%bSZW$3rV8v&8;=~B(9Z%mcXA>dxM1a+?hjMkwyE2Qk!jIEEp zWLY`JryDnLmE)h0oA6FH_ew-WM)fL#+G?h#BX74NG;G=u8h#!^5 zwvLZHJs0QkpBo}f4eCscr>?PUDnp5n3hGD%YACTQg}avUC=7G4AT5*Ya+Ryo*gAB+ zUC!kuF2iXiLUmiJfn7ncwrz}Y@>R%2mffXr5=9CECCESL<$rMK?r&gqE(#V_8Xqp> ztJ8Uo8K0~ofGLaBVSNDdV(ogM&Cfy-dX5N@5(oVisr+cl>p>4&a>s`Sc{qaRs%dgc znfb$L;SGU@*?4s8fscq%jUy-V${|RbnTjTfypGC=t#+w6(Zi-c)-%kR|Hynev zwGz66bz2)GlXWTV)7V@MKtuL*;sKi_i;n!bZUQew5sdB++otkDC2}FSaU2o5x*$7o zV~HG9GT2@T#XQ7{!x_GAB60pi6z*&EC?;Cu-cE8(DLfZK?+V0ZT}~oHlc~kYhF980SX5IcO#bFC4}shQo=# zy}Fi)N;H<8Qz?wm_tW0WOqxRaC<4@L77~G8ATGGpZhv6-%|;xc)4Ej6d+e?`^5tEe z>ZB=9UTNU;mSb01Ao7{51+qtwOuoT8^^MusO!K_PTr4r!4d%Oh(BjdM zK>!hUXjyBg8xGC)EN3%5)(|n8JvLPQ$&)oW5N9ZP_(B`{`ncVQBEcXbq{vCjRUPyy*4fB(q+JN2bzeuETHYo3wW@ z%U@VYrvnmtp!SIVC2xOD4UZ)DR1!J^TgEUg8FA*eo4)?~DHKZlCHO zzs0yKl_VDE0|SF{lgRs zqP#Ky%mKmd)#Q)v>FL-XHh)|6b2~M(etvCrvd#isf#uP*U@U+#)tQ^&O3GE#wgMRvGWzK>S@mnJjaj@I*dvjW2r5?9MXXAd|7k zk*f|?X|%3MSY1tA$UTqw;-|t+!0RYd_Yk}83VXz?8x7nBCJQ|8|8?QNv0q(m_e7WZ zB8T!Or;$QkESmDYh~i$NTz$*4IV9`1(!(#AZD}-Lk_hwzQ~S0`P-Cr z-#tV&Z8+j^6TQU0nXW3UhYfz)z9d5@<;r4eAVLS9k*mJ}Ne=yPfE>D{meZsyF;t%u znw@{9fyY+MQ15B(R!Z=dap)u!dLvjiB*RZZ7kBn28tA{bLvkM-_A1kj#{)D z<_G>F=eb$`-EEuI&!fr$`mbkY*=fc(fSQgpPqs0Zd;nfxmZZi~SIXB70GdDxE1`eO zM=egzHt|a@$XO2&9q>u-VXNc!A;{k3>&PDij`!spe&9cYzinB>7D?(WOC6v9@Ed$Ji0cUq+@t=v=4r1y*vDvA3H-(QL#EAZMM2KcUP{g^yKg` z@36&r}Xaw&LqZvRwEC5*0U2RIpKDSFc`oNP7EctcR?&v@V5YdfXX$OiLy&5 zKDx~Dbxwp%YfyC*)&V0Lot?}0H6V2bEFgevV7kHlUV9SXfagbifQ1-Z@(4q2lX&Xj z*ELi^Gcdq0qe+!rFBSfo5~A5A6~TMjTO<0nN}L`qlxMg|@V<7Z2_%m)4bG13r7Bpju}-gINy~`NduoefL+5$!`1MXvRreEqj9_jfm+SZ? zRcfe#c!QNzgWi0p{V=p0&Ceu6TW9#z_SDKi#~6BNN-a)xr>Df8;pC#dp$1VM0--d> z(6Kj3m9hQkK4_t4`cZ~M=do!MZ#W`bb#{juwHZ2PmpEld$-A*s!uh#y3D>N6Immi} z!rS^3UlEYYZ&b{{Xl2)KJ~j2+;=<%LxtYR_e&ktGG(v#6{tr{V=`BojP5xl){vqX) z&rLL%5)Jg0GI;y-(fTh8jPIa#UJZznf27wKyP6r6-X^2eI5yMSzISJ$yc0*&?C?M% zl3x?E((uwu;5@^90zkQ#kuKR$J9luLHDlXpzNGl$ z90I#IkzEF=zrZ-9<*Ute_e??fIMNPufhP+d6hi(2Vt6#|hl+#0xKU43$tf2a$5htzaF)0OZ(YnQH9fw!`FCdOiQ4Yog}-7LfqE z(MZVk5z3>DPc`%)Fm`{kd&#!#imR;7jXg}u6;+9lav^y9P--A@`*+Yify96cWfX}y zDX9EpY1Ht)8%1I37kOUPq=ktf=d*Hzawu0Xpt2!S&_)$91MI|+gIbK?llCVPKOdOoJ_B+VHEk(jQ zaRl1YQ{DAXHLNLv2!O(FFgIdk=By8$D}UIr7}_5G4zRo#WvGj%CJ8hJ5CQNb3wYL5{8 z*GcIzJyYb2f;fdSUfUK!(X1>xm+9ESIsVSeZH6qDGbEX1oJWpnk*IQBbn)(P_QhBK ztxt&~2aPA?$`dW@2y!rW^_9Z0eKDLlezWR#g9P&hL}9?g`5K(H#JX_|S-y3$8`a{& zfeT2i5DYCiRVv|jrXHiHU0*7Bhxwa96@%6@c$eQ9At`{7Yh247jJ6wb5~C)!mO}h?o>0r`zeuC_NDs@U!8Z6;{0gsf4l~!I zbRD8^_4hNC0?X-&aR{hz8fd!Xo*Lu}`P=5#kE*#F5Wr)v0%hu4^p{?H&Gb0HrN7%J zOHOQ4MTwh+W)Q$^s&ia+dPgMy$x&PIDU-*UE~3ldDeLxID&9UPbFXM>zLn;fdZ&9cEhedu|8qk5(hrsiXuWn2=R!1a2L%Z$|1Br8vyxH^eM^}gQg3HCkXvA!Fi z(;fFtBi2}z!X6OjM#QELZ z(+X+djH|El7@S*;|DkqZI#+Gy+s7lQhjS0Y0h3lIpyUxUA9)Fy98$OgfHEIvB&O5* zP=z@lTbkY7E(*Wtv8s$MHz+%9#V}oJXJRa zb(R4+aNIy9c+rqK%Jn=_38lrF!(R{ysvlW}SH=?i0tSay`~J3PS~8_W&TR`=vZ7O( znUeN-xZJ4TzGN!$(em}nW+a7l()5kHQ?A~a9*KLxV7WxGP`WY64fYN0n5HFgiN59Z zgGNiJce&*5snR!0M8T=xiGf?G!d~u$CB3^p&fgu~WzXRM>1B-)b|9Vg;SL+rhf)2A zmx)aGF#=8|G1l;mFuUEWc0-Fg&%`6M(xYCSPO(CiFfgfY?S5m ziB~KSp>MC1|fK7|JzPpch$mbqVl!(FV0- zq@i|;Q2RV(#b#EnE5*9O%Zbqe(KXlK22+_~EOWey{4%K3ad-_vukMuyfFh-0LdU03bn%jRWK>ucQ^Q5}!jbS5cj{*J4Mek1hBoXVI1S)o|5g zmuXMh>4LIXmrr*m{Mjy1H3Fk2Oo>t%9V_h6L?c+59t-H(y+uG^O$U zHun^zC2J|hjw?SCO5|}^iHdA2hTxaU#|1ritalPX!3t$y zUz461x=Ib!-?oX#@pdo_abK<0LN=#H|nx; zT4eds`%ARKrJ$svt#U#B5^iGQM)LbvY4lYw2|7We#0DbziNv=MatMFhL|h#>Ncn9S`Px;OG%s|Mq%E!6EdibRR@?yJ2*UeY ziuS{Yw4Zg9BZs~^Pdv|CW{N>hDpfv$1aef6Pk?XYp0G?36aKaV9VV2_zZn3_qfWUj zwY3i@_O|};&Gdp<_m-`}At&{z4v7<%i4(Pcfm4!{&f!$i|JC`6U;ius8WsRvLdpHt ze)NxtApemI_ry!_1ZN$G%D3|0hj^-<#Sc7FUA+l1vSIIi%auG!MhGLyi1S&@JtT#e!KS-pflQ( zqf$tG5YCs>qBgMNr&I}yHLQT*ffl`8qYF$C#H^qRpw9=?a?cw^0r)*mLahUn!W3Pu ztxclG5D?!dv^)feg4-M70bShYvAu3K!=hdbFf_mC3)TAaL24&&RaDpHyOFmzxe4BP zsZ?TXsZb;RAb|_ftVWHY00(^})8(95q(dj@su%DY+}`@_rV>_ZlbPdDBxbFs3G2x} zfJtxt-uKt}fs=K)MSNaxuW8+N@Esn|O6(<>8jg5ExzHO>$s)^BGaaQj_Yr!aLH=MS zj$T16v6);Tg20S-KVGJxrtq@o1wv#eXA?uc`OSW1O1dcRYJ!^YTXzz4qtg#EUiJP& zn#a#q92&=q|6F!T))!I4uo&zew$vLLWG!#Mmut!~f4krjvp`?&#jNnDE_V!<9{l#o zyKlvAf^Y(@nCh`#s{YUZ>Si@CrO^YrCyK7yW%@4)8v|aE+hJBFZWD@BS%;aodS(87 z4@y)7%NhMfkMX8AL#O$UTG=;WkApBF3`v-q`%&VH0 ze$qeFTy`@1d`evBQJ(&<$iZP2l>51-fR36T!R+kFnW)X!pNF?g-Zujl39W+N0wSVGAgF1@zd-WPziyCZM6doUdT7hXR@M`>L@o@C?riqdDr zft7DIQhgrpPSW-BJc_7d|J?vzsAuQ?NtbAhDi<+bFHLq^Z1b^QihLSyJ=o-rVL}vH zAxIO7LKK{gGCQ<)czL~I+&r-Pw9(;v@FMjG;HLFyMh(~wxTwEhR*sMN6-ab+s;pkL zm5%8vz9Q@sD2I1}03pP+_yI7bPX2U8Rht3~yWRp^ZRk@Gb7#!hKh8aSPvq+a!WXFD zo%KXJ-7A1Z#L8U2Xi9YoDBU0N^>kfD-rNWDn_q>8Jf{hO{c5iNLAm-A3*CTl0kWim zfl?3?03b);l&uMbN7(Tc`}U||SIJL6kLO&aeDbiV6qHtq8(`slUOkf;jgSHI!W%k* zE^6!JnMc&dy9oeUDB#VzGNhN#Z*6)RyOd(ybF$%;?d|uw4g7C&-L|eduPQpH(8NU~2z}nx^vBN&Sd)SUoyQ zBTM~ptHBEn$&Ibre&_Ailq*W#0{o=<1E+iw*Rty9c$l|z_dW!4@We)Z+@fKE zr>Yx9cr|)YER$$T7?w{LZNky}5*6v7*De-0u_|OiF%&2OVW-%f>Nz(CPEy0h1Jc#zlj&vm(1{rNi}i)M2P1DRZs=C`7_zqd#JQSVz< zQ;4I1%m33Tb5vC8vl6SZVvxVcEqWKKUpjY3*^ZlQE}nj-g#!qTUfI1G^Q(Osr)lGK z_93yci%&%*<{EjW7{oc?>j0`cYprz(;O_&Va-d~8{N<7Ovd`luWX~Ccw8v=)hP!Zh z0Nck?JqEy+G5!HpE8pNQ!)-HocMz~EqIZS?K@|K?)iwi2?y?k+5z=`OkQ!DhiYx;1 zB;lo;ZB0IM)3jvFJk*HCw;5r64^ZJHo+|-IdH~M+*jj*_EO?v;hKx_-;v@Iw2#K5# z9&NJ?=5j%(vBElEL?x7t#jBNl9&P9y|L?4i?{n{~&zu1v^#7)w1*5QyctVE>H}5XB zk~Q)YC;pgI$_F=IvR-%G0tG~sfMFG}Yhwfzws{JMn{IV)(7*V{P=2|X16>($^m2GH z2zW|r*NV)B-ZaiCG#SFk9on9k0zH-qBP}h=sp@ckcP@@8tX^X4_xCGJcJdEnraj%3 zI!oeWyl6(^x-9UW4?J7Zr%g<$qrBs4uQVTRf}_WL6^|R6@ilZ-n8!{}8E#9ZIea|O zPV=(L8m+>t(}aoUQ$BHfI{jWYjT1H=uMbM(4l9{uVvT!OT^+hdAxlpaNcH|46+f}5 zJTcU%X0jRilf_o&#Xp`hS`gCuFpSNI&CkDM%Dgb=KqqKIJ+a^tCvEe{umhrgWJx!i zLHPNmi9%j$xH@RcSBTsK!(hBeO~;BFW|aUgnjlV;q~IA-UVq70n){ZET$9vcYu1Cg zZA?y=_vH>|DowCfZFQ1u7ed?oEEnhcW7}h#oda#TX1(PZpBJ*D^h|>a4!TY zUV=k$clZDH`QCqq8FEP`lN-)HXYIAt-dm@e2iJT`WL_iCF!tW2*!A!;ulr=YpNl)w zEKi!`Xf)I|I5zulmBKSc%TmMV%zY@?HsCHinWGvN?VGW?Smg`lb+(ZX+{hm-Q>OeZ zn#=f8pF2`m&DOi(Cns&g)MBB}BXLH*bWBpePCk$Otb^my$`pW+FblR4a1ALg(0TjVTpRDU17y{(xC$6soCNnQ{O;*ppQV{m` zSc$4od(_Y=&F$A`UZ4sTLiJ<;PImG`?|8Syd`*kk&7ubJhI4C*WpCvOT8ka$(aiBq z`3!gZcGAHr(2M}EDv;0fld`|Qo-#Fn^6ReqY44TiMoM#$o84drTp%r!^vrtcCKgY&@H(d2ncIqhuOok`Jm&7$v z6KbyaEv|h_J9944Ji-39JFmOzIDwz5bv{+IA1Jp!_u1XdK2P`Fnmaw{xIVvS%WH6# zx2hviTZm^-&a?#Z<=m&Y3umE~yk&$_zM2t3gHW?jyx| zaGt|ndeWrtIfHt^wHA!Px98VQZWg8U!}l;Rp~yR7YwDb8C&S$E?T6AOpKZ7De3l>{ z^FmCG@o?}3DtcsaS2nM4KBm@qxcwhB*`I<5r%Pn>6oMhOMPnP(GW%`ZapzEsJ9fmA zMu~#M8km7uyEbS#q?K=TW{B)^KPP;hT|`s-ri_tv^`=ty#01;~{+mr&7Q|Z5uP;-Ho@O1`6)d$Y$iwt+#*AB(MN@K*-~rn=#6Qd8na zKjuYejbA){i)H1YV&t(NeffPX)0&lMfg32kWhxj$JIb6oKpvu#OJPtgNc;TqyJE_Y zq#BXfgFUqtzBHLuNz&ryQI{3mkENq;4X@0^kR9ynofmJ3J!j$YpZ1!=sj++6PkKn> zi!$dz$)2zv2Q=1_S1}P>nF-%~L+qK8kJe2aV`4%@njG;!0aiH74YYt|2E?^D8uC1QoG* zkx&B5@eRQa(=Nn20MSg#`pt6zF$4XBrfG1)7C^04`Y`=0bl5oXMu>_biWw5j~%| ze`!c`;fb-N{HWcIw*QW+H6*zMk2a9qss2cseGw^E@{JwznJ|GrN5N;65I04`<$Vr6 z`iKVvKEZT9e&Em0jMHd`-{Zs5JP<|q+5Ok)AA<(CB-+@V35!M_X4=x4uO%Krx9guqbXvIw)zj*TRf1$n9!I#^j@a;<8nI< zzUa)oesQ#27fOkXTyVT=UO$H4?b6!MAQP!R@3tQ!MrC z$;a>TX#cGV`4Z&cbaEF|wlUS;x6>2t>IkluK95ckchv_>JVYct&&&)9@b*<(o=fre zMS~dN0=#L={A}^pW}7U`#o8rT0`w!WAz_gEin#qu)>SN$gDi+1T&wlVBKG@U=Ul`PlOVh7FGquM1Jm z;F3>pTsMCkBdEv&IrIPhML^To=Uzv*>2@c6RZjCO3$ zm=Gp!14;XMn*PCx^G|OV({Yj*;N#j(3$4`XIO=g5DG?7yEkI>|ImAqoo~xE0Fc(nL zmnM)L%j-VO7r*{#2zC}e5g;A_h8QCnj|4TDO*%5u6mt-|K3bM`zjvw|)HHOTtUPp9P;6TFWLp-WOJjVO^*$)Nz?9ttQ zaO(76(+22Zm}w%jMi-C%QMsIY%Y#yE$6K~0F&3Bh>z@mWpH}7;w|VS;Riaz;TDXfY z=%+|!GvX$o!0J@skEb7-5}3y4jUtO1aDB;AP*%7p;Hs4sHCa1-sWrlcVmjRNYtRx7 zXo5juaEx8o;To6iH;JYWYN+9XGg+6d@&Zx9HXcJ}sf{q^Z!MrhBXz+*wUrAIA4@cu z!?C5MFE3{t*|^%~cYJLHt)wZT*O;?A>Ayi+zI2bAG~3xAtwXtY#rXU`wv*zO{_Xe@ z>_721G8raf$}@*`zA+Ow^Q@ChGO5xyR($I6a&3-iC24vuPPoGxr@s`r?DKxmB-V-g zYm<=ETF1m;bnpTJ+sie}gkLtKQcS$jxH&TU@;v3V3!;M}Jx}3#+N(Y-aM|+-7i=H_ z*9sNrO13HJ@MEl(l7%z;TeVfN#RmVL0xj)D0?<@k@aro@u}4ik$VmWwFB2^_jv&#m zSNG%fVb}sT!0U?~qJ1wADP1Oo@->&HYO6ZbYt?SGl! zi8h<&x};=3E(NZ~$&B_oSNLW5EHo6D5?4I!B72+QXRY@n!xPQtQ7KpWP4*W7dV|86 z;h(TsHPpBE!2Ug3%1MLt+=OuK{rZ@T6Y=Xr4Ou<)4HK9d5qgxw)}}r(pt0Y^6xuOD zc|GdAOEepI2zfCZe!}fn!ANQ$v)K2O;YHg+3)lc=e&iC6U3mR*LCS1Ka3r=1%%56O=1&#@jWXQ0UR39~tK6%3gWCAFR}ZwR>%LS! zB0)_r_eZA6W3sJ(&$QgJl|?FsYG%5+4`(A|Em#(6Z12(Q;Dd5|6V+1EK5DPqRDgmEGNXy$3w^FL+C=% zvTVu@!%ntR1|%C}h3DvRt9mS`qhdq);l^Frh$N^%U-pT~`g)3dKLM>6esp|ZB$O$c zs3!pDZ8s=Maw}^{O!lfh&)vH_70D?Nd=}VAQ0|Klv;YP2c0|r>qKmcWX63DDqQDR& z9N?A>a)V{|4rps(xhNeDi`}T%7@$A^Phj)gz?o#1n?kRV&mE7nDeXH2N-6IfjAKP- zXGkkvQ!MPw)+`$ioolSeTR;B07a!W64GpPKC<^FcxjiN^aqDeS5(ELK&oJu(6GYTp zr8X4!g8G_Tq9#r4$&tfl<>MP(DSQ6i#=H%P_W5aNaYF-lnV#SWm$$aQ=74-VS5gRP z>l=8KUb>RM9h<0mg3n&W5jD5s_Ng5ZjlD7yj?itzp}y{FdgR-kG2IAA$M~`$_R|~h z{mq)teG1#K8Tj|REUM8VuKs>%Un!MhiCM{&k?WlaLCtMNn?I(qu$3xNpL;)PlJ~~% zpm5RA4))91J*nr8e1hSD=DE+JS?`<;bBouX;i87_#Xl~(g&-oWEvKgyO4Lkdr>#}r zom=#&c(f=1lV8k)T?3f4-}B);{F<`e?P2%Mn*Za9mGAp53MfrQiH z#T2r>J+~;Yf=B^_wXC$_^-j3-`vLOjO(W9nHm-h0SB-t;T|dm*kjg{>aVhQyNaZuB zABc$}^R8q16S2M4zii@(Y^|mM+j%9|YC89JeYBb5a7HL64|6+&tAEVJZ2c~Ti+n{} zxqxuBos&1HTwIzb=dQ(P_h!@Q*Yd3It|IXHY{5Ahw2*KARx*0ZMuu9BRgiEOM>VNR zmsuBQ!N5BJe|P2Nn0#|a?cbTL>y=f?;GyqT_=psb8ep^7eM<6R%hg+U3rSY`zkL{{ zko$OG#edv(&gXaIvkq8zwI=Pep8PhIE+2&Q2%Gw4UG;XAzA+E_`vmhMJ4~Tw zx@mg6z*?}>&uUCPQ~m8&cONf}6pF1Z9s!<(cXB(e@)QEiLu(fB`w*|u?c{K~LHmnr zm6&^z%iJ&9_CF^r$aw?rc6hjy40Vl52F8SBUnt|nkTJ!^EYq;O;Lhx1+-w%%gZdgu zG#=0+mN?BiEU`0j3EpLv**4zhC3jya@I+HJHh7+^{B3gQ%8b@rMfC~B?7j_H8qg41 z(i_sL#IPL?zqb!Ar8~5xy;Wlz1Hd;#Dqh6I`TD&Z3H?7vmB`>W0BvaC6cYM9nq5@9 z2+1Fs8$&?8G&89RqR{zgu6yGT9|KU|cvdUDDe|FV>V!sI8F}2B zflmgOoHk=>fqa%Pt@zY3BT|}vB~3uD;4u4Fc5Cma1wAp>gk^q65uRgw)U56^k>ubf zS9`g@?=Ww5x(tUKu&0Fps3{;$$A9X^s$!CI#jlmb2>v-Og1lNqmptOb29i=h~bhJ^}C&cmgO02A1 z+pN(07PkBxwF@Q55*zvK7|u^H?dx=~GS1HoW{wuqERi1~yp}Nb_<8R22Cw?X3H>%qrHjDaFl6mBqcFm;{Sxj-CM+z1a9p#C`Cd`RR1&VUlM6Nf0m-H>#8z}`)1I8?W01YwT=jxtjMg*u}3t=lg{2yZ&2;^%S( z1sY@6p`LYWvK=NHB#2W{Z$eh914(R>t8W&rj;L+dWj3twnKDMOFA-CT4j%pKM{-kq zzaOVRsIY(Tp1Fa>Tb^6;h81cw>9I?k_UC6pmESZAeoy<8s`xMWRQ#8F)?2>^fHwvP z*k+yT>Eh+%t&K8$$j$J_|F1t zYGLTWpd+$`a(OT~4vB1*uj|1#AntjJNaYNy6u9L@z^eQEfIfHi!YbYj#(KP#WhDHn ztKP^#tj^%eC0dUU&FnSGIAVr>-X7mlj)orhlG~NUR%hl)a)y?89lCsV0ZhVD~iue!pl^@&3%raJUVv$ot{YCj^I2rvD*QN^k$jC7UEn50~anl)M7wZt!t z%L9{p?U&0_Q#71dX6#5ldp9q8^Hs^Ox3PtGG=p?wu;b0TMl($)I61Z+0!X&6Ijudy zCJE1pp7#L5TK7mx-Q_ok)h3k6p*Bt^RyFdx=`l zvZ#*s!Mj>iaBS{&znG43Pm}R>Etjd4N`zbDFX1YPt?t6ijW8air?U*{;eFBtdi1H% z1>%vcxF)hix99j?LVR3Nhn;Vsz#3?@mdmzM0t5AQ!FNBlkSJ(6rxv$TgK(Kn?lVMP zIQg}3a!jqM-7cwhtSe?& zQm1GumzEFd5So~r5S@tCua=xFN%u+x|ACF&l%P3@sEqMyOU@b2(5e_?`Ga6qH@neu zg{OKm;b)4VUzSVX8%QR>0-*ylK3`9vYB>O}bEEl}s$H3#3x$0hcCX&vrF@CVD&}jl zG)G9HNA_tXz(mrX3(}l3*q{`?Db_x7vPdUT#rLvZnuOiTuf7o5gk}S)x zm?qG02ypqW@VG1%680lZc?#Gp@0t_AnJ}}b|Mt$>h4B3q)(ulmsl%{MwGL!XHRmYB zzc*zBQ~%MW^_F?Fi%*c6;h|?8Wjpm$Ek-E_5I)%$b}6wSwi{enW7=7{W>OV#^N(UM zaKDDmw)XZGmwOGMgT-Az&62WU%;)&(yK!)dZATKbUs}1aHn%8pQO};5d)Vg8D^8c)X64 z!Hf3BQ`hu!UxaD_?NdA1`EQ+_K9@FWKb*!CO|?hz&Qw11^*{pyB7F)G`vTEkr?w$)!oaJ)T#NOA#fsI0EYNbgFOImGJn z^WCG+T`}UC^NRC6+ws}89t9+AK0x{UJ*j8G%qPfa9Dm7QQp|`o^Le7!UEW3{y1L_J zq&0I@(hyA2JsP+i7}K!eh?Wk8VE4(BwEsnGFh8F_V-4 z#+Qp#KdwXl3@O$m%>2Wq-8z~|g?v3RgJt;;JN$BW!R#H$fH6#+_2TvSFx89G>aYxE z*i!HQi2U9NovmhCS{;i@lK4&K4DN$&4XR|~>sYc-)E1Qpn*KI2-4RbB)2a;#+H{mG zP*x>P0wwmd!>40n$p9(^D6wZX#9ml0Rv*#ge}_!vKaS_m7r=A<=o5T@`3c!#Oe0A+ z__doijx$-pqW`=2sr!ph;sahanWl!IsQZ$e6E8c)F>a;sg@xAUUx#aEn-o0gF(U}v|7(w{cjjh0L=BF zK@h(N%}Rj0D(Haav()s*M}-HgFl)vfr&AT)wNd%a zL?eNp7ir6jku6h0QrT?gi7R9raFyb1&jDXrKJU!0W~R_t+k8yk;~xL_8Yrgn1O;5T z=hIykq#Q?siX<}!BU}@{=&A}e40?&lYO~*tUkQ7GSDtZW9Xf`|V8(x2>)?Cp9NTE=kwU_&mRWSmPj#drU zB#gycg!SdqvFCY_)>kJn*=Aiv3sz=}$q>YvRe^W)_=2qU{!r2EL9K@T!@7wpjRG?@ zt3k9$c&3uu#g8pz3S}d7oxW=PW{V}xR=;a7#uiqaHfi&;sNBaVaI5(Z<2&)t7 z*xVNs*iY`4$8}?h-KB#s&+T&r$-ij%V+$XcTVE<*AqiTFFTAr3q%d^F$#HlTq0dbb zpGoqS{qGbJ@Q~{Q)>85g6a9$vkT5t(l4wP3===&~ZjYXocCAY86_42% z2NQy24<_&aV^0zPHuJxr)M6ME8jD>lG$C_oH=9#?ZMLL?REqkgFQ~fA6w-TFzs;b7 zA1Vyvyp`b}7OnR@C(HA-bc$mp>OKX(As9~CplXB+6$$H5wvWl4mvuGYsbtTtidEnR z{}mgt?68_de0UqlQCT9Fyxvft5i+}0vtB{ypY$mXf~VOAv8&``}& zF|cr2xz(t69qI)7b-`R{N*!;3M!0jUzyy;xnw_tPTa6_pAQ?H^ag7}ULKQ;ezF&$E zDy`MK@(A2MY1LXJdVhYYqa$m7dVk{j`oA6(uL`2CsaZrPy^dW%Bc6ErT(2Fsy86kx zy^l@rqUc@91c!e5O3wu>nO2hJj5zNTs5f7@jk1VRPFF9rK5%i}51OAm#Q*eD#hJ5J zeu!Obdl%=m*mHPc@@A~zZ&sSv3W)?3_8Te&y_Qi={OBdgUk=P6O8MfNg4XN1bVs#p zLxfj1N7IZ=R?~jO2(xDqwbs5&*1lk%hLS$DyQ%6fT@A2}H?0Pnov(jrFvp+}bX1g1 z9GdX|`@oi0^z*LC^nPReEk%Qhm0Vjo-FyJ)b`RI6B=JSZr$5i^s6V-r&T=g$c#$iI zE^U5^cN0a4={D&0>o>fQu=|^JIgJNgep)lkC=i~BgI0aIeXaAWm%!9+qAKpLiLw=P z*yw+~A3)lmBGpBZchTWDT`PsPFrcx(hP#=kX^%0fgbaS%*&zBJ4;<1<9=^J4!-rT z>V%X1Ge!WcQB3EAya-U;9O2G=N-s*QoF^CckD}(W?FM;}G#{Zbn2<7@a5#mAw>nsfmY+g2 zT0m&~n$JcA=v?n#k(t32!dD5&=Hf-^>d2|%`P1$b9Py>^pzA#;+cOX~wSV=$G0R$k zB0Ft1ZfXo87i)RH)#+~(_lvEj%1MEED*?WE6#eQRe;wNX6LO`n zJ#_ifz(3FC24nK3)3p#SXdbSe}rN{OsV9Udn2Im z!U1w*25I$6J2MMb=kj`VNz$yDV8XAL169me71%Ur-aS`-P zT9O`el2>t@Ku(}AY^z*6$?(ND^dom7C47>xHr!)~a+7Q3-=iqa{K}Gqcrhu2FbS+V z0)LsuC;iq;%H4k(uiS6`zg#8tU#>zo0jO)_)PPVDB%Coac8Lg^=mC&da}Gb&IJa77 z^`6uwd`gY>*6Hur!#8K?smehhWHQ4f17AFhexC_m z2z=RPix!aSP7ky$Wfh|o!hZ1g_57Sk_&~IRFJ?cDj(GEAobAt!Sx~la`_eRJ+s6_= z#powZE>@QXnqmZZChFy1@lvdfhYGnd{JTbWM(WJMR@3MgE_Z;oa6Y;EdMe80kZt6Cm^U^T4c6Bf3b&X z?~d`>3;w{NL6R{9|KrGBniM1(CR9_D-9EuQhxWoK-<5YbFL-UWq5ZbKGDfyY)epBC zm8^SgY3T8JGqQ~Rg>5dIsF@P^urlCqN!BA!bvj*EZDPv--H!Tow}D|Ej}VlY2$k^@D2i)FvN5~kAbg}Kh6DQLasgC zZIV0weV^D*4da_^`T+0f$j4DkYpn|)pO1*fjhrSU9r-E20rit77~{b8Cm2PYES<)i zAVg9k$E#_GoHbu<;|%rs)nhOhcHWQCqH(gHS9ut{nCWcHOhK8seQn`P_JjOpCw!;D z)dWOkSMU{L`c?X1Km!stOVs&WW4b2J2)ky%mSiY=TNgV-z|j^%#txQ!8mf=~1Al?F zzMW?eEPLy(bMgE#Ys3-jia2P&2S)tPSnugK#-PZpA@tth_M=K9z8m{B1uouSfh{MCWvNMInNEw8yVNGH z^7(zY18uoh@4C%?p!CQFB{UGsi8f}I)W4c{9`vXE?~rM~hz^~5opdCVQd$E{)v={N z48(c4^{4^!dHP}IuMXn++{tj(96vbI*^pAAE}MhEgL0{r$=`36#r0S)n}QBBByR`# zK}Y#-;ulPpcq-i|!49=?3nAxd3pWS27h2D_f9TrhWnCMRSCs|e=l0a7e?;NR?&YX{ zGJ+~4*~iHK7r6*TD=g6fCAS^iSfOjsaAcHvR<4$01H$qvFC=Ok z={l*uZGNKwyDL4mn?bq}m5QHX7?hMd(<;)NZ2j>6y#PWnDL-1x{OgxHNt&4$mUeV2 zv9ek^@gym1$6?1FljSN&irvkD!cAMJrEAl+tdP`=7pM*xcbxye5yO|Zc6uN677zg& z#|gyfv3Au*u2Sp`Wwar)9p(vH!H&2#{bPVc4SUAbj9z?l058B46H#9~*4z$*aQawF z8-_!g#|q#%F^Ttq8i(QB=BWoDC8-KwQq@I64PK~b(F5gp%~LK;UpDu-W7oh^0)vQv z!*c^3{I&F-+;`;_8g_Pe$bkH)XJe;_Qy!RS`#8TVQRVj&W%BvcGcr!XpFp_vM*qRh zR?NAA$pcfwDP(W^(>A${fWu|Nn72P&B-<$YQpZk8io;0VUIip!=qU>_MYIyI3fpO8 zT;kZ{D@SPAOE!ZYz!W+!CPtO+LZ2>&m-ttG$kXrEr7q&hU15r5`@e$AUByYJ->H_! z2z1m_C?T%Xd%k@U9T`l;1ghC9Z!lYEn|Sskg3G$I$(lXT5XK&wUL2Q+lJ57$S5+l^ z(^x85$%T2njqoZb0_ky3pj|aU0&+<^{Y=dA+{|*~*(<8_AlljO9tWuCinbbbJep9# z_W>$ax!u~#kE+1)l~p9Z{n(H(dMpch-ff-B#AzCzUHpi8P=T8Hbhg<{k4`d0qu~mw z@9u0hg(@Q*`FHCfpI5Un*yg#Y$S37VS!iG_Jm(K?EV>DNHV-#vcRu_WUR`5j;qr1K z-wisED6~Is+!FIsP%3gBrchDs?)_u9v+yD_bP=;#MkSZXbAUJFCBI z!P-gTiD7#_QA)~#xYxUWgQr; zep>Swak^XpC4T=7j!$p;36yh1va4FubG)EM z_C+f$+>*-|t>Ocb#G3?uv!%+Ili$r~cJde7>2=QPRnqJai1d#F*1;}Uz1FG1URyRP zXMr-XJNDbezTlKBWq#jxKKUe*B+b55u<|5yYSc=roN&##1j}RT!7FE_Ikl%l>r`AJ z^*lJqPFO_d(U{tkU;U7}^;Le$u(Y%^gbZqexiD@*YM8+9y7eKjLl$tAxNiNfh?Z0$ zgH|at54SpL{lM9zTAR2VKG8b7h(g2gkOWV%6j0Ipz@e?Fbyp zthZ6CyR$g=EkVoF*DB@nS410n0wQp>}b++YdLLf$!in( zN3myAPPjNjbGXZuDlD@w579{)ghSEfnoI8y{eO;XS*|7Ar5#x}b%5L-L<~2o zAY32~nP{$&F@778+t}#Ii^2{dtIv%*mDTa!_JK9a`KF4L?JXBXAL6u+oSz_k%|Q{$3RldHO3R1oqQ5A*ItfTsw+Ou zdv#vKm^zKFr;S}JI5>R(h~yAM<3gDL% zGua5mnU=#lAMz)?(Eys+F``%vmzPMSPXyH0M%Gsp7d`AD{tW=c0!@uG`7&%iN5)?o z^>8*Y;XvkIRk+}cXllSnB5F1d7RJ&2yG5?wMJE)R3o6~Y?}UwLEbN9=SYL?&@+9!{ zMMG?`*=vi@`YKstUtrf&#f7J5exFi)lTpHXETswtptOn#&VNL-py#*QHg7XzaA867 zP0c_I0V@Sz4A~L&#ITlWTG;71*_vvnQZa9@Pyw30l>v!+F&U~S(AMj|tg?_qu>7!& zItYFpwv49mt>t_Nn;>3Sa5KT`QDlCDvUS#0wW9_#9(BSo|C_8(uLNnW>M+fyyUilH zdQ+9Wi61X7)=-(N#b?4s6H&u&Vh8n3E8}73-!Se13F(lXOaj{u`ZX{nZ9Qmj5*1Kr zXHg<+vy)DXV6M8~2$W0j zk8nYP>=~0`O}s!8U$qV<(h9AHDiUMT9xcjc&GD;+CP+(x_h^`n+;JzT%d{^SztQpZXF;9o!Mo8P{vUN2G5}VzVa_5tQo1AC?8F2syensvxmivHNNmCtJm|z z01SuDpY_tT8)S#lE+qyL%M{nx4yg=>XT9A?rs*J5n|AqNp*8K#EE0XuaMg3#O>`d) zAJ;(?87`&mCIc3Cbuz>pWGsY)NUB1)4~SVp_gH_X@ZJ|jo_@x-8dGx3(iB@rUHfb- zkmpUemO@oB`XExmIOrTyN#ox#_)_=X?!kYjncMIG1RF$FjU-X#&Ghwjj7U>_FFzIb z8!Sos5%AcCuT;D+=Evo)no+h1N}tg$d%h>Tebg>@RbS7ljO((}7Ka+9IMv1f5oO;5 z(v!aL6?*bM5Hw4HTKfTf5FCKa6?tO$kV=7hb^D=@8dhSTjofAU1lWFq36id>~c9qOq963E29T-R_kfW-wS6-1!o!k8f( zYv=|1_2;})-SyjYdutEwakme6CWn#`j6(P;<2NSu(r*r#Jj;_i0RLe`wTBc3pv$D3 z@k+RxUxpm7xwn2>Pv?ASsl5tjV%Yy-q=9cxKKIH*Bjj-O7pJnAws_5@ATAt7cM~V$ z@pJV^K6M8jz!Q`-UgwvgtvB`Z9Q|`5d_)8r5v!qZHf5x5G9%$M+wF~^@BIdm{Rz@h z=5-#E&wuvVGpd9OsO(P%;3sHDW^5~0^iuf4IbT;CM&B?I7eZf-yE;D%X#UgJp z&LhF7hD~g%3(?Bp>d1S@Vsz2MnOB|S&@M&n^YQM?$@{=yS_@7;pl>}>gdvjBsCFAFra-;8WbhTF2WO#PQ?r(G{ z?K2x)n;f|<6DS=4>D5f3J}fIt9p6i{Wbqa=`rnMAJqbE0z_OaSw~5+vZG-I>ozb}t zfl|+HnZ@%~9P9+gx`%F-`J5p@-949i3U!W|(}{e~ ze);=CfeiCV$KpK3Bl(e@aE|pOJwo089b&VL{~n>dTK%J`x-sm&mjRM5q7zTMv zYCI9G=T<-&nvGhk2<=@+2ny)gMI#}<^9hMs@uX<6xrr|qWO&o+^bd-I-V^SB)m#;6 zcamr@LGS@MY^*%vwvN58mae&mrRZ(!FAKu+1p>T*0%9?KQjlj%4xpc=_-Yr?%3pjkIy7|Lke}2;Nrq-2zPSRo=1bjCc ziR*yAq$i!U1S(#RGFL%dd}La$Y!44tC# zw;>e2D)-Q4oAfSZ^2>D@3!Bz_T$af}W$#F90OxhhPUHA7`&%Bu2|$xPg#D`p`FuJ< zYK>)_>Nr3}0Udw72ZE(|Lr(4%a88g;9EfFITz0qHap)SN+h<>3b_*zF-yaZFbGtNK z>&m{I>b|kWy1Z*h5uFM>jT6MlEN8N+;T@KEcE_3UDSD=suPL0@fDjBbX_NL5!Gi3G zqF6i#RAXp1A-;ZEhg5@ItfW-N5Q4bAw=g5|hGBR!O`L!{&zIJQGs{d7ve0X;H61N!Tm%JIHb}n#7>oaj98vMj|4hNE3P1*g_5t2A)SfZI zV{$rubri0`^ObU|_jBU=$=oB;Y`m-t_4?F2yXeb(n2rMBg0(wy^<4jcJ*< zR`Xu%l_qsJnK~mJz8qKN@tcz1m?i?8(NhIrlLs34tZ=*NziIMzbUd~+JULEVXr*Sj zPb(5S#?mi87fw!ze6GMacxdA@ID6F*I>*G$cZ`NMjzH zLFI93PhJ(G1xy4`%Q}5ohh1$Wl$n(ckJGKZ=jeg~jIkehO^|=8@Xls2z;v+~%nzQN za3CS+m64^7Fg?_YeyM$GdkbwssUK1?cuOi^5x3YW4cLNd0jS62i!H|{roCVb)luO0 z6$V@d>_T6vJ@V#W(T??ST1mN^J-QPDCbS;T1oZh^#d?<5_gBFOl>#sifue^69QbSN ztL}ftkk&hv5;3FSJ+istzKvlE+>|DVfnqZoGVi>Fxe=kK0?@CZg*3JPQ2zQyo-%_q zw&PDJtbd4;T$o}yc6Wq%`O@O272MgB*Yy*{o)um1XO5Zk=4r=6PJ78lQHU=_!Wj9n z=-VU8Q}~YM3!j@#-~YtNv#(rlykX{~))R_zqvZWzKop*PeC!=7#bfz%3r^-$;M;;`p3Q4Z>WB(g3z7zH zp7M3lC(@AF6L&PQe7awKIc_ydXFTgT*LT1P;hul+W#(#+t4y5=sy*R$L-LU|**)+V zPDJG;kQ)hNF4lK<(j}nIT!j4XAX!AGM`~<{*E{L9->KHHPnr}w)5wDZ=uKBQo?%{O z;@P3Xc`|F;oDTzIwRhG~)%+KyYS&4r`TQ==UbTeavXu2{%}kF8U}!VuaascyICH+? zbFsrI8BO7%z!gsp*?Rz@0Ko&({#QfAP`nEIFnXy#R`G$Y(#!F6wR3vX!+F<>Z;W$q z2GFx1z3y+#fzm4dQB5(Zu7$jJlI> z=uNX@$n5&hp@`r39gEAt7W9toW<*#81<(AY_X0mOnvB@1CEx7#b4RejbCL6|fdJu` zs|6!U@4uog6sR#F70nJY^ZKZbdF>yS`RPT2buLO)7q<`*XyP6g2MpN7-0M(6y`$Uh z%?I^h*?IgKbr`XfJh@w*ebTdD9dU@Z=^~tOZKikrS17h)Q3{7^YE~Jdca3J#hDSss zSc^JGXp#+mJIj^UevDk(LIWNyS*MzC`2rod)rOuKdq_%MhOodlh&?`h(Hs7)zz z>J@_yV;~)RKK^Oo19U&f@TgWQd<5m|X~s^?E%Z{oJ^gR}%`Bl$3qbdki+!)7`XB;{ z!3-Rx{v`-dHB$Ht4VpFlaS?yC%8srV^Zmqt{+35i5n*=z{KPU-vDJ%o zI@f(Ur{CL`F1q;g;ywKidLnQLg)^y(R7D*RW={z7x{cml*LR~0F*W1yx)b}XQhb>v z4W0$S4m30g!e}KLW7xEC9D0H29$Zn)^2apl$+$a#_sMO!D!XN-GNk@=Cc{p8ogE7- z&H!oVDN5LyxQYi3lwkYR*E}!4alWn-ZmiXq+mgc+-mBI5xcVqS!BqkRc6Yfhoocq- z{-=egD`Gavn-WZ-=c5uO{^S3O1wJAw8-j^Nhb2`sv)`R6aY6z(x24+7gtbIm@^==B0m7QFbM5<(HaAGNKq{uZ;(L)J97>pkPWrZdZ&I?T*FL*AHkF*I*gyXBpBx*vE ztZv!n2*M0!4_eLDw^1hgm8r^M1^$4kpQ_xz`btKeL2sxNze4TsYY|XDN7g|A=jeHr z-2wQYm#L3n|IRku`kPYy45AVQEI52@Yucqw$2}z`*ZO7 zL^0NC|95ZU-c~JaH)J>4n3ynNFAJZVsKH#&cni-2?5;@7m?G7bP=MVyYN017 z`3=QCIcP5J^E`rJNWF7d9uPi^?Ys%6b^2Vw(FO~;?z860J%SuLl=q#3*-L%nvchDYIiDsSXrH=G4jk}zdY{s(4gXg@20iv0%KKeL`+eK8OZfO=OLc?lR z^@&|OrLIZ}A{50S60A8FrmKf3Cx1IrKTYccf26s({{F2T$0O==9jvJq+1q=6&(>u23@4#G+1w~tw33}FYx+G$8 zi2jA&x2(cE3lYhdygxNt4j(c8-$=m!g@hU8i5wy%PjUB7=zFCMg5b93dnV~$jQ0VP z`XgdMp5TtUf#BYCy)n%z*A$)*VBYy?&uYjzA*3db;dC+CF>E!9KSuz!D7SXg(kK<& zFaOuzj7>B%dbcq1n=Nem4DARUV@RIlSQofY2alNo*&NH=NVj$vDLMfIdyfr46AnOe z!GH|^^959ALePuc1IKHxET~1S9a?-9c@#Y`&%*=O1O{@Sc2d2RN`xm>4_*wGc&|>X zjB$P~d!MkOa*QL=%VKs^p;+$pZsyQX9b=fl)c!r0-V@ooA!tBQhqAlsGR}SU`F?R6 z0PX>0JRRBRc3>8rvNx7G@XC38|5bG)Fb`HzJ=~a7O?}!0FWF2z&Q&Nyz2?0Y$!Ha+ z3sfT2D=VN3lyV9RXbt+3z`Bw?ZgX%BGV)z{&u}=4dpMYQG?@5!%2?&96e!C(j<&-= zP~kzm4&Tk+K-UIVt2vw#uk9mHY$ky_B#jlEX#6$7UE^3VDGQq$zT!pw-UFIYl&_Ve z2m$aOk1)?~ZHt9?NM*sB^b+Kg&&R0(b(g&p1n6}t<(m_&H}?qnxkCaU&xjr$d7QNn zx>PB8 zg7QQwSK3LZ$S7&;s2dc&!gNY+V?y75)84D z0N}SI!*CII>HWX;fUQj_J6PV7$46}3+imeo*ln8UyY$b1=~r_Wn%5qrpITtVviq0P zQ$bpwP{On4j#sTS#VnPZvr!4;jjpVFFtcW!B%;(wO>TeiBCTjxW-#g~VCt0t+SY>Y z1pb%lEVRT_R8Bz3&!l0UJGAab%Q7c$b&1=!F+-0%Yigp=GMgRph5tKo>a>K z25gEzNMzr*S{-*suG)vxRT|cJK^mcFZ{knjs`t2=GPbLtz%|3E4>^JF*WESC(npKc z%iYFmut@5_*yS_B%MAbl?M&Mkv9%>35bX)y+AGyoLK-50lPkSVk6Wb*{U`auD{oTb z&Q7Bl7YZd+lV8k1bI{*g{+2pGQ2!qbkU;o$ME!uUd;uK0$uv{$HD2tHIxwBX zD0*(L+^?np4Vu6GaPRI>)-I&GWvJk4Kk3GrjsGK>A#SfU6v#)~kTw8c26nA5MXfS* z`nm(NocX$b2#a-k1&Gu?Z;T9_fB$b;46Bk}-h(siPq$X(JU5}&RAFIsiIz|Pl=?+6 zKKrp+Q;v)0Rs!_{_Zo~&-hHy3@}o4;MHD(tX<_wREF^njtv?}inJFJ!-wpdIpBJ*5 zQJVO6kxsMUGB9X@e-cI)5{6Z_b&?ME@I*{HYavcg>vOlh7csfP-~VYD*vlC5f##=! zt4z--b|q6A7kwq^yjG?-J2Y&-Q**IR9BNl)6*VUfCsFouNBY8VAOYS7+v-K1MuA#o?uP!8=g{ zS?rjI{qIhy4nx^47LeiOsM^|_$s?IPuFEmIp1!O(_>LIaq`;SHUB8>;pK<58m8NGh zIM5>{--U7+=ciuBb`)jzWnif`e9!Bvo&yyo;Y~Jw&hF3Z5Je%Ck834pV-!=Cx;|H8 zn zi<;`?zR9Swst zUN!W}4(*L7ff88LZGV#pQkb?0Du2y$yC5WHGwSjgygfZ_f4c6VdZbEyEW z?YctB+>bxb`enjn>D``PLWSAxhd4OGMkMu ze;+6``tK0olQrjP?m@2@{0o%d9@$pvQzbHRi*lNwQxV7c&6^tKG;)4~%%A$vpD(KE zLgh>g{rsG*M77aWSSJU zldN(aZcYH4Uq#SN9o9w&37yP;_;V;H@mjh167HSx5OeSPg^Ydd(GQ;!wIZl1HQL^u zeZ1JnF-UK6SQjz@Qh0jPo@}T9-S9m{t>K;g?qE0gGasB2FoyiLp#9hY#RI0$w`I+! zeaZ}%UFQ%x`Oin&Rx-c z!?jWI#!2Qvz(D5o!8`MIUh)PFtpY;BAH#G^4cv9!$Q>xDdb)hadG_zGi~8pKEoM4< zF2n{d`3@`9)T`k5y?|zY7HGwrA2J_V|9Xe&0SoA&M~TIL^!mQ^milsL)oY<|&8{11 zmq6~cd%NdIK7cb9GhfBq+%>H0Sfn+2mi^$L>F3a*fC-!hJp4|0gge%Gs+(22(vCap z6n%M6@W9P9iAV%E82 zrNOTklqs2^(hEG0o^bkGVi?EG_tE=X5+A;!P2gRQY$=|9o46I++8Y{48{Uso;Z8Zv zgJ|LNQGiz&D!1*5**OlazN42Vk)LjilS@pvbqb4HP-GTspEpGJ2%=GsfAlwQij}|# zj5LHT1HbUrzB}W6vu`*5oIHOQ|E4&OQAV!_?bKmrNkFMIy;(rZbeDZAFzk+00Oc0E z0MW0v>A=T$+(xmPKKy(GGn!mJxZ27M(yOy)U5e!sDbSN5ckNwi(`Bag0adly6fS<< zHb;YvJhtjIC`WO-Q}m`>{IEta4i*8m`5(j3grfIqf@9u0?FD+xqh)uZeQ(2NzVPK1 z%$NC*c47bOn%7&g(Q@O-sHGg5jplO{w6Cb&Yei40O;r5{I-ul~K|`|#!cEA^ME2zi6XCVm&WehF@W_I>pSw#50l%L##aM>qjS4D9j;x2!4AL zAu{gLj2Gux%BMHgPVHNLbo!}U=+40O4v*?o&)}5ieUW1naWzF#pLwTfY4VesSxeH| z+k_l&@qj_v)wAES{e8;=0$#^bY%@`OB7O*EaC+RiiEnnz!gT*YtJ>^4E#$?sy#}fc zu+iJ2YVPfa4GhQHdF*JjZK6r3V(7B;BpY-oRUzmFt*AqQ4&-ieophZ@PWuj;&;Rv- z1B5oe8ma$zdky&LVnrLp&2rwHkW)QH=W8VSDeh_j3;1Ix|6+6p`p9K7xvB~EVa;|U zi*Y^d=NptBEh~wCw%02zXvkS5`N?U%S(~km_6hx1Wa{%=foFF7X;Bf2ME`G-w7dyfEeodCa%p^c zM>%ww$(ANqR!l(N`uA+c8&ve2wEvRO0-ZM;r<54r*IjMou8&z6ngQ7DIdcMM4pt6v zjra(ErS0}9^rV7*@DB_NFAp!o&Ll|9tO(`ucYV&zuom1qPOjnAa1|N->O9|EsG$sj zKrXdQuK(Ga;0mNy*HMsd=I=_F@f0_CfPPyk=+$1-P#Y(~%Jqh+p_BjI@J9D#rN#ghi?!L*qV5Y=DtDANUK(oBNL9H7=HJ#<* z($umum4f!H`nHrAwJ$xEoWicSj!qd|ViGyBAmMY;!F;*h{8+x{jc9+H20$HZ!q_Lx zcTkStYESa${N(c$szf$RV=16b7H;wm!hi+&NgM`PS1s5C|8FC|Ogges@_TLsvNpYlz&GNRYs zpi|Vo&hulQ!=8}M_5lBVs`b46oW>71=06Kje;kj?mj+&aI~PbYq>x+0W7 z+Gc=NodH}i6vPfZPrs|-y*3pdE7ey`T30nD+1cc7jn@hYO7y$)yK=B|)3>8XWR^R*qfWkX&T9vaf-o9FL@pC^u7T5dg5tG)vZ%e@%R zH0U4tM5``0?I@jeP1r3PinEsGq$KQ=4#>R{Dkz*R(i8k$JMHLC^Q>DfPHVdyV?vwI zZY_GX`&JYQz_t`8bfF@C<*Tt>Ki@0gOD*+HdVO`(zfBy7eN!YUVozp&KHXgZWiDv%rGAAzYU+#=6jT8BH zR%p!t38_NsO+jK%m0B~91OxDB%b!&Y-*e?8$(JsD7}Na(P)*8wYlOD!%&Sd~QrvQw0ob8bBX8_;7vrmOx&OD%5Qp_I}# z(EePHmEAY}%MgPf64PaZ(5ojb>zsLAE?1lc?VpL;+V|Np$30d`1M%8QO?G&7H}gKf zh!b%g%WewZ$c=K3>-Yobt3UPg&!3E2TE!K_Nd6p@c_%V?qa1djpz1 z53KK2A_(;x1%Fr|-xTiEkg8`!LBx8z5-(egmo`kSN4!!v&_W7mMVsVq+fERWyhpbc!5)`Rnk;ilGW?p|k`=-G@bbE~U9R<> zE^B-Z&mFQQdX6^X_GL=z6|#!WU+C$4UBw%7lk`_XmFGS;7KS9#Ut1_I=GZXn9k1RE zc|LdSg)W){ufB`Nahh=f=L@^u5*l2eduzw2^Xp(i|8^S@Oj45aOzn1<>eZDg(9Bh+ z$?U8NqRl(3NH;ZhK@YsewWYi?KH#2v+&CLoSX1@-R%8dQ2bfByea!H=X4gRv-A)Ok ze$q+b#mrHZrg06q7gaQbH=$T^SN2ZXSjWNaSHkI99~F32-1_2zmQI@RDQ|!NJE+Sw z(X$8&TJd-cTsgGF5Y6-Mr0fKk3GSRV6)I-wZ^Lif^GAuHqg!;G_7Tt&VsV{)Oku5o2yQ+u zJ|mjhHiFNZIR&+W){dSRTn)0$4_@!MUk z#aX6}lmxdU#m`>$z1~n*=7H1?Z>R_$_`NmYI2J|=)_%%jo!-k#v8l&VIfbg6*mLm` zIJB?hfZG@FXnErUh{f*&e*`jifx}Hwbnt#r!-4wD`|9{&4|XI-8~04*60(8CnY=#i z-PD!b{6Tr~y_&`tS75=?(4H3TX!BJ>y$|X2+ILOie|k+XHdZxVq#|U0-wAlzXYq|T z@KD((!lgrU0)DVmQ9WBazrb_%0}MjF=9c?uqx)R0utv|mklbDO{AUL%qf_vXB<4T zv;<#{V+@t}dU|%o@4EWpms<9&=dBku^p6tF7yp`{$q;c3imVx&4Ure5>OR9=*@XpD zYxPdvdSc zg>Aiym$7l@49^F-ZL|R{sjT!+UP0wrDFFfa+v^!8PG8HdjR2WdG z?x8MrW$PGisCfCtVZ+U{sdUGNeM6G5%?C*AC0t5p_a?%y_S~=a%vWu`Yss24bBMoN z4>Ddti{zf=%pPGXXToysUe>C~Bp)|>gXGbnnW9Ew%;>IX1*8`yL-4mthR^9{p1T;d zG$mg;x41)z8z5pS>Im21%X7%*xm`#UUL=__=1naqX!20z6RA1pg z)u#ohzFTAXSb-kX`JbGFUW5}pPTX~CK|7U2y+c95twCF?Nb*y15OhWDql?*&qS{f)T^DsLERvDS3a>)mpoiQc{=aq$3MWtjnMyd7$_mc zXt+OCmIw9{wT3Lk`l@!*2;)_=d==qZ((==hlyXq#CiQ?1yAlRIQOAv&-3_omHvcA3 z`vEPMVWQf;C2wp5Q^e#&xd%O+M=I^!n<_2qRgu#mO_L&E>7D9P;A zO`cQCCM7i65G6MoK;JX>WcFU#IXiJw1=kMX?_U0?Z%y%Tipq`w4p1Z{rq_7$NXVSi z@LXMcH|6-xN+~)PJyE}S&B~KMJW2(7u{y=Sxk}~!cr&62>EvKYbIJ<_gX4e0&UMiZ zZXD^kXmGs5t0hx+E5@e3B>CMtgBGZP3yy!cgm7g=P{beKB>>gB4X^HYymp8xe1*9# z^Ph5e6s?ZI*KlB!d9zZN`Mzp&k3mZ9339OMuE9L}5&y`+5HUd&5FwE2^}9L@Hi8aO zw!k0Bmqz)QqxK2KQx^p7SgW4V99YD719nu*5Wr_~EI) z9yGuCc}I=lCL^ETWa%}5lcC3m+?>`chr_H&V;RV_sjrg(XG4&vE^V9wMW&s_w@715 z<{Bpg$QP{58Wsr($S@*v|}%=+(KQ6XZuYzd&DM{Xk2Gt9;G+M^Z`}z7d}!Qm!pVW1PWhbzAB*~9R!DOF;-Q6lIGXzAtBaU$MoE0DKxp+7NRv7U7XN_az zqutReZRfP~uHOq>erXtqdcwRj%0)j}?LfhDWj6n1>4-5H9lj%8)#W0fUHkSDTBtHs ztQ~8c-L~cyhlrnr=oNI#Q&FZomD}3Y1zfzrBgW|NWxf{3Cr?Hn-oxNh64%IadEb=g zh%fJn!3A*>Qpf@Dq!X2y@x>9Hj<4E^od_}+(43S`n9FlS_Pbu~!)J6=+4NjQnBy$W zS02#t$g}1vWyzsC-;|ruzCvZ?@_J1GVa)_QiH%ng1XAFAAhy)t>6u5e_Xd9-4Ik09 z@te=B;_+IrLfqiP z{fWW|1HfTt%_xQ^3YV?o8q6bBG_5Z81UGsNMi1I3&B`Upx3Wo82p$rCyU@iIrdIzN zukQB@{`$@;9CIRQO!^PE|G+|uZfbWM%NMKEs0TjKtdnhzV|4B2`;aQ8c4=RE#7Gfo zBV_STD&Hr<2{!%!`X}KJJ_7?JS31)SDl3Chp%GI-#Ij{F=jPeC`Z|A1{l)1WNHz(Y z?Yh_4h0~&l_NmBZW}b-JM&~*_3U-{8&lEX`r$6v6%$F={Yw2+LVwV205Vc;ml%@Em-6n%RC z^u?+CTE6OIOqL%Ag&>}Rd!vK^6@fsEw^D@TzJ$a%Ih*0(6n?BKo9A8Z0XVLlox@CJ zB+>ti!S8W}{{#vF8C**D>Uqx_AQ697lmQk~qi}qy>JTmXV z)QS&k{kEdntGypnbd|ET44LZPu;SrirNW(mtgh3bpP6KdaR?^R#)T7@w$`^x2t}*@ zeY6_a`Gon41P=dl`6a|~6@B4Gs*(mw$iv2}tAlObEEs*%(Aw}$<@mFetF`11t|aL~ zLGmRfNlV}lV((Z999NR<#Zo2c2SA+FzIZRi^wY4q4q<~;Vq@OA9LDu~R z?X9t6K)$HA_~|6i2SHKuaZMT&fMONFtB$gGOTZYtx1KA8Z6=gDLt~ZUQz|3f%9#@;4s%8=K>#zvirI+xAr9Ue5;?7H=`AdieWZ+8@05 z=bvZ>jlM%9N~op1*?B4#_xOUY3^`h+21H@JH%Ns?sk+JdRC+KIEM9F5Ujh8jg68HM zW~tm%e23iDOL5dD+4WPsEHRv62h6)KT;~$4BuGE*kBL7IhX{`(#>h0ex8tqeM>Ah# z&PF}Jw-2|EaoOfSz|SWR}GT7nKP9NAJiGCCIQu-s8_3&`*~tTuG;*4u=#^d z6A>IZ2qmG)Zd6>ZtgU#b)u945DG9DHl!I`}5l3@^M4I-096ztegFZ^&P3|^qG)EfA-T*qxPVYo6z6gPL1NY>_N z0Qw_6NEIO-!r9jo`nx;i{X?3a_80GKKR~dOBB_dgSO@LJA~_~XwD87H?{V(M(VApk z=9aA5AVl9^GKu=dkngi;M=#U_^ZkT)jZ;YH$|2b&@64mc4W{-8NKAs5G-z!_hqMzu z<>ddM)M()ETabm5g(m*e6Rmj3=B%C<-%QKjc1&|Q|FWL{o{!EZxF2_c;hkkVU=fNO zIC(kPT{HUrXZMGYh0MIEP~p~2;AVsc!N!F&DCV7JnCTDaQ6V$m1)C(u zpY?t6`dVmAcBs2-Yn*ng1|O4pyJc_xynACYb7FKgEOPEZkvV;@Q7;l$Qen#t%sE*E zEnfKXO~f+*-ln)@kp6~0#5kz6ZPpIqTq}$}9$K!waMU`chHX?u``Sq%SQ5ssyDw%W zqAfQGFeClu1hirOn7%0th!BMHxvzb*WKkLK60-z?zoFY;KTyixsnBhKKP_jHWi}rs z>z=P!)%&zTcfzShi47Jm&6K_KzxC!fUUOGmoZA=bhePxv+1^|dbn zuSD6ISy{pfyX8HF8O2Chc0LULbKalWw@xa!YLdfJI#_!aB>L%f`5WkldCeHTU@3`N zTd>tx{`zk+gT=6%g|9gQI8rwljP;r31GG^^xv$roMyk~Cgf6=Cq zt;V@uA2wpn#Ly|@L$rsTaTR^L;y5~0H$FvLul9UdKgqNk_G3={p|`-+nB;bX4fMUD z7vWHhIdaTqS1TH>MMQt+MuifR+jVo8(SWxBqxS8OhehmwBZ>J7+Q9kBDGRf98S;*) z%DGy7{rK>^oR5`d7F1+y$pOSrHc`DYVNr~XxF$<6tc>e(+aM7W06OR9daXpSLMk*LO2tul#o| zJ|W{uC9Jl7=rMog7GZRw9jSJN?Oz#ep#AlIV8m)&1geR!Mi4XQD%H!!o7y4?(npk? z01drfi07VJU;dmG!dL%ns=VlS7-3da9vniw?dVwS&U|H3_k7k!w|E%j<`DtwW?-m& z)$|yC(U{#9?rd!cb|tTbh|<$W1l!%hcF?Aqc=Rc!#ob%?XJV5(DCQRpF05k~D)ZHr zed8x(`Z!0q{HAvfeSlpH5BG;PeD4&7>AW(JJj6d&@m>fO!b;o*`s|*S0S~%|&@DS- zE>8MVT*FePIHO2M9vajeq1ht6x9=0uEGltD(IkmbUprTnEB#6oVpF+98))uc9MENP zx`xSJgb(EkN92N2Ae z$Br%eS*8PQ9cS;Q1`3QHP`b4W%8R;AR_>sSpCm(V5-KLBf5t0!9fr5Y6it3=Z4Y)% zf%^-Q-47L+wc?5mfH|7~&8*IX5P9w?=QjLcSb)y~Yv@wLKI#g**zNA_($oR$AqM$8 zL~gw*r>mKmT)frM2-SS;ifj5Bm1MDXg_DzRxBBW14I9DXrkgvOakqw7 zV}gIlbQh4Pf!ypP3!f6T-4e&qnPJaJvTVgQD$REQntfBq1fv5v9TO390l)_vC(s_> ziM5?(2Ew}s6bdId_&0$WSJYT&_OAEHDE|c@kb5_<#J;bg-#G=MJeL4<9K>$vZ7B@1-7po1ncsX+#(Ov;8NMrj@ji8rtvf1<^tSo<+MeLm~1&`N|GNyFxi7Oq5#m z5zyMxo+V%tMCLtgQA0dPB^n7KH4LycJi;G(xEjY~$Bxd=asp|F#5K?@lC$Eh8rSlZ zuSd%QQI_*_>XE(KMV01=-*kZuiFX&$24Gap7#ic&t#VFxZwfpw+1TF@dQdY_R!)ii zX=_L#`|1R41*3MqZ13{{+S&=K>~;QRQa2L+b4dw-Pv|U&H+rzQXO=)`uEn?xBwO@9 z+S_x};ZByD)wJo-0pdmPM0+CYTQUhm?nA5}c71aKE<6Pt_lmuZz7DaNYZBLf{9x0M z6_9aWt308ihYqb-9MdSXFVfmEJYDtQD{WnzJ+mT3l&%96d2F^}Y_|TpZkc*hlbl!U z@4kxM5gkbcX`t(ax@F;uA`V3;8;vP7ks}2^GzZSUqc+rt&+Ox`a_7UgH?uFo zotK0;Dj_Hc5qP%mGu8TGi$!umDd5#v48m0UlgR``mI?J!`)M?T-P*>c)w zf>WPVeUFPn4I~s7K7szee+br(*IJ7q3Z1)^sn?npNugT*!%q7<$BMn*5@rg`HV0fL z4~ziW2X9h$CuW{8(Z9gz^jEgPAd*79Sm-aVX<}5$Tl%oJaYC=*m)r5(_v3_WKJ->? zXnmS4+et#Brb<9p@x#xjYL5X1rsRV<8!=_XK?*kIYFqxiUWLUEyJiPfEFDWYXJ;JP5U!oq^5Q6R4(uaXH1sjOaJ7rQ+x@8Pv!t{l7$!L!{;JzBPa z9)rzhxfrXxD_?ycHs#5qlJk{M)g}caZ{D9G?m4Ly(4S28pYsoEB!Q)&zm;A0DzMH4 ze)PSA7y)xpzI8JuRjD4Xo!9T_s%L0b(s|^+%u_PR8u;es5Mv0PM={+zGcvCMDI(?f zkOo*y0~l;NfBczUbjADTDTz?$0q63PegU6D4jy7CS%NJF71MkKOKBk!d-rusn549A zcW%G0g&HN=<1XQ2rxzC%WcB%;dRfBWcsF0k&dJ%0Zye}P0vJANKNt_Aco>B@(kjpS z!Gu!5F;zq0;p;zrXl=rNhZ&_fnzm86o#b zF3`hV++F=a3G!Zw=82U=mqXCZ@XPiAzXoKj1pM|Z@@ypS3`b)sJBXHXtI6)f(S#-E z{*mu_y=b2U-C9h3vGLM#gDSwx!s?j1cL6vZXQsf+8{LNXT5+72hdoS#+E*W1phDaG zd)~!TXmu-8>tDA~w%Xo&M;m4nVQPg3cwv4rW#GvIQH9+VeeO_rE9feS zDWo@6X-#xQWUG*>YzA|DD@mvsywfZzfp&d4nM6TN*hgsP+1+*tp^IsYqW`bMDf_<; zr#sfqVDp2fXD+~2?IV-?on3NSAgy0b_ThR zl(n+?OovwCvRfLfcV}#oHZA~dPqeSx)*5PAAvxSYWOAB+31BN-_c(UkVjPqfEM3B^ zzgv_RdaMo}n{E({N?v?&P&h9MGTX193mprtUkus)N&NdsN1#}+>s8&s^TAm9nCz#g z->)xXTZR<@*V)f$TJbA)P`A&V-!mNG(el>21vIp)n07UCv@e|x>koS8bc0%g`gMz| zT~|n?`NH8l2M0x`eX41o+|X%LH=4+_+o}3$%fBB**&}MV9VozF*htb$Loj#4v%kQc zM4(B^YLUL_H=2t)U1vt&bwii5lcrYzBb$w#w`=d6+JF(lr|J)Q5}viVRz^{_th^_| zz8j(veTJu~P$9TZ8ZBF$KbF+Z_JBZ}bkdoGb!|epuKg2u!vSWm{?j|e#d9~L33)}c z|C}}HCb6JBrPuMRB*~{{`^6cscj7>4GTjdxPq}RxnF9Z{({@I)T|gqOp_&X#IrlkR zJdWkA%*_ZzPAUti7u)W%*raTk5YUAMPKsi_F(8??`-jPd;G5FM$ik%QlD>qaMpK5Ko3m9ZX&8LuuPW@JkBqkFP%p> z<%y1|wpcj`*w0s8AGGl7h&$=uRINwt>qC19%YSd2WGpy_f$AP6BD^^$fhx2%SBbr! zka-84E)N$WG)I)Q75vh4gwK&^HZOeN67Z*HJ4QUqVJiH5k67qF2b`E%QO0nxre%wy z%@ENXx~MREW!T^{BE0_pTG*TWV?uhITm^161$)2GhE)y?dR#>QuFH3r35TV(I=RhV zYtF_+cMrpbO<@PW#FI3~j|t3nlTjzZ1n&ZtGZ;Pr%O@I)loFOst|g>s8$OjzLiFY} z9Eh$z!K(IwcIu5hfI4-1^kOiHyEF?$yLSAJ>wLX|1wcIW?@=WYp&K)X!WmNl2h8*#~{M$asMbgC$G& zV0zM`+oKAf)9=f*K2tqMovG|of%h!NC++bgL3s>7>OEp8vj1UN%R^AB631Sym4+Ox zCK(yM$2u}-j|ZGM)3SfE`d3s@(EHlK2(!4(4+lp>Y>g9AB5@d!^@#}cqH=loqRz#U z`G5>o-11kOg#@88&8hqUuz~i=i}3Kl`Vp0Le%G}rP072F5lVA&EQB>P{O9yB{i%b* z(W!G}+sCJvkeZj<_&TMVeo{3j>~)4AId?J#v$N3&TN+OHs(-&k>s4OAw9)Q&Po=>d z?@vG&_>JUbioUL&7V7!rdQVBsAATj4$48c^>+8y&u!BtGQqG)!kGO{am&ZO!~ z)NkW^?<(}X00Qn5)e5w!Y67B)+8N|#QsvCHcjfh#r2dCCy@=@8yODIsBnf!TGB1Mk z^wDXt3QGRRw=|6qBvvhabb_kNLy{kzB8xhLs`Kdpdj@?QON8OurH}}|) z>wG?psZ(!BPa?~p&Vchs5ngz;O_deCkkMP<>-BLtgQL!+Z3_ovyV$~a2)rM9Li0tk1xEdbA zI3;1I>yb5`Ic2Bg-~$Q)jp}6!@l0C=u^zKJ5G9dUB zZShu)6Qodm&NOHYz@kZ6cu;oHzI7TldsbGaLHT{@q=+A1@0QRutUwmPW>vUJN6n(E z!;!!s6c05$qb<=D?H#qfDf|2OW?ZhpaCB%V7##-u#-lc!4%@NaY$6kYRfuVM<8Fb()wI16bXwJj1F zMux&sribaE?e^iSvoX%;!%cAY!TEu<=u&S4-8+L>Jpo6KzUn#Aah|D$rAZFu6+h}Q zTVlYU3h+NgIgeIfDR3rZngWUx&ue#$OZQG}btjjwu@v%wue?ie;iRAAy^|C1esyB$dpE72RJ5*d zUN21TgG9e9rbscG-hBA@=T;S)&okZ?5bXaNWS+yVM0oB2F0qp+F~)+gB-f9y*uh^qv_%T+L-W^#d^KcQ2O*cudgc_>|rc&67h%GPu2 zzeI8HMcTYsD{)^b@-&b&e2G4mSR;L}nahaAwWLR_NVe!1% zX9Fvq2oujwFxsSV+~RYU662EI%{Cq}LXr6jX--fLT1yL_Y2i!XqmukkOR~~78{0)! zO>hxmPC)6KcTse7S~+leS6SfM3ykxAvLgpFXZQIW@Hr5jTsjGvN;@6dYgAkpdA6;4 zJUR*L6b6@G-85}R)<#D9U!n&dWhAW+i#yGhqF$hZd&Y&-W~lfVS7V2qVJO$=aaQp2^TN?h%7A`w#5c zd2^(0hHtNe z0#nv4Z-xv8OIKh&+Ld*6fM3Xbp`SdDp3Jpw!L$ITR5Qa6O>uCQ-Q*=rYMDiYOocCB zX45<-(E=dB;b+ugq+9njY?0*p)DX8C{AC2W%w*e>sTv zE!EF&SN>>50n7M#$-bnG+>4D>%ncCh2MvC8@ARk2fn=q+&gM(sP7SjQ#nFTmZ+R{P z;J>C0Mqc`GL^AkAb#8fKnf#h=wFTYX-O>3k_&B@`$oS>ojI0F7&|Az2TRF{(+SS)2 z#F7cv1AQBu_oD@khRF`6bhQJLIu5B|!azzc&cR!tlPZrOZQhk^&gpUljFty%oCT6H z`4hI8kLZ7Z5s%xT`sY&_NlR0bENn=p`lqloOv0(pGpYUTelK=yoQZltCd)>c;7K22 z`3`N)neCZKmzbUPIe`wcu$lMc(Yu%i3}a1es8@PJ9Pj_k(}a-ERERy4! zA1{%h@%;3RY3vjm9}QH0jesV+BcJ=|_L|R#$dL(DXz!e;(7xo}Zk((jq}+22eRzD4 z5A1rhsQsAm;ADX1!~|SM)Bhp|Gacb~34Y=PL*!|~FQh-WY z!7IJslfREBIF$(%Q3V0N_33thW2bFU-6HS~pUhLOUCgr6B-7Peoc9(RR9_l_wrO$} zJ+S8X##9DfV;;+uFUj0g5ZNn+SDBnIAIf_&Mn=}zV&63cRyeeJ{+pNx^-YO9>0UWrfQQaWB1&&qzZ%K?@G8=3?-c-ytCfGJ`9TB5s!}u{@-{cm8x1;zgjW zp7r|d?!}98Q`fDAj!tV<_{t2DcCOPm|U`%0=O9tu|&6%9lUD53;K;$ z4S2H=*@kZ2Wkw+^A4J}Ju2}y z{+HVWgmCvCuV!4pzbvx8=G+OLpE;HBVDcX?IhTH6onrXID4ZsgM`$_@c3L@PA{hk? z-aC@{r#;Ce($xh{hCZI{r^|6$Mo}5Gvqao?=qBe@IN{FpmakCw41je zmh#_ppZ)7yzg!e0JPV-|Kp;FqNm`A)e&`AJrjV>qSwB{Pn9ii%eO;S~@cV`+7bOW` zL$=W`oXoT?5k7N-etL&DT}~Wl)Jx@8?n*^JJSlPze=631$PQ>D`MbIs zxs;~(Zdn5R;}<9x8Fn$+2i><6zX^W;an~f4vDFET@=p_Zpi|_r$UA7qMY!6VG8X@S z@~*ma>!+@sC`_t8>qUvq6L-^*ki^(#>LsT1>zd96^t76B(*wh48JXxh5%GtA1B>iq zUw;2X0DE^Gm>Yq7lbibV_ULtkzF+N=_#M4_7pwto`Ki&pYt#};Uo z=?PzJU7LTyRkU};EtRZ(L4sWSo@x*=f1ohF==r4n9~U{XPWbB1`-R$nB*bR#p%cxD z<~*M%h^On4Gn^1$9{|RE_wmXeOlnyi#($|SDb*#c+U*4o1ega*uM(#Uhr|p2f41zd z0*MHF|K62whT={#fG8lQ*#XGG*9-ul$yJUU%?Z$!9CS4io_>(*^*(dXIx7GRLd+<) zX*ggn8%qte`U-#kAK+K=e}EqXq4Xc%r?YYLu?iiQw&DfLfahCtO32^b-1uzXYVJG^ zMYY$5E+FgNFIR>D6MMllQMygu%yw?-EKI~yVc^9(n8V54Afx!ET#^$z)h|q0o8Y# z0J31w-Av-6kw3<4@F(jtAIT~e8c&p#n`HQ)Wtdp76_IvqKk2vHMB*;G2Uhn*&c+u} zOxkXb!Ut1HH?0($s&OCtj+W8?{UW0TmySq?W~&SQ=6$VmKUYS|Cl!+ukOj;wR$l}- z%fj!!@68dA8I;R$p8e2kB@@WScbe-5dk@P zwy6K`Vyd}@P~b}(aD_d=}V=eNdm?`zy*EqVTmIJ3ND6(Qo0 z-G*cCqaDeBhTKjNd=hQ0y6+u+@Loau{AcJ8zWLA6jb^*oJO_&U3?yvP1bE>yAvvuK zW?moBM22<=Wz(`%KByUf{gW@H!RNFHemcJz<%?FkMzedc=B)*G_ z(d~7TL*BP5Sv1@3WubZ8@?`&uXQ}*>6KIdsOT4{Q6_)9E@UVW1Di202TaGS;d zN7Hu)!})k$D+!{D-h(I!f+%a%AP7;D=ylbIZlh(@Xc4_eFOeYXBFc)oqFW`RuU=MJ zz4!OY=llNtzzj2n*}cy__ndR@84wv)f5I;A)$DQeo#yE+Wkb*Q$|d~umwfv`dKtNK z^3``eQcw3{@~|R-*JYJh9xq(1&Vc**(%SH~WndeAJ+sDdo*KM9f^NY(kg->hqTR*P zfZR#4P4l{$Vfm>`y%Pu?NPx|Jw~%F{BbRL1-ahsgpZjRm=x2!ese7xlFsas}-w*=~q!!_kN;`kmo2Isy0v?F97)<@^zP1(C zZm&Bs8Uc39diaNt=P!Hy`bD`D6WRX8$37p_5Ma0do7X8@USWw%wdeuB$gBVN{ZN-r zX8pYUr=kL_|5~s3c~vJhua?c_2_8U*R&HXp@QrY!&y9yxe-Z-I=cEVK2QL!jPs+lu zME3*dU9Oy+JfPLI+kXIG4Ua$YsI7DbHTT=YPYR(4&i(_L6KzetMTZ%xUZUlv!lOk) z&uUIY7TtG4czvI)t~G4M*OEUYWl_pY$@<)2BfjsW&gXm#|4#*ossb zaymD2?bPyz<6St^(Kg)lxw-;()r}wOzCx-!S$KSNE&uiQ0z~6-LD3hO@*row#fP5x zS-Ekru=M)dz(gOZ*SEKXm4}|lhm)HGrKVymlceXK?Ivx&`^Q;7w z#}AxZ1h>nfz~KXrWK%D6%gSC+Uab62u4z>-1A~xhrig6<`n3`sqtVwU{_}2o60aTx zH5*6b$F{e}TYG)&8M)L7d6Wd@Q|0W!d^#-}AqS3j-Q_z%cbzE-|6nJu>-dRjPbZd^ zPqxM=h8UUEKV?f>@K^DW{45&#KMpGIe;~TfC&Ss=4KJtsVW6&yoyof96el;LWm2(H zpGoARLA3@i@5959?!e(1Cn`G}TM$W->hV9F=abyZeV&*(=E0FRtW&pTBqpu=lttoR z(m&fHCx}P*5}sq5Bs?Y7cUJ#lcsK)`+WP#c*KG-S{ie0=M+Mn|#+$NTcE)>*rW=HQ+oxj2Rhk5n6E*e$BgpWC+{DGy{gw71{9c{e6 z#^u`IQ4h?YR~<_&ZT!;ppj!P6P_c3OM$JkUhG-uM>T$u!6pcycN!~j~ZhFoE=Ydy* zMpcgS_u`!YSvYX?XWh5UVZg;H7}Z)GguS%6($6$s;Mo=72FC+RE;r`!B!7S6qV~3Q zm%L+R$s%T#vb7oNPqDQE4Ul8XWZNF_W=^-A*+hPJ6BD<=FnlewaYmrd@6(S~pHD3< za%EvqVfhO>t;WLuph#cr{IShK??+z-G(NuXy9*N{u*&jU7mjr&re+&rA9WW1SzwR7 z*o;o?8h{guC;3jYv@VVuIW1f`K61&jBWBUDB3v)PZrMK#D7EF+WFt6UFsBLwO19i* z;fW;IOMwi}AfJmOocBNHql704jIzbEn_B?ZmZRGVkT<9rfGAW)-bxa%t7CAvUCO5- zQ6i|Idd^GmKKYST=IMt>U-v%1o>#8NB$|8|#5U=TPm#@R#^$umw2Tm=+1^nyIz?dk z^U93J7&Pcjti(mYnY#jlq5kyY|hmi+{+M`_f2o*KL$*ZDUr`y zQOvw!sXu4`dG|1Q3x4bhhz;X-(!B>({G+nnP84vG$yEk{PuU@L^`WBeLHi3$gL!Vf z&Yy}jeuktnTl>9us@1;eE^Mn78!5z~5w|KSbI)r?B<&Z>b0JxlL0c97|BI?G{)wvm z#xt>Pk6@ZrVXb=)QYq{!fwhwtYIeX8kT^W?dY{=^>)`5Kew(v+dalb!-OpM^We;8X zKohe!TmV(fwvd0=aVC^9I+XMV zYqMZ<3(_ieB?WcZWV3>Y^K8|X;_3%gR{Zj#yOkNMizmeeb*MBrQ_{f|36 z58E7iQz>KH@4>FN0T75 z^Dyib?1BWGgii7F5{BdI5yLD(0=M1yCSwK7+qZXI^!eZaG=?F86Cr*5O}AA=oZX1T zmr7}{J0K{RdLfk;q05>II+c0ka47n+0pxli9gW4;{gnZIXlj06FgLCQ{B00HhL9lD z-Bhtu@AW(@1olmjbJs=!v$}s(+`De~BcgugzH4z2HSi@a#3ZuY(1PWa`&)j;LPQO6n| z{P;!dcWn=nncj3fHNQQ?M6AMNemMyZ_`lt1$aAVSZ7TRuNnw_A>=WbK-4j3pagN(Q zZ6yR~3+YDtSh<~BB8WF<*6F z-RDzVN`9<;MA%C?`tvnx$zq7=$7+`~ed5zAMwOF@MMOn$kD2VzwI$4qDw%9;f~%kr zvdqyQ(m2!2$_XBk++`IZ0$$fu_WlNT(!=)D`3P`p=i27!Xq%?V`RxyPR|&kTcQN12 z_Q@Ddd2XY4m?|b{b~x@H;dOVkn&(jqM+L^nl74t6d)7FT z_t;NaZrY{%x5oTKR~uE&0c756MEw4=YxfSi6)C9;kZU)K3J*9uQ zDHS>t@O0Kx{P#W?#AgZ7(i_6@X7;fY(D!A-T@QX(@tas}yZoq*Yvo^Q7;#)WBpFv7 zKEZbh59C94ScG*q85ufh-7u;FK@z?tq&8cdbi-p~%Brf1AiAE|Z;CrAM}Dd+$*hmL z?IRG@+RrT&)Ur?N97U>OlywpCX18lnKPWMhxPuOVwp2V8m8E{$L73(>j~k1^TJIvM z8w9^R-EB`wgB8M0ihKWjcX;Arid34wTFr$#;*kwV4)*UZfOl5Kx&HiPBv#aFRSTGq z4edLYiJm!4ar2i6+qf??hRWiC3WTd)k7O~0mS0aRPUTq;DB;nY?0%m6G7HDqc4nqL z$)Q}?c*{+J+83^tkL*jfz_mkP*!jK243C;j`d>QgdOSkzv^h30&HttHQavJkfQ^Nt z_VM)~^j{A;$4{3srM_J}TFIa~nLGSg1H8BP&e6gVe-S0k+a?K@aDmGGLLy_b6#0qg zTif57x8)6oF9JX6^gtL4>Q_4!&s~_DZo8d>t?R@d{w_2PhI>80I#aNz}F3aqw@l=xVMxH4dXHqB(k@;K$WZZeu&0S zl>YTKIJ1tfFr3dZ8Tk^ayRM=g^VUVgw4@@W#% zh0G|c_&v*`cQ&oGWYtWG4l$ORLC4L-*X1Z?3kH4&W>-*4BS~At8!}*-` z=*oIT&WYmC_wWbw-cw-qkm?e1g7an&*++dn_A7Z4f|?z(bYTh~9s9B&-0i&A zi*U{4;w9-vkWozL(IpQrk;edA)?Hq^kTl4$mSg*b=I=)&%P;8M(JH40>*j0|uI;-@%z#ac}y?k;Av|t8Fg=!yF zX8}_TZ#WDJdpp;!?KR}E(@P5ea>VtD+jpB_RUEwR#`WvI-YZE-Tg{Xy#B^sbdkNTn zE;p@sSkvK!EB6ZBmNgtXWxguYKRBU!bXDv!rKf%%wC!xVCBFYDhg}rCUkhPaR>}|^ z(1V2~UO}o-wwicu+}kg7gSXysr*CBzNWJU7JRc-lj5px#Wv4gca+7{P!!*{W4{@(d zu-%Hka7DQWY?Ltz2v5?nuicw?;3~0X~LI+gEFAsfYp5$~gMMWMA z4jyW1%-ht!5&h1Q(>ECj|BE#rG_h5+FfgFs-j-h9-qw`je#6*>_xAfTEx8fVvyT%E zKwIFzRuJ{jc~mM4u|I=qabjJ>FgACr#W6JI1yn&sFk!;46Owni?ej4qLZxA{L2!S9 zlSf+HG6QpAgj1)5a&}JPm`gJrtu*AownFh(f6=>a%qYC?Vu6CNe*e8 zy+@jMoxDfiV_&+lc*V&dZoqy5ZfG`T>V9CkS+zUa8q|!gQ9t)NROWN}uJVxlT^(G@ z{vfYn^Z?mkQ*Z8xqajPj=JsGU`;Tt*kA@HR4ePCcqrbI)x%y%dzN7O5a4(t$rujll z?&oLa@Keq*%uuBexs)F3D@;k7e*-smB7FE>gYR=3?z)-$!##@*Fy{B*HZQFXUE7(5 z#N*dJ*CfV2LMP6cnhHVB+ls3z$qkxsH7#IZ`_=<$p6g9;vMHU}#M9)7teqanR%Xo} z%7|e~A;Q|if*l`5@c?UfLLS<;T>?z%8ch?`UqpM}2 zOYmprjG!nadPL#HY&C2Yb;X99qdFO_b8973S_q`9+`k~UoS8eREoqb3DTxVs_nFwh z*>?)%hf}|bpHS+>2S3&<;50a#gu+=NdQt|>U7+xp9Oisi3e`$mK9d0UT!R)M^kkQ` zyOaKLP{qVq_*)ZrWjnhHpD#EJZ4W$nQeh_yuiBP%oF%|FR_7n3)$VxbmEIQXxcb0}=1oVB%FIj{ie-LfdZslW4 z$P|Fg>wzZTY6K5p_$xS}jcdW4`1+)f@;6fpu+Ef2cqB6uii$wfZKkZ0s?Ztm@4uEE z(iYM=`xk?Cz4oK7F7@Ifd;wZtKpAGFDOM~Q9fOG%1Z4l5Kn}cn9b4JYp<3a`A15TE z1#dgKu`R%4pFY(fSTmxoN;%HBxw!^i8w5LD&PHZkZ3Jj#t=mrfs{#*-@1>fEL9B!;QTw_0Q^;2>A> z=g++M(jJ>tyL2f{z7A}zL@aY)6=`A{NNpqfP-sf9Ws2$N2_IVIj%BApZfB>tloaui zeA6R5xO-5^id9n=Kh=qOvZ+SZG3)xdy{?By7&=0!Xln##!I*XNW{zoR_x$r}12KZ4 z0B{(ARW05yST_h;RDWrI!!ba?@5DUzU__mK$BYq8QTyEDhT=q1Y31PaFBuYq(31G< zr<_0>Zi8iU^SH#yd-M)K$7TMKVmT+v@C8G2UNT(6Hxlh{ofm6p&1n9f6?61enxJ$*D? zONsnt*bJOk(^ziKA7U{oq1F5BJkj4JeZ;HfqyH;t$V`ZJB>p^m=%tAQY-XN2{^Vm| zYzikI@GE0?l2&156O&>d3_c754iKNWD?Z@UioW5V$ona^B@Mw`$glDPLNFT1dp@E9 zM-Hb2i+P3W(bUZQ7LEk+&!wa!V~MX%+Z>9)xYwnYC*~x6Nos_Pzd4I-WvN5&_Ih*v zFPVzALNYBo?Y-((gKDWzPx95Lfa1_?;wrFxpYGS6@qUkr7?<$Xe9>c)jkQA;O#Lh= zfAY#xNL5W=l{~M&&1_IMatRv70-S}J-P&|uU6g5+*BWkCSDV|gGn5~+b`@MP{J!#O zl`tq!RH9mGQjfJF(7eYzEYXRcE|=9dcP6Y82*5H{(=QGGT({#Uie9XPYa04VIq#=G z-gcta*Gn_jpL%rJ`yM*xVG^b%Zs26JnpMrN4KheJp^pudR|D06>jIMClQb=r22YKF zoJifTP(5d7K~K*^+_$dtIg&Q232=fAWne%vod|2+)5%odY)H5LmYJ()7-He{D?N

    Q2no|BODBhN%1EBaBC;O!G2D(MH7Z5C5`1O8>Myj z^4f{3wFrTs9#&i}t`Hsk9Uu2N?&bf8XCd>l6~?le=j~0=tnXS@5eNUt(G9!Lt&Oa7 zAO?e=)ap;TX0PIk!f-Ja$S=BK`{~|;N~6((&yV9cP^{7&zS9~Ok?BXXo#2NU{ zBa2PU0I^+D4l zm!x~Ltc=d~J&$Y_LR-Y53%IzKp&o!xZ+@sl#$<$kyM+r{6ShK$>Ev+C`a0 zMm-}We0hYDcmtBwBBkgo z=7A#o{_yr!{BmGifrU3wl%9IEx;QC`Zxcso#V!A=jFsfdE`yPa_m53WK_IvXF^k$` z<}OBCf> z8LzIm(S6Xv%a6_ZT$kLGrnvKTe9T1YM1%x~3zk-@U3NF`c9DE~#scRf3mkZR6!7_G zDDFJmSTl}x0v9=xmE;p}!3ZG7Np%<`fyw4E7nn8MGc~IF{OJwF44t0$G|VN`rVohjn}Cl87Wd z!0uVQ)pX$q%z*D(D%@ahjzyd^IpN(-7qbP!c6aycmd@%E>u!D?oG}4G3^QN1o*H`1 zlzPn3dAN4;xF{MvaVeB*lE_3tr6{Fa+gINoPEd{Gq6ai-JlKH}wGBOHaar@m1N}Hg z$GcxOQ^`>W2r&$elM^Gz7^Zer+PwJ6$WBb|wT3l|H}RBOJCozhoEvahrj_aB@JmEAhT%;L8Kh^~uw{xMGSlG)A86Cxqb3CipVQN` z=n;8F`O!!5?3-x9gXDc>Xve-+Lg=HsSNC~7W(c}te#X!Jjo$p?Mk#qWD|ngpzW%d$ zTj6cPHmLSM(qE#eHwOjB|78OmJ$`k+PjZA`tM#?hY9po24(#56trt;dCYnwLwV1A} zm<rP!Ha)Gt4Q=dt-1;%dbv?i?WTCL4={SjkD{E|ZKM6f z1V8`*_4b8ypivLd6>kFCKeWi=i8aqTu6(GB+-fd_*pBn{9-DIkQ|m5W8OC03(7M9) zz`Q=JR?lOo0tjgptgBWw1S07UEX!J$`3(kzOvb+up9%{NJjz^20%F2O5XAtN{r+YGfUL5!vw`a_+^nMHcOg;SA8zg*U6JSlHfB#h=({v&ebvc*ouVR2FNzE(F^+5? zB?=stNIyDPN5Hj}2bNQ*%VLIde3(-*?AEQ$ou2*yAXlq^ppWaj7G!I=+Ao1 zXOl_8Spj19cpm~h_RbU18CK(Hy>5vxct|$V-06u411hVrMnv|Ubu$(=8bBxePIy-# z`}@l;y3)<5FSRpi7xe_D!Cp+J}xJ2b)=L?t?84e=#%fTV;Q!y8qm{? z{p`1ZN+*J?eq;S9+m&u|1Tp?oV70bm9{Syq_bk9}?St zx;~Oumf0K4L;%+13}RHT{_Wg8wrl@PjU2z5NRg2pFLjV4z^S5CW+^%5SMlAB*`ANF z$Dax$mWq}4R|xhL2H=wZlc91+Q`e`W&cR`)JZh(|9VK-ic-DR2CGM*J3mWGe;Wt%_ zoqAsRmUT>hU{6zG%QrR$KhN~rN<+WArHv{OMCwgrq85=?vv*&1;d{zTtvOeW3(2mK z%fgoRid%UhutL;g#V_ig1Uw5|$nsArsAA9IYkNvu{X!jn)yu)ft_K-u+nMhj$hVcI z&3-(*Etu?6=XTHp#ZAqr10I$Wi8-wJeouT>U1{5+fn@5o@yuA zz&`4;DSYhx3x1Ia(0ObEtNzY~a4wbu#kiJbR{oHkzwQ7kJ2Z4GV^QW|wsyh8F63ef zJRP927Pw}?J<6AYT>V2wSHhreGIK7_2Tk3bsfO{#y)ow07NBa{C)3*WChp=9t)_6f z-v4NO=qs~XztksYDgdv=${GfA@&Yl;9pjBV8PKm*{#D{`lJ{n!fL+_sM|I|O!IRa= zO$_r{(ePLfto7Si_KH>_6gWno7)dqs>a`KhUu3_Z&*m1{61K_o|l_%*Dqn*RMFeXpH4{pjoo zxok5TWLMen64}CX2i`fJIifE6R*S-XnJLtav`ha7A>^*`c+ZW&n-)@&{{E1y(|inw zB313U0Nl)n_@ub=BpS=rUVA-^z+6D()7o?G^;alaSojSJR=yYD)%chXP@N|D$|Kp{ zJJ8+8MOBr;JUKaR`yw8ESyA_d};G~PljYX@GuJy0VmE1 zDOYOaerbVK-!e|hU507Hy%#mKuKMfOv1s|ttZnn==$9RQ>q;0Wnw(Qxf*SMX)kXA1 zhhtV8{8#rBg-hqb13$gD++k~c$zppMsreWZK8NAC6OrU5;`-HEhN*5&ONOE5k`!{) z!6~b)*|Rl)(B>q?9Z@d4nd+rB335a~;$0Z4q!T{QjJT7ZK|jQ#LY}FKT`s&kS4bkQ zAO%rMg3w5-xpF3>f`J8?UVJmE3mAJ*{a;CA86NA}i zgUO&Z7juLRBwbRR+CV@+dKdH~uR6`dBh;c5clxUM2w@gZ<2^;j(bVncF zJf~j!IG3)v1s&D`7mMECeL;P;pe^#lmtDgTPm8~I>Z{GBsPN&6%7u_-{_#UZ%>R;S z_$~egn*qV;D99*Saq1T_xB_Z2$&ZDWfHvvzjqlBZe2s^e9q4a3c6mS@*_~w1DF4_N zx>lP^Vz8;%8=2^(I=HD?&hRep-7EDW180mrsH2GZ6t1Wi;7M*-`I3LXI0rNG*t1bA zA}%zKhJnDPG$jH^y1d&QXy|0Cx1M}G$B-X*i|Wxw$(oGc3aJP@Z9O!o2NVrk5C!@p`e)tn^{7K;1!JPWKo~ zi-S#s!Ys4WTUf!wZxHf2uyInoIk6$5VSbd~0}P0Lo3_4>A3kDIuE~Di}cZ zS;+{Lq%z6&;pW*Lo7sVn!yGda`ch$QZ$6S&y7RRB;BX3a)dHxkf)(Y4^r`i8HZhFY z%XiVlL2~d@AH#Zzd8}%$ai~ARt8PktvJW=`Exz|Fbvdw)Xm#puN z>#ceFJ%d=-B)m04^d2gmhQE|yQu>*ztI(iFgjwZm=LkD1BlS(wbWr&k%MW5(+|T9p z`6;nq!K(WxMuBuUkuN#p>r#I4If5{xW35!^tSpU*YoukF>)@xz0D01K$erJ)rYCO0dPeLG4$>o81wgd3j)A&gfs_ra1bIdBTW-RtUN(eZ2^K9Y zta2MeV4LY~G8Y2R?R4~$1`w#U8xfZ`#ZeJofCv7De1o(U-F5f5Zbxludy4B|r(+`r zQM!}7beSo~sr%1YAZSJETP=Fkz@uDiDV61Ag~=hVGR%m2#3PrpS*mW;rorqUew_p2Kd2D-vn}AkcDn6aaB4^)YvMHwXjIwZdG9;MoNj+d2%lmxe@00& zYu0kKLYtRub8C=tL2!yZFz-Kl=m`ntZ?Ep4KY0e!Z_>j}_RW#8*WkNY#mQetc3Bpr zVhQnRDiB_rkF8}yfAOH=zOW9wNj&Sy8I}5a6d({>)(=q!~>ydy3 zakq`h8wuU74R(CJR`p@HZG1CTzpB(-OnMZXcvkw191?+gMtvA`H@(DaX^p3pirr~Y!rqbiPR z>R=brP2>`Jw&pPSlEAkA_PC|X5jo0o!!bJ$7lZW;6Miz`AX+Vxk5LV+UiEKjcU*$6 zy}4V%pZpCm*(YvJ-5Tx89#?a62{Bw5dE+%9_Z4%Fxw{pifL1b&1h@2htKN%f%8y?* zu8fQbZ*Y#-l&bvqZ4T5AB5%K6fNMnQ!A&+54hHDT0A`n19@?u#3=rty68bvSFK zD|u*lx*`-{nbmWYC#k7UeiQSR+OV5jYZKw}>ixuse<1qRq%CM1zPP9tg6@=E<7M2+zzuWU1_FPc>x!t2a zTXUM8xnWm1X>n)uX4FaH*gpR_u|MyqzXafO*;@N)FkrqM9x5Vi#6XE#ZexnKJ-|gQo$HB$`E!LgFo{$Z!D`rp?G0f&%|8+z+-x* zg#q{>)Z|SOAovhDHgWZ7Zi$;Q+guw#Xxh`uaoqvc( zmwtpkJQscg#Dt$Np=e!<=d&Vm*a6S!+{tyZsW6YaURUpe6j$ayMYKffJDBtievHe< zrfO9j=N*+btzOQ->GkeIzGmFQw!SM=NbYKqN3rt#ZFq>(lSL~_imX%~XzZ-EcJp&; zx+EBDVRm!w#`lL`4gX~ia(`ImC%1bYrUD-Lg3IOzS1xdMnLxjzAcCH{RtY?lA^I z4vFEFStIO_JL{9Y+^u$V;0#0GA}7zBqp{Zw>6toDH5<=w^?uaQK)vbt4a^l_mtI+` zog_L@wkG}YvDSjV{acsG-P_nqU)2V` z`Mc@$^d38n>Dwcj$mRZsg49qj=PP0=ty$Ai2CA^}hyTgN=l@>j(EpeUksTB*1) zReM)yJaR3~u7T5iEMsuL0l#8(bGCm~$qcYvpIGX)Hs_-fzZ5X(TiOH)uN|`peQFk7 zw%^O~b~#RcP=?`O%Y{p+Jd$sam2>SX`SP}D!djEYy$ywqOlUrp!3>)%`Y)AY-p6St z6IteGLh@&jjBU8)I8s68_quGEsgyI3wulFzXd6mi!9PP{%ZcrpwQXt(0>Z4txH;jG zcRG1-lPasz0;SGlAO7Q+?>B!qni>j7Ev;z$ENVZflk`vf$(S?i+3!VV`uG!Fb(Q+l zvQvfLL-@*2=asq{qt%BuIrHYX+0Mwl`H(hTBSZ7dVI+RpsNda(QCap1Stdnm&MW| z#`V{ z7|=#~7wkS_Mirm{ETdDJpWnmT2x;T`dF>dT3@hYm2CQS$31_A zGuc$kX7&|2b<17URiXDgAL1yh+XS4ul{Nu_@`s^|x^xf3y1D|H-5tTts}q`C0k5we z-Lf5B9BghJ5XhFaU2WPgUCPqxG1A^ZDx``bfHz*2#Mbx8Wf^%+_3S(|j6gaD@O`WX zyjA!*{Pg%Wd@DB(^yOJgb1AlVcxJEa^-g|ep)#vSsxuMX5?wh_=A)=U5hp}-rK|N} zp=Ajp;GD;bx~uk}KkA4%}E(6momYM@izdwr$yB#`XP zdwue7m|~c0Gw3->4W+7JXtgCVpVCrA&jUDBl0fm@i=g{($~8vjjX>tTah&18oP?v8 zWmxflRCDrrO7X*F_pb(7g_k@e$cWPIi+<|Z=Vv^g>VGJld?QZ~&()rWvAj%K@rBfA zs2vFlIY#)n=Lgzd@boAD9%VWCJ>58k+PhgIFvp0GNZhfJXk^Sl(>2zR9wAU&+sn}p?E}y@efYZeTDMhLq~qf zJ5wPU)M3J2;t}OavD^MG;hyT%T54=Waog;~;2jT>vy!TWR%5sv0{l=tx%lGRbM^7& zCf##iH48Fd8Hs6Z1IUwls=5$Y^XN>( z^$T5R9-aS0t_it-ig<7MzqTvC{y;F`2=B^XBCRU8Cf-6`zsd@9JK5X*zFS``rYj{= zj1MM;Eq%S5Q{UYE0eG!4A1iWpATT*}Ckck^W*>8e!X{kZ-ArlyC8Vg?iDj%9veAhAO7$Q$^ z-qEqlV)1ex^)h@lSg`KKC0Piz&cJ@9OT2zANOT!C$)KU^IXxrCw6;#B*usw>g6uLc zO48}}_)~ISy7{nH#wh-#$knDuT<;7BZ{~M1o{Cj=-BE zx@$6Cu-mt+EvB2qeIr1 z$LbGjq`AXIO2T(Or<2y`igxL zQz1?Z8RY`4>f-Q%z7~T=y}!_;GhupTx|e`pyv-$P3OrfRR4%{1s}n6%?}%3~0P`(j zzuwQdHJ53JAad<`@n$0Ye=S@rCHsXf;p?wo^pTs9rqvs3&K-5#O7#4` zx`vqN$_#@C;+Ko)Z5##>gPKI@M=S5tK!D#+l*mz7qbd^&z*?2Y^Y?~cL5e#9TbsO` zWj;5Pulama-ye!aJK4?|abI$R$`WseK@l34SiHgY_oIFloFyarb(EJ88T|;t$q2DLh8iqq0vsYZ9 zv{!rl&ewe7TKLE($}EW-5e34}RwVHwI$reVS2Scav`_a-}SJpnaV{v4;EHpm}TU<~}^ z`S8o$eoB2tt-!?hhZw4HXu=je{!(CLjqI5w4Y9uAP*uf^tb#wxV&#(=!h^QCxtZm9 zF;EX&(b?7}>^=YDl?O)&ghS<|)%@#aANe0tF0=hqHjyJnvTHZ41D%ggzi<|tV|_m8 zJ~VrFrT1sSggs+0g*}i3dV0@`NwzqgMx_n_T~`d3SRQAx#=(iPTS*D6FV=8oi0A8` zW^yiO0VVk`Q&Am7L*;1fIJ{hO3_iIZKcyR>UrO1s6Kh_uN{J@$WTqnf1(bak3jGlt z;<3M)7ckX(6*5_S)hm>Re%dCWKiI1{3XuT=B>AKv*&Sc z>2zu)f)27PTe;U8Ie2{GY;ATu6A_&Nvz~C##Bl)ykZ{3Vl_gg;x1H_Gu9=f!HQ(qJ zWrQS<4-~}j2$cmtbh@bZ+l4yb0 zoL_xBPPiNgR*>v$&K(X&hJk;o^9{h>04oMO+Bq7ks=*Z%72jT)6Lij2sT2FXR)YE^ z)6kgEf5i}HS9a=il|k=Aa-%DZ0Lw0buqnORkvmGgk$?`YI*I#<_GE*or!oB=5ex@H z@$7M!>$r~7w(8JC9{5o-Hjl*1wSv0*O-N2FQTZFu0S@MsIN4}8ZvmKk$bCPA(PLHctFQmWY4hG_F%QYAfO8_?OQ$g+q5#m1;V{(l!>+B?w1p=~IJ- zqb2fY%Q+2s-iU1h<@YE+EEXrlZYdfDbLmeK4riH%`ai(a{df5aOlSTpoXE;$E?Hsn zyQK-S7=|GON(zyt`g??ONVpVh!HPdoo^GfDZF6h{NFkiRfbZBo#KQ~6LcAyx4$22}ANiU5H1G9%8_SG%w|sz#QuW*e_}Hex zdBw?XpBPYhY+3nPVK6|q56ROuBAVO={fNrnGoUtN&HD!pff<~=T>>MV5GBDhU+N~> z+Wl2E*LLI2dm69$vWCndP!WJta3Q-&&<`bSzcLX7z!oN!Gh_7i27}){F>}H#M6Ivn zd)i8d`db;CUFU)jlt zeg)|t46{&F?!WVUtvY!ZJrI*0^_RqByzm(mP@ugcF8w+2YJqqQe$R+ym~U8zMDdL5 z*A5AW%$W8#2CD_{Bgg8uY5bmIi1c~lUFOSz)BV*223V<|+)fm_Is+<}WudBiE;9={ z<59-56*@cYBM)uH2OSO$gJrHrkxl1WAw0`c6a2!?lfK{b%8Q;@}0tqUW$4o|rHh1&3$FoYFd47SPr{u6x*9BC^ zFYDKb8MX9QS}p92hOv0lgMbVuu*|m@FNgt|f@yf&JUgEAa{umoQNM2u!BZ_@&NRV@ zCpRv%XC~v1xz9VS9BJ-@D<1gm_fVWb{gT9i3_#HNIZ=N6{HD0Rvvm|4Sd5S<#_%KA zm|J=;XH)q?-F;`~={?XZ;*c{tJUc)myF-dMH9ft-@o7^7Np}l+L}WsW)PEZrr+=`| zB&5ffoht#4E0P71h8(Hboso3ZJW_I6vf<+dcTMQz<{dbglC=(<_ zG*g-s8^0CFD5mfvS1AQ?mIe={xQx_>{S8N_63 z;u{?KbyPY5P=z4^_%n*T>~@9hc8SrSHuSOBVXu29yLZh>*Ro00u%<6ofLyoABhXVH zgO`k!Az-XHpH&rbFx9Rw99)yg1k>{LlFeIfsUMluzJ4{~ zm%tvSIq<-}Y210y&zv&6W^Jjwxp_)Ws^9c7{=03F>)*MhD3X4EIuaSy2{oVz;-9G$ zIz8ReyONu7lBRp{*PWyHfuUqsDo@*v>JYN*0XI<8hYKay-%q>uJ{og74*tHJ(KO?H z=WvK(evL-$uSzEvxRq0oPa`#_oT$a;S=tjW5hvmk5#>`7nLzjPo|h<2prfiW3It#~ z5NKSA-R~?1FL74HWN)6fN~95k>|X9#^V1|JHofR%S*Ci+eA}dk zb3WsSc-S$P>FXG}pgSp7(v}_AYhrAKYmJMUc@}|9swDbnJPzdj!TC8BLsF(y^YUvn zlGR-E1z-$;KjyyZm3wAuan3FbInfNc*HrZ5uBEg)A^cO6!_gx`{36zR3pNr1jo1=_ z>6*7MADw9AcZY6>w$svGG1xs!t63Y`t*>)T6VR-&8@BK?wguLJk!?%&x6PH`&4Kh_ z--D%S-@g{!R@cQfTV@Mc_QLjKDzDstwV*1z%t?O{cX@GMDSLYmNc6p?eLhH+cYI)7 z;bu=_NeSj74n4yR9Y7w&R%c$0qnlWPyt_2Te|;J0F#ttDw=^r zCxyb+o6klvB-A?B!|qH|7e$ExdixD7sUomptG@YoGwpt-%Op(~tNkQXU;460%_a{s zqQkV!>6D^F2I-fJYw?g2k;oM2XjkA zp(VLV(Iti+XUWO1(CT}Cih{JJuAmXbe?a~TO~Z~BNY}qplF#?u?UwhF{w@HG4-isG zFn4bv)$={3d8`blCN88Ux!$SgGN26%{tz z>I$6mB3j((cCQqkP$!`4!S;6TZRSeQzb2y#)?LM^;Frwk4OSxSuz&qXHFf+7Qx@jL zApsc7w-m9wYLk4{NdCk|t2mfS{_9R_V21mhyY)Z=jKSi?q7c~Q*-;ZqgfPYE!~{-o zxFV^79a9&$&Z2NhBRux`cEkgX9%6ysJ8y;eA7|Fkt=!F|nBl4QIl;r3&uybM!@%w9 zTw==01tNk%)wQ+FH%6@Mz7eUm17uQU%a^=^XBdbp)`P?45>PXYkDmhwzb9p!)XfAV z9zJBQYS?TVWDm_vQ{=%xcF5729M*^FjBJLEu>n5peGXS;UN4}>DD?ZS0gkrX?g!Hn zI`>;jz>KT}CHRy1x3FVetBzq$>j`8{H+t@NP$x0Ht;Ha5mTsQN3}(IgCh?W0F?(jl zXQ=t&?X$I>O7GczAo~$qTB5YC_=C(E+t2vgy*=(dJbhG_tYzcecIZ&N14xFPWa?#9 zJWKeO$|@x3Q<^Gv6ZN1vIe^ZP#lm=p)VL(Xsewn%bdnzz)~xbP#_ukWnDx+>-?AzA zS(=gbNmS^R?6skEmTfDPqvhu^vR}!=L8QdgrTNnzPk1bH5ngiXc5- zO*}hB%0d&0Fs2tW`eHU;z06(J|Jk={=bU0KuWDW0aU}45^g?^D66i&%?XEeR>J{oN znwNuVWe_Yut}G$BF#%140z|ZUY4-@`B#6FG5(KngU(&8J_2(5=-}wv#jseT5Lh2vj zT??clH5U$`AjVa=|>T$nH z`a~Hibcf&VMN1ZCKukCcK-sLz40oc~lDe#R0W^xSKOOI(@>P0e5259OY4t`PC zu8rq2*LQ^-8XZZh3S0CxRDQVWnu0Pn(_-~=%##fhObIXQer^BeemFAtWD+eQCBmCi)b;+Jm8j&q z@LyHTI_?(JUm88BmxdqoavB&v`G9xl21-+YoloHjVtDd2xte?OR95Dlo}QlWsL%7!^!M+o zG#uH;sY21dX6jPz0{lg{QO`F6b;rW6Hi!3fQ%;ZZ7McT2hlhvTPvxgH{Y3j&rG8fp z?)_QOb~Rs0YK?<4i?8DZyAJVtx%IGLPS*GprC4US;)6n5ag0i(qN;F1nJJU94~5&x z$Fk@ascNlM2T!rUdm>drLlfcz09P2w51dOfkd_1x{ z(IK=be}*?OB6+cL1JEgN-MMLJE&%b zhOVy~-L+?bIN@=y?77Hl@zhX2POD*`(hfl`=wbGXz+EVtTI}%L?JDy};$wAdIHq@K zVJ}(WN*1zH7G4Y4`PJ8gkMj49TpOls+QzES{#aQmR+_xkM;&pRcx%rx?^vHiY;7;B z&Lw7q;Gm@LYa0fLsYjenO?HQXv9FJg5ONy7R4 zC9c(!*rj5n2tfR&jnyfGhi0j+BX>3K{i4?{$f;?J*si1!rP$q-39juONMlVh-AYRL z{mG|6I2pVfeso@e;@I!jys}UEvSxPuko17M?2-C^M@NiF#lJw;mq|{TuW2FcMn+v< zowO#b?(JbW<}37zgtcR~G_P|ol$vd7gQ(c4K)qw}GyHrDMl9)CuO?vf}T^=w*aqN)x~J+iJJY-4cMEh36`;992)!#03_Ey|NIucKW8Q&;!ZWiWO2o0jt@U%EM1#3{mtc^+1jlPp?&`y12MiwQK6b~>$ug< z@tSraoDJ?gAs>(g4jk%pPXc=lz7+1dy&mXJE3?Ib&gYRVzcgcRsTlWOz^aDV^;{ZyYPfTqiP1T$l};n0CE{(Il(kR$>BEmC33|izNO}KV?x9 zGRyp6NT}p!F_udG!YZgR?WlWz8|~DUKmG+S@fg}8h39mqaEQP389$pwR?P~dcWpTV z63K&BByV%pO-IIeUx|HTt{>^{>XLBF>xauTpVp~0#=3g5?KosLo~&p)=N-9)$H)iA zrpY5>HuHmK4~||oOqN>@`n4OEf~pj1N5n)L3tGXYCQbd!ssZ$%T1rqWB}ytXZ92-e z{EnGZtk9Bgp36mPZ)GCL3+v#8BX}tkb^OfaBr7z@oVf#it>{Z;r2m(}o^mmRahOM+ z(!d`9>_km#gS_>yJH{p3y8QUwbFpy0?wSmOjryUrV9nZINimKtHM+{0!s-g#5an$y zW;B0}yG{38>|HsX!60VGr%_|cI!v!>Uke0N!6?jR&advLEdE^*n>yRj)V4jdO&d}8F z58xhN@o4AXMd4fElo@Gx55~T`sI}A&8@)J^pJ}_wt>MdT>W2&3g{+DdC4%n_2wmQa z=w}CfKdn3cl(Uk2eYFsBO|p9MMtsl{x_x+R&cbSZ!uj)&fHZXAV)de7YB{$(M6+Sv z7>=QpnJmx|BZB9mz!E0=)Oa)N^{I-}W*1dORP8O(3Fgfhs|#M?&*Vr1b)$9RPQ<`O zj#8u1)sqdyF_V3O zt@R^|>C3runp@T^iI&OK91d3k`6!V6v1ZX7i+C}iDuyZCyyn=iUeME(SFE>E<-eCJ zgp=uCLpC!o5!DviNjz*U=0Qeh#x+~rh)#>nl z_hWYXa~f6EO&5tuhWa(PylN3?o2wi=9=AsBnZVYM(exwAT9}pDYQ%L-bVi*8=z=rJ z_u=kDtRBOcb7m9-8FC^%|0k{EsU^vU?cR9oZNAYH>^;{jYf$&zJ0fT#Dn#RE`XAPn z5wg|ghSn}FUznx6hbL<}0$W)2pZFjCS&hGEfnKt1SYEe4F`#7T1~!via{CGS z$-~bG3&GB3Hl)?h7*YDLw{3VGxbshyz^iDpxm*>y2X!NU3 zjsR|{KMxdhxxgD5IHr|gsNwu{Aw#Dv3VNPjS8qxYjpb;r>G+l-@{!&6th52>`_AqJ zHLB9x%-nxUx{$#L{D}bvnvN-|y~6zZteEAu10r4R)|q}H^^Ae3vs2~c1n4C_ zzkDLtap|DrTOu0_T12JGx~P$_>qA}%92bEkf{o0JnJO4L9hHHxmyb<@4sYp|of-tEVB?;Iie z(h3(2h8EH)8nj~OdV=Lf780BFPwO7m!N{&4ftn@*nv9ttj8x-`Qcz$@R{^;R(PD-X z6@^aAt5{&!(hT8E5NBRzJN8TWp2(|gz8nzml>qg;@Nm{$NSIs>bsfnS{gofJUqB3O zBixs@$9-nHqGpxz-N%2eQ~>D*83K25&pvfhVm%BKh_6I5FJ|wk+A}hQ46L_LY?uwc z`aAR}pqXzi-E*jg#d$b(Fg4C;I97C0cyI<`k>x7xH7V}!P9pQO_vqO&$*)}!=9&s@ zj=WKboxZuL^WpjN87HgH;Wh<(vdW88p8x~p2oFu6ne{TlGcMFp#YiOm?+%N1e?v6s z&gMi8uizQWlf3vx7dF^uR0Y^l8p?o&Q4Xt&VNFAqr<_?0+)C^k6xe)<77K*HT3QS)5a)j*1FMVHiS@VhJum_SX>e7qzW z-Q6WHI$U)(bZ#y|xNK*4w;H@TK>|eIV;0rkpc2;$o6cGx}#G0eocOvP##B~ZoGW|S0X$9!g8h_C}yP#W%jSf?DeQf~J`yrKlVW^NhSXTf?8RcYdDJTruD#<$N_ zDwP9{DM^C2t^;DVw7=`?Df7lppxM6ii;hc0Te~k!xIdH6ojQ?OBOsdA3t9!TG0-C4 z#q+FouexVcrvu=N+6Wx)B8m~B!}P=um9`0xv|`&>lq+(1l~ozDc7R6sehX5)bn$}QD0R{f~rD*qN=nhfy^U0of3v(vexQqZ+{v==p*wuZP-JtkwZ9!ZlA`3zFA;AbS zeCV>9yblSszf%d@K^jk=-yWJ<9i&ECUN|3Uav}a|KJ+nbtPgNIJnc;Wb`>POTl%oRIhdac|3KegmT$MEI;YTm%EdwWh`Dk9j zdyj}xnDdjk7^MJg$K1z$`ZuhgHUj>SgR?V>@@;#XzkE%LS6lW|m&{`ji}OK}lL;9? zFQKN}+ulSY`CbM6mCa!E6iVk{FGZNqd19Fb@#p+IAdSo!RIR%XRuw zjxDD-VT=e%PC1cxmhJffrKh4$DMY7CLPN@b85okfIOZp0aKDU=?wDFq_HEST4Q@5E z0*;dq@~!cHZboi~+gQE>Ea%qQxSISW!Xn>Q!0*P|zGfJ7o|Cq?0u5<;;@o1b@AXkU zR^Y}4bq2hdX2clDKPbVb%dYGdKe9-~+|6e3(kQT}Ie1WaSpuTed) zSv0yEZy6^@PBHAF4q*<1OD~@-sU`?{zqQ9G)k#`jcvW>C%nMx8KuU4HX6dAVA&Dv? ziAv=hH^uGC89(|~8!yq}D>?ptQc^|8S^Ww#84-g+cB8k zRcbE0ZgZ8Yej}3HaIL9H+B7P~>GgV50J9$)7Mz$FuJjjt`N_LmBSpi^vl5F>(c{3! z^cR4gfn9HbR^N2st?!Su%S~Lp{Fa!gD|5|tISsa7Y4Muz+jR_>mYL}!!nWicPNT6v zO;>HaiSvBZ+%pj#(qQE;cqn9YVm=Zn&t-fj8sUMvm`Rx=OAKS_=nE!5T~N5}n)BfM zBnt#ef8Z%M+_ij16pW8z_|>;-yVWkQR0@DUBov;sY|R4PQt5zt4LbFx^Naj(@$RBE z!u%S#F@M6=HtfLLQcq!@U2ZTz>~_d%v6OV1o_x(|vU)Q_n4yU2cJoMDT4n9544#Fu z7&W*&-CAWKG2gan+BT-2C?&Dw^SsEqzGED1qJ*h{nPD?rqZve+;AMNI`_Y2)hijrdbK8USCd2gyl0#8&ZWZk+TC>?m9nN7_p0R1@0 z%wF4X4Tx`)0-h;5(6VZCs6mXgGst9r*XdOlAAiTp`uReTT&=}ZM%db0)ducFJJSZ3 z*Y+3kPqvWF%wDNeeXF?mqU{-m5VI9(>a$#%D8U z00F=mkqaJYlzt4z1vlaw9rI)Tu9POLvR=CYv7dP%KeJg%2E9X%s~kq!=F3|U&`RM- zyi3qJ^Wr-%n~HP%B%jrI*G|v!;5UVn11BNli%Y^kJdArf(`}NM>37WY8a0?|{*&R? zY2W>GjveyET6&dXU%7A^L5k7jai}OS-P&!){2y7D?=Z+gwRx4CXJ5-$C54Y&XOPJk zua;g?(9|nQ9wuaTRU0pE4cgz)$ALzL4b)(w0>+_FQp+gIaNPtJz3~1k%UoC)m4fEH zb8^yXy+U+|GhRe=B+3LvPfLNy!@!eHPWxWoSX+m(*-y&e#=_Hn(W^8(Dsei}Y)Ka2 z3u`omdR&$M#yPb^JlQ=95u`hZ{l>YKG+yX)Nfd1K8)^9_0lWeK(qQvpoM;ou=gvfq z#l^*zW*Kc5MlKjZ%XBPsRsXb?S>_bsJ#jnyQlNERL{^sByT?0OKm!z6)h_dvj2y|f zGrjoa-S7XO1)%S`Sj98(W)?potM~BLi`Y0XMX0i$kL0=}=Q$0@JD6ngHWlNH)OBV=au74W=ZWJ!l`&ekH$sUcJRRIEfIQH4UDk&xvrvJUO!&uZx zTH@o(H%9Ue?MWZ~< zp8?Re^!5E3sY7RXdn5cP@;a3mpbOiQ@`LNH!5@e@8`pPt%khzlV(zBp6jaY-!J`@+C2PZBP%j6+yR~X6*ZoSP2?XMe&=cBI&KSPSCjbMJ#fop_U31QrUb&qz6glVWZwV_H!!TAY?EM1~dHpFmk8 z2!EzI=V6s_vmY62(=>QpE13xP4)bu=YA(-ymgX*Oa&nFL8PDFOJ!;7w1@TUgZsubQN->%L z^OJL{Rhzfv?M4NDBV7c_hrIOX@`<&*M-tfR9>p4CUZVUT>*bs2w1TV`54qHiXmw5J zX-{^WGpeeDqoOG0_equ@KF*^00sM6-KkA$M9l$%nzI#`}MTzkuA$DIQQxK*mgDC=h z*eFQhkE2=(eFdv3I9(`Vpa-sf?W4?hfRQw7byjG*@R>$Swk-98=LLe_yQZtJ9LcVp zmAO&zh)F>uWooI1dxpevO+y~ql`f}a;QA`N>}dgAnA5sHY$wH;pprCEU%aCZY#3{8 zQ~LfJB-&}fx_TAC8wLvwKLkHTV{Y!IkniO;HfCJz$yaVC+)H?koCtzQ^OeL2OhJ5e zb+yUld9P0&m!uq2x|VlU4m{qWvf{=`1{!luwjO65p>=^emw9UyC?MTvSbt?n?ucIfftqP5(U}R zi&4&p4+~@gnBGfNDZB-y`LO_BxwmD}1RpDgYRT3lfS>(dG103=`_Ym0sQz zmN!Fvz+L@tc2cf=*R@I2bx*nF8pcGa@tcEUW@E#i=Q^7t&Fvz6MtD6Aiy-iKKveBU zr9fWphAe6+L^$n@eO?qJVzv4Z+(#*d$?uZB0QzY#OFvE$T~5zP@s*|M#c`ZiYgRNepk_KpFP zYK{5#Ds?4p9sW9w_xmOzMI*QUXbp+GO9kPl71cch_y4N?m*N7N{$a%g{hVs>_>z%e zom{5^(GeS%t4U4t$%t3kOj_Sd7VpEdLrs&W+)%;Dzt!<~iDxSJBT!l}p+IVFiOe5i zMXX+j+jq0-Rvg>Lj3I6s0=JQvH};31e_Vb0_O-y@S0L8bB5(kFN!FyOyuw?OJdQ{E z;l!sO%c`b7k7@+t`GXxIXHKP~I(^bZXAbjz*OJG%Mjvzv0)n|GGmac^n~=wr?7*Eo zx3ErPaf&7sy98V5ZJ4egpS?oZ*KWPe%K?yr1ZlgiVHNe8tR&V+H3>8Qc3%)E?#FvR z#MnzZm8#AW7gIdT@JVAE<%Al{ZhWIDBE7B8$R?G+vMaL)^@aY6f(rFhsh`irExzd@ zt=I^vaC9Cf`HiYXyy-z-SZx(}Zhv;x^*4yNhdHpvOQ$9(Y=5;LQGiU%MYFRrZike7F^SFN4~|QTy7yl0Qp+6KXJ?M8m%wrncZcthDgWKD8}^&eL?M{sZ&!`? z*)K-{Zl?WcXVl5{4iD+B-yBLtt|5=H^nJ@zImb}V$gSDBe)Evk3}yF#FU)`04RS2< z>`ZthG8f9Y?R?iMd}9!lNq6~F{vdcH5~W$>Mg25jv|J@FYYcrldccvC?`E>vzE5wu z3D{ig5RCM*9=tFeZ+d!SPN`7c1)ucw#s|CKW%}RGJLJ{!#HaBG&i`^8Bzo>Gw*TrQ zHHVe$oe)G!$iS~`@nO9O8?1rM)AsBFoCxjz(dP*r0J6=62nAl3QxT&p?ybzJ2i{ZS z_^nB)aZP<_j}sna_+)8c-fyY-KO3IrozG9bVReBC_9{we7g-F@GfULc-e{y0AbQ5| z$cvOYO4)?e82zzy`QF-yDeo8zhZB>@W}6{sGILmxXWy0dybx9%7%godL6{ z^mf|*E0*O8!Yp2nmfIwcLJ)5S%43+T^Q4ma(7C#I1yde3j5XH3Bbn&<7AafO@v8H1 z(t!vBiZS;B#_*zzyUt@crb4dHPUO0w&lA^wqJtjT$C_bAKx$I(^##4(&Q#j zG<&-tfvm$)l~r?;s#llGgQxCODGo{&enb1l35jo}MB@B2upUZV>z(R-b-jPf``N}g z!4e^EBY`zFSo)OkZ0my*aG64B=n4g7F;^$7&1H_Z*L&E0m8d5f(6g1XaR_y79PwI? z5FK9lAl9L35w3PCOFvP6Z;og{-#$P%6qX9!+84>N7%Ca}2S6)W!%bAV(a}4_;i#`$ z!0e@E0`VLK158?dasM5eJwgN^&tdT9x>j+iVs-h+-l^0odJ@-*33>Ou!rrsY^5D9Z z#?mtVKCKxaC8c7$z^i(xn?txrW~m>E1cQ)Spr)YPhTy~8QF5`l~j52O~CZEV>ZwemB*LB1u2m&)rJVc0)2nqw#$blsc zY^mRV0D4wOXs;dFc0vKD?YYu{1O^R8qPM(@fr(xJK)iHXp8AkdkQmsHgM<(MYW@Yh zCS1k_-^@1(}Cm%B_z(1ObKK*RXSO>j~gA5a;c;%YNMp4AN*FHZ0TI~lZdKl z*W^JR93r$Zbl-3Lb&ZkjfdFlfxwjuI69rEg?u~KzbG(k&XOM{n&pc$fVjhXyiKxebSc*T=Veli4pJKLVA%nZgiO0LgAyx66xgGQ_z=YNL z)pN@D5R(c9u%dffj0JBMJgY{P>wVMbI+PLDK#%au?7if~k#KT<}S}f7tgSx9oNLKs=q& zRQ;xfsgtveTfX`UB;6}r$snKYZ{4@YIV_Tyj9Ca#@(Ne6pw*JRftQA)mh5NT>i-<^ z?9PqJ$VyM<)SE^jKDv1$8Yz3hPWk6pC~S6?77mGncW*}VUN`QeDGFqx(l$Clgd;45 z5gi<^y@9h=E)!RsuZj}uG?&rnWseV=Pi73oD^KQTUO5{Mem``qYz4%csp|wbOtv4c zfjo%|PyBX->0iDewFRIJIbO6r z?QHY5+n-dW3%$@!|hK}S$6H7x#& zGi9Bj&Uau!X$G@sBQSGu81(qYnAE-x7%h-QjrD!G)(TZlK5;w%Eb;lDjV(rf#*D|K zUAObLEM;*D6ApB#VS>p5WSorGwnn80MZ3-iIkE z<<9H#Pe0sEN#Kn6Nvz%;SAo`{$ABEx#}|+R7ABZ0ry*`4tAIf-l?N~@ZCl+AkCT%? z{T{X8z@H=9Nr0?f{sz#(_&!IrIWtN++*X+z%dM>T=n<_SYqm^U$(}|HA!)~y1*YYJ zd$$qwXrRKodNk-t01@AI``B>owBoNVx1l_2<}JC!wHwhGpYq zD@#+K&X&|}N%AmJe1xxQb2zq!ZL~)3cl`Ry{#7_AaI~10Fh5t6Rz=8Fy$QdeT>Z-f zb$@$c^VP*Q4TdkAR%Hw|b#qr=dEp~@RvCYh_6%-wff923$X+z)swc>>Ci7jawYgK; zi04~s*H=pY4!Y3 zC4w@y0IAclLnOK%I9FYcSK_6mLyITLxIefe2&r2|dJ1XJbCboSgV|nN$L_ zh%L3F5>GF~-1s@h^57CwW3ojQ@0+w^=4XZC;vZVCANms5XQM!k`_%#aXmL2E&gsfA|MADa z4Yzx*XWTp{_v&c09z1L!>359QbH5J!2mMteEcB?3c0_r99AtQa1{cVNgWtQm$!>J` z`ewoaVVYchdG$2;=0bAziosj%Mo~f&$2u|}sIH#teBE2Q>{X#<(_-N4pw<=PkFk!y6i%14v0#J=bMt&Zgyk?|Gu>B zwLR&%5nFU`I*a=3nadPh)QmsB9iL5_H^qhWa@nmmmZ1$u$1_>f_$a`nm9vdLn^VBD zNLM&ka3=!=e$3eP@zcf;MoEUOs*Z#EPcKEwwP0VVC~6Ay_pI%4P1rw(vS{OSen3;W z^POpo7(VbXeb4*|9^O*6kEyOCs-yFzt1CU+XP}2^FPZc%4}Lup z=^IVgwaaj9V>6j8nB-7^G+Jk5H9&JMdns73k7JP!w`K;uq>~!Vawm6*+x}3$kd;Pp zF12miQPNTNO(!))$cz;hh_ECz`guEcy4j14Sjjaama6mNwne3z$EOxKr*p4%PWUT*OLLs^ge5l$;IB)d)oel{XO`{b% zeTIN%S5|fPSYk#alT<54i0>i(wEMxcC`6*}gg?Zow{9eJr^4(V;SNU(oP&GRmS?Mq zCl=S6pdbfJ6(4%?$y_(ADWoim&tDceL-gJ$R4-GM5SavVpL5f z1Bh{itMg9sfS4l^W*%iq1soofp~k?Cg%4DJ*0DVS}%V-{N_6 z81k%HOIw?LM`U1EPM}rdflB6SlY6@6eD&}q#rI20v9Fms`A=ug!Jr-Cu?4D#WnsW3 z=z<75+7WTtrGjIk;M#vX4qKDp+KU;oK%&f>gs?>MeS67fyV-8Gw3|z23dZ)S{ z)STJ)7@yi#CggpcP6EoOg?{uw_2tJxk1E4sz)j8sZ0zZ2$b~Y@UF|#Br*8{sP&6&y5T%!)Xp3>C-$=*1vJ^wXdQ8PwOF7>tYWd=aE zF#U1a^j-dlVWg!e(l$xpyg%4%?8(MIU>TcWE$NX*C$GH1_v*ZY^MrYQz z?1q2N?&%cnX%7x!cDZ`tYT)J2$-MG73sME)#RR2rn?2aawC@plht9!2mVTIv0ds^cI}F@zw`pN# zM)f^khOYf&p~!CnkwYgxIotkzg6gkjIFY6uH<=6bl+d@tIP3E!%C@A-Eb?tdB|P6Y zYiO%t&~qrjLJlf^zXVQ&D(g1qXV?$WFJ7Z24=5_sGFqLg$)gI;wzD#*4g)+Jc4j`h zbGlUAsPs@w5TvTA-I zY#O=dDp}ma^tr{-cc}#kBhMn&R4hpT9RMkpt7IMaaqMxp@bu>rJBuO&9rkMoi-&J$ z%D7)m7!o;O)2uo^-!6%AnK-#;H1HHV#+^|T!1@*}oR2?=)Qf%bYwws{Ru=_T;( zzH6`tl_9Oktn<4OyZZC>;-8JRWY_lcYJHY9rEh1ikag6+n)~(})A(2Xbf;`3qh~fM zWM<3Dj|s{VIO5)I_e1p-&+IsU9?d73`*{id3ualDp_co*D@*7n{K&QfD_MRLMl468 zYS!^ZzJ3?7sh47I@XMlCRA7WScU1D!)oU-U&WHcddLzK{0;5D?`!)G`=9`rJd%z1Q zN_+=BWVP7^I&N)#$~CYap1F0&*CY^gf|gh32C4*`fLDYvY-je-$8dQMg1YzS&9ScK zsJ=OshJ9?*&LtJH7A|~_X49IRdk^j6rn`M;;!U^Fk#uj||M~b+lt1B{<_Ku{LWUzi ziJAIAKCVn}8uP9*8*O{x2qEOiEelyGQ{wywKI0dqu-wDic&O*>#zuzY=A&{b=cZ8< zx?mi+A7s?9*bS{eQ~$8JV%^^V$q^WLI?fwfBvP5|x!9pw+$wy~c}T+bvM}U63z!0zm{F{s||Z}p6d!wdGst->uZZx)`?r*aLG-gRY*1Esx0rrjf@P)?&c z1(fvv!9MRF?D-45Ai~F-Z6!dfOa)kjq}ZO|uNsV(*#3lN2ClPJLkKe-3W3?W=@z=+f%om}OdQ}74=mSG1XMYQTiYdm1hrTr%DO==8cmZfpxf>7MT_M^R0|v z34zcrKwCDtzJJBIK{I>$9`r&@l(CDNG+>xpnp$zZp~vEpE}tOYbov1zs5)6)eDh-h z+{o&nfZy`zOyM)xhkKZVU#|O1ncu&+un9~<>=6`#DT(Gzf4+{FNJD>0jn>t-&^Hmu zW}>`s#3jI+Sru^t6VFB_>^QjTeAt{5_%qu97-UX<4-*)1%SsK3Huv+~2^8e2QNPupilU4lI4rDTL zx77DPzRoHV*%v6-S<1M-Nbsf(;f4g9xq)$Fs&TiGNIgZL>hjwR=)PzHso+?DE0^cP zM84MhKmDvW#xy1MUL1>5d-_Lq-!MdoQomn)Qy?3x+r6FO{u_K@d!PxJZtTDU-;IvI zz-HJ{?c3< zB0as4fxnkAwAhkoA}iOEzB~Y>E5sk*L2>^m-U*qDAlwh429){k7jWsGlV8IB+gj^l z{I74#P;m>s)Sjy_V)8|O#Dpp{NTpsiJ8fllE7TA*Vxy1gQ+`yeTE!o~Cu^;5_vYmV zCl?v1-j^S08GFvMzN7zHZYEVa-f>_Vu)s)A%7vp|-r&27>2jK_pp>-^uc>mHR_SLS z{#IvxJgJ6ycZ;>{2-_dxqad_%F8i9hW3epre~8KVNNGi0T39-cqJF2;ycU@z0W9=PDy18bA5S`P_R2 zz&#Lk(>aaYL+`?1g#Hy=-cs+YMqD~Ubo*#RfK~(;sJt^w!!ZE)+<_H+JSl0IvH*eN z;ge?iTNaNPUtvCtU(@`!TXIbU&XD6rK1qG=Vkly2yshF4i{bjNlU^UMQp#_SuqLz8 zVJk>5t}ZMbdS@jA(a4rGeEhjQyz<^rg9|H@MZrg+%>XM$^Rm4U8AR5Oxff_?ulNb7 zp&qSzdDo-} z(-RpJZ$Thw$|y9nsfA>@qIJ0mf?sd20R?~QFyN|&HD@hVJw8G6ZP1b2oZPeS=6uH~ zkCyO&@2s|0`)(1Uzk6=TeW!t3Ouj;zlY@B`5XfK%#q8C!2CGV7gg9qR-Cgg_Nz$@HZ59(1ak?-$XNT8vELaHMEnAkvuxjW1_F%eehnoujL}&uh-yG za9|Aw5mG7qlP6o9aNgCg0HNFiexExLI60mUyLY=D?)Vk;2Ad?A>oUrb z`n3W4 z=sjwb(R+{H6D5+2k`P4iGmPFNq9z!|=-nWC=YPFF-}`qzaxD+6S##OvKKHR-$KK$* zH;1r+=6|j@ZnQdr^RD+#z~)R>t;z#s2CjKqmWOnf#BZrEQq9f&1(P2+#`lxZH$F^1 zvQB}uCrsVVAqHT#o0IR4{&K#OeDouzml)QDb3=@-hAgz{`jvYZ3buT*C}N~5rsg4%YQX5(69RPf4Hi% zG8O_Xt*UJLGyG=@mi!zx=%TeyIGO&oipEBcS>`Qy+@hPgRE{uzf6w%s(~}lWzP)47 zA$2yZwEk$S0cIgW2ZU4K0PoG*u6V zJYUWxZ-bhD#$m1vx^^3Vv}PHzB=6ilLudYnssmxVH=ej4NIO$V9qvu)cv$1{MV*?Q zIId@6eYE=UQZ=^kuKC0o4;Yko`G6O<4s0}R?dJCQFeRcfx#3ry|e+8;XBneNZwDi9Bv$%+4eP(`=VCV4VmmmIym-) z3NwZp!X@GYsn%V`Cc>en44qDptzyBM)EoxD8mfqsOIKZ`O7qTgn&_8gS|Vn{5$iW6?i!Y-3FOzDPvPm-5rIS*j(ZdwiS`Yvt53 ztQ?Qa<8}i8JXtM3z2N)MTT8paz8XvQa=`tmg8cVbILW3h+7QsF#A8qRx4OS^Q2aZ; zJN7ou6sWi>bZ6Urm=W&y2ZI^@`+--eDu1K7TD~8ixE`4Rg|O_eT@9$_2E89UGCPLiKFXWs?*EZ>_(L9L#Dxaw2_GKFXHk8B#CC+!0_tN42+b zz!21`d3BsgM3|Z|EDtg>PCyB%K4F*9HwFDKypB@*~YV@#RO0UJo6Dl;-u{`Tc{AvT8tTn7`{kw5XR1 zOG=pj923}yD<>Rw&d&e+AM+3n56P%X!)w5JNAyFB^a&dK|Hk;6=>ci$_~SUo+ZFn$ z#JReCdU`t=sk~d6Nf(?d=E?xa=I3dKIc}d$<=0rv+W50Lk3by>P*j6qYsF95y% z5J=aP1@8e$l?xW}C#l;8z{?(!u@xX)6?d5{|3lChtQ@Y$gpQCvWWTqWJoyziKYS1f z9`&bs4m8$a#Xobwa&jR(Z2D9J)&B#|7^J-o@m$Z<9YDX3yn zqa@e3Bt^B(2Vq3GQ&V9J*h9mGRpo-JcUMHA-?i zQew}8@k{_YKvOb1Ehjn8Is2l!a<+ z2Xp}KSSs}LF)^1#LptMCHvl^9!|v6bNm;OoVQ>2niZOoy+s%hly4if`NJEBg^CU|L zji%p666kA5Ui|%Jo1Mn*ll@KJ4HI`tM9cl-&Z?WtShA;cDfjEa4+8+Q^Rdd#FVUf9 z0N{N3VxxQK4|TNnT3M%%hr?*E$Ekzz%;qJ1Bx+HP2-(v3rNlhvsfClO6fS_&8R0lH zJgqbY_P%#YCMs~=xAc1<1qCdrpzhDAQW-#hu={iG@GjYgz9JS@{-J2m)Y`b@4G_n< zps6ikybGJ}^2r{YfZt@azbBS&TJC`Sgbj>G{u0@;0~APiJI^_;PB`Yhl4$Yh28Ll}@?I{pzE6xeKOF zndGqad{$iid@=y3mf+k7;ge}l!T<84KLF2~7POJCR^dJNHfFwTtc7}l@561$VheRO zSJd9?ugX<|OZj5s_b_#r&tf(lKJYNi7^?W8Hl<@+1#B9)7Gi*@z<^cEO#i=N7c13$ zt1rPnM~zddxim(lGO8}zGC5SI%qIwGDUCV}U1Kd1?JVcR`dO4Vc%ZiIKeP`9{wKPR zb$3DQa^x*P3NEZBdU&j+Y%PMQ$Q-{9FSyAYPpg^{o53Py&XCgc8|%#jLx*YFQzuWs z15Bo#m%ddS58isK%!asp-o5b?N?L+}+6U8M*sEOAgBXZn-j8L8nf#W9Wt0KZzQf%( zWTECGpxuQ_iT@;6V872;8kql|QGApSe@vKpQSd*vXh3^#<1$~?ZIcVlBK7Cva(0N1 z*yJ=KrY(4%3`rhG*6|iolJL<8P}v*+dx>;g8$5YZB&KIJQwRS%3^@Yw*qIlaG&-X3MPSkLiY+K{4WPsb2+>`SNtXl>Uzn z=Z`Yf7-Q<5Yz8XhcXc@2ZJWuY7Ii5%wZytCuEQbEyUY!QH;96|59(8`8z&lI3K{V4 zFW$;%0sP*}QwO9SP=bx2TMmk!(Sr4Hbnu@5sM=Y&U=DdstqI`NAT5Y57fbT&l@RHL zRuR4h6tkdi(6TiOjQ()SZt37AB?okqQzMN8%qxAlC6Uzl+4lCmEOted-bL# ztYt19M^-Ac_I6t!)5@8e^i$be0u}`?lf_>D@HiN?J-v zHUjgY;+KCG_J!`fkZ72dNG?dJDPJ1C?c3-cUvakDX52XW6^+#y#GB*{#EN-J7^Y;KUWz# zxs6QGBb>d9bvJK*cIN_yYY#q;+`TcvaRZMMTkdVS*``G)U_z{Wx!b>}%)DljunbIK zUZlaz%-xTZU;^QcoArO<4vJnn`u9?=m5Ii(mt< zy@-25wKR2tqygiiNVM#_v@(tXoVL&Np4`!!hIbLem&YZY9!5vZa$zmMaa z|0;cZR}LrY`O_E3%*e<>Rs?J`9aje*Kpz|Ts%)B zc@^SK+=}VgYKs8{DhYSq)qfIeQ)tg#uSThsxD$=8zM(81A%dpS`N!h{Sv{>kTevYjp~M7%tBy5w^)<@%K7>OYvzRtk+411cIkLm z{8kh3;ua8S3timpQzsyni+Zq0+iFcf@Q0vK(!%r0RHc!h`E6}%+zbtAI*tGMktfQF zKPxMr`~r(4W-ot2Up?g@*W(HG9MGB1<@IQ`P|Y;!Dm83rw4cXpD=V3RJ1Fr+Ei+vg z*FvH(3x2n5(VmC$0`DbD1v=q0N@hYv8krlouF!j8fmgi(}Umq`>wkZ`93wO!JPnR}^MgU!j?KDUdgy%pIrgW{RE4$<;l8HA=7A52b4ZraYz9Tw zA}zQrk~!>9k1i%-XR6b5DqpP%$b*4BOMatFcGib!h=5Lb9n>fA z{^ZX*dvIum^zgTdsr);OqTcK|9vs1iZ`JP3IvPg195zQEYj{%fT}=G+y`@U+jI$-< zpXW_FW6!iL$F0`G85FaDQ>;`0ugKSqB{xjYcbm=}(f|85tO+X6-o=2KBfY$wci-c* zan-Zbd5TreH17s8d?SW;xRB1se`HoQiHI5dHk)l6&a*%9K2iCFM*TCaYs&T@o_G-} z8+F@8xofm%-=oakti*3BS+PX}Iwm;UyneK06~;1QL;<+5-`|LD)V?7$bnP;IW5ujy z=lPvG?6Ty6`|GZ`b^4sPjK{W)rRqo%U zhnxUc$8q`jI??12L3<$457quOOxNTQC8#fVHfr4tqkM+iUmwurvFn5?DFf@0~^YeJ#TYj89 zWJV4wPptw&yIqAwI4|jMPF*qer^XN5MtS|>ZH|SK;w-|nL+TT1u5{~^8*8GWq+iY2 zh+4SLSqjJES5o;nIyf$+9=H|`IdF&(wGdWLDdo;sU(Ypq+%iA$fQ@K{E9ChdX>{8L zQ;QDMSi^i!iHD4ky}sdmB}CQA`pd7Y^Pp|GDo}>Q_FOs629DAtTnZJo|0-g{#coty zkYaxbot1W-=X{Z)5wet`RtTBs9Ns4%(6k-$%Xn{yLYU<=?&{1gMt(#moC&i2LiF4O zE5tU)>OOS!_nKqu2K#?A+mEi+<}G4WA5XP%-$*6bqcFuZD0lpq`Iu5)+SHHcCb|qE zBYxo!Msl8OXlG^$6Wzuq*mT4$PPV)&YA4#%7FZUwAwmxf!iIcv z1v02!QIK8cyP4N%$>Ixk+39~J2qy^!Qi0h9s;DNAU~rvj=RZzdneLfCS(GJZ8_iz% zw($u4)tZ~zbLpy08uz&#N0wKITxISI%`O>aXrkWvsT|O6^;DC^s!psQa`yf#UMtJ# zcpq7#Bil^@Y=dv|2)l*np2j_x=k`_Lo(DYRX!4J9$V{uc zM{G7j3#3XM6HUy!TR3`4xSB3D?mBlCf5{`%_ ze?Fm5GE{_C24qV*I+R%VR@hQO>}GAuzNroNcSw5?R>0BS1WO7lA$Mp{orG-d$22-* zA9%%imZaJ~7DDXC(Wz^U>I=wGO$D|E#>`Z z{$s-uT4T>rAcL&Ddg^gRI9_={NN<(nGvKV_er@UA#AQ0BoOA}pj+;h4d8g$Xz9p6TgVZa1RUW5WMfW1)Jx|+1<8C0LE!s?fc8`a$C- zKaaI6i_^EYjiY0b4OzGpferVA-3zz+`pjyFMx;HX{M$|Kmt7Yj242*1#%Of zEss7i@wg+kjf%Pj3<8#qj}BU6NvyTPnG8N*!24b|ShXR^=+`;i1_2w`du9C0KSct!|BA7|R>p^SK+niI z;@;q(ks*(5s#$-X2>ek$FqD!cpjg|*jYz+V_gZP+MWo|5UFdR-gf-cl6p1TSh;QPi z;qpZc^v>ANUF#EFaTbKs_ejR|)VBTZBhK#(@T4g;?iprKPQld8dOpac0x_Ldr z;dmV6qMoNhx_ab_J*tEF0$)!H8NGK0WX8N&JB}s?K)3lF=x=vvxYmyscE?6KNGe1; zPbUe5brciQ(}2fOd|_fxA9!yF&f=pzGbN&@kx3}iu**v2SidAgs@8l*w)>}(`*h$> z4XyFL{%$xj6~;mwxwI^KRnL{IoN7K#%-sxwY~9aOyfHdxh1$xWUsKig{CBqm{&-6* zTGEtDn$+V!B{iYGy74!<9iujM0J=%Jw})iOVpPw}*7X8`JMt6ije0_5`g&*1R_w={ zZM^gI`vVSClYy7leLs2mC4#?KC-p?9nuUNTkivJp(}L*?@+H15DxGut_cxm7Fy2WW z@$c*oMZJ``Mr~ws*q9)ib5^b2glAlH)vGqle{mBI+Gs_7b%nx{@|$r!|I@Q0%DW4f z+)n~>lQF)(+rz?*XUX$#W*7f2Qa+5a+#RqS4ZaLZZ)|M*D+1eI%3kQ>F`j00@J$MO z6KLUWYKd?$DA)ZXFy}V+wHQ3e%<-A_)MBy%qcfz~<(C?pisl$z>T%2YJcvUk8NCkuVr=%sWb^KW-~EqX&=gnP-h{WMys|+cS(v<&QBKUi9>(H7`f?>9jvA9 zeSth8-w_(2W#LsR=zN>$vo3p@BXNpnk6T3_h%2DvHc7Y!Wr)iRRG^giTbOY&c{ zFziM)B9hdx=}deE#tlAGj46F;7U-WGJF@f$w*#fGu61Nv1K+CZ(^WkyQQ!F{htmpH zt+DS&oqtv#v<9k-;&bb}B(KJE9GY^0aneeIVRP3+$i~F>FmCjFzBPHw?P?J(xbDbnM=YmUyzb$ye*mGv^# zzcf!Vp~ig)b|dhi_>uYk-!y0#BZtPL)5>W5f9fDKGCG@~2gaz1P(V%bl&>l~6o-48 z5q(>2XPR8at|OCDeIwW=Nd{7x+&$;)>kFm0f_nCaS;8F}J?Jap$+{s_3ykW6QBC@z za|VxhF%T4)>8>B>;QDEIyQ0#SGO!44$I}fO@%b&S4X|@LwCSR6taP4MgNbjZbGW*< zTFCN~D(c3}ys>*vJ4BtzSap!uXU7jqU?7?V9WJngb3By7gLip0ev#@oTv_PO)9^Md zrO}D4+TzBOHfH|oGfyAs`dBD#d^)%^Qz1&Xl~E@gZu|OhWcJl79;P1dc_(RviX%5n zF5g!nTYP!Jv{K@WytAwjLe_6aT{N-&z=cDjd;d|BM;7B-lQZSFTx96QZ|MgDWazY( zp{XGzQuKLGja7czO5l@3$x|<`?lV9CKgEzq&7j842=_Vy{znlrNCJkqh_Ep+nq>z% z4E*1S*7Cl{=kt1;sj`Y*0Djh{l8o?ug8xPkzI}*$g%8=6ma+`*Jc&pTfd}P9LA+E^0<{C9 z&4FQ+hm<(rZnx_jNCNE~kGai&$JFa|s|uQc3D|0GOLRoi7u6{+oql?S`=R0aZH2p+ zRL+@0wi~lyx>Yre@n2_)rCmRfK3bo0w#@sVrk%0CENv7`R_g%xqCmC}z$N5u+)H(X zwKTtHuY5{xMQFEJ(fE-#p(RQt&r_iXxnx(T(n13pZJK$n)BU4|ftv4Vo}F&dooYw1 zi2Y^kiSJ$82Zd)}fMX0Ov86*VNje7zaEg#%;GTDkpOO#lC=K4xIN}$af3r6eXnB(z zKCsboBAsUzkXHhgdnO56BfP`PVl8Gh78Xv#-VlE&PBSa(rSKa*e)N^yj;1(ZdD-20;U-DRH$C;^mcJtg&^w&VL(HKlBBATbiq$7N!cOE(Wz( zF6dqTE8!V7Npk7ql~!u30slDr^6h@7`ad!0N;}2&nWS~`(oDZNUu#%E^V4Vy(eyZl zAO7&$0<%Y}Z&_XM+M66h>$zfE2A$TlD+|p?Gk-7Y>^@vcbdMHk6I=4X#PN52yxGM) zMFEe48a!HS77jW$G}f1lsDs{$oU%xD#w}F)grPX_O)J|u93QcD+IcBPD(u|yG1Cr)dE}=k5H%v7Z^hD}@8^Jwts%6Pa(P^T(2(xy9^!B?j2qn+4`b=cm0|2b zuYyv)mP4D}9{q%3f21tB75M;1K;n8u!RlVkzTvVH_6OXPvUk4J($fWYZqtTZ{KUv0 zt2IhXQV~Ah%k3A@@>z?qylT~&@iTJ++6jcq^tWE8n1H>jtR@?AzjAP`+cI^>Gu-@` z8wb6LPX}TC9&}rO5XA?*rFw07`Q{&mRsgftQGWc&LX3q=f^w>*yHSRu0WVHlP@eC* zxfB@>Vq?0e@tk3}4GM%3G@(G&PMB{ zokAPRq)9H<0`-vvhaQ%TyH zrg_d8mkDgA%`9hL$f#+vGg zNW@v${oxrr`$$l4*bw)jB_U4r6=#ROJWJHf1(}B zmKFO5dgBy{NI^7Bgk)QIn_RlkzeI9L`(dS)OO?s2alDvvT>qw~sh33R%4t1Xu`Jh;S;h8PrgubJxOquNOm3yrRw> zgu0=NF!@cx*Q%1ZY@*uYj%;%}?sB_pmlUU$@T;};LK#G^MI+=?pC_e%5n+moawk(N zPF;^kr)wP~K~DC9#hgZ5YjV(_zOw_bmREYw65_$aiMafejEYr(vt&jC{bYr!g3z|G z+!VfC_f3}(&dkb8&hbiw=aFdqUlQCm!5A}9pXeHYyj-LK2G1UIeGjrtgl^ebX=7S6 z7d8BGv#or3YYZqmau=A%k6%7|kM6zM`~2wlP|8(URT)iQPwp2YOjfzTQ1q^AWL?$- z?Hm6?zst9Mvz_fDO zVrpQW!luImV2QGr1JuRt+G#X7<6m2AK5XClw|CAqtOW3^i9ZL|>@_JkZmU01SW`p2 zf80mW_wjKzGYI)}ALM2Aev*GD>-!iO5z)kyF)&)HKkBjTK3{Ox7?Ub2Zn7ftC6y8{ zlaYj39XF(&98k4tcFfG-5HfhtLo8W#wV(N|=es)p;8p~_+4=co?PN~TM{!)61){KD z;O<+g=O@=2!im)b)rdSReQua@Fe&fg53nYc6GfB##^tx>w69fIn^yzuzcQUtaDFDb z0Q=GOZmLIDn7*hSLAK&1HL$UO# z_PlrI!Ju;_22!V?X^v4bN*`#|Tvz+dl9InNOSZV8z#(lRAiSsDzq4(&>%~25EWpj5wwInU&5i5lY!?T>LO`3N7=mQwC&xRv#nA^|dtR{Wc zv6#*%oyGrrZ{;bfZSwSXAZt!kNDsXD5Vm+Kl)}32=agg%IlRiE1S&&l+^*If?yL%q zW5yz!AprBF$7n7j2{_BjUc(@GGlXjuS|{UYYXhXK5?U<7{wGP{U5~>j-6|}%nKPV4z@ls=dabTC4(hN~Q-g}!Q{i&VhvK#IzFKg=vV%o6t zT6s=3ZsJO^*I-3PmFam%uXVMH^pt$wpGLc8{N3!m|E_D9eIFNZjr+6~|UCEnftdgX?S@|S{ z1+v%AE%QU{VPR8pO}598Jg9Hib{=!B5Y%p6b2gxD*nR-zd!5p8RwZ!MHYgI}O$t&U zRNb7CwISIN1NH431bwNeW=95gaOC+7{Gw1Fo~QebykJw-)(y5npM-dSLI(#swI5mz zNUb6isg%CFtOT9igJ#ZsHFYX5lQ;XgHFYv((M(r_h4olibep^YQl;;s*tnyK2#md@8ic{;jl_o`OIp>!@8fzTS{&jYFo!3OB86G{dk4eXK z*V91A&9y%I>(Xdoj5zT_?bXA`(5CW!(}s|j1GZ<&F{AySKP`b-EB~N)W`zM9bJbl^ zcqW6G-&)~JSRcrt(#gw3 z9|LvSLw%UFbu?blSUX(u*>qrt7FxE7wI}DNIudIZv>EU=kF=*ksX{VjJnsLCv#}+w zVMs;`u|l(TS13=KdS&Gk{2eGUaL`@$#;X^i@gkOlx;$+3_MBDu&njj%Nr~MGV^Q3N z?#7$OoANZ!{l^NN?;el*|GF7Q|LbOO${@ultl2 zNmf=%V;{PFfD$?wNyJs8lbmz%ed(zT_JCJ8OT>m`@Tq?=7`CxQ{U(Mb>dtvq&e#tx z0k`E?pdDdTUm?x!LY7~V=hzGWOuDiAIyb_tVC|=(dFx5!7Mbb+JSnWL{lHp>aOHYg#H*uo+^?Zq_xIe~i; zb_+rVpxXPv{J9?}!UR_>42x8ZWuo9uj{I-<1qDU@yKR;fD{3ww89{A2cN^2jLxG^l zLPlA?oW`7iyrHxY!>JQ4#M>t_pK~<&kE2ZM9%W`Fe$b1NFdHMTi1D?K^JWffB7c<3 zl%9zFPCNZUTV;l-=pj&ee$b%dN*mTM$xFC8T&ZwY{yO>P+`&BwUjmQr5l+ma?`nua z9j(xGTFtcQ5&hm@9OPu@&`BKGe|>uvd=%(c-2?llJ`+=tc*3$peSZ$ZD4P8UDNgAj zrz*v?!zSdpH8AvqGjWqX-Pi1d`WHmOq{D+>rRl6w66zlUPpbsoBhly)U?xVYTjBS9 z1&Qvl>NGLgtEa<8rtYgP7Z{>oY7T#09(kZTMRb}hn5&|afO%J~gSMbP;6WIW41FH& zZ9Oc^G*9cQfGN_Q4&<^WMSVgsA?`1+Mki6_WcMXC# z*ggmPjz$P6SJ}yWOhSVxzOJQ>D^~aT?B@}SGr%#wm-D$T)f3aKM}og2yxXQcT(Gkl$}IN0*UyE;b7Ex zu~TFNggJy=xe|8Anw4EFoEY9*c#Hcdp}qGXMX7KQEg z;~yF63GTTukG>KfBP`X;1qwTu=c@n3B+RmP;dem0MU_JiOi8;p-nZT|zE?(j0GS#s z7K7q0vHmZ40p;vpNSAAw1|&D9?!(8J;R;3inw>x+%bGtd8vIc|ox)nLth_d49) z^BhFzO7@mXIzgaM=!qt~816m^p>;BHX?DZ;pYGN2K6n;90?;12auEF23N7r1Mj`Z2=S8pzxPhHnaP(ncM>jM zat|t2WCo~cRy_4DedVU6Md^B)467C58$;sFV!rq{a2!@&$)s znu_da*TMeZ=mB2%mE;54X-0wAI?apJemAqPzsLoV0e83fZ)PsFe1@nUqF{M~>hYc3?{=}9FFR_c54@tjF-*JTR>D@Q6KYh? zOgL4G8WcV1atEV5E60OyBVur)cMC`UJ{1GxpKfl+S6&oCT*8S7NA|^Z_+8cu1gf+- z>Z3xt8~S`)#^;x^#~tvorQmzI#kfBwgcDid0*Z<5r#6oryMtn1IE^@i@<}GU#R4+u zk<`+=Q{y>#H5Ng(8lTdy4u(He35#wP+P>c^GL?#g8t8hlSVBo`M%}#4tNnb39tI0m zFtogLCu?l-K<@z3)WQu>@W&LsBc|o|)!xC?X@SxV=7oqzn1%NPkCo~1%G&@~`)7NH zON4MD?bAPT(6)sW*_axWX;~GAF!h*eF&IK zXWpP3e$oe>@iTI}=ZXoT(uG<-cKtky#J~e#*2#U586@P|YY?g6VAK4#588-}l9b@7DfQ zd;lcuKVRzS@a*}D^3yO4&|99&x#^P-y1)DFd`vuZR+<}jU{0VG2 z5ZVl*C9for{zdEn)qH@rXlKoVzhh#}@()Dx%ZX3oI*N0CgY)zGpZfT6*cmUc;vHo& zZgAwzB3S!%NAFI4FGG%+i&WF>QlH z_^UHp$v$cX!5XH=sF55pb9~66RBcc2ri~Ey8k~P?2~IiZESW26F$_r<$n0&_D1mJpg5S6`Il3 zKDe+gbac|fmw@+UiXC=n8Ce<9%JZZ`C zfBXDdhX9C&-jiuYeZFX#M%mnx`|hl&?i`ZQ*Y^yX@6mL761Z&@3XAMgmSjv>8cI7@ zJ#+*ClEx8j72tn^+?8v5>Ucc&kD1TF>94rquY&vi>L2>X8}g1`k^kgjz&#CWyL~0k zKQ12|z@7TkunwFzRr!+xK8|P2hAOio5Sosv0R#8lS~dxw2031ajbD@Oy;ek0_foZ7 zJk7)|+^aR~x1qABe)21YhMNJ~BQtqaz9~e$r2Wpl>IwEMjo@c$r5^B=O7;%LqzaAy zwq*C-gWQIw*AT)-ez_%c_>83lAC?D?T=^Cg&4W_LVh|H`ihF;LoJR1vPyY>P35=PP zTlC~!;@F(&3dkkM8azXVI_bQ`G2~*=K$O**@t>y#y$Bt#o@Z{=q$)IiV6!bc*$oud zBGK~bW%XopB(2bIR#$;4liB7?VGRP74mZeWh9X&8I+UH@7BPii2wIPeZ7W3zXqby&IYw1|foO*)ab{a3$|c+vhv56wn0n z0><4uH*UayYsNvVJ5d-EMu*w%;*Rwd7h8k@hf9oeS9}TPdR{6WymdNNd2!xYlReA& zenVGJSS*yXFrbhFPuiqjGEs@(pVw8-XsMW3Xb{z^ibmY7-Zliz+VmKBHLsTyr zw;lqmRx0F@k?ir3*Na|H;VCmr1G+yS5jCr!^+k+@Im)rycCF3l)t*wEL-AWYzD`Qz z6q9hAss4zYP7pvPv~Fz}iKQoudX$Bx*0sdX8FcH)kNk!dbq&mAo_MNpvpjTzWZ5{`jp+dM)gmq5Ds=k*W zV*L47g5$HDgP%p**m%it*(N>1ixu3kxOBs%+pK(hEMsb}N&}DxpLG7dAJ%Gy`P!*k zx7=bGiQTKccJ%&HVOl5K{jzS2(xL~H78~eHXElyeLd}4=khEpz5~K?c!ZL5HE$XJL zt%AAD>!6lNHhdHVRQ^d%_W&S>x5(1R1)oE#>4F*fx$wJpEQ@5*upuQyO4Jx3S(5ep z$uE~pLowvFQn^Ga%{4p#Z5hoJLgV_rHN@j+r%7KsTK?yGvqE%REEG_UZ=6PCAP>tn zfF3$}(~u&A_$DG&*Sv4|j=*$RvOq3Px3zCPPt~s8#KB>HF36P=CtJ3W9HoRBGW*IO z;U3fpA?lH|{laEIJh}qI8>Z_4lM9E9C}$R)&)fTy(}#7eaMR&5K(@ppVUs2aPhA$f zeP8L7=v|6;=k;*6r_?yE%vQkiFGx(??qf_fGOzaEUb6$qmuo=|6g87X8%F5A&8l8Y zeQ$clSF%bR70}VOU4%aHR6N5nLlY%*u3_W>znH9#n{BZR;SmGuhYXJ$m%?oek*1qcTeK)j$M7>CQ_&Q`o@h3ZaK0_ zMH@s10`(5F*zV2PM9VLDw(LSpeI2Zp&5@JZ!6l&8I1}hCEyd}ihgLg4waGS4yKj^} zwp>0?Y@~aDsnfQ8mgzaI_3?gh-uk6CLMd=#eWm6TT9#x^&C?7^4ZDzie=`I zHV|ltm~R=+bsi7ncAcNDOii6BoM-O_n@lh&Tt7e;G5EB7H#488WKy1ai3|*D4$2$I zTuq0H6ti2wKCfqj2MOJL9iQUBUj|E8E%dYlz1@9cSjXP79%dI7(v|xr&E1P*2`OK| zes}X*Tqqzz;K*#&K=bt6VfwO>+UBV3UPEq+Dmv%YVd~Cz$Vm-vCEJzLspCBq3qd?B zpDKwRgI-@MYKgrte;)WnKR-3&3UN&SB!Gg}UVZ(oIA ziYbNqMOv<8PH@cUJKKaJK8Ax7wCzBu?W%>}g4EyySesxnEP~K0hyALat@jFaW`FNN z7Pd%_UJa$~<063TB4(2#@){!V)Yy4qEO6Za=fK^Os#AUBr_-elrQbg)tDRV1w?JT66qSO>lF`qn{wa{T*&Va4@OH^;h$kj z^-cSac+4P%4kAY z;jq1jNP}nIK^{jhp$RNB@VFXzamV|G0n)L6j{NzfX>Me_FPZLX_p}+t9=R4Rj5uSX zGlky1&6JC%aeVqmEi=1&UpNU`+0d(wxK5)|mm<6gd=I`mv+Cq-SH4>?Xg&;xJL+9sZf10yZte`}pN-iIdIq~Ui^v%QQ&cRJ zeZHeKS74*$xaK!k(P+#66e5c07f66iciOItzX-nlbM%|ms zjl3d*GOXb}de)`F|{c4)2d@3~e>c9Qrt0 zk2{$5zk47S>-vIMnJdoiD63qgrtL5w%GED3-<_G%#b|%!d1HqyyBFmIl$ozmqRg>4 zTmU-&OM8vxy|_1d)RCYYBH5yCEr$J>7JXD1dT6oHNKXMlZ0Pz1`fYZ z#CtBs;zy7=c5Ld&+i+7E1A!V1O@h#jS&hXnbAt32iO_>s-8qp=`LFExRW!yE&H%IW zH9e%=REc99(;_OjrtM|s-Spjz-&qIy(T%Vk5TpTCBTlu%i%TllSTpay%Y5hX2JYRe zK4dA9*qRTD8ow@th*nFRzeS%`HwE6-ZwH>9bNX?Cs@Nxn4)SU~1IT_Q%~)s#Bra60 zirosJl1W&k0=Oy_VcU=N9@??UKl6=b8#wBj${)OpFME}Osf~JC@qaxd$E{2ez&kB5Sr)JOKn@b7xurns-aLKwp zdvAmUcCSd0ZThI^dnXe^=P;3Z{Gkj~fvTVM51vvZef(iDS^_Ee+>(>K`GW_diVe%0 zIcMzXY*UD@adJs(bkCXgAZvAX2cb+yRAJA}T19Rn>y7qDrp%gaZ z@$396YpKx@?$Q<2uo;^LA)Cim8s2#C!D2V|$;&&NQ!TFMp9i?xW74mTFZyAb9pcZA zviOuZZ_(0{lFZEcR29|L^{uTw3u$-5`{n<%J6z;EukX}H3I(aPt&IZX@%!*Ao>TXr zsY{K22a=#!lf}r^t@vIaXtUTP0k~0)j*6-KVGtl_h$McNS~e=LeEO@aA)7(DyfO|D z7hS9V;8{#Bi!kG&?e2LMiPMa_6T-W$ZmJ&r%$g8MUQY42dRV!RkgKV|NS|%*+c(+$ zg{$TICy^W0oybv3+etX$7ot!;zd4x=J&$gdnn*tyK=1{iXHWLzf4F1FeDpDxg|VQv z_LVr!f{v^1yplT!aD_!BDj+;Elvj#o{ciDX*m+0JA~@WqW^F&*hqT7iK8!d5uv9Wj zb2B6##L#e~AN(zzUW4Qy>9(Mzt@kj2l7hfn~m8b^SsL`TC9dcKNJ$+dr#;k-(dQG(Ek4`VjhkzSF2gZ zQfBIlf@D$4URuepIH&n6vLjZ31W|W|aO95Hbbv^c(}Dwo0Bt42Yi!uNhkNf_{;Ysc z{n6aNGqMH^O}}!ngG*$(R#PCa`lEfext9_6+av&ONK8F=#{fU^h5~@cVGi*^&gSh! zYL;8;wYhBD&gc7(>s&8V@Ye@Zrl3vQ#w=Ejt$2}E`+CPi_Nu)11?>~p6`Ez za}5(j$Km|)o3NsLc3U=7=T7%5jN@MEu1p!b{*po)pDX8II-rxSqS-zUZ&Un{DOJV( zVPPdYUCA^`avY%dC#M>WHlgrdVUP7JxeXJA-Th zg9=N-Nz!QV%yjqLT*y|2T=?bP&S4-T;P$v&7Q2s$KU68O*a1awpSk@x)u3?nvwd7W z_bgnVVGr#pl{Zh+A=`ApC6egAuyj-M>JW#@@eXN!+dE@Ku||$=|AT8jrRxPw>Kih< z6!22e5S9$Q=1RK?mM84J@>Gvm2)sHnlJwm3IueBNZZ8GL0lax_Z{U&o{CyHNlYh|C z?%H~)crP5+!cp3_l2=~TpVpTD67(mr*;M}3_5jHnkIkOW1ekc44&tf>a$w_j5)KgW zxT~Ydj(dRaF%5h`Slv@Fhgm6;x}f3{x5n=GPf}M&8#&(5)SJHhA(rvs$wl zs4~-fnLl1M`tJXu=`Ew8Y`^z!8UzGsq*ag(LApdrK)M^GyBRv9Qyf6LTWYAGTe_Q} zyN2%Ox$f`p|GZ(%V)5cy!@ACM@8kIFV=s*F8zyW$Rqw_^rw@AY*C%YG=WSt>>H1~7ST=MNbRhw=mecH(Rk*4SfJF&e{ zTg~YF{CaHPqoNm%hZgPN$;IP7lB@_-Tib#=g>WE4dlt@jqmGOpl=CzmTf1oE{RrAd zxZyFJvhfX@s-*1g;rC{5SK<(qnS*dCkj=YQPu$*IagJ#!7RCIZT;;cuAYiU4jDMgB zHdr-Puh)9PpeUE?YAYq(?4CjTDg!Y2ZBg;+3@{R!HLz}VV#HRrrnsh} znFeCm7PV$5tefgKNjFtzkp4$Mmh2M)@*~y7$G7M5BJ;gYrOX4#N!mca}fyG zEGDLd%17)357Hjf1$&AeoaN_r52j<82a-xrrF`QLgd5b_%?JgX%yzly-51*EZT;R< zT)fU}C?GCBPNUESgCtV?x&30>IaC+`fK#*jcn_GG5hdV_q%x~(&ZPc3zhOW4rjJPa z982s7YM|>H%j#a+ka_4>^0lV0%7A!UTMuDsaMxh6WFts2Zp+X5C^{lB>E1OI@HK<6B{DCDzM-3iGq!YadhNBWxNDG;j?n zA{^{#4yjyA>D|T1dR9CH_M;DZj&|n6HFZj(CP#t<6UFLtb!tKGxs7*p3ASI%-|!mJ zhvUu`6BD0}7_}!}c8$T8omZCIUl2~(bQ|F=6=~E`1J6*e_z!AhqJa=#ouOB5xqS}* zgjbE-mCG+>Pb&(CbNS%%9R5~gmb1rL3J6H0&Jn*HN+xLJCfA&2qET;+;r)&R9mtvv zjIEI3eZfvl@_VI(@gM*UqY1e$Jqk3IbuuvSEeV;R%{QP{yn~3MR4ZMJLhe*EJRNv1#W4$DzR})(0K*;!FqU1394S zASI2kDH#3kFl*#?(S4RYlYVvTJ#DgU3n>=~*0(UfSJKMk3IDR9C;C^kIaE1a++`MN z&K6Lcx8AIn@>Cd>Zk_%~trL4Vd~Gwyb9`EV$w$KW$Pp{BDkOciw)5}<9X|W~&adGE zHs06yPEV@4S^&5x zRS=BEEqi6wu=MPV`Oq`f-z^aa(|+#qiVUf2AMH&HxxEEl^xclWTzY7R9pxpfZEk1w z0hxOdpEFaQ9lD{u;p+2utzfTj8$nzhFi!>Mr9 zv^R>u$)8q|Ipi&ouuF;sVS&I7P%9+BsXxxW@J=j*d6t!BGb1hAeH!?c(g|5nk^H0DE3=d`;8?*FP7Jm0xw2sHT0t_)y94@Q>gXRjhCDOf z{(k<+@YuqG;_Ku^>Fpf@6tgsyDgj|}|B39e$^ANH3)`_vY;xt-us58SvXZ!vb<0l) zGxN&nEDpH9AnVV; zrW5Wvc+g+=<;du|*1hgFo6T@Tz+~863Yko>q1(C3Y~O z=Qe8=hDurn#TzC0f}+f?%htoEk?VkdgHOut)^>$s;~!PlJ+Ilu$$q z5(<7gYZ5zxc{LmfV6FPuW|5BHk0kHj2C*GFQt%^M#{5`Jq>c5&?FB(t z8Z%P%zqh>RZEwu5^jA6BO1mRSBx%WgeBrgYcv*bYs2P2$^+$ z1Yb8_V4?4)zsBsC+w~uFDE1?a}oA2p_vgm!GDm z?QO@&J_tzqkY}o-OPmZxFF@?>FbP2W(HMQEfOnNI@p3#A{gSoIv*^Y7>tUFX!RXCA z?uNCasH7EsflN#1T3hVt6zBKS_a9%67zbgKg94OO!OWw~+I`>AN)K=q`x;|Vgha6t1gk+{lDQf@2fkmqY z3PM?s7<5-qs>x%ee*HHNUS*HP^VM>~=KeBOq>Xj_dzP0rWXJNeHJQy~gVBeg!`1`G z6|+w$7%E=xO$8+8)?Aw zXXkKjAmoYIa$DgwYBo1lu%H{#vdXQwsDV9hmq9K7WCD0~f(W^QS^X^N${E;|ATfWV zRYH%fb97AU+vLU-S}hy9me!iaEy?xvvjtwBR!q)e2JN9i%Mxp_aB!NY*j8=%xHylbRXf(HMP*6|ILl~)NzUiNSV8_+?8n*yI6v)Wt4`|gXO zk^Q$Cfyg~UWjp%)Uw-9%GKy+202$trh3D7;W_^R@2ZrYNL{afnu+zu60rgUTvf~7t z%j_*5Et1Bfqj~FG-75$?GD9i9{9n{ShijTcZl(fTK84grAZ$a|kwVjJ_pVfT!yN-W zpv&~CdgguppW!MBN0vDw_u2H3M=CXmqp+{>JgOEoHZe|$F&6c4fA~P(- z(KdJvw~V3OgnAZ!b$l4SY!=<88FS>Wdt5=tAop|nhs^sZQw=Z;K8>SeN!g;v7OM6a zA`F%3m|=euB+vGAmvc4q=kpie%oH5GzvWu?+X6b}Aq;a)=Xrh&CZ*oV%W9W-D7ykCuHiu4*+=2rO0_bKJJ+OQ~Sv zYdi6`A@+{&ppE4?9%TngL3bZRd+l}~$!Y21=ZxYHWrF%o!C>?Wx%!{?q9I`P4-n?E zZIO0fUEzlS18Td&8C;+A8)OB8-24d0p~$ue6GISOtl5v)VyASkfS3C2x_G&E;$_<3 zfhJuD{U=8+`7K@q@4}i@2f`_-Bk8Tv_^b`7zs46mSmGts%_E^6a%g9<{??@pdv0X{ z#~-ZlrjXg%PqSc4!~a_zvHsuk2w_)i8y;P+h`>QP(`Ckmt_6ZosS zM$Us_B@$xR5pyM(VcFlv$AoEJ3%u#AaO6aYd*|XJ?wfzd(&&jT@MrtIf`0X8yvOCJ zHVwve*ELIn$iy3Ex|HHk&W#k|<@&yBM3+Q!mjMP>G3@~E@?Jr&h#_B^EfZNzZN?u= z5zF1`HcSIpGupGYI-22IKqf`B;6RM9k$oL*Ln{+Y1!h$H0fEkKoW=R(DE2RA7_d5~ z0sI&oZ=olHgI=+HbApuEzP@!A%GG^wO!#&!+~Qn;y2vh9A`6A?%k{b%DgKpl#Z>J6 z@7En)2%+8Hawd}S7*W?2ZDJMHmi zOw7gV?NvXiS_X7+m&19d3WL_KfXmUAy)(5}IAOgQD4XZT^LyYvtSHZo~h?` zaAGIdVuR}IOK>Qp8jp5~pJI?J4NuSQoSct~%4=Zkg-iiAEb&q+*#&PF!8$kA0{Xts z#&ya4qX1j^te8y9L5P5C(;i(QSXa#=Dc6|0Dg=TCx@vzw^f-$v0L5FF|J2K*VPOx@ zpiF-|F2^Y3LSUJjBotimW}ACypu6)NZdvyc(zQ=g>aoLwx&ev90@G71vLgLDcgTni;|&U}VJL70k7M>tEH2i_4{3#9d^V&PesZ!+GtKdF?A` z`i2-M#B|Nr_1S8A->xaSvmc?)i~JVp9@rt(Y;#IOK1NjFQ8=GJ@ryNvWvy|INDAousYKGi6{2?CP?z}{}TMA)NJAq zM?oYE{5E*zm<%U}CBWeChcff=KT~@J0@MSzL#$0-Wg%?m%DBFpDfCMhSllq2~0As!jLWbTZ5`lv;gZH8%W~I2+AoxQJQE4oecc zHQrye$N$)-@0xcY&VJ#h9W~(!=f(oL;wy3~i{qDTi`#rWVZx^aa;PS{OMpd*UY0Y& z#EfGt%*l3E+&ot*hJCiPTp#*ug%PTPWGAO>p;R=S81$L})4Av4@3W%0Xr2dF^XocQ1Y z)=X`+z}R#&kWcU|>bo{99{mB}=N9MPM$a;Ica5^Y0V5iSQscKn>^(-Zzri%77=2*Q z>zJW32KyHZ3|aid#eBXw+ZU#+L6}N>PjF1wClrr!D%~sj9HhMF{L2p5YU;#{f@ES+ zm}^(x1pK^aupr?*JW9Fj>A~8_pgf>cZ;%GWrAVrit79PD08o3;dB1$@((4&i#m$83yKzFB8yXZOIXvFE;DyW zoAIw~HgRf>`SI1qeKBxOuGqOhr8 z|CNdIwS)LK>SwZ$b$wuCj7m!c*A&{M$Ii!8K*#03RKXb;z4x!P{oFz@m?`{l=i3Y; z*%1(9n{H0B5XwK}sg*@N?V~2vNDi9A+NqT8=;R_w%ngE|;cX)Z7rYx>-mTmcW9r#` zGmCk=CA+2}|1h4T(Z>bcH)(qXfs|&~gt<#iyKj0IA1EWf0@jV$bQUSb*U!c^=`|NE2pxZt_*-v5YjJZ*Y&HBt!m8?o+mg2L}? z*%_LBSqn|(EI&dOcv3YpUT5sRO|V6sK!#@2o!Rl-Nll9$r?Z2L^B->YpB~$ms|6qW zkD7FG4mKpl(Y?gMiJa3NEo?0*Vf5cOk#ga5;# z%s#E`IvGUS=TrEjLu3j6=WnO z*Yh`<3YmQwZ#5)RSw4M>NPl~}y$2HIFdZ`x533rNu*UNGuOGhiC zPIQfKS$*bA5hWiPP8gDQGlT#a3M3UsE(jGaq!l$}L^^$mQFLkTd-Px1y7Rwr5_!5D zW0HKHWNMBzR)v5^&k=06#4dmVc6Ci)|~`3ZoX^CHznYn=wiUmHYK1pwD9pV{k1JD0RuH@L=HtO zJ}7*oZy&wAG)}lwBA}8IlNdT~ePLzlVeKtK9Y^`hBq_=ZzrBp;Ke8soS>N(4%2(zi zEL$v8DRVh~RI>FZ4?jQ6^gZ3%+taU9r(b<_op_I6wkVdM%21-rNM-Ef#fYQ{KDb~!L(vRTk` zjp?&Ye45&9QkIXn!{VvGCXkbc$g_=5zgm##Mz7zN`sD^h3*5KeuW1_G8LZmac(;Tw zSlmy~c%24{D`piqh#8NAO6!BPm-94<)!d4m!C4jSav_ zQR~NA2uMTHs-D-dbIY0vuMAGql=`TjPEP#pf8L(9Uda>iae-ZSu>=c;)_jJl+=W6@ zNxK-(5fL zQg+#Cl8;Ijv`loyh}6S=#Jw*gpJl%r@yYCM{BQ5k<=)<$|I^&vc~blL8rb&^+gu6i z5UNtbw`yRs%?&m_!CYE#>z{~pFha8>T)fd(rhxSLW?%jLupzeEa`feR+O z>mA#Op_$J;O0Lki0uO>bM{I7qCIRkrpP;k-z=|XOJ2iwr2@XH#gK9{uJs}OoI@7PxNvC1_s|53zJ2)i(nPQj zSD7*MhtEA(oKymGc5uO>r+%Fz`;jUetX%Lp zJgvNq?&4nXU-y-m>ld*8(d|$w7~7l(YIsjXkBQd(#p0`E98|k3J3|!xOPdP{KIFk<_%H}jeT@b=FS8-elnmpDxSII3Ea^LIe1oH zeE%?Lm+(FBBPVGHnt}+4Z64mps$Aj*!{$_}GT)X#$7~iT&SlpDRQ`}y>EpKAUhWjv z#wWlTGZBOKlJjRXQr$)GPBFY`3Lv&&t+AJlAHAb{SmPrYO6iBA{wKk@9yczl&W z7_Hd;P{NP~OcEu2#xr}Un96w6{0ZMl%r_1_31*Vyl-)qA4_th!HJR=Eh7ZYym?MC_ z^OjoiLxnvkH|g1uYV)N9!%c}b;^5mniVn@6LDCaqr4Ma3y02xX<4hk1KmQQ+^#2Wn zm`X%YDfD#O;t%poh?ggTO-pNBYjqN~%o|ipAzp|;FE_#zv7<0~i08mqM0@mreX}@i z&CnWrfae9xfw_Lm5#+*V^i%{w&=O3`1fq6Q9xy|ED%T_HKc^8HI~7Q41LY{1aQsaS zlJ3LOu`%7-^I=O*eHn$O_y%f@wwWdklYd-|_`$LUzbMDNy-I8-)@)|96&NB;zppHR zpg4U+2P*gGZ7oRhkYle}FlkjU?-d){a){}wxD!>+*iHabTz+3UboySDuvJuAvjn8} z)Gx~orH(lNG6T{L{dF?Tv`eqjvlu3%&%oQmDQ66X2Q#Ib_n{(3L>nxKby=}q%Zhx{ zVX{ylO0sXZUsiGm-_@2CQ@2c}CkJLt`1f|)HZgi%^3D`w&6UiS-&Jbm0e#uMe&z6J zJZIBt@G{=5yvl00EuE6bmbuG4j0#tou^ zP~u(WQ}vlRao8FU_SAub`Pr~7;m6t4S%l;KaA#Nhr2S6)DQLYR?lT}tpySP=rBd#o z>Gxzbjo#LZxm~{k+QPgz@d4v$34wkrZxBZ*O#5;&kZLLo!v^`ADx*lOvX;bv{9h7l zQj)NrK54KuirJr+QH(-0F$QGOg;+KSbVRA;cm8!0nI(BJD%shR(F!9%=uo?gP?SdL zrUF%W%3E=ER_E)(n!SS8$1Tvu-&X{Fd)vP)wMw@iA;Vu5@GZGtD--A2#<-5x7ud!m z&_P|C=RT`IrF5BQ{o(SnFGn1urKNnLHv-qxED!t^svNbSBcI5L6>+k*2XZW|WP9GZ zu^iy)oIH#kmzDQ?rF4KWl2b6fMl*v`gM<{VlhM^>w36i{`BlV?;90u#_v~fv5Cb&h zy75Dt8EsY!o5S6**GUm_>>)?fxM37uwdqA`O$9!DVBNzQqz5muxu5*2n2f!yNCVBN4wxetS)!nAHF}DPMl~LD(1W!>#rWtuW>{oB{sDP-#c$p-p_A-Gw zerod0As~tK3{AczI>OsDa!S+i-%v{UYpn9$EqUMmw-N}q2ux8EL1kUXEGaO9MZ>~r z{WDrnvNt1_sG}!cP;!Cm3H^rj%`nqIpzQB-@aK>jRAXHANDPb6bg=CeqGu|Y;_vA7 zu=$_dtTy~h`1bOWl@jq6EAC*6 z^Hk+MEQ2hUbDwfxq$W-5Z3gJvhpT@IzJ&hWV8)jCIsjUlI^r+%^kdA;ze!+dA7QC& zA}{8tIDWSltQOK^k+5a)w?=4J;Yy*3@@S^-b;Z>^1H%U*O5Hp&w=m|>WGVyg@xNBJ zNElVxlMi2E6{{?AYs=!#bKXrK0YBsNekX~NT(BpFOVO_^`^o-E?Dp%mSl0pvZ58CR zPz@2^56QTTDfUvn0Ci{PfO>7Fo-{mL;3HDa`e)@9YU76#3eWDJTR3jm zvU5z)Ep`N?))_Kk;Rq~@r^7gjNweeaE~I&DS^gL%h(a|~Vw_`TE^3tjoq67)!hc~; zIc1{$Iqh{0|hDdwRCxx(9E#{Fry8`%j+OJCpYqMr=p z*W3fRY>s|MuNMmY`pKpD9}h51iWH8Jpt|NbZlCsN%jk}iZ^SHV)az*FO=F=^J~GNUN8y7XTX>lk$pt3PmMBv-K01!cS8HRIxI9@ z$ciqnrMf;~25~R?%Pvj!X0us4LQ(s}`}>0B6XM!5p2U}u@Os;y=-7eldjGT-Xf#-( zbrAD3zSzv~F&Cf={@;qPFr8OGD7oVhmza!7syux_6>HubVPW1&{7mINU`-mzkNRk& z5lY9}f|-7gk8r7+N}FpXw?Bw<6A6c}EKUl&od!d7NQmKG8@>A^Czxix1U(hh*=Z6? z#kG=00dPv<71qfIM|pcIp0J?tChk_kP7Te3#)+a9zkHP~MvISHqh3aR)fKRoMf8Q< z6-SO^1w@I81wzJ5>_Yuxr(r|q^Y46ILfZ;w3Ry0kiKgZB$#sp;KK_+gOHlu*ZaZ%s znKtd#H-Rw1Q-V?KFrj$nu8ml8mwqnK&XjeC1!tvy7~yG=)H|o)kN4kd4QZNJNjTPr zl1_V~+Mno6jFm)%Nc3};-MpV4QKF)vsGHKxh-^kr^GA6yM z9QPGur4sG?uZdSZ*0^7MfUD^D!(IIKx_Bi?^^-yGielCqq*uzf`f*-2I z&L|s6nFY^>T^kIM$3<1#k%=PKG}20i9fI^$({b>j-L+1x9;_Gu6d=YNQpDX;QYs; z)s=g1p@vp6Kq2r&3+^j>?t35vw9HpgO3DO6^n_|CI~9#zt7ObLnrCiaMp1rV6fd@|O+a=Vt#auJpU*B2vv!dbv(F}l=HhNVM2L%W7ZS${$4yoaFN$|;x**OVi^BKP zc6`eNyYJ($ARN4ejgI2QwMjL;yV3;feROASHr_B>$f|AJ*!{;YvgqDTyE5_?_ZPnq zg%g7zK#sHYF&;f?^n0J1esptB4&Rbg3MML@Zzh(+AM^Ozsv@6*WWQpPG%#4Ts*Mxp!z%h^i?~0Xm zOQ5~N+nt$C*b0cZ7-3lRMRM_qWf&kxd=JkZ_THQl+SyX>`f)_{OPwL&K73SB6HK2W zloW$>EON6i==fyzi)jFlyA$_>%i#nljJLCa#BXcg*ll2}uTLx%CQ6aDQnzGU5MDxC zaAtKVvdEEmDCocr+Ci(PiqMAH|2Q(i!l4 zYVV}Hw{v9AXZ$?OC_$$}gWCdeAcW#RBg~H9KSJt$R#{NN6s?y-*`q{{_6_9o~X+*NsMPQ^i6STY|vI|urV2%Dcn;14Z)|%4GaEVi(%~;5RNqKyuQO!og8+qd5bI%Nb z#tJLgqp%fajqdRC-dHPbCdtlQ*BUI5;70o!L)@V7a}5rmU1uSeZLd>1tqSx?_`4h?))pP1-~GOBT{5ElfYi-UruU+K>t>8htT z^M`&y)$(ulEYehz8CTZFB{Ni$q)Fcbz?=o>>eaO>bGS3vLy6hS-JhY`+N?3y7-G8A z08eiEvGUyF@q#SgXhwUzPo3Yg{cg$83^hATOVuv7x7G8<&8e_vXQEZs)vM#pGhjvi zMb@i|nKaT6;K^xZ?Q=dtIWWWSuYW(EQOnxL9j`xow6}{j!>yagnm)gfZcfR8j=H_J z3*64VR&nJ-j#SQ3tT*_i*01K>&ZD9gU*6{WTx1>-P|a9`i_t4e$*9QY25=kUDIqQN z1rl_8T4TYe8NPK;ym@)L*P+@?dFvQJJdXYBaQ8Cyw0xJZ`hRucui*dHfnEjojR@Ty zYScgFAO$en13DdCqs3G(uBo6C_vbV>V<%<=r<;QWBH8o15dPQ()v}&hz@K-)asimW zBXkO4kZMgMp3B^dyr>G}x#=22K7PX{@x64Ssf?DsajZD-w^PTo^&mcVAPqa*!nw3> zk+80>ieaSiBg^yoWt4D|;9AOW6XtvlDV` z`Lj;+sIpXFwcrfe(g}imck1aW+?OhQY}YPce_xT)@#4)YakSQ*I4c3UB|sh+3p)H5 zZCs%(M9_^4WF2=9lIO95c&UBPVdSMu&G)8Bn_eHy@Ne9!!XR8n-3N?Cg*EVzRvWovQYjAeW$}Jf=gTy@<>sgCRD>ABI})3@fMnJc9%)S(Tr61j`-+#aj(_JHUn-^yKun=Ur3L zF&SS6crsz@HR?f{em5H9P%b>k)gr>g%Q$~C7fLnw+3`_%noCfBJ+8U(t$zxaMX$D= zUW<)Cg}`HTCjCP&u7-1~;_bdIiPntVd*?APbFKs2%?TuEeIpTt^vPX>`w;rE!^&Kf z;6oV);e!HwIamjHa2(@AiY_jf-_5fF@aM3PvpeF-ZKE5~)S+0x2c$CIEcW7u%yGgT9s=~W9%NiOAjtprG!6=k6HdbBi_LBKUBkRNW*#3?P^ie;QwezT@J5+7L z5kuwVafNk3Q()=wnRO*i*JvJp>-bZdyFOEGs?_W(X|WY{4@IPx70sV8XBQIJ%VC^M zST93xBkz=@JNnr7yd*O3W6c3$rXJP&Ve-%Xz2zw%{OKPwf<2`>;&GV>P!HV%}K&RSle>Q z+433_Y80$vB(jNT6aQnR`nR||xI0q~JL$6Gm&*UlPgfSP8lyN_F+pr;3T%sl_q_X3 z@MuD2S8JWmm6Q(g>yUEE^_VHoB2e+B7Js2NSxI#^0Wwr!#cb%1gGabG5FD#ax`6YL zc8<6+W2n>VXB}}pMBei9HcfZ6UR%Gl`!{bW|9L3xwc#z?MacKUNlIGU%7-<~^NvFn zn(}f3;=trjxIFp$^fXsp@1$as|1tT>Wr>+MyLY!|;_qT^DI z{n6giIxqBkY*=DyY2e+ezKy5vL-mnc*v})opan(beD!mN)Yhs>Gw;BKCn3>bYU$gF zkH@!^(%F8Vw%vA1FP^?QBL?^LgWRRG+Mr0NMQ(t)(W{1dRL%~@wKqlqy!M>WVNc7| zSnd2_^?SQXS2`aTnqmZ4oHEnJ+O@kH{z#nuZ{d@~uh{?AC;wJ9F=oTCvHd+Mm!JMt z;2s3c@&T;`XjsTJtL6*EyJKe-B$`?p$Ce37%4vZ@YEm9h8dyhSm#QBSYf{13P4W5P z+*k#(X+Ip(Ud;o+z5|FLa5>ekNd8va`683?`ayxd!s4Qrm14cEeyP(^#(PwjW36Lg zt}I7oD_Bs{O@{k=cjpv<)8Jm=i!N0i0iOT|A8K&W_&lZ_ z>C=<4o)2!RGg$^|ODVTM0JD~ucCFqTeEQvwrC;*l#_K%MIv2MP{kQaWo(k~ZuebpX zl)hUU!?i98k#uAtL)c-_0HdIh7xu7d-+#(SHZEfu7<79rN96Z{81ngvkMR1{ncw;W z`|?^pxxk4JTz`^%%fs)&bLF?D z`B;o^%vRT#26Kn*$f%E-RwFxSt*gFP>>wwG?th{{Sk{xj5Yxeo27MpR$}&1#je(pm zP$I+;)V(jIsPpS23fj0d0@Z{1OR-qak*Ebr(BlcBq zr*(U0PlqX_asnZb0_`cFZw2!t6aXZ)g+KDX>>XMbu~z%Jcy;^Kp;L4t#^62tUddhb zVE{%ZF80tYP~V}1aPBaoVU-|=T)1F0|z|| zcvxh4z4~0A{<|_^7+YvwaXjhr-HkXH52@!iVk;+3KRPFdDN%wJD`y} zhkeA%9QjE|eY5#Tom0Gk?=$~Vex;x%D zqL3nP4od#pxE3VYZ6C}NVaIbonSy>1rh5v&1O05!x&IfgJgebL;_oG3L#B2hj{eAlv_LEz-4~l94jhd zWtdTL;q#PP?zA9Tl{wo3o$?`W@2-r0jzt_xj1_2bAcPn&FuObNSfd`=BidP6{(6-# z51)ma*D$aUdr`pu=frq+GhCup8dehC{ZM+Tcc%dI*X|CeVi)no4pZ9QGH0>?mr{KTBqTt zau_z4&f@YmUipUgJ#X>tZ1+8S zw`Gy-q~urtS^hoLe`J%B*B&>`I{$9Mgj_&RR zuWbKZj$=ZqY)tKSgrS>vi?#0BvM$W_PX&>VWvv|;YBoN)R7%sh$^B)^Zi0)bF&#Fd z;-K|Wcg>5*Nx*x;#I3lgIrj@(w=jZPFI7Mdnq!yC2JgNhXl1%u1>3Jv;cEo3dZvjN zh}G(3{B|ZTpY0l01*o;NVZ;QzjebxCs#)6WYgl-;ZNV*{PI;g?uM%fpS9&Z2IxYt^ zh;O$j~+2N*Z`TQQQ|4y^^@bbszTT5+YsYO{OS%2B@Xj83hV=#g7qW z0dB8Z7FtZmi!`6M6LCpEp+&a;%Is--u4HuO3p*vwprgN%d(kCnKQ-$<9;CIh%~^W> zhA-Go`=_~fTw)}$3zqWALca{T%jgdqppYOu;N#k!WZQ2JIJ!nQPTO=3+L^W^w)oS) z355DbZ)|BkLFQ(^ym=OIEyTUeCO#eJ@v=goBWD?2?qtAr19VXmlE#Y#y9z^K25>St z>FJzG*duP2x9!_KYUk=R9R6Qf5&KuX<(@ohufVp}ZbTsmw%nOM$&NAmA`_b^+E7*L zOf;)>`n%(KZFi)F0LxzlKjvY5_6e$=Q5VF3@PY46GGQrv;Yk5lD1~-BozXA6f;;(f zp{-H}Xb;%y%gli)<*NS^JjF_gD+Z#|oL<|!7=dfmEn;tc>@n96PlESv`R(;>{NIp9 zYVibz4`qoMT}+;YV-!;C`ir{`Pfj!;24146?pDtvc(dicfeU-Q*#;J_mqwQqc>bAy zBE5X|-HF%8hOmu546uqMw+s9uoX&10tm`KZ7k}qL1q6dEsKm7#gvYBXOIjqzse3C> zU+SI5zi)+8)$kl4D1A zLi2ybUtZ3C#Gh%x)pjch?l@tPY{^RR@iY{3C@$O#@D|Di&)Uy{o_ z^Y=5>)_<(6wKge&ojjFfA^o4oL8G&mDs#6Alp0`*(i&_}bHxB)L@&dsvlMP|e$QGPZ-k7-L(llx9ycvcFwMv3W!4m?^69 z%JQxq*Pk<#_ulS!sFym8bKU9Yjc)_R%UF}D9+4SZ0DGe<#rgLgf?eBOUnZ35|3d=@ zi-`M=uYPVTk7_>1V97kmXu=5)XtUxX3kZFL9l4skDW(81Z+A>lqN6p-Ai4ctHQjtQ zH;zn?hWw_})F!li;tS zj)MoGOs;0evLUG&+WQ5;03OfQm@3sfYxzxb@v?uOEb1a@oTaMUv%kXF_y~=&%Nq5K zn3Eke(qOXLc~bz0uo`|>_Hhnb(@_iOf7~mc1_8Z4t>Xrc5+lxL3Lst;Vqx%m@($9$ zQ}{0@F%=B@G6aI3Gl*(+&`6`VjcjvFkwMN_##ankgm`5K>h|3lsp17ZUL_MmIy@u^ ziROTX-KJ}2GFiYzB#kNMdThV4k0rt_7z3#ecMiS8`T(3W8+MzN#5)x~2rt)s93(3a zJ*YNt#owQd$6->9hcUd%w_DWNN*|GxH2*qL{Vy{o7KlGWo)2xbBH3A4S6W9w$3zRm z?8BQ4z{OIPcn2!2VHU$tr=GMI6zNvlNVd)BH%a1S0bqPgx(=02 zKv;pmiMP-CYF0EwjiRZ-#qhW)1FUy|_il;#*V$U$W`R}3OYb>Le#Z*!i+2V5Nr4$aU(Hv z^juo~>0E5}%?~EG9%ru4Ta3eKQITjg{Nh~ha2p(-9TUf--2p!+we&{SRF<_@8xzm37U{wjajP7 z$-BOc>d96V_-W3r%=ql!v15W^^V~M%)-e#T43^K11+E`?aq({SYV?4h&Qn#6=b~lf z=&N=HNu}Al5TQ}U;SM{cFxuKqEr#qFn{YF%k0lU8UX6@xM@O8ewZm}m-a|lrtE;qD^BTMwa*Sz)_#K2lm9YTtN}g-)Ci)$WCtKT2B4;rw zG_bMp9t+Dsgp+Ns^?asRoFkDs_MM zDBcZu&^v;ATsp1m?AD0B_5g{pyH5(2lUJ0RtURkL|2zkG5??mi`FU^5pw9zn;)=Lu z(<2s^zU2{4ceLGRoq?-D6rHo{q+6Js@IPwBGC%|m1Pq$T{ED@jtQ($Qx?WpWes=lj z5*-`s{D7-LiVYVzt@JH`RV;Pt9ZoAvelh$kT*D+y$Wt zw$&W$nIMgC)Cgg(8L5Gh~c)ul~G&ga=fvYWMa{?gKw(cT`zfQvHT zNEz5Wen$G|3|*P)WPBd4TEGBmH-#*hjqX{e3k}6czhc#e54QTUFTAqK5u85zvht33 zrs8zq3kify62XeMc(m*Xp=-jDguLx7o2s{<;$H)@YjH~C<1Hx^OOhQR8%L^{qD~}# z0xHTgV%j+D|G+EX@ZXes*biOqK%SlJpS6Z&#=BH00b9I+ViJsDvOJK_=# zd+T%0Qs;k}bq4#}y|*V8-9;Vuu(FDN1tJHX1GJDInzA3R@kkzQ)HlgSLxxjU${r>F zSwTeM2tP>>#t=fIKs9N5@uqc?%Ef*qZ-hE+9HCWP>{AzRqp&W*6LMw`HUSO>K&BKH zkOhdzFoV~0+Lfa!pd!+F#2Ou0mCDh{v+ta~G-|p7nF@;vS^Ld@7K`NS%V#Y2=*S*i z8DrHVu{GJp@rk4sAVVCREROh6Irubk&^n8kPK?{yA0fJDX(x-L z*WXP6#|7_V1Dw1|nZfU^kINj0Aj*yKd=zPZQT?AaZs>CU#hPSX{?d}!6^0lQ#i@j0vuW6IgQ>Zb zv`R0C;=BhgpM(D*bbL{(7u7Z4zE<(A%2$PN8b!^W_;suFbrVx_3$L(Y`L!E4F3x&r zFg>eRb&(?mv=Rj&tR}nO)qqEX)gCuxk~BpNPe-ZMm>lblhf&ExsaN8doI5p4jz<@4 z6FdERzdk(SNMoS^_Vs5&`zfEsk&X_dEgxZ*9hq8^NugO%6CKfE)U$s{M|!I5pHonJVKf97zj{b={z1@W6^@6hIf0HL-`Cws3qSJvvGH0M9oPc-RB#fQ<0 z40MBFE05S26E0!X4+WkPu|tpo8x`kD2^j~ZpIt?j#rj`(@7-cyU@GlYfH5 zbp)A10+B$orkGYgGZ1ECFmSJUqQ$%cwiQr)mCMP11I}Pbp67F$xC%Yr{X>}eA6Q{= z+Ft@S3^74UEtF_o0i}pD=ztb;QE@*uL@d=v3Sk8eWv|8QFh%lPj z;40mcG~~d<0lQoic8A5?*TQ}n=4d|SH18zlDdAqI$w_NPfLrtqN?&NEjY2DsGGK zrgeH`Y$cjIERd=`eV33V^&PqW>|?n9W1qOzTRQp&y6~Q-Cw*xaz1Ffkm(FGjVe=PD zP?*wvRE>9(O8a>j@$0zozQfXM5uR`2qVH=~>{HsAv3>`kpmE!SPG=9);O(p1W8v0C zr&mVa5!&@k){OfbeG)7i)~G!K$g+CXyyLH`1u*=gDJxC^N8IB&8u>xmueS^7yU#`^ zg0ew09*H zy&`uc)EKAqrJM-P{`~E3`cJI6+}1w?JW}8=EU4y57teIztoFrqu!wha$JK9fzgtN* zFqYOR$KQtJXKYab8w?j%c^(_9%Bnw&8Jx1O;+Xn;7m8>#er4F6g(V0UkRHMI50XyU z`5UWe`c5eNWqQM{lV523g!Jeu%DbaqQSK9@dw0^?v)+62kMSiXlx%;7W` zX1ZR!d-k!07|UH!C}d93%M$WXjXbY!%bMp%2u&evZuRsKVW#Rzlgk_|1&VfE|GMsIKKzI=X^5@$nlfJz+4J zkRGWS1#Qx1?S^@`ArH^`?CkcmhmJBUeoN#PI`;D$j5!bzoEU%W=;?~yxN2H}QR?U8i6E>B)$!qP9=?%4)?--t6;T!f*I zB5_ z0e?0Ok{GE?Ld?l z&!UHW?SC%Vl*lACURixCUIIO#S$%=nsKg=Lh~*$lEuQO_4(?VBRyO#xeZ=P&_4jKN zZ#S%F#?c7H$wYe`sS$gAT!4A!;#cyO+q&$-(fi~mte8U2;}jl+9~9sd%wmY%gDfe$uszZaBv zzT<0i#ZTk!Kit3d?rTw1N?Uc#fHVEN;9g}aJ>t*u3EDt4*1o`VwGPUp%D_Z^c2ZHRIK=c&`tf7h2&xSqOvLn=21*zX#d2 z|2hO+9N6989ZX--)MWAb({?I6vFQ6v!-y^n0uuh9SjD)PUX4w&SF+%3@!d=A&OrBO zsVA0>&OO$G|15GA?_K?$0)N0L6wCWcFzVC?`0o4D{!_k(PG)lbbsyjCA4skuBr$*0 zd|Nb8Us!PkRrIl@?dQx#D;W;aMuRu+Od>okYaNRBkRHB#4u?rjbD2 zq;me}%9-mLi^*tuO1_>mtzyHMrJmWcu}tsR zq~rZ?3>W)k+Ix@(+bWyOswXrNQes9gIgn1U5ZC~l@G@Cw9vRo|9%HMUm>Aa%-uH5I z@H>pI;Vv*Q9jQ{Kai@#4z9}Lo=uaKbHH}?b#oqMt$=%Klx#*B3BJ-V z*5CMJ<{+*)UHex3AM>gzNwCW9F8+qT7&|o(^&FNDQ^fyst~QCrRfF#G6dgL2-82th zT4=v`3wZd<6kzS<)^jrJ{F)S~y|8kF<<7vw+Ot-lbFwwNfFR}8cw+e9O&x66)+DhBW656)$tGLZXUSm1pSBtV*0pI*&}cPSR6XI z08uw|uq~iprh5FYIEf8lPR%JSrLQ&aCJ~zjN&+SO&v9rIHak1S43bh=PiZ zni|JUGD~5Mq^%rNX_0S(R$(YHA$v!KU{rw5bn~Z@?)(R4;#Ux7rfb7dhdh1aC3+rJ z#^K5bl9r6Bc`#}wxQ`Z9dNy2)B=5Tfy5z#dH^z0O-IVcfgV5@%-n*X93Y|@X)m(Yc zl|7eJ*6Va-NnV&od%vz%TV8rvxqd{k&x*GagHq;jX^`{w3%D$1LsW7`Rb@NVBe6La z#^EQ%-UlZ1vcm-BkOVM2;0dvD=l8X8tDP{K;hybx?HK|Echpa(OYs#kpid>)LNIeh zQUmALM}?Mh-C{P)nV0lxkQ5hgCeJE`>hB4xe4B_u)$&Po0>tGf5!n#BBvk-~sg;`} zir&*&m4Lj2EjY14vR6FLmP7codiBmxS#}*-O2Q==`Gd(Z4!f65lbgt=*g&V3y}e5> zwU>6^+y#BoT8eqODQ{u8)lZ%ap~NNHm5<0zbJ7})8Mv-gW+I3ja-34p<((GBYw7q| z_p6uoIW*`5v-kq~xGEla_j$aEbK1IMRIioo;BpBXC%D>>!@%z}QHs<*L^=UI*LHJ# z#ezxIO^hyjL^%vxflWPFF-I|m#r4fI;z9xB4g99o{^1zvyUgD2jvQv z9^8n6Ic^=98uKpnVc@33;nG-D-vimGA{V@hZZJtK1|XKw92F%Xma1#~d5M_G8?N87 zkk@W!h`rWfHh6qH7_oR}A?SK3Py6u6<6wRRKdU?AnNFr)>Nu^NwHdL@Kkm&v@J9Vu zQ!l*7SA^vS4Yu^E^KsN})(5;bVP)sI*U)I*`RpBd!!_FZ=vZD!$Ncu_+dC|ky2o9o zH%Y|*ganYSm8*qu7NfAjb4&aE9WjCw%={4rTXtjTyHl}R`?(6C+4N0b_%ZRS&c{cK z#VR*a4mMr!QI}-4ZZtw5!>z&p;|MgTJ52_t(I+VUm$@i>|9<`TwlQu-Hhy2USosr` zkr!cK(Vl!4MFM$hY&ij*lHkU6ah%y)iqUVcRBS_d^l8&=@=;G7*N}LVD{=Y|SecPZ z*lGD4L*yN~X>Fg5;>Ujt6N{z%7@5q8|2G#_MQDp4FnfUwaDN->q>l z*JAQV!94KpG?Nu?S?#V-k=uM@0=_R@{YO}oVO78W<&y?dhQ*uAG=-AzM;g;a#_@Cw zYr0_VvBnL43pxhU?ET>4Pq`ms+u%tNW=k0#JDn&lYKS||G;zS%J3vq8!5CE-0AaZz z)k}!7&Bqtxs_9Vwl(Lua zes!r)evZGo#L9(J_hty>VQ96h?#P%{`{{Ev;rU&rHaF6O{+BJN6a*P?#aqkaIK!XT zh3~*GO$ZJS=5gAeHpld>TPoy$NO71gt6F7M3kuD0on^>f-L&=nOm&Sgf2B6gjkMGU zi1Jdtp%$=8aRi~M+Pfmt%c&4d!&cv_#_!gi7)4?rm@rl|89RV)_Z=y{-NCuZ5qTwU zHuO4@`VMqDhTo0JFJrG}X_i)1E5M`y1aUbze~MS#4>R|f%i0Z?km+P|8^?~wmx842e$b_9OCK!!OqFO75Yn5( zl?g^3h#1jCQ7bsGflSoRcFp4!8~}g+^7y;?JHiYD&JsMf#c5-J4w=_1dh1AGvRC}k z3`PnAg{WJ&M4XvS-}126#AQCe>)n2zlC74TH)FGoVI9&IzT8;J;RE`E|CJiN`K*t2 z)JkRSK&G?tt5}65SFFCFi|Y>m$M5Y=vfW!Y@uqD~546JxoVj-& zjG$TN+oOQ(UoZf!F`3pGlORL5HR>8Y>+Ciruc;@9fh+g416) zfxC*)4@notXZ>T(lGb3BkDT>WS(#xS!2&jV{}wFJr&8qHUSbT^(XjK zp*fedVT&bWZH7B;vt#9H;;m%@xXUC6rOT!E?!|8DLhD;{X)`Wq>cn&=tfR*12O@#C zi=pEEvT}<#!9K%dPO76H#^gdo*SErBtdwB+Lby>LUyc_-uVxOC6`zvLu9CUCt!irT z%=@20a(=EvLoQfO*3+2PwAIh_q9TR#L&bO7L^TaZWW(AP@amc5^D>#P<} zE0G`32YThMX5%C~i0Q%1P5!R5#LZgGk4BJptbcS*3Vi&%04)(~M zszSwcXK9CZlbA)~;ar9$v-&a70(Vxk?++#9{Jsm@*N)w_KBGnJmvsEDx7i&@Owr8$ z{+OVt1zTuHj4TRCOKDYkM~18ZbsmkHD^03}dvt{Fm>GkRzVHV0PqU3CM%h!A#Qr`0 zhp@d+Wz;-xnXqhyw!6EV?0Za}1cgI3@Jd+pJz=;`3Rx<2b=Ym}>_g~yWd$8%Y_{p; zlMK(Kz{_e(#j(qTKyP-!Wgb!^8x(skDR4|yZ)JF5J&Fx~H2Dvhd={JEnU}>-l7l-6 zxq3&h!hWrbK#+BsT{%lnP>M*D-q_wn?i}|b%O^kNMWR%?sUw@OB3=gHKMXI$T(fz5 z1nuBrjn@H;xx3hfZI!1k4IF);1{R6|EI?4aVr@rjI#HYYAHKFXLdamggk}`gOsyJ? zOcExQad{JnkQGSUrYA3kU9;K?o@7{L!q9BMgx0K{SiFkj0BL?wHk)fR2L6$4w@_AV zBQ>FR@mY6ftS-WI>CtGx!Bf4WzMXcG3!PhMBNrO?ST4F=^N~`Xd?b{M-BW!o{okh^ z9JkwMbM3MR^Jb?)^Cb6)?42@UD)xROh)aDlq?Q6Imvy5S-D+<`kpNFb-SmgFflUuC7kPj ztcNHc>x%0UNk=g>nRu$kM?TI_K_KUi({RLm*ZXK?rtbsO%#}vr#nDU7JycMh00O<9 zrtMv~P40q#Km~Y)_3a~g+Yb@^TPt#A=oEOG=y)_38#*6S7V(?GOK(wRp@Uy{hNfA_ zGUUxU1MSQ1)rC9eztUOS)kma--dRchzVsbvbRo+i$iHGkhzOa^7Uz5@~o3b%3p-+=%a?8<6wg`Syuqn zQ=Ztn27*Bk^QZ#{#10GHZh|3g8&31JdQQ`lczSJ2pEbr@{(+fKEmiBqlB5sf(3k5{ z7)Z@z86J&I=5x*JehMf67(DE1Z_aPBr|U&;nXrt!W1&j1P*$uCN$&_g>V{kzN;{&S zg2g%lMgbC3bL-e^U0mkTBTPHBgP#cs5+myQ0s0~FaQhcbkK(P{E|<o>-(0Am zc7^Q3hh*&>W9X^P6Z$#nGmWFJ_-obKc=U(`{G2XYeQqT zooG^h+jR)Lm!zX2zjJdhQmvkeJllak;K})i*`D7)@ma3|K!aaRe;j(yAYh=YRH#?A zMle+Vl>r+Jg(1KNI|jH@Oc?Y zJQ`&=Ju^*6bR=euDXV{&Tw0+sE9@&z??WcH)~g)GjWDr9r>+s~W?2g-XrG&2dEMwn z;Efg-f?Z9*AoGl;uYX6Fj^^{fMT%NyUY&1B$czz5b#So+altc&50u0N&p}Ws2Y4in z?1agKe^j@mD3MeOa|Kn?TcA=73yq&c$X*P7PKW8qr@doy(F$WgM{+=w&VkIBWrD6> zQl|U=c>yG8IXY1qNlodIxkb+_jkgM~Blz=kXT78W%k>t2D|A^{|+X+kXcd(Gwyj-o(~%Qt>ka(QRKh3rmDm zY{-6b%a6GDlQK0%7fqj)X+t9nU|APug?Uf^M%bMLDfm0yEgW>@3RCub>UQVO=#nth zLAg%Y8)w^ZR#sO2D>VY1WVM~>kGgCwCuQ3@X!&u+=I$#V0Bb5!6tGEt=81{BSCL4( zSGX?0!B_){9p_Lk8Y?>|mO#?p#45Hj2t2U(xUvIYM@M@1IlA^i1<}>nJC$p&n@e#E zAb_OXJ?2Gv&=ziYGSCPrUsmU1p;$pNY84W@xSuo>x}o{2OpqcRWOq`?^DrAfnAtTX zI69RC`fh*OK8MH{zK8hB1P|oDk}(ll^{U{loXN2U^3nfF3LO2T&KQ($L-T8aUZIvrAo6Ai++Cdx zz<3ut0*=Ixld7bkL;3lc>d^~ja!Bc*`sK;2@VnR+NOpoy`+|gB<(MH#DN#Y%!6if; z^Vwm)1f*1t#<>+^7V6pkP>L zF$~Vl!D?nJ#s%ugkvw)()9<$uQs~E^zg=x|x^-#&`Un1MK5D&DdCoa~O z9%Wsx|F-Uvv>tm!E4?;Q+wW+Wd`~~an(473N&eXurp}&g%#i%^BH?GGG<&#z=ua|1 z68S@Sju@#@?4t{}O{p@<>DNmK*S*yLz@;-|uz860qmtz(U)#K(=%7Dt^QBoYgM2!K zcr>20QR5VH326U@$75?9H*1)+g!)Se9!X>sb-I+9`YPW`?7goJ)4t71 zu?CQT)q>vFM*{YzpI!F#tcM9!@!Gh$B53Khr!4<%T|Cg5>6B58AgXJluq5f z6Mxl-B5^Pft=1*GQ%a2AF%e!pB0s!0x$ zI=UifhRuafSX|p)UxbI}yGaDD8`igTFYrAYx4PbVaOW)6Bs0(Gfvx|)Y9Xo}uX)Rq zACsrC8v`s1ijN>w9Um*4t94$_C5&y7RnnI1P)F8EY(paKkbHzkESEs|0IKO$Q5K|p zpAZS|3`|wrdPV2zPb+f<3 z2f4}(UTJ0IQAT(FXGbinsL3JY$4WAjv?&mt7CMWLPuUhH3k8++7r<5n)~nl zgsnbWFP)KGjA4_S0P-9l(!P|g5PUm_fFU%5a`r~V{0b!>1xb7NP^7SHf&{U0E*pfj zBMZOeG}!mxP>N$wZOS}XU4Q52ADuTlyszT?;9LQ%v$FUKJ731Kek@Vrlq`oseqAqj zQzjN9Ee1zvt!zO^<9%nZ=8)M#6j$O&qAKRnr4jQqn2t8znhYk=vPx%kMWG z@|+;UQ*i#GD0I-P@Zoe|xa~p#4aUw~^TfhIdWV?m#^!%kxH&!=s2#{Kt)2}<@}>z! zhRc9&rnW=pk;Ne&3#O4|$Cgb^)z&PW za@QXU4e+>&7w~85KONvhTm41o4uLt-o3&oV7OVN? zud-qoy=(jH+~RGn$Q3lkr4Q%6EYqeZ{m3n=M7^vjOF$Bu;&F|&6cn}ITvMug(?47+^)inz=!J)+ zHv4ST33eSoS-mN3s0~2*hi^tpb5D1z?G^k?qRa5Wyu$ETIpT630agLnRo>*6GOO%< zK~SchMCLjIVPi#4d!U&x!E&+P4}r84;ejDhWcUnLTOf$PTf6vr9rg-;mt0HT8aLER*Sw&^Hc|=sd**3=B zDJ6)|AZFR0tv=1CUW~Pxi=zPnL2_~K+_>JcR4MI!s{&oUG7k$ppx?ZNI7hzWu=k1^ zW$*cEf#q2_{9@WgFqf9GofJ4!^2^LtgoblC`m~snI)UQR-3r%aNHtxqe_| zR0~y&7IdHVB=xHbS^Vei_`N~6$)y-s<6xWKf>Hu%VEU)-!6w=qB*Znm;B72*d~@n|4yE%=^vxtGHeuj>-Oh|MLWdG$1nnJ$7xC z!_NM;%?*I;iYOW>GM_Iu#{K?v+S7l1N_vt!175=>iiv>zXWuRr)_!;2SEMMGuVdW3 zKAMo7-!xaTJMeqHI-oAE0h5wm4{te@;q}-2$|3n%QbDXG={>42Ih7Gyw~hVJ%wW=Y z5O!+u$Z+cs3>X3EfI$L!u`VudxARH{M^kO+sfzmoz(?ftv9btjW`#T5FA66k^Q#I+uxXiz-vaC>p3iH9X|)}d%l}# z)da2b3ysZ`m_Ca8**(9K`xsofv<@yc+6lwj^&Z%))8XnB0qXf{vDr^EOUv>|T%PGD zEyc;Yl|y?z?~JC90W}K6M93YIDbMc6`7CH-@v!zlY_U->I%w0e;$ibPh>nm&5tThp zHU#4$v)1fe#cnmevuBC!8tAGej&+8rhn!OjO~4L?>jh+n*IFzx-z7DhIdCJjr_oFJ zdhk|%U+|`{{;u#I;^$*X_q+mm;66F^LUcVBP5$V*AqpFi^UptO?HsuWyVyW;n%9r? zS^j4P*#FQH3gZxLn}QhYV7*c{Bs1;$aZd`j--5z*m1_V~lT0Hljwy7dMSU(bZf?{# z-!>=VI5tMd)Kiz!A?@cV^*#)e<1r^Jwa~5q(z)QFTklCykS5w8n*f~k2U zN2P2Nv~j!esF(?waktdvL&BtNap;K3&n`tSc-lMq)1A&ChfYn=rk&i~=`d=6%x*q( z6{@uR3wgmtdwNgDs??h7o7rTgd*+v8mZ%z9-L?JdiQdfd*3dzM^NK|1y8e*EP}+vS zle+1mn8A-*50l-}wc-GRqNePtM;lhwo5L+MxtMcawi|p-fcb zEMwv0QaeNwg-6F1>sYx_)$8q%V{=hYp>#GA?o%KB1*@hYwu=c43K2fNX!+wQJ*ta1 z+WBm3iaaULyhDXT)!oCn6S-zvyhLgtt&DVHlQyzgh|F~&6Knf@b?nI62SHnAxhcWg zv89ruVVJxmT~yqHFmck)F{;|x2hZ;HfU0!fGHir(#7iwT5E{TB6YSiJlV1x*i-eV^ zICE>hgNh{=N6a*9Z&I(<8#BiaG!a~}H*soD_H4$|V@VD5ob32C7elajT zOS-Kww)i@)nE4AFgWv3P`vY5RgkS?1m#p>?5W>|axHydwD4&c*v}QJ-IwBak<1;!~ z=QRQvoMIa3z^;T%`S*#FM=(6wRr3*1<6DL(meHF1m;Pa&5o5Y=U7PXCwrT9TFB3(aKh|Ww0P{E71{H;r0T|L>)6PHj;^Icu(Nn(;y*5F{! zTEot0j(AjuDT^@Id_5pu8pb4&99);z3ZO68HE^tzr{1cImvKO+N%QO41}^pURrEA? zkHGN#+jl{otq+a)8C7ab{OmW_(3*gu=Q?7Z+g79YtiH5+o?NHGyaLugb|*dm@sKH+ zI=<0c7g@by&+mIO&>T(8das=S!oIK}12*tUxL-qJCgi6D*so};pRO>X&zTYtWxxy~ zoJc-1{!E`1`r%=iU;6%Tinv$trRNaFwSPnNi3(ab+r-cuS|n+sp`L2R5j5-g@iK>} zuE(-at9T}q^#5o^r{9e^WyvR7HUT~<*{%#U-;U z^-Y6JO9-F0c1=-q0r^#Wt3tmG4b{m!TI5@Sy}?lhcfPcG39!+!KQD;!o#V`A=$K=c znPV1rw`s~=pYv_E2p#`KKj)#NQf1a;tx8n6^0<#Q*{E%W8_>-QAZbH$JRR!D7FB{H zEtqD(-rFijBwtopd&?ztHU3g(w%$airJ=WyXA_$J z%MN184oeFejNgSxWaj37zrGgn-{-Ag{C>TVO!hnbSJL(_(@sU+d+gRt*Ft|--iO;5 z6kYq~3F_oi}s$5;np0XDHocp4prwQz}pA+mwUBQBEGg2qx;iMngi(+E2z}o$bY0^svgb-McNFcn)|Q``q)R$|yxhkd z_l5M}!sw9u$eq$9VqYb-qx$TlE_zgzqQ#?>)AftX^Z272dmhK`y?yovHNu!ACi?02 z?cQrB6;8p&9xibcq;~FSZ*GW}hIOl_v3o<684597G7 zVPT}W5@oh&o#9(6;_|PNz4Pl&t_4|o{vn{dt9rOgV&yNj;Ln+T5ql;zhW+JtZF}uy zr|hRr4Z2r8Pugcm0#C?meK?WCf|x?J8qp6OR%^bxfL4#MC`_ZQX?PsW9Hxo zot?i7>Pzv34L$#IYl98=w=ntfs&96}1l^Wl#g!&~G9O=i!(*j&B7 zJLto%rwE}lq2YD7-X41X5$3_A`HHyKH>fkT9H>rNpDX$;u;N`i8-^I%r}9sUeuRE< zAPkuRf!~(SZ;xa|XT$#tUr@R}B>TQ#&x||n2!BO8tk$r3Ov!&qomN|N`A;N9Ek*~?l6(JIVfQV|jrlO0(x8pzW@`ut<^ z=t*$-<{GJWAA3M)>wWHPyI>K2ZOH3mgJnu1yRKcun6^PvS$r*EjF5LCH3e7F`it6T ztr|mVPXu;DQbDix+9#aNtqMofJ9jQ=6h%iZKBkf76K$ge>EDZB7tto&c=UC1Pgz6J zc(>J|3y%;R1n;m_ZPtCA^n>c>YO|}Hp4sCCdhORuvBbf4qzTy&S9dPY2C+w6I>Ru# z-)c=wi|0f~TMPgF*?H2^?|8ghx?oYbclj#?Co5wp9n&uQELB`fibq7p<2Ef#4Q@Xy zNWV_&^4%e}x}5Af`g;6huS(>vd{W8bn+Pk*#X1imh{F@BH8rds<0@$0k^##5qfm*i zYo=6@@OLFN$coX%Ndg)FM)SF4pOt45r9KT@0q6fHKrLrYfffGhl+G&jJTw z5(k~xr>l4=APOUItW+`%#2yY!<0s2M^A_2K8=jBXfhoyhRh-FbY1{scb^Eu!A0~mY z8TeWkwGFVSvdu#8Jw5_{O4uD9CZ9FZ@$z{5WMCdUiljM0z=YhVgYG3nIo!Ij9Gj%iEL?Q@MzjTb!e@TGZ* zc5(p(>7TV<<|JW0Q&s``5y#Vx_P$bTJX8f^@jxY25d1++TGo@l)D)oLy@ zRlTf0Mi%nCHdc;y8>d@P=*>Wu0p*;pU33}a6!2uwzA*walaoZ)C)swlyT*NM^AW4& zdH5X2ACmH56}~bsImNEhiJ4i(UbCGMfwoB;IajAmqMyLYkdZ{L3`&uP_+AQT<8X?6 zDK_0pWICk#fU?cBxvp*)-8HfF?oE1h$Sz%?iQz8yQW7EdThY~i2C`T5`cU4P(okLZ z1=2}}>0)^02YEaSw$gNHz5PK{3;+ens@zjB zdC#bWPTb1*5s5^mJKu@i--U@XUtElja#8u>QN3PY`j93!|7 zp|s`YWH&e0wbuRtvAw;0Y^-g`!6%A-{4OFf1s&n3hy*M*@&RwT!`G{4JH;5`{xifF zL`jQ9%Q_j9-?y%qwb95%oyl+xlb;xt*8a%Jo@Y*u+uNZb&&I|KllwmT?>x{2tX3hv z&JPMW7;yZ=u#(%8kQj*Us3QJcb1L~6@KM)khs4-U7sb)wNUqM>Gv7fpVtJqLA$|rs`!T2x-_C z(uf*1L9*e5wJt7R915vfDp7LE$!+&DOicZk-<&SyaS%$=IGe=g&vN9|5eg!L^?e<< zkgbkswi5gj9Y;6~HlRfDX|13Oz)g3U0F`zeG|h%WX3;8nV9r;|r65v)joI=WvTb9; z-=QXP;xM~Fv}Egf-TEPw(nt2&CEJK;0)b-!z>crn%r{w7M~P5S9VkDMoy%eOW4v0> z*n#dDEnhtCsN4R@hL?ie)Zjj1Z)28jH=*!5=NGMSlfk_GfTlP}kWEi;Yas^;SWF&h zO*7Llh+{pO%wgW3yng-mmTdD>(RZ^D^u5lC56oy1Aplx#XT=%KX z?Ctvu?>{r&4;AQnYQi&gaFdtK1oa-m+JeDO3bvYwP7{VZg%`(PEtN(p8GTvFjm-*Q zu*Vvi1D>3e=t;^45x;+&+0$mVatjPaTTrq#?gAS8XGexuj~y& zSN#&d&I>=9%@njo(q_)G?qvJGNujWWj)qoax9-Pm1o;nCO!wOaF|$JYA;@A)$6V}- z5+h>SppztYon;WwcL!8_-aaOE_=Wl&mMG;5YRnqG`%FN=xl>p!7fk+x1Ukv!H#f}J zUOdd?ke)UIVLBlY=1Hh>OV78fVa(uEYoM#xXHigI54^nfP(p%;6E(|_5NQnSqwTT$ z!|G{F=42~M;mb^)Sk7zhf_$t zMEuRWp66c<&PxXlou#XJe+aN}2`_dU>il@n;}O_opOS$7=C*-sskMBrxwp7q_j^>uaw6&(E(9#E$Hiajasi(KMo!Q#*#q8`4E5%~SHB zb;m=7?iP|K%k}iO)*`jXDMH<`6tY@EkUF?sb|8xThcwCc|MLPYQktd(+O$(@y1?-l z0W}>cHOl#*(`7P6U;mgEXceoc_!g4taRWPjg2<#DHo&g+y4=eMKlgTb@zqoJ7I@5( zj0dr3tj{!3C1iHjiZ~#Qou;b|m>L(%bO7i2l~Pqe*Utgnf*&g!Js@iu(?#*Pc)fbT zm2F86apkIlAAhl{M)ROnBk_6;Cej5qPM!NQiE{o_-1ijkJ zLw7I!m|6gSGmi7o*j(cIy+(XJO<^N>hH0RVfiX{BuoJz^VAQU~d=%}xEg@^G)(8DE zX*$xkhg}>byRE@L98#yFMmiltc3XSV4|wFi)XRF~rG=Mbe&X1Q6yjyRI=SiV>lS&x zeQWC&3pVwUj#p$@(Ha~3%F1zbg1L;(jZ^1{q=~x`79GDTm7UJnb3kTTo%Hc-(N{{> zf<*pY$Y|T!`ol|h56^>EaNTyY0s27sP8#}FspsgEVp8@0+8JG>(~|+%$U#zk8M{^n zPlTP1Wu41{{4h5XYZXpFqZStsz~GduK_4IUCU@C8TBxix^sL2zX`tf`0`Fy z(81|Oyi@(!-R1oIOd=H|4@b}=FsSid^NhhHCCMGgf9x1#RyUX?GAdBzGSu$<-MUVL zj}aya=v*V70{C#n8PGkripEi)ns44yb?z|QFa80$%4um)eDm@@HDGb*bd`YKcCpvC zqWT(f{Sa^-Ja)CWnDTL@KZ3%oOP65hWcPSw6=pX+Cz)P2Y5qAiUe>+_TC?cr>qgM? zDeDz!Bb?qb{&;%Z6mpeLc_x!tFR1T8$xeoJ4x{T)B6rqJQJ#-3jP(CPQAw3j&*}wz z@|YUW4U<#u^%6Ebci&EahDdWh#93iHLcU(uE6864O&odA>TH+{?0D(d>R7l$nJcVC zHYd;z`Ab^hPe-%LE|Jm#jJ>L>WzYZ|E^0W?=1?SIPFOkll z-{baf%kagnX+F(~i?M}%4*v>f;i7QI3PPUiu>@N8Ahii zyQ~@2OTYOGE=VuY*GR_b_KQuOSOc9J!ACY~&VrOl+$E1|M9u>K-HJyeTpJZ7D^fv! z^r)JYI(j~9*WufxOxBV>?}L}TJeYX^wqHBNNJ9lJz#zniL9UJ`SLf1hQB2$dtA>qG zt}dM^+IEykkrqHA6F5k|u>VmFLIE8*n#gQlJ>}h+wNt}|=7@*n;s1@8qBJt~`PK$x z&X(R~WpB-ejvw5NHv2nyR566%ZuDJC1`mcrKR^Pq=jr{%xVdmL!%(Ibgp?8^bKnDzvuZ+Az) ziOTe-uVQ7=uut4a$9FJ_01qa_Tcl*so5-3=!X+b2yhmy8Qizr!Z3n>RAG`RsfjxT; z#5JP(1$sLlIzgFF(%3=1322w5N!`z3McL?=oCpt6uaQl*pR!hoA^)Su*^&s|lqkX+ z#fm@6=Ko{w*Yu~fl^7M2nWKyX4?DCb2bf3^DwzUsH+0EHz1&gVQR4mOJNkdQhg10z zLx2-DV(~IWydJiFe41ryF2l|h=JyN1F2jor!UxriB=lCA!ZhAtLU#W7c1m#y^7<95 z?2?Mf?5%S--tdA%dFLEgR?!(^Woqif-Zm+9Cr#Enu$;+Ej6DN32UsKKA2F7xn3}N| zE`cd|7cXr#<#MsGT~S?ovUO{5BpyQAZoJ%* zrs4TwPM-^FH~$UqM^&6WHNndkPW8l^BT4?o&qh=DPf8(-gUKR637X@GI; zA829dvM7fG(%~e`NrH*rVStwS@l6FJ(oEU3gRG3Spt>?Jy^WkGmSAjG{!+P2szDCk*@n;^#5z;a2~n_Y$1? zr&om?aU+xh41>yM=1LvLwL{OE?tq3{k0m1d>lf$8Wq*pi*E&_K&vc#!GBaW#Ys`Je zv1wTVs5O=96*p6K+SOJ{!(yyK+8A!Jj*lV9cxZy%3{HL;{mwAC^C->9P-6IkLZ~*D z1VMuabr{K&r3w68YT?>ljbsOPdIDlyON zFpx;oq_Hd?<~XPSBKkIO3{5b$@Ksl7p%Q;mkf14m`T20jg{_)Q5C8M1!;GKYFFh$v z@XZ_^tclz!UrJ0Hw7VJ;7gQ%f;Wowex$y&ymP}kjX+cgNwnQ+mDv%y$!K$4P;Sen5 z@=mF=QIo_fp{owTkCN@oc;~}>x!LGXL62<$kmwt@rTJ}<$)*9}!0Y2?;(3K0;vL%9 z*dFF73^x5Sd*fN_6NXMnzwyq{kzWM?5}#g$>HS zH_evIPPDmx|FR*E@`!k8itsCo|Ib}#_{DP;MaBYOC<^msegJLjz9)`Hm6%TGWu9@2 z!>voFZM^~if1=m%@i9r3_v-(^^pk+fgx`2}I*6OfjHH8iO!-cjJ#biz54ezU-Fxq= zWR@t{bT4!u(RVN|rrk8>2R}u`AWXLsNl>5GFGd#jwNztvQ$=ySt^_A4z%E8RMAyoE zKBZ~i(#CUV7j(o}g_4x&q{(An9t2w;AiKM$Iwoi5ubP|zQCK;pH6gg9E|#MqH@m~G zwMN;Sue=hNaINOC?ZKlOkwRZBsSNu={Z6XPmyjJK6y? zk9F$e?uSttjp)B2TeC$dN~b#+e{Jiv{Rc^2rfQ=v0F^VQba0m8!yFJA%GKX-Rc4Su4yFVh)295eqkKuY9C#G>8}5er?(Dkx_#q@C8ZINP60us zyF+OZ5JkE>Mt662cc;YY(Jfsvn$g|e`F`);^E~h0+p+D~j_cef&xA%~>Vsdd9K2Vn(Z7DwKHf9}la`x#iqA!V1md&RIxKxsPZt&P z0mfx_wI_Y$F^@q4Zu)El8hQ1WlDw&ZbNhYF_M;)RgwuSaWJ4O7Oeuf+c`UMwT2_cG z)l-OiieKO4;5~G~-`3+ya+jE>lhVeKV*lzg_xM}~=vBa_6r1p3XkmqgQ>LEXSxCPZ zD&(wc*V4DPjz-TB>^t0%OME%PodIe>2?9VaQPt-jAM0gPssL`v#&h4BImoSXm0iO` z&0N8zXV{6=v_7`>O?xygKCb0l__OS#Fl^Ik-0XvKf@}f_1Bb}^WI1P8tgls*zk5a1 zRaEkypzCHM4@PxiO%A#tqOfFp_zjo~(q}3e(NUdGsL5iau*$q3`)mFqP~)d4UEDjc zUe$44FFWMZa$JSgO~FTiJ{|c&QASL=Dkb4Q?HV6hqrO>yW1-4{U&0Bpe=+aM8 zbuI51xhAYg;}+_7@BtbRI!ulkB#z66uo(WVX&3!{DE$*0dgS})Aj#Pdy1&|uOm183 z!2T%H(b#`4(ki~Fy)Ph-zO~cPQc|gF1&R5ng+ngqxl(3YkqO8v&`s&!XmYj3=DNy? zmSd%yGmVFZEYFFWSviB_TZ%ckCJ?s`r+cz;dfh<85vmX6`OzMo%;7?vSwl7RSB5O% zz>H$SvdOaAy!P|3eQM}_l(g1*v32U>aaHbPkKCn}o3K*m_`h8zeN#tO2@<2Io& za=$*HysyQbm(|l=lG4*{!<6>Z8gF@I~ClNg3Clt4A#+G~~I z9&Cr|Qxzv8oi$K9A^ZjXOe}pQkO5+Opr8DV9(c5Yt#oXyT7y5aQJ2M^P>1UBfFO$L z+y^W?jkvQ)F4Uz5lFO9BDW%V?wc26faRpHQRrA$+9_7&oePZ*~@b`5yT*Jpx;aPn$ zMs65hQD1)OHd%hrVIkpTCTWfy$@qKxJ8jpZLI;QMq%GCw=K?e9;c-dYDU|Mn=_8YNKa{{-jWOqd^6Z6dJ31l5s(@= zf_N(M$0q6C8Dbldxkz`>!v4%|Pu$5pdDtA$gpr zMKU`W1TI?Jty@T$tMZ#U=4V6aESG&EWQC25F(HX`&Gj(>Zz&7iPjCPtT`TSV)GC+h zO#3!zM^kcSOKfJt1*U`U)>`2xzNXCp+?NR3jHF3(Kx(0l9SZ0Q_p?u;;VK|V+b(jSoCjw1MH4&r?>~;_T_EW zLGe|5kWzX(WS}pzTL;#gj#8Y*q2Ia{F3lw8|Ecb#`w#IBIkE99v(=AIIvjLcK10c= zv8P2V$iNLM%a3*bc;)d>`@D?iRv>yQW*#36xU`rf^f+Z^dB2r3(XH}f_zhe|1xGV< zUtzS?jfYuB&&fiW8kt{t*{emdlIqX*dG*oj8DS`>MVdNTKpC>2A#qPel{JUyAIeNO zY4WKw?#G(_%nbp|jG??G#`W5Twn^SV1`X*2)jA|2P3L+QbkSV!j78qZ7zp_}#$uG- zmbFc*#RNF-H@WnOtl2z-O58gYc#gWI{6uX&Y|O%`T)}iK{94Sw)}?qJkAnHoz}q85 zadof;`L}WxCBYXtfZ2FNE|q7dz8K~b?t2P7b-KnP3}kozFIgzJzW*Ak5<{J}dtRx1 zH>)#TK#4l5Ym+G_6mDxeHhSHvzy{OwmU8b56I@q0;DqmjgPOFy5nQ@#IT_4>mnR$Yry2^L7mTf~ zPavb6C;z8PdGif$*drRb+9J5!zv`b1QoXevli%Q**lFYGM(Ev~OVrlHa!`rlzSjTE z@Wnllll4^oAI&AmC*o3&R72?&6mJqN{>YY?Ohn6i)-`Vdb5${vvbdL=<3Fw=>nG=nR?-fnI zx3&FMCaDth0*cgHQWrZ`v0kYVp#uQaW52JFTkmrJX?`&GqjN`e`PiMwX2&1v(^yyN z&bNLe)6}X3;dTP#UZu~T6um8*tvNmg^gEs59>4Es2C~m2 zOC!Zu6iNKYGUKw!`IA7$gf?UV)E~(hYueK`z4J7duV|j^`vUR{YAakx&LAJCJ&qer zolYuFW}=FwKpkAfk+;b50w<}WpIPmnMu&Ddo593*apO{4r|4PxLkgButvoC>FdGFK zKFjlK>U~b8&!`tVAcx2=P{@ha-uFa7IWOYtq0=X8f(tgY&r*-q1pos)TVtINeoV@+ zXA&{>kd|VfpXH`6*6s1M*llU9%l6`>vpq&hh=t*I_2R{z=23T6cIbmQ8F`6kY^{~)FPF>H#m`3W=*fx@~@myHA`|R9q>pR710ryG>y$aE)F)zE@RdhQ~C-DT) z>e18T|CK0M963x{T{Xq9c;hr~RP=Qib{g`fng-=}W|=MeK8&p$R; z)JQ0pODMV}ZbPo8G%Ek}EMt6uekE;=2Arnk3nC!^IDTBZRj~1=ST&GoV(dTQD8;|U zuLUv0uz8RNnmPq+Hc^w0lk$NF1@YJI)%i0Q^h7*H3XYg!Y8nOmE!SIM4I5$K0JU)# zsy>Cb@XsO%$(~H0VMEmI{VxV#W!Lm&jdKkipPOKc9V`km6EibQ-hVET$KqpHY5S=W zY$GGAm9Odsh~~t>d)Ec9AC&el9&Wn(XM1=-PA>0jP+4lfcz4GEBw5_N?MKk%#5ajq zK2=-A(k^nP^qd-@7s28l2cfSgEUF#l1Dq#rem-5h4jN}YyBO0n=|f@E&7J5oo=>kw z?QX71dtSRhIr{#>T|zeY(^s=FFKMs6J?n<+7OR1MTIVC)uwTXlD@%=dRx?JXE+*Uw zMjRR1@^*Bs3-lSg3*Rq5Kjq~66aES;&}P$0rq)k5KZcUKbmzAeK_`oZ%QQbp(|(9| zm#FQse0_sfK^^garcvYCi$XXE{znrW{OQ}(Q*1QTkFAM2Cy5h#yBOYUQi3-x3^9bD zfGIbQXeRI|KRMS^VTgA-z3y2m^BBes0jJ)i^ z3aYL7tFntcKQSzW2~?<~Eo1X_RZlfv#lEgu%v21 zq&0Z=!M6n`56m55EibF30@yy!>`zQj;$l6X{~ywi0Ac z6$P%wzODA#yjb@g>pz#4jgiiI?V>bPIh)K5X<{u0HlsFTQ?$RnWwjw)L&H_dTAEoN zv#4j5xVB1&HeyRR?ZIdKOn!Q6a3P7y<@jWofP;hM>gJ}y z!ez;+2(`l3YVuw+pnkpJMwHB4(7iU)(Vb+e;T^oHlDUnBrAqldFJxX3_=WVRuwXoG zmHjf*S+qJPaQn18*QAxWi4HR2A06jqO>y=aH;nnuYqN-Mo-AuY4H`X%%jH2zeLloY zQ_pw%x715)$T6?NeQ~ET!9J*!&eTgXPgjoytfc%pLZeS5C>6^nb2Qb?cxuSCwphL1 znf51h=d~ihK4=->(SHXh-Uni4*J~}40~+L_O`B1#QtgcBeiCm+ar_tb&{Gk70#AN_ zh&`r?WCb@HH^S3Zza3S4MY6wgZ0ZbGxFUq44VsdV4)j8hF6G=Je{maJ%zmF+tTSaX zG*s2OZeO(A|7Y{3C|Sc|e^!-YxTz>v=kzVwK2=dKB*RyU>z!q)Tg#!I9#enQ>gbf= z{8jq>9Om%2W#3P|_OjBg>w3@*Phjo()c2sm9IOFdF6*BR;&y?MMce&<#rQ%+`il() zO8jiq%iQkq<7RC^PLSU*DR8)lJuswoYqbF9ugXm(^O#Bl==nYM`W)>R3%fybRVt(C zDML<>uT?5XpLgeXN=WENO3J z&!G&xn13Bm8~M>+@91~R7Zv7KWR?2M^%zjq>?JUGRb1vQ0+@N@UtWYyPK2c!G`2VT zpqdX$Boi5!PTwrc-kLVN2(Yi9RaZ{^lwdU^waXI69dS)V3%1gm*NjtOA$N*BND@Dq z-Dn-q?uIM62PaM}nDGHX$dz*p-D!k-9SwMKiw4>AKW@cU@(yF%tONabT{Tsg#}n%3 zO%0ZVT?sCe&nrj|Iqe8Pg=dcEq(RhJ5a(yUyY-Td(5)d2j4B3$Pw2Ld(8xvPU-;d( z#a=+Zi$kSrBMKtdAJAefqX8E&dEX|mSz}l_I@31fvNMdB!`5U#io&qwxw2JD)2xD% z*@$@}b3gi?))3OorD_`jeOi)^v)Pu%DB{b!a2x0T1W4En{wco{_VSmLE;dhqLf7>& z9;61|hJo67a)n1LKb~hHpA+`W8^h@^rgO1|3$I(lcV#e(e^a_bi_cprmjXI2VE+-= zFe8x1DPGfQMK86fFT)V3Z&l0e%tx%PN@%~`q;vcY{9Us?%aYZJwK>LF>f&OAr6$)= ztLkP^Iu5J>I<`f{c?JvDx_&h`36`suh`p7Z%X80ddGJ`OqE=&;h8VSj{i^A%Wt3?&LUAM`{oieN)PeP51~I_p-4_U? zbGSF`B9SUmC>7rDmI9A4&jdO6TEH=K<4F)c^n4`+q0pKtfD@cE4z-|-uHpyYvgKI9(1Ik}9R5Dp?^0)t*_ zlDGq)RTy}nhFna4Z}iQrN*MAFhL4x-A_MilR&q=Y)6nB0f>f)0NHX}#)581OI=<>D z2eiqPeAD;FEFmIU{d=o-!9R6XEiI-y;?obJk1XBAO7ZKw!)Z~A<$4*B z2(m~;>yau;A3pQzVDmC+B^UMn#A`HdmvbJfRtL5{^b~0`>_kme|G<_m64TVfA#(n8 zwx~-|Jfb*7pr$;hK8IE9sDAhVvH+EPH@^;N8?BJ7cY{Wr_#e%o)pJ3$4Xf6dQ&$#! zPWykS*q+`8=k%XVx$@X{%T~Vg!=EcBKl_DwZ869A3-9iLgd411h3>K|9wd+-!sjyc zAgDa9FD^Qpf;67)ro#$SXf%kk(eSuA+FtAKjf{#?V$3#|AZ;IOXtA~(`S>{OR6bq4 z3`}7J1OXchpAzqX1AN5Xi{3Nbyob`j9vK_Vlpc~=r}1)k)1yBv$hU@ZzeYa;f8XB< z5E?g7(I!1D6x4T#!|)^sO@%2GdMg8J-y8_b9|#HS-q&^~k+fxj0+G^gB|EcPxU@B7 z7;?wZ)NE;o5J#n8RTSZl;;faw%-w$q`{DKP3Rho~pWEH5Ouz6G7F3kuXdEWX8j7!t zj=D-0O-5s6HOS{GRNk0YD&*_i^oB#0EsN@+Bi9dImBs3j%|)`$?_?3XgpzR^c5Ebm)%!ShDdO-U$tO5n}BdPm4}Ld?<`|IdKhtQ~a>hEU7J zmmO)gXgP3|xu(PXO|hr22S_9VtY--xHIVpgdqWs3_gzIC!=)Ebk;iwzo!&(i9@6A* zC&jLg15$i+RD;v*l2WLccJ%(VjrWE{AU?Wa-Mf7UjhPQOiGd^aI+aP90Pie|MxsOD z@O<0wG0mR#bktSQl(fd-=0z(_fkAIL4s-cB7P6wP83vJ93lDy1;F4|y#@I*x*#pbD zSxT2*5FD|E)?m5FZFvY*ikaLaZH2Fd6twsX?MW92l!Bg@kyx+}0ohJVRuh<&s%n;Z zwiI&8ea`6~c^iAGc(J59BI+Q;^lq*+Ys6K#P6xw00i4TWV?E3Ui@PvaP46?KDDM=z zW0yW|QLaSsU;jxqM%LOvbL%m}_c*NFs;KJ~vw{KnuBeE!BReho8>2th_;8>6$o&TE zOosFG@(jwH82MGkTHA{cAY zBnGS>wP4)#-Cq^vShJwfqjR%+Hf3(KE*ShQ5hwtM+9SRBnzCjO;(GW>H9E(Uhc3@b2#B&e;N4#|;4LZxeIa=BF8I;W`Kv;{PmAvjM*AMs zkWUTOBddas;a^+|&sXClSBw6+1RcX)xa}qjbUr>j5E0Ga7cbSdljy?tGN+*(hi}smJ++&lxjVCQnQ271IVB_yIy4p}I!bv4{o`S$~rg|UhQ1!<7|f|``n<#KsnQ^=Ir8d8bF{Rz=)%(2ijY4V zIO5NEq*fuA!Ax@W!L?jtq&MkAn;+M~=*Dnm!SW$0qpA1Bn~r9E5GX6P#>72l_Ew+@ zqvX`ybhwU)#5KO~y*vrG>Zm8e(hT&gT*$@Rc@$++J4V3v2XQ?%mM>(VFsBHad^mVv zCHRlSd}aC2HOTQ?IJirLN4R;X*h(e9Sw(pdi&64zjKj((2aOh3YKr(@c6y>S-T=F#BiM zDx&qGtNrJf)qa&gK@&;Mz%`x83M|ll;}EE)Ug_vUM(CdWr*`;%)X)94VdvqYexUY) z567wpo33~az3k2GDHXn#V#eOqGu2@&6XFKjk5OQna@~jd##5a|7!1IEe}Aj~J!_ct zYJeP}Zk((N@eNBzZKxu;sKcphcZ0*%&XmR?CQqfT3gCvVDVZm2koH=fj)z^(+4zAQ zc6@0*=afWavy&fpUP8J(q{6kFXzTF1kzjf$_-ESYIa8BY6tef8+jmrimvj-RcmHg| zSSVo=5s+@NX7)J-|K@N#)8SpLqWd_!k1r>^Zw>W4F7EU&jDf+V1;Kns+L??qIBFvw zbtUcpFqaEjL!%)3+`oJ~*Dn1|1h0u2ECDk{a+I)!8LR$FVhFJ|kb(+n8RYF~H2A-p zZ=ptBLM>8j}B329OLJ)Ct&VM>L}dT zAn>RY1~IBgNZP1GM1y>*%R8&?I}gTAaKjTfeMSs%WeytwdCG zL^HO#_+`Is;p2a_et39jI;$~ly1jraq}jh4zzSq&B5UWQLT8WW02kp-FV$&i>*6_h zjx;PxOR$8DA%qbPM`ve>@yi5esG0W;(SFKGmEsQzep#=_O$>=oy;t2$7jiv2!(6U? z6a3tFwjlUQ{~;0SXiV$idXMWWT%g9CLxMq zoZ@@0@a?RHe2*HjUOP|^l7W9)!4<`KA+t4C{K?dtzJ(2*?Sy(Fc;c>~2Q)fxIT(Qz z;N$j`99Y}%dYA!sZgayic5pa&Kq#Wo1^FMFsx0{*>iLcNcQ_mVYtJ`GRfp2|cZ_PG z&V+^$QAc*HE?YbmQly9~LKLr_Lo@u zo5c8Q%DESemfS@8{Buk`SMQZNC?ju^$!XM(snzq?MKhcCed8O5&nX_O?j8}{7r#^4 zJ$x6Sx%_5n_BIEm*QQ-SzaPC+a0%`H68#Uq`=5y|M2-QH;=mX#djvV24cFc#Lw9T6)UtKveK_&v^+kNvlxCB^0(PBdGd}8T9zJFZJ@-`df?LLmz*`*2-uW;(0#6DI)x$kyu%m zrjWZo_jJ~P+XU+=nG^haNjKKSo;_LMAfmvFKxcgJCZ<^K%<&T7Pn|=!y1u^LXl`~T zQ9Vp9kH2;u;!b6d78d-uwci$&c5$yZTL2#^6%8u~uQ3<7@orzXF{H{p+8u8?7wuDi znL{X6nHc=D@jP}GLfVo`I_#}sA{EiMtSN7L(Ohl%H-`)#{odUWT$*Ur zK^W|(u_T#aHD1$OAxv;nlP}<{vAd?DdU!fe0F&(HKWQAEaIup}i`j9$_Y93NSc?&s;Lls~fRgL;dq;VkMw#Cd$mtNkM*z9`P_(=K zGjoe9CwW)mcpl$I)Jkc@*BIl2LQzI>+4sAqMnM4CY%k&PY#7oh%M#+UeRVT_p;sY`zZ*kpsQ5JWWPG zYo;cWuy_7}r1pTEq>*~#ge11ITP-xRR#A>!WFzQ@(|1llH}cW$;bSr6Mc0=$+%D^C z|1v1J)5kjdnWx2w<|DJVW1JBr`QD6*cp2{~_d<{PMR*zb|f#L&zz)Ta0gnP~|^ z1TvNMn((y?r7`^?K8(yT>Wl^Sfr`PI?X{FpV zcoiENJ!B1clxmP&;NJV4zFj{-ZOe72#4JrWrLS$su&H0{wL>-(gO${r%9B=&nS4Oq zV0vMKvCW^fqri|WZ|)4QS?NniHslvM&{{`G)D{KrB{hdyuIAME3rQfqdY@#P7c(dLET0AN?%jA|O*}^Y+RK z%ISU;A*1e$?`G4Fhg|i?)Kw0MSy~PH_{tqIKmZzKl&sb?YQyKT@Op1Q2A9F`3;1?w ze*GsL9FjNGXma!0;DJ##0}H&%2ViH-901ciWFuv|wWwY+L6ZM^Xn>fGCyS?y7%|B< zWsNkth^)y@ku^C&!DLl2Cb?*>(i0bI=Hp5)g%eGCevK9XI^P{3V&|7~;+Y-R**<)6 zIRc8Ip6R?9qIYw>KzZAOJvlcwkQ~Nz-aZ687HcNfbZq971wD(%h!*rN9~`~?`(t)w z^anp%RN5)(gdd$1miSWlV;i?eksr5^$PSKCc}iw{vEu5 zy3q;hEU^_{at1$Rqs$fXUZ@WCOr_q7L|IPDnsQbs9qQx>UUiDc5=6ebWO7%gB7pH` zQ?+rcm%3${7KFe3fXNXVE)jU$d^@9v^6dWFlrYG#e%Wz*jzNnX%9gTm8o4HtPB(A8 zPAN|#7o=GpiDt|3$9Q}UeHs`#X>>`s zh5XVvL;9+GKq+EJj^yw+gw*3CEJK}StaWP?6Vv()1G_-t$~|3E!PODged9@;)L3m-{qvyjm-62M^1*3md~(JK^b+FuVs#UG$}QX(yj|m>sHW_e>xP@IBJZQB-ztw zO5;Jjvv8?a8eD(rs?0<2tuc%(SLXt1*U!+7{rVEqVwP*>Ffyzw&ki4E$~75o5`*_A z!`1gWBc}@RTSxdFo;iOx9nO{G1Ns2i+BQ--Xe3p?DvYtiU|!1{>hon$k|o`Z&e#vG zau2hDs5ad@eAzqQO5^-n{e-f4YNbXTVn@d-k!gYJX0poKQnpZlR-2jyFyBhqY*srw zfd5#_W+NN8c7kgQ%ke$cx(Ui3=|$Xk0eN5h8T@O)sjlI2a_)C2avCuCP4s^t^GXZ} zB<}Qn&cT711=hsu@#gbh2Y6!`9ctG$`)C*2s|PA9l+dWX!z`B|6x)k-8ka*;0@>|6 zenSB+m#gg}A<|@V3c)%Y)$#D)ueX@H%?NAu{8;9f5;XXEK|sskhR(o$j?snORftn7 zpQO85qZ612Q)nBXmcXSRrihcp8E>+zi+J!W+qTe3QJ|l5fL4Qd(Y-i$R5gjtoHSA$ zZp1vN(8^ZYyg%PO+m2S1+GQiv>hIZg_ZnWE%LSn`pZl1A+;4bBKhUhKXuk0DV0zZWToF*_Oe5}&tUBs4e2h6rq zXId7iM;kD8>X$&fL2S&F4U{dwvtz5~`X&4eC$oJ=x-42;4Q{38nJx18N4lF76v$so zg^zB@^CuPq$|2xT7{K|r5eryYo)2I~FP7>YXA5~OTx=~zW~HO?xN5gAY8=_IKWJly z|5Wpv-QCl*-4g!%`gPb}=EMAo zNzvrVGK-Y(_%iZRd`sULUO46F$iHE>IhlZmxvKy1L5+Wii*3N$0;e*WyF$@}W;s$! zqbVhBoF_J@4l!BAZEtSg=V*@gsOkf{KBh&lbDRQ-(TEuNr29i`szeiu{?03>;A-V^ zVu&}M`W+gSk8r~9YO5r6Ts=?#5YY|m`9uHP%q~T;1bJifBJv?ismx16{34@slseZ> zy+=8qh^Y&EwAYdJ$N*{B84h;P^7u7eBrN&5&$g9PIq`MjodIJcd-5(>q|N*wI#xgq zzxT*Db*e94?RKo($TcxR88bcL&g}mup<9;!k4&aWw}ci(=qO`GFWl{Plzq}2TbDPD z%Nh^1oy{116E=sq);~h8^_^q&jqxTaEr*X-BPhf+ElewXtm~*kMe8#*8>O1#2t0Yu z^7~YB7EFh+5o?PjQHI69kv0`X?=o|tMXo3$s5xR|hOg_0iMMv+QLUrdWi2Cdj=tN> z6P}+$NJ^1BLvrEN8$DQkek1R?HG(9r=tZo`S*HbN@ik{I-}c!; z-DjIOCdT?v1@hq#n(C2%Erjt%JmW+#KtjYhhZ#WIlFA{ z(s2nN-q-nbxf>)7%2spjUXu)!OcKFpmfjR9j7pOHXq!37ERswHf{A(xkTpVs#oJCH zQg&LIa z)+z^^EeahEI^`YRL=LRiPkfhPC6zx7VW$8h&PY-~PRLVgc-Ir2AViMrlQiJep{lYf z;oRW_$~E~LAs%$lZ~tl=x~_=fd3n8{1H`SNIO>Nxs**#4IGL_g2Hrx>Q^k9>z2(tY zr`&zv*Y(H&IQ$kHU~(^LrEQ1nT`Z9~_}n_}01)9)m!zc46^C5eJY&xgMh@57id|E0 z9OvQVj`OU0Qc_iwBbBt%v$=j<%v9#*5d-yP-CP%k?YbyLUuY>0+=N0gn*9G`fyRRF zbreD>qA6Bul6Er*;84F~W2ydSS`{*g%jdDU#0g*!PbN+PQ*1DUp$kIoI?nx#@YpsC zIQOggspdHr64fHdb#K&U9efr`-ZdM+Dt*hNxALvd2E%Yw$;0%Kj=n#(5j9(QRQNJP z8-?K8@;{Js!owbTx6-Ga`@^U`3cPd?>gB+CD{+j?{@_H#41Cs8X=H`y{%3(ilOfFI zx(FwjVGY&h-DbCx%jDeZKvB-~&!d*8yn{0L2CjFD!at4p?5F8Cbmp}^kjoH?d7$Nf zB|u<+haWjbtJ{7V9fRqUhatJ3D=$1zRb_;=k~u$!Cb(WTWEe$?+A82=kJrtdHZrEt zt26%G^+i1F<+a*stUWAkHQW}K=EH*0*uFnvuYx@=*|)uDr=#MIxg?HG9TQ%Vs>pz^$U z2nben#@*W4H0);1uoOf7uZ3s%pP2RMV=kvaB%x89)i?<+!=m<6GiP^v(4=7%x_0{z z#)?t0UUyGym9U1|M5%lqy^Z8^a64ENLIZCYoMu{{Rx(%3vz@GsQbE*Y{oYGZi9}NB zjm!ARJ8>tqjP3=b%2cM^)Z3}hxxD0~_%vMvW4Pp?k$A^cO2H1~wpkw=WD@}WEH+RR ztBp#HEal>Kvp~3ZM{6@lg}U?s=Xh@%QP!E$=!E)$aCB zwg>tLz4{=Q0J}yskAxm?kmd`*EJ0FS`cIj;GV}ic+yR+D@!DP#9tVtnQ{* zNZ&rs_I89o9mPyIl`WEscr4pIqS->+g^ak9Uiw7<*+HlqP&&h{ z`VWUskuZsFA8njBUQUT=Axi~t5a!>fYGV%r*kYccDnb1b0sx;VFjP-&+M>ODeRNgF`Ln;W4`)9jz4e-inTy z%|Y*0R$P=X?`odEx57`vjVdD=A`K}^u%_O)9o$iQK!ul8e2X}NJUNFOUedYR7is2s zWH61Po8h8jLIWyadG`QKHT;*M>rR5K2Rq&`^9($H~PFS0aPk({P zq1`g~o^m?khrmo1BMi_ku+8>^#N6BMP(o5s>q|YtS%GBZI3;f z+fp%SM06y1gD8NXlBr!R#>h3XO%4Y<+LP+xcdQWdIFBdU8|#}bpAM4(|LHVhFOthN z((HedcI@9=48zTeHhMh&+Cn}wv)8m_L3+iHyN(73QbBRl0*62G!hLMB(M8GU%9uL&MlcJ)1z#ebMqSJ=$Rm+(+Y1hm+q>fJ#`8A`AGBqQ~arT`vz} zoz9NwXY6Nw6Jf_h9R4shB)$h|Kf@RmG1*8nDhxAYKznpkZuX&$ z7UghQhu(37*_yuM159x*e3`^+w#5VW!||+Hroe=#0qQ!pHTr1?#~uP2OH!YYBFQG{ z4U-o*WLM1eP-2m8g1_AF7|@QVpe#&!|D$j99sem+$-a6E8g`?QkMB7BseL}k$JW0) zX09#ZdtW}2&sF#wPG0A(fWxSEm+*O5M_CnOdi-?dBys-}>%*5SDiSwwd_9Z*KMT-O zgom&=R`!ekD(#+hwm`cAp=mjo+#8H1)An9Xxt&qYPomXvHtMU+e~utC#c9L8V75M} zes^_7G>6T6y`{v==)lRmdkW}ZA-7eC%2iUxJDgOjow6hy8eEelHKJE z?P{hnBtnmUoMDADoz;VUYkS2$eo-aSu6;u@-gCUH4aMOj|yoP$~c!*-oei!+TC&& ziG>o3xy;#ysY~_a^s~$(3lx}xB!>`x;5^w5?}Dx}YQjS|BMz_iwA<$&PMl7UsZr2B zWFn#18z)!za?=OaTLBwbhIct*)fz^Rdp{;0YDJOq8OsEM$K`^OTAFsrWG1n#t!+1VlNqU2MCRPF${Us8N6xT8zi!IE_~v> zaUB_&Y`C`2o_u2rODv|@?$r0K=gztLMAwL9!c&qFR_E1FrdL6d$zl%&uSShoWy)JnRfR= z*LLDn7!w`dsnM!34b-Zvl}K}H3RiMR{>-+4*Ci|zYmo6#gKOk4$-bvM{9K>kDJTxa zo1{zNdQO1Yz^-xcX0EmRV>^b)KH|*p22;xeXqowIRA%k@f!tdhwYy+>Dy=dcTcD{~1`JvN=U$=E5u#8a+H9bA{0hHtD z?93hH!1Jrh`Q+h^A$SdXIU-od39LezirzZ+Vcj69^;m?DpX=tMx1&c4)3Ifs4z98O z2%2tiMrLy*zptad7r|T)edeP%slqz61=4-P_+Qt*zjt_2!rs-IKh8{O+O*6|X;Dph z+-JWLnVG3uF0d<^1GH}`>bI2yHm%P(l`74yHCM&VQYBEk;~~f(oCn8Z87JUFxk9?N zBv^@`JCK!kwI=I5*!^qYNs>LfB>+xVJB`GT^m54LTIsU%+r*tkr7?hXsi>}*2qk~< zA8|Uofc1Xtc;{D#T@1*k#g8I8!*;JZ;kg^es%N>-qgr@yQ$AeJ?6fuM`R$@QrZ>+b>a+eV-aN;f!H= zv-oyo7eXq&-ya#(;Oe3arObEoo&HF2ne`@NWYv|EH(Z|&aOnvo@Q8^%zR=EX^WrHo zPHOI!0uToQ(6R~1iKVFK=E|+g9m?n`sVHtFEhgh=aT$KJ6kRtg@WSRadgAJv;j_-0 zgq5)pj4$cP!D~fv)Y{R7G>bkx_<#m|5j(PWE_BoqmcDt|owVpBTj!C)!;aNVF$|x2 z|MFi#z!R0D6RGzkoF;|`!Ggy{akX>*nR#ghz!wgMzy2x;eRtcFV!hN2P2L?iuciD@ z-4Z+Q;F`89Embfh{B&hVbb}x0fyBZQ>XA*V-L%I<_YgMnRj$|;|Mb~DTZfnJdRh|i&TpVs;&NuRcq)nu>z>Y39Y&( zV`N4TGA2>q-f=b<%k8e9Z#_oSiatp3)^DNq&bVN$iYlb9P@^--0yL-G71XJaYZgcGDl|GJ zl=A4qrL+IQ=(RQa&Kg=Q_*_zg+48-F8!gltRj%&;6rT?YX|Sek1=BREm+94&Y%ksk)Fv06;yrnd>4|u+H{((NY(ot4Lxnw`IBCK&7-I0bI z(SF zL-7Bhe&>sSbTBT9+jOc+cR&Uq*V()PEKj`hq{UKZY6PIUxR!)JT$9jVp{$d-Dz@Qf;WC-l9%%P zJuqVcJz9og%`|Bz&1}hi@KLY7z&>A`I$T8oR6WY$UwiGYJG`sB74OxE59rqb^@=I+ z+(E~kh$H*i(v72KN1FiYZu(Eg{u?)l{V9rsS;-#hmUc}IJWBXl<|0qC$J5EHU}{Q; z4$i&X(!Qd-tuvj_nSM-&Y_E>$=O7wtf2dt?NP2OLP ze81@q$$*2omkMz^^7yrryeP%#q7U2(U9_ zp*9pKax|?SXXLK@n>np+{i1!6FC2%`JInus+J2y}yJB{Mou{28&L>TWR|M!1(%qYIbgXutReB~BcL;qK5#8GO==;5lKE9(_`1 z8^xEU*XbHP_56KlMWFkj5+RnXKv?@vMsIB3jVeF6Qu_i#mFrk_BcA(+K5pDWltqJF zf*)9Ds}DaS+LS`YCh4}vJn9*=F=zu9LM-^=llNO>JMZy)>J?K%C{$kr$v34r0UAd6 z7Mb2;OanSBk1lMm(SF#~lJ5e_I zLAK4x6yeJa*Owk0ygd~vr2SMA7JX`bQmv&G0^^w~8D-|J8W{*p`0+hOmS?W>$h2Cx z&^)g*R~pZ#7Q9+f1I!AA*ig|=@}kawtEKWkSF4JIS+=+S-kjk7qv4VU4jL7_dsy>Wm(+a76Jq~^M2=?UsP>T><+WfJ>7R--EA!1 zv%aJZ%EtepKuK0xvljH<@;!`|oXIMh`lID&eq9}S%S+byS=>K3D}x|1qj1PRm2b0Y zrDJvvFgQCGaA%g?>oT^D*d{z{oY8YKv;fr3<~R|-(;9D?qq>U!*)t$f(EI9h_%}%> z5Zy+7+nB!Ztp{qluL9rjpZxkL^iB(r-e*OUsP#!%$(0$#R zDdT^e#DEFhDJSsW+Y)|%u^MyREQt*N%gZLz7O#!kxtE0`*#1O9XOEd-xFur@=H6g0dGY!$yy2z&x=gVJ!A)p?6MOpy+zJ@D=j|~$qd8rZvO|5qxi7t z!(!^fil*H^?p%xGAdab6b|W2iJ>{wZ3r#mWyDJ=gSmB&|7<69p} z{}HafS|jM#7PgYF#jgb9yM1)f3brFb@4xqwiTV*!?XCuwVsL<~s&EALx zAPbKL0GED!{q`;Sz9i)G-7AP9_uEhED?1Dz8JJme$e1~tD(i3E_|~Oj^PXv|l4)nv z%o^c81KIix3^0~JD_*R_)pRQ0mIIZ2IVU()!DLK~jK3$>;_pj4*v@Ygd{Sy;xOe0C z4yB|0k5>aNnL=e!E${wP*3x8+=1j`mUev>tIeb4SN+8osI7Z2?^IT-@35X01BUF+67J>yaKJ%p$Jac>AM^uh~BY2)ui4JzF|| zwr>+>I<&z778>_%1IuYq@p&uvF0jW@E2g&4mV||&E9&jm%*@Q`smCyfiI9YG-YD^I zPbs;!F#B3ZBiqMB0n&0l9%Ti(mgzbQAiF=;N3UKqv3L3C-&@UZW6YA;lceB#w+BE% z$9%nfxn4OgwFVgDHw8F5>|=kjnhgMu+@#E_TX>ub zg6-$t(!)u&{i@Z7qs@$(*Qk$D91BJzYkI*F;)B;0E^(_EV0`vm>J514J!WKR%Q2er zC`EM8x2-7ESNdOUlapwql}g|iDT$b5jUeZ%s+vz0N{fQe63hC`(sDMnbw0IN3KY}z z(Q`I5r-vPnXRTK6?6?aT_u%dnt{d8%WJ!D}t?IUZ3ZHJ}pJ0?-9(?$7q*6n<~Qf(X>C_2^cOwxbGBl-vUD|K2134v%^ z3dj;n`Q$*A32lAb;&Zd9?UE3I+$^rnBx;7-@n?F2R%?$zzJ2|gxdWh|1Hkb|T4?Ps zaiC5q@HG(;ZCM!PLW^7Rj>q?3(T7*4?VaxZMM}7=-f@ICijnFo!ii9D*I#talxoM{ z9`~Vmk9SPANwY1itf*XMO!&V}MCiy0eK6K1Z?DU->x?@G*M7@_ovvs>Z{#K<8Nn}z z4?cs96J&KBK}c9cTbTXZh|APMhO(wK4{{GNrIWdBUR1bBw@WC zLy>*;Z-&?o3Tc0?;}Rb)FUHU?a6z2t;OL$Ae_aj4X@M$)4dTcz2&+kAg|@AA9FRTx zO4NX$i)CDZ8&m0%l7+GdE%UF8kA-EyGD7}&X+;WxvA`rVgl*;aM!O2e8+x|pt|zP0 zPq6I2hiv|%H}W-&Vmdq^CKjCuFeB(?0$K^i=J#k6wLRxRpg$_FC(Px&>ncFo-5^nd zRk4K*=IXMbz2LjTz#l?^C znCSDkZ&#)!WI+?P`on0l;>v_cI?N9Z#f`_yWdI6m?1f&&%2)}7dup1wM*DyMNYKBWik4N1P_tW=dkE(ftLn&So%lizn9ov3UP)ydFIoB%$VHp{vI-z(e5a=}{pYM=89wLW3g@rp6mOZp7QU6j! z)VvnzUQ6|fJn%^d2$CWQ@7?B_FQlrTQL0%d|EVLSM=|G`pI!x~x0s@~ze7OPIiYtS zynq9#Q+}?V6$dM!SlU6YaJS1Jd4s+`9tQb=*EccWpZQPZ-nMn|z}o{YAgfJQ^@#TW z(;n&nr#*eCzm1h?oRh|+XZP4jW*N+7LS6z!jG*0j-M{O~Oc=$lZ%_oj5(?J|pDl5o zgx4CNP&slYf~nR$4C}c)6zGxKrxsa1S&J%VFxwMPPTTxR+d;Y2!?u=sKyq9ZV{+%0 z`ATjo&NM`qTNR^MXCzn$uIQY`fk+vzoBHia%N=4!ak zbGtg4dZ(sXag@XZQ5J^Esl(M&-Fw&`b1h4wC#jPCB2o8avmnznN<5( zScp`N_%FitII@7UT}8ErU&CDnp%bL&W=iUQ0gJ)IM1FPxjkWEeR-|LcDA5337?i|x zTly>Md4!XE*JG~Z=?0e7-;a%6B``-}hK*MYtXNAbNPx+pM5ldFRfn@iEYC?Ig+mda zTLsbT7mQFan9L!RUvNM)@GyUGVFhs}<;`wOyXo*vLBE5-+&66FaN>#A;a$PgNDY(8 z)#26CxH4{Jy)&~Ip&>YT^GPw3cLVY{yX9TA4Rgx<1sg;Iw~vC=!GNdo*qL1kkzdHT z=YRL1*tfo%rv9#pD1kK!^ezb2B*U9+Y}GzhXjTxTve{~w^XKGDVWR5c~W4C z3GCQW8z6r3c+9kgEZUCl`^(fo*m0k#;vn3tfuh!N*PW9aQ+q z3^}^TMz&&}Oun%pWg+EU9gERu8vXS1)y4%W=OnRc`zW=PN>(iMBm~yh-}9Rk9$jB` zI;`0(?)@;732ZOdI!{EPy?vKL>=VF}<`E1(m%+o3y4GRkG|d(;5k*Dm?s-f1TgLF? zd^vU7S^&~j&0c-LM%wMkvJq=NBn#DhAT8E6)cA69rp?X9Xk4L{X^LA|D*HTdc5i{h?-?Am1Uz5iuDKS5A^OMU zUKT?39&`YYpf-UeKXR(MWZKfUi7ye%B=_3@lbAGSAuD*-56xcDz|MU+Vfc}i303n` z!&_a(>ijv_Nrz{cFPb>eU%U^T^jO}ITlbBB6VCo$ZA9WlQ`kK>%H{jdQq~mxmz^Yi zc9`Oa=qQ)`t>=$+VO|(Dp4(mlFxwCS3X(X$q=tO|3-a3Xf`m*aP(sAR4rw5DJ61s< zrYgwu=Q0NhVXcc_-*TdgV{DL? zu^*hCQy|(?{C(dfKD-5VJUnRj+^?j6s;{Z6tTb|}3R=nJw{3_u8IR|S z`cf;!KBgX+ZqpajiC0#zWSd0N#@ua@*NCTSa+VsUkCcf=TgDubg}CLW<-KV0r}`=r zuaxjN4^rM@I8W1WGuwgI)WCG^KjbH0a;}G-oS5(CPrTSW6wO_WT@IAl*qM)04drR( zOEsD3!bW`HEeFFmwdg6UQ5^J|e^NE`JMh;{oDS|UCMk)CX^@kD!bD1wj@pxu;Kq0u z-*`|M_*+?6)ZLCgcuqlG>Z;s5#&Ty3I2HlqnVN2*nik&mU zTW&tZlZ?K$nccmL!!U=pwvyc}g?+z1je7Lwg0%@6f~k&9xqjw^1%{H>aarM9_wVL! zRlDTEdDG>4|Hc)vBHm)!g<(&vao5(!32n&O4!3KSh>ri0NzZpKAAZAefy8${-tN~z z#&LpLLPi~I*1=UoPv}D1#F%-5UPV&-M`-WhqR_||Jp1fw#k#JQ z-(L$-zHP9(!ptuq5bsL0O_O#oYE~QIAOe*f;gOg%{D$`9R@~wKpyV#6AeWK z*gAOr2$|@^)=K2JQ`Yxr+H7Q_66(OMDjS3i-oKraY;guPr*Ch6+jxB~_J3(`QO*|{ z*iy(250{2hZ{tDwRKxNCv!)!7q<f^ty62*1+K+kAIm>*!EB<}dX+eDb zR{K)V5u)&j2qHIH@H3L>*G`dB&UBccCMQeT7bV5_*}Wm&I`f8TlO(N2{D0Ee#f(x= zWwUO7>Dnw4%3Qkk;~$W=f}fBGy=XnqD4liU*p0N(7{E;TA~W3@YFgO`-6dmbx#Lfy zoBD;yHYJaFd}&Z)w}-PI?xibP-Ctv`#WszlXVx!@e$_}ql#3qPl={BUIccuE=p^`~ zP56*bJmRF^ek|%it+^<5crd2vR&PFkC5sle!#0BLJKeSR;QcL#`oX&Ijev?vo=|@rr~R!*V&{4M)b#Tp&E@G2)JC21)NsDatqvs>D${uMm5SsiiOrio z!FEZUL7FknB$AcjT=6?bf|Ukg)w6@@ijGhFc7A3?6;j~r=>}g!2H?NF-0gs=M4+nf z_35aDbgd*z#&Dx_~<@rGj z30RRwYfFA$Vle%o(5ArZdzKfVHNNPrJAry#(38y*ROzQ31U;Y+U6;Tg+_w3ly-!DY z+tFc9e0k6=DR8Qvb zqUaL4kkI6|l`wET#3dwX?w=BQFMgF*K($)!LD9A={+~G|0>xMb@|#4@cFE(?wFPLd zrVWJFZ>8TWl6E!jvM+ebu3?ycex`y~LdIonBS=`Y-`tQsE>(Sf3QCw($~Dbj@GK@9 zu0I3L@)D}fy*+h)`Ug_>g_<@Ao>eND^)Qe-5p<6$zO);U1Jcv|u#!Hu1)PFi}R<9g8fZj9(PMh#FoN2vH+(-lBOg)!a*Rrb03546 z=&^fQP<*ezL$8uw*bS2lS<^SM9=K=rqYiI`%B$N&BnfgLK9j}7Wd$FS#SA2y{Km+- zlLT(WMXN+Fu={jRr+cuw-DNcGUkRx1d%j7;{H^UdE22GbwwYbO*cx(^h_OetR6o!0 zUT>!C-sWEe(V!Q>DnfE{OGwKI=q*qDKRG+fLK#v%g_1t&$*iwde8(??A~}A|P6(R`mZ3TG{# zxMaMEWg=ofG}_W(k4=*=HjL5`@LViw647sUELE*LJUX2D1LMiO{R_Bt!vlQHLPWT%-QC%pXRO`Mj z_l7VafpDv*p12qT##(IZ(l`I5k){x+nY{&C#@W3t&Bo5hLh-FX&kf_sa~5%(Dup$) zSdqXK%ipT0xa8;D1HPspM#sh&ycOy>K}Z*>z~)q|aL^BTm7*oj`3^RzbB5;)iBHW$$kXK}-AO3D zTI&r^NvMTB%m8U-4R3+P>}I)akcbyv-gC`0r?2Lwpq{sb?#WZ*w?S!UJF*o+uK>JN zElo|$y2?ruK=N3>z&YtMJj*LAcj=%{la?sSMnpT0mwA`vm^9-m7!j_Wd{q_N#QmafLsOtEaPA=W)Xc*oK--#mS&PBFrJSM{v=7{Wl>L`hvMwiKDjb0h+ z@0*Bv18QO`Gs&OM5DUXUKz|t7Hb)Pfsa4KJuTc)3g#s-rcneHJw5RTlDi-_0E1j+iQxlCfUPB`8Qu zuw^3W{8<#){5kG)N@b||%bt)&FBbQfU#aBXRS&Ff`LHnMu3qB_57|nBM?t=wwRW3z zXOoo3lJ%!=t{+cAxHTatgL`vsq@ELgj=IX}hi|s>9Y>tq%#wQ`bIclX^|Y z`Z2Ek;wsKJNtqX#wfT65qPr)9g@YA>1P5v}ax$2VWWJrTh@eL6kQ zUmpqeU$uo_LY?;K+09ves68jNI++I5kT&4#FIhRvBNV%mA-V;P z^WJ`F)u%UE+|zn$pBJ&u`#{|#XY%7dW8B=}EbpSp3i!i}*C|$1I_=ebK(q7&&BqsU z4J{&c@?b-v6fTZPwz`=Pr*;#WK&H#bg7JTfBsCoOv#+NS`&-p;y&~rAIaFuU2*f|F z6h-IwQPsbIE~t$?n8~@4MhVdDowTxZ1i54k#^7}e+Jd$i5&}QDo>x7;#f^vtrH_q` z5w6xcbf#rIT^5S8q=PTA%34~|Qf7D>97c#2q8nB$@+06LIO~*nz2|f8>fYXPV6Tgn_SnZ!i!a$}Xxm|%SRsah)=n{#sd$>qVe6t%~CKP2_z`7wW0ki*5mZYO+vP?AThh%-ShQ7=Ehzz4jcZRd%1 z&P?-LG+`!B1AD7tP}l?lo7bcp4g*7{KcqKdZY#lmJ$wBYI_+r^>3;F?H_6cD6Kr9~ z-5`Ak$N9tC`@j`$Ywmb0Cz>OF(a#dreUh^_RNWu+An>WE=jZm|1(Lc$MRs|G1+lM~ z`_Z`f8Aib=b_eSXatvVEy)r|RfHH~z!pF0v-OL`f-H9q+XdRn}hX>G@37p2sp9EiO z7e}E$Y<2>z_>>7`joPxrQi{vt4Q!fJ70)LCd(mg}(^T;Akq;GxDIdNni(TyZ+sA34z&lyt?xKh)s5e9i)MV=IJahlmJ!v*QzFq+5r+YAd#xk*v z6%|pr6~C_ai0j9RzFycCNpuqH`+Hox0bk$@D2Mc)sn#(Jka+~DJ8di3j$bI?9|c+U z7sumuJ;M09ArR1Zhz|XdnBC@%Z&6sAaEjmL4v}X|`E+FThfy=ni|9{|%ReAa zqX@a3lCsWTUf4DfLYF$Z9FD8%wXuh{!>k2K$tEpiHzB>S>jv2xpQ5>IgF&46k%iU# z6rT=<*gOe{xLjr<492Lm8+lG|oBYre+i^C<+RI&!rIM;nl;e5;!dr)dwpF6B>qw_W z?ei(>#fE-A2qOKi9p0P3S;IzTZJ#q;VOP^2CO?woFynh;fAUw)G}tlV{og*l6BbVl zcBOZ#V$OLVjG6T?L-Wx2}N*>b4 zoD0A&FX#s4FSO$D3LT6SHYx)%`f3dep!`4pH}h1jCO}S)>Plcc)LoD3OAXgRi|w_! zsBbcq#E*M&o*pYB89e3w_|XjRe*x69CQOC=|bTz z=mBdjC+Sg$BM57PhCD0H$1aHUu|-c-WwZJK=}@1I2@wN`e#AjsW0 zv%M*IgF$iv4>s@og2=N(!?Xm0?dDFNgPX#55^XKJ4^}EfJJT4qNI!2#e$eiI$Jc7f zI_=Gkoogs%zHVstD!Hg4k|9IxQdfEVrZ)3Z*{hxZe6T)`W{e`&%Oxr##ja}lH_=x?)ivA+HOvoNh((jy7vyre-brY|+ti5Jn_HW4w9$uJ&MSjF7= z=rKx(mv_!?jLtcFbWeP1l;pAm?^9V6GIS?&ms#}j$+`8|&4h7QN^9(kp9)hNukb@a zNTLeGn|R+r=KoxJv_?&Nxr?UUcl?&@q!b!*vLw;LK44G8a{F~}`(ad^eqGx?t)^ZY zD)`oO(Y_{<-Y7L#MN_MYwkv^NPSg6UEmiPa(Ur8FSFlvNY^CpPjX}t_?-GMrNar;T zAD`b`r(ZBFU)mj+C9!MzRt@*mJKWbVwYy^e(uxNe-B`mdnv0(7cH$hO;Ty>ndfIY4 zAhjcZtiZ~pXBILBX0Ur777u%P6o(@nbeO|(IH7($Cw{0mz!@K&nEdPR@x-^;%y*G? zjU>bG>Tjw#B*08Y)xPdAOoG?`9mh%ID>1>|cc%IVKE%@GNb!x4t{5TP6ZzKWX6Hl0 zgqua)(~w{HPV-a#v%#7+5x~LL@_3BRpw`}l^dM#%jG@$nB`f1$=*eQHJV%4gTvG0&JjPToQC^Uf<_qvu2dYRNwTQ0)?i*zG$&&2*9smKA>MIvQ9~tcCg}p-jlyL zVV$>+cu%zDHy(Eo6kyfwGP1+NSr-%1Jc6Ex*v^i-)s-yRB$5+HqqRmgLW*{dDy02W zcp#D(?%T`i!t8 zu$%A1uxa8k2zJ4&1u~qv3E}a3pU>ygtUe(0Msep~A-vRnte21-sI8tkU@aitn(>W3 zLQc(TljY@fnD>NJf& z`qxs}Ddh0~4 z{Z7WQBY##s!)+*1P8PEyUwnI;F;~sC0>w8aICpIr(eC) zp1)$5(u1ig@cjzz_Lnhivl2qy3he3Z32W$dm+ava7H!Ct^w0aBlR4L2ubdoj53*i3 zY9{=~UzpHNlOzC3P3hm6#0S4u;}W*nEn@oF!f4%0$HWUe%1dBG@Q~?JSk9It?C>uCZ&}j0xbgh@y)+T z<1E)C#tiqV{iWSmiy!$~vPtDN77xk6(8dG73WnSh+T7NLY?{LI5xhS| z3>9sD$il2M))2DZan#^J(fTi%wPN4ju@~c+WY}lW`PFo}dCx zKL(;0rDh=LsplP&+eqCk_iU(PG+P6!JSIfHz(1{ramXAo$Mkug?>O0CcoE02R@tG{ zrGhxf-{-lnsAxMH?gl7^JoohlZSLo>MLlI={n^jwczbhk3Skq#H|E07g;^?UI3In~ z4pD{yVLtOE=mKhYqKDp;7{p_1etyAhx`_`M^-el5h0MWzIy>aO&c)S!8aw`O7#M7^ zEJouUeOEsc_iH&fepPS_23qj^%MfD6{3m>()7-X6+*KlneOV3|^*kH(`Kk z=A7a~@I2`?0&w_URGgVJEN5|J{X*-qFS0*0gQzGbpFRXnG5(F(fLp`x8EE)#rf$$C zj6|7u51fwNz^^E3awb&eeVT`pM3)AwPFOnm&|M_Tr4q56?Ooasp7<4c!_}B2OLgsK zFIw7L?X0)RteKju;0%MYocDZ$JTFeF*%V_>{*VT55xhT@`MmM7K>J}^)Fl)>xBAx( z`GY*1S3&FyW}ERapoG7C0r=dEqZ_V3{ghme1u5o8VI*0l-*!wbH`=y7p?VpTUu>~&(tcO*Ygx_(bK5x&X= ziC7sD6`-}b6I_$UoHmKrr5)rl=@xSxPTdoF(z1MSlRSLuL+8lNXl9rio(`rOF|}Jx zFsWd&X&ziPJSCCU1NGvGb)^=!4q)(StUlx@88jHd6++S?JA0S?`{Yz+E4hvp`+c-s zhZ}ahcd_BKBvk4}aEI7O$5wZX!gd=22Rb$IdQvqXYxL#f0EZL^iX5GY11;b%sxU9OjYG}OgL1g_Sqpqn>N$%2K0|we7x3> zjEjpavk#@jo7ad$hG51{Ta_2feS@s!rG4b5o%p?oNvMOLh=jlc**m{Cgwv!t%G)>j zhC`7s0z!gw3F{?UYZaPX8d=_Gc8v3uzlNApw<7bxI7=B*0m+4&KQ^JeVfWCmdy=cJ zK;o>RSO>peNr49oq^H*peW#*u`oT&%kSd$kd5=lB@{lNB2Kv)cEz(Au-%!sF-_|Af z@*PZAH@v|F*3T`Q9k%f)K>BRdtlwFADa_5qH9J4=3z~V=G|>lS%&1@yKdIzwkUgaACGD3EBr6(qZ$woB^+KhY^i$(-w>k2TjpuhAQ(^(`vZ1ydFcXA(-I$wV_7!|Sud$NVL zK{-^^pSIftD+IF29e+ScnC>`=@i;kVDqH{TPFep+EhyDGs6e!QVYQvdRBys+d;VN#OCpIVj|w^eh$*scb)T{6YRvvugKUZumaEkZ>$l7C zCx7r&U0Yj384 z8y`g+XL?4rb!U*kY15{A5Jy9RpQtKjhQjUq2ApVD7fU?5mY4NS8piNGQHw+5cFo8%2qrbKYgu&4)`yzMKa*Ea_J0%+EF zX$AMQ(*Yd#Mhx+FpSCa4X}7a_hF`l8lKWP$3K^DZ5+RdM;RfFp>lUbF9t)%nb3;T6 zRyUmFNSOo$xt^!^f>!mn4!znMMA<+U2Tv<>%g5?b4uP|2!07wABG6pXqdV&qa$_KZ z=WQ~X{K&395Bs?lL4Sq5AQwE~PKoTwBi$r>;z6s9B9BFqGhBGF2ElE8ZwxSRsS3AZ z%ZHI9aS!px%dQ_O^6H>w`luLUe$PIw_7#UF#@Q9yx9fkqo>64o=-A|tR3CEAJ%utX z<3LV;I8S@X#vjgiUz<(E2DZ?;PUPi+jp=p#lhtJpA#X^o5IdJkNK)Aulc(T-n`&QvZ&y6&1MnMlZ5u|XIvP9-<q~K#2eF3j;7U8fjQa1anzba!~a{KURxzRIoH7CAzAsRdF z=kdJ5gYJQh4XGZy^u_WHb-w`r1w~wSk^gjfkYV^$K%M9Ji68GcfIA81l6CUwjt$4F9+La^l5^>E1UEVYImNaqiliMU5u2^QMtKp8NMs}Zclke|4 zr;njc9tU(1Voy$(+L+0emA*gfIL8jB$35sC&r@~lPw?xQ{e{OciY`IPw9EDmAEMgSXza?=M<-J(o?0m#r8+E#h5EuuV0Uy8^5!wAJ; z9IdQkF1pi{w_>)ed#H1T(4;%H41b86O@qPERwBn`;@g+bu;05wt-^Env(YX8!!hKJ zli`;C8ZQ3eDPQ1+o7m2E_ZfiMlCD|(dS>Y{8`TSEJIPv2<6A0d&Zf!K0jcz`J&X@A z>=FP5p*;LXb&BS96<>DIJrg7{0(Nn;%MQEjVU+l)-xnco_!H<8M zcCe<{-?uk!u(01Wj=_H}&%-cfqs?)EDl$*Bm4OgJ8e^xH#Cd0|xcjJF>a#(L%P6?_ zsJ3SxpzQ=}h$Abwmk*48<;V9j515zdJQ{DOzNJ5Mv@0Lj)`lfGo>Ds(FB!0zOt7SlVJMd=WcBJ9EaBn&Q#7=pR6K;2 zVRW6uq+DVhKKU%df04|$7O4rg{qvzTvh!254+J*>8Cej^2^-EMm9cUwEC&9xqV%{FifQOOLr zpR1-&Nm+cA>?;|(kHB%<>(d|pmJ`dR3~ak*n97(6d@|n@Gg#m`t~8wfrVvdy99Z4e zUNYEfcnl1A7)omxypLoull5zwcR>e(H*equX$DC}oXN99CWp@4y4|}KuaBVyD@64U zyHjC5z=h4I&-pe2fi}4*@jupG!fUc9YnKe7xbDef+z$T4=6LpoI6;M{^h!I*oq~5e zxa`u(hGRv~ylxsKYTUz#T zO8%C=DT($|PlZ#k+weDVrMu8;q^|ULvf+jiO%`Ye_{;xi0kr&8jb(4wXDFi-g7_2Lq@0`o#Pn$I{L!b+%u}oi;pZu{FK$@ixx68#`a;?-7e~r z@J)%-xs7s8lPuAk7!rb>ldK3$hoQ>SEkAWT6^1GMbdL6$LprA{*M7eSN{9YJa$b1n zIJ>`fUZQnNoy;c9{kwR>H9ejk$(G5(ZGj)Ccc!`%bXicrHKxO(iC1395@mLwOd=84 zepj|_{>cpSX|W@D*Mrg&V41Os|9eIa=!a%4CE8|p34n&*mOkthH)&t zPa6D4Mm7w_6%=UL?<>SW_RBJiai{XG9q#Xg{=+oT)?YY6zr6k%)^3s5CFgKHPAz;0 zK$IU0o$P`;tD)+8t4DV_8jnUZsvOvMJzeV6QxoLo_5g!=UyuOH|KM?VpnIEEW%9fj zBkmSay-maBwV-;&%GE}>Yc4Qgu7S@QM$3VkZnX(mNrvBM6)^5ODhfQ|o7(!V8n-)DE$c!8)^z*H*y_&}9%HVr%2g0&2fQ$#F=OiDk&8&3cD?`@f4 z@S(iMe^ts6Hya)=r1u#Jm*WU7Q?m~&@DsM`SLjXMW`MNG10q@#(rb`yDY$nZk8_g43CN=|A_IgsWi~+5EjR1pa`O_`@$jV0z{fS$3}qX5#ZHiowT_b3$6h z?Z5%G6LlSH>FMcb3NL(lMz)geg9>f%o))iKtJK?RBmcO3&jBzxVf1{5@^nH208>{? z<~p7B&*ZEKexZ zB&nK-7Rs9khl9$a=wSKcdV;EOLJEeZ#16{8E({cCQQ& zX$Zebkl^M!-eR=CC<1T79GeMwO6tqeM3gXewoxa4cwk7P3hmL{usreHJS=GIEpWR0=1B`uQ^w7|<|`uG4n5HS^3XcW|J4zCLg&9w zSyCsKoPPMD35f*FQzz`PQRy&y6;Hgg9gr9PqPJ(nK4Sl^ognBZn(kq* zsfV3*vH>2yeTtYi3Z`96(?^4}dD^^bme9sIciLq=jHwAeksl1~cx%-SxrB{8av8wZ zE801yqV6wjhwtmF`@wQG4Cr_4#P0J95GiNRp&8e*dV(ZEo>DxTKaO;v%EWA2a5ZU; z?;SI0*qFMdpw_#{ZWFo)79p#&f+^GNT_%EQQc<0SDY{w42$ps&KO0tYzk_aYCTf=6 zVVh%>$P#qfpb8N2oPI6G!%gR8d*?$9Yp|PRSd)ouWRL)Cc+CHW;n0xNB2It$UAek2 zW#F#rQgIV-RL;-a{^Q2_`#H4(Bo+5zDUX5SU@AW&f-m!OUaIiMwYlF2SL?sg0CZIQ zUc^<4{78IN=^h*5Jvn@y8gp;}(x~MI*^pQ(oW&A`(gPd53wayhWF-a^Bt-Q4j7J|> z88p_F+fD5+Rt0e1^<&nRy4&KuygaYEOb~SjmGaG0*gL)3eMv$v8f5${xNy`%bJ~Qb zvq|*XETTm1Dt-g5{JqIbLq7H9Xep?KOCK1JVJ-JLGegMAOE^G?^uxY<0B#r$Lf zg1O#fo%cSWR+IPOwBW!80F$L%|A_|;G81*|Gd~lCee2{^3Jl_^-r#!;ce7b^5b%tr z?+PJY_5DsAUN?w|Kw23=5Ubt_2aIgUIeOiv_6rhx_gJIuYZSLya{D!t0c4{+pNN|2 zN!!>Z8yC_tQPEuJ=!ny6d4cxT%XU3b?%wL(UxCCIBGC)XLeJyBI*M@mD`^S>_7Cm^ zkD;J~uBO25ycAz%*wmNg$ldsq{`;zz=fe<4G%M2TJ@nETXBFdPS-?Cg1=heb;7)p$ zK0-IXkS6^zSxzX|#aI@XtD1NicIJAA$=QXK24?j4Bp9Q;y;}BD40@M{xo$k9XucE+hT{S z`WsJ%1+dYEp|(z^EJF<=SOe>~3X;?D|M7NMOXD@wDS4=TcFV^buP=%`tkCwZS8z@i~fb)sXtzheEqP3n6Sf%&rKj+?3<(js}W zDou?A{(|sL8ygmkMC}cJr??_j*lH8%5cJPQl2OuIdxUd7okibRi!r6rXtPtT|Ll*D zgl33?re;sCCSsGOCX{2pZj74Vz(1>Wb?rO;JG*tN>V|8QE)+ZaYG)BXv=i#XgCG6X zX|9Qk1du|MA4;A7ZYb08Ro^S#6w{<%O2e|_?K zuR(pvs_Aq=0)X?%ETv~M0iBJ3q~GFMB{Gc1RQ zRD-en4LHV9{u7-=2B0fH(rFxF-7z9pejqLnR)#DlHR@9>-!~7r`Wgv!j>083TBAQM zC*vr?a5bKz_4EKKwDwJYD6Oov~_s%OsS-A2>=Yn=cYzY{L!vg`DhCX3k+W!VxUCc6Zb ztPr2);e$`@jOjS@+olM6e_Nlq>N?xlKa=2R_vUzrsBtV!Z__2O^MbqITe;YgyzMzk zqxQ*?@Aps^{Z@{jc8@uohxHHm?PU{Im7HSj$t*~LkThozLch+;LcQ$}^jLGh4z^#h> zhxmr@$eH9I)XAB2ZKk>8t@WLgY}HLR_igHD5=a@U;;fR(FV-l*f!PdTRxx}`10ic+ zDSrGWervev3x?)!M_|ZsV$_FC%ZLw#a(>I@79&LYex~W+B*I2Q&LXzKYz{wbYvT`l z*}vo&&9sm>9SnEzxV(VvGX1}?JOo-s0uP<_YYyNpx6}VbvAu;bef9i}yKeR~3_#X& zNX3OZB!#ZOKysnFPSkU-01C+NcHzXuW+H}Q@8yAH04Az0ohVOKFk_qozzvgun<_oM zG?d*KSPpb~&I27ThN((LEMt{VE8zmA*axL?X&Nc0)L1!$b+uix;~2YvExHs9ZT+$Q z8%!AB#(9&7MLv9sQdCY@PWhSdO)0uTs(qEL{_hP=Zey>IP&qD3>K}sU0^fp=DVrBQ z_|@+Ii6AfW?^YCeNIEC4TsQr{db_Y@-8Qh?K%5i7s?Wpe*uaB7TvB zK)pK)W%&Ql^wvRb{onI2?$8#eI213WxD{wiaV_rd?(W*6rMMJ#2u^T!r$~U{#U)5_ zfA0J9eSS0fX zM7IW=ozVKX__&vAqZJczpPKDp3r$k2<3ClZ&-P5MlC)zS`F?jN8sD}6L#vhTnnEj! z=ZG?tdP;=?j;Q6KL&+NQ11Aa4;I8tS=6_w;kxU2=tGvH@t+-55X;?8t*wcbjcSjdo zt-;o-_k9C?$gly}Z>=F&3J0g*+4|_A?XkFg>8C2vGz^q^vh5T%iz~ zfw$napWbl|>o4V>mrk#Q>Z-#z2m>E|5E_$(^5;!A4(Gp=T<#ott5UlNwp7LBy$9IE z(#sWd#{6AAk+@i+c%rxE>-nF&%EY@y??2rPMFCNpcZheb;k7bF2#z{>b61Q9e*;^9 zEi32q*yMi`-^?Ui9YoD>#9jKe?0C$47}O1juR&C2vqsh`OVcX=c{kX4LQk? zjqq0ww2$d>uBMC|rA)V9I4I{suTWaw2^>n!`UN-!Gf}dI*i>x?9R$u%NYQ71H?|!K zT40w=L{e=1#V$LWjVW*-d&1{XPAt6LvxWrp7FIGats2FFS9N0xuJbCV(2AD!v>yFD z6I2;`Sd`AlJHneEASePA3O(F+ciq?Q+Bxl}oOmCn^|u|0$k3o^%v*iM&+y#z^&F;r zH!;7G-DSg?v}+tf{yl(?7Juvk)B0WSMQw``1!La)+%5~`JG(w;@!#?r0FvuYX1Puj z5kY=`=*Hz7UTv;HU*A~&faQ5_tlD~Cdl3M&F^wC;)z@8G$0P`D15 z$5`gQEDtYQXbmD>JdqQy1I!$X zMR$!SbpHQ6c^JJxLC2q5>iK%?jKBEo2Hguv_b^_Cncd{In*kfpXpSz-hfIL&se30T zdQ;cP+G5!j%x_}bDQcc(I}rnpo;}d?M<}&(KC5oEXr)K8k#Vhh0{-Tn+QqAG9S0w$ zq-wu^f^Quznf=6F|7~N&`CI-RA%RNXtPI)dNIL$F003{xcXVI;$ogdihn+u`+pUHX ztrlTu;I5 zplk@I(zIRV@fZ-2SWD{4AU4n6JsUURCF7*axWVp=?N!xZCtfv%l2snk%5Z|K=^@Lg zj#yj4_4zR{bmro4@)uG9rbY}ON1MyH*d^_ujD>10#Q_Q30v-T7>r5r8mMf>+loDX= zg@eg+?{c=@jfq&_lZDwE@D%k#eS^QsLHU?Rvgh+-}~lMv!cben=X1+x%B$$jBoo z&2{;7PwA&@*^v=`>Fnw@tlph|>9TAOlET1$ZEHdVl{YAQZZ#Z%wCkF|-vXng1}!=b&`NP1#+$layN}gE=oORRWUkV0CSkz% zL0#3-Unl;auS^=MJaKlzro4s-4T{WBpI?oKG~U12F5k(^0y+=|#}e@@X7z1_Z5r{c zQ6P8vuRrLK{j+$l%y&?Y*7xxdJmuMnzxZl5!Bx6F7)tCUt}OHch|}5p#-wjkBsU8Y z8G{!6#uH+R^q6C2)gR4MSQ47E!9tTe%toh>UGJ5o!sLA9u7T+4p>SGF>Ki} zdXLjFa8;Cq68Gm*F7?nVQlZ6O>+*Bx)ag?sA0OMqD}Z6am}c752n2N;*9i0Z!u|62 zW3N%VUe4*HZe&(KT5czEfa%rdZ@64`t_Z=|FE&Apq!{{ZDPQbIEz3`N@4QMKgB(Ew za^5q^S(RVg-zqByH}o;|jQH{REfQP|f)#pxw3|g!{u>clM!1bK9iV}$$(%JH*2ow= z{OCl?=2INPs_9U)2K*oe-Xj4+e{JIiu&cIFH3zGfr~HkB03+KvL1|n|Mmfv(9_^xa zpnLi1F=ooupBQwK`bY3vaPkjV`UeB*o3p--P2fd=3eFY+Y(Zb-w&8u+uD}C+4&?(a>s!oh)NAu|_<05ore_fc8K zrQP0ten$t_9Fbu@VnNx@?n_-5O zLSe>_zlP?k#@uBis$yv2uoJpQ57HMg+m)-r+(EoOi2}p&Uw;P83B(MqQ53Xu-WJJ- zn0)5wcoziNdgWTg+Pwt2_O)s5C=`l{<&*1(%VJYsu%^7k*+p-4w z0z~Q5DA2^oCk9Z!t%W4izS#Z-aHS>kygXfGiJj4b0=&>cqLf$W!2^0jrP!!nWa*8`-l_!gkMzLUX zfB~z<=dxG*QqFMA8}2b-9)bVL1<(wLv#Jk$zpUFDU7KW=5qF~KqCx;#3M>7eXU$wT zi~&mn^b9yK@8_!{%WUV_kgPxt4^SVrFH2Tg_!5_bPdMA5a?!NNnzi z!xRfqc_#d-d6Wx<`mzK%?3j+UA@wprx~_<6y7aPhx_AI)*%Zp@3-P0yb8=`OsMM?Z zYiuUWM7apvywu<9{&Cj3`F&batB26fAWe)~r;YSk=3S#Qoy3oYI*O5hZ~ zmvAYp92-HKrW+ece{qev(T$fcgl;GNcwJDSSzpf6{R)0q{!n&$(Nj-6@^x}4s~-0oZHS8QevQbzNj8(e2uBd$Mrug7Mk^hYi zYBjLKP-kuUEOFi8=H>=9T8ZCy_ab{eBvwgq|1Pb1iFmy|Sxvh0*HDPCD~G3hOBOad z%=g8a2EwRN^xfViv0T1UD$%>XiCGHrk`wpyrGy8{k8>OxX2XqW>ic4b@KE^pBcguc zA+27;z~1+P5vNblywiA}uR1)qP!0I~Q<}gBEYZ`(Qcmo^)MP|Ja06UlHDBm@A_{W}4?-Tl@H6 zZTFdPRqj0Su67yr-{+fjPO9jNE`kR< zPxi!{1?fzTmjBcyUs7lN?Z4saBv_=@HRN5)Kf||-5W^R*Z zC==_Muddw{5$m|xyv`N(X^f^rmn6htPvr05C^E_DK-uKi&17+11MtF zpn``W@AozRs)U;ijY1A3*(+~nko&Sh;aOvgQAb$5N9=(sl*>vp!}AjF!%wApwmmLq zW3-!oLUE>IfvY*?pGwd2l&&N&D^7pDM#o;emel2SEh$x1Zd(;J_Ts5K%fq0v^f4`XeR_+X`J$Df{_Zo9~w4F}U*eCpv^Y*lhKOdZpbsrhr6 zj>>U~I`q>8!;N~hB@5%`w4!%>Zr{tj0C^cKn0kK3y}!RGD>Vd7#of+twIjQQ=p~5> z?|o-uwbW!Sc)^&3R3fzj!{=%lWlz7yi;Su~5&rCOX^tiPYd5~0v~45@UF?>BTp}7` z&We_Pcz5u~DLwz~crB7yUs517;dXs2Q=e@5pUcUhV!l41gNk5_3n+@_g)y z*UrU>;YB+7(No#=2L}d5QRW*>wJ*+3iA`#p*s3YUy~T0RjB*ROE#60`r|)Y#56NtH zApX#naa11O?cwL=m*DyhcM)2y0qU|bf@n0h4&vA2waTDg57Za24jf-GH!;-wCUV7d zFpV=&wW9ynM2d2ll)pF~o5PiG0l2CUy(OF>pe3SP3TtRY` zqqreo0w%|5BNtA^(W>9@ez=6)HeB=AVvye&FRxs4-*{$hrVfb^OfX63C0sC{Z(Wug zRBX&{ZTb;pzgsk+=i~h$dnU@KDLToK3uF&##{nCpFoM&r6n6a+m-?@(SuUryJviCm ztVYYZM7B|@<3I2dBL;x`$u>W%v{2JPq}B*w97l7%aSZLYtCO*V=KN5GS|m3kghYUUkDo2AIOpt1K-&2(xDr-y z@N|UuF9(N49woq~Yh$ox#9**W0Mqm$M`67|*`skNYacD)`dXo($uU1KFBrJ$PM&`( z)7}?07@?2NeUHM|?>{9iUj%H-_;a!R97}im|GWSahXw>eD{V0UwMR|V?8y>qZvT_D z3h&m1Ai|GJwoWrC?PhY>kdSN57cNrym;GfC(ItWgdS3fE0|j^1iIW(qKPm0?ZNpkJ z%EyVo+=6Ldhs9g~V;C2cz09AKEO=r&!`8Vx#;afOSGz0C9a0CRi&RRb)MCF8kcRBZ zD(vY|w>QIB`9kV!su?f%K*O3;Sm2n*^7RTJI@>!m^2zSZ|NAqt`g%OZD3aDXPx)Lu zl>bZfolv}IhdJ_f(Dv09sMfNBdi^rj!+Mt*I?R#UtNc^^2q#*g;#!BzC+D@*n|plX zrIwpkb;$U+uMlem?9UeAGzp|Fu$pxJV-0={Smo$iGn=VSP2-gf*Xdc!D?>x0w%0R~ zaOTWwFc}C9LXDTFQ3%n;Ta={npsk7Jvb)*QlP_Xf`W4M0KzThtQrR8h*ZaoJZZ+!W z@5g1T7rdEEvO4qRd_JUxRLUM{s~^COFt~W?JNsSuGyVCc{VCaYIMd#lK}Ig=E)?q6 z{`L3z=y;Kj!P7De#BqIOuod23T+)46rmLOEMM_O=X**~NAe}L)6@S9*vywo_`SjuA za^B2S9eo;VXMI=VSlmV|I<}u@Ak#&6n-7-VxKGxrrYjO3^xNHM#X-4{tKuneo=zb1 ziWK!BCC2>-u9asy?H--VwB5aYiP7L2+V8-ghP|AT$0dwOM%OYDjnElQwb}bI=JJ9) zc|jz^xhok9TfTWvg$KM9Nd6(wyO0C7SI^q8s^k9K=lzF@RwgDz5 z^g`%x(s*mZHXYP3wY4i6)(}sZ72O>z?MvC~d_KXW)A8N0%5-QeM?#>$is(^sv}CG) z+6(0nFK_Xxj?T2dOR?eP`9IS8Wsty6&p)Eg|jKwVLq3 zT^MxXY`de373wg#avMjPJ(ADb7+lu6g%ib-Ph&8OsauQ6G=*{-OaDaYrsz5ip2%q+ ztoCnYlzMF#(!xU2IZ!szw*USUbslWs2a@Zh48PL_3Sc7vp21qnj62OG7vxD0e3ZLzg;b#M6X@Grbfx&0iZ3Zng6&})L%#B3?JZNweX5<9@2vYtzM2?%HXp9d)uo0s zB&9^+D1}>14B+&yCeNs;bGDC^zy*37vk(2Bh%m;Venmgoq0S*y^7_N%bHpAO@npqA zQt#hc!1js)d7ZvUKNzl^{(8yeNu}t?d3HdUQM^VU9a1Snq6de`s=;U7PC+LAlUi2~ z6mr|vRP`|kgAua@FTj412`d=)kIzqLnS`7%|B38Z)SIR3WG*OOSwT$)VK5J`9}8pt z{b1&iGG-~$qJ962aq-1o}K>Uu?KT}tR0J3|bIq6&^v z2zN^8$p1uMz@MxIlrPI4+}hbkwj!<=wqS&i$enzM&xc{YSQ>lQtQ@<(neG%q^_1b$ zaW8;&h62f8RJip?1s*6SfXl-nUx^*n?uL2d?FOpuKiv*wJ;q_PwNzICyW--&@&X|} zJ+AFWWH{kRa3I-D6#k^o0n$Rd+0$c`MI2XPwUM$LkDI9AlI?iY% zrG1WMTNit_(c>aHmiE@l?X(OCN6F z#Pr;p8o6-uNCj{T{?s<2Sya2^%>Rd7?pNx_^^N88ylT$2{A&^KU3w+ug};-bcQB&Z z&NB3mtCz}KQnvGc#V7wbA5e*HyG3SE(!HDN;jWKlhF5_qPqR0-tI5s z!i7f{!)k^f4WY}!Lca6q4L%y*-cx_?sVsFp+ml}@opmY&2djS(s_9TsN6;9YySZ`a}k7P&%c#thh`0wFcH7@yjoJ0JYeW+^nOk$y+gtRlESXKnl8gPW4ypT;B`%yi zsd}2(;6V4}K7V-J*X>xDi1Wyq2f(y!n@5jF&}Ld*F52^ zO{_}I8vLi9blvtIuBgm_0Zl+56SPDnPEKU#F%qa*t>SUqXZb);o;Y`MI6fmFb)9a* zocS<-;B_g&MuMpQ5Y{hBYYSkR+DxyI;BcLu0X+Piuk(4X^>*>1474%=JcGfY&U+e6 z2v)T3#-CIWq7|tyxhPyu-MzWOOeU34AwuGGlQ`ivKZ%P3B;sAEJxtXLRq-`Z%{6sL z{1(Em;Lr4zkxs|-f~n783g9-Bb`cx7?1PH#8cVwos-ioi$(^y39^m5DszhfNg4iJ< z=}Or9xx6_IJ_i$IPw1o^7wAedwe5S*f1EEyZAy%6Q>ZjdjwwGV0$Qn|vKT@ zS*%|Mrc@2Do7RYC-y1H^9G&60@VhabQ=}F=c^gfc&A*avsZ5>-_3|dXD)|oWXkMCPFMeue!wx< z<(Rn(?1SG|oDms>E?)@)xF(>3xc-q;FBG|;Ta6$%*4eeW8L=TUFctC%nMikQ_a0%G z5C72-zlMV-WC!#!;4ixLLlJo^HNZ`D=3d#jUl@o(yN|CZx5^Ngb>?lH=ez9yEWCd}kH<5P>@TPhIRD+9Dm*XTrYUIjUPVbQ(v(=;`v z;K(HQHuJAh`q~j{S96f`pxMBG4S>~{{^tn$dUaH7^Vxq!P|C5*IL}Q5GnwiN1Z$Bp z<|LnKRjehw-{KV@HZ-7VV5mWQ^!_p||IFl-&lmQJx_O;%9~WZ9?CD58_2x}GXzCTM zI$R+6ZuxAg?M!f}gAYD}5B%D*KD-YzW=~hpWs)7gV^lcsGYY0~@cb#W++=m2!M zM_PZ^NZ9P|I!=Vl23K>Twn80nI8)GK_ynGfvhK@Y<6lzV|NK?fc->6pn$wt~S8k8R z{lt(cNdajIqkmrUuR~ViZFqVD+Y&VsyuubT!0!o%xq}oG6xz?eY_{Un*r{cJ$>K*| ze*(y2vi&*entC(F{LIaY2@}yu#v(;X9O)rlIoYGS_<=uK%aFfZEnRseAy%!fvGv}@ z*4A{P>Oli{Z)}H)`ehx@_1`6-5+!CGJ@t}ssH-RfBfI?#7mtV1?aEP2PI9}KgQ!8* zQHKN0q|2#$#e1g-4>5FFMj&n^_y(j*UzNx-k<6CwvV|4!puxwWHdZ>7&*`G+7 z98s6Q;c>N+C*F<3RKi}zI>JsyA1k8o3hm#);`6PGOh25tny=hg_h0YAt_DT3o`98L z^|By&$l9$A9csa*=)L6aV-w57TIJ9mWulc|AsyQBzvu<*$=XHt>cC?~r$54E`5J_& zyAU@FP|Qmxdw_;ARP{TxqqiyL{eZWmq-2`&SE8iw?p=Yhl;6((CBDJ9sMuw>t;dLH z;gtl7`BOq6&=}2RF>>|9nYqm8Uq&7ubAY#^MX398i8fm@`9>a^dp!2hvfc69V2x8m z!nJdu|HoVXns{2-zFUj8OE>aol&4R&MsGLUzwSMk{INks?ubVnimG~{h>6{PNpLfu zf%`PTLYejZYeZumC&gJ6&V#T(Wt0sW=0jWSc+`$~FYB?X{vrlY6o`>lWFNbqh{HnL z()lel9R&&K0%4*!>{HOU4!`*vtgP@ms^6x8)p5t4&jx*}h!>%`_F#v?|DXHG$s6hxS2}#t zM0IXd_L?BuzMQF%PP`^y{J&rIzKX7sN3RC%HT*CGQu4cdpkK?AcR@$D9AC1mpJD0b5LJAMR zt(J^*R3q6ZcJtjl+XQ8X)mXqR*A4W|gMCFtA?7&d^P&nso)23XzD)F@8Q=aM!NmiC zM}30Mn~j$PmNQ^I>a#qCT_PM~F&!?N-sH77C4FpKhovQ%>^&~NT2Py#i(|TVIx-dZ zFiB8KnK51=avTz~CjoCwf%n{aoaz0Xpg>xg@&3F%(ha?2_q3W@efveOxEE*P z#3kW0Lr>9%OyZEN1(M#=uR>}ZcuT)-F7f)KU=OYw;&~=~WmU0i4dxXat$32Rh+9kk?uOo4Aqg0`p-ACFCki(T&7D|l z$D3VEKWWoM)F9|`Q3d3fEpl1e+V(xp-H-vgRBuWH>qLa|03~~u;NGC@a*@qU3TKjj zX`wyO6RR?L@FH`dhq1)j^$xU>o_YBf?vqqn?G6#Qt*yF$)ocGL4T@@~h&PiTkUIjS zHGDr*f)XbK@xd0sg!w!nnMZ^CO*LERfoO3X=BG&65-k zI%~6a@0F^lgn++>2_75!G;rF6xBYM%x~G0YvvmrCYttT1ruF#cE3_DKB@?Z6bR)MT zOYMs*A3r4KBjkEpOu`yqZ}ibyBvklaF~SU1?hhJY$jaO8F}}$75`JX|Ru|(N;b0t7 zDLK230jz7({Q14$0#jQBPTh)T&|LTNt1b;>yJZ+`e}BIcC}dV&{~sB{Dq3LcpZoV( zzKP{)3)i~B-n0s>J1@_?Euloca1Fm=&`QWssI41q$uYxbrGp9~zsDAT+HhSgaa3;v zRfF=dH92QncWcwPVTmE$Adn>^?|DSZeSiSgc zfVFW*<}NW`WoMxC&9<^JrIC{ls!e*t`XCK~k&;)Mt5^TIyxjfBg@{9cb*!?~0G`=( zDMiu8uo!B`*)m9R292>}|5Fv=A96ZJ;O>;sHR;Iv^2*fVC+$j>assf>pkZ;s93*Gk z?3W}Ze3U7-JC7u9+bEsq%iz@312_5Y2zaq3X7HYcZb0eZ*j72-`X~ATkwz;@zct3O zBL%IwK@`PBxP?~NT=HbZO@uyHu5D*U6Lx>^G8#=xYcsXKnMexMN?0q9X$w0$+SvRT zv1d9I$0aJN*rFGQjvbPC1CzO*aC<`;+-zIRkwVJ=N2*k%Cf1@F>yk5&geb*y1l0nQ2cgG>OY|?`=%uCUcr~fbDr;`9|vBr&;}E`J@R__RF?j)fSJP% zg7XGYCk`RFR~O$*p%1^P3Y}?Z>n*=)|FjD96Y3HFy--wky*09> z#wLVdJL2y*;in9@rJ_OZlnSe{78%(vtqZ0MMM@9uqLJ=Gd#-O@Hl%Sps)-k$b6{@ z%I?XMin&G^3HYCBQ7_ltXMwWP)k?R@(r|>slZh6>%6aV+sXb9$>W`7xE_b_@Qd@{) zmR+53aswN;^$&m=Bot!r+4RA^OjH!_*=^FiZ6*t^=_a3EIWOwMr1>(53zJOZ*2j76yB> zU^{@$;c4W8U$B0%wp8WV%|`C0hoH#f*;?i9v2>TMVNE0F4w<<<*~ zvLp}U*C=tEOXLUI^3k1>+WPYx6etvkH^1mi?df`6Qz3GEv zRi9xXnye9{_g~$CpAOdOHRwcZFxEMWIV>O#cPbY86K^J^%|~g2Aio2Or;g9ZC>SQ>$h6|Ih zl-L4nO9}w1`1NKbph0&iS@B;L1WqaIeG+MIa;F^vP{?j`jcNs~KkQ8Y&0|{S+lmK5 z2OmOxZ*}DscxnSYMORF@y@U1cf_!`w^Lft1YnMN*`3U*7rMwpB_v8TT!8wz&w`FFy z>#g}F8VhV#V3B<^qD6)&rpkaL!ti1$w+^g-c6&Ww?50q41VciJ)^lyL?L+VIcrsn) zBSDEjr*Yi&*sbWE9R72Za81zfW?TbFE!xi_lKo2pbq!DPTn(aIgr$M%BWh!e>^Zx`&TD#8~*c}4nbIB zf71oSn>-bviCgE}HJAFus6(6u*b0YQDe_{sfvz#6wb4$C$7aB6FJL!}z~WB|!e4n9 z#DsssfH;q6wl1C#TzaFh`vn8Lrgl-GUW0Vv#%V7z#4q#txvx=J$MJ6z;p~n}Ixq~| z;^%Gh$LO;gUFWYSXRt$M=b4M+9MDHsjoY}+8cV5+G{lz|`k!aPqs8y^oU&Hm8O1D8 zoF-FET%u9?Kug;_aMHYLw&Vo}u{I_FYz_ok>ANos`l`bQrU3JETp=+~yn6nFa9tKv z&V`AZ2h$KjvI2fJ0AS5LqLY9221zMC4mm!}Sa*89uc3P^8YiamG2(9Z!*24NJ1-Xr zApprE8m;}Ey|JS+ywsAgUVb`_cE&r9EuxwZMg_B_*lYGI$2XUvyV)^OEHR`~ykWB> zffV3OSD-?w=uIlNFq#?Q?ete(W@HrppgH~Ir?sa|x+3h)DV6@^NTwtj_%kq689>D6 zP=H=sa*Ln0tC_Ss1MyQhp7V;7O8mHD4pMiM3p$hEOIyiITW&J!K*zw`t{`<)*XzZT zR<0WNhyfG1ZBzV4-PwyF)PFfxQ25;z5>&H~T&44g=J;w zuU-zKdB)w08dl_h55=LaB>nC{!;NL4V*TdhL#v*i)R~?MIW$vL%HeghrUy!@os8f| zszw$C;AWK)`Qo)ld!bgn$;eY)O#KqdZ$&A*TvP>{E}4Du+g5iPMHSH4q=pfX!tB+h zz{10Gci)^muyYHVc?BD4L?c!0__KqpZ9#`W0W$K`-`zE!4hs0nqCCi^NSl!4#L zjBuJ)FzUgd$Pvx-kx6Ne9?l$jL#bmipb#X`>r$Y&d;3}Rg(xOaIOO<&M~9N(=_|EP z2RZm88vJ{!(-YZT8fv5mw(;L&I_7_74Yp?=f@p|2{9mcXwZo4-?I!r)h#!@y;Z0iX zCp*{#y*qE=uT=Z(uvktAjhM&iV6z!Jra5ANWhgMI9nW;^UjjF`k1@VVZ+P=Px!#|2 z7CLjWd;h@#OcUy{#;6eB{(wi2n*6ycTa$3t=Zuq6rH4zRi(I5++7+vyr#FY&bfD6% zG+@d=FjRB$?^HVJM6{v!LsalZ$G&y=9~BY9RHA`D4v*RdOAU2MT1sVFu}40FmxVeS z;T52Y^7pz3B6%s{kXSY?eDVW7q9jzS*LV{%7Eegw_Gb1gDU-8=NGi1UVGY^~ErBB| zFrRPv6fk^#5W*0*j&s>`UyKHiY^KoWhYBLq0pxLndSR*(3Kmyvk@2vgCI`%J;iKKO zg{Xtqz<5)e;M-_)={rW(&5Q9U{HxB9uR>FW#+!2FWkeCn1BDIgZ}7lP^3xfup@`hO zr~l6ja3?G_kiJO`G)lCDl~)TJr+a-E%(r_9uC_6KaOc(pNG5@LsGTwS7_G<~Ad3>Z zDs?zI3OVSn2wRNg(AYzJoN_PLoIXJ2FA)Vy$;MdCD$v$dbLB!*rBWk>(-(Yd-JQWz z@Wt1wS?4Zn>zP#{buB=|Ysa+g^>2qPB`h}a22enWpeUNiyjZ{LlQ<7Auj_$}h`qhN z9n6Iv@JWocPj1a^fX_FAyyX~d=kBANC77{|ZpO5TGBZLuYpR!|SZ6Czf?2)VKw%9s zMio@kW@{${XM8GjRVa2Zz$u^7Mx&l+IaUS4!8-8uAp%a>)p|;af?fQ=LttF4u%}0Y=w{IIUST2rO^F0Mf?vcBBtC`M{s6eq({>h=vp5&c> z$rp3GUbL2*?oT*Dz;L1tn>V*)-EZ&y=m+)PH?Q0^jmomd!cGrDXi}X+52nT>{MpeU zc{7V-Z=4-~#qD3=Gj1=EZ;r^vbm@fqfU&_(3?&|(r8Q6G!7%Vh`$)8FP{qB`-`f zv=h!v?xYAo85*M$7F>Q{?eAw_>9ow&Ud8JkIptgX(1m@JZ1Fx%xzkJzq9{5(Jd6Pn z5d^*xlPG%t&y+qob~_=f?s8I`F^4j$bW!jPy=#lpYmBh!)L<6O3)`~op(<1uMs6hzwUo^g zpAr2}GzZKSl6!2gr3GMSrCS%!uhus`I$o`>#2EYAt3L#=7y;x)vSBtwwMpXWnR${n zGb5vF#JNO+A9`gD=u_KJmu^09oTva~hp)QVI#1hbxZ{AcYAlJOo-?A-92~RL9Ls5< zu1y9~8`aP!Y#)CQ3-=gUxDuI!$-zjGhXsX|$0V0~4x7X`Xn;~HDk+q4+#46@;<0T` zWfqcOd{;v-H4lxYB@WeGvH}791fORgbP-C?7o-nIQyI-$v;q$LXcS5;XjumBKi=1k z43bZ6_~>({>0=mS4^XXK=nwNId!IPP{gp!xf!pgFIf97>O!zw;2R(+PA)i4Jtz$c5 zlCn!?^VJ9eN8#cH4cdtY?JtL60D56;y;h(V0LyJpO)|~ZUUZIRY0QmuN*H-4vROo< z1K6czmQYFLI)FTf=sHNdOFs{G0v0XltWcQunP>=9Ue)p3Guk?&Z$KYFb-O8;vbcd# z*2h-xcL$7J(yheUM>{Syv^886OVlrB^HuscGjnrp^JMwo?3FX5e9%c3*GD9DxnN8! z+$2Fwdl%Lmm+J4Mffjd%e$NYcO3yG6+MmSGQ-U9Qy=G;;Jgd~~CjMj14(08cjro-a zwvDxD%FApUQ!O-rS=>krRPo7fx1^mksjSUyeoGG;3wEXtBBu;h%(?oD7_tRg!GDF< ze!Xeme)udonZ!2@h2Yh%?mh006E(H$DPaZIc}Pz`@FOoyp%}dv6uIen&H4&+Tp<9* zky5k&Z2ly*wj8?h*VN&h?dLTmV&TM7MzoJI2-8lCq&Lbeg1ro(X0>&sWN!*<@#)tu zHj}edl%&-zVph|sXwp%RNBP#kT4`&ZpjxOgeRj6&=kWtt)z9&i$py4ac-iOs)U^xv^r}<#{e7a^s}WddfEi&<(L%dKrT+|qwfNi~Em9NK%cnLe)E6w_ zj$+pqSfYgpalEdH4}Wk^r1pb|=OYf0R^n`w#x63BA5M6aIP!+E2=kjLoK?m2hpv z>40@}MRInpEKF#|6-5k#`V?or{es2BiG04`)R*dEL=X_p1+M2_|3_`7n6ix@kI^EO zAh`x@vAWPzk3JmbPR5lRl0N_E$*EKpQNf|~y)0HM-;tEsI*5X`#}y$d4x**hWRZgP zV8Qxj{~ka5J1a9_E_+K>ZF3j?`dZ~Sy%9*8>p-sEsZDUT{wAccR%JsYq&6`L{b#=Q zcCw}2tERgcr7~MN!+KUqAVj|nsEcfi{A2zGuj4HbrFM#H5;W^OA_PRaJv+XcWRQ;i z_OXWOmVQQwaPj<>=}$Q>cyzdv3g-ylXWgIhRXeVAPXCzQP))m0JI&4O=_n0qRA4^! z9_irmU?W0wKGN9=$NJ&c!u8fy2#4Zx1>DM=Z2;M^xQt(}@4^%HDT~I?qd1&KRYQ3s z)gD>C8~xyVQ;r)05Z)VU!Ujy&ck2}NM1f<2i7w2m&5Z3D{+D%X<@8g5?*Ky7 z?Ho!_VQyX@Tg&H_-H;#!c@KeKl}u=HvMqdlUueI|&9tK5 z$B}=zva35RR1g>HD%9a)pxAB5UlaK1-=M#FU*FwsOxuoQi-m4I9mNPx&X>`Mfec;7 z#mn-&(l$8xro^%l?yuE;B9=`$49|`e3&rd#P=lC(7uU1wD~!3r!}~tuSI4^e)9VSY zEd^smNu)Jv3#vxt@6xc)+1BR*-=Wo#*pDO;j4zk+*vjW%Lt^sm+GbW#u7K)`jnym< z)+ylgULjD18QVBzyU7L;x?p{^IC}3bqm@c~prM%>o&&tChIA{mBGJ3gwp({x;4UFsy04OLYCu_5{hK z_cwQXNv<2dyUs+o*^3LuchY_fDonInk}og-wv(G`8g%$E?M%br-6r8+SP|RNdvrTv z>u`IdMaBm$6hn9c*W_md%*Bk%C)ss*gk_8wi?uf=k$u0KL`z%tG0^NrY(?8+P1m7W z!tiqdveI9>Ng#NPzai|imihE>3b-&mL={SAvakbRq1glR4?x3kk%ZZXda?ya3+>h3 zik5ZTvi z^;0)^G!#AhfW8L^vImMxXpK7X!J1A;Wpb?(%8Ws%u|Fm#F+vS%iC$Pfcf##u4+S-_OY>lGjBl zrInNtu!7rN3Ih+y!8{q9Bc9&${LMMOx7l4y`6>1hcOFRQm7k5itsrp`!APefP8{n| z_y%=D%%6T+l@KeTMmHiC(ZubXV--rR3|`7C(LjPI zC`>d!AkewXMjwfCGz(kx3Wm|u^iVY{(C@tFBLtt0UMH}6b@c+vqeZ=}Ld7!SfN<-1 zru=ph8?quhQ9$TO_oTtfHOF=sWrag@X6rc&X`=~0%Y9*oxe!^GTsz?Ib<^TZ>;h@$ z+VQ+dyl!fN7InGgUbPXqe3~Hn7d??`=1C9JIrbX5Y}`64iSh=zX8kfc-@nPDKZzq6 z{+g$%j7l;rEEYPBFy+3-*rd_5pUEUf-oStq&w6j;-&M{6JgzhiFy?`Lw2Pm*E!udq zM7J`%97wo3N8VZw5s##{=AJMHzmns5v?#>|h3$E&ORd278qVqAxH)z~m{kZdUFp=H5ACCN#C`%m1^p zAb4i+kGXmRyF(nL_cP<{9qjWFWAg_a$Ms8bi98?l{i3M(LV-^IxJigmM7Ji7@y1p z#LBY9JH`fHUDyl_4c$F1Fp=OYa`1jg|44lGxPSyr+~fm{qm(d|l3iA1c1$~x-sN%K z(8}qRNWHlyAxIwYtmvdNf>~nFdo)PdG?ieO8Gud?HH8miBwGhI@pyA>r_QGH#aCdI z7==YN&%oR|N8rE8b(j?(2{re5xj{Ux$G4Q9zUV=^vTfRm!CZ45n(f(ZK!7nWPnLeq zv-8^j9&CU5!ujc$jW+A$pePtVufbK}l_%ozKV0&?dDTzWjQwDc6`ZNO2+Zt7(R2xf zH2jH00{Vr_H+(is!SGJ~x4xf#J>1DsIia`!*3MlEYS;RBfB9d&UF3bsD-Zf}4#1A^ zlVsq|8qlujv4+BF^xRscxt(LXzV-6~Xx7cmZihe6jo@kYi@(qJ)qshlJEi|ruY{-bW_nVL_=h)1l%6Qm2b6%w)(!&-7hb_s z@TN}%*lu!%qezgf$~AT7(Xa!V0xNF=*e}!b#*5)I?fLSaV2J9QeQfo{61x$L+4xO( z?+R>3Px9AKlmNfqk{-Ky?Zervrfhvo#ecVU(*1-)(Y301CW@)WSC(BIh^AxhVu$Qy z1RKO6y8ktcYz^4J;<9v$Dgm7bf9A_i)lAvooc&ka*f8w*x`fv2olb z-j3NMjh(bfV>h;)#4j+cw|(`TpkpXK{CDc4qhPbI*Bjj^OI9 z8e)_@~pq{#I95&1{*ie~NY7bv(6| zSy+QHYmay4pIioYX-2B-eg->z=C-R@Fjd%S^^V%tyKfQu=JKkie=aALFr0z3Sq zOXy?mNUKo*nB|02_CTHHs9}w*MYJRRoo9{Q7UO)+{$;B>B;l#8M&sOHc1|3eJd)d@h#lYj1D$tj_L^eT*AX$n*OlWzAJ)vRiJ ze8o~f5-UkR6|i6hEpu<|)`JHd)e-)~yd?Wrnik{@AkPC4E05)U2}qEdJU$B^E`6{m zrzYwva-sN*XFjox5Bebq3Fv?bsE6*|)T%cZ9`7x&(iF0Y;w^mJ3;hB}fB{;~gNqfZ zgy{f_VgtktJKt;lUQkE(t|Q;RD)%sEH(y>!{K;^I@z~eppq=<__E%=v{ZAXi4vVoY zW7^+H+U3&wU0wa!Xj-?^BUr8AruOb8o5e1tfY#g;m;gnTJ2ELa$S-tW1u|>ts{E9Y zIv9V;ax%Mr)^n6)%R%}{Q|xuZQr` zlB1_WsCy@T!B`>f`kcnxAHtPI6P@!F)cAs`bz;>}%|;~Ds-oXdHlp!H_XQ4({gx4I z!$lF&VNx@~`A?Z|*jGFtj_)^Fm0GO4{r?EPpFjqV2CxzjEc##gXV(Fhz1?i`5X@xy zmxpvh(UnzTgc5Aa50Uor0P&me zKs+x%2X%?^tKAGOH*BAc!RILYgo^9LG>GQ=z-S}eeK-BeT0OwAQOglrbI+o6Yf+*l0}3y04{r-^;C zB-$QvM7IiLyd9O{x~ z@av#fm69Xxp20_|S%V)}s38G53t=|S#hUX#*PV!7wagBXO8O-f-G|WexLe>X4eq(c z3{8m2tRWdIm|V2{LMNV%5g@D1O;-3O95u+ZZc5N&hidhOxCl5O{3GGt>3m2ZNqhN@ zUVnXFkpKMcsSd|e z!YZo3=6vH+oZd&B%^K;CKjG>ReINL0dix_%adu9zcbxvUbWuh zB5nIZdC;?V7smg%dbR7H9eP{msP&S(FAwCD#Jl1z<(1Loo0$Sx1~3M*OnWSoI&>mh z2)$KIa?!{*L*mFLE)!;`tkf+tnw*s<8W!Uhv#Dg`pzI zq3Le%vlY-rxg*=0>3BriN_K>R99b#TF)6aJ9EH^&AZRXr(*11s2Baj+lIH8h?&*apjHcTmmKKo1oBm_=V~U|GH?BO@ z?Cnh5Rudxhs?wnx>3C=*+4r8`J235}gPUoP_u|gIM1cXmF z)^N~dj>~i`t*s>#nvy;APxgyMzW$ibF0Ma_^tGuJCi z!;GI05^SooRMO`=E>5c+X>&T+ugSY?X9HI z$=7!#6-ak|0M=0uqvE_f?ZgL?-dFvctEIBrNREGFIhYJTzx^YW^vCi_fJllpWd51g z;l2j&N<@=<+{31xE(-(vp%61+&3&w8hB-8ns%2)J)G>qtAQ35KY{jfbA$=KXLP*^W zbhXqW^u{~lI%_H39R%&<>U!Sl`S~0Ti8mmPpx&{REg03v#HhUNox!7TgUePK!a+FFG>>phNq5+?9;@!2&@#8Pu(x;-FmfW6o@1%#yppOqy@J&vuvC? z?!TU?V4=Ad%%52{p)kGZcb<}To~{+;;UTKFwB@wwJ^Y@h`aCIlIpLZv?vvWQ@yL4& zk}^m9ed@|un+q}C3}J)#`vhmo2P-;EapB8I)(>dA!l@~YQggywNfPc5qnv>;YhTt- z$K0s=t2h@uhFX+Zg_H7k>&RAZ@&BMjMjc3W|3@sj4>h%){~y>C{N4Lpo;yMgdgwYm zNHDp_-a3f{Z}H;ghF;d3bKeq#wlIctX4lTekg?4QB+yM+wL7yF;_}Gc7}Oj0Cclg9)2<)WVOJ-2{{%!z8h(^2w2E^aJR_;ce$1D~Oy1vBVW>6%8V_soep4X}?<8$~(OYCo zZ~Ti+$ek|da6CA)4yGu3D$*)|Ww)zxo-CcW44bvP&9YrnB4MRf?3^CPs}bT(JIDzE z<76>(xxuYI4rRX#uNMV1*W`BmB>mxsa({j<77CDz5vQ3fhAo|qgku_rHe#V7%3LFw zu-8DDS{H(*0OUK}@4UBEMqhrL2l&3(ELQti{V%k4$^H-?BXd){4jFrXu^Y^g@dvIELXbzj%PrmBOo82gj8B=zQ54M`H(Of5~E_*dswE|2zBlKCQt=0-M_l$YfF3i-}Rbr z4|<(jwf!B||KJO_12q&a3JlkD-q3IGcH;-;dD)^coSgrus*2euu@_cog1*cEwG2&F zu+bm#l0fx8wAF2MEX#}30|Qtv63y24)dJ6a^iFra!v*+(#_&c(;;%ZGKjz!0Yo9TX zm#YXYbbs@(b@d1cU9@RH8omXG@>4qv!M26#o%UV293!NL3$YV|3FCg@{mne_8^05{ z*OETJV?5@F@!L;%5s|Nb7vA?V{NG=7tsdYR&z>Ng3FA4JZxgO7C+1VQ@^b)i)dJ#|xnRJ}h5NN>K7WyM7 z_Pi^}ce*C)Eb47vyf+HH*UV-&o7v7*d?zWx!Yc+bx#8k7Aby%X80xg1m>dI|OF2DbaQNB{Z;AJwo2Pn1( zAJvk2i1Dw?hG*5;vK=#Qp;`rdw=UUe4 z>s?N!CKEglpx;W!vcX%!u^M;ha z1dUND!TeK3grPxS6_O!~q0_pi<-MY8+hVBO;hNmBb3bmR$VSB{z{A44G;<^7>-hg*1c0_@U9=Gb2lCJ?Cl>MjS zfkp~pHJ2m#)hKy2(rHuH@=ucGy_1N65yizY>jrS-f%&_?zJ^g7_3}@Pbk@BU9!hZ+a(v1_8nmbBQAm9tydkFVmF}_4tOb6SL1;~8W1Wk8Ja;hwqvc?Y z%kKi}9I|<4`GvFQ*v60lPrz&FW?0y>h91e8b|;q-fO?v%@OpZ{ee2$T&q@b_Kc`h9 zOm(Z~tIMvU(EQbOd)!++0(UdQTBpRf+9+eiyp@`38ToYXvS`ReN(inr&5(KOOcb~N zws6w8H!Q{F%qvkzE546Nfc^ho07cT>!JHoU`^Nb%_UwOb8~wXty2&(*%sLfm2&=$` zOo(QEAXz$f&BF?3wKS_3j-i!NmvSo(>wfrVZIiNck>*Dc!SlT@7YD1IV!xl!2JY~M0 zWv~%sAT`t^EykmK)#Pq((c3CK2+%pquQY_N^D;HVN*n)EV zX32P7GRc~Oj^mQ4*YT^%n$-18-bqDemQI<%r$MPfu$$e^_+tGWVP?bjCr&5?ni;ZO zDx1W0FlHY_Idj)Y^<&UG874)H3wMsJ8XPxDnIdE$?9!JMG~=6s{`N=p;f@AaRcX<# zh+$85alW3*sJmd%=NQy_QKK9*2>I|xAri%W(?%v6?AbqK+Av_{8W-|jII}woO%9!| zdN+Hb%E6RmFxH!(`nQK7|2J>=(Z40##Yr#fzh#IQ@bGhfUC+PYhSR@af~eASbN2&2 zMu8do1awIqo`x527${Zm{MPf<`i_*ZAn(>0Z;o-om5&CN&@+s9`dknPOtW)KzwU(* zF%I@7)6Wp+D6%)ya9w?auTT%vfqmntFC z&qv`; z7T1cS>(HZ{?#%HYMkn`~BS(n~PsyyM_u*P3O0i^zYNOPkXdL!b$Xm?t425p9Sn{lY zjH>Gyle*A~dKsA_ul+A1;0AFB8n1(KFEN=`n*_wmYlNuUZ5z}{p`$))FU5;J3f5kI zY=G$vMaHEamNdnc*sqy79rXKbMBMkI3*U%XyrHJxVDj0|O~=G>6HV#bZtlurd^RwF zM)CAw=*R~FRW2seIb{Z4z663oi*XoE+8Vd_CEtO<#D8T`!NJz+)D2F}rWp z&Sk)?OzBv`GA{blK<`(cdq2zxlJ2vWUJ*@Re*T!9Fz*Ei`2xR* zuc674r2yd6m7*@bs%HJQ;iy4&p4a}xp(XxfnU?1KblB=bv?^6CrFk;PDx3G^GE?q$ zYcNn2Q97UXLHXj&Q(;u*z+;^gJtVp%*$%WX=_Tjx?SL#JqAv0 zVl+;@zq~fThEYJa9Ho`c6T*r5#n$+d)?`kuiTS%+qwfN12K;egn_*tV5aef^7?~OE z5oI)8Ot0!AZu5}rc2+V2mGSP#!U~&3GO2(LR0w*DfYSg;YvOmuDS8;k4Tho(uz~5H zBNk&s#@$;aw^L9+dqk%OOa1bW?eEwsbFEHcS^+lZ5e*++I*8MFz>2WUZxudg0!t*T zSPvuL&2dQ3{LAz^;89G#y?aTJ60+*7EI$o!V5#qh9r3ReI)Ccjf1H5aC8Rr`L>b^A zr~Pdw)2>+}uF4qm{8__Z={BH9ijkE1tBH(^k66c7YGgCBg4Jqfa3?};hRxXC=OuXs z1((-bEQ0{+SY+JEn^d3Ny~`sG2>&OGYUWu-ri#0X^bzMQ-qH$g6T&D!WVuUtID?we-@(J(;`<;Jbsxva z_&l4tzTVl$-I zH}he&4fD5TZf7^#T~MP?3EFoO+m^qBiS>^ksA{)KyZ>#JaLn$!Cy$k-L0+q=H0Xi6 zZzb}Qs#gepi1N0b6jHT1n`IB+hsdV(#z&?U59{$WT7=kKhrN>x^f^@9AnGH$_q)Q| z{6H%lHd}lr(sXj}t5?AEt#Gwn}YeN3Ypt@fcBML53?X)*!t{2lc@=luIgrb7Cl${NBc6?Q!*a!BCAFd9z6H=j;PCmmfGN3c;qx8T^V~J>nvS zY!9L|A180zJ((u`a7l(SdOCA++=M?moiH-(jx{$xp-);gG7XzPwRyj&@`~Ahf0-gB zmDtTfU!dW0!J=A=wx|}?)Nq;+6q)TsoAqqY)iUIQys4np!37qJ4{eJs?QgzM1)|yN zgnZD2n9=Q{gWi}{AM)TAwlh5PcX`-eF!~9)&%k29=~7%$(&lmt_P^&dvn zJ+>64S~TOd2>b_MO%b8rznw2&^=oODm2pV%8Esdw(R5Nob(C31r&MXv;lBdA<74h&w90 zFV)jsqt836Y<7+7Nj=QawllG5oYsm-R71qZH7#BC-r8dLEtgz%!Qm_(JEOXs3H?k)v2{KlV`&NV&5u}AWkNW9S?%CY#tokA^?H;jCv%3!7c-%emTJafGr6 zGF4eN(r#8>e;cgx@6^J~A3TjLp%|Pt^jAqCYEZ#&7}8b#Rbl0BYC1nZ=8N5p_^ zXkBQoA+*e_e$)mGl{O5m)%;2?mSXm!-*|zwFuUn%#E(s#FX6LiXM|QnZ&(L;hkKzr zXwG%FjOP4FDSZM|IcyqHFBvy-nNXppzH&~yCChBI|FX?l?M#go7mOt|n+TUGZnrq9 zBYYY7chyy5eul)tH9?}_ff<5abMaNkd>HFu6 zU)&i4J9SY7d5e6Lom&lKh3-o{PbP&t^&y%P&v6$R<#zmB`|YQC8E0#{4SyvjRGZ#( z*AMZ%Il?id;W^R0dN);bWSyxvq=WFK&g?iJ@@PaSDno5s2I+t+--hN3# zOzNf^%!F~=97rsac#UYx6$|cu>A?DhKjL2==%yUcgy0PNYj|qDQJ`V3?CPMd{`H^B64IcWzb34r3aeWn`H(=Xws5WHH%6^zgH3i2c*O+ zj+|C7UWfWbr(c_jhfB{6ietc};ZN290BR`z2WCSTPn?D7dZ_KFV1g65xD8^wT?Z(` zhrY&!qJEA~YqxkPlmF<>@XJ<^?PO_yZRk|H_>GKOQnR^s!q z{z^mxj%+|-pTh}lW;hgIrq@)?yHGKI9|$tLj#FCwXz<*3fI{TEk-uFvOYX$If_JzF zV>>qes+V!cHsjry@2$pkbgR1XsD!^+*aQ>S`~@+9dBPXhBb+v+S93}GSv?@Y=ubvJ z-L9J*F!M3&%lwC9fX!EPO)V;Oy|xVHO^8x+`u(MY3^82kKd_KOpTff6a=rHP1zwgx z3zPB;`YuYI3OH`zf4Mv%b~cTfOF5*FHu7K%K_6>T4XiPMJ3cFJVL4TzDg}?~dql$M zooaA4t~O&jle;k-X@i#`K7#uH?$4< zzFV|hYxu54VTH4?#{LOjd}w(1m9Ku|*#ct-awu60(@WcUxLx@YG+!?N;R2%jmz_lU z^?D8(u_Vqb!J@n2y7OCd(YiFNjcGbC^myVFo8+JAcXM+0?t90MaStj!gZIE4P1kCB zNy3~7xt?;)V07NMcr2>8I z$vW7}3fN08vp%mpeB1F);U{xO;pGs`T_1&*ZKBg%q6tsn6I<|~SB|+qhwFbvUjOvP z-Hz85pSiuh=kdY!x|ea~;@%d$`Mm7lhbUMezj|NH)?Ok4Y0Ahu(%9;vG#%rmu<9*HF~s^ zK}~Csmu}Fw1#^h=1!}YsH{F@{=K|q1XKN}fJ;(f-w25o9%CpTSIig(s+z`m8oGaL^4NJPFimGtXCp-xPx3wXe^SuQ%9kZTm%S`?p(=g@|}IP#l}k zz?hB?n_y=;fxsLX^Fa6@rCw-vXt;?X#7{CC%(ektn$Zl#PnW@zjcgQmiOKM#GLtA zIk$}in`%g<;yj~QZXFrn&fyZGk95U0VI4Eh9Ztcdh{GjzR(q-_n`)1K!L$gQ_8}dP zCgLI(VWPm~u3Mbj1~S^T7-}>)uSNZb^xsH6_!1mn>XYc(d`gM} zZjKLQf&*pJb#_d@AENC9b&^m7n7lwM<% zBvDoqL4oF1-TPgoR$a&r$W^KRwM9-rLB+yU3Lz@R8`Umorb!w!jdgmFnfOhW^TrigwIC?KIPx=&0xiax60C1f={jSZu>9j%?{HF46S3H(VWJIVwr4JG9T$ZySF*7$X6B>X@wJIw==_Ao zOZLkm&8~W=+UKGTVrs^dhf`tOJUrXLjge$i%#JP|1R`WJhQR_wM-lB;t#prn-)SD(1B5LjCr`Fd_R-(z`#rS4$+;hEu5BT(vIB zNl}Dq)4nzu9YpgRDN~}4wxqpU5s7OZ6dtKI0eC>WD4QM3H_q|j>t&p6n!_+h54Cbi9Sx!;mSd{w4AuP>7?Aup~d3QrB_*3SIF|RmbSKbs#;w}@vv*W;NzK9I29`# z2)_0v=&jpjXt2{TNwxCC$%=zN6Z3KwI;6FiLUzj9JNdeM?+R9yIU~?~*2D}-0KHNY zY9W(Ek0uRSSYP{6tuf7H)`18wdOrlsdcZ6{6USEy+}1M^8ZE3`j%2f|O}~LwW^N*9 zjG7?WecBv4Od`B1iLQ>nPLQ!v+1x!Y1tM6@m8E`yxZ`Tvul~K9b~)~_bGsJg^!sN5 zcdR)`WE&>84IAL8Kzb6IxYI6}mK11JuD`b5!!O69B3`k)t0S_!@c=eUx@G&eso(%> zHgx#)onv#M&zG)Sxf#&_y#sX##+WQ_(el|V`1lIDX)%x&g76S7H+`751N;6JKi3OY z?E|xPPEx5J-6%(_;l%#sV4}FVSm(Y{>xZ7tR{ztX7Gik^`TS|TftHfW_=2$!kQSR> zUsoDq)rry}V5i&Bo+HD_tWRrVf%}YG1#sg_N=sRTZ53!v%k317>J${`?O4X0k#5xh zKdyqX$E3oLxSjLn8AG{kopSg8N%F+|A?wh;dMP4udhi0AG8@;P;%LvR_~qDQI2NHb zwAid;OR|fyt3z1EfPePno4p?r(8Z~@ApHve6{eSEXcm;wSH^@_s2q_`e6Hr zT4=rEq?XMg{@>B>b0|0S1a|mhF1G$rq3yIR3ud(RaiJp`yG1cNUx)kXzu~#~Si)&% z3t;#c5LLrGS>gsS1LRG4N}S{C@`mx_sSZBx`I~fnJLj>W&lBxu)M82TiOxDRM%1o$JzNJXEN;VxIiY9rq-{ z@C{zCx=Y%Lw#39>M)N^9O@%v0h5Ie6GU@_hPC+(kS*;j%8H-M5plmOyYb)Xa&%f;g z+eykM4xkiZ1##_4cjeBUSu}hS)a>sE%q)>pemfbhE7BEbr+AcoFY@z&PcXDBkDgX_U;8vMM3T9y+X7w7Vv z?eOGXg|6M~*(ldn^R6HC`rB~nKA*lfqUy?_uj?s>CM_XRBJ1et1UiH-mt~0&o3|Z% zxT^k*Wi#!jd(SDo@IC>evYlnjiwB1V}ceL7$lo!yz#QABo^k;KK6|4{vtWhWX&zF+4{1_%`dTuJy@YY$SJ@ju(aIFqNKC^i)8$BM zqAIk^zE<83#XYXZYiE<7eeVW24zN$mOm+;kdE8(yZ+Usn>YOMR$%|L?_=W~4X?&IE zJ~qHd^JluNQ1%o2nO<;wUXOL!gtEB_5D!@si((H+@)wlf$O?S!#qfloAfz!B3{Ir! z0of4`vSJFOg4r_pg)J@)SiYyBFJQ?(4{-UBqFOr>nGhL82V0IOoSY}xoV6*EW1Gs) zakXTMZH&=0^ApL5o4t{fe6upngIAyzSKBw6@~k0Gy|h}ITwE{n;OB4IYzP(RRzL+zU9YNi1_LKg}iiGrHkm#s$xQKyki zgMo)DAG?kl1dlI*6^$P+)(!_h=C_tlmf%TrYdhi09Gdky`8br8C6P=~33g>64gDI0 zE`$t2e8MC5p#jJm;nVW!0$Ar=P}+Rn8X@-64OE*_!dpI+PryJ+RWfl61xtmtc2^ z?l8pEC^1r-O2U&4^IxSIQpdwL_5i`2OB0PJ4scyK`>}c^Tcyr$Pv<4n*_lgU*LaVD z+wi3L{;z9`G!N?R=bU$!(Q&1suOqy{<1Tw{*P_9%ikDBuH+yj64{&NM7xM&0J}34X zt}S%m74VBlU27Q;u5rc0@xKIAzY5Y1+r@TpmRWi|GoUWC)!(_d3J3`V);!IU(dv}I zu6e-QQA0Fm1bmkY=n28rVQQ?H%)?URws%=2ZtU@eu&pxeYMpm`*L;Ev3gs9+^RWNP zclxr#Ir5q#{GR?>yw3psVPhQkQ|vx0DUxm22am~Re&fJz3a(6CK9UXvjRx*_*XG_0 zvrn-H;-(h9-Q+oJDju(aRMcRM@9Ohu9`)Q#^J5Kw~d+DVE4?b7CN~+-4 zeW35*OJrURduCcKQ_EZz&FSo5UK&oS&DFMUR%T=y06K%R`0RtW4AymD=7w@Dtmh1m`UA=Xz?Ger}TGKz}F0VfeLB=zZXDEu;D*US`N2PlGP^b$nw5S zq-@t)L-J~Kj3JpL_=R^f-@M}bJCO)fXrOJ_asoT1O0ssBX0>ShR}Fbb*)5QYk^y++ z=W7Mlv@8C(XjowIPfcy!x`CtoU$~qCpW=ARi&&CzPj$}{yc-B<8mzCbB{UYR zOZ7T+6L`x^D(Zu)iW)6>nkK~8^J}5Fd@hs1Yi)z7*k;zc2^dwEGW+SkN3k}VkVPnC z2|q6E7c~}QtwvBuH^WXwQL)SLYjB+#f)NkfKr!@I4SDopd$$j~3D@X2)I`WEp*s;c zH246P?dD$FS-u1`N}bafaHsmumDx+b)Of2hqSz$#yW3qOZ9Lu+4NuBBJ!g*rT_E?) z`0QLGluOKTmV1q{8JJOCpM#rk_n?|x!|Rhl2IS@&TBGw|#lfK!;TZb#UA!IA%kj4J zV3)DT0D<>iKu^_@EJS`V7rkWpsXKOA;|>SdsmX3o0Q3tf)NW}(`JpWV#re4^1qs~R z&Y?UuG?P^PJS>cFOZ-mhuQpyqkCKHxf?8s*Wh>S zho5D0{|Hgv(MiF{G$`McaPXZo|3Kns$pan3rL~OnYo!U+OH$C86ICYv>BB<gdmPQ%yp`@u z@DW;rbomm?9f4a3?$!f_N$$@4iK;2}KaN@YkLYH)cldW)>Yx{;{kJFUoqtF9%ye!$ zRcvCk6{ks)Qsgt8jMpt@o7o~Vc7qe0snfKGZX+`)Q$oYNHDXt~=qHWvuoY9pHxX18 z=bKSMKk9HNMirx=Q#!M>k%aQfks&Ug_oh9gOJ$s)tG)J7hK^i;1kt=wfBO_l2Wr8p z^d>Td4$I}$nK9ahEHv9d3s%?h3sHq#TIU68M8YnCmZFrp_4onHar)qT2yH#YE|zf1 zh-G9>xM7_PVKzpH(JS4?6=UWT{U7;!q);al?`=gVP^Ggj z-&RTX?}p#J7q-oaux{+4431ypn@ZQ~47fJ&E~bWg^O)Q%1blz(s5b)W6aPSS`ZZ>b zS5IyrysoY07+X>OTzx5xEv%HeYSyDplsGG@UBi%JZlou7bGY`Cg8lwW%t2ER*@ik*y z0S4FH_OwWyKM^*pr=Zd7ibk#*oJIfEn4F5X-Q_VnqVinFGaHu z{j39N+cM}JVNVCG)Al35dt{IY{Z#UyR+9G2O0+k%9kfT{^3#Eja~K(y>QTNAq~W6g zMj+S62$a;{kO#zJ^_q=wt@+WZLoA?E#9l1v>5!^ETx6NwdOmn8m$;vRmCFfEN-t)vZP%ij^92sN^>M(XS<0D zUnl=dyq5!}8ltV_4q<7uDspw!pZHl&zi8LGG=pQ^_k*%p|Cw`xwrxJDd6Cn{_gn$R zU3QQvpkm~J)xQn36>nD;#icfEbU8r0dt-72r=gi78qDM?moGgJNyo7}wE5fhm(? zasn%Z5`1{?95kkFOqdnP}_y=mjtBl2DgF816hWy z9^pp$AVU;zM4X`-v%vJL%pyFW_g4*e!87M4%ccrbXXfL!$E8CRRc%}U-7qV=K?mYGMeySqx;uykeq?f_h zisNtk{gn{ywCLkI`!zx88W|NF);el)wbS1xL<}-2+I88qA}Enf)Sd_q$-*t`rv{Dj zX#Z!(#D202LXx7(WQcalh}3ONp#xJ>(CD*XW!lQ!n8K{*KDJy8-^c~j3WHcqZ>LL_ z)%s4=D7XzqzL$NQ=r3U5nk-7xrM-6yCn zd^3hrQJm_R0WZ*xdJY)btaExbH0j4x{^RCKckn@NIPSX+Y8I|Wv0FOxjBo;+t!&X< zc)eL4n!8K_7Gkpy&^`Q8`%x0GY~Cyb$&qwTeGe31pl&%&JEMr5`6= z^$-glFcgvlx=NGy?O4oFbVQhn>RjCeeRKSkvrui~3GEw$JbP&w4=oLn#@u3(qn8|` zU%dhE>KYhp0a5t5tB;##nylA62V3cU)$@GK!=A>;%s1PFN$%>bP*nHo7$B4SirZ&P zpE;Usmq($&9EJw-fGn3pcRbzomjDMnVgmcFGUinDr;q5f(hZ%>*W`GI#0;o z;4)9AFV=*z5a2mRPUUsf*Ez$Y-B<%mI&-T|tlF~x0~T6~fJULC`evyk;%3gkaX|vL zptC*$K~?Ofurm~2Lx3dmd2nw~6CB@otN1u0SQ5n3`qtwV($7QFYH34M_xj-=+g8cR zAFCP6L;`TrXpm=)5Vnx*McX>uIXTK#KF}erZbOC^zY|f6>=10@bb@!h`rOONG{KmG zYYBM2-Ed27AdfK}JI(EU$MS@e{_Qe^(&s2U1&r=(a_*C9>Tp?WKqOeW@Yraa7XTM0 z($`zH<1QRZ8GoPEn@NlS+=hQR#ga3(j`V%jWtybBWqz_NTkitl(}`jAO;SI2t!!+Q zktS|i;i5Hz0nYl&PaY1}X5ZE*A%nmXm?@%i9U+@IXJk0z@`Wb;9FL|@?kx#!e$eqhPh5hiU| ziE5r1$o@#Xr0z?%)7+b3n{?ZEO24<-K%DF{Rh+>_=&AtDP z=DO9aF%hC$sgIshx@`FMPfN_j}oWzb5SNWMvV%J!Lv6{I=R1^dn`zLTG{sk ze_KPrD|6TSLs3t&_zD7wkSgfbAN&#cHt5+5Y!*)Hw@+hG2q$bsG}bRy$8xt?AFZ@sY39tX zn5PfY6d%ZFD4(yG(doGY8njlQNN(FHnsbsoZ}!R9t20y7f*2LCmlzwFWA`~%us?H< z6fBD<>=*1kXRZQ^8_p#`)8@Im?=Nu@+}@13t%1cUQ+Gt(5Tc9t85HyNfWb%zHr;N{ zwz`#Hj#ewbD2LkgDqFxj(1}6|lRoQ4uG3hM)gDBaWeSkgh2B~`OlCeSeSPFj^6M4U z_CxQF9Y@)WjXWRvou6}p`rU<>Nv6q~ zY&&gpF4Kf53>%ozwtlac`ueQnjxxUl5fip<&nFR$-AqqVJtmb{v^j3^4QKze{C&j_ z&eF0vC(Dp?Ud-gdnDAz^#LyeStL@SwLp2bkCTs$2ngxX%iK+$J>Dt*aj3nry0OrRh zQS>D}q@^&sPrqHYZf@r6)j#=K$BzrbyLncq)cv^CN`-1(Gc(NkflI4Tf_Lo>3@e*l z%q3xTAQW2m`LnIkqq6IQA3`e4t4nY72{!Ov3Zfiq7Dv&+JYq1?_1ZseBs|3Rc6{$~DIM`uky{*Ztlv!}P*BhWWmQSJRCH{K`(A z!d*7P$pSm-s6{8m;r8CyNYxh|Ciio*v$K^O<}UY3sxYFc{$8->%jyu#Yb|gt1E~9| zSs#i2VpG1U@`t~d4+gx`T6s2ynIKMT1^e9NF0br3|HG(c=U<;TFl{Yz;wza=4xELI z$dOBCh=c5A(%IC8Z~+Rs=(5CS)9RH)Ww7SLIuFb6W-k+2rHbYKVZmSs^aI&7K+XvB z-1DOgYf<^3P<-H!tHhbd73_Mm`Cu5eA)LU-Z=mzJ&}H(6)($z&5C(QIe>V^VwGr_= zG84Zr=BLQ9f$!|1Fikv*!xOH)ut++6bOen>+rLs*d@K%(Lm?@mFmJ#i_w*x34Jhg zI!7}s=z4`NziDR+m3-?=<1A>c;wt_M_#5FicmuVWra`-oyxyP5pH708x4Yg-n}n-X zJg(Y9&xbG7Gb5BL`uCS~jJ9p>1+xTH5$8K8S(V4#v)95E)sv&#%RXb`Og;VBv zmQ(+-kZG;(`K)oH)>p})5&5Myy}sHZi%+LtZ#hIDBdXVy=&w3-gT5X_x{3OT@npZ% zsc4=T5zE0Mo$9~i-Bi_a?{uzT0#c7BYPv~nZvwSHG@~{vSd)smc9<4V#=ykN@J<%q zuRIL3lIpC9+opo&O(d>Woj;7|qj=Xsx(oOeyb`zf0B0oYsANZJ*N?FgIIrn?nqLcs zl2dl#WAcos{CfF6=h!-cVgj@N_|@E~P8$T+Vx!f(8H4K^WRy#m$9*UpWM;lxR~{|l zY7v8cC|Tu6Z*rw`YD+8nmeTI}T*p!;5f&D0_3ZOvec4}js;k#H%>q{En@&4k623cWj5s#Pdtvjsf@&6DIKh|C7$VD8sex!H%E&rm zwmyZ`bkdHrbcD8RO0}#vftmRPM^&hnu}`C1-WF*yeF`7w1(iX$SJYWRNiL=Tot5P zE$-1Sq{HC+xfyaX&QQVKSa=oGA~#Xqk%qraF{$^B&S2ZPY{}GD#0Im|?Vl>|2A61r zBfI(>5=k&W4;R@o4L%zDq%buq7_|C)%Pz{XF>mb6O7HzGED> zL7`tzLK(tpprdL0wYuwvQXV^pRmAKD6o=wJ|Cx|b%U1z!|5^ZEB$DleDy(4qiuKcp zLlfvdx~@nA$vCz2q#m=+>&$>w^VWnqIz;6*^ky4IeLLdu8&x+vhS{j3XS3B@FF>Cr zlG#h%m{jSaWPCyPyRoK^uh^l^?!?buzDxksuWWB!1)woD|J=|0xzvT8P$R3G#&Yu_ zn7b@*b4J5c`WBbTc)zO_$D5)vz}41l6{j-fN8!Ui{V%IZqGGXY!T2_q&ozT-#{$Zx zBG1^&%UBEOn}<1EOr}FGVKy7+l%3&ZFAn|ZTPrOz?H>=}9jW);!1$tcpj7?ul-nC6 zB{o}opx1yB7+{3x4c{dTxHhJyx_Kr=`fS7>mSM|f((J*#kqy7%h_=5YN4b+uJlVzC ze8BL#>!>-zli!+t|1-JNJs%$NqZmhiYfZ0f7QSnoonzPa7`L8P-Y~=1TV*UhPXV;_ z4vfy*e=E90DPmMn-9=o%A-!9^g z#gWt$r%4Kb-=Of596gu2bj+oW|cGb80}7vtJXH1dOpe8 zzGybM`jgK# z3RF8mi11S(NLdqYxU=ljS=W8&#sL-HLM^TM8^@KBpBMEY*uSGpFO(ToOB$A1xXR7# z!|IW#&~8W5hLWYYdOrLzCuYR0FdD%?I)J|dW2uD3bJ&0OrDHjdIbNJ?*uRhViGN7E zYokSC6Dpm6|H#cu8oJ;=9C!f1-0Ezienx8O(x8GH}H_LusPhD3$_Y&dUrS8dYuGMxA z`bM{gis*U$LV*Tr;5&m&4L|tj*>J{cgAW;&lPgC;Ij_}x<`x9KfJnjsdoP%ob6(%e za(m>OU1al(kcdzB=5lOLNq$`RC^iHYwEua~v`Ui~`D87cDRg660A)09n5?D@@}K!N z0)0B?>OZ12kqhn8Jbi6*Cb@&EyfH*@S9);#^mC&*g(u1%ITB9{i#Zk<*r%7O)sp}V zFa#NEgoGOGg^l3DKq{F%Mdnt-mZ(GJ{2d0ejP0mLd93AjHMeY0zsOJ!1d-_+E9m!# zvy&N~U>brmpO`JEr}=|1_UgV$jJwa=$Ad`+>}R5$wv+Bdq1dsrtt%+P&6;TdO{`<6 zHdm)7!oEiU7rNhb7qsU4^Oq``(L{I|f$HGs`F@#q>jJ<1x&ECope7rxhZg|G#-9J5 zu~8En)DgySZ6T5&(QaNyGr1O@Qdi;_Ys2%G$ysEvxWpVwWvEv$TSDCLvh_pSsC0$W zGKs=+wAF0Q`}u;bFI$x-QZzw!m*E^)Nf5IGE5$OqrZA`+3nji8vN?I z8Qs0-H^8n;c-3Oj*`{N1V#4Oth<=v&eZiLDvtF6O`!o9dqHX`<;)l-{EFV| z9Isx|pM@I`y3lFTZq-Q(2x50{#I^*kJCn4Bok9$i{4+Z93=G?g+MCOqu|x zzQw>s{d#+|@VEMnBZI$BU8-;4TB7yrcnlA0s0y$7E+SDE5@4p+6({Sih2787$$9XT zWmJVcg5eP->9V4P2fv*DH%mWc?wQ`)2hPyJ8FLZ~*|Duc6r_)fNXx83qCb2(C?{S1 zGr})j{Y!TDO1V@7s+<5jHb-rBm^D(?gdp!a>OvIgGgG~o-I%U_t^V&s1f_;osrWI_ z|LCTY>K>Ik*fji&|4Alt)hx&aJ!nfcS!M1^s{4$-jm1r4`T<+-ymISVyc#^lDA9rx_Ie9@b3e(LN{E!411{za{Nr#wj#w>j%7&}oiFE34 zNH2fW+5pxjNH?NBafN!3zNyl~ShKP9G!E;iBPzH`3w0(Ub>YT}y&lHD=$-E1uXw6D zP_+m1c89++-neH^QaZV&ed3m@i~0{1_R^T1~yzC3^d^rOJ< zY4JlO(`!)%@9v_iI&IeV)~+ZUhmP$!q(~mLWZs2z>JJ9MGV4~k5|0u&%5R;>F*(|Z z1rE`kz32Q|+1aW|fjQ-lem*vDdqbuG$+yI&dicRmi6pbfl6~bX_lb_OTwdvFh!a5x z!y&yVL|`kU%G;WU>H#lpNI)GknfH8*H2Q(&r^SXlh68mKZ_MHP9|M*&j>7$S=VQtu z8nQboe@YJRo3Q zaOmHde8-8>ze$>_#WHk{4ViSJs8OFQsn(U}b=QNLflS5&B3DsiOBz*=)zm{+ra6Rk zG=TH}ygfgytqf!I4VfBUDP6aUM=R*wU_;|$Xsh%&S;UsW{A!X}x)k(f9zP zi&{+z(MC@(7c<(G4f=m5%B1h?wABApE7A?VUR10~1U!j~d*vPrH>l;yM+W3Nj-{oA zC%w#-lYbyr`6|icp$s#`3uvCRxm`|l83T5B$K^JxN4vbmEd1!Lfi|!GCw%4W%4j&v zWJrgnJ+JMs;=pEO91)RN-?QY{M-;I;XBPS@u{o2$Ikw2r~LnU0WPOyHWFkgryZs3^$?WUrl&h=fYXYEu_u3* znk`js6IZ05!-ZZqZd&pbeCnV#5FyknI%j)Qd}FJpuvqi zO&6;SXm-h}JuDpv&l)3qY@Y<=o|GTPVKhSwjqlM+sIq+9V?1dHFQ-lPb0ClpmUz?Gn5=ar1VkdG5(?vp}9o#feG@UL+%%3#BmG@IO1x9>K@h{6lw`&h`-Ghm`vfK~v|0v} z`q%Q8&fCpm`^x?kZ7HW)A+~OK-872PGPqgA_qLPClu}aPJteYrq^};; z?toT_1ku1fMQ8mTp5tU%2#7wNNq|+oeNDPs+evdL2Js47DSb1z@G`mHE<5D9=9QZ_ zScpK7hM@O$*!+7Db4bzKL?ZdE5$(r#D&gqk{y4!v%RlD~+C(J@%MBSBNn^`vzsEjo zX7K#3oIFgs``Mp|mMa5}p=f+tD(pjQ}7u<7fkbc~KpRZPF=j|wn6|JMw zhKo$1M9FiQ=f`icvfI%Rx@SR$bMHZ$E=`;^dI-NVj7FSd4aaSa#Gg*bRB+^%5{xE@ z0jbD}*{_G^Hj5$jywNJs@E?whXy|JrT-(vRMw-dn<3x&ubxsoT6g)CFR0hUSZWXCN z4}QdxAKx+L_Jpc)ACf=rhZ-D-)9VOv1{5Z<2^X8chw1FtDB4_u}k?F3C_@ebC)HM65|(KOyN3yFzvZ4TVZf8z6s_z~8G%xsRQoNVvjtr2-1yZXRM z^H8hoKCYBsUwhb=k-6=rz}0nyM)%jort_)puKu%?&_ssx2}TIDWB=I$twJCM28M65 zsg=rS1DLe!Moh{RIvUs?XX^*SRUiT526!0X!m3NfmMsFUn&9gBqr&OH8S<>q_hG5{ zK&Anyyq*!U@naVnc1}0~7nb2cu=FcjE1kjy3xVL}D|9mdw5fIZ^fqkk>GI{&zr8*r zwN8i>dt4otVG#O8uTNzp*6sP2Ex%4?n#J4+wr5TPUb%b0e^7?rT$f`yILiv}d`z!e zY^ruR5^A_^Bhf-{xGrB*N`|p=51Qm9X*J2K`xntve{%8S94v}#sg;zmO)L7>`KDZv zUdAxC%%Q8K*Ut^bz>hm-F+yX&=!pb-N0AS~ytJrRAX1-!Fm07}7gX1tmtXOkdy7M3 zhqU?nRVCO>)1iC0c0k5Mp;w#o^3Syd@BBL!Cy_>+zi21WU)p7t_WMw8G9KOeinHjP zg%tr(g)m%x>%Z@H220dYWQuTd3=;cROt&f3WX@6!`Mc`CTqL{89NJxz1rdmvtoM$u zT(sF0uwsOeeCyOnHp@ugO1UGWU_-Ssn(U3$(|;3kz|xg4Z$**{1OqVmI4dq}E5sUv zglTQzR>FMd4b7hiGZySxZ zntU!v+uFT=qD~?>*fLO!DEK{8wQE7TZME+eXXW+9g(uWE=xB-#4ciDw#A*n+Z4mFj~G z$q`h<%NI|4J~h{%SVPGRu{uiBRWrH&S;yYG`si0{6`df!%~5o%LS`C`wKL~I>&a?r z!|zHE6_U{I{<;!vBJGHgNvvS}tkcbL@N2q|!BLP7y@FzfTln1n7~$32Uw9W%zujG<)zj4RQI{(_n6tyz)l2Z^}uA?6v!M8RX7p6qB-Z5H( z)QU^BHa0PFv3kBmwp60tPr7;lMRd#R6=e{NpYDe2kn_sC0J*eLZ2v?CW?grE{Tq$%oNOeXoqo`KB+v zXkMVHq4JVBed^oY(KpXvxP}{QO<+xihv)Db6cKnZQ6&Lm3nD*2uEVuOu4TVmlzHQM zNF#uJQgtk@U7fM3|7~4KS4Cv#26>39L+EkL3PL@1GgS~kd|7sh;YGA%{I;7?zk6^+*n({;DRbaT|c0t{goj23Er&*jVlRmiPt9 zy?cxz|8X$_@_}C>;8ttyhcHGAO=LhCo$d4{1Q$ahd-Bz(A^sPJi!Q~fc0@x=rXb0_ zmBGKh0q?=rKVPg~Rmd;jA1<;m{eJHtrALFjUtdbEfB1SA zgl53d?TyQIbT&rdcqDB&(r|r?<=H~$(llY2W;I9Az&J*T&RzHDL2icWKGyT5;)$X^ zxuW1e8r|ab9>E)U9|;I+-a?CdZ}wM$hVMR?)bwBLG$jvOH_awK@|{G-q2hC&nU8aH z$#Ij4_J51v)2XNmYuz;EcpsE!K0VOgr*CL3k$s^WL&S4UOuwr=4qjB!rKQBBwwFL& zf14go++$b+k*P+sp3g3F5sGZ12gsVVb+iv$0rMW>R_;UikDId+nc+tvC~; z5$?C!0Z|LlRBk<^TPDX+jarpp?147}GX)f$!};$RrE6#$LZ9C!Clbdzk;$;2L3i!> zMUoR6qy1B;&ZF`Qo|M9>3lhJe+UYwn{4;=1vm-y;56DAP@qJG^ORBEbRomyDy;&aR z@M>>fWa`Wf{6)-c9-Xn0WpFywkm1rH0{S#9omx%AJ8NGU-RWvP&NGGb3lt_p30g*4SZN^` z@|u3>t5<%(N%+wUdItC|nS)YLmcd~KMedS=lH!92f4mp-eNeeMP4;=VM``k7U{ zHd-CR@|iA)>BA>fpxmw~>e9b4XOg&)Fc&EKEt@Op^UPk6%9P2WVp7pjbHw2ArRh@M55}~fE@E%Vn81`+PNsRmx_e@tB0&~ zFjR~sT=+Qg6s-y2MFUcv5iXl~vuL1xgn_}rM zY53*0Q=K4hQ$l#<=70vZTTJgMP7^Bpu(tk`oDg}1y6iUE;=&>CpU`bMeQTvOSd&*Z zq$%iiPc1{WDHrDw6Ul>LWAx3r+`wNyG~DSIv&qd#`rYlq0|a%7{O6~H9$mXE&AHSQ zaL@-T!}*I_$wvPw-*pm^yv1@D=ML7R9VEA~bLMPx+TF>O%5Eh8z+WN&Gsd4}Ta zR1#i`VMkURs9kSuY8-Q@$gCcFm)x-}D3+&sQ@s)T_Low*opb5)xjuNhS5%4)9uwxt z)GHdZHI4v?*3whLF=`aW-hYXD*Q9K{2(H${Q-If$j$D&F;jdtngm*f@+R29b-nOjj z<4%Z@mB$3VxFLSrB3ufyWW|aY0;pr#@Fx_iR#{uYN5M;5#A8e3G0-PuosbDIXc|0l zD<6AVfg$V_GLQ6nN)_@dJ+gK_V%)tOh5iLO*$^30K^X(@Az7p869&zR5?#tR*Ys)X zEJkGgFf3bi5U%kRUZQJmY@C{&)&u&%7Nei^4GI$VV9k=(u)`Ksu~ z&YXcD6`G&vU36R(5IL-_c!s657{UE&44d(!9}qsV1A=3DjoaHK-#d~EP>l`?rE}L` z!!&*E*aNtAu2*%Y5!>KeCVA6fWwW_w6`?QL*1SnW`qvuDk-?+)bz<5TZ_VH3sgAre z?t6>_`4#)?O}Rk!{5w)EZO-k1YN~XWQmm1|vznd($FHe+X|xG5CFF8LP@9koc=KY0(xjLYaXRo(MNx_egs zBmwyvbFEVv&~TzQ0Aq%aMNNaqJ3vJ;DA8VOY7;vVp#5B!pdQJe0lnNE^gaWdt0f6BhPU%4%7Cg_>QHKA%w+ zGs0qOM8oILwl5?KecgX^0FRrG2A zYW;rIt!o=wcMie%_S>C`Z;;vfsRbeD!GC;mT8$%z*fxIYIvZzg%?|(c09xDzGc4<-l?ZWtBbUhTJZjp z-D=dyk6FJ^vSg||fzTEkl$*@>=dXnO>EwN_06_9@SR$7qSuXA=Ff5gG#&sD&aiTT< zl~cL%?83zMz@74KCcA*HYL_9rS4#k$qT18qH)W1a*1?bau~=;aCX%(?gCised>##A zjAAu9TQ^@ySSAdBALFpI4F32_YS zFezVpzQuP7UwUrAaTui~ZCpFA>zD`+pdBfW<1v2~%%ActVP=E?qHQGCz0wo*q1jk5 z$l|7hj&zW1K0y84*&X${4NZ{d5(rM`2ye`nU}u3EZjx(l^8Le6mdR*BctVyUCIY8@ zgXtLduvMFSdZx;7D-@FLMoxZlKV8*ZI1>ST=pfr%egm*EuMrGv`}YUp@IaE6%iRS^ znn)qm%sL)`xKp#xoC~VJ2f%2_YsKz5+s8byhEV(CC7AS&RKJru8#wbr5&W?g;u31R z)~PkE-G%@uFbBmu4Ms*ti1z^!)*o_GNhFp9gr$Xne zqgk5yF1BuOtam!d4uxIHy!mSg7#KEif)dZVwWqfdlboM~RZ%98g@fB|3OvwmKPu?k z5*eTvhop&@lQcLq)@x@^FetBea%gx|zyxa6@eX1Cqh;S zI~~x(Jlgny6OOC$Q{PI98Z>`dGqG878gl|h)NCkPnpT;D#RzFYbL|s}b*^9WFO9l6 zXcfM-RpuP6L{-I2%;$!_Z_qBTPE?FBL<@1)9d%mo2nXnpt({#l-J|TW2UD6+GFcoo zFl-DMvi9HAu*N{j!HsRY4)xs0s01L6)Qq_Q^q~V&PmaklRIW_LFn9iyW~!;tOgzaJ zU2S&CV&d1K#$m$@M6{kV@}!bkKLqH+A>4?eIvL9I+szx{Jke_L(PeLea+=T z|51UmJfDo|1j6T=jF@cZFS9c<(H$!1>yc+g1x=LgY&*#K0vAfnNoTnHoGTF>vRiTU z=(Wy}5&O}vUcv0WnF@nPLJ@Q7AAX~!OvH+AGWZdnnn{#dZl>U@_93lco%@G|aN=&^ zVP%(&3-T;n;_euS3pjH9vyo~ULP77UC2*Om%AfB2N9TFMgGSpP;WL;s>RB5OYVrdL0ewHSX@_bO>dnA)1k_OSo``0B3R=JWj5=h%qW32x}ql_+8#F8ttf>z_34b=%L5 zH8tF-wYmy;>y8E>-uYSPX6L^dGzu?yQWuQ48uU+6fRY-z8alyNd&mX-Qg z?Tx1nMErRhju51aiQk2&+hzARb=@w7Z6h-fDD z2!LP4MeE9vFgM1YqglNQtdVD#Y8NfO6SnW2P5Y&aywPfCU3J|+$0q#g7%b@Z{9eO? z>iq1w4YKA4-1@?24&kkyCGQdA3Lj<@33U- zWGW1y^x8L8U-l(C?6>6c)6w2>=WtgZV}=PM#%{vb;to0#Y{g>}Y5Ko*g14w-T9R;Z zZ5IjH40cBT4e4HwvxjvHa;=9=B%Pq>PiqfWbyM}*>+lEH1rl7VAyb^r6*M*kw<3UW z<1=O7P`+(6L5(21bB%R=!ZEX_;YDCK{o?ERG#c9c#BFK0Bl$GA-K@ICTsyyUJ+X+o zw9w-St)ADp_8InmB2%x)D*r!PmLIEVjAP|oQeBc<)%xi3+I3>U|NP!8sooOD)4519 zt?2egVC?Ui52)3EG=F-=WN0;{03&H`P*(5gq6spfu?HoK3Tr%E6W{FpYreLd2Q|hX z#uIz)tLD_R=4n@@5;s#t_Z+JafLs;DL&$d*l-t6_`R!Bs(=Q2TF%>u2s0VN(xvIUj zOtr__ek}|Wc}sJxMA|1rEh`vT)orR721M0P%Z#;ZjlgPq2Axl&_~iRj4k6|a;u7wh z=Id2Jd?lKE&u{_7Tl0dM67@t$DZG?Kj8#^QBTj2(H;nN9FY~qR#>vF5@0XibEIp3M z#BY1xLc*Q`O!LkfnZB|3BbQnkU>o3&uxaP(1|h`iQl49$fOK|DW-5i~S5N66Hp``m zde&0XUn7Na@b6n@)$)#B3iL3CjSkg`pGvHDl=9qES089#jhJaA0*J8?3^)ki%IgHC zBr9w4mF{bG;7`38D`ca!wG|7JovKqBH}KD|Jy9g}uU@_CaNekRKbHGv)TBKMtNpfQ zh1?{0!%v3||5*3)xCb{kx5NwQYnC{24?(|%haUAJFBD6#ehubGYKVdxmz3DAT7mG7 zJPRa($nQ?KhSvo~Vw(iQEvez#V@n@`<-{pAsb2w%ZOo?0sLt<8yf}r#_=5*tU55!g z@9{F_&7U!*fP1lnZU52AKyU@|lP96gs^K~GZ9$$e-JhY|FSGS0uB>$(hK0i??D3+7 z=n$S2{~d~OKY7|k<{52*m2+5?8S17oIWX~=mB_gT+jCjt$Sw1l%r_73f7-XPOc<+6q7jpE(;4FPV@yeiKqub$1Wmjda%*8zA>oYJ-k@V{WM)O!FlEOq#dW|gN_ zX>EA24*e4+BP&;*2^85L((C(_Qgtq>Ubl|7?Gxl}8J}iY_kNO;w>IEo-P$wrBE&JS zBQX+kXG%KVu<%domlriPhd-m|AHz1`7-G;y^sT1<}r;9#U`uP!YOL(UeH#HUr(!UZGq3Z<_6AHs|sf)MQotZriUMS|Apnf2Pgou8 zhK?Tp07NI(0jnd;ILH9e;Lk`OtM90;DCPr_)b5=#sVH@d?soFU7=H(L%B)C-si>%U zt6xZrse;7!Wi!)h9;6UBCM&nccJ^CE8h$9QZ`8MG8E}sCK_j;ry5w7IEowx6A40eX z-<_2TdPKSO$ndt;5j6`=gEM35ZPL2+Ufd%7cv}js{xnGv&n+N(BRMYjrS7wl2m{NH zt5>n`Kj6Qe@3iMTG4r#9fz&yf2HB)7?!vc95we%|UV0oLXmx;jYfzBN8l=UTO?w%3 zf32yOW=8RMY>ar*f2BV_4WBiYb42{+-=+WE(d%W%Ig!^gZt|eO%o;S*nQCJ&{m{G5 zoyNJjUiw#+LW*l&0I-!rE>$K0wDwP8zvO~GSDb%9_pevc*UG4C-Qe65u^7y#o0xq! zF{`$IU@ZO8#R@zxBi;eq2mdkRk_)2!v|i%^#=d_EpP=*1<*Qqa^kzUifTIqtMIWcV z&yg0X|EwouV>`OiilGZ(yKg3T<&e?tq-01r$gZozEib4NaL~*@i6xZMoBB6%e(me& z5Vb}zXzIDSCe@P0$~shpbm5y)e=cS~nRtpPXEY6|&sZa=fR)3mVx#r7$?)TLCCnDsEil@Z@pGN?=cMFIbcy8QNiwes)sPqIBR-)3|X zKSxc2UE`JjL=ATAowt>1O%9W|J^IUKe>c?nTM4eG*#jM$j6B{LVJ^M9UrZQ6`<)vd zY}4FTx#6QBgJUJpxAHjbW}4+!6zu-)exe$|(SoF^*c`R9k@)G1W6&OeY@ol#)&TL^ zH+};&UH#66J>wr{TiWSd)b5H&Pa*809ZnuYkQCJ1eA#^4$l% z4{2(}@V@^1@2ZyVb~>SlY&{jxaR%Uuw&Ho`J{^<$!qHV9kxK1Z*|162BFOZ*%F(x*3+<~tcIM^9L~Ph z<~&HUY1qu?m#<`4K2jg2NXm_oaHV zVs25pAG((_Xzr3fkZ?K~tYSU7+_17p{mX}&^2<@DRkhn6wP4eF9RmhV#D<<--jGAa z4)Z=F-J=FR5O{PKY{{I8H_+Nxp%l5L2)%tx|EvA&z7~so-4fU=xf;_cCj8B~%t6V8 zeQ9z(=M4|x)r?&yAE#4NK#`MyVND8pi|5e7Le2gs+dT`h02;XKvs&MhrDx@887O*J zS^BIUDf=ud`-b#x8rz+Z#NO&}!Nc8(;=#Ff8l0lQQC1dRN{aJesPhZKBFWX2ZOax; zx*#%Pu+M7gnJdjc`71w-C}HNW*2mu_V#oa#WKXsDcr2jUXvivfTVk9polb+M3qA|| zr&x9El5SlZ-2oD+6ny5i4mH?(wNyrUHc7Mc{|=R-Th_98n8Pun*of_Tq8b#zB7(n2 zvJ*b?SUj|(F=#oulTE^{0hI;GQbi{}V~y0jIb3UV49Z;Y7_Yi3N@>k2na?aQ;vi%ojh7&RnoyaAs0*G-CSFmT*yAyHESoW!tI2iRB8~M4boY=3+$`d8J))(zMapf1s z+Og-`S~i!98mUsm9k=Ls&N1wMfcUPyHDOB&y65Ou6hJ3}IZAIFUsf5| zxl_TA<}K(}i6R6-T#UYyMkOY7qx9wseU(8B-&j<#ZEiTS=?YJ*`1kOU@XoICIEGm$ zbc=5rE*gA*W8pmu=;ic5h+St4x+>YGM?E!Myi>7TAZulL?Wb{Z^vw?m`Vdso#ry`V ztf}&4uMR9PlW*sIrsytZxUTQOA+oj}QrKYzjyVzz#t~@--P)$FgOh^4dmjk(PMgdM z%-5j8=m(DRolUqZ=!_Jf+Ti@+lWnB6O1-dRfuZ^Tpp(|Mn0k$Yng^FbjjxdnkUz1N zw~Il2IB7_s4PnV@Ew(A?ryUkM5dj}wv9VYYjR2{~LvES75H|Y~q zD(YCxmV3&(Dh5?HqW)X7VRj54Lg3btDqaQL1jj?brmm%aM@XMh!jFR6KyT6n=o-FJ zO}TdM@K0897)whHS?fJq#oeDtC21;`s6Xp$8hvj!O3SbJvxo7^@@T!Co!qnte674k z%5P0R7OmzG$^Qu^pSky3=_zh|MZnInaEOBA6unoa_bke~Kdo<_TD8zqA-Q~EYtFSE zvwTPV)2POQjPY9xH0tK@1K0oTqi=CeSSfd`Hnt^yurOv|pJXAGk4FrBo*HdTY-Fr= z0oL6HfIH=ob=lX*WAjg(rg}Rk7Vc~+0xytF^iYMQH`GhX+px#r>&~~j_Npc!)INnT$|h%_luAf|3?KqjJO!gQ)7 z;m->(pBAaa>ZJxi^-@|aptNrd{`oXEp0~puSOUMQ>MxOy_k~`;W4qglSx9AxR@!L) z1Y{uL_P^unI9dKh2igmyX{|$YtoR`5fM9S|Ul0N+GHujx5KK)Fo6+{Yr=#(S%zgeV z+$g#iQ{ycTQS~ftOX$#_pF!4XQ4@70iffbDIK52kL_Q_(Pm6O3c58Ke}z*em?{u9U+VJ+_GYuJrR|1}&1JC(S`HP1oOO*6U;2-%;}o zc~Qjm@&NuB6bYS9>`AwA0c-l3nMQGP{;pxy+5C@Rdka$4PT*Ofo-{dvb;=!Tq_fs2_^`RIA=)o;t?*$VZt$q z5176irEuvp1O*7fN&18jjx)8owB!R0JiiRuN#mky`-5q0|g*)<9Ympj1XvyB<$J@P{RASG)RI6Du>&)(B zMqbCU7))s!o1%+1CV>(}UyCq5`f^u$kG@ZgIl9OEToX|XQ~~P12cq=|wK-`Ti!ouo zn3SNgjQ%4~;w>oP*B(V{Bj{rq=`TzhY<404LhxSMncLQ}`}y}G1^H;DClp+0I`;Qf z-4DbXk>wv8urGxk!^Hs5^sQBX6Hs*~vd^g{9r>5ec6R!m8`?mz!u-Z%ZNuCYqH`qV z1~e5y-^Fu!9IFEAm|&}dLE7VT-+uG{^gtEfw#J`69b9hQHPojw9BblpEN2+D&z#UA zX&9IJ-a2IsO@Z2_!yJ?Ua#3l2e>B)@*VFzDX>4@a8Q!{=wu9Ph&!pbOb-d!mv~us# z%jdO@57LYGU=59NYwzWk>Y%Off6BvNvW_y)70Yi){8+WHHgkO@S$t2!@h7_)w|jJ? zJ_$98^D%dGR5_Yc+=Cm9-1s-`rBBt&*pr0BinEx7J;D}c5zYL~;LV__&0yg8+lNw8 zWAb57I}gYEP{f-Ef_=RP*xr4T*l9fNQy@s^*nc(_q&Rzq2?VFCzWR3MhnyqqLyy$| z{n+d*8sKBWSBD7gLj5^}=i3*Jjv7V6NUH~O<82lMUi$r;{23O9;W9YJA%KR1W?jss zF5=1T){bpCDLv&GLxars3(W@D!D(4kjXWlUI}8#se+7SNHJ)#jx}j$_$mIytg-c$& zNkVh8Kyi#j%|NF&rDUNhE@u72USRsZk9+YIi7MI>6&;|Z(}4zB-EFo#4n4L*BlA{y z2Mz~)V36azLU{G=`gK)o@zv(m_k@fQF=b1-G!Pi7SBSM#B7oMi{nP&A@>z#np?w># zQAnewK@=s%hZP3Ko2!dQ7%<^VtkSfn(&#|T_6D9T$2akOE7X>@e+5g2NUz&4!$GWA zZa2w2-AoaGR(C9ezQ7N+qrD^y9QLu1CIwt_x!InkXIP&?IPtdd4sXWx14NBJu(mE{ zNoFIuXFR#;t?8rHsaE}3vy24B6Z!|SNFy~XpN>Dy##AHgQ$F%{e&^cN+ttBgP3P2Q zOSX~R=}M9?!Wty20&{l};-;YUVOpu`U-~7E4kCNxTBfD*SXGLt~ z`Nuz~wXEDb=5B7S!3JzXNFD3i!_8xZWVQ7iMe1bhR$+e9CbAznr`0pNzb^c-fvLLT z?r9(z;6D>=p)m`|#~b%8gofKvihpXUauiLUnc}b6aJDs}`>Pdp!+}#1e5d(oYUO7Q z%}dQjLC3y`X&pJ~A~I4AdplkZdb>9|@6VS#TL10{rTiNOU0g%N67{JM=nlkh970FY zhP%+LuQoJ-qL}yC$QwYW&wp7y_dr2l#%7}R#iN^#8wyAUv%El!qwk81)8f%Jl}=Vp zP8B@d7rOWVuId!B-D5_jSbTv>|U>n5b;#I2<`F1l`+4u!O!W-zo)soaINfCLu~m3}c~uB`V%8!>%CdI2HkWaCF=Y z#6y2c(BXuF&$lELlE7-2{y2Uo@;4{k+plzjO2A2J&rN|{N*n{DYVS_6D=}>XQVLwo z<>xBE-fDTL9kyefVYcfD8&&bIMm`$E*-FUz0ztMl!sfRlI z0esg|iUM@5;hL))Ab#E#YIv7irKQtu(B>3mSf;NE!Ld|i4D~y+v+~_D%Y7_N@QxRG z(k18vuj8XzzVy>S43Xy2ge1u#uUa6r>Znoh57SiaFph{uKL;82-?ho#hx!UnEb_&p z*0xK|oZ-7fq5#!!R75ROk`>mnxNa|PpX}zk?;zx%dhoDM>xJyK=z(4sa7MNHyu{s! zD6;-knzYe&^Z(jBf%>GvA-5Fse7~sUU(|2XPOw%mEW$x0qeD66%#=w}m4J8?TI!E7 zWLavyNhM_&lX6p`N6}tmJ8!f{N8=X|Wk6iij6%`B_DLH=QX3bXF8tn{($bFQgI_?l z#=DFFu^Dw&V-QjNz)HI#*J}PrOrGdR{m6O&A@AG5Eg|LD!{ebR4cWVOT^=(HVF=;H zrRW;3BXOfcy5|n7n_mbx4sGWbJ^WoVLomsYF?)zkrJZj4A<8 zd?&-F%)|2T1u8=BA`jWms{*qtNDEFYlhZugj}Jy0HTAMTNLn%du8;GzLh2HJl5YN< zByFs^Gos5-c@TUtO}uLa`+ov>uz8BuryG?kSNT&7?n?HJFMsZ2DzD%QGX8z?p<1vPz>^c>?Uzp&i^%u70~%5w-!AvT&4OZDUD4yX-_ zeiKbs9Y@;8U;{e~94_yjG_D+^0#Rw(QZ9u{92*$t_c^5eb`0><{* zdJSefIzupR0HL}A!5x<|hg?@oKHMFcShBx8P@pTek0p~-FRh_kLp1XN=;`u3kF0>& zjr=J2oJyo16Elx1LgI^Zq#g$m2mrQIQS! zF0Y@AYZeXvN8zC13Tup*)P}h#l+7C~EYF7GgT?BV9a;u&!%fBrj}N4?t0wZbyyT+6 z)a5&~)%lg|f%$ox>&9U^ei?rlo=}AS2s_(YW3d$+2BitSMcPhg5#=|TjN8t+L>T8pF5gn1tdK`jp2ksKbBmm@Wh*mr$9tN zCTdktyTH8&rPnU|jZXa3rPY6z`F*v*1&og+e4v2W;i*ARS z1%WP5l8rt{G!#;SQm6qd*m)d~&-JrPci*3ITRcSLm=s8~H&OJ0=Bq1rDUx;0p zxB*6?Y#wWpTJ{Qi_cOM+|6JnO`c*mN?6s7VJF&ei>BH#sDgO^sUm4U^1FT(~qJ`pK zw73=b7AO>oySoN2Uc9(Nu>!@4JHg%EB@luXFYX%TJMX=7XTF*I%D*Hh&+b05dvX~} zr;KYSDFRBkukXTw6a_x!N}i~1KdT2F<>*+5pPD;il^?}R>A%^-#oP{w`i;J1<-ZW` z5Sbk4(an9BeM|J8IZz*CWv!wWa4@OdJX2|+IB>EB-O0=8hy6!z8LAD89VJD*y&t_` zGWf4CHQwi(wG7X49^m0SR#SodXjLvn+V4mho!&22*0*ZS_MQ>sv7;YzM}_O5`$&AT zar(GD1->_7@-NER%mdafF)Hr;>2#bRL-&lMd7|;pksgr>UeiYRIh|RAo>2H(A+rLs zR3^YtJEJ+goa+4&e-ilG}oo&$9+=BnH{Hj3I47;nriDPKjXEV z?fXMhMep=#VHd{ZYpc1`G10wOrAwnr>E~QlsggYEgU6bei=&ofS`D9}^<|&b+C@gw zvJDXgt5cB==OV_mrwS|etW)T9l8v}?`2Wdi>(Z2K$-DS5fVD`IHh=jCYj*HyHoh87 zK(4f1t2Gaci&Fv?mG%qOg~n0rf{w4TL^YBPP`_h~Y83SARE$@rd~O3t@Cl}4lZ{5n z3N*4R8GV~7d0WrvAGzRw@XAw1+so!Qy27~JE*QtO8NF`+Ul+gFD8C#jr04GOcWAc+CR-;4a~ml6>78751kWw#Po}}vG0R46!k6JFEMnf zrqr|hgH7~1)~Fin7f+Vf9wwT-e%_XlPPmrE z-d4iCnLEX(Sqv3i=XDS8vAs6|3sCE}$#U_p5=rHHBiX(`8stI+x45Hxxs+W=H6qlI zf>}IQtdeXhrk_9Z{0v2ZRFwUz@SZ0%{;l*YkbZj@(`h2^);thiMY&J)W7}^b$j!-X8iRAc5?%I;|GwR5db#SFo2W#=umt@4m6li zUEqeJ_~Tg9iV}7h^%$Ba$a{qtN=@y7a@~5*g6q1@L9^qQnDlVpUNV~ZwD&Y%nL1Re z(eU755!uS0@fmK68kP#BVmfS#BMn);_89gB80uy}-b20n_>mPoKR+;q$3OpB@3Du- z4dx#r6i@8A+x#Ef5Dp`gE8J=7KLJpqlO6DyRU~SInXz!w%!jIAK4w2_Xmpo58>Qk1 zwc?1NH+ya|Mfvy4;_M`{zp+T(s_fydzue(%(;UTeJtB5D7uPyQeeR|4*LsBTu8E7Qm-s>1#*`ZfeNBIu+9&x@AGrt_J6C$rMe!(MuDC+R>_dTgJ}afoSL#UY_F zYW3^+Pd70%BtK|LxNhC$wgtXxpolKkeKPWSEJK39s{aRD+CBou#m1 znI6!@25JU#tGMN46eosUOS=Pd9jO zAwKpG=Ie-%Z^Bq9|WGKVlU%=NhPTSC;>-&Z}Ni0JQ zDlTxdx6J=ZFt188k3L<=+}(ovm#BliD8x8LS-*T-2@O1_i#LiGp~>-VLoEx|MzQJ> z644rux*^m!PEOiv@dv1GK3+%6P>L{BpT0l`wI?0a+v_szO7qd@C$ZXJ4-+g-<1~jl zUgoG7L*F07w}%dvTvOR3cag+TfE7XtiSPwPXtjPd++N?dhRfUf>I+h+Q@C)#xp|8A z2(MWvnQxdZF#!iJBp|y5Z6r*fgw*h`=**|0L{)`Waz+%}!MCiFR zl`G;e281eNGJs>1tH%8H4D#A?)?CYT{w**fdPFC{y5i<^BI)b>cc1#V$bDmYooiEP z;@`?wR^TAQ+d_hVkL4#V?oLvgrWQ%t$%vri{Sg^PMn*wy;kVRXo#eVSNJlVlfoC#5 z@WAPDd-q6~2modHEqV(_(eiSKSU}Kjxomr$%G=`2ZIY2vm8usn-d}8d=okvCxIa+G1Rb=;?m@>AaTysZ&zfn9Dgw zxx^xeco>bK$`UZ=;Zo7HfdEA z@-P5fXKXpTb8TBeZ_sAxBwIzkZi$&PDiu7y=sZc+%)Rk1_2PE{&o@XO8(UW1opY4l zRU>`+&aAd~l2m2~Rh=rS6MXLNR?##%*3Yv;i2qYQqP7GSrjf@-(N5!5hN)9)4|T5# zB=lR9;154;R>xuL^?Srz*}Nocv|1iG1@n;y&_L(#jA)a}4N`Q^ppPe?fZ?hIP$6sp zi>3F^6=|CQiaA~B?IGKf7m~}Dg8)m%Nvq3V>e@F~X3|5&8?q+s%e~E*I-z03_T8dz zg5Eok;CNsosCbMn?&VIg%4w1b+s83NxrvYEh+90Mo4+FDcp=sJ&)W($c35HlN+D38 zdi*9Nu5Pknvly?YopZpG67qa9@1#|==$})$NM^oN>Cnib&?zw5*gSEFO!RACEeW;=L#Lt*XRV9bd0oG`f>RH*jJ4 zKQ91|r9z_!S}Lj z7YE2b+w-cQX6lgUVJuTc!jv^$nqhzc=#;s)?)OZVfeOAXnfJupExq<6Bl$%a5v2zn z+}T59zO9k z1~A0iC5`P(?WxA%FHDD|8`qtZSv(rEX)J4eQL~A;S>W$$ZMIl{7`5Ik z$6}d>HAoW$h!*hL4gqI2M&WZ^f6`!`=aR?bf^>M5-Z!glkC#pS7I?=enwPdRzEpgr z5^wpK%Tw72T;DUC`z>{fy|hx9kNR1fnFUin{`I{M0Yn#{9w^WeO;4XUjR#uqeiDaT zv#qGJ{AM~;16Jy=0(+Z+9&LM`*Vk@~+6N0gqIM9ZrjdpvzrT~<=6+74P&`SDLL$xS zM1ryAT#C!s<>e<#h}*uqWfm3|zVm!(%#eV;$lhOQb0o!ANa#*$4TvQg+B~P5yqKr> z(cZql7(x;A%|G^=p?!hDw%mDhu10`1%i44PnE}(g`u9o8=NY$nTDU+;&?Zt>8)b`n z)1E(A5>iSftt3AABpZYjP(yjUZI5JEC!g5mdhCA58~iwa`(GPc0w}3os7rVm~ zk3%Q~yTnlKG^;zlT_SBlsdb$4%ttYs2Do`%f@xkDKk7pBho?9Ko-L?_ovSV=C*yRt zi&5&nCc@NAUdCD_cKL}ncRVJ&x2N{aX9FVR)B%SXMf&tHuEZn99~DLK%OiucVbI0> znSkEaxp%TLxY}xpzO(pqQ!+I%un=NATl`+Zr>zAI!(vKjdk7^%#4pa#NBas^u&yBf z<|sg~%gB~xrFIzcdwBc@LNxzoG5;*F(i~1|OUUkLWFYKk5gv#+9YPy#@-kF#e5^Gr z7IkF&ahJFrQTQb|5QSx^3YYUmY~=fLxJ1+N=Y!>=9Q|!HnH>_jhNtuA+tW|LXh$dK zo9hHW^u$`PsuIzEI`;pqrbV;Las9%Eko(y%Zv)in6YxBcv=i4Bymv{+=Wua8OE!w> z&vXud7HL5=_UVn1a;Q_BGbds~nrk2i`R^oRv{JM_wC3iIX!?W?fVwjX2R#}RinSCl%gtn=#zvni6Y zp}!Z^hxU7+PU5``wNaYVDvbz4nSomM`3)#GvaI@x2i~E+IUgyW>3+Uqpg%abHbu2j z+TYUevos<4Reb%D^NetCN{u@7Bj=9VnZbt#f#hLD5o>45eCt^6T6EZ_gD}o`4}Z^O z=WzJKYrRr9Y@yuf+6S&-$PGyO9a5Gt-T(~k;%1SIGLAhaf)&|)#R?ncgP&~s%gJbo z#IySX=z}c=?Dc1Ug6$@@8ggI()?t8Ya@?M<@;&-&fy!*NrlMh>HqUP1q_dEr948i2Ns6RDzI z>;C)lzYv?|7iif%@4{F)zixwp?!6!nPw(_JCYw^W>^OS>j(JaCmV4DNeftTEw1#Mu zCJ&C|{BWIbP@f%>lq911C+j=e$Ns;6xwlOI62i6%jd`->k@<(x^|JEk zySLPNoL%7|F8FFLIOy(|741Zo>HjCHP4WcVle|dyI#E#$xv$^*lPU1Y8GvMhK}0=Y zk(n{*8C07aE%YyFVdf$(eYHn|iD{A9KWw*!G8B16wi$k7A^mpA65!1k$xItp?}Chs zje{wNw(gc#=sYYGeu8xC3ON$-)J-L6$9(SvK z+mFyI2!p6R^vX@lyQv?`RpYkTN7i3LhGxvgtE{E@2eJXleEKTwtze$87T{ofRHB00 zCU5sGQ!V-H=|{C%WAli(>V@7^0Io*o2V^B1O{{6S@q;rCIz~v?)WHQQrR3gnjj(V5@x%E@-ilb z-ohrUJK&m(=MUY7rr{k-P0;&cVh>uGSi??W&HTf#pOu578Nq!RR#DA-45YSPT1((pHCsQWz?0y$gTh*ry$A5Hno+6c9ui$W z@>n!SQ_F0rzj}jG$`lx9DmwwxGE&jfrq2emurgmx{&QMBnKZIuU_0XZx0yE4$cUzx3CtXr7Bx|_^ z?J}|t{qtYV7e>A*5M9`A=|qr>3#U;`&j5qX;f7f!h`k0C-A}OkmhaLo7LZ1gANYm z`Ik3eG!N_?c5=4za-%3ODh*{|hoc=$Upi9DbV#+!)ST2vKXD9BFKoovrQO{!;k9JE z-7;Va;cVl|b`AXXVuSnKIPG!U9KvltV^hav+`t`HEzTJb{e1G#Bvl71z>V09X6&HY zV_YOE1H2~*HH+k()CAm-y2WgnHw{1aXo-#w_u7_4cp7fx0=(+nj` zgd^7zvM}AZ@Vmq#NiqZcL=!(EGmthl2v>WEPh*lzPNpef$`l?|oN5lend4QNjc7sE z)IxSBD2sYmwu|Vf3fLT?nTqM`evBPRep6eXsSPb;k0P89eXt&lC$ zyN=#9y+10Rc+U%gGSOyku5}$m(^Ncx((jj;5;6%Ovw^>ly&Y7)OD2ewASi&o=o^g1 zM*W`Jtu^Ly!P&<$D>hDeNC;1Ud-a{An%C0!gM5JYx=rIRq@>v)Ar`q&E{PkAH+|VW z&L2Z7L@cENMK0q_v%2h+uIXsRGn!l^DOalP$o>@5i}$iQ)^O{FxL0(zL8-IBdC?VX z6YtLyPu7*73qL)Ke`^WP&a>UG7wS&_1o@4`tflR|Tl^=wtq~F)Q(le;o5kAJQG7{> z-a~{LBB{Hv-G!OOzKRiOm|6TTQTsr&c`p3x*Dq(JkjlX~V)mCypBU?;5)C$|5E?Zr z5AV-2^pvuNBYD}bcnlzoLnAxO_(BbXtVoSAa)(Adw7%v;#6BVhJT*m#!oaTi*lZNI zu6CS$E1CotCIuW;4ToHTe8i<&=$xC<4^2d#s z$%&IEn0S`<_1?(s1KGjJ45xQ>)X|!g961)X8q4x6vBQ(o?PW?RK~j@`$7TfUM<|pJ zcHwnXb9%Jar%n8-+S)MWi9xsCc)g?e=taMway-o8QtX2O^*ORVW!y7IP zZduRH@xVvqFO9SmGA8VK5I(`$%aDiGX`$#OZX!#RUId1;q;=-fU1W2J9{#>Hm%;mQ zFI2RwTn_OY)wTkqf0erwqrH;Co}1LkZ$5uU5ms)*$>wY$a4>Htz=zM>9k!wWklDNo z2RT%`)8$)<#p_(M`U%IM3b5HweEhsoH|yvWeYjwdX=qD5%HtphKRao6 znHa@R$Yh4HJ+A+!MG8Vke|cPgKjJbaGb6V39AB*?*?~SwOrQnML+h%t-!NDX!&=L4 zX{mozrk7+qAHuEKo$fJ0O4|PGqGH)V6SdlIaE-)dYTogC>l;Cm+7?(}=9fhB0E$yr zfoEyrhPP90x|A^-6}Pxge3Oyu9~*CFiRU@DpJUpW<;~7lZuUzF)&?B4nvULwRISNj zM3~MuN66qs9f0i8$Apx#w*NyFoG>(kL{oOe$I-ZmmF~9vqFHzxU0c_`Z5=-7j z^Q(}Sd~kY;g>|qp5`N+vHTAUl`sg&1%m9l-u=?Og<~FA1#ObsL%Je>qo0i6&9s64q z$X?RwbKI2xzMx+)s3ayOvp$ObT2;B+I)}G5XKuQW$C}67S3I+r%Oc^Jc!~4hlmf50 z`FQu^(ofXt(p%r*YYZ4S9mydDq0U#SKOcNMG%+k+JH-=7flNnf^pm7AZ6{RIzi&x8 zl&V2oWKc#srBc3kg~1^gfxp+M%mdb?!=ldfTQ6eSbPGn8SHEWrDZTkPDUU>|t+Q~6 z1gpE@6;BRme^c|7|6Z^lc#1#E1n6owoT9+iQ?7r1kYAfSn$-9|p#o{LJ+oCc0G&W~ zhCiA`BMOk26>bkT#~_zyqb&a4Xe7W`Y1RadGH=MEgEWc%{zx5`G132}i^QwpuHBKDH`t zY}Bl8s4RPbR-JbvWEQ9AQB6l1dd#Fw74Ym;g*87JRx`D{%ie(vsa|*f>R>58U7Ntd zo+vK8(1%TO^8R`~J@?&;e^K_3g7^H^w26RubHM}Ilu)#@vPbK2$5+s zoa@+jvWSS6QMv9t>lqrAX`Qign(^{A5*bcc_OA6+%U?+f4oF^*E&Fn7GZnTCdG|}& z>zGg6h^8~oFVDWgsF)3E9|>zjQ5)W>_)(RG^{$ywV4(JF;{4M=wGOncS8O87X4glX ze-$lBF-dFG;YSGm9JkFv`MI#Fv~mShQ(2GOw)}|+*kd!*q_vS7F}X=7AZ&OSLD<5!8_oM__}h^XP|5^PW%&o4G)U>d-773Y);hJK z8NDzFWsvSCLvos%ldp;J=`D2SfZ}xJ@>GTXZi9tNyOiy<>>gv-z`+qt@BpOUgvbmz zxR+Z%bRnJcueHaUWC3%FB zVmJqgL830%WcDKoj;uR+3>xoUf#EW~_jxZaeF=A@#4qXozUxwVJa?SeZX0L>{j_NA z^2Roq*!;2%2m#H}{j*oWM8nnBW_bR#dYZDz{!gRm@W#F3KYxmkY zF0zh%q9fO23i_^6vNY7=(%-yExy#Bi>R+smq`xaZ-|wr)w;rgIg0?bUU;06D?y(C zQWrQLFr4_T7kst&A>Db3gnoU0>*{sV=>=WeX8zY&UkJ@LCe@^r)J4zq=A9649kY_( z(kDlaCC(p`?!yrkQ3yO;*#&>eXU4FNRpEC9;#qXTy+R?qLP)n+QWwA96!D<}F|W@) zi{$1o9SlQjq@~_J+)lFpj=#+vcm&qDM$-bZ60p;=-%dMAzIm>f=uf@1&KXNhl*EM_ zkp1x?O5=zRwY6e`-IdkPCKt`MIEBDUUb5w%oRBh6YmEfGgLlNNza_NC3S=e7nG8Bt z1LA%J1X9Br@G3g$9}t$8wOj4M2)u0$k@d2aM7D`O ztt{+mzZnXxp+5AhP%gKzX10rVkXoy(2{55;V&QoKpj>+`*MILZW;NjaT@kEQSh(>= zS1e)M%%U0)^YEo~kx|jF7kt(j-Eu5lI$Y7~(yi9kHS`g`d14X~d^z^RigMxbf5gGJ zP177ZfY#XX0=3x)$iwB~aIx>Vitd+B-giGpcbGE%95^pxm`sJIj zHuMcF9!6!_I%}P6gUzHQ#Tx}8zdH%A-Jgnb5llrotCBfxtFN)tCxUS`<_}NS%7#|9Pj`E##I(}Qj zyI}q>BiwZM>Nb>b3lDQ-HX0pq#J&s_r zB1AB=!!lqv+OBjq^NpURuUmC;S!%=xD`!E}2#@bpxssbOsJiy>Zn9Z=-l`z^-=>EH z2t@09wnsur`tBVSYn#m!ww2t6KX~W&dj*5^E#QYckke}CU$4R~qzEq}clmq{&m!|i=y@9UjeH|RR?$Zo3PcDE?>R`+0PfYCKOQXK}n8t1&Mb_KmS9e;CFN&H&d{wYz61=xYcvntg11oJI0 zedSt7>uZqU<0*J*jXzU!$gEp19CkBU+8oaNZdfVmOEFKmQ%g31gKIhMrL|Ba!zsgc zNjShN91Le#kt)C}4VMNvndBBi9X^c9bHsuFe%oa6v7uQYQL?6&Dx2veeQPl!4Hd+^ znNtwUQkCLIZXCFEt)(UZxC&I|Z{I*1aBN}s1A6AMEeT44eqc{VhKSprRb=R!C1GM@ zC?+B_ci2eBi_`*4d$~pdd)`?4_j2UTU7Ry=6OF!%`mERTJ)DjJ47Vfa8!Q4KY305tvJ# zf(ihtq2Xp1!)tYJR~RocJJIeK?#6cz ze6koM#H%QmHpDC&Lg-UH;}dMhE*kS+JAXW z85w?F(oduHT;Gat!x`N126-+1IfHyN#~EkqT1=%~JooZ?rzu{&+a^A0dWeY?_j;20 zPV4HYrlTJ!=S<~sY=|z)hL60zC9c04@$UVFN3#9cUjYx(xN!$%BL$4=LJ>7+S#wN9 zyfusp>HVioPNh`KS=pS0FOM=KJaF@Bj?l71x1S9I-*q+F&&!jxV}|4vCvn*{74yr4 zxid1VK5i;A;nhy>`hM9|X2jFvy<}!Fy^gfFp9_wi_*!A(!{hUDnsT{&v>$nQlPUeT zXye&A=`vZg7ZLb*bjTWS^P#|yo^0+a`$)zRhx0e_DhY${Ok;CxZK;{QL8-kXr@6U# zlfjAe!MjQ$7A*25-@WC-5q_Bie_VLr^Y{s`lhD9X!~91N-+`><`=j_BKMZ>r$=$9! z05WvOkd6XA>_4@MADw0hli%cgg#EQdfVe&ZhdwBFBH&6?FBiITRJSf@F~ecJK$&e| z>-Jyn_ZO}w@Gp)(Qdye%rOID0$5fMQ)1bQ>?@E9g`%iN`rXdwsM*)%Ng)#iC)qoWo z0!0srp<>PXXrPSIqH`+sz5Q1ToNM9g~nGEy|u4Ha5|xEIkaW^KZULf>>RI3#nm zC{#t*eNrRkS{`pu;C!*@-zQ{ym&n77O88!1t*PA4g_|5I_V(n`4-p_CFWbD2it91z zYz#BM=S&i?F{Kf{uxUVfzq;nd(1u+5};p-Re(Xbi7Tw+wTmae?+37Xq6T<3U`x|#)z{X zTI3;^6F|2N*(7%qd)482o9NMJu<&Ln^%y*cS}}8&^SxYoQH$C)ClaJ>fg7${$C(ba z04=JjBs|XHSZX6&bY8=fYo*TNF~H;FtzGg)oM!21N6hUgeibbHQ<+tO^~hRr+e*gD zI__%m?eIj@w(p}&)}p?Wk&Va;-;T#~+lv?OHlx~z>ez8@P85l18n zbBJ``sJV~lj$RH!vhJ6nv0g?B(a+qU7r4f9Kv9zugMT*bG(SD5AlX0P(5m;mlT8-q z_7w78L>cto3pm(kpei^XlCauj3XpR*!9)9r5QOk0*VLA`20d6y0oZUKWcp0tvTq-8 z1SHMF{46IBC^BN5hn`>!MKNn4q_-S+Z~2X%=rN#Tv6 zR93GvPy{s(mLJk!c$?bu4Fa72FA^L3H3jaL(t5(8IS$d_|6Is&y{oaA37ke(&-^&; zR%6go%>ShwxA@JIF8;baU{{_B|I$SVlNY@v*|ZU&_#&DaW?ij3!K7p%|9HkNZKTY4 z-b;97plpp-Y@E5Q?gfT8g-R1tIq0>7H>fo|?H@<*f{W%@&QE3!U^mo`L$LIZ?1>TY z(6~Q%K8*g{UMp)VIHUX_!5e3{FP)XMC-N1r&!~RI=dO_8?A2L#AN1{8{vxC?Dx~kP zl9Qw&?wnC8c2(|ALSk@9gHMY_hqOUf!|!MYyF_V&UwrLKxZ3XcE<({HV~ETe2Kk#j zj{!yPVH$!fQpgO4Myw+Z7FNr%10Tv{H`y`VG?*y*`zve*)VHIr++GmntrNVPr zb+3X|uY&M>ADA&Buku9dZ?AHfNDN_zW`%(N^8(0!m~_};NkA|7{v<6*-tlT#8#E-6 z)@m9BHS;Ykv0!x;*pBk%P z32C7Ho17!qAMhAG@csI<%)~D0WXkK$3uDjCxb zT)XX$|A;v}r#|_?68B@?%bi zUjq!4S=)?jj?Hg7xsQ1?hOLw%bNEb)3_`s!;!`jeZ(g_+IQAcynBk z^$_XU7V8&V|J);zi?_Ty+54FTf&D`fp%IMU@6k9t7eG|aYi;Z_X@K-$qQ&zDTvbC!N*dXy0APw< zdH(-U9ldIl_%DX?(m5f^^dnEFq>pHAyE;^83T)Y`ZK|{nl>HlQn-L-RNwLG0ctctC zS_4Lv(rY~=MqYY$4fHm3Rf0+%95d-{>S+fmZ&L|c;>F{fDPu4m6?`<;S1z zbJjFo%dZdls=mf{j*fytS@g~488|)7Vp`LgKrsp^ zTEHxs%ba`Ei>xh>`wj$@0C~_#H)qL8}?>5Cubi=mAok|d*ytF~c{B3kO!?^=?ZkH&^E za1;Y-(OmzZ8n!4i$y7#S`9Cm7{ zJF{e(D39kH`0o2$#r(2dmNRNk>w@Zcwz^g3pNEKmxjJudlqp!jK_-w zdHVd~rckqi`(n>m?n5CrxzWqqAQ+~w!`%MG(B2o?0pHQTiG<|ypwnE+#q~x6`Sx^+ zt5n6Luo6`Lx|d)O`%~z=l7k&_169s3Sp=&;4pvkC?PRa!67|XosL`IeM#y>pQgT(#;oLp2H-@QI#oOS-ZT;^S zZM`F}lWyUHLV##hN?5gr#ZzkVlh{53VNx~7O@n5UC7Tr9La}d+ucu47%c>U}q&4Yy zUHc31sDp8T4_{UPi^mU^UV9Dgv@!x#nGx&^7}Dq{`(o8M_BicvJobq+cFiTC-ge6t z&DH5gUF%ll_exCp9vKxE1yeru4|2+eq}_sVY1KxSgGf70OQ+1y^zc$`hhkDZbHDq9Ib@5luC5{dkBsLwv%OEX^5 zp=zfKEt2!N6O@5J$M3v1;Bx*P!xIX!4e%_#;Ur}3Cf7!)a*=u8HiVa`ccWE#sHyE+ z%KsBIKdR!n;kLc9#YayiB6U2e9npfS87DbnWmh4!shce8OAr`c7s_jx4YWOxSE2vl zOycClFUj^9J`aLvot_c3hU!_#Fs}`TLzNTy+TT-ek-`FAs58DVf)!x_LFuzk`;mqJ zD4+xX#Zi#v|6mj{!ITW5^Z4af1-%cYg7#BGV$kN{=kUDiCl6Fd2n8LVdr zNB>Cqs}+9vleeV7vY24b$LBARdd%Fi20zLdRS775GROwRs1xTlQZ z#o4XB&(qnIB)gPGf8uDt`)*kB<8++VS{!rhADEli9CWg$u*FiBw@@~uJ`;cQ@$C8w zANep5YYCVr>o@ntBtqlhpJ?uu?mO)}#TXI1pRr{uVI;<{T$S4*UWZF345k}-`Ayi8 za~rO8%8d8KK=J-8e1YB{2ThQXg9mZmRfIM0s%Ys`Wx9JH>nkXKh-S*bj`n*6(e*xY zT&K)7h>MANqo|i?=E0w?X`ZxV5(aRt{n^79EmxQA>mdQPhh>oA2dlnaZx{gf4buaX z05DDd7W36#`6jn|x{*ahHfWSiJ$NI&9IpOm=7oD&pqz81lZ*Y@p6Wt86s!;2eeEv_ zd|lIJZ^nT5`_3_@IN-woD?AL~o9SORdk{~(#*jHrjb(h{sAYDGTStTj?ekyM$Mia{ z+R(gDnC{V=TdlFM_4Th=FPVg9Ux282Eb@siHhI$NnF|g^67GYJ0@Bf*;?dqmUkl#< zkmZP2G0AC;=EGCAw1s-s{V@f~dW2Dx(@!YD?XxQNBp$XY_;bTo7ZAqEB`UzeTvNqg z@xIR5LTo}FZtX)IY4fYt4ZL!T9Ig|*4*Yxz6Fm}t+w#SBIDn8#|A*>`T^Cja!mwSa zh+oPnr&eP2;ju}zKcyV%oneT^m>b&|RWS?lvil@~g7@!25k~8YJ=!8ak~yk4)a<82LxVpE z=BtYcHu9pfhXtgvmpKL3`<|*O23*}v(tWe|tmc=!ZzC>o4m!1hBXLTCZeFfWfn$uE z*QAeC#?lsGWY0#)7utxgec9GCCRzyAf1$>qw)KeGKLWNk$`MLX7MSti6fwLf4lpa0 zC@4@vHM@^`HETcp)<5^6Johr(p(p}i1^D$#zpPrMykt{7-g+RIoXq}ZJdgd5UyW{= zEu_+@BSS-OsItPmhs6s29zw5UHi7B1;FGOf4w0J|7OLKaka(P*zE0yq2Ftw3ymKK- z?5e|#ENU{*nw&t-ADMjHjp9Uda&l;6B`+c7HmTqxrK9~0Ok}{JQE4q&2}De z2T#E70xlD0QHhDXzBF&k7cNd=B#?poFNo#XU12=EN}9gQgPzbg5Z-|+t76~ZmPmAt zC5aCOY%(qKiQiR_peM#>HL0k7x>Ba6zYWt|o8q>pns%9(vA@oL)bW&Ko#W|B>3a<} z0}BNmlIu)JA*-mJ-qujQ-5bVA_}T%B<}u$94(%A4=ki>lX&Lxj1<9xdU?vNQ5QJyc z(V>>2eITfXkE0I?7bB;lS1rr>kUuyxqTE<`ce=2gm};U3GBger24Z~pd2H~^^ z*~u8i!arQoZW5}n^A4NC)!Chkv5!jMxSIV{jFvMc#|$4y&tLpUCniL^M8pePWu`-H z9LTct9F>Hy2-_1V*@Uy%Ya)Xb?C)2dwgB5Ag{Y^H+JYV*g4WkuUi-{ZUi->lCa4#w zuVDGT{HO$j*f=V^9V;iJ|J~W5F(2Y@?W`hHiihp~aEQzS$goPt@P_ zb#I2mn&ik>x7}kEAN_1`WDC%gZSY=%XaJU$nadThZy@i*7TfLz;F$XEErWO1Cy``y zYm&YWtZrmJtTBdpi8lPW>H)<+q$evwvl3p2NZ6K`*uuuC!ryl7S*MXR_0X2;yn_L?oH9J(N1V+Ju(W`~U61m z-s@MCGh2>zu3LXr;cqo*b>7M?^E5`k{gPYdsT{R}M)lcC3E6ppN8Y%O*hxWPGe#ZN zL$mzP>8Fl6`_?xhID;k8O|?KKFk9KBTv7hy8Ottm`**78B*ioH=kOxI+6%Bx2j&iJ z+?WdSBnZmI8P-*SX+EA!JpQ22cN%H}3|MbSAb?KmuRt7R`i?``jiAY29lxtIIv3JQ zfwM;#y&>@9vbl!q$IUPGyL`-|hEXl#OG(p9mtZ?g?y4RK70Z3aWs-EM`+Cg=`YxN| zMsb|HN^Mvypg=J*0gI&5>9v!kH0As2LnKyZ0t;cLAS=>~WU&%kc`gT2E$H@;2fm_y z;_7*pCFR6l6f);UCGjah3-P^-KO66%L{=xV*L&s{&I9Bo3poeNrrWRh(Q^^ayr1Ru zD@;avOFV3i8~xU%qWS9qri~D``NdG35H=2+v~xf>_g%}02SqD5v03|be3l};?A2*e z+%U?*6tl>Gl)b4mf<(Q7Q-5uh*xEQE(usVPi#0r28MW4R+~=(+iFHJsu7?0CJC4|~ z8mN9&!$TWz*JQ}}_O|GcVlC^3`Z z#?9)_b6pOv3&8!XaoV*_^(Nry1`0pX*5Mwn&J4v>S8*WK$uQ_oFmdqO-RU_q@;z!T~=>lXzBpE*D6J1d;$5!L-QirR4tibS<8h9Naq`lRu7+ zpcUe8DW25lGC;Ti@?ld&)sNm$i~@=wdP&qy9625k!s3TpLMofgR;x1V#JVzu{2}wW z??fx(39WNz$Uo{>S9j}CP5iF%v2BAx3Jds496_DB?EG%_>%2X3 zL|A^=4KbtmZ(5IL3y=VsVXmZGC#E$`ywF(k#pKXdS~IhK;Os;eBjt_%aUXra#9|_pBazkOWSePoFHPZLMWvS1u<- zQ_-D8Rd-+g%_3^5&}%F(SNL|>sFu>&xL#Pac-1z)*d}8PTYhfOfy;+3`lVx2^vNwA z+6&rK%o)WvhjAaz9)h)`J%XEgV-rOY;<^=>Cr2$mw9&=PML5^ndFVKP9Kr6FNJGr+ zsTX>dV5;@;PqCvBf6b(oFJ+5FmW5%$&|EISLlndP;fZEGnBrikvNDa7K$)8#62E>; z-N!lj_hW7ksPDZFQa3WiGjh*>L!v|Nu=VRyU9w>aUXbog&cGuRyb;6;Jok7X{v(MB z0i+sSmSgbk(HWllP99S;@+ndftbtX}xXL znYlf^qQI(TmUpU=Tp=Ekoc7ES+1OUmEV?v^VC}J@4s&@vVDzSUwVmvGUBL9Y_gR7C7;Zkt?px9 z6T3j)xt!SP@^U{GaV(=Xnj8HJ(2a%+4Ycc-v()oB>vL_ zS9jcYgPj!FDuY|@f>WLT0W2))OQYJN zyLwrA%C|PjM`+_fDO@xwxLX{=fv)RIHLTujGadvM!`-Dz_bpEaPG{hd{CO@66TeAj z1e|ESfk96e=|et)G}j|%m&J-%+I%{$H&Mf~4d_uG)ScmJxK;o8e5w86coyNk&v_%E ziFi0v9pj!k9nt{!d?F^>zi$v-J9A~UKP@UN3eCe5F7}X_dj&}fTzi@R+$s<>$2lA} zx|DC|au7mgcnb%p)ajetJYjz5{uTw{j4|M#%iJ8_a|OJB7V-a&rf-hQtpDE5wr$(C zn>5*;YO?K`Y#S3N+nmfhOtza`ll`9O`>x+wXVtn_|8&l}Kl|(pdtVXJ&9^Y18~py+ z*JqJj%n;(9DrZTuoNfhuYW+CyirHGecL|AOmUz6960HMwJ%lRqevxmfhvl;JsSz%zXi($~S zG9It@hw#nt9&D7ZTZ2&$v%B#}K#i!H2_!es*I1{ilDI!?CetJyn74-1)pR%(CR}N4 zsgYP>P|g#nVE(-yfZv_>_%nhX9eiB}sWIdJHJ{oWAw>qt8fbq|>RViCK=8rU+B$>~ zz}?JU^QY^{2{_2b^iYHj)ey4EzNJQ+~zCe86IkSIKjaJ)M2vd-M{G8kNa9f7dh%VzZ}V zb&wRgcd!9(feR;?d#-aXg#P~Hp?Lj<*NuIl8=EEAsfp`z$MZj2zklTwgsrkAz6*IJ zroJq10*8{-54GWqRFjz(B+(V#(}LElM=*wSYk>=XZxWk3@HTq2(P|I#D+qvJt^oWZ z)Nd;$cA>TczUKP>A9z8PUM4}oBbu88WR|sl`Pa7``W%YU-maUxp7k5xXv_kEtoco9 zReh?XTNM+Lwrk9Uz4}nTZZ;`ykRd74bYL@VV2+ly5o7NCRvN`;QeNb~w$|#ANZRkd zE=1R>sTVItg{03NWsRH#{FVm1kFu|u-m@}TcO01!llFp|FOI!Ilh}5v}7M&i3WVH@EV;uiMJenJL^KKbQjftN0?xUs2 z`^U6anc0h$pUv%{iRAj_N}*4n;v(A0VugSmx4086*r0e~_?L_7*moUW%~2iVZPl_e z#3_27)-u6mRH3xH`f5|c*io|1HZYgG?*dckM=5^ za-h#m*J8{?k3`UZjFkNNJSK=0=1Q<3AS+#>2Ko1WvsVr~2U)y&5zmDCMEmOaRqm56 z*i|ACIjvzFh4eTzz*u8s&7U*NJ!+Pmf@-^o2`K`2Jx3zE^o*qUd2W=!&sz8` zV};uD3msr!fVpO+IlTE&*WTKe8FB3H0O&!IujcI6gl!Z3+C*xj5%j^Vj8`l(U{<>B z>Nf-1XdA%-)t4f^zDF0)rjN>4O{a&f*wS0+N!jQEKSsqG*JQQmbLqt^Y5dyBp;|Q= zm;bD+jEO!J#Di6Hk{3OW3y@j~HJciB!de+jfwxNUAeb0)6@RAOi#$m8#QADJNPD+d zAd|$iHtW4hwRh7>WD3|Nb}!4;Y6@)|PZqDgthRVYL-J<;msfYZWSI0&EDlMs?b8%2 z!8i%F--~d{hPC0|;=ZQE!|2HsHARm3Boc+RJ^BU?xIOw3&aI8HW9j9C6U-5Wwl+R` zWE$fgBwZUpCbLY~#^t+Wse>H=qPz|5M^t$B-B~GE2l{i|lOpzD&I|Oi}g>{b?iu&O9muT+^$G<#*i2)jj$wGnK z6S%4Po))pqcIme#1{lKK0g7h5R@FWXTvAFMho4$<{|U814^V)|EMu)dYNlp)Ah`}r zrw@b0Kkh+FL<1E$V+SO1;2FP5@}c?ej6TA$R4n5$5_7+8@{WL!@G076pHuPcA0V~@ zV*!rJ%useQ^{wrW(UNV;07SU!BKwp*l;zsyGx&%>^;2SUKw_(N@yBhkx= zR(RxGayWj;M78fsf!B8+<9B15iqvFhWwbF#2WYk<-5xI0j_>e#POp$c+9XjG{Qd2C zK0ri|Z$vxZ_OQe2X3CJWp_ZqBIAt4%v=fE3wdc^?>G0;2(JFzmTWwV`#yUSa;uh<7 zq5O8rf{}8_uwmd1Q^$}y)10s3AP_3cS3UH=$D8y!=Tt_6AFshlWS{=uzF^C}vz@~$ zT)o?eeG6uu6pjj6OyR?CP_d2zN>kDE_}`L-V)OsH%-!~K24b_)TD_*U#Wr(l-X}gI zFIV4m3+EX~?{lC|v1zerwimaF2&FvIsTJJR7jVgc&OluT8PVG62DKRU0R+(CDx+K= zH@byxnaD0S<*cQhhUC|UxrQuO{|~a6cPdnNVB~QXl42qv&67cZ7a$jM_#&WILkX73 z0=5SEnV$BI1!8{@A26ycUGFhM#>OJu#-PUiyQ~?^B}&s^HA=|VndnVXa96&#hC22< zs`@`KKu_RGgsa9^J}cl#6s|nB;)VqTAYsyJ^DA~rva@_%IpM!2Q!6zhTIxYP+Kjs! zrjS+Sg~yQI^P=+K;W!vMTYts7v*KY5RGW@stKyi?Na~5_-Ah546RVgoqZ~oMmM*Gi zl(X3zaOS4PV2#uCP0c@Po!bWB6f%ij1zrsD{|aXOlX!ty(wE;aY`b%gn}qCj(|-DV zA*5w1hV=KjM(BalvZT}f#ckw!>(%u7W9g~(yIi(- z$jsd)2^l}DA`|Kx*o>;&0HOl!?dc5zvZ*WQ zpQ&)3(VoCH*_W;;j>-My_ndkI>-9afsj}Aa*TW)J%R^%XYsXTCt)Xh6Or46eXMdj_ zdl^1lbdWTXr{7UFr+fOwzPHxZ_dPRh?nzH1&WqFiNhjN1Do47EfkR#b=*qKV%QR*%j<)FXD6W=#?r#%dS0S@9MGWAI3xgl+Oy;lws61BX`TnVT&GLT$KG zd%kK+ErBcCPYRWia%eNZ7)5rfCy$k($0s=XbzdfczXtgR+qAPmM*v+C(Qa@5jprvG z$RPwBu?)y+#$amUD#YIHMk*xv6`k~yb7#Nq;IM34{-vj(PX&9-!&ReUn-#jX^mJ`6 z)X1@{)5Fd#7U)Z`VH5w?P1yk&J&m?1we3erPobICxjR~&fJL;fNxYiJPc`D?LQQ>= zDy8HNQp>M7R7VNNAtqOY^xdeQm`n|9#&n-TY|P!LVOfQ&AjqUDv!_STq^E$F?8Vl- zACh~kci6xzLB}%9je$T&h{u~tnodM>m6V;V*uWfWgcUpbTfhp;ddGR^>VL3$gr z^hX|f(A}5*gH8Hw-%j`+nq`felT^>Io<-^MOU}u=`@Vcz|5##Gc^ifD4L=x=SK{U* zO5(X$I_T6X-kA0_sxQ!Dtgla3T{W6UGONJPop9LCr3S%<v6z3?m<$=D6K9H*yxsW9TNpwrJBJ6$?68f@#6oN_L2aZ$p|Qz+?%K1V*hWSOg>4 zVFR6U&6osPGd07hwwqH5M?&b)_H~DTs263&?Jj$e(==sb@>G6l^f4PX7-oWgt7I8+ zwwpyUy$M_lDlP>6}0Yn)Vg}0UpeRQODP}U5Zp@t)rd}xFL|0E)v0nCCS7t zQZ&HfwG0>g#zgo}byF{GBilz8AEI(HrCi-Mq{FVLWLb#uG;zxA#s;@A6*?`Ebs0IDW}r^su>0!cLy>j8Va#JtXDBD@l(^dId!wavdRpglGW}>!ki)X)6NGi z$mQ_+xJihfbVC}!Kmpu?XWQ4scBX4l?IHEDV>f9;DXCtv3a_gM=qqRIyN@(Eg zDQ5x|!mioHp(0_{q35Y$TJ#(@L?=;SH}&?Vzw+vh&{GNoY|w`eqyjJyq!-4?BFFrY zxckcgdR5ZTPoL->eYXp>ngY@BC23=CKNqWH>vA_2iSz;9v_{bGE1x4E@(+01w|$I~ z3QhfdvyfUOo4L^ZZ+QLcqLwmqi9hAhp(C{NziKpu~8p=kyty!2z4vBh+}^8Yw1{Kjc?N({BsC-sfIUa=6Nw^Krteg57MVlpTgX62ne z69Niqk{Q`F#%8tix(@7FgEa?)w2}NAug!pLy@#!%_CG4A=lRUCNiu$PADAkuJ($uu z&91_l8gc2^a8pu3X6?DdFn-&^Wz;VRc(gDD`#BX24(N`+0`WTw>+OnLZr8v}aiWRj zr=>R)$;vp4Inls}GMkJ@gNHc7hZc;M)|4SmM5b+mD7`=Odl4_U8>|*ztEesl`-q)g zELRu4$X}Y{gROm<3hue#Sjf8=;{V7geUG|0{G%l2BAP*d^V#%xwCkMvn0H+6j0N_O zS`4So482=iO^7OKfKfl4LOlXjQ05 zg~wFI*NXR5kw;KIpNK(HWJHTeKiORaK2bUtYqdN3oBNGeFql!Y*zTI>)~N(9N^}Ow zmv?^>p-n?W!()Bc%KsKj)IEY}IUaV0`f>=O z?ogARcu@D(<7sy(f$C$(qc+S<%AIV2#h6lMeJ=n%=$kb)f z`S0hmyZeB$1d!Fb6Dz_2LYS{=H|>(>?IbwZYF{G;+gUG9lS39Q!~u)+aW4;t3e>kx zJx9_G$z2kRZz6=VYn}1=8JEZNVcL9tb{e0T$B>Pm-;-YT@u8bqC`Qe@~hn z)yI9oR?EiTwSYfJevZVMh63v=5)c6v=;$U0^tq9atLFXW@bd@27s zi?h5zp8}RjO{k3CE>pAWpp6P7?@&?wC0o|Bzx0^`-d$X>qRad<204b6Zdf z7SLKZ=l3mM8P=698-!Mu_uLIiaqP5tH;m4(9gt!$1w*5RnVo z;Vnqwx#56#esIl`u3Iu>WBJxCpqTl2itFIR9r%xD!+muCLr=RSd1e}YTF~OZ$19yc z;ZnGzE1=8L!bM4{X-ZT_Xe)E+_@=Z`rvlG$?@Y=IkO6)9`_)i(P1;NxF%T=zs~NZ= z>71xA-wN8sgz#o=y%9TYXe#>;_ae4d~^X>s_m+$sjnq-DMi}M>B-B1F zpX-Pt6s+x_s)O!6RmOvEmi2Gz4wGasmc#ft$xikJ=;_ioTN#uFe}Z)l+I#Eu7~pH% zFcPY>sl!?wVjIk)-`I!Tt+hcl3WPfNA>4+UyF#EdP5cEj{<^`X%+yvMKZ$pd>1MFfQGs{B3w^cpK=)P9}O zRA0!Q{-N0}r4qNNfd_+vE8`TX+g3{?{dfh%H@CW^_dXtp&v3L+RekoRwnC^n7f?|XmtEb zxUeOi)W7m55$k-F;_p=lAC21#xg6M+z&`=vlB3xdE8v+tp5^KD}f;!b3(FyWOUH z-Kwo91ylP6N_ObG2TI*!9=s!}1*LFyzRs!bb?WMEbQw-%f?U!wY|`+G%}^q$8prS|A9R`&&$}xs>~;g?dcLpFB$@7)8p69Ikhmn?O5Zk&BPda8M@U&x@y3UL^wcUh`3J?q{uFG zS54!Urd|GNPG*pw=f$?)?F~oAzF*ioTa@g5I=h6;-<&ybyEmbKWcY=kF^#j5#E%pRscea(MGKC8nzGlbU+iX5FOL#Hy!=iVO; z5zc%F>D$yOj;PvFg~@iZ%S785=}m(2y6{Oz%KARt!y_V8(@U{om_4n$w3 z5egAIY3z4Hoelnlab&(Y#hb`>*RX;@>L#h*6CMk-DK+0W(5< zN6fEr8H0aEL!_bMjnBgT3u;-hn6+OpYft;}ZqWzRZdvUvX$> zxC*)JrtGdHTzO4XYK14cpp*=M`S3ITYq#@>afL!Qlu~y#T(PdBcxnH-9`{AQC^e4% zqA(F_rOrG--3WRI8m^4vpuAW9M_g9+A_@)1!DwI9#vK;yj6e3{Q+Y*!Ux4z4vwV~I z#X08CKg7w?s4ZW80#MuB?5tSe=h;=)yD;GxL=@!`VP+I#0BiqB^nHNR&Is9(AYN#M zVRXLe8SN`C4hYrVk0GdsV!){4lcNCHDZnoIT`(qlgqe$%_tt40HFD3xye`ryzW}_^ zrK;#S@MKhw;yNB-qxePBLG>vV<^=V}isg^n#;DuIkGLK#3V-8BPYJNvG|FHJGX7{KeML$x`ussxp3O@GE-fq-my!P+tM7<6vBI2KgI*ZeJS-5UE1vBb_ zb>Hzw>wZ_6O0KSm>pxT;i=lIQ6-#R5z(Irrsm~K+O|&q46Tg1p>sNN@MALc9#86eP z2(pfCVDA`Wl`Kb$VIy1#?=|*n_89-Hwo^ao&82-MRv1P9lp6KHg^i`UT=xbk76Q5U z@A)1pmh-=->g$fi117)h**R+a&w0PXPuSEb>thdYK6P;sY<#30Meu#$o25KxGU->?))Fr}=pZL*7P%SDHUxdh2h2c#G>w)RuJ6aa*H|QW)=TxLs$!}1P*)H$#Mwo-?L5SxOW&x zLt4D1QJp47VN6(2=__50#GqUfuWY;O?gIlE&R^{fNHU@tE1OYc`iXb$9D zxZM^^qx;n}f_LsdaP2;z@UYel_xiah+m8+mZqg}GK%h#dDFwDj)ueZ_T--GJ=YBzV zI2FtFWbChYE|qIu8DZjcHE5znQ;0@j)Azyt8RM-rQw(KRgQ+{T^VZN+>O4e^%Q@SJ zIY?qQmZP45Gt06zHYy<4ln^^6ONYt{4A!`aP@~!A%}}t+v?0+CloDr3s+@K2k#FQeqFu^f5zn71l`{`Bs=GYUb?>;aDER zXNdSE>g@_6C9p!>>zx9;k=oO)f~4%$9P@beW#kPg^-uQ+1$%wMrNOGs{r&!w9tq(v zK;3zbfo@dM^^)Zh`X?DWH452n9s=}EJKc7B#F$>Ad*8Q4Ar36VZlklnbg!h4Ja`yf z`qD=Qse!Yykpl6V9K1D8enVaT>UWr{12*8H;t4$9-Gw5{LVW}U zd-92-i{O~B#w70_+Z$$ZMA*UizTjcA=m}y|_wz^wg+}FS9hBXEQ+K9%Nu>}jJsYv4 z2?Y{yN_`rst=m1WJ3-=asYzn1PpNpK7KvHeS+G-Ld#km2R%)NEo~op)&OOx~?%oGI zUj&b|W#kKXo+-SUI1HCk`^?AMzC!|Ew>?qgPZjl;;ats~)Xag0Z7D7hi z7HTJ3UfEneQGcaG_HE?eFo%x^kuBMW_R`mS3xvRh{ywuEEJY4Mh#uyvLfABijI)Ny z$L(kK{wz)_hsisnK#V^fQ`i+=Jyyg6grnEA>~HV{2W&#CL234;@-+Q_;n+6_AYL_T zN{W8R|GI@rGE7KAw%!WN6zI#h-WDs>GJV>Y@(@;Uomm6bbjsMDU8#AxP>1$C5|1Qu zk-nkb_h*9RYW*axR+#N?Mv*F3(6F-gw8d=Z&pXWc^Mm-2Vk1NKA3DW)2<2p9J6tO% z_ooNT{ei^kZJM z@vqGKty*;zm7S)Vzt3Ow5$~Nl)h&O!@?SL9E;ZMlzGy%L*zF!={M^}LoY@wNo#};j z_26A%;!`#L`UYi+bV{^uCkiQyb(94NkYeLtdHIpxW@7NK;p5|ltm-)=6u8*E%xCXp zMpe>Z8<6&f-hvpts31!sv+ZB{79_n?V2gIBop?6VXf`&3*$*f|so?Xw6ua>#v8JTH z2Xv1t1ZL0u;-?#**+Vm0OkE6SN5oQJ;m_TK^-#~s)7C-l=jJ{6H9?JFBiMmPbUBKS z{ewamQ(|lL*RxfT>@YZP6CjduEc0BZ!IihZD4bPbchuNuq@PAi?ybJ_Dy2<5ef8N0 z9;+6gO`J37nFNlr^o*!YJ$nSM2+q*22<}YjSf9x6`QH!ZNo~}l)?2Yms|l!7^9<2_ zkVdOb$`R?xr@RBcdq9f36O8L`5Q4zi^I**1jQ%SPI1^1WN`eZ2+20mv!=@9yo3 z=uE+{W75EEGdI4SQpsZ-Bi;eli%tnu{I@0ACG>?0vURJUHd+wZtgZQ9SmG4ehY#J& zT~Uwejo6b#Kcj#C4zIYbBe)A_L}kT#(sm^NUXmkG^7DF+AoHY*ElS^?_v{_W3tN^4 z3E}K`(G17HI2d(N!~i!URJ0$Ab}XHe|Nia;U^iHaP7&;#?(fO37u_T?v19KE4QDvS zkRKkQt5Z@zxoTeA5d5X}<;75L=|T4J^XXfHf6f1>;KQdf`?LIB#-eI5`;*d%V{T1i zywMwM1&c)(g6Sp;o!hwrFG#Yp*!%pFk?h-eT;-j#OV?|~UKT@W)lYsXhmRp`^LFm$bl%*Ea4{7|U z7gs40^)B#co4sP4=Ce7J3A?R~+9)K|$ui9Fcu?wHjgM8skNHRFSGw&L3K6&<#-jd> z2bNEo6TI1_bb#Mti+yxMg5?ZAFPz-GZB(PP7YkqY9_{~dkqZ&aZnOnro*hDKVQ@ez zc7l~F{8&MIS#kYSXKg7rimI8Ox zlCzcW2*Yu7cDxlI5v#AitZDwIs}VvxA-yLv-cPYZ}=<$19wsvqfFl0uMG?4>i{hh>mO480h_e z5>hg0E!6dB)#$b8&VRO$ELcYI?M{Pt{iehZDY&56SpWSJxS_2#jKIbS@`~gnIXX)_ zvxFH&N#_q2<>mcA;xwO?z>^4ee<~mX>`h*rJBv z@MR{r!zQd`c1x*wr8ZJjYmz#wXHx*=WfI_2qbR?d?+{xx4E1od?uzAcF)APenG%YO zkKj2x8}R+IIm8_wLI065TsW4Uv_)#ZuROxU9#=Ik4nwWWmUX6&=y{qyWYPJ@tEw`2VnI7%jg*o=^@MowcvFV}_jnU)Tr)cw1b&_5pY?X1xhwl7&fyZ10UCK!)mL); zb{$8QTgSou#-+^~KuC!# ztD>S1a)KmNnTgb;nO1<7F8Z_E_4tzESI<7nTlQ*Ko3Qh^7V&Ib?UbSTUVJVxa8^nE zdBt_Xfad4Hv3iI&=NTHAM$Ve=j2MScl&2v>_6ZWEV|zw@y*X?k@<93#Z4{CGBS`#6 z{l&AR?yuAmrtANC0rWCf%bB|Q^thQN4{)TNzd}-v=0!24=U{b!gtnZ2+Jbt`Y+&sa zN`lYw(R{6c0H^2HhRAt?XzslN0wm7qoaG(1QVPUky_O0Mn-)WitpTvF=#zt^-+Pei zOix~E><$Mx){~Xc#LFv_7PagN)|1VfjQa6={=l83R$X5VWibyV<}_B?Z)xsegP$0l zEj@HV=GK!o()kG7XJs%Kc2*5INH@i9tCRUFj$4Th{80LGzaQ_JR$=urE(ZD}K`1M9TXWjy1j-5_bu+5!W^BeJF~9k!%3&;L~pSlPRny z*I0n;Bl}4YxnffL#5RjJH$`yf$vB#?zR>&&-;lUl2sEXZ2xgn9a=acHHpvW-5S!@ z0_u-R1UgW#KAPjXSch}V+rr^Xrq7YDL!R*BUI_w+mjjV%_K1mG${^U-rG?UKDOqY5P`I$RToNS;3ohQ8GZ4`Icu zSi%~d*!@|K*xm?of}U)|1mn8D<2*z_x!gukYlsBTZt4`p>$O58S}i8siQ>Y9=4B*Vd*j}tO%2tP zSa@sSRrfF;=~c^O;27H^>-kgqSD#JJyU&(3;_+P2DOt>PRAvMU!dzGR zRY$R3PYu%FEWIzRS(mn}q%oW=^67Txyx02W(hECmFWdKTUKWDzJR4-1BBOL2j-Ool zQx^*iHR7Zeo3-1m#k(x^^$Utx+=*q4@aA&@o-(ZWPqLiL)>Z!`zmWgAc@wI zKR{{83tX2u-Ud~}s*~AEch!uJcj8>8aBd%qB$eL^auziCbKa&@VP$ne3Iu|EJ_zo& zA1D0t-{JI4-=%n(4~^l+u-`w~Pq{-v{j-L!I+$pUICjLmrX<}}0sP*;ojmH`Rk3nh ze{J9PzRlVApNgl`?5GL9GxP3|-($QbdD(XB_Hkv;hJ0b~(`PAyzVl&Cn56>Md<<;_ zgmig<{lV$jo@jdXeEd5Tl!1HDn`(8Xeb2^PSH9gVo%Eg`wo&9J7-zhV&@p=N_W1FU zAH55#KfG-Kdz@Jxd$$ChsAI8zjFIf)ufj7c$ZlRsiatSCdoNn3iyQWPkE#Q^>7{8R z-ovZ)at#jUD;?6jd;4~v)vCb&1MEUp4;?=UA+_7IG`g?s7Dm%^b607A+9XoJ5M+Pi zKm3x)tZsEN#lA+uS_eQttponV#9sL)y!txYiEKfFG$s;w z`x!dXW^ZZOe;AIPYl;b0u-bvNSRZH1-xRa7wEINl^f#U_kgj8?^7yCbrrml+UT5l@ zzj)sAm)XTgcN45#<@zz~g-*ad@;m(Gg2wh2KJpJ- z?fGVCGQwFuJ4_eMcYc%MM@ItHnz%^E-)6gNh$X4tkaYZEK=u;(X1bv-DeFGRUA zqXe%kOQN}w>-yvcgb=Oh*Ump)5f~Orv?qFz6#K>D>jL0t?ypw={&wmL@1y5RtPz(b zlqC~FWqb|nt$A(s3rye2s5Q0%sp~PkwB?+fRie^sYiep<{iyU;(d4bv5Gg3At*Y8T z%rHJ8+}L`Sw*Z=-LF2XrDhma9U5FN)y(2m)$JmdbGbZUsjserPFh zW+-nPg3cfJ;AWM+gf1&ZKPW|?|5=)r(^1o#O&rcZPy;-@?$A3nqHvqj~2N60YjLt(ckQbI^FhT zX%5BOug!H|zoF_M1kk7)H`!y4F5-G9HkQ#BS=|Mkmqlj8pZZu+boTGw7JuUznRK3) z0Gyv0L$9Y^9jfJaM}NRq^V=@~6<=2RpU<>Mw=VVUZT9}~EcfkA(77jfEOYScM#ew4 zk1U5iFe4!&YaQ=z*B20NrRJu+7OB*1zKR;v#wY$Krr~Wps6^u__Ki+wP+5%NMm_yC zxMR*?`l6oR-;k^in~VIvB-ONxDUOUv*QEK08n0UeViY2)P@wI)m)h<~t==qJ+rckp zWY0QEln$sg&I&NQvHX_ADy)kttkqDQtWEGO@1Ld@e)hhOiD2sw+?5aqT2r(zE!1LX zdD!s%?lT}8M)qIKzt`7m6m7*GVuy=sxVd=Sc2HuV()-p)2Ydk;-m&9C?1c z|L4b{Vm}s|2ejRapeu-j0lWAjT9pUF36++=paqUY3Cd8(&LyFKAw49cvzyooTN^ zi;c*dJz2dU_jRtH?~k0o-o!YL+R92#J=4+h$aC&YkUC<#`I9u5;;8)A41T%J(77{O zT|3_KQGz0J0JY?9l{3_tZ5pWmdX8(inE0hD^mbvpd#BjLTE|kP*xW2GMr5yk^u_UV zu$|8{e=joP8PiHRmHjKasR8>Njm-=U=`@;OHR7MVs5;FYs&`=8WQ~g5H;@05OV#f?tovw6+M-OM+$C?XXI>KNy`qaYaq7I6-S3coFS-^1 zcciSJ`-l@OYE=JlKKx8v(_}kmG{a}pL1mDUj~Qqe`vPU(X?bG&SDmCmeR)$+|T$4V?bnq3j3#LNx$ zrh>{`ZaIu&6t(1heTo2wgujQ}=gxMqsp0w{Q)qXDx%QiZw+bo}2Nr4mF~V&O zZIt`ueP5(|Kjf0uEvGR<`tEJ!{ac^o+%4?8*C_OfM~}*d1-h{D*{C478)5gi#9ozA zb6?uMR%iJ((a}GzEm%z#{}JFn;z>~4bJF#(;%$?AMY|6>YqLh(eVa364gx4u9;{=g zip3i@vH*3@M`_-7u;j?aMi^iLx)cZu7UGlkQ6Ea7TpBqjo7^PhK!u{l*;>7!AN z+?J#w&Ui&x*>*Gfh`lPDbt8PJ7;V$_l&-IP2B6{8HT*GIfQI9GHQe zBZ*6Qn(t++)&p)MS(gakSB?8!XjdpyIG?R^d@AtTC|SmR2vC`*8*S0I_>k4u+xx_l zfNhpIJnhFi=CTI&P@&I`YLE-~A~tbDBIb}zKA1?%vZ3?C{S@_EPl5~C(^4s<61lGI zBYqV3d}Xf?BasOwa0stmK`l}bq7a_q&fHiTLHk=!h>B=9G0qsc^D&;z`wQ$iej;8o)Eu@eI?kX0zwqtH3OL4Y&!Y(GYXqV_L+3>D~sfT+IJtXn-^Pj*c?t^#D)FuPd%!4 z((}3XawZ;KZUuy#F8FGe1&k=X8#W5k79BO6Hses;L(|yNb=M@SKK2N`YTLDN1pzji zH+~ZyENh85aXNu|77M_C6mrC(5xT%_L+dZB=!U)s>R&5tKs28ijmxRaa3PcGgCNkSr$Bs)o!k>j}7Oxr+WLD4L8zR>?T=dDsdazv;{pc zi+=tL1{^_)h&}66S9`vbH*{_E94BDMv@{?U#W!$&^$$eSyq!VRi``Wb=^Sq~R#qn? zu7(V0KwIzFo>C{`ax&lqZ+w`Kyz?iBwID%sGGb3zYXIwDJ)$?_z#uz&TNsKVZuC%) zQqdND?d>6{E8G`+Hw~SFzw3p|3E!lhtr z9~y$zaj&X9{qnN#TmLZNf&$JbNv?D4AqhykU+1wX+{;7#$0pX?t(>S4of9a#{bzrl zO`;L;a)mvCm=vz}KdxIy8yMxV3D7zdtC9>r@S7w?$!m$PBRc0pm$EZ7%hx2T|FiW!ON1^z` ztJbhp;B3DjIpD?opChXC(g{LfU9uaK;9z1p8f*5pC7@BXe(XKmVg2NRBT-Q4-|X)= zvDGPB%OKkq$e%`S(+u7^;Y*x8vjI~$8D{3oM+_>4#2W}A-Y{1 z-+NiXmB3g%#$H-vAS@IH6 zmY;Hh;rMIhR3hYsSJs)!L5fTC*mcI1LSo7l2y$nJSnZGyzTPFa3aD@gE@=z#EZ}-q zen@$&geAOTW15}*rMzL|e5D^_+A?Y}tx(@NeM3vMY5+KQ-Z(B61aiWmRX( z!ykhhPW{E4O5juFsW1)oRaH>yv*--^+awFJ>*TH-gLLL)Ki{!=fE5cJ2Wb0;{(ThE z-u+p%e5X1_0FWhpaDsOrI)+|T&t8zz#blGCXtNMaX|&fFmwra86jz_w?hyBzqU>xc zN{q*sc*>|8VhpHpRsfeJnfs58rRQ0o3OV_Di)(LT$_ED30*>T#K#0$CH53+bAU!Gt zK^?(7TG0u$lD24>k>nr#HJ}_Xcm1(0$Th|s+7uSi1>fdD7Lv8QdxR1@DKc`n*X^+G zqz*f0){{3BmSus$3rK@E?6p|;wn%2fK{4KzIKNQuucn%mq3fADzD*aoZpN=-Ofd)R zmXS9%3$6?Ca&G_nO|w#HJEUiYY7*YSDG1ZB)WNj(Z%Tw`#DB;F*`@|CcmgsVpNiqG zY7dKjaQsgmn)|yo7=e_>k<^4pp(#~Z_RG^5Op>MVJl3Mf$jAoBy-M$C#|=eU&yn<~ z?1!dG8lWyH^J(j2V%MqOtS`82rG(z4h)JuwHvZ^ zc4f){scXQ1&^d!K9`+*da4ssRHwY8`7b(`QsMnc+-fho9*yyG)*w<)^Z&QoTM`Wo$ z%(L8N&k$=RE(xa2R`R?I?zlP%7h&V839nR14cb+*7>njg9QtZXx=|fF zwP>*XM-=EvwKq#&P=K;D<(!qao!F6P&fP;L#Y5jc=ZP}~3UBP#o=$mBmwu5X-%>?> zdY|n_MegqIN8Nv5`%VSce3$Lb)o(;#y+SG|-xWyi(SI5D`$QhFMBVcF(`3os-6U^e z(ty-DjCS)dRum{Vk64F+%-iF$yVD5R?tL>DuY5H4uS%tEh6m@UOdJW&@N&xA<-4^T z)yd|jAok5Nx^S4w2E3)T-}}%B<4@w@3s~*6_r1+Ilov$X*r%|B*_19S2jd@99&vR` zsFdBrCOo=r>|w(AyUWvtxP41s=Rid7!+f-hTe^2Aj36JFg^4;C+`e7vDL1)ftkyhuBi@Sw-?{(C)LVtc*#+CW zIKkZ=f?I yCaBcZbFyxI=JvcZbH^-8I48L$JnaoZbIgd!OgreHZ<-Ty)J*HQqU@ zB2PloO>Moy6>J~+oUB^d34?FtW<<8OAo=i>x>p^48+R}prY%oeiIOz=Z>=lpBQw#3 zXKL0g55Qoco!+z8Rya&F^okBkm4h0O;PHzsm^*pBEvpbX0`gZl8=uKSQ+vKhc#YOS#Hd=Im|UtXma?n-Ase)(bJIP z>^;B~>Mz!y)#t{QPEUV%`a*Zy>&YqL4w&BKr=ZTKs*Fq`Ipk@Chdg?@*w({coO+RGHIGfsSLkOImj zNpCR2^%o7WufwAGgp_=pP)%zbHI~cqyfAKQ%c+sq2=9(##SA}hXiO*3{oHV`^jIU-J8Za=lk=vk_QwZL;5EEN}o1(53-=3vc1_vKvspql(zTH@t#$)Lm46es+%Y z6SMsVu3vROi?x=~3O#I2x&nZ}esA0>yElYBgPcUcRNv>_O?2(UfwoqvfZBh_5I@mx zU2Z?>2oewG2u^-W4E2y(iDT_BgD5kQ5?*~aP0os9ce{wG_x}I{;mutQaFmC{J+a>J z9bvdSb8^O#-c4Z*7u9AAzSG0}WzbRjrT^ZIp^txMwwv|b!gMhX_L(MhFpJeHBSpBe zBX>u`*Z>Ih!NTy6376gWAj*M-J{fg7Qx2u!s0!?5l5C(II1Ofm1J*-ZnUw2l47J-t zd=&XAWf$}eEu!j?6g>d{fZj7Hnw#Hk&j_F7R`?Q zJnQ=v(tam+3H4tqTy+0P>{l;eQOGHJ`17fJ1^6>QO}~r;??-;7B)ktjyh|}c(}@rF zxMC^f(g@VCMsnT`1RiCSy+k@`ryurO`t0YJ5vX6jvKY5Xp)Q~YX>>;(xr18c(>u%{ zBJZHnASEu{c3|~TJ7%D93p?>;Nob8iXZ$|u0S&pXfT{^{I#BRnGoUz^fI8YdcFOC* zR+F&|L&V}3|7d;dMi95;3-feCa8b|*+;B10bJ<8UX6?5ET9l-*6<6N&&T8=&AUMrfofLN<+vx2P6M9%wi8N3kHrYH3Eu(ycfgY|5?l!BDoQ-G zNI3tjh1MP25aQnxCk{q{%e)wv=1aHAX`yAv?hwr2eP4|QTePmoQO94#K6; zeA@(lI%llZ&S|N*zQ6vn1ItJ>A2@ggCoVm-uH@H*ag-7Bgdi_~%YDN#Q#+th@EgbO zgw0r_vV9uUOts-tMQNys&o6;KA_$AXgj0{rw{m+~DQXks1j*0A{jvr((qhefhW#^k z%@R|o%~=0|BVII;@3JsUR4QdXIdJVg4^rMX0^^~o2R1%cBCWa;juKPVn~1#Qcw|>s`TO;r zs_Z|jtJ*ilx*8g+CI5>psE2|Aq*kxL|5^#(LlpCRTXUqnj4g^^JD85-L_o8$lD|lu zxY~^-LN{N`~B(8L0b-C9)lK|6z$$=M%9a4D6fjJ!vE%@ExYYxRpUKGLn$K z<+n0~tgz@%dzdL{9c>ts={XE`m`bb3v0m#J^}Es{(&;8mjNjX|{4SDAlR}1fJ+`;K zI--MMDNm`H(1ImuJBQG0e%`%z4@HV1 z9rt`DtP1FTV3L&hOE1^jX=0d$BmgTaFHBFD5Ry= zFlh8h=nSw#7)_G_rK!8f_oUw31e;nbH(8?qOyM!=-k|3ws>)v?VOojy+Aa5Qn$o39 zz^C5nr4<^G|Ff~nxR`_T&ktWJ=th5iSgu>+Ko8yd|3MINj*VZlu|hVjZgIoWqK2fg zf1f}=AZ}u5^L5x98cXs@-;<-6**{;5`Z8x4?Km zbH@qCVM;DAZJ4^16AVe{oJT4d(Tsd3PKLTZGsF?&%5c|T%b;=A5GNhF|DDKdaAM1N zG~@Vch)*3ls7CE|PXnuj^hf?1R31f@(bZnclf!OL_Dc_>?hCCO4wbt0l!y{iw~b;A zygXmWAq#*ooDF$!5N({5`<_D(;;iWEpek*eZQYP_AhEvUg4I20&cLe#@n_Jg@H+O% zB{H>5xVvkKS#)@e`Rn4(^VMGS-R`R6WWUit3Qh=*islh+YIOj4{WfNYN}`-Nc#goy zkbB}yH*Y^d{Kb3gVGD;ksFe|t^SGHNa?I&v@S+(OY3ANKN!I3KCbXp%d>()I^Nk9Y zJ&xsv;@A&Yz2CQ?{*4Z(Jz5NZNCw-u0b911o@g9Dfm}&o7ll2R_Bk~TOr%Xe49*=CiPkmpImZ>I z7wb~hQqea;Q*6)@W{{7&zdt19$*iMaBfw|QKpW`6knTvbskL7Zk!%M-xOb*de@N6% zLU%ed?mONVJ3sw?=cvW?nDEKFxwfT80a=?x;+RXU9KgZ@a&}g;y^wNx^>X%S%+|d^b6HhRV1SEy?!c1II1cKB#U0uL5)zF z_^1$>C;l0a031$OE7tyH8H-crE8l?2j|n{B+Z`vd@BnrtA5->($JfLpSp8Hg8dZ)X zrKZP;(q>Psid!^%`4J1HFYi5boOo+rrFdAcKZ^Ff3H4*$>)9edKwhcVuOhncqyz6= zj{jcR+|d9Nob-<8)CTmfobdo~rfzy1k8G(z0no#S|8nQ+N;%Pt> zYBW6+H^e1b+19!^o*`HEqA%X5_6Aq{*TlBwS8W3{2JAF6whB3OFDbi4er;%R=zG>p z>jh}G$Rh`=Dw=P6a`cC)dXT#b$dcHi=g4;n#7(p?^PkH+$l{)TiC7U@{+Q^^G$C;4 z=l2@uE4)s&*rZApXnxw6!xC8xdh(_H#q8UVeI-G*>2@UK!{V1*(gwz3TSf|28r}t! z@)7ew+D33w#DT?+MUirtNxBViiWZhx4sh;j@QicEV<2Sxi2p@!2||hiAa|itvO6ly_EDS<65zV?L0fwevZT1isbH5 zs5!xZZ(S_KGcd~rp)cBZY1#A+s+8JmVO#V~$tDa}-p^h-3!Dugz_v=7S&ZjaRo-LVhRA(Wau>~>wpI?ESC0~Cj zp0qC|`Ct|tPrXHQwZgTZ|BbkFKr0adq2o}ZKvoU7G^j5wg0si_&WM`BZE`;83p ztKzr3HVDmf;OI#r#k3Ge2~dAUXk1%i?M88ivs07w&J9B&JCn!>j#T?{T{j#EhV_cl ziang`BW9N{`?W=wxB)R<|4{q8jYU<4a1eT+;kiU&@NI&y#fRyTP^ZlcisdX>@FgIs7C$N>b{`Z{gO~az9}~C1Ww@g6wpt8t0K)8ooaDfXR6m1}X3!U`g5n0m$m4Da&!UaNu*+ z+l{i|?JSzy_owiC=3Y5q9lwO7hI|7P6(ekQp{&NLz}U$? zgbeF2YcXuL&rOmyV;=*1_~fAMkv7Z9EH~SJY#mjjGt}rO;@G)y z?a`~$(sL2ioC~Vz)Y+;fJeW}EPkn=jI_;i3XsYwTU8o$mQe(L|Ic8F0nPf97syIuH zeh8fJm*$B3F+U*+6QzL*tGY$F(!y3WfNKQ ziz>><5@lH7heHM&-7=MLx^-wQ-vzeLgM#AP=%WVIJ>-JpN6Zy^uT|ZMoZnik{*EE@ z^P4*zvidzp6A!52R(-6Z*J@|s=~?ltETe()ztcK&%?U;yg9CiO!JmjGV{_sF?7jP0 zGJ5yPEG2%zpt`fUSy+qY>$x4n_7eB+&mSxZ@o%nsR#$7Np$g}_!iQKQB?dL4Vhw|e zU8b*`U?ZX7n?YMr!L;M)OfK*4d6`3D;H7$SmrMCM8tbJc|FH+;7W8JabPiDeeRqiH zrtevCm@(c-D{HrqZE%b1_2az9CxvvyZ|BKoS^>?{$qIqN7$J1f_zD3U^RsM`>~{$1 zr6ga}Y5zUZg0YcCG=rQz+bsuYWa7Kau5{9jNFzP{_6)gu)^@Djm`~EZGj7^gqTL!b zZM1hi`!yv$WyEMTv^s%dsF(h9@!yt!&8kySCV3#PI5ymi$7~Mhq^h>6w$rVvN)-I^ zraQOdC|}R3SkEi5YEQpB<{Y}kGXRpEAhB2=o|ITaA7rLxx<6CEZDu^}x3lxHBb%aO zvnjAv@Qj#B3L-#f6Q0G2*t&kBKLf@?Pv3&h!W!LPe6cdP>6qb2xU@@Ov8N85N@I18 zjdQ)Cf^hCP=tn<)vzan0nB9LYJIhZX?taHKRi$%s_qeopu+!1Vhwr2g zO{7@84_I!`G(9SaUDik5ngy>l+*V zzK4r#@I6SOsx&1_#D0JWxO)BVO}G`C+dZk)-l|JHKF7z)Z?H_NI= zLxmbK+N^%nZHcadmudL+5cy%ozHJQ`DedOYVlA%;PW7e~ylXK*_qQrQA0KreIq`ux zuf+s&LmZK{H<6GRzfH9=O#+$Lnl+ymK67idia|X&4|e) z|K=5Iv8)$UBCV|TKaVl}hB$QiBO{+=J7vCpnh`A*_c-bd@|l*D)?5|4$}^xor$mu!B2+;q#HHywG2b2NTRJBEi`fat^b~ z+M8tn>d>9zGrTc}@I#w461^zrmnRcpwDbN1Y`f6}H8kjYcDV2`ZfX_HISC2SlV44o zf5JXG+%RZ~S~-_p>h$cm(Tx#sg9P70Gu0qeUj`)15X{d1HL|k~C$(A|rNkF&MUJZZ z-JkeHOnT0hcQO**Ws7G8O0R=@JuO9?*5WhMI_xcS$G3#sTW5S+FN?ij$mKFY&@Kv2 zkH2ZgRdU4*NF!%G<`e>JnxywM6&g2ubGVVc40eIP-+pjlwja}^o^vNwSci*n zzVm55%cQU179UGwn%uCT-O^|-Zl{?67|zo$9obIDtg7Qvb!dW`C9=aOjM}zucpjv0 z06so1tBn@S>^(o5y$XK=^Phdr-PZ`&`Jx`WrLwE%?oWVo!wa;!)b~J@?!c}m_XM7$tJ{nCvxx>5vfgJC=vwKdo1^!}C*{I=4kpd}!N`uq!29CO1k$lSQ> zABPhz672#)`~j_J{7z)V|H+P>(Vu;} z-Ini_(H|s668soalk26%TBK=ctZ@NV_U$``uNcLo>+)0V3m5`Pffib`fd`PahjhA8)};j;0l!SvopB{fj?yF+Zr9DYkE)5zM8%t++rxVn6<3 zRN=6Y7~q$&D~8})Mt+(mnoi^SC4`TeLmB||<_CQKeOgomJPU;%|%cnWH%o?yy_fkgNVi#9)>iS7*ZR$sz-X(XW z*MI?xQSA3RsucLIm_7dh%tvQvi<1lYmyBCl{Ta0^USwiO;WvLtj}*f{b#hf`pifJz z0?ekpA=PuO*G~p!ai0Pv&Q4HazO=ACBdNkYT-6A=<&U_6R+DwIy|!NeB{?u#Q`ewi z)2(9mp?y)K|B`T#5^R8OMY1)_rkOS(x_)wd59+pw4bnxu&vrZ3e1N7HQx$r;Amh~- z!xz!~)0&c4V_`Sc)t-YEH7zWjo7Akr|0Xc!))AGuY}9!<_qZHSZ<6=9oD1B+3Bpnv zYWkGsMYCSDO2W05$4oKsDrilR~at~^IA*FDmlePl9JS_!Wlw@ko z#<71eOA*E`+aAZUf^eYMUUg82pwsU<0|)#mz)_J4H3?=g{P;S5!w@=xI9svy5$IHr zqU5a4_J4%(nk9gcoCNSd6_GiZ-yO_4ndjx!iLTYaKC$QVjux<|pF#*`|)evUcGM;IjiF(RE>}j=8kT7-Bc4MWP5` zV$;z0ZSY|FT{G+(vX$D`iNh_*>TVyWA#d&GE zf%{&GfqIUMlpnCnPdgx_GrKrfrGFRlI|PjOQ{U?78`a$7v&Nf>vLs%rX>WE~7+!TN z1^V}%&jisqBxeOg;%XA|#GXyRlXEAm9`-J!_F_?LNmIJWsn~E|>7pU0%T3&#R~Yfm zx$L@+q+KW|Dc$0HsKPi}bjkizQc`cSYbs8pb*dKkW`V>L@=R2AFcHSFCJ<=Zg`+AH zvZ~npzFN*hOD5eQToph;&crTZwI9(}5B9}8LXAg`G9#XbfFHuz#WG;BXuOu|+h#Ij zkAKj}4R|g!Z_e+(Qc2s^eb*noa-z{bD{Jo5%wGxamos+J9tIXB6jCz#=KSMdlvvl+ zIQz-)$6#P1&DM`gPg~q%^h=(av zW0so?!@M);#+Y%Z+Pq3-pJ_9iqp7=@3M3Pl%)!kO=Ih76aN|5;@HUS!6g*5SZa)PU z9c12TIAAO|5NM%03|`@XdJ}&xem6npJH|!QTGxQDhDR~eGlth5%Nu;^`v{yUDoE)I z=bCjKd_-8@m}?Xf9?oe?Re2HjzRs-JgsnsC53{Yegzj!3?sPB4Yiy8PF6gXXw)P%F zErD?tdQt+d^DOT4owV-6bDx3%mmVYrU~ZF(uBI&GRvpJ)v>JuR+UzBu^b%at3}D$n zSNz!uiBl9MFkvZik|Tk8OVmegN(+M@&DC}Z7X2t7Y3Pc%9_pPP4Ip^f*RJ!|Dr)zD zXn0Br_>nXA{6Wn8CAQiS#=@2vp>bN? z2`|cHK9OWjiknmG>k%m+JcNN&W0?)1X;c>eHX@o&&(WSlk5X@EAzv{keQKRzXA$3P zQ^MXQZTg^(9i(qCk4dLFDF&~uP{xz6pgKv zZAldzPrP4ibmS28Mk(gg#s;2IHN9*EkOAa%KNmX({YH z;AM3Cd)^++aYkFOp+In^-aPTNQrTo1%a4I|I!6SY#%x{9P}A@^C=ixt9~{j9C$X$| zHQ?`bvxVV33;Bb0>L0+4MQv?$HU_V3mAGGjF+hd)`AS-S+WzuW6Oh9Hj}_JeI#=dp zy(ZPABcIg_{A(Pg$b{q+1p2#JiEVg+r38IG}kDvpK8ta%q7BO$Dz$S4O6$E#!2;e7kDdRfi1}WLS zWLo=M-${iBac_A{8-#vCy!||G=Q(MnO*bZ$9O(9AMKmtWFwf+~8EYBsazN9DgiF^{ zdv9cuE|mSV*4WrrgJGYaUrME0i+^0LmZ+iJD%!Jo7!m=gG|eWh3R?mK^_G>JIRVNn(E@x- zb12;$Z{41T2?5)GK8!HOQI>4BGsNFzmTVf(>bof!4CkSi$d={wy7clXI+W6!!xbAZ z!8i$!WIWnU6P$7*m6+X%Exi3$8%Syx;2>vX`VAT+PbU$ewc%ZUx#B(vQb~UG;8uv% z7+i~g;@eQap`TmSHV7CVTdPX2I-Aowk;n_$|lxja1u}=2>9=rWJ zhOiuyn`73-Y~P$b>n}2JHa(0q4g5bg#EU9s9Kh9LVBPx$O_gj>tV(klDf?Gp=dQ_Y zE^N$f7$#SQ?HqAU$29<}SY zfqkDwUftU`Q;>4zvck_E>a)G`t9in(HW(_sdtnRrsMHV|p?<#f8~j4s#zZ2^T-%>M zP1CsWXPnSy7YVhdQO++2fGZ*9JdR8cT$;OroF542wYz(p{AJ7t{@`MTx+a}~Wjgqr zE<`r_T9t;{mH2({MCH{8c_}({gTpXfR174-9jH`9FTOV={#(aRLXsS-BtM0E1jDAn zMriNa{>qDb80}bpJBhktG&D1_7CXem-0QF3-k}!WKn81JKPeX8Tep%&R(xX{J8kRU zvg#kU)D*vL05=v0xHpuW((3-NGQ_@N_(neR^P?N&Hgrp}PB>PY1DoR77ot-6b+*cH z+~lzj4a=7&B*6tK2TdfG?(t{Xd}Bjzq6}%Wc7UgA^#)(v@~b>Jt)mH$uVz)){hXYC za9H=QR@;gq{r;K_IVg+W1ykO?2kkbXF7uwP*z4aid`waey78oSS?elO>D#hHH%TiG z_zpNeJzM73N|BVIZ!peN*B z)xUD`A*`J0?8ubN+Th{wULb{nAGfC*+2l<)~ z8Nh}Fiv~MjgVMA)LdOfCI>)ghgZmrC)SMXt+h|U!5(os^TR1b4#f>{2USU8Jigl~$ zbd1r#Q0w?*&m*oy%t4E_@LZ>onasBADFT^5|4oVJPOMWK%_@w}NX;mG$ve$=C}oOf zH{M~bit=SlFKZWdAY;`;{gM%8+fZtEokRHooj)Mshwkq~3EjAzp*iY(fY1@2UKv9I ziF=_HYrT?Wgl@pIPzG9K0-~7`gdbm_p3JzBSI6Yl9SDinrNww!ncbHeT`x(v?+taDwQ-A`zE zT$X{57$FS~F_QvGi_rqk;=E^@m}Tn%ukYQ&vi5XndNmcdI* zQ-jMILcCp}af;yHlOQH%lIOP%cQ)vTZMTrY9X6E?hlIC`_#V1n@CjD%AS|wiSGRa+ z&DsXq>u!Yd6Cc|YAP4DNQCM*(drCzNNeS4x+SW_O>G6_G+z|J>p8RE8nOE@nkgkr- zi|%ut*wBm@8n2l)Nj|d}j8{;J!3v|D+5Ls1&HY7?e<{_CS7A-$80yVVTT&2eL6boE z`}UWoOC7#!+#7xKP|_pr4cj8%dVr9^yCD7zP#eY~x%YGMe5$AV*41cmZO8Wtw6s^;*{Xk{eQbe1Q`N=23`O*62 zY@X&fj`jC;CnF@V%h!K&jneTZ_I9qM#|z8r6e~=C0}*z2*zxUy9nDXd%}m`-)_s!7 z_+nwyULuRUIj@(5QFoKO<&aIlv+G?R6k4_V-)j#XWDM<_wtYm+`?l@ovo$8UtS9tJ zN{k1%kuWHzXyF-^@O_(br-gSv(EFryF)kbi@^MG_s3#6Q2Xqpv|ocXF=7b&O!U--x9Ll*-lcc; z4TKEz6$*LE9Zi`0P))n}sNk~nh&Qyn-1gJAC+NQ0o8uA|j(yTk=_0N)uW|gF&R_}6 z!rKQo8QjXx6L8Mfz{ykVgT`gO6lY-<-=!Pk%3VL-6%~nC z-?yGR_+2{nKtUpDzuY=oq#x>I(pJM|X4`LvYBqBKQnfW#qGsc16*YvMqti(n^Ute7 z7i_i~c6n|_1Sz3a295V}wd1uuCaeI5iwf&q?L9E5m)+WW&^R71Z zfRj%*Q58+wJzGbsOhLSEbu#@wFSmVg>M68fC%qFBO=VHd3jIjMn+*=~hjEPB28irqgZV`X98ZY#X_OPOW)7~2XJSE8f*XqSH z`vOTqpK)TJF{C`!7faGE-j48$IAB)(ES}cpr%J#HHZ@l}CnVlouc2C#CCjF0z-CtV zk&^AC5ep06Jmm~Q5qVl`6REpC9X@aLigi@iSl;Q2j2CGRzI?s^jvP=fN&98of3VzT zODqo`R|$nFsBqu_26qm*5u&%U@n!?%SR!5X84r5x=;CMTLbq@rQ*tkH^$l&02p|3G zTC*kV92I>cUIs&4;?Afpt*?ZRI4O^(4u|&3G%Bn6xUNjY-(4tr&a-yYIgY0nilhCe zfaqm4_J)0oFl-XDgKI0ViS;7hTC#sI)BpG}MQ*5H&~4$*+Hq450zwjCKh=$c40epE zcEl5&D8Hbk`g?-jh}(%juQf(~1z>bm0-6e=H|pDFl5F!DsDN_n=Yc>KYZ$7jmDUrm|Y53fyc651$%4A?_Ki zRHKy+kEaf!U8Y#+lj&xHlngyk`qnIDBToLzet>)Z?DOi!&$JsY?$7w8Oev^2Uk8SW zV)`X=(jvH$oML0WRuxm4M=Qc1lfU@R2-lI(7qjMIuW5s#47_97zf)*X=OfwLH1X`o zXkEW;_+~sBKh=>pSD~RFVH|%^;t7n!Fu$fC1U88}sK3AIP=Rjls#~IoP#s+@?Aw2{+LEdx^$u+^Ocb@GVwWPy^6^8s zymy|<5-{=@6f?x)vrTRN>|d{7F-ZB5mD(RkI6f)1xP~VvtQ*R6*K2~FM>yY+Ktt?O zvI6K@fi*zx5+3dW>>Eb5>M^*$T5R^0U=x401a1)nuGTAM!EljM&Zy>1)qaO5{W_KP zdJ_5;`&CtLfB_bjN@!wE-1cNT?8J)2?N%N}T&qz62b+M+3XGV5?w3EXAGvbIl=8v* zjA*9OR&XbXFo$bQp40xTV<05x1dE`Tq{x`_sIBz-_ecu0Tip(T2PD@dmP8}sh>s4ZBPWm`ZYvi+6`j^niKZ2V?7JP1Y6~0FonWo6^^O^JXr< zXJ4>|ATnhdZu}in7EJaChS}l|ojb|~dbU>QEyQjKJYj7T?@k7J_V#P`R3NuxxpMJY zrh~XlzFavyqB(VFdsN$=dCInqn5|kwm)EW#8HVrTyF?Sl82n5L#lNjqHAZ{v*n(O{ z7SM&=;D!=92?;#7_Xc*FwaW1+htSh_`{8zKNlYwr(x!)ZQfq6|N(0s0D zD9P?BJGQmota?VTe!>e~iGBzisD5FCpZva8P7yW<&ExTgW&1=`XRi9|0rnYf$A=<9 z<&)3Xdjlv`%p+-*Y9RMY^n!tY|O*eYwfbin7Y~KhrD5`zPg2xsj_C}e0w2T!BWel~eR)*9A+9XceP%5_2 z|6%|FcdQUqx=4p@u@7{G0;1-d(;4hWY$EwsIieH2J%+188l8!X4JArhtk29e=P}o- zX3z&IFmA{~701 zfI@DVk8ehY4T)0k#AdOC47CrN$dLZ_6pW*~RWWDWnw7IKGu;HXygOBHIwvKST(@G&n zB=vB-_xI%XB|RoxZ6P~4jUSr80dSdcy0b1*zQ8WvgKoB*wD4SgXJE~zg8#^z0Z>9mM&|2o9*p!;%V#1VF<9b ztpP1QvKkyg&WVgJ(#m}xiD@A!Agm!3LPu|n>GjKBXqSA5Ad4DG&o zSSMh&!XO<|shgQ!tHa_m0Q&bdyJF0in7*G^@|HB$gw{Eog#i`nNGWv<)9@Q3=h0$3xUfLemxm>n1gyg_TKgw`>>`FvX~|G;>$hgcVZ zaYVbsn(r7K-L@VUf>C6#+ZW*eskQ#G{01c3oprPM=0f}B3u~GG?4SM}VA%hfBZB&q zYms~Kjwb@a(=yPf{lGngZ{ud#PonzG!WaeULV+j#wrfXEYewaFcORj9PlSd?X~sNZ zzIt43Q{C-=p3^5E(wTTyr0u5i|%9hDuZ}`9Z>4-#TeW}1f)1V zQ*ZiDLyRynaAb@UYWQrp+D<#rV+eG9Iu z!GX>vNIQJ$Rv&kab6?X=$HCqnVaq*c^G56oLgeLkzR((NYcVB?cKK$tZ%k#YaN7&*}8#t5ud&ENXOkPZtz3# zL31nR|7VNT+-bh~F|(r_lBiEuUPi0eCpP}%$Vlxi_!oWXW$$lq&!1*Ga(eO8!^8Dd zJ(B&>7i~;azMnOa7w}n`=Ur5Dt_%!s4ni{iQH_SftfOQN59B0#4mB~C+D%h1Z?-?F z3EF<2T5r@g#2%N|c$q1jL#3&cl-p_>dQ-QE8^U^`eiz7F6r=V&lEk$Qk+_b6T7ML+MZV0L90K*#o7y zK6in|G@=6+aq88_VK^j^vqz(^m)!WQg%~Z!$y=yDQ*|6&+(1NtkhQxg#0yQMO?!`XXHm zo9)%&q2=b`v9Ke01&IRFTP{C1!M;_k-_>{_aJA0xnlqM0{^pZ*Q)sLGw4@zpDkHF~ zr-Yc{K!1VwqO-@KV3pEf%Ix>RfTIL5b`%g>r79;4eNqr48$o{-3aMwvP;5~X`3bv` zXYN1aq4RNhtn;>c0Q7otg!%&AefQmOPKKl&9qoG%r2SicsQxKbxp7XrQlg$gBl|`U zMX`}!`3H~T7^<*`xEIVd?*>b!HE;-6^+dv#TFl#?2~Xr0ZlN2CXxcVEl{U{2cV0d8{_B8e4BNg!2Q;PqFYdBEz=ZcM^1f?@ zb<@&@JDUYES`uGt$G4hiI);`D4G4E3hx?0pqkRBhMma7Nbn?y!+n3zMm=Y^by1drJ z%RB_ej;JPg%6R*u<@Gsdf3Z@PEJ5RiY|>~BtF{em3}0t+`*=6N4O7)v_t`zNE z83Ilc5Sq$A?<-)nEQ#kZQqQt&89CF{-0PclSvmhOC3nTLKqHCefZQc86*dy>;{dS+ zHBN}|?eX~f@pA(Ug;0-9es`m7m-F!bGI(fI=Fz##EL|94BRNYg&DXf+7YKNe6aK|b zC;Zy8Cg64fiG$i)y_Z^N6PbfF_4az*T=J_nD{CaMgbR6^YoOUZM>5Hn@$5mJr3>Zl zyyEVAOmU?!r_flA11g7q7o4eGED<#|G#ePj0@S-AwAr}_O3tpGgp1oCiog5f)XwPE zw|^hDbR2QVA+^olH{KZ7!?ZZnz6e!RwE~ULG9o%_x2tUdFB6yldmfc|os`|{k}i~2 zvxQgWPBOE+*NV1&8UnYlgtC4^&S#`z4i4F&s90y-Ii?qLzdm;I#tX$rPtbxxjE42Z z(WT1X!ec}i9D@4~@0%qafy{*tmGs8NK8x{m=`c^afKw*yKJj^)1}fwuP@J?t|7fEQ z`27cYmG8j0Cu}?Pg7zkzW%G>AkkB5iD~#40Ym-B922}TKLXdbH8fO%@ST5kS-JO9n z!*mi8qkyyc^EPgX+IOn24&h zjUt~91-wLPj)@p1LwCs@W%;nE_D6kDF|q=`w3jP{^%kTawk(8+@G87#NbNy}pNXa$ zhIrKMNR8m9?#&JLG4Yw6Wd-kYKRQ+vox}A)z)TG_T4k7*iYQv z{P1-tft$2bnOtH619-3{QVECB$IEH=9impB1DCTou<`tWRUQI(eLg+YD}6mQDqFCT zM-2qTk({DEJpCuCkwrY9c+)8}ex`aY0A=nofGbyplePWnq_|Dzn@(vu6G@tBL*@FL^R|2 zrfBodPEbR(1Ct(Ku6K71Pluw?+^kMsMt6!N_)7vSjeOIRtI3y079wZUV}W5(FMU>H zg)|v))IdT7Zv>N56LqaH{}ξTQYaGF}{Wp8n`~aU1$`Uo2g%eou@$&o5n?60526 z8@DVtD0*K@E*1m!W|6F8A7sw>iXLIU<+a;xU|r=AN%}A|KmIL9<@M;!>WXo3FV6A7x}inAy!mtSz?8UkJ+GKvF7tC8 zqVCY_$D%O&QncRNK9X&HF3pDD=unPl7ahwj4nAB;VBT(}j4v9??R~!q!<=ejpI&dyuJXsReZ}T@uflb&ZF-gK8o6tI zBGlHOwR7T(w@uopQbHN>-T6rlSkd?Oog<}O+DGYD`xf6MO}`5vH)wGaKQ)XW(r6- zoFv1)A{JQ~RyCMxrlYLyJN9zotW1ze&lNPGMF@8elW zV}Xg?Dxl9HVFRf5!AB5J8RsZOuoKgpNa6eZ!b|I}4RJbriW^_PlDaH2+aLH0Jyxo> zwsbTZ34fV7&w6qQM($&tRkLp=>? zHf|4&eSK{V4Qm*Ye|F{TA^v)t!})Zenfr~WYf8p&fxi*LD}%qmb(Eq0FDu(tlxor- zz+(?D5bxZgnW9m4&oikqP{=CK)}Tpc+ZI}~@=t#)hA5%WJh4wbR6JCXmZ`~G#AA9m z`}e7Q7x%CO8vlH4!oqr4J0IQ0eo)sikp?E@r@D&L*xA779y&dGbE7p zXv&@_2y4rqJXs_)3sFYN)im zoHZJ)s;73&$)Z?|mRY)y-QwO>A(3)d4_8s6GR~W4ye3DhiBxKpJa2nQcnkDR558e` zkT3~dW@F3g%DG1V?3NEd865B151_`%D8wao*KD#=yXsW0!(;^5ws|SKWi!_xjKqz; z6)u$3BPF81@Uwo6$X$Ttj9P#xH%P>X=JYnKt_c0KEFHBDkJ$z zl#p9J4p(Q!_P`1^_Uv(vTq(WGTFaH~<%4cY>=vLtrl;gAQl%KP4c4V+{?8`g{kEoyU|MN z+G_d}BUTFTsCg#R$ZTD7>7@lZBvd1$K0Ua4L0Bupb8!%B?@{#0USQ6^;(_8#YuW!z z=_KZPTx<<6MRvNJ8W!*6wNALQdkOP4_ zgxyy!_jTFYTCsrk523st{#F|`OWNuPYQo z@w>*Yx&4Hn`#{O-@C7%vG<_V_sPe+mVuPUa0LHD=Q`wDOewbj1C;#k~bJ7NX`syRO zO(M=(=e7n!2G(8&sr2H*Qfw>v7(d1!4RfO0c}I;m&VKP}h-{oO)`~uY@oaUEOfM-_ z*dD!FhLPKE?jRz;vjwWFItg__DlWE*_bw|cnwWHb~A2Dpr&z!7?{($4tFu&Qktbly=y#J z6RqLEoY0p^YzZm*me$ZHtL32iZ;>DD0_s129pZ&)TVts=@1s}9qG$7X?^;?R86sQc zORKIIgpIc}DhPAoi#geXzLb{L$_qbtf06kUA4XWMe^K@)VSkCBp5(AuZn+A(X`EXC{h!Ba$<}bvfr!uhXvIZ zxvHo*zL@3)RCq}p_2E#K*tl7=?Vgk9GZ;*zH6Pu(E)$ctz>O00LT(lWwBwZa79lx4 zC71rh|IbAC1Op#gqaHG>l(%D(vMbVLWFMp!)3Wq4%-_bd5q2C-0$Q;;qj~9p3rq{; z0s4kz0y43%XzqNwrRgIrOVpg_<2}n3WHuasf$-x0ors z!z1WE{D(sd!U*uS*@@aw?;Go)HtXl!26zd1lH*2nbA}}9X+$Q1H-1tNbUGUwP?2&0iKY=eQF2;=5zDKG2 z5e0{Dam@e;0mu&^a}#49$KeIH_v^9E-mZxUb#rF(Q2@HVqvSw%Z|LyOBc51Rz|s-c+4!wFAoBYS z98Z@9#sK$34T26fp+rZ^qtV>J@qr{;RJ?u~Ve`0)`#26IQnW7`c9TC|gSABX8yr&K zOM>UBXcZ&@6v~@WeJUg!gzVd-I=R7*3iNst=cmAoJWKQoyFMepEPt=)-eIZNTk>E#6ZVKcD=)p&aQ;4 zb_y7lX{k|s<3Vd0evLc|m{AV2P(9;8IktHI;gjl5I+f7?MG#v@8pFDV8^KPx&Bv>G zZKA70I&`%6HdH!FHN@tpcrW%<5L!h_cJJ#V`X8G@?`i5Ve@D8z?-0T%AAIT{3k1Jw zjz5p|&-GI$sE=WPmL5-!%Kc9^`+HNlzNbcEwKRNzL_?frN7jk*J!|2=Gu?aZpf=Iz zB&`T;lmL-Mz4kt}wgUf?B-$oBz~teCC}=`U`9DjE87Cq{zGLw8rTDNq+CU21#uX!? zX;OWT<0Yx#Z)T=iafRd~)oVDvq-nj-*ibfsPiovr)o1iIoKT<|c{uLDS)Hr`5YQ!V zv4WR!y0z!WDR<(xz|FmzDska-?dO2jI3?Q7$j0miABNp0Iev5+kO`i?ZptKxVi>_W z$O=^ZBa-wB&Nw%#%I?Lke2IQ^(#?xfnTgLiw!@R4P3vBnU4-=ABHInI>0N26vGPkSC+2K-yXvIk&IRNC-e?j- zCZDR+Wpi75rjVp*?~g>E#_0yzPQ4@(X+EFu-XU3+Yao}`qKa135uw*|rw>h6=itF| z%Zvn_2BNbu_Ra)-2R~Uoe=hq!@)B;_Z!fhD+2)>d*kJ=_*R~dD4AlsZaHGwpm>#NR z)u#{GoBF+%(_91KDU9WH%yy2xuQveWWe&%7pg$u#_v(X+UIjME@f?fN+Y)zld=6&)I{3)lMc+tRvC#OcvM~bEQAr;F^uiAWb^(gKT1AGI3VRoF}_g zXUwxWz*{Ij7I-XUCp8_Mw6Hd^+azn7Rb)5bNc(}zZ5Io;i9^()vMv@|=dGWtYZm#7 z0Lzu9cC;aC@Ms2}Ub4}Kmn0xjLqTv^Nm}@vwAo+@bZNBT7*~yzi))a1=O$q<<@t6J z6C7cKVIK6a+K<}{xFXQr80Df1FmZ)_zhNkk7uao%YAc>FVHL0FcU>$u5fQif!d(3| zJOxG}r&q9?!|+0t{5G8I=?DH(Md=!#da{k!(FtT)_zZLo!};eU9a)IxSvx!cZW zduZ|G8x4(`Z<_SP*2V6b#tj)E1s`No=;4UW#MC(zZsNM8OcqV}RAh>*?ZQ<4OFDvi zO#h`#(9|6OK=62-v;?aP6oNQp{4kRe4=)q+usI(e89cRhL5R4Ml>8FJHGl$N-Ar|_ z^4rzOev}n!j??ql1VFa8@mOMg;CrU(#-ImOv3#5!{;^Y+Jk?71NOu%(7U#vpNdWPr zY-Iz>eNyr=DGk?2R=7=d48PU?1lc=2{n~3WC}~=NaRs#In7Mt>XY1X+t7Ok|gVnVM zaZ9k4Fj?A!P}EppP&PR0u7^+rC+L~2HHEM(F4+UW1a4!PXm`rud=csd%L)YdEh31x zS+M~$K&O7CbqH^o{YZ`}=IY>b@lXHcdTk3%fz?%(Yf)bb`~2a-&vzb%Bynkr1W0PX z8_mfEz)WrfR4=iUy$2=*tx>j<5~<(-Xq@WNyy};$eBuS#dOjTU6KJN(XqJPPbQO}t zm+0Nsz2@tVRmt+JxJ&LrEtAF9H3FB!3k$L}ga#IWHpHJ$dw83cf56eVz`|v%4v)@G zkgt79Cz`ur-zwN9ym(Ra_~_c&=JlVqM6L{seG3)*1&Q^@eQluV%B|}vgVre{ceyUw z_w$q+xURqx5EaD#onb`$r!eGmYn~F-_{T~U1g_u>yShC|;QB8RY2N(ne^+tSq%9|L zrv0oZ+JWUCsRGk%vY$Ya>r${+7$;}|s|PIB8cX)GAsY>V?^m}3HB!VGLJlwp_e@AR zYlI)WVkL?66P?=D44=0wGR$wRqG0U!B63J1F2Kb#8mRPrja(peSS5bq3gIy*I!doD9H(({fGdH*op5UKZ>y1pWylr0 za)U^wI$n@>fPo_H-Se%z8o-&>Pau>{uN11Q&^cf`dz`7q7JO<${Nxuh-wMbiN!x2d z{gCdb(uDJrBV|Cd8TM<>12_vQQBe* zz2NEzK{5=@qP0}qQ&S)1`X_kXvHct0tdINr(OjW=Oz zO_8tk*CiwarxLq-`R`O#UK^)P{pUF_cD;ywvShdP4Ck^LwoV~bt^2UT(MXk%hO$uG z96P%|<`NmxOEQexoVCFgkC*b)zak4krU_=4S4nkf(PYp}+b0tnftTg`PaW3SJ4k#} z4nA7PLmSFb zPgc@t6xSwbeQ5OeAkrei-g~hT150Mw&a-9AUa{chrbbXPlJED{jEgllN8x@WFX>v-fLYDrhE}iMAFG}M6B*MrI6o%gJS54g!%Wh-(N~D{(ZO~# z7!x3Dv$=doHlD)oW`%-Ic{}*;4Z09d4Qb1SG|40X)h&0|VntVic{_mLx#Zey*>y3AaOqUj*O`R%=fR~^R6x~72WDo4z+||&aJ23hj^S9y z!2s;8H)MsbSDu1y0w070u)iTRAcyErz!4oO!O*o<>S)GKci0`lqpz88hTfP=11VoS zXCoY4dv>0JPD7$-wjD{s%4=$vm4BK~C9Alt4L`NMBR^Jl-K zy18u46KQyPz4l5mLtOzu*Au|P|H0n#hUMF17C7993oi0|dDZ`{b*-4TnRTSa-p3IT zZu=#Ye%B1NM?!zR@xfGEtTg&9ZPD8iw@*&2H0#D^C-mqhI7GbjBdIWR4E+%R-Tlsi z+-8(i@euWnF;L+!B2JW$>Zb(7!NTH~PRg#Pv{LT|XwN?(pssW1te+v3XU5l%h^ z8$BC~^)>zAw`6q=T^UB<91%?jr~UyVhm2p3#1-JT#?$NV`U7ELS23P+&q%wtsAHq8 z3n4lruJ)FL*}U@KwFSI~{5Si>OC*Oe)!<-m!*67C9!zSZRdcM1C#oh-&&@|aA1^yn zj#wIQK8#H__Qu6M$wc%p_emJfE;OLc=d=SQ;dw_>V_ zoNuuHunVsUT#{7lK?lp$$CQ1;){yvL!)J~rY!?jnyVH*au`!!4RuG?P9ow9xDu}SL zDBE^z3jAGK8)j!Z%qa552hKfndLD#c#&D9RyY;GftXmmG6c8NM@WE6YF$ZT&#=`0H zZv^l~lB;#92-eWAWhQd)(t69yc*|YU-}-%nV7q~y9uf929F3R8-hBKU2XMM*q53jY z6NV2F76kz{2(l2mUyb#eHTG+!M{o-Jk13dCL~_T03m8ZCI+evOiC>Z3%I})S)4$&Y z-56-w3Mz#)XIo0RYd50|P4Xl62JCkUN%;p`{&K#rZ^H0Zc&*e=9A+;h*yu0}Z=T%^ z(Wu3FHG^%0+aihjnUFq0iSmwc_YLq*tor2%cW9~&}hm6FSFy2 zrrNyvwVJ_+3&`bKgq8G})8U4iu-ks+Ei9NqfTssbi${xq7l0>1_ATHj$>l~KsP14> z%&)L(Q>U=#N;LIo!<-?QF?M6-gn}Pmzm#ykvXQCFS1Gt@qY#}i;i5|NLcJDmvywbt zC@L2D%>w%SFJ0E3Y)Dt@R<=hmO|7k7tzRSwu>QP034HuibkW_cD)lVhe4T%K18`Qs zn;m5CZhHqnIg@8#jU+?3>5*lq+6e3M*{$P?IwQC6WLnu990MRGe8k zb1XzD>rHvU<}sv}{2C|7?z!+0IwRqHp=C`&xb}a^G@z=P!6pKVQ@?pD4AWuo_QVuP z;d#yXJN-P2|DsZgu2)lR`Fe^~sVLO%Z87)${)V^aENsL$RMjI?nF!Oa%d3z@AYK`# zVUDu%Sw9x*S55Mn<%;%lr;&zj!`N%DkZU6Ydg4d3WdI7w4CU+pkq9Jn;TL#_vj~mq z{@Z47z{==s^>q!lEFT$zq373h9fnpTqH6O<$fAcu8l;#39>ZOf_HE|Ek&(7|+N0Yv z>1MbB6f)~tN#S`00dIYjmd<}aq&AR}{HOJTPMZCS%T`*U_*>w*u4w!>`g zrGNd772&72Qnn3oVdcv|6&QWvx4q)>i$pEKHTSyQd4Ec{_kE#)M*yE=(O zZxfP!Q~x47#zoy*T5-9k5YG{-1^U3}iT_gb&-mfcj&v(<%bvQ}^a{@4JU^_0By@%i zkxi{~ZQ3u;aoNs|I+Qy|8rA;sc^&gPk^z~S*XQ(&y=;DZJvW_oWi{)3wv{ii>%mzd zn*1>M=~aRvW7wu=w*&MIY@{3Sw!BZ_wx3>DY00iPpX!Ht8NhLifXiwc^}oydJs=ab zUZ@43G^#QY^}9r$C0s*StL$Duf2|bU9kW!5C**+%tEjg+`gpMcekp5>&hbW=2nMO! z8g3_v(Rs|l(_RfMT1sLN=Y`xVym^kGV7~}@vqDXsItAt%My%e>kO=U1 zP&vxpjhR$Pug5(-$a`RxhpyRdIeE!%C(C;P}|k5!(^(d1>u*C zSvKOUF0d7DT!~>aJjBuLV)w3;B(ajQjk2G&Y%SY&S=v^eJIjbm@LV6aL@l{~)a32a z790fpf_gXel=*l26hZXSIs2cX#n_Iu2JTW&k8N96@z~$54L|~d=G^brNUsg#QvX)A+ za)W?t-;=iMTh&iIUAFJHdKJYdjWiN?fxHseL+$lT zlotuI6=PrV@;cDxJStk{B~j-bSi8J^ejNC5$?xPy*W6xH3>*u__g0fe_SnF$6W|Jf zbDAB#g}yMsIm{1u@6uminl@DpI9R5)stm3)-nhES1wPS~GsZ43%j_Jz!EYw?dbhSS zHL55-kBjy;y4v^=t>czDRVVla3iXn5IANu@$d@8FIh3@Zo9xRxzvV;fu-qwHm} zJ1C^@|Fd+=nx$X=I-H!VK9bD4aX~2`>@*p<(Cw=I;zqD6TpGF4SXt!lc4)60v*O=mkY-9gXTu`nb9!m)*d!zd1((IlhS7JkHb zIHAR6My955i{|~p}c4jGTD||^EPM2N_u7ob_o9CFI ziXK;-|1OpB$kRziCG<8v?1`Ljg^)bz+s(ZvH*Rrpak(w4X9#+qu6ZMV-`swQ8aOt7 zK*TrfXEAK_N`glw=L|1z)v0YU2DnNZHIrl(0=Q73yrjp{rl!CEm}&oMKqD3o55-~_ zn;k;}nZ_N5h+wW4KXkM+Ov zb-Wcv?A#Zf4C0`AIlru&dDH>bK+Qf5);DiZ(r+vs(e2cqk1v^V;kDv8Ox*&%V#AdT zI*99@3<7o{FX343J@7&qZJl6_^k3n{sM5TS>57EzhP;nYhBQB;{Ny2-jEJGCDqvj* zHL8gzmS5%mU_L=jKlFZyWFV1MFm`A9X|l+6iNEjnyUpdp<}+x#`6AK_HiSF+GoO?p zXodQFER*R70d`lDL>Kp$F|zYI!xe#saY)Rtb<`U6n2lcJHo^qe^^zt1rJ%+n)SC5k zwc-DbRhKyg20*1GRd_RPg0_66D68Kcb?knkdcJuGqx3B)-j8lymYY5?T~btTZTa~4 zmhXrw-H8c2OHUy+_fd?AU+r$*1{OBnfjdUf|5!nqaC7wAs^YN+HG~uU6@Y&%LCKi3k zvS8QrX+ZGVBh;TpwBe^F7_-Va;-`F7ec5$9K*Eo+^_5W8O!jeC1%MehU6t7Q=SdXz^P3s#qK$ z$85vk*Xi+b#kSxBrzXl`o;9&;w@<5lcRepNM%m zoCY}X{q}YxTcE?1yG1T=^QiT#%xw?oTvoRA^tsY``{??jTBhqi&VVyJKW1_@Huv_E zJI!0OW1(Jlrd~FV*Rn@OP|#^s%vECSd}8iRnY)7}smsYT-`AkbL7|9RKZE%5odU7NY>tT6ozn*mjG{R}}Ue!_{7 zX4srD`2cHAxfX#3aa?xbprMocBwoFlvAV`~34-GzeuZXps*a{pG=Vl|p=ic?-p}s) zp^v)0<_aH_l?!U`82P%|<`&1`9WSE(DOxMv^X7<)MDIxEDFF8Nql3LV@&hDF^?BKw-o z)Sl~VBU10q&VkxiX$&pbcTLci2|S5{p^#psH{-jka8Ia8Sju|(_-f6Z)CL_}j=j-> zjf{--hbnbQU11%_yhxUb@G8H2nY3KD&Z>2loX)$I)VM&yIHIDJDmdqa<~u;56A9rX zbPmgxUK!Ad^W_Q<-%Eq~&o(7&NheZ?h2#U~jiS*ucvKBbXC8pzz!yr(Sm!0Q_pkNa z;#}G*!ny?s7}jYO)c~#6~^3C931dRwOX5m35Qo z=f(vT;3^WRNWc$_l9?xvd7DOe^}X358&^T{I|{vSDyl`me`m4;M|Ym-6wS;q8D6Y7 z(EtDdm*`?{;ccDw-`8LyD*ufU6|k`d@R)<041NX1Us9oKza-06seP-2aBDy^t-l(z z?$&G#(`zGMXpJt;_6kVIM{EudsZv`W>n-!(sMf3%Tg+hp;r3EX-&n+?Udx$$hUMy2 z0!X6_uK3ZIxu}8KIVG`gAywSv#CrdtLOv zzLMpUg>3!DBpgT2!k{T+S?Y&kLA;BUeCEupFVVUKo}2QvLilpkvMtKZArgRX{hxkE z--f#r-&?I+a14j(Aic7iRQYbZM-b=$Ty7CN-VjVEij@&-qT=61c5KJ=ODF8s_^79k ztOJd1g|&>`_~HeP#gOa>`$RM6X9SGXc0>9%8mL!lpG+=HFXnztvt3{~mHJrVWHM8! zA%l~d++4c{l$%;VLf}KS532d?g>^vdG73oR!^jepQF_ivKAHP>y~>ua(PllTk)T!! zCv2hGQF+HXby#NLs-cO!`G_PWB%0mch*qt(h~>2w`{t}sl9|p#PF9;Y?>OxjCvScA z5CVQfN8OT@1>qTOwJWP1kJ=JsbLA>C4=?UEm-LZrZ3Oo+Eu zsvP)OE{3SBeBywLzEHFyop-p|XH*Gh zQS%MA^_vEvi~7zf^Z8PcFdrSZEPcpDERI1BTMI3AF)B{#mr3GdBQ6?^AKiKe9p?5` zO&K2iCRJ1BE94PR#gKYHaWj1)g5fIYvjK6m ze?zV;=B(5LA+QR{Y(i-O&n|VdQb3*gCe~q*k2*Yb5 z?mZQLy;%7AgpFh;fqK2JMXOy0b8)`j&BrMtCx-}*=%MxC9`d`xWeq<%(;{VIrn<_T z{yd{?LA4mX4(HUYm#Pgr@#a;VR!er@93Zl14Ud2@jj2dK^ka@%WkC=AxQk)Zo9#F3Q{O7is5jrpK3Keeff) zwKt{&g8>R}+*3sgiCa`06tP#|@GNaqL#NK*sm4I0Zw^d8l()NyE62J_)l=UB2u;46 z1vTAQedSTWyMMxJZ~>?NMA*>JZV08d7gokml4We<6!Vz&1E!*^7)-(OWVVPhm8ip+ zjrJ@N%^N|2p$@7h)_g|0^p(*MW=QeYkjPdn8qIs?@0wM|Tfe$nj0R6N>=wy3b|}}d zOCSArD@3hSy8|M0!Q_+;Vr+<79QF}XyT^xYlcl8g=Pl%9t(Ns z_YcVQKDQY{$5@}~A)4u{U0c*%QL_0W+kPHRc}^%@S|{`jJ-&IDh=h(uTS##Oh`jHydm-;nlV-W^fxZxVTC6qsAgt z2}cr!gM-I1xQ8RPRKc0)#J81SO}Xth9aRrh@{^17-`5To%A(?XLs5GnH7?03biPk6 zQ|$4iWnhnQ4)0k8|BmFN=FoHTv%G)t-b6_ohnKpD{bMW!3G$`y9)mBUNV?Eq-`2=c zY?{Y!yyNZRN%zw`y(n72Zs4Jo#|5a-j=&mdHbm8y#C%Mm+JVCr%8BQNBzX#nzqLBT z{qv$9W6M$nH_1H5`Wo>46doT+%{vC)TS0f737=typeO1|;rDW>0NI&)R)EJx?71G~ zb!^#R2H8kINO}c*$FfzB&sMbS^(+1~K2+hKJw(YV{cnpC$|jp>4zc?Ef9!Y%vg|&> z*CzW34E>+BN7df=ITKMU>$g3)&R}Gt#o)Z(J1Wm`n+NlE9My4oU?OW zo$S1Q-l~5EWVl#`1A_0CKBTc$aeTLm(OX0xz2A$ib1OiT1LgFlUlP657mh%}vMR^I zCD=gp%!$t)$`UtAR&C`4f+N8!{x>m{n?REO^ceos7=D+9#@)hlRObcVIw=`KKcG5> zH|t-XvXm#`w4&=6%7@cm9$7ta@z7Ut=DH84J;^3+i>>=HLwv;Mi zpF=!j^<9Q zm(8~twoPAZqQTFRU`0C!-r%Ps+Pg`}gYbjt>UnHSra{&fYo=eA;FK>B+o2H(e^_lu z)QvLIJU{=E)8lzslfasBtz*UaW*sCeyZPKYrRuJB%b?u`^uAGyu*!7v(QWfK^R&iG zBQOtmHab?oKxTcwKH~DFPP|W}MOHOndiPHNuAcs1b>)#(O2}e^_y#DHOQu-fyrkO6 zmaic;Uys*L_nxT-=z`Wure!t7kA|q1;Fib4G7T}!c_61M$v>K~?IDqkoYW<-V=uPA zrP#*Xky5$Ni(~*RQyp97Uzwa>*MHVbvzR$6*tZ~WZ%}~PM%RxF^YPE0pQ#M1&XwYu zrG5yu6Np3^Y{n<-ZPQJl0k%Mzt$+}aN_g&FD5dvJjrT7 z(CgB~-M#tpvwc=T&zjeKkt4DUNz*O3WHb(3;xL(`t799Sb+enfqBCEG0l}=vv~&@a zf52YO6rb>g{dY3}(u>RFu`_n#v$1>SZ5tE>)0!O+UB3MNM{jjNO<}0K zZR1%%aRL_M~|FIQF!^NnX04pNmu>;1wi2laW8mD&cy zSOlJQOj-kKdc0}f?$^vuKwnI85gdp&U%JFPCv5x zb)0(ItOrqKmqRg@yXo{V;Pt96S~zeH)exCjOvl-B@(|xJ;8BRw@2Sg37Et)+_h=-< zHX2q>P2hJWUis>Ptc7Xu+zP4Th0wcjU|ES>4NWi_?qQJ;eR)7jCbFO1cG*$bWPM^C z0tEADOd3m0L?tN)9au}z{|8ag;7^_VwM1%QVfcSM_$|hzrNreb?xd{kfTCaQ0TaD^f{hXL%_bjmXC^>-1~ zMU9U2uW?=hmz(H|OwYl&&L5cqxXlRaa?6KC$BI9#_u}pjR!|#dWmUsRF<8w#I z9q;jD5On&m&aAZd4HP=7u~nuzUsfp?rm{5L(ordW)rVSe0=nXTJa4JreZ~|27#Ci+ zb9o>`P}fw1tRN+teLGKE<+d%vc)4i3o$gKq7KsS`MX&e6eh^gay0p;A*;oOBroPi!Y zaW!R>HBKf)=>HgnG%FX>kTKwCSId_>-#L(G?6=gyceR{ep7q^*%g|H*lA4?P`1si1 z;X)gqu(iN0onp8{BW|LVZd6jxeBe|=bH%Zbwh^=&gCgBjoa_o&GQ6a>$uHbaT9eSmiifK1j(x#TUsfPcy;I#g`Dvk zNyRoj#j8@={af0Ug~_=ymjrnFI%{p0=zsjWUrdW&#?Qv*&rbz9@;9cXkT^WkvA&Bd zCQ@c(VD3}jKgG$1+gN9BrrCO$w~jD<)$qR$jLAT|XOtKtTh1vN-pGo&wa>u0xC%#) zZj*|Q_+3({vv!X_I>>1w6Z3Xob<&v^s%A#Nx>O&yo^h7kJC*t z?`paNR}1MfBse%ITtpp{a%_b^`lS3bj}TI@14gbWqgYq<_VUzEiYXjB<LT&+)B zb=(V(0<7B1P|j7G>Ore3C54$Q!-Q&AO#)vQ2~YDun{?p#wCK@@S!H` zcbNg_EkiA@winl&sZhtjJzi1k)#Apf;_0=CzK#u@lNldrPyi#K*l@^LtGN|TS4;s? z(eF^keU}_S*G_Z^coFt^VG)i#g?5-Jq`as{vVWU&ddoxBvGV-tulnH^GF)j8$ZO^Z z*;rca4Ok5fse?DTP?`3GXO`T%^%yN%!L|^w9+#{{2%s~#Z&k3dyJFMt`+J=A`(geu zX(@`BnE0k~Zz559t;Fq-ZEZLWFuzci_dm?3yPdl#w7-^ysCxNr9J{Ul#$xO)+Mc|WAFwL3tx`-8acAfNfL ziMU^mpaH*+WKn-!i!^AmNY!m|mFP`44i=+!zyXA)iI5{4=3cnUyrNh{_YPj`6#l+^ z)a`QUSnv4>C?3QOq zJQoxSZNp0>##7lHoWOxYbU=~~NvUqkOMK8n2hwgN;spG7Ub)?v_drkcE_zih`jOQa za~Z(dR!UW^IEpKk5+T(;jn7i2&#Ldia1;Y~!K)tgo-#W^fY408E6S2aj7F({i?S6t zL})fcdO4M1IklH>WjOs~ZT>&~6I{dK{d40SYHXma zcFEXqsid$Pw1$Ay2afgel8hz9ykUEI-mWbx)~#>5yCOSGeC(|T zR?dQ@GPhnmWz)k0P?2^rIUFX__8~fm*e9J_xC;U>mlx&a@+PhO)f)~*>8P$}M=5D10ax@$Aw9IBRpeRO|2`KNTD zt}^_5Re+9iyE}>5Vm2*mGEoL7sOYfSZ95C>O>!Mz&pWoGi%qMy2P<$M0imL<!cv5Dqx$Kbz{XS122Y7?_OMoh_hw>PhvC3c4uyH1D zn+B_Zvy;v9ib>}Yc@^V#he+(|6>i{jWKQkpQIG>2G2ATbOLH;wW7)5+#n5jMZIs_U z-2AnhTMV=d3mpo@8ZFmcA+q`XNU9gecyY*R8vnUoFZ8K~FFrRDsjHqYx2|!NEi@KB zQDIkt-u z*RSnvZ}m*Yi%ED#C&-nG8cg!bc3*wvxy5?MDuE%pq_fglk7ck7V&{EIDx?`wXWjF9 zNq*`1P<{3o!%bO3PdAfXr`xk_sHM~M$JlWI`%eT`J*H(2Whum4tmHO=mhzXig54cy zdA+!B%PE5%j;{d+%527=sTL0xaObgCk1slpNUOR%*2Z13HBbIc*bu z5K>Kjy-Ahn%fRjzH@~2@Y{BkiJ709;USsK;sUHe8MNJv_>f2l8cm5G0TSnHlFmqk@ z{7!Bad*j4!hI^8Dn|f+nTwl~LzwGp_OCkHoEe>8J-kGlX_e1jCxDv&A*^U@j+ZNGB zB@s+lI&3sAyX4Nsncf{%EoEu1{Tk=8I(aLVnzYFuU8rHV1^WgLWzkFrNqVlChZ2(3 zB`n+w+|?nFjf1@~=6JpP(lJ)8^8v(^4NJNEC`fjHMyiGS!n@odcRGJA1+b`zt|-Gl zSs+=AZ5g5>(oCu8vL-QyJ)W;fZGR7QH}W zht(Z{9?XF+Tkc64rHo_IofJLt=K%%(Z248EW=9B0Z@uXJmwb$lK~wi-ST)=9?c9q#?{%;=i#2sC=k~a!>^V-C(6I(1i zxk?_c;XGO)TWwjff^A5Y#n_j1rx(nyxgX|;wJ;7Nu$~sj7T6V096Ai()$Z)}qf0&b3mQ=pVF0@C3Efou`(inYbNSRX%3l(c<9JNivJf;tB_l%xyUoOP zHGZUfRbaSUHVgeOH<0=JTmfcXXqWxwLEYmDlMcgzOq(6q_klcB)~0gQR~{ncvx12K zVI>F#Btk!!?wiDVL$<3E-8R=X2^3Bk*y*ZF5hx7~CqVj`o7Rlqy%ivWSkLahr`MP-9n)f21S zfqR?7Pfn}SvM+Chs+#}j$Lu$CPdO7?@qQfodV%uuC@I`S+Rj4zk5^=+VrT#5fi({( zL%3&HSJ#>N*-7HE(c*2Xt6TjR1?h^y_cZ|v1tiw6nU@|>SYA4CzE_;~`RK-)WjAlR zwSzaR=kxXkHbvoxo*Ji48b=77k>^b0n#4@zRzkGq5u5%2Eg|WC-gc{E19xGXY+)-` zY08tq_4JHAeRSh?zZuvU^kl%7x$r`ny|2ogw5o2S8f@C51xx|zcctuqu&bLj{1Qq7 z>k8Ssu6~QIJTJpn#Rs&3O;0v{6*UjS=|$J|=+omYflFPn1E1hMdEoD@d2rWOOsg(N zI#*HK@tbV|mXHUUOWS^S(U^|=3I1fZp!O4F;kEHc2_W9SQMa%YS$*vp^&t-^TT#po z?N*2uyw2If`0eXsQG@JrVYrLSatTxXW!LEd-re!58gF?Mv}WZI2bfm>66t`NE&_IP zl2of+gfIZcmxwA-*ux^23C%v^>knDxZqAo1CiP8BbEfRi6zy*^yx5|NN;lPuzF~0{ zxw&xGY-LG7+ve{@+6rB4ZK>q9cVfdPM2KF1^*qAdN7y7A^>6By*mT`nYfV8h4Y)7$ zxDTHMEZ^;u!pO~A=fJWs#D_KlPs%vB9C`R4{QOYhvLH;<++nag!@~z{I^+8fy9Wmr z#PB&jajuS$p$>{4uBUMMnT8xd#bhzI8uKuyVCF2+^85R9zzcgMG44L~cUGXb7#ODR z33A4%5Z%hwCwt^W9mMnQu!|)tq8|>U=*i9|zk>6^OyorLGZd{ny7QG>EBI+*;e$g( z{p7xwZ}#h=H6zA#TnENT?0g%?i)@C^!ak!y+Ha=-D_`F;Sc{#g4jRNJ>DSdnt5o|% z)I#V%ysQERs`cxua%=;c1)XmWqwq#;H`{~d z%hj%*<%S&0C6J6w%fk(A95$N|65Y68&DM62uFe9!db9xxoU^%W)vccCxvl)Kh&XSg zkk6yhj)tS)_8k>e!G-W(3p6JIsWdjkJO@&Ei0Ey&+Q4Mj5fl<~M?b3L)HZ@rzLsu9 zVx^A$d*`HMQj*ZsUU<1lztmXLs(PJ<>l)|%McOn3j}Lj^zX;$S^ODu3ys`roBm-*&cl|I3=o(D-s~#}{RJ1Gg>XB{$`V2PtzE;D> zP51M!6;N|&rkod(WTnn8w&{+f@`7Z5j`6xc(r2x7gZPDj7BQVj<|w&B%hEY1n16ax z>s>7rDmpCqH^O1z0#jMld@2CXZxUl}Kf>0spL)(n@ZAFz`1|`2^c=6~zbW%x6khlW z7_<(d1E5s5(~&qq-qjb~nJ1;D}^ax)V2B6;|yr~gVlYV8w{Mx*Nx3%AO~ zbfI6r#`FKtbXHMqwOzEvT}yE-F2#zww79#wySr?=|K-*R$qQjJsYg@zaMCXA_zpJ=uicB0ZCIc?)4yivN>>kNnx)ZHdu_Q=)#F zyG;Q2V^=_=q6$^dn5Lw7}y$k%J3rxwJGjz`G!NBf{}ogG%!i=J2}Sz!N`c=YR*@jidCv&Wxdy5+V3L&F*?y?q-Q=mXuKp8U z{2C}N_IbEa<{>p`=;igvW`$%BVR(S-?S17a-C~59&IsNRz-$ISuI-dn0^)KtO|jqV zb#VKaH<&x9!d!(8Jgm3%KLVC;MwdUoLvQz6yejcgS!5HECp&&&{{ve zWT_NKbLhce|Bbr$1dw}dbQUzY2=KWCj6aWj-u=aGrNRTps-x zOzXmr2eTf0n{L(Ith7(!J~e(P3t>GFQ4#&Ddh0y;;=YRFXHE9u=M;I%)W5Q@Bra9U z5J}tq^g93bpAW`uDAvz^4VC^G$ip;<_A+&c@9!|%A)Vd_=!&P5%gZ#|zn+bL_iwzz zWZpZepm&peY>On*)x13Om2*1$69pr)EydCg4k{WA4^^&2mVrPnjWIO>R}zQ1weGG= zm$c#MObzCt+==}^jmNvuVik+nn7$FcRW4)EhlH(m5tCE^UN;)pwy_(zpAN&qOe$*h zK${e>p7Kos^OcW(gxzV^8K6AAEANH_fACnraR=cKm~>DTZ8B}?E;kQPo2h`XxokRi z_Qr)3dW?5;BflC=K)>+%+NlshYB@}kb*+zNW8c+)cZ%*(#@c%nZ?VQx7Isd*&BI$qFqOk?W5TsY+ux%B3@82Djc5u#YKByw-65!3>=E zd*l&+yLWb*5nm*bSI@QO8027~vUu28SkSSYv8R#eJTwudQl@JZcC`?Lp3aCyRH+_O_Akw^2Y@Gm|{}t2Q=Y{s|P& z`?OjEu{Q@*N*|4##XmOs|FZy&UBfT*OYJET+>m?f2=x{>Un!PstpqZQcCgm?a~Pf` zdohGGsV!T6#=hy|+Qivxy-;{Ov%mKmetg8&srEv#5OhHZzL$PuHvisf9@4ix&>HUV zNFlI2g08395B!omC4by)#_Fh7Rn~+k#r$;rlk%7+_gAnE+Twq88Z1rN7wfr{o*zq< zQWw9-L2JSn#8=|e=v@-j>yv8Dc;zkDFqttH@1My6Y4|nsI9%*fKKFVtrg-{jig(f( z@Wv1YxmX4f!7~b`POK)Zr%26h!7FI4by(*}Z+WV|MKg!T1${-T2z->2nw`xrgsTBf zDKNY$&88;4UP*&GuNahD+k?=$>q}$L;F@-I;V{c{g``tluuHl*yI3`!kN?@$WJw6?J+EHqJr zp5#Qb3|s^ARd!na0*~$awt}xJ;3$jG*B2(m_q$g*BH8>syY%TOj^}7Fd4Q)cY+3V7 zQZR5cO>|7p>EUdNzHtT8(Ch#>3o_frpqp(iea9dhB(NJeAH zttM(REVaaCf+n8hco$jLjxqnT(&<;yLJRDO>EgY_ZSSO3#IxP}=G(^={-z>g;z zGcdYDD36*P1G-Aofi{ydL-8r=FnwzSGSIyx`S;&*?i6d|r3u9sUqzX{?uxdPHt_{} zFl)?^c5;O|%?;qurKYrQdSHy`Rx#TITEUQzUm6RlfZTTzHNczWR9ixSHPN?xxl<5) z#bzQ6fNavMv_4%U9$CsNd(pK^f)S9aa!7-${8aq=W!*j<3|eOd{~js@rX(&s#IQb&QeLoHw198UZNA7;lqN|v0CTmRSAhk4=;!)7zKT!m_h zshVATpP<8crfJl;r1X&P4nOBKmH zEJQ%MT&(y*KLgCMkx-7mfFWVa(kvNAkiPxapdw0uK@GNZx!;g_h%SuB0+?)|Ptv0i zb!JY_nm{}VA}$ZCxpQ|p3;rPKX0ZHZ9jY_xlW6b)kIHHBMTeQ1xJzC@DqfT1v`DQdo~#M@JcwUa zJH0!yB?kl$1O()|mvBJHFqo;e3=rW4o_9*jbXEU-Ou!- z_6>Y*4PJ)UTgRlcVa7of=MNe16VwRwDc*5~aS!k?jKF>IjfGZ$ZzqGK(e2ZeuU$r4 zOG8@q?2fzG450ltjBSXPz2|Ktq}vTY=osr(*&TZ2QuS67&_905qs<>;fRDEm@OqmR z%_%S{dRf!3A0RX`tvAAricrpdz2tCOXC3AKd!DDxa+aVvh&Z6?)+|4Z0VJ)(+CgL~ zBYdlCYQhi4ZbbY-Q8oGKu;#KWZi)lOqrg)!_$1xES65eRq?YBbmThzBP3$Mjcxkqq z-63^#6EVAm|DzYgH;{^pd^ecF8&1s$kA4=ydss{ZcsgUM?ntG2|Y;#FK+lg+1eye zbmU+MT;rA8qRJlHuqJnX_^(UEzZr#AHh9ZCOsXH$C<22kwEvS}0a5HvS_booCBxlYbTX(iQkPPC!G;BjQ`zrSrlC2WGfV|zFHc`Kfe%;~V3U3Hgc)+^*wLp$g*(|-d ztUX}@Udr;#4P&?d_wx?9%sx}3)7n6*ZuHky#C|lwTT6~!j%v?%h|@NdRG;@u5->~^ ze!~*SgJ8g5HRXHXJf(uBzLKSyN*Fhkv_1_f;$yiQPR>R~j4V`#Sar*ILubictGxlv)`C95%cr2ngXEx;(Qo zbG`M?;dycP)ujsDvBe(-PUTN0#t7?sH^u3eIF`a(Bu5-JWr`-AL)z2E+f^Wa@opFf z@0o|F|C!JQ?i?y|IfubDuAO_WJBb|l@(6KuP${qmk5G}FPT>`4*c|=U-`%CflE~1u z;P=bw;%EA^-s#rx8I-gk_{DRm$L zO&V<7#&srO5Q=*y-ID@t2ou_2FS~g1y?0s#JOz1us1TYZ;1iCkz)@$f#*n#OW9W65 z?HYl0@vpu&X~+(N>Bm*uw;w{a_MRPZztNMlj1oxV46VW#J&rY*=`6wJ%30Z>#lK(o zr-TIjZ-wlt%u)v)tO#bD~gS+vQpRmCY~ zaFu|K-~1qpSHq@Xy|nd=P6!^8Ni>1nBv~4HC(W60SWyRXPga>nc#`1 z54jhd3N261NCK{oXBb$TS6~Ctdj2fkspncUeZ&q&Ep@K=Z%m$C$y!Bl)ljHNwN~fu z2X5+_IU!PGW?@C%_g?Qj#Arlxlf?m7Qn4&ug2ODEeXpLiPGE68tG?tb8Fr+N@S5^e zDbxWPPHS@As?BfT5!UAzTartqq=c+3=Q4rj-NdqPWz9!^K&)TTiC**PMm_7 zMr*mUb0_$|1wFl<^oCnk4s1Nvbc1U|!>zyD<%ITR*&GiGG0uYPeD1Jlvu8wF%WX~8 zgViUS#cx|=3k6`lvc!%Oi?z}?tlgT>sjY%1X3BxU)Vby6s)N>wN8yPbe`m0X4_9Tk zsPVve)Q{*nM0u3s<2_BshzY8)R-alGnxZKV8zNA3v5uhIb^~e+URn4F-5cgAuJ5gHNVcbq{@9 z!T;BSWV1nj|I8x0pR4H9-tLax*84TK0sct+AkKKHO6d-R2lo`6qo}fxrFw0-!!!ol z`9sK@?(IONidj5wss36BAX4*u|H3%}aj+}TKlQR8s|VgnIQmzC7jFRDu@0&;^@oiO z+-FJ^rVcJQKy8m@9SeG-t2+n=D zjR^4?jI>Jt=Ukg~MsTZSQ=RtE#BiUIPcO}+tLd0>jH=}{vvzaI2|i1{@mXf>=I0U! z+a<5RntTRpeBQ?0j{g%PuQMTT@w=i`i2DR@`TV8p=;m%`MVOuV247z$k9e!N8W3N* zA+GDXS*Peelf$Gg6MSFWG+=Jfz)2)+DqVDz^>~X+&6PeBTub)%*1*^aId}~G?P({=K2Z6Ru z1@8nyBFE?4nPeKbhz&Z@`>@6>=&O6S+nIH&NUN2jxS8AXUh%XR3!C?gHq*l`qis)S z)OMm|GE8uc_pVy8Z93B;oAK?AH@C4Fk9}=;2P34MKffRzt>rt$MR9GcbTYoIo+Di* z=Jz$)khjp+=Z@Wy_H>7%+wu=Z(J~S@=F)gkUA>Ye(0YDy`(}B z6qCxAWF!{tm(FB#EhU|3|8|C7DBkB8wMY;e&BqPUKOy*e zRl~P7fsCsONEq&;(tJh7@Vp8wuR5^iLC6q(g2=!6S!WFYp|wHjHvT*)YR+(o&5~R< z7ePmADR(!}jcndj-qt2pGR?d(owbu@esa1vyQkmy3Tgi@=Wt26f`G6I<`K$&2lG4w zxt0KR3+4UF@{#m`2|u|@n^8^QPAcrZ+e-);b0}EG zB&u~oF@a{T-Vo2GD0AoF1o6hnekVgS)q05w5Z=J`|J}79#1EyL_V)FmQ|Qbz9GN() z@S{d72&kPW$j@vI_syR`?Aj;DzE`59#Q?m|z0KuN%r8e;?WCy!8TMnhDe2Ietn99D z(_2kP2e+b*!F|}_z9Mi9`~^AHAUXtDR=7#)3&hadAMIVYYPycms}mP2;XHS?D_YEG zp$#-pjk_t02bk$ebL%b!y^@uYx(6~a2PmNpw^=8kxnhvc+&RDuSG4%bs4qCo_T?m? z_$nt;Ypsp1z3c|-vR|Q_Z#{?65*B^KA1`5p-yC1xCb+jstc4U^f8uei zt#ahf^EUCW0#{Rvy=I&55#4#XnegjYm%S$MgTxhch7WI30NQfn3Ck&jy-t zOGvkqX~s(fr_2kQnDsC;JX*Am{_)J3MOeLYO-K%7i}Z4ATZA84z0?{Ryo&4%snyRj zm*J*gsT$gQLhCq?8`t9<0%8|fr`H;xUe(VSMbizVn`^N>;g&eh2`pd_K#<%RsxtrYlCr0w9u9aSel zgyBdT^^y3Fb4JNg>+R-}@$xdIU)~{**z&ZhaAKy&c`Lz_wXwqiOz*`)J zJM?JS6aXZoU;IRwhew^P2;`)Q+bFC=0VP2lCX;cjsXSMULhcoa;(U!iPhT5q-;JRc z;?#9FSB~wE4{i(l7IP+?uE$qpq&9{y3WUywvePVV@OCj($wK}7I}lV)LGr+gSi8&X z{{2l>mV$!?$`sit#+F}KK1F<|F^=bJtvtIp3#Zfk2oj|{K(V(%dtkn(UbFhKmc5w8 zjxU9V=g36kwDEo~pLAKyK02?2ugK`xTH8mH6xu9kWw4!F?J%WWhZ$xZ%2j?XnvG1- zl7fCMT5;q+*ReUBRkyK$q{063j)exk>a|5&*C4y};4W~IbYIc~&$K(e(D4_AQ&L=$ z=FXY-Ed#8|<+bAj0&n+vSc68qcgJrY4n^y26N2d|dX43O#nW?sBjIfx&rBriUrp|d z4$Ch=Ll;;s!(HVM+RZ6LE;R_2--tXh1Y1t;>nF8Z#7*u`%toflEt9PB_1v&Rxxo|Q+pfRe4l~l$MEUIjZ zxF)k=pa+C|sHCJ)gt|W86Gdd4N9TC5Z)TSd%V5>bwu{wCziXwc9T#kqInLE8Rs=9m z*Tr*Z`E6>k;-jh`&$dgVr?$Li|IGBNPN_fdQax!>=1@OrqT^ZVH%L`gv?m|0=2Vr2 zW0URV(`F@+>bW>|%lB$xGoLI1hZ;t&XyPg_rJ8d4`OCwpN#&+jIu>r-1aZgj!&Sz#p`Q>jTB7`g3=19(u6;jo3gzwApvmCAV_(u| zR5^elVks5fL|KYg8&R7+n`CtKP7Q8S+vdTL$i{8jE`*zf`^Je;y-l}e2Gu~i{dIQz z-^2}HywMfG_#WD%oIe`**Z4e;N%AL zkGm%a@}a5&?*wIc*W(8VjA^uA?tJ4&g6`S#ItZbc14X%dm95-8`WtpjE zOb*uzWc-_4%edsG!}WtOoM(kbOj$O}4jE^I%w*L1fb8+n`^+Ru3BAF8b)d5vsjV8s zO;U?rZCMTppN1VL!j}`VN^|30I59n%8YO>X=y8Cg9w{KwsI+XS^Ei%UW7m=lu4l*- zMk!RsjnWU?uG2>+;1c&Wzz?ivG4>arA_mX~OoebggeSeqcCm&BHkoap6 ziHN%5_`LB!g%&ogB}j;~l3nf4NKNKU7+iFs7POZRbH5S%)MBEcc`ov!81Ha!taB$=fkvl*haQ+pmQ z;pVIA6|({sepa=A-t^;63~)01+m5~rrBQKXQ2XPGF5 z_8#h}H${_yyLpp4?`+}EkBmMuueZ~IWQ0I*+?7&<@fo!e97F3q{JyFN4MpyXZIY$Y zH-9u5n$ZIol;9*RN{1^c4?NANpS2$Nfm)SPJ7<{OKCo*7!ND~~9w+HZ(39a1G|aW; z(%*mX5UGN6j^;+Yzt0c18EW30PS|5V+OJ4Z1tb?$@L5?@8Sgy)6ot7A) zC!Us8x_|`U6Qg^nEJUc&zrCPn4G9`Gcw<-kR-847A5Nc;A8}+q@i9lYqJOH_DMJ2k-n9($YcNq~RhAY>G zoLBc_|GN5~r@07~2xe;KWsoRF@1potAd}C7#N}|hQaDzotX*&;KWDMPP#1GFEO6TM z>BEH=y^F-Hx)V4Qm8PhpLnx^4rEfQxsM>M}SsWptvZR>^3{~iPaId7hV+-^&R6>Y>afTLsmpaiN zpjoF^vuLv^)X9yrc4*Bo;_}Ut;cjG;UTrc1(5RL2fA!`MdaEf>7oUVwDW;@f+SL6{ zBf>iO1J(AzGua@`YVIfzL(V*q-eIvjam}AxHgNUii}M8q^ebp1STO(f`MP~3-jdrV zDRfhjU#0zFROH4H#Dlfr4+XK|kFw!!8!c+vxPP619d(U$`HNd;B*TGA|0Ky1kPA^U zOX`cT?J9nG+8mScVUC|1^Y0X|((=xqE6j16Z??_B^y*T!;M3R_wn*13;q^C4pDotA z5n-|H_1W0_`@$&;RXOi&gZz4;I_+HgvL0MAGzvxeMn7gW6pU7YJ_%8bgVmUMr8v59= zE~jS?o--29G!4wwth;4)djKlq+J`8h&KZ$2ms!4%fS$76B`y$NkGzB;C$JQBCYiyf z?NoW+YFQ7#S}-%_h4b+zw4TUcfp5pm0%dVYyJqKEG4G0!}6GiA}I>`C~oI^-4RxxN%}$ z-SAWKXxXuYqe?7s5LIy6KBz$_9yLgE&j0qlOj%KCnvj41{L1T&(5aff zLVDvHV{p9~hq;m-64JCAyKBM)TY;^5plZ`^>@@D5RMsGCDe=AGu;$$qEx@ADgOfnL zraXcW6!?-Fe2wJ^x_s4QF*4-%vTLjCt^ck)cY=da*WE$0X|(d11cL)O(5A-Y;QJ+_ zHuCdPG?qCvu{I6gj1a(8by@^dL@O{h&TacEjJcn1zQjNZu+?tglWS4D zC2c5^#q8BaxZ-VRwxq*Sk0=CF?a3;VC$Ae>-M|urXu3{B%uqALOJ(Jh({DdJ@xua; z^dq>&#PEolepz`|8_6=Nt+qTwKcn4k{kHlSqRwPSledJk4J2=SyCfmSW+6}N-p>po zkX`o3GKaCk@^PDJx#{5>+}RlKveejSz?8{Gl-#5j)Rz$n)wbWnBK&X+NrGyf$XO zVha3%CgG;wdWTT$2T^-r+?i5*HuIZ7thk<+PHhbn7P~C$ai~RVU+QM>I}6y5ZH*N!fwd(@_^emoBbV$lkmNF`f8 zc;529QAw3SF{jTI4Jtj{Z%zc4Qx9yeO1P;{U4~MuE}YbHF|5wc!wA2H$dt`6?vQ@I z_SBDHb{1{?s@~t^U-ir!)|0LA zUo)0)3S4Yc%U838o*v#KrYQ1UmweRYI&|yY&JOpbk=qLJcYXG=AJ+}c7X4puZ``g0 z6Gim_$t}a^BkoW8_2z>Q-;E`3c1s`GJTCaFJW0W$5^Kop_l;!ksWmbSE80v)o_{v9 z{(j`c*7=-q;`hi>xRWMYyvtuq_;DeR zaZIAD7MyCGiTN0Vu-X7W>t@(9MUbjv-W~>_&b;J+sOL5(>3FID(+Yu-gKdYc{a0<7 zCAo(?1qpj)F6Ly-D9U5B(Tgvd$dq7Vwdlj|IY`!Vc(1mY{4ZTCM4O-=vjcVAaX{|w zj)>Xk6X0xb_9|ASE1UbHcISsTbFmi&o+n%D%V(1Jnt7c>n#B#XQ;Xz1 z8z-%KcOSs@llwi`7D1umcJWrVtJF3XouH`1lN}!FG?0?-`>6HF+>hB`>Ig>`d$;ew zsV3H5$4UEJ9De=16)C3BeJA}D8m{)(=TQIxe8$^O;BRXwmnO;$i(kFnZQ905lG^fR z_f70P)$dJe%u-V~qa;|S3fW#6%PACx^0z7Un*?MXKjSwTE%nP{{cg$cSF|au^l8aT zR2zp@Ao0SN`2@7Pmw%lw#ku~5tg9u~p)3@k#w}*FOVmWBl9#79JA=~t*Z>mRuL$9nVp^ORY30?46-s=5n4J=uv0yha>0z1|6)p$;3pPu7#dMZ<^%X&%cFojWRvs%ANx(}F?c!vVrp!Ef!;V+eqH`RkX zg>t{UJo+K4QmywG{itZZ;CeR&$@DLgP29yg|Hk6T6uP(;okT$FpbQ~ONk09)(ozMm zL-XkfzMdoa&_0x4!epNdhOYv)PCd@sFqmrX!RO0-@DhhLsLDv{ww98Zt2TV;M?;~r zc>{tvdgXDZ$rlT5qAgaU<`!01+Xe(Q^AZ0Ch6SIFW&!`IU_J8h-@d^Blt8s1%qdByzJIs)=lg0Bv@<&7efiIxD8cO%eE zO9oN4Rv&U|5rJkF_M49k79Zo-7nym#9+4J`C&%%^2~1ZrSQSCRG!ycPs!bhaS`0#s zH2J|GzK?>K(r`+ieOiTqDpdXkGvdh*no36Ve^BNRKC*R`a#LS=ir;uG782nhp2mMF z6N3uK-48fdKQU(w0^i^l2gUdTJ;z)*wkgn1?tjyaV;~V4e5fgXQ9p48u%RXr;7`tD z2r%2xNVH_6R5a?PwBJ=0{Lca?N|{&>&dvHg>TXihQqb0Ac@fDfy;jil-LVfRPyd9s zbNO`c{Jdt2H!e+q0Z>`6(zUDuIeWe`Z7-oMGuF~nfQ<(2)Vb^fQT90pPN2P;Z872M zUmJg;$r)O|C!a`VBuyeMX@j3Tmq3sW>1Cf?4=H?DC>;ZQ@pf9m4dPa{|G40eCf; z#t*h?L}Pr~-_(ivd{}?rGC#=mhlhtF3${qB6|3temQN&HXmGuqK?*2OLNyNEuKpaq zXkn>RRllfJ&WJ6IAGhS;*tlAYYXQ}4XMJsyzjl0qSyTL`)3`e&J5^U*n&4W4sda_J zCLM+DAvr+V8x70;+i{I#u?~K~1w)EDX8<3kh_&E;>h6$saM2>Wm5dNenvsvzX_uhf zKZVpr_EwaqgV5g;)!t*E@yQmpc1KXuoSry-$FZxB|IbfM9Q?giR zy$P4%2Z}FcDSPk|pD91Is1tYp-AJp`Y-x0c5`kIVOg$z$m2g3fygwNUxm-JVF*nm4 zZ9?!+a;0fN=k$OiE7036t;}69=dVBlmcx5Zf)8xG(@a6{(Xma6#tw^hIAfAZGAQ%J zaBCYU0X~KDBL)l|qYs}|XVfd7PG~mylwO5#JdC~Clp}&T^i-ALm-kJQVVUhF$>a}R zBy~oTx`!%P99bJiuYyI3btrLfO$RcGmA*(49El8mXNPV`BOL3y1Y^{shi0tes5bbC zlN~Naxm=D&J8Dg77WG0ON7xMsDkUyvZdt2evvYDts{HZy$Fxh$T)VaXC}yJ0?JPu^8N<@!Zvm1ChJkFBfvEc}?fSBt9o=Js!o+wXkx8NO_2$+V-EzK}#Jkp$hA_}pXyrCP73WS%!~o@&+751=H2Z_bIC+JlntnG)1oRj3>0n1E_+Kq zB9%X@vD-{$O|jzEs|*cZJ+9SlsS-VxDc-v_w}(GHO01KAD1%)#waOl251c{@zcGgi zu)|j1?$p^H-wAx#aETWXK*^eE@)Id^&@;Ka#F407!nAedh&6@%JrDO-#NR!eGa~bH zrnf8cH=@|E26D};?)w!h%m%(NJTmA2mwsgF)gpCH8ksxUJ;Wsj$ zat=>`&FuNcF4KTb7s(a}bc4x3t~dPiLmUKImfz7sss^fAaZ|c4$PebgHMAkAH!Eo6 z#R$p;PW(jz;Se_Zt|#SE=8KZq)v~We&j-M%4{;y(?}@doV{WW!rBvHDLZ?H}39X;2i)C=LrHh7T`5i*rz`}ZF z@@-^2oy$Z7Mtr7?#4S;ML&beKAK=_TUH97mwu-^&F8?o@4G$_)SS~YyL2`j8Exj)A zt~WxjF06=Rd5D)l&EK}{fF4TA*ihp*VaNh=v>Dc@+P10sdv+!Jmr}nf$Vk0PENDC! zHUxl{0t1W9%Be*o1K7UkiO92c3czkzAf9)$#*S#R7QgY1YHNv15__u>4V#2WXIq zzhF`AJ{1?Rex0-$w{J%9LhcrKL9kTu@J7Pnl0xbR{~TE3q?PA!do6U9QnV@Mw{@q)`v^@E*HXcEo|$VSbaqp6pV18%-^N$uCMH zp<)`huM4M6mF(5od2{aHXIg9sYF{YvnI*jch@6y-ysB4iY5eZcavc@8yhNpSJYBZr z#u7{3(1rm-V)>hfWbvNSIqEPE_o^AnidR)y6M;FzFnItD|!*+|S%oI+2BBtI^M>^gM;ce~WI`o^lZil}&E zpqTnq@msJ!w|B*;1pT_>eHO6x{BI<~jiao22$ql}x@{TVpXYI!IKO)!kJB;NNN}a= zZJ1MdbEcH(Z0d`h z1=t&ZIQ(;3?gW-^dwBF>`tt5OSZ_{b$MtN{<9-Zw><+D9lYFc%zhCW3XaaF z9oHIE@t>`6mD&ROKcFj!L?)Ngb8pi9B;W@&gi6LS_b%!GCSR#KJ<%sWneKGi z3X%cFln$+BsQ|*@3c)Re@$o0_TGEYwu?IQrwml4B$9?x|`zQ91YI)SGdzV+sTrC`I4Zi1QX^Z1yQs`wj)FyTrvi^f2pwmd>u*hc1LAd`LZg zzUflppik{8s^)vfb|tFeQ=pap;U)IA%e*Fdct2gc(}#HknB2?0mWO;LJoI zb?V%FEoo}%t~Rr2Cn{1HzTX6_i?b|zf7QKUX7hY({L*twd=v*dTT9v<4c;HE1pG*^ zbc7tC@6Ng7WQRKG z3%Q1#K3va_P2UI^8+Vz=FCEG36tP1NWMk9Ns*CyDv1kNhJl6kii|Ledg%1@6@ zu*aug+uoyD$vC#c#>2@MJf(FV{!=S(8J$+G{=G=~Z<~Z_iLH{JdT2dF3CY$OW~&58 z6$8};>$%*u5Bm!o@TiZmn0TG50!#DF?kw{A3UlYW5vq^nUY7JW-6#RnBpwnT?|{+6 zR&BIll~kT;*0zajO8=b8MxzHjJ6@=JLfn~O6d8-s?t=EI(c>w1KH$c(*uhA1fMjtZ zbq!}CX*j|e3kzBh5JKXfqTFM?OCF3aMh0@KKrWSzUq+eigJ_X1+||UDkIBPWVNrl< zB)OGTP{*%V^0x(3NS&orkt+U0&crp!Se=q`K-OYp@Kjx+c?rFmqf1QvyW0yaK!P7h zjljJNEh!?oa!!zW>=RZ}ruc_Dd=tVr)GE#WksA$$*$m{Qr|`Nii?M+&qm-q8vRP&s zv6sJ~SKZJ#`!1y2z1Nv=+)a#(0Rt!?iE^4%8=@FI*D^D3mp_#!!1818WE0=Pys=m96md?PrtG%n>~<9}W5H-{)Y0 zyIFz?J+@qpPnw!X*89MI%$P+VfwLHI7_X^vq)BSVd!e7d0+73L=!`cgw2LCl5Q-nN zbw2`}i{m!RliG(=YS1gs8J`Hu{Q|pO&MrkOh6gH?pJ!?~k{MqwhB>mV`@q_5Z4NYY z`{4wB)FMY-;1H=7chzn9U8dx$6%Ct)p<|*TN4fNeCc3(8J@kNRhjlc^nx&M8$Gfr^ zMX_GH{x!qj15~GN>8fJ#zgEh3kvUDqIh*sf*bieOC6=Iha~o$pR1P*j;d(?$etT_J zk4t(y;>SV5v3$~q$zd>TrlK>2WnSe)P7>^~wCXR%J<}|!BRgK;Bjx?@pvdOqO3JY} z%uc2^aWB}aj%6~}PCU-N<+3F3Eh(r zWb1{MWY&$>0d>>GK=LoIzmOcMl%9&E%yzTx^a|gq#T+?-4_{;+H(>h)Hf^J;_lM5{ zn82Q~G^5YAttw^Qn$A-dYeREZ33fF0P#QB7*n85TQ zD&ERJ{Dod>N9<&lC8EJ+qkkSqf#=Mju9NuNHk%Z3K9Q)!EnGL|6?mh>H+PCq0&QS9 zb9+R}%MM4)y45=BYz+Eco~B-udM;r$rLJJpXOIzUy~KR>_lc^)zaynjr$xjk=dF+Z zqk^)X>iPE3UGY9|I;Ymbxz}Lgmg^1mz4Tz=>P|fx)e5dAB`XVqQ*z@{am4o}iL8c# z(+nDAl6i(82SSzz0>Guq7O6b>BFq(Yn$uR*!;Fmc-B%2nkwLB8<&ki6-TKT0)se0r zIPczIT=V)uoGCqRTTE}*ten#RotcEdbDMDG$MfIkEbrDRF!beUI`kEyQIz>Fi0^={ zpDr5NteE4sFQ{V{Nx-Bk!C+#3y%52|V9mzgnd<7~EIQ_HX7;>PI&}eDno<)TWb(1w z=hp3S>~e<`=vgY;_E{`FbK8TM>vb~jO9KX6z3AH`l`4=3|2^)kPP?6`?14VNZu1+! zS#&M>c>*3Go7kJ)VEerwt+XO+akis3+m`ukLwCtI=_E_N>@#AV)*b+L2zNsm%s5> z%8iS>Pw_75H0?bd5X;AV|9LYQ@Av>jj(*|cEs@Z54oFp69_5qHyD^S>vjAQ>$frVX ztdp8u{afK3{#fmx2=n+2RQD)8GJC$h==LxF9(fy>TusfwmHky!R)tc7Ra`VOb@$UMi9IQnqjl15Z!Ke*7@0+MIs zkN!$gW$zW!Yv<$fb}){XD`ZtI<)#9m18p*+XhT8bb&76Lbu%T{88nxe#Xo5EV@n!f zwEX%Hg2VC9gKO88w2rA6N9spFQL@>CxIq1uY?lt*z#nNX#fO57S7+|m!A!X6)a4_k zj-l!EBebp4rDq#UOT)GL{TjTdG&2-gk~(u z1j(4QM1CPXi=t1uT$hY;iNqL~!m?IK-;1GtuKhz}K**@LaSVrzq%Tfxg1;Y?UlUF2 z9T6W9pDIN#U0GtMH`926kc36TGkP6cOwDv&EoO#-30Mu$@I&B2hp^K1j4l}f6bXkuxdWxicJtIq*j5mW&LDW4~I$jVq<2oM1_ z$1EK*=_nWDiDkDb?VKcACTNb@}Nus>~jb9ePA~?`iq)Y_j zJvjDQ&qD3^ZxZwwfVVtz={~Yc%;KHKrHGWvvRgE9gMpT4iM(=muW1~o^mN-1NZN)-eE2-&}k zb0vk|-Id4ZXS$DUkhVoGnOBU0cSz70hM|MfZGFp$X35}KRK#?Qg_5nBR2Fz=8^g7R z@=y?pSxt&2Zd`W|XZwb3vn>yJNmfZmKp+svo0INBB_JRm4a+BDcrP^>q!^`F!o#8 z*nc>O`w=czG!ujgH8l|;2;NZ0yOZ`ABn@bB{Ex0eQpg_6C1Y zDgJ#rBHM{rkq_ef+oItmNwV<+C3y$z#V%zx*&6)0I08V!`xeDFL!Fq7AVz|fuJ|Dov{qvL9z zwHv2#n#OEw+i2XNv2ELS-ei)-w#}K?jn!yk+qS;B_gi<(@64>6ANxG}(avSb$Qwho z(R1&-qaM6q_h924fBvu<^t2@+ zQpS95<{^=Iw=5Jtj`vG)+pe1xv0Wm#PpQi4f$f6YMz~3IK zXg!M`X*$1!&%KG8N^sgfQ^lB@FjjNescJnv-^jnZm&3 zDvf%ir;3+ScjAO&f3iAI|8-_ zQNn4Og7B5Sa{BB}U`VFWf}8Yzf(J81rYf?B0Q}4P+qOM<1K9+BKF}$k8!J|YbT%&% z0@iw$X+|!v(gq#D%RvK!@W2v!$PawZ2aPEJ<_mu$yGsa+sRY@e%Cf`o&8kNrtj@|9i{)HI(GGU+~Op0QT@^gdxp(k3$!ishQ zqjIT(dn9MIjkd)#A#tRQ_t4pr35lJYmsSC`^KX0GAsGHr&x8vuwbZIy3MSNVSZ|1D zIM^L*-%;YSke7t|_GaumQc7HS^_}(Q)!U|epZm6FR{37IIE0}Wt7iYt3qVikS@<^= zp%|UuFX#OA>Ef76#IU}i!KCZEv`h7=)!%HQEs}-$mLsiOswqfI#<@ZA>IunAvi%iC zF)3HFxO;r>Jy&+Na=n{Q`fX)ZwU%q;i->oQ$_}VoS6`Ys3%lOIzl`U`lh@B5&s;1b!{Y*!}6n=xJi+Q>fw9NJf`E{_NB+~OF~q` zaG)7Jtwau8wQ(F{d(O`d?RL@L=lf9<{qQ+}HM%`NTCM-0+LJ#*QI^-{ag zw0&p-kwcDGp8DH*GRsr1xcm(iFHh=7V_6#!%8C~OIOA}9rzK2S5zN*Fg1NwacFUOa z9b?VizX()Z?|me5Y-Rnkft_4A2DZX2CFbAwrR*n`Vdvpqe`T;EJpB10S{&COmc zjTcg3d07mYMJVMR+@|ggGb#9y?>jHfmbf`;$)k+atoQbP-sVLYR8RR1^t5~)Ue>=q zWG(sZA6lpP1YcyvJI~$Y3+F!ZB6Pp8>rfBZQz^5XF(qNE$!6S;w zm0;z-)82L12u~1q%wpO6p>?X24X5^#Q;xdQ&l9Q9gIxE2JWmep55eL2LU4^Wj;Z)8Bg^8B&~_gf<>XSJ&-xUdb(O?}l|BbC$<$zse3Y7Hq34-u zk6&T6{HRHR;BMvje0b(p$E?AIJRx0p!jn`+SQEyLR{ZsVuoqGxUW))pUfu3k2wx*m zn7uMPX8!TD4oH<<3uQe?limd_lJL`Y9q|MQs^$Z^;}=^MWUznArip1I+Q+rTZdN=B zravql-|a>F)LXi~EeD9D<>6;z_sO@mCApDh1*EObfkE zLMB|$534cpGFy`AD*pP?TmMNiiouG#Fsy=VtxdS-TzLZ^hCeYLY3x-bdv{Gbh zVN$HVc7BND>3ZzpOKCjREy)MD6+2X5_1Qw%#N>?B*5VpCAF{z?mcu%kK)cdLeRl%? zDP|ghL_=EH0B#E-3gSGa349p?wZFZiBnf}<)B=7_0DKk0{{xc?GBJ57Q~cg#@ZAqc z@y?0@>`NXLQFrePk5xO)C23aY69+rxUd?^y8pVM56zM6&8)m7SGUHj$7wR1tRx!?XA)+qw1@Z{$BvkQOw5xY zrpdsZ|8EM!UrPZPu#C6n9MQSk=imk}%){PysyX|D=$p85%Nb(@2*z4g&(VXOd!$xl z1vPU13bUC6`Z433byALyU{Go#FX3%w3~v-NAijnLyNCZ>W|66V7`?#yYk~xp+Hwc9 zgXuq}>q9`J3rMBxc>Qa?18bfW-9_xw#-CHfw#%iqqj2bqk%u`;&d%qH1oa@U!!GTb ztaraB&zLwa>Bb9Oz?jQ3T+aO{(SrxEZR+3eV#Uc!mBV6m8E9O1W z9m|F69(VaDmf2!>anxh^cGo~WW2sx&ymgLW4sAO~8*R_BB+-l43td@D%Mc1iI^J~= zdHUL|Is$^=RiuR!xi)*Z(BD_O)2l5jVz`}M_GgsCtEa<2IRHF1 z>Ooowg+PO=Mv8P3`1GEL6?8gLLWCW*lEQ__ptE;)h19>3NR>}zjy!Zd1&3f4zd>cw*(Y54Vbm;MM3Nb z3G8WQk0IG8gd3r9Y|;Mbcn2l1%?Y#+&7rau)h4-QgK2kwzOdc9?GOx5u2N0Ho-al{ z`0^gNRr=ru8&mRn@H%M#*-{`_uD0BqCHSUR{>Pyfy)FnoJu1Y3E0)%L!0z{Xt32!6 zPv$1(R>%7ngF{0-hJRZ`q2!Px0|4LY==z64m%T{Ys~~sh+IT^;SXXwR;rq1zyi#YT ze(IiO6MAF*EdiQ0{JNpO5|O#)T2r8~`yk;lEv+w#mdm2%GTR}wLFz4^5GU!*zuR$= zk1ZkMdELYv<;Wk>7)t9?aald$>L@39Ye>Bn^<7tr(`D0dth#eeK6kxvL%RR;f8b=h(muungvFDQ7_<68#jc2u&hTzSNh=@^4wMw-TgHxZXpk>$l z1$krp3TziiZC$<|`umegXbTAI!sBf1KpI1GbZ{WO`-`7_B3FnHjfmH2BQFii3GGUr z>5Iey%=UY|4^ml7WjXx$q`AJuHJgRGjI25#H{MyUG4c!&fMjGarsSbc-$yK)!L31Q1WAX6@u-frZB(o?bo8$pFeiX zJpT28|J>KDgb^J78<<7_vE{I@#TUqdy~y-S(-+V>@I+*aL`W1hp_TSss_a&pGz2}Q zQtUCO#?0w=L3RQXuX{6jlke6MZ-Lg*XHHj+zy5r>AsTw}jr>o1288uL@tLL(I2;qD zhiW4Y=K3#q0o#b}rbWcAGd#<`SYdFQeeOQJXcm+lB{u~dN&IW27~x%UFD$etVTeA4 zyR3%wH6Hy_lmb33p=iT+2=}mYhE%O%%jT?vm{-2yZu48wAXy3h2-~!lR@RtmLZr@` z@ja}J59bkJ0RgU&&!J#g8c=0IIP$f>JxhA-?@7_I@$My*@9CI*%Pn#M&=sS{i&RxV^Y?jXT@QCNz`M;Dk#c^;_d-z4lqnj*SR8Mu zv1Xd3hJ}yoQl?MM_o2+tVCX`10(F?e41KzW2p>B3R0jo1*XUQ?5AjE`fv1mRbBQyj`gkgln)1MTIfFLm$;@f)3XAeC) zGF?W?{Iw}wzN1|kF`s|5stX;cmgf5dSxrJrWu|_;|9PPtLQc%eC#9=H zMe~!&ClO@>lY2Oot|pKLtZLC*?Ga$@lWx-0gP~X4g&(YiG7&Je@uiKPh>W=5%_Jb| zarLoq5emq{VjtrFxd@8z7cX;?iz#JU7qO&oksipTuWk{Tnm_PD$+l4QE{Q z{LNKP)WyBLwrdjN?|6*V7-bMou}>#nec?u@VX^Arh)=@Ra-|C2%~V+;QGRZIP|SHa z5IjCaUE9D&Mxz_wDco6?q!9WJT6NY=rSPwnLyg4gvpNyL#-)V!pZKvLtOY~CJyelI zq6p|cN&78e1h)^v`QLPoPG1O|!kN&{twcqTNr4=Nu0Wz?m!ng106!B;xJQw&I)IVv;W6Y+gy;G;aEk5y(r>B!w`UPQLTM&ce66inSxwVAxPj)> zrc2JnQDki@uGrIyb0Iv`ExOpOSk;_*|95#ZEJe$EW2W!Pi@ zd)=hI$j4$1+AX}p-}l0DM6p}bd=b+tI&c_GBK?D+mH5>0eeSG3HAEtGi|Cd?!Nz(Xj4F1Q; z_r@m3TKXdmtj5{mxHc_sOVBo<@HFa;cdU#>D^*1A%aeid$%h-N>e!wXPLQ+4Xt{oIyH3=V> z?Ojmo0gQUxKU+L08pGLc*W4XL>GE5^Le}@9_LL=SuXBNqBB#g+)|p3kakm&0zxZSw-sYacOYcyA^FS zWQ=^n@9m(G{J1@zIh@kikXGFj!Bu?i$5-njl}-2zb;_(wJX-^Eo4X2*LGz_Mkf&)` ztuvcMO0Z7;4Ah~s=Gp`#17A3}hbWGl#I?T&RjF0qmf9IjlG+y^l0N*%VvGQ}Lr8WA zg$dgp?MQ{;OT4k!mT{bFX1S7Y$g|vZ<~px0l*2V1IO?Elsk*Yo!$8_=nDf^#_iqOf zJHhi`T;zWnS*m-NcA7{l_WS>qJJ=*Yy3S!y<@9}p?-_Ih^&8DMGp@9aWdqDl&B2Yk z?j9OCi9O?cUK^Niv*6+IM#Jg7LdNCE?UyVIQTAigReo0sxb!9%J*9zcVm(e)2;`@9 zxNd-WY)(yV6DXaF;@@?NEz@Y5n36QyNR?q4_qtxZX&zEIf5 z|9Np*5w}*FE+|{34Ofwq)ur8v{`QS*PmXLk+AoFJ(tmU%mw5C+E43R`oY4I8ew{;n zJ~jr>JEMH{CJ`#i$$)&`FV+k;A725`Nz_oIHt}y^5kdu6477u`F8u@ICc|!LT8J9* z^IeMWe1G8J%z46%z_kl0TrNPVo7hM$`UURzzH{lu=1JSWnwgQv=Z3?=QhKpTRj6os z5$Ju%rA)g!a^B2rOdY&T;pmE`Y4{K^aZHnIe7WZG_pa# z59if{5m0M+6j1tZWNL|IW_o2xW$@fpY`Nkx$HrK%`mI&Uf>&*C3VETwNbc*4ABXC? z80ukpFY$a-%S$>3Of}Uvq(34h+b{HWDQxwg5kU`7C0@W5y3^e^IzSwuODhf6w^Q+` z7aa7%KaIrPmT>6`#?lCebjJFI!D>jfDd#`nyywsfZ1e@hf#(thV-LnKwhezbYE7q5 zoLrz)VOh}}dLowbjPMiRf~1DCT#7qTvxWOgu~aJjXrS9GePopI+%(Kbi!g_W#dpY( z)%m7Bv$fs;P{p?D2aW1~ewP8B%HvfzzN(gyAgsK)rtd<5%VSH^gq^q_E+J2_KEgbM z$?KZu5c~@o?6}C&;AxfKB{A?F?fkG|!$6p=nqN9DbJEZM;nxE`HLjXEW>!(&J?pA9 zhGpN1RY#tfkgZPQvqkTv#~$7nX4$87iy#a5yKek|&S9fys^<^>9MXWQaQROvY2x~` zCW6;ATfszbtrXNLoq%iLAtH)=4N3Ed*4Fz6_}&)rgD`J|r7%J{V$KeRHzX`GT3 z@s6TKEI-KU#jvR-Ykyo*>hUXt;Fs6OW_|6ySS{=DjFi>VrC0NA+les%Og}I{PPA_R z|FEdK*S`Q}NDA@e4&4%gbl@!F1()CkzXaWcyB-BO4%QH1)G3 z&u>|+Dbu&|7u{>8LqO8yPaOtwD~1~NJ$_+=VC@8N_BCk{DYFNuODshtSgR6Xl-{dv zkmS*Wsb!6X4sO!v6Gc9O|0zrPyL#!FNy(D$S^tR+^NTx=t7oOVB9Whu4&m3pG;}~Nc)L$$#m!j~QjJTlMgSIG#NOh5?05b+%SPPR5R~)PR zO>F7f7L3)g;1W;OL`c1`XuH0`_=h{qjS6xbm_E3P?alUElzzq`Y|~6<2gfv`#SbY~ zL!oq9^+}uIn_-WnHcrPibP6d^$C}0w z|7LwU>qmv>wM)gsR~ZCU3(@gv1YWP>!=;wzx`hD50*4Ej^Cu1HhE3zELzrwQSVybr z2G5<)vz#XkgLid1-g|%y)v2QlS(^6I`WSS__lf@o&|IR!d9%fcm^X2pi_KONG=*JH z24v&W%LD@)@=&uq_(O(CwT5o?8OX6skJ;>UsM@$MnkdwU9Xw$LN|zWM>nU5B56Q=O zE}UNMbF^_XpgdRjJz6gwM5e`1vK@lwm<+gq)qE^um?7GaUQhXNVU4UF4`1&CXWF&U z>q#|N(>kSs$q)0%HtV`d?PClp3A=Z$T~7c8*VJ`hSnDf3qcKwq%r%Ajm-BMD4~4NZ zEjkRL^d+odB+8t3?QEUk_53_@!x!;!@zmvN(Bi?!FT|VOF>#>3`2O$;8!-(|fBWy0 zB-_O!B!V<84%~Ci8fRJdE2}EU-%c$$MgFYP-8vNUFQ@!#130E|)?I&V+YZ)R^yQQO zp87*}4KxniWgJJOnh;el-d`4f4~8Wqk6R;zYSSd<>2QW5y-r}EX)rh=l|hJ{|6O_V zBb!!f*r##OQ!~X9cFO3l3VE)&9!%+QB|hNu-M|496R3pjj22{eGUGX@>p4eDGiBxX z3MK2b5oN&MOGW&nKJjW@k;F%C)4xw+Z38kAaldCPINW{z;=k6*PI)|xvV;4Ip=z`F zS0@iLaZf5`ft5ft`jnHolk`I(mA3i^5JoPEO6vIow|?+^=@%0tAZ>4^)~V^`e2V)u z9h_ZGcCXD>4wJ=~y;rVpX-|7f*7Ttux?Z7@1XAU?oFZeKbK`>2MY<(h(tplMw!BzL z^xBr#xWA@!J}n9QmVLDqm+Hw|3Ohmk{YH#EjLlITqnw(!D^USxSckM3 z(1lw`soFr?Lp(6jSa`3G_0~Uk=D+UD4iltmQJhSB$DJLJFLgRL_ihvzyT1wgq_>qJ zJU8`W3I6Mh-Q>WX=`{Nqs=iR|U}aR_?z7?>V;RyI!xWuzr)4CYyHeRCyze};@HCZ* z?YCXZcb9^R8BWYSv2h;n<4SMTOS~_|-^FVY(3`)+9>^n6+pO@E27lv&6na zs+dT4E9?NCrKrrmp7b(rS~+3s!S!ZFblDzUI8;IwT9xauF!vU{GE(&r@s<R`TC=|6wjL9a4Cq&(t!KKVJ44~qQk+O>Tv z{m>~7=AmjIL35BInoxek!j@J|!n9+Dp;jUJbOe7z%P3-;wtzf2a5|L8T4Tr@NO3n% zIGT5h%!71)q9Y(LVcQ&O3|bA_$Ze(=;LgN~1!o3y%I1!keaQX!V{cBBbf^YR>SfFJ zrDbldvp6wczap)M-soX)vm(hrRY^kW3pquX}hhvPuQ=|Cu zCa7~>;2J9prU>!S$jY-bzBgM`$93jBSB6g4W7keUjI@VfTTs?$>aV;%p0zzn@cA`e z-aFoGJFNfdH0!KqHV}0XIYo8Vlim5s`sC!KC$Gf`=b5|e^;mErGxvma4+pBkzc+o>C9N5{8LicR zZ*=LBycj1QK}DLd$<+m6eh7SvI?q6yI1y<{>3`Uy!3OE%#VqaTZ$7RGbplP93oT!~ zV?0J6{+jn-7ur*QvS<&%_@j)l#*Npcy^ngBncd{ctgaHQ%ZTqTCE=YT;)2K7DH4Pe zT-UYe>Vxr$>#2AjDPJS>0ox+JVcUMh!48EY!e70BN#4y#%>lkP_F36Fi;3@>GY05&g}$?m4MV`<@-; z2gsz)i8Csr(6WM`qj$>6N~`yK9%)!4dNkAz*!OQdQ!9n?2@m8P7av)wh{>L>IrF9mFXZWf_^n7e(=}>6dV^vCYjJc)WPZ5WH)V!HJdaD(em7x z*j8_rEm!rqL0t+K(5~b-P=T{2f0kMXz5K9EWbs37r0{#AegJx`#A-Fp{fi9x!!Kgp zqv=cm?^^n?IAZlHP7Zpj%kdeFRcO)vNA&|sAkH$jM0q~(4SBgiSd~SJj=^tZ!WcTE z*XbH8!QU-mJVNitj0$~uQ_I@CwRSO+FF|TOk=nRM@u%ji*xGo*QH;?!Y`~gn4F|CS zw7Zf1R^Hn3e@yxaqIyqz!<^h)aw$TBr3Xy9hv`v_iDjutxW93#%;ktQonC#LAhNHF z!9~JHN?)l(NpZ=SjO_gLTAZ6Q$e+n)4}>VlFE~$SWB-((7H8P`D$_MX@%~5bgkGt_ zadWF;cPEA9f{v>>wOmh&x;GoM((aXui&>8cj%$*SeyLemsxBkwP7&tzR}dGYGg8Qu zR(V{`728)QlLCJ3((2yx^thOZY-JoWgDZ-AdzZC=T5xpyv(|3nQdlFq(jp;cec$uEJ^w=?Z|evlh^ePic~4xksdGzP`Y{L6ybn1P&Y(Yal&brfN)BGb59GlZ(01 z4kSQ8#`23Nh$9vlis)Kh=C36|(dT6UIdBrwW_&@EnVE@5U}=OZi-tp8I+>+!C%dtl zLDivtD64CkRnxSR2x&zjoRYcWIeqhr?|VreE@~k_lxH76DTh`xgMECPC&M*hC_coW z_^h7p5J@q82&84$eejFxCxlLYPl2n_i*wrBGXif7&FE$Cy(7^RT?~3hZsqwawH(3i*+pPE=``vs%6o9M4 z+w`)FvD@oU|C-pFzAHYVt%cpQ3(3(to=ISYY%dpw(pDvY$qR|SFm2K1@wqW0qeYNT=Mf-ZQ@U**Pji01WzS~om@|6}U$QuuWE zK2cHi1t8aD2l4o@*ef8|$_wc6aBB zfYw7hPGCJrwb&ikYbVP4u@{E-6m1?g!4~F{e zLrQkyya@l+0yrOG15B{L1bd5>=lWNk`L{hN?aLfBjm3k^ zgV#KxdE=61)W1N2&bdrf*SkUT!j<^RQGv`uNnC5$MpC=EBz1V@x>IFMxDk7o#`$OoBtA_{304!|Vlogj(b%evABjzzLYe6$t*SC(g@ z^;<`anSVvF9r1H^vJb!jv`Zbh;6bQJ`@m&DXRkPs3pqyCyA{pGfm3c7vCCo$g)ZZs z3bOwpgRS+$cJVMNB=MJ~(Q8Bx(G%YxZ~UW+fE|36>N>zHBPUD%H(=%A)6K$Lv;T0_ zI<#Zp81kYpm$lQSxwP5SH`mVgYKiyPM3h^UT{B=(`NOwrNDwZ6(?xPjioX|c+d9mZ zxag}@Mfp&~e=M*NAk#fSagV07jAJR8OttFniXI!RP5RHGMNQF-MGO@M<=;GKOhN)C ziT7T?Q99oO_wiskcQ(IRcRNvODui6K{WLg=Xl0&S%;Kes zVg8?X(CTPoi4R_0$TH}(Z`m7Bh0QBaK-o!O*#esWi)k6~omfVDDy((y8c zx%My+*CtbG=`V(Ee)87_ezSh1QBprst^O@p{|knKf=aztEj_9 z8pu?>z-Xa<^Hr`8jd>ViwGI_@*U}j@m$IM4rsVN5bAk5FQ#2`2;y3-%zDD6nsrLYj zRLBjdHL22Nz}VnY$E{m3Yw{OI+F@ULk)x(kd-J&&8n?efbT8^v}Z)`56k} z*VCxQ9j>yhqP%L(4bSTx%tz51AUB*z<183lL8oha*xE~g_QOI-WzQ#;P@TNe)*A`yutEFYd}Staxtb6jcgPmG=#2@nh)2*V+zr(3UE#& zP(;!ZtxOkCr>OdFueEVjccr)N3Kuigc2eiLoBpK->>a6G7S*qUtEMir#0_ zh!ccV3WmvoHm9BLpy>ub^G$a$Zaj;YHz&8Rkxr0 z(n?R9nNX(oOpJ0*W2IVLbfOiOH2t5*wDU7ovS{`TeA(Rfm)6nAjkCXTM!8apg<*kp zIN0{Kr&I+#C55R%i@@{v_5~41cRPyxlac=^SD4TUUP=->bshC@fcf z4TKmOZE>#C_-?k}Wt*rn?BVC%e_DRPF6r}6rWQ9)3^#7B;}fUdl1tcI8T+07jQzCv zL}E*(<^nwjaO+>2TR@{fXC;g?f$P?WXN>S)&Pasa-${)EZL=#q_q;E)I2QF)2OG|* zs}%iWOkG`20zKJGy#c9?7YEH%4YP?8MA}2!+vc3L-a)Em5Va3?&z!Xr4d)&8I}SVB z&B5q{GA;5R9;VhB8zTC8W6H1q;$mRA=%2;{4pFK zTQQkBlgI2*tI#z3U#E~ei6-5M7u`8t8Kilida;{dZG|3aUu#NC?plZf>8r($bwls> z{#Z>s_Y(*(;cNFdS~-?;Z~q!qu=;8+<6ph6RJf}2Mg7k0T{2zvm9>36G_4&?TG$P*H6EGoBLx=F__=N>}jy4n++=j>k3@ME8Bsa=PO%v&Y17 zGLrY)rt{fe-|JFl8=Zw>$vu0)m1OHZNBbdnEq2uj`>&`cb=q$v3!tiZ$TIbd2Vu>o z)rZP74 z#nl0$!Yt|XN@mma&m-4b(n(!;vO5~mLAWV12N_s`;N zDYFDsI0RMP#|+wBEx0pz462gz^c94PBT-ifT@xBXR>MRvkO$HLsc5A1u1HwfYS^b? zXcfw(dQTS%5FNOfVIzc@jmL*@{AWV#jT{#lL^_k-4x@T)(3t+yO<`&TYMJ+Ea$wVP zNd^J6Or}s|^uAZx@pwaW0Wyr5bv5BXU=8wSamZ(7?j|(Jg@PJiIxs@!Sb4zF z(T$q`!Z{gD!fC>>RE+Z=X9n@ zVo!BH`MQ{;XFn6;sX_PUwn-Kcw@fu^qA$M=V!v-BMO;4rHU%!i+G;JoRKS%I4(q1? zsp-+jy zI<$NSMYbjb!V>y;SpDvhlM+9#pOuB6cI9b)`2QBu=Ri~cX5K7FlGMFd#`4r}EWfOCB-CfPH#P+)E@E;e>{mC+1;VhxD?T&Z$+EcX1oH`1Mq zoqq3CVGe5{)LzqDm=I8@$MlM_Pqp}`>zxVlkT=uUBGVihS~Y)PNh!;;s_onM9^0%^ z=gzB+>+9DEJ~M$NQLaqiZ`-uG7EFO5si4bLvE|Xn9A4Y(JT3eH9CYiN{&+*U2Ajs5 z7L0UP%nTvCV^YB?8?ek~u*0TiW3EB5`_}>ArWv^C4jVe9^&5N>+-9d|I_;`4| z@*81k?O&~HBw8*dU4@E)KbpBWG#b|gt9;|HA;;+rEdWeJhm8ODpM?V38Oy+{iIj^t z7Nf#!e8P{1=VLpqt9;!QmiUv`;7GQn}Z znJy}DTzKDxr+?h!Vgtn~qLiQ2>{kbnOf@^6A!WDi8CZzvmWZ!${fl`QsVy-yz0m&m z2SV2>b-Ha~j@$J{s@nL|Z(UfMu1Q(Q*S>JSW)t^-A)@ff#LeXoMtl3NbjbT|dbw@y zG)Eg8ZsakXjF8dNT=lEG!(Ir|L(T{&)4|1cHLGz?d=ME;_^1_oF@)Gm{>|RgtU7so zUF+UN< zJ2ZxCX2*ihmM9@e-u(uPz#}IPTZTJalr~=KCM9Qkhj~UlKyFaWocS=2<>HX1<1x|hZUmQe;v~qd2zP&$T8Y63Cr0em2(3k~ zkG~~9A(u6|k$WPMsnRO1P6urB$Bo-^dA6l+qJIfZe2bU5(D{o-4s_Es{tv|3->VHJ zfs$sCME1k2QK`o`oDczEB7JO#i9SNVV%y8c>T)jHa4Tt)!RQpN-1*#b+IUJ0r=Kl< zw}!8zx~qR68~@MB)^=-1T+80~UtDGxTn)Z*syKh)M&wanWplK|{5_|Bmw?^l5ZQBk ztI=f~A*21e0sW|0!^i9<w83t2o=)EiyfGUT-uN zV+#Z`!d4RV9J!H9OZ|6M=zgsob;kMiTZCyn^Y&aC=9;s9 z)e93pv}MQC?y7sLRw6QE2?@z3aHzk|+U=ap${SCvTbW3}N8uhC=1(H$Vxu^JF^U8f)ePO)=2KgsVW8Fi4js>+l zt;q0JOBDdbpW5lOHF7W~emy~qKz+%P-Nr(|IHUdrysve>)Heix9BmsWS!`AhlKy2^ z)CqcZm(N!EI8LU8BLZdaL1YEE4T6m38m5RJkxtxNc9p)#^sL>U9~I`)k#8o8bLmeu zal4=?bLSLC1r*^IXY@@l-(A>?{nUm(Mfj>i^oA!=Ir2hdQIM|{ekj#&*uG)BD>a4J zY({jTHna(3W|uvcQP`glIa4dDkL@z0?#Xd%5oXlg$UAI@)ePXqyBrSq*1y*KFMpQHmzDsaa?#_&tw%L!3iTo8Ff zRmLj)mQz8Som)$lnz~#(EZa*B-AEJV^Wz%WtiAyYZW<$yDL$*XH29b^%@z0oO{Q^d zcEex&zkJSA5kIadNK5k6l*0cAu18bnHUaDh-2}fb>;iV%zAIcsC=G8+I!&8n^u%m? z;8Cg)_m_2y+9gZ?tHkOCMkIV_k8&%ZmvrrQB!K0LsmO3*K>96t|ACsyPV4@FA^I%^ zeFt|_WGd(mVw<_o&>cUxPVAAc-M!roP(xRSKb+b*j_=6}4pz;6E_0N|C4|T;M#AoY z+S`5HUP-9Y4*JjAJ5a`OR+lHRgjWv{ne%S67TN;@UO(GHvH>=$!h6-pE}3Q69; z2E32^uVG1aFikqb@d0UoBWBI@|IX1~gdUOwbXPa*1EI@KXGw*20i(6vIjoR?`4_&N+L1*}xB(Xp%7ylJ!+=j)1 z{RdFfV%Lzkzy*EPE)8*PjrE=3DlGB@;u*BrXDinE&)k%z3&^>X4`~S2QCjBrmj3s- zFH#h6?)TEulSZ@gNc=XAh4+{&Vm10Gx=+Z zC)dv6vlb!cu_Jz~LAePB^p|X6=+keqZv>>4nuzQdujlL*HC%}k2EmY-{x#U{RoeA; zYPGL;Om)oag;igGpqiLI*>QUt0z}dE&kJ7u{_nYf(O#bkLhpae=Fx><`M%n3gIVnr zJZ`FD=g4gdzT8_nl}5gN^n54A*p!Ou=}FqE(4^AewHQMR-@?Y??MX+B;}G^{>Mf5b zm3-1oq3n?jv%o73zz9B;W-2tw^IMnJA_8#l-hHGsy?~L?Y=5i9tWY2^WNmq~cr;)y zg7*CxpKk$cF0E!!u3uKVU&VPwpVL`du{LY{n|>%gSnjb_s9s zO{U^BmUe`IL6jOpj*Guo`nfG%4S3OtgDP*I8Y6Lt-{@EqKF02)il~`mV9uadYzd9;Z~o?4DapyWf>(AbzTjTtqiYsZpgPeW` zyqvF~R!%MheB9RPDvfu`Qu?{!-H6YB2(9uWgHxHBG=kUfh=5&e$z$M}g(!4-F8dp^ zr)68NkDYO$RxW}_V)H;huS-_-9o}cv$kwBmVZPgW6CIJ$+wtABMz1~_?!aRdSdLb| zQ^vSY3p`gw+R(0c{C_60-M;z^Qy#=+zt6`fMaFOT*u>@nt@Hv6druyp?pk_Zk|E)( z3y3|2!y8Z~;IejKgOe>4Y%SYd_nPg(H6(6+mR`j+m-svG40fxfcLs#h%{SlQn*s&c zzT+3oce9inw8MzYL;Nhp--5ZF3?eXEOH@nw$ub{Sxpp0!Ka?123A>OgSeM*%2*X;X z<`w8J`R$V3U0+Ek!6cQRn&T$~(R12@2sHe>k=sO$MQfW_yL|&fmR;@HR?TFk^Z*H+ zFIndB*_<%BOVmp<)~rf8*)w`z;itMU*%zWPX&Mv5qC0Oo<#TMe7;PfATlO{OE4*VqDYmpAdPg>Y|}d*=9~`BLg)ly)Ng zmXR*9X25Qa->Q9)$8ye-E2*)JK{Ss=U-{Scc~1Wr@p|pxXY%|yvHfuk)Ntua%eL5Z`stSw*L!zKmmAz3zzj4f4LTzr@jx0KO;)-4LWN`-AS|IVdT&KsIMSKQ@o zA^q*>lR|N6oe6rwq!E{!64$a>d9CmX%hX*B+E-h|kJX%MdO6Ufzfh%!(jwu!P(>5#- z(Vj_Tx=aVFI0aQp8PW6qC)-+5cqla3b#F@bY-)H6`x5O9riN4%Fg5n@#XWwgWuUq| zq$+kkmSFhiAWlJh@lcNXH^P{ZJ@9)i(p=ZcZ5gJBu07amQ2E`&89@TF_o?!ucsxy> zMjTR_1fMSE)}_zS?1T3CRh#J-OI9@cv4+K%2s9$0;5^OLp+jXhn~?1PIvaC z1yvwRevj?e8KOOZ-E{+4?(Fpraq5G6;r>zROM-g?A5U1%E9}A97gh9;SAxI2%PjTG zfBy2kEUnY4Htgo`&7u>wmL>Z`kY-i(7sEY?p66TK`oO>k$xSTYUlra@ zi19wUnyq5qy$DGVIBC^~r1rtI`;WT}P8!Q?Ke?ttNVUSua2#8rZ>YAL1f+3VJd9fX zTUG~;Ue!};nCR;WS-qmHilrcbT6aPzq+Hm?V;83x(M|`bB392PTa7tEM#eTC`NGQM zmZ~!AaV$h12;$H8w?Om#Ny9gwsxeT+Vi%YNlv6l~jXrA9;`(O!>kl0x=qSfm})09b0VV6DgIh&cu) zAIavx^D?#Cnq>@HC!b)Y)leo%<~vzO9yO`6utqv=OIXU(S4fd_G_t>5MS|9W>E)uc z9-O@Z^YpeHV4eWIOzBU%45|S5aEp@i;HB6VzG9B#K{m$=SSO4utnq7yOlD`Bto~0c zZEp@;180EnJ}mjmnTFUbzM1SIUIM_`Z+@5{O%9W=axO+fxl*lzS&e7$zouT>%W&H( zX03r68j^m-^2=I(va;j`n*Qu18^B&rq$*9lRH^0=PLrj)`rGx~m{eDj64Njda-p;8 zcumg4A7&EtYU5}j)nS6f`OmVUcuzvN%gxfWKf^F+i#BHQco*@-6(xmK;8kk0 z=d&<;sgBE{Q)!t%6YAAI=OA(``kcRNM>vL2wg{hfI#F;QEH2+)hM8^+|Ggi?*KfwS z`-=nOo5U&YL~Q-OdWDDN8XI{VA3kTpAs3DOUkVrGM#vXpb9)prhiP^wlolXsB6oU} zn1pnkjXb-}>EWPvQ=7M}B$F>mvL)3ucggo_M_7yeFLn}3GN=9U+J5?#=`~QF`d>BH zI^o_8%q{)87a-QPX>S2rRv3cGAVLd-wMW&QYziwR>=&50EeX=r>{NknB^2JS=Kz}r z{XwhiT;y;*Q`!l9iN0mzfM*R7MMBPion0cEPNcT}ogME-*Y!?>5y2l;&x(Y%i6jtM z6>1%N5H?Nz%z(Dp6PkH>xgVLMZIKCul}dSPlkEcQi1&uQ$_{NIEXBHMbks|XG&bdI zbcA$5K$@>8*n4zku>gOPF+o~OPrmoz`(cm|4Oum;EmM3-eP1iu zfP=5kCYEQnR4t&|+PH&*R5=0P{~PFivH{OGDMSJuu@GUkPKOX@JNqXu&CEH59F^v7 z3HS?F)GwC)WB&UvmQkLPx1)nR#k7dOLui7HhU+WFl!M!A+W)#N z^GbS&@$if`5$bk7>fU}pB-WT-y}z|tEo3$BZ;CZW2hpl#?C}s9=-UcWowON9GNbv# zbpz6@c8EA8h0TymXS={{N4fYRGIQh2$wLa5-T+6Z$^BqY0*`Ezsf_$Tnyxaa%|Kh? z4lV9hT#LI?yl8QE3s&5{K#LW3hoZp=?(R@DIK|zA!^?g5y_x*@CYi}3fA*ZSXU}eI zs{Lm=4jl)#-=wTD&ZT+SZT6i$w|))-pb75gG-JY@cDq|Y$6X<4FjD^-UFpOS5nlFP zO)NZT$+8h(_Ga41-cQQU0=iv=d=|c{QDC$><0QOzWwHc35c|&i_lkVmn-a53E4QHj zXN_Z?YfSkF>{!WJOeMzRDtXt@jxxLp=<_In6}b||;Q4$xPq&pz#8fDX=1 zE|0IQq~7Kt?Yf2P#gA?%7`F3rgY4)lWySij_u!!_#^ z-Bjvb2arGlgrKicQcCa(x=S(T3hgjNMr_O%otbO%qI~{^|vQG9>&Gr`u@w|x! zCFNgNRumYs$gZHrweDe(enD7nU&}4lnPW9;9QUu9nJPIS(o_@(| z8BQF39TG7wf*yOB0L`W_ZM#fSRVNJlvU1;k)E5EKnY`CCr(A9shF>U~(1Wq1CF8XF&*O`+5hDB?s1;1Grr^jC_W zh9&jK#R_tDhR)l^f34}6hx^;!hsDwf=OqCq@p72jh5$G!;?iQI@h%C=-p|5>s!LhZ zbEqZ%P}NqtqtQ3pdf*19I}-u zADB{~NYx_J5TVftNbq{WgTjRwT1_J=^7;W**}A7)oVfNm-SnQb7izxVp-{gs{T%gk zXW*7B-a5|B*--F^n52*q1J4!NLTtu_#)4m8pl%ewfCNlRz=#KD(xh0=59lL+Ksqi~zb z+BzEIhc0SxtOmnzHA#GH$rcKB*{E=7`@&i8OJ$9uX^<$S#MP!1e;R$VBi58kOVD+1 z$YK+Xmhej-vX*9ONlmDigbBnOBX}q2lhqz9w%3NQV+jkq&~^=4EI9W7<(NFyA4D_z zDf`7K?IU+Q3*|NC-3aWWR7?aLu9(KA6<#e zy23MiOW1^M#u7;+7aJoTmR~OsRj2=DxBS!pv%We@_@;=2)wW5m5dY2cfZKyn0ro})S*0!2FtD+ zB0x@7mKiFRpZl*^o-B6_Iy%GVw?F?}8o+cd*NO|RH!W_)PUp2^ULgccC`3y_4HZ^4 z!&B4d^eNx@_UJal(|mD51WkaSH{f=t;Ft38+(w-z*$oD!EN}34lfHH2+ zy6zX!6M5aiTAQ1SXEgEL92^qREjPBVE~KXjFYs|I`M#z7<3uaI=`L zp0XQD{JUsomYhJ+ubm#&ic*H&stqfeT$d@RxB8*i>a@KTSvtMz4*i#VH*xPvu~gdo z608?5+T=dZOyk{ajp(&Wa_A2A)2hY0qhd+L`zOuC2xh%H;jlL)UX>t;ayun_s5@NP zRnaXTqf%M!teLZfZ3mVNpyX+ICW zT-$;G>|bglg!2;w*mm|sEs4V3_%6Rns!>hUs_zPa+7QAcj&)0AzetzLN-nw=VZUmh`I0w$thLiLk5v?F zb7k_n|8UhMEv)riwkVI~yBy05-?nUAK+6Ccjnb@pB*AnO2?u(hRe>m{%?RKY%q$d* z@7x!U7i)!}zfI+{k}n8*ZxOEIHFfzTVWjXop69C2#o>q<|Iy2B>9Jc^yXf#BY97qt zI0{l%vD^DP691bQzpH7mU=|j)^_lthewa6|8&O5I^#i|7-P5lhJT=wBPY+a_R1aAz z^>@{Z4^@f}Ymd`x#UAi;iH7NyJ}=r~;}LXh7O*z@rW`ax{P2MwGtp=qF%N4AHjYz! z%?#Kg2}cwqsLGDBhY zSY(JR^t+CTOtBHkLI*93cRCG&^0>G(0@pl8b>W}LUo+PVd9rVDmv zt7yT7%wyAvO~6h!OUQDn;6=~rW1<=BL~x|A{=;_j{P!a@V+&=uxWx^;{T%*ph*6XG z+<_O7M8b_2YB}s!ORWgc)rBs$dd2ziuyUKAlzSeLu_>qCf4(b{u&*#VyZj`%(5@?YOuhRr&gN+QdIiM5{gMSxfQBH8~ zUdHzAQv|t02^SXE&A(O)ozX&YmIPm#Ab%G#0KwdK(a*!4P*@J)D|Ls92j; zxj${2Avi~d@GsN ze@o^^o>*++@}L{8;u0FNcON}EB>-$Igk|Qsbb74#ZinRxmxYGzOiA7NSXmyx1YCNh zbZ;k}Jd@L(e7NF8Ibh7+I=x->rEZ0MfG$^|LY*BzbR<0P zOqA1U)uW|PxIMfX<&vAdHnjUZ;!)i9m@-(GDlTivF424;j=qa#L)Zr%Em>Es^M6!C z>-JCY8s^FtIf7F1gA+e00M+~D24ekR-|?d57+iFWBtSP8$%%{Lxcvyl16>U9EA}sc z+A${34xmZZ2yN@UR-|O^tL)8ODuE=gQw;@GYnHRPUEQ`BhI|1uh?0Uh1m;4Z(690 zxa@52E3)}eKe##?z|JRk-g5;Sh)v=5f5Bnr%Te$dI+w5$gR`7xj}ZNh?I@@_FVxGa zZUm!cbrEc-a9#ZenieYdNJDbv^(?Ud>1o^@UFe-J8d?v))U_82MIzv-8td<#sHe~F zYhsvy*kYO#npbJ~`<4ig1Ya1V@XBfJ^Y55|lmXF#2$^)i6qbvsy<*B90D8fhxa2K> zjGr!VbhIr3G5DYQ3_oYUTN{9=+0+pgs8Z3MVVV{-`dnph^?TyZL35pfoT zmxk@EwuA<$rO?C9S_m0y!BiA-vpsG}5p(=ajH^gTQehR{fBRbU z@>5XkTz%n9<3h&z=oR#I5-+IE1!pS6#5gXvh;?UR~d57duHD;+cXX^KnQUK}rF z7)sj+rqUTXnyMfS4C5nQ2+c|BbIT)9s5FIwWYi4wWwiY2k|Zt=0RjR-y%bBa`9S;; zlzPv*@+tf|t0`H>4%xi{0@x~pA~SSyfF%yd(?_&83nTHhz}!oOQD-n!m#Wl;bWo|= zHuoW4Rcs=sDS}odY^##cTJO>$PYFjXk~>t;x(8}SAFB}0i<+mNZ0<3wozrwfr}M59 z2Y2bb)Pw^cXN54SbH^zF?KU4jzCVo;v99&YT#yyO#O$%}Iui0Xcq@x`*_wZEFa`hV ze=!|LvqWJ+Hj4e;Q%n0u66?6?zHx&-y4^7}k^(#ajY8QvI1k&_S|W_t?jB%zSCZFC>ZO?vwEtgK7biS3OFL4Bvijq&D)!>1eN5XB& zLsO>w0Id-}I)=h4)zfY@3CyuCrxb)0KrazQ)!auWBk}g3#y}@tL@!okRVt!)z{@{5R@xC@r z{%T^jo)Kh|N<8DgOFE(8BLZHOQe7^ee^Adv{}2@BAsgJvxRsa4VhgRWj>#hKS-s?7 zKt|AxlPttRTG$)E_cV6q0cGA6FG7q1Oktm{Ij&8Z{AL%_c%A$xaso@@bS8 zu4m4}s*Rtri)_z#e{?mbCIGrada`3(u(pT!w;8JBwJL+Ze`xE(Oc3-VjV2hf*JBxN zf=&?P>PRkrZCw$K+H%BAgA8Ai2!@CIt;n+o#^Ah1@7?a+EU+1cTil^lV|s_7TC(|q zrF{k}gZJ3oyrQ?xJ+wKm4yei#{Qw;e-Z?)th}suro=|5y9zxdV{HsO&>QjQrlmPIp z5OD?$LK)8y=X)0IxpVHFmu;RJfG? zV!}V?LvEcaJlK>HAY-=e`~X$Wt4nT_Ymc;kZlqa?KwC80n+rvx-?(7;z2OQV?S)H9 zU0wZz=u{Uc5K0qgYPMeRp4Z7AAHP$5@t#*{K?|lFhdhvc0G$pf{u5AfkdtPY!tK+; zVUr8NiF5t6PQbY7EN!P$5QlNrjC}iiatBPs+(q}d`zuv2ng5Z>hB}0nJJo-5X=qr8 zIF`-NL5cE&$j&P$$luzgDK)3q?q9g?X8f?2wWrrP)L-CH_2D1q&8*dO*<5iAKY;bbG`)ii7^~BZEu_9 z`ZC|=iIoQM>^1Zz-nM?y9{1Eubl{8JK|>P7TwUZ$i=cJJ`bVbcrV!<&8(mQ4B>=rk zxU)DhXBbPI4CIV#|5jTk$D~`OL<`=WPN>7oUZ1WBX}DKKcDawzWkR0`08o7U0QGse zij%8Y&+?zpPT>YPFIfC=0E4_;zVrvk&Ywn`Y;}RGCs*F_Uc}RQ$>&ok{b3hA23C{y zjM=x$t5X6r6ZI^&rU(x1-o8cD&#}N(u(>5@sQs~KF>Qh#p9HR^Zy6Y1nNMm#W~{$i zdI=$oMg;FBNbH4A&DNfHaQ*ycR42@2it$%k%m{eaf^u4@aiY&ax8DMnlclmh+DN1Y z8nW)J{{%tP*UDvKeEwJe<9o%R&ToO^RJNFJY=KqDY%E4Vq?Dh4#UEOqYs#Q3<&GC0 zQVU|quRFy|jbVcM4jej{KM0U;p?CUUrja(&V>~h_Vs&@l<-#mozS4j{x=iQC@&DP* z{YYyiF>Mxho33g-(gX20?H4-#t+s9v8mroDhU_ciT!Y7?5sj_Jjw-@a5-4-GdgyIy zsTO;+ckd)MfO!>$YW3Yvdl*81W3QpwKEf>Q@Xtv zT~V#|yXEfFRJJl<0B^SxkpUU}?c*z1*QJK`wA21ZhwsN)hsv`B9V&ozoI0WvQ0=cE z!Iu3Tmqn@Gr_#7*PBo9L@X$8(?xp_Sz>5^i6d&5_ze_AQf&_vyhv`$q>d!-#WJwTpi?m3=LW$=h?m}M z#bdCaVbuN=iz*U%d?)z`aKqcI`|%T##_%$eY3P-X6&!?k61GQ12W%08Xi1Tu22@=VMD~ot@$hsUNZ~W)N1-XEe^Vbt(5Baz3Tg|PiMwqs+}>IM|$q{`24On{&VxzjPC3FLiB z4Rw~j#PChu50SaPG;+r{cunwRzf!MON_qcM-h;b#7}=UP`p=`EP@}#2mjPv2H*Sit z(>()CGbq5x58Mg5dSJq1v{?Xfkl!u%}+(T>93ETuxKvT zfVdtQNXV7xg|hEq}sALV2T%RLG{=UxC@wlYk5=3gT8t2MUf8qFOaxwgP z*o;!GR1ve1SLrjN#ClB${^DYU19rkbrZ=x4Ww9;Qd4pFh2fQ%eByQxh>NlpB=84^g zex~66f|+PVm34|y>qtI~-x5c4r=E8^?9a8yVa^BuCRuhDQuvSfuSONHN<3-bxdgxF z$2H0R!?a6}mO6c(sbf!Y@1pMs{5rhOW-S4pHwdVTraj-tz|1?R2*HH~*Lz$IwXgnT zg+6>=T3S`;rq_>fT-YjfQGa?hn5unR3Ya)b*xr949N7i}0g|hcmBA#VQ_SfIh zp+n2Rl;riB+w&u+6>Wu%9(h(d_azQmgfOb4b5VT+#TUuz2_~9|=W-^*?r}x1D}|$j zg`tU~g+r>;sV{jAd+6D$iyvWTqoF@>&3i`ddf}W`qlqYj8rpPOW9(9aaWrhTr~wqI zi{saEUghFg#uHsWH?8NoK<8mtxJdUDb-)*Bu3vy zvc6SBboQGr&*_pIQBLqmlQgLx52_EWkQJq!TE5ulDQ$2`lB0Ca&tGExe-Di1tVSRMt?e=nNO*t?XCOdf;=G3+T+;1 zB(KeDKRPD;YKSV&`=I-vRV!iKbX@300???uc{XlD zvIg84-oMVd0j6(ZCfss#80hJBn~pz4M5-=Q2nfd83#B`jImYQP91p(3e}4a&=Nz>A z*IuTDq7PdhAoe%&y+f;^Pw<*-&N%#3Hzomm^@;6->t%j{C}S8~1+3qOW!EGL&8Q$Z zeT`ThwOYNJLy{em6L|i;h!*a4*=T1RoaZar2aZqhp?Y$_|7$<2+DS|^S9uzn(^(39 zKDRMiG=%WQ#KgKlsDKL(M^KmM1w)@z@mlLiecAUT28<7R#SdGbD~13UPf`nzn{R2e z8+R@|(~eM}4=)0hy4~D89Nk0T^9gT=wHi;Q0kS}m9HD2;FZf@Wcot~lwG=2#d1jRN zMIb;c52|C$dFA&af0-XH+CEPQrzboi1Pc9_O%gnDw~YMp{*$NA<6}GvsYz=A{4D?6 zU!7ZFA}`3mE6iEmnMN%6o*77x$P1f4aH34;Qaruy!ISqTInChVLX{fiVd^gzkoN3K z(7M>y(vG}yj&aR}{w|szdKWw{S<1EPSTw8bMIL1|muk}-wtQx~Ogt9v9NlRHVsUz3 zW#6SE|2$f^zOq6B|4g`YdF=%z3y6ctZqbSxg=ooB!!cUodRC~uKmP%H8&e8)ZvYfQ=(m@OT>VtZRnoiFzBok z`O-6@52!(I71wu@d}gR_@Ug4s3*8N--d^T$74;z1zLn<77B zn)BixN@-|?w{vvd%LG(gct2S3OpIoduPW)z0lm0gSKx6(t=WmVDKMM&kols45=VUnK4SaG2qQlVHzjY*k%bDT`(k2!OUhZ2cs0YqV6qeJGX zG>6WL^DQ(PPj;~LC@|KTBvpHRekLaxNeZhl9ug(!eq)|%1ay!ykWdEKp|Hvt*;LfW z?Y&K;*Nf%8tsnIZ6dkXD@jY_-8jrrb?p?I0H0cBc`RZXNYBqeZKmvmW`7ml27Iyo? zB`bPMi-;VHaNKz+BHWQ-e=zp*X&ma`xeocSA(f~4bUeYP#n~>$`6|eD4zQtUV5W?q zH&c!9?H*>@$2Zst7qYH+i((6)-UasW`f7ZtFLwIv&NJps3J+av#1$47m8FXF9wpiF z95O0!-655K=e_va5R#S77ayVce)t4%K?2>pKF)gPtYV>#jFFM<0~vVr$-xO3R=-Jp z{t>oWskeobbFRVQ@Ah3yZm^KF8ulbkG0T~AwH_xJ+PfO7nOGa+xCz8cx*(`}gIAbJ zIsK0C4(i`(OP&^QLyFu-*I@9^w(bQabOZpWapUqI_(L!FNvjTj8!i{59wo%2a%Bzv zzZM__$uJ9I_YgB+ha-}NEwY26ttXf&)6)>HQOR4>Xo~xfv0*?xn*#p+8Ef@Aabqv7 z9_8nqa6`t^tY7Q(C3j2fr=6v6p3Q68Z#@-_s^3VsNEa>!Lef+T27zdk1i3o_*;$Y&Ti$!EAD6q{-zSTSV(((v~93XmfXVqQHkCqOmxctoOGP zQoW8FJN5<&+4mm%C(?z+jh2=yO4FpbEwhbUs$q);GdZ2T7N;iKW|7)tBk}ehH5gTL zx``!Blz`5GX(C&l%A0M-4k0r`pux9J;?}v6s0v9CuB@2q|?Wr>keIw9BhzlQSuh;m<7IoZ@16nxpic% zr<)&XgUHvroL7WQ6awc66BbiYyl%c)IlzTlGW30)PM1c1Xl!f$B)FGynj@Z`So zs&8lhn*Vf|5<+2w8rOh$PAsuR)GnFXqG3~&3Ag6P^Z@I{y}YWYl) z$!gC&`enFnHV(6p{B9(uIBSbnVZe#-Ed9PPcXdpaq5HT0DQ4=xJx^*TbwG8`J&zEp zf|pnBDnH0fZZWVt{s~H*jQICQZ95!f&DU)?Xb{ZdE{leCqQvP z5qzsGw*T_ctGh?Iz^q9DN!7m2qmI9jQ=rP&>iOS%ir9I6*{ix(yne$z7d<`w+o~w0 zNnkzbMf2>48PQ`0swQH%S7fUx8*Bv{OBOXKl-mGh6>J)gFO0Y(JO=?S<*jk=tvj13 zg^*-b-&WQAWbAn7BJMJ~bX@B5GAhx+s$bCUBLm*@j<17KHq6B6Z)Jv?wYA2GULj2V zd3PaIMBP{%`rd5H#NM84TrS;G&N90z*FolGFtxQ?6u$wDAcJXb{;aSwjF-l5$H{FK zZOuAsBcl6z5c7h~MKe@CXK5;Dpd-P&!mQvGU+7wbgw z1ZbMqV*ebaG*%o5(}ft|2+&D>D%dcPN1BDg`B$kbp{6bh`}HyH36)#F)Fm(w_xlnM z7dm`E|5vHX0GfU?wSJ9;yd1R#Ssn@1TrrpJFnf2V7sblZY(ar8`N;yn+k+%ypK%AI zK2Y=Jwi93W@lbh=;!QBMKexoyZaP`o0K|ukXxxbut3u2{;vCky*XErtB%AZWE zigF0AdDb5J;7Md?su0*w7fU|(kIV_29KTQ%e@E2eYgm61Wtu=d#2FnH_bXgr&kp0m zhlZ^P_^-!4nNG_S8@L|n=*QmsHkG#CFGAJ}lcja#8M3WWg#u$*sk>#wsh>G5JRBbb zTDwsZ!)=PvN0OoJxHO$TkF<(|gLF5|@Z}I6TCQvo9X56gX4?uh&c|&|47WPJ?wir@ z*VfR&QtXu{!Bz%GM@L}!nDM#ajuk;~NzRBBfo*~Y0iJh`3}T1uM|KbgJLTWWSrwBS z3P#7(#)LI;6KVa$2C)a<^P1JgTYU1(dPe`z47HjiFSPIxR9$XI= z*!3G9tm-DJ7amu;4E%b^wLfc<_P7Hcp$)qUli*pCke5~iSG5+W7*Lm_0k2t!07ULh)SC_K6BOl4eV^Jace;$OSpZ$?X8m z^Y7z}9>ukIzuL0*sCK8!%+H<;m$DsDgtwE@-1I-deP92{6cG_Im3eVgx&bBer3>R; z{_qsEMuB4Af4M}?oQ2K45XjBxm}X9Oh`oFpr%eN3ppfhLlT&pG=LE0#CVh za59xrw5}Vo>FhjyUz}@i-SI55)HIIVS)!(89(FEl@xK3XvW!HOnYn03uCt=wVuROv zEnV2LmlKJ(ury~xXO4svruZqmpRbRMvppSb{JNUXU_Q)TP2MYCxF|f&3!FGiEqb_6 zOn5(I-0|#@F}6>5AD|CiqUQ`$19oCmU(mLQL4Ee5PhC+7GocL4U10q4Cti>tLEftI zq4MRu?}9Y^<_OV40)Dz(gl_5p$U}otiy#3K?~a75#rF+T@~yq53=#5wzEr6&Yuij8cEE(1w0P5yENc8@;QdQ32BGMLL_UhV zDUI{9y|16#M$~X6ziLgr`qF7#z#(#u^L3ZrQyRN6Ri0!%PMW+#QDB@BkhjZ7YS-kO zMHGx7W5Oe4@o4o02-(w|K)Q;lBuWJ)r(i5!Ip?~L-b!nq^`p&@N=+|P zib)p96}|(xmdkqOl6>p~cLcIamJEi&y0zp%In|rU8#%)+Mx{kr@P?yYGUnBN*TzuO z2|R(nR?%hgSbabzg-ZqIbzJD5zjNM0*j0_RK5`t>7L+f;G7oq4Vleq+x{@kC&qI}C+jbKQ&oP3bGmGy^K6US{faWF)Ow5I?!Er-) z$|Ef`0*>6%5G0g?40{`ZM2HUCv9k!U8^iVl7Wn0%q9kgP-I3H;uI1cqs3W_Qxsut$ zDKcp=bvL<`a}@(@agrS9%c4{)11I1yt|Q-;XZFJFZM#Mk(dp)Q?3}5tM zjNN)w^^zfa>5xb93*E4G8J7|Kk;|pp#j4VoYZN&qNh5f?8emxo>6YoM;64@Uq_-`wI(06hZ6q_&hB`^wg+yqVv}Z3>Cz=7D~B0Ai*W&ZO}7A)m+crG(8} zQVIAzAA6*9t=0y?n2GqQ+U(&93YZ7IPRnP<3kgz@h<)-(5^eo7XyeaW+(ZIBjLP(4 zovK*qP%mzxT3HmHIg6a_D6qQ`49)ZPN_pZ-d*upz>YTl3?^L{Ndd~Df80F`xH)VI; ztfvf)zIfsfZ?GDw%U``OSiRR`a#*-F4sm)vWL-Ti+T{1OBR!lj38C*qK}R3y12-66al#BX+Iw$F<+P zPw*x(PJ+KYc{IRpRJix>h7Jn!6l;Ix>*SEN*v~BZ%$uX%(4S*g-J0n1Y$M3-cs6pb zeNdf8pgt{CJ;#2C6 z;>$M|&v4VDr91ldF`!xM;HfOQQ{+3S*XQlq8O(WbR7yQeXHWse=$VuJLbo`$jZuSi z?~4pmyUEt6-#L=TMT_h)J*8K7C_xwlPY15eCKg16{5}JP_H&A*^XN7f8dny8xMBJ( zs13RUy?NUHGe_Dvg=7ziRiCcmDw4%u8;7pl=p1ue(U=IX7en$~R6DWIwb+5eB~T-r zi%XbMI#{gG-E5drJr3Pcs6u6VN9YJuJav9KGmg7FpV5M`OqisP)>09lWoLlVJ*MK( zQqI+#x3O}sk`RLcZ$>FODs9z1c^Q$sfoXt^DgOjN1+Jx|qnrSdX56K|K>=2%fxW6{ zXRgP}N9gJnns3lxz*3#2-@^xd5!@vS5g*xnnx0d`OU3d ze2l7)^cG^%0#!DFv^{72x_HHu6TRcL~Ii^jeqT6%6!D>tXTSV6=h+i*r zOKA=7eN^&3E;r1UGze6l&Tpb$2uk6lg90^%^SUgjH1U7h@;ed;tI-|>Lvm*wzT$+G z{3qB>Ii!&Zb?p(+!&xN9&QO(phiik*arUJ6`GI?n=%(rC8FxVk-;O zd2KZLw_2nBP%Azjj0CMFyyrw;! zBI3V9l3*OPwfPL{hB>iPE~J`ca??I+vd!h8>_$~sfdvb-c#YLK%c*tVo_eeC=`7@I zLz@~flvMU~Ivf+U*#Y}N=n z{g<5GOgx*a%*x*rphA9wuIjbi#Ya2q%?FMoWbNzSnt-T?_t%;j8NmkWz5+>R)4-2b zI>y@LX_%n~n|>@1s8LYWr>t*%q?Mh2pm!-ms#&5)I%yg>ShdYHjV zx(27*aa6e(2tTRdAzEtWWx3}lK>UbX|HClu<->(YAEcaA&rrv-?5>8o1OFFG;U<~! z>I28)0Gcgh{zQtLx|$~*qUEsK;!q^2@=qs9KZTyt2BU`Dla3WAi_FdAUJU6m2Tp-s zj|K+5I0jWNC>if%gIAhXAHVT(7*y)N629jHBp_g=8%;n-0yy$CT{$pm41{xj=@z5o zXvPXe+-+Yfz>Le8-FO(Rpz=X2U<&@!Ci)G?vIZ>~5Te}*D^X&$9oNvQyIp>nnMqOa zAs_h@xZ)<9q665N3Ds$VueMXs3r#6kE2CcB@vSG?+@6~jBCoe|32l(n<&73!Qi^EM zYd1~yI*J!VrWaoDTUQq9B!T<0U9kt#{-c3-{anrR?3N7Ad|y%>h#~78x!#lcY#VzK~wGEGNDg^9}FM zl7hdVm0oS8YMVk1APxFNK~=)j_Da`fzUb=L?us!(MDv3utyXbXVGf zmbi{zZrm)Q+B9q+49};VNGWsK)SrkUYs!zyt7iQ!HoTQjU_fY~BVTVay6uF$EDnU( zfdYF~6V9`wD2N>rXWs%3#{kWnEw=aG@U|g6ce>Mq%n42)QfE*Sx2RV;+_zt+-$G1}2K6kR- zV~CTqcerYVY0yHQMp*7H>yFx_tt_FFjsAxy){%^uQPLS_3^#+6uPWAWJ5Co;1W&19 z_CqMJFGg9`mL;IlWNn126e6AqiGm)_$UZE8p(v%jbXR5qoWNJP zK$^9}aU$)TgD{eS(3+idvWl{&|5PdQb z+RHSnJk=waYD;g4zIsiM=>QG%5Dh^J?3F)4n16iVv<-5wa#&&#a9FC`K1Cw0QHgFx zHLX?YXZ-=KADuVKZ&tKZ~jn1un|+ zSDC+?{e^dD?l{IVu&qZ5D8h`0!#GtftPnhOba9yCaDElV9QhR2B|W+DJX*FErj3?E17D^fCQ}lGzSMQ}OF#sXPU3r75;6Clt>e0z&Rcjbj_Dzv$}}uHJW< z_nfkr1wF@Zz!sO9-EKrsvtig#J6%}M=1`jTjBq5r(pWnNrJ1kui%pb^E~z8SZ*ws4 zl*jYk5TT8!kcb+(Ur;}(`lr_ceW<@WP1_w^ESvk-5(Ty3nVYf?`y2p!@LgI^?Ly}aInfvfPjdSZwSK?rVQ zsCUp%#897={?l#Ql4M|(6fBr2S;I3OEngIkZ1@ly?=+r<&n%LKcpZ%h7@rkts#s_( zlZhta77;N7oB$UDcQBfeVW;vcpq>1}F=8&G4$$5PTn`ce)Or5R_Jq&WmpYHrfl3YpafFkCA|i#a%0gA+KDIjvicYyo*pwB*=$`EcV;`n*z10$uDh}=EFE_H9L8W8$ zTI09OJkGnUC;n`Y%FdDk$RSU}i$iltEyz&vg?cSuZqduCs&>-q+rtt6r?mjiY$IrL z)X71H2;}Dymx##3=|#C)<371`i=VmQPR7kjEc98QaL}hIkojk0wOsdsdN}Dv_pVf` zM?gaCRkf`!Mu88s?$D$-?vM-8B(v$*vVYTxG7)`R(Q^=r~T*hK4bT zlNnIuUGhLw0aboVD+gWoYclWc@7Y@(_*QHZZ%I&IhP9D~!n|iMy|iu^-(lJ$=KY)} zS>hcm8f7%?Wb#r5Y?#5Ih850%D$kP~;$Y=mE{q5p?6v%|FIu0jEjmiLO`};JtcSce z)F2o2g8r&I)1RWdv6K=g_gxIJD=lHa(pb*uEDn}`cv==;fbLX#gsVt?HkeGAv15&{ zIhu->4K=W*SazpZhStLz6;nbB!Wquz87O!3`)rKUTZ-l;IHcXg6!_axJiT9(F&BTT z?HSQ?6S^&g6l*`bd8aZTXkucVmc8bQO(WIJvF)ikA3j~6*|)3ibE2C$-1z>f|J1%( zujs1A{96n32;|nelAlwg*sN0mzsAY7=6)O7UzRKNT)`x8VZQtTLk)MRlNQNs~Qe&azXVa}|L} z{*o1xZRBcL{--Fiexgug!&=VOQXiwfUl7qfn%bIE)07vk5ymsx_|7zxmzc>S#Njs$ z4Ti?wcsIL(6*S^c%PYmFG2>_}=R33C7ib@zoFO|VACxG8Wq|Pt{Tj&~d)DR}sZv>;(@-!Ta790$ry_2cM;KZ-l@Dc{vo8afw;|4 zcQI`EFy3upf5I7eE~0o25uOjYKs;`qz37fKIB;+Hn@9%X34Bt9_loQhF030#JbmnW zH@|;=&n88WuYDUkORi49SgUMUU4(Y{>@7!VU68itnV^o8Sr3AeQBny%l0O^B9vmCB z8cZdmVIx&4;GVI0yN1f+9xs7NWL|(r}3)!K07G< z5-qT8ueVBVhnWo6=Tx%R+>hq~ltjW$YcvQsfDvb3QJ6l_FdWVVDjtK`GiV<_J%wh) za<0Z@zg*qZamQUB8g)l zlsNggeGb(-zPKmOI7kb?_N~Xdcu}tz9YUu6D7%%74SDbL1i{+@C0q6kH^xV-_^~si zXU`)4IpWZosO}VD4MtMLIuEcv?h!zxk4xg@1NNUMZ!%sxgT%){`f@Xm*6z>4(<+O1 zWdE-P*my{I;&@aJB6^j5ooyinb(yyP&$rE`aTmHrww{|`-971dT7EpaPSin}|M;$EOQ6nCd+A-KC2 zcPkDp4#9%EyB3NBr=hr0f&{tw?_KvLPgyx9SvlX{duH}b+z%POOl2rn0pbbgMDp1I zS~>+M*}>R*0hvb={63n0{FM4^mVL|VR!tn2fjDjIUbP&I6GEts%F9L^S4m&th|R_s zz21cP)?3!~KNyqcX&-%_f|I5tCExSi>rDIGoz<`5sRyr&| zV}~*j8l_dEYB`Hjq-|(i^BP!d=wbNuR;t#_z-r|P$Fw41?YiNWYSQ^v5z!Q z!Y61ulAf6+q`H-faevxwd28&5*zXk6t9N2{ifz2Q=CctwUCrO|&*Ywh=x{88;*C># zB2qMKh&L}I59a3N|Kzi>ASswq($5;Q#*XdY7lN7m(qq4wDB4{l9Uy(edV}eZd zQ-s1nYMQKX6Xb2R{*K{h@#lZaI1nwfTADC0q%f7YU>=McajUX)+gO>e?{}itcxaG) zTkw{GiXanFoNB+ba(niZWyxZJ23gC5C4b`2@Q3r#{=(`|H-wr>UhAGn;u>o{95k~} zL+r|#e8xJ}ranf?j@z!1(fTHnIAge%a06OG#{yg@ii})=#h=AL4Y3>ZJVl2Pnn=^A z@5q4q^G)z=Dy+4MIEQXv-R-deFFoiPkI7r*@2kIPrK(cj@jY9Fc0en2gz>9?CQrZ= zavD*Q-tur)l1_~SUT63i?AF(Wd$LX74Ho~MKeF{cd1(}fNE?fI;y&P$*-gdA?H7NF zmDe2q6z4t$gYVeBUc45WOsR#Va5K~zI3G-Y+s~A>m%>1L#lN3N*EEyjUa5rN{vo_* zoe!--Jn^|z6cGXr2$4t5Kn%$9PF?ZR5~v*kYv3+i$Uww5%ATVs(vd~Ic0!c({t zH#URb1~TmhnQf4zJoWRwU%h(Ij0a>yq=SS z47KcS($~W*>&OIminFdyrEGL;@M9My=LDyhW&mR=bMmbQ4eODWZ+FyC!naI!*@re9O% zl;=Q}&?0K5i`>*Ax^gfE@9kG+-42xgSEGL0?INr*OYdrCw=Ge$&^0R;*H!75ja zQ*X}|iSmigF+JDe=~3mXKBtsieGbCE(A42(@c6U%@DN#hE@b9kXFYbLcBGqI_{Q)J zBeEZ0BO5=H_x3HRQ@u3ywQy7(Klet1Rxix(KQ+7Qdmurh>YS%;Yx8?r{(~_rWBXeA z@6U`2M&Fzz{h}UBBb(oUYNJuOLGpz0BuqG5zqC=mbubN&~MHerW($_O{oA)W9v=79Qi!>2nkbi5>i8deF${CHGG3sz>v$ua`gPoW z`}u{62o2AyoW__>zb@(4tO3Y;xus?F$>11`sIx!vO1-5-UP0p$>yaa_D+_8BoOyI| zv}X|G9;*Vs@jLl8^;Nhz5hkB&HNsj9GG(}RJTM3)i!xwg%wb0M(PHD1mfr5&4c_pV zeuw%myM7-)EVEGi@rd9fe}w-0rIEnbsNu-)2E7uUP?dPXnnd!Pv>zEgR^$=siNz~C2TT6Rp)n` zpy>PX&q|0JtM5hdEtssIlnLp?au^mZ=7oNlm!%ar+np}Qv$MW&^&Ke_#zBJYs5z=4 z>I0P13a`mNv)VXcnaME_85)eC|ptRRH zumm! z&fTUo%x>7GWI_BXtppM3SkNo;+&+VJLv{Qm3=%=Uy}mjctbeIEN_&B|pQFqc5XK~O zi1GeO1vRFxYjfuqb3#Irx02&EB%7|Hyq1Rb-rsL+j9mZZ;p<)o&t44a{Cf~1oQYf% z-p3#=K(kdB4bM`P&XXz=%nC)F2u%~5+{ZaF%!T^dPATQOgv2x!W%Fm#eM4m+{P~4q zCS_ED8Rt8Vl^UYh8n zLCF<&bbeDI%VW$0H9JwlG9_#aUChpY%Bg()`qjeopAJsO(s8~H&h+xJi5`6SXez5^ zX-#1^Jr~!O!Xd9juSL{j$nC+tCoJr&C2xbIu~dMGh$rG^f&qxPW&S-qFv z-%)8WiNDhR&X7MuN`^}G4Tk+8&b82w8p6%+JxB=QMCj>)Z2JvMvg+yYoRFQnlvYXhxe|qH9>Q^zJ$=> zIfyK>Dcbv>rUIwU=+?TN`&DhNtC#RjfB%M?Z@*y5SymXCH0MGsZ{Nrr%v~d7YHqO# zrrt~_kQFw*dT%x$0B0k_1JmHEm_{xqwsW;EW8;A*hHYK0kMtQvKuKFft& zg)BuqT>_nhU+~&eJy1pq$j+xo?;&hYuLYy`ws@mLeB&IPPk5yrS^?SX``ZJskQ2xr zvvcI#rolvo#Ntca^5DHQ9$e=R3E+!1wo+R5RNQL%614Qu2SV|Ff8UtqZ+)-u#N}lU z1#W#aqrSJ|c?{@_di_U*%c?r>$NU^f2v^=v(5IA_6!n#g^+rM9Sm&odjzn zv|nwhRV|}OoAe6Fnp>-aNTd1q?kS=5OAGIX&caxyY#L(zCQ^+l+>(Z>L%9#Gg#@!4 zPPRf$FS|ob-z z2UbQGvPFDONA$A5QOQS>9%EB#O(}`@emty*_xAThw)-rt5SoOhq##pP^iG*^5dlmf z(n(w$Xkx^!_fkh#y8qyr*qrV(lS;;?C;kGEUjHZn?Z^H#~Iw& z?pT9uF_We|On`Hc|JGpx6S)F@S6(x_pR1f#e8to>XON3a)cz2nR>{*aI?>%Q6DlU8_O+9|XH9JvmeqRw$!B>CW{ITm4VU&J2jt1qeVT+8eKTX!)QL*@lYqI}>PyhvT4u%0n zCEIqx2Z$&&qKq)gfx)pIsbRz3t+J>dw!a?QYX<{!m}W)Ljwbg~fkd=igvzs>t)(wsA-~28SMWlNU*6yqZT-z%T z{nwfKXNi46XLG)c{;F~$$dF1PxTC-ERdDQA&S~S6!`gLkg<~?u!LoVg z2^?1cPw)=)*j9qeEdU2iH$VrAR`~IK_OpH?)G*-qz6>~V5ZQ1%>VZ2*7W;URI#q`( z)y`71a{mfWTee)%Mr%r%d&KdP-zLKt3(0DX|K(q>sZiN-BDT1{6m@DaJL2OMf7f9u zFOm0J@y(TZ;hZuinrJpSp%A_L+J5QZ%N&>jU5mZG72CONN$owX3&W24Y<632aWlfz zTR)K{-xRogxyz@fEi9J0%%pgdMh1DP^4Y1_j{SAx0$)EW^)e*NCYpttV0OW!jgd`3 zYobrm-M7I?sI=1oFyjsf&QjqsU-29NU%EBtlw>0IH5ta|PHWab(lq=G(() zom6O%3+emHA#k%C**L>A=F|Kw<;EffKL%~OQ-n-=Up{YY~p6Re{^vhu4(^K5s zAQA1Osccciq0g?&VwO|Q&1=)$`L0|3E%?<=Z$T0CpT_`y;i`K+tD2=)ES2h?;XMo5 z(v)JUB|zo>A*HOa(Pe9r;Ra>tS7nV6p>A^J3UOuDf~8SMvkq z*dE@fS}_#p!@D~k8^cqa%2t~{l;90CK6~Yv&URRlXqvboj8mz%D@6*N>(vO`la21` zQT+4qc>{~sr>K&{#(YOjJd?#Z8pQ3jlvLER+Z48DKBg8Fpu?u>!B-4lu3tWK@M~;2 z@J=tSZA=6om`#I6&>zx|Ie8b6P)VbIczjM#>MVKX_`&~m>47Pery zbZXUg@;sHG6ntXuUyls8x3TQUc-TeSToknsoG&ik-=8F2#>=r*K4a`l}JlcNWNWns(~y}PD~!o)8Cer6x>C2k2Uv?{vMvn>H6z;N-x>)q>*wMmuZQSxH_$Gvi4a|Ac|9a6+=&Fhe2*_#+ zE=VDncD3LNsO6#L)T9NL^&dyY&cZh>`r{AWtnPCG{1x45`}K<5XagtZ6$YN8mT27t zj?`@Pn+wth*`G5SMI;LQGZyg}=hqS;zA=)<1aAhw7!zx_9FktMU#ZcG&Zr z5)qvF7&8}FQYl?4U;)h<*x`oxUedN2Z02zDWQ$2vT!Fu5U3KYCU+a`)h}WDZX7buD zAC_v;`~acEv_ezE)R}vDgzXPa%=L3Eb@OqbmL$}b()!Nf7hpt+oTyGaN~Q3nW3OuxTGdotCIN-) zo6zl7oqn}rlW#u@PlW`|WI#^h5#Rndmop?g0*g+~_OV2p2-sKcS?|~SQSxhVdzYv? z$+`7Mz)i6&ZmNAEU#uMWd#AHzd`4DS`fdSNMa~u$V=4=V4~2nYE}lM@ze_2k7Qcy` zq}fqsd#P}bo#)N+^+<>}hDa*793k$wc}Vb;sam~uG%MvnuDX4KUi^(9+d+ZmN#RWk zdU}U0y_tp_I{-ZMxqDoa#@}*g79L*~pPvGoET$sz{MMyNzSnm|)Q^k-*IFi%LY}D# zpL)DvmXN&r|2Rs$9kTJM=-*@$W+7;}lO?KcB=LJF;<0W%Iq>&ZAdD4!b51| z4+>mJJw%zD^u@k}5aS`2czTljDLBhCR&EjIEeolut>tPIt9vdg2n?*Fn|_s9kSxJz!E;!(q+xVx1>{CVjL(weg}2b5YRtT)_?YsdO_er;A_{ z4{|G>aOquSn=^&c^p>9~IKAP+laK!OLWGF?jSG5b z$WG~l-iP_3q3IyLj?3%sT)Vq{52SPa_W2L}bLAUMHRmY>K<3`J_U19?7Ye@Xf95)A zcAezzkg*TW7lX~CZe*|zqSJf(-hEvfMk6aud8PmID2lDXmModeeYw~hQev_FHl(mB zYy68ox&3-}2WB{%UC9HGuwUAp_}WP8Tg5D6nAXy@zQ0oN z0%d7^EVqktB?RFh9=XSu|8o1*{|kE|k?zQfZniy4vf5oPpu7cA;hC?A?DY9>=svx6 z*q|n>y(p6>5Hk6GmHwwoWlYh6TMd!|D{Qy!>TQ5Y8a2+5y_5a}s5Xsyt?`>I1uA(4 zYSSj8t}{T{uw@zawZedKEOc2}?%u7i*8ErIrqj$PKa*nJf!IG*UQNRkiF`pd{V7PT z>LH#$-4>BohL37eP7jVJ+?KjdVc z1L+l7p@qh}i)yX>vlUo-)y#P;{{9DfvPOubN$sCYTmKf%I|rKBvxFYz)K#*IlD8FLi<=)@zN+jrE7h|1IR2Km&yF2U(8}TWDj?qMG&!+{ zHnhuCmYo)Jb}c!tTNe|T>kOeUv8O_ZoGnZWkXM}G5;f=Y32^IPn&yPQGoS({_;=dU z0Kcg=#_E;P_iOyXue4cw^9ol!&R5rQYW)UZ@lWOiS4kgj?mB*FaW*n-pV`~pl)h3A z04(H0^V8lK*I>E6N=I}#16VFm&g?Vsf`SEi8aT4;<(|}i(5a3Zy!()o>xFXcrevws z9pomqi`PW?nTyY2>iHJ4WZhoQJ{$9%Vv*Of8jf-rFIdYFZuMnn26c#>kO|n=vV1#rP@CPm6*9wkQw7iw z`0i}54?^ajpSfWnqM;Q(3}K+}Xk^676e{f55_ef<`*$0IV)`#JVcZ*G z-62%um)kXZ$mD$1EKNe2vJVq{9ml;Z?!MbO`Kvv|IA0BYBo+RctnE#1nj{-MQ1!n4 zLQf%C%YVJEjdW2aD4*TKS#-8rS)7U?HcANE|Csa-k5@+wmwG|u)k7|6lV_YsG9=r0 zB@pjUg@H3DU_8BUN5j$X<4P7K@5=SRW1q_Q-O*Qz47?AcqVw$2m$)D552hlI01&E@ zgz$z`(Fu1#RQqTR2k>U|-MIdU3y}C$r{-1F%&F)2Hn7^+#-#pxr@VrKVe?lviBDI$ z8n+2x|D}`C`1q!|kI@n6cpy9VAHjcuM7SOJZdf8<{xHzOdGRWY z`kz*If;Qy4=J+e-f?3pMVRo8i4JWAU8k^wYoIXBJjxcC8!jsc1szWi7Wj{5Y% zjk&0AC5$(E7DBaPM#gPr*IkJ07I5*!dWAq~fBI-A?6UP&^OYUxY;rkJ;qER%j}Aoq zIc#8|Hzn+)p7BQQG@wtR@nS9o%8sqDnMz$=AHV*i|CEx$k`A_dR3sCizRgyodZ*Gn z=3_6T%639`rsmlfdD@Km@*!gN^vCzWEO45L-tg57!MekNm(caho4)bh4gltMhMHr_ z5TGlCq)H6~;*9E6f=Z0g2g?l(z7z1dOvgd9jGh|k>*AisEU=RUszm=^Jy<*CI^FP3 zpenS8W?4PQ+A6}lk6y>x_)EG$xG6supV_r`->zeM(C@z}oOFcnEoK z!Ij{8&hL7jAQov==7=-7#=-Q0NCgO%g_nj9DHaczV$l_=Odu?~|D%3dUq@)0@s1<^ zCAI#^VUPxtWHI4Pe~) z=1Ys!EpGk}TcMpFEw15V4B{Vl!rvqRd@88KR<`IxALY?m>e8;L?jiQ@FzLRkg4sDq z7nF#l0cKP3R~vtHOaIrLa(;#Th>or^7R-6$wodrDC8oic=?FrnCoq`A_*r{Wze~xo z?Dth8nj)l+6BDR?sgw zU{uTG+Kz=;s6!5gftPSx$I3P^)I59 z`5G4YJH7rubpK>X1|UBK&}WT0ED*Y8ae)so>(&^^9={H^+^IMpa$LWF5j_M4r}K0^ z0?|0TrL|C@o#8Hb%{QHn{Ub*yZNYNa^TZL$@N||l0Wd9M*YY}J+sJz=J8)Y3BHbNO z2>ge1)dn?h#TMzkV)S$~ef8)5g|%Q4xhf0pX*BEyQ85qZA*KSRqZB<3%XR zM;|ojsNGR@EsVOSC#DucgHBZU*N$(R4e@O{#=U&uPzbOhT(gh+njX z^h4?A>2wc5bu^5=$wu#AKSvtf-Rz!aq3%UK#NhFV^o;sNrPFx1Urf1xsse~LZ4KX# zLZ`}4GBc%Oad`jm_aE!&yK4!rLu9gpscg?rxKHey0C_o5jU-*R#`qU=B&!FQ!{;p~ z+NV~j&3^Lj*+r8CYCe9a9-HFNf7RXog&xZo1gUWEFWvE7_ZS<#El;PNR(m7O+47r5pkAK;J3mjdHV}zdz=-u#i=6RFMDH z*w6M7>Fnd~6|AF!xa}xzOfs<224IwBZ^q|v^!*7jXSec(UvJ>!cK6y^V=LOHW8L~i zU8?Ejld`(~ecQD)+vS1Nn&M-NRjMfW}toXCmy64bxryl z2CC@6XtfhRfb}^LT?5#lwQ(MFOV=@vCIVFJReY>%l z8$KUUet9I1Y?BCUN^PO-eUroXLEqOH;^xCtZ8-EGjbwvZc!>hbhsZ7mMz;Mey?DiA zg+8MWt^Gd-o9*}#T zSG(dOUjURMrJ_m{YgjYW$Xt1&ne&6T(Y&C0+tlNnSI_UR@w6eig5!hzT-x3wv*`>S z)J@6WB$_94CWkM>atT1VN1y%@fei1SUnJmCG@i&YzbXqQPvP!+d@)oU?N3yBCiutFQ9crY?VCaK0xm*~~sYuv%5G=fRiWe>3 zzO~1u@2ZB)pb%J~kcTStkLUsFovsxz%am$e&ynqwzK7!>^HNnG!H!kuUA}}9q7YbC z_k4|?9^FdnS%A?YO5p0)*xA>=S}FCRzeglpHEF<1y@BcF;;QbP9-tS^4~+fV_IGdU z8=FO|AQ0ikX`-RNX@!S0hJh-}4!PVIe-Rk7*{J2+%Z1OAq54DWtl8iht3k-lT^`s_ z`x9iF+!1cblPwpKQ;^16Y^eE;t{QQSGGaW$c`Pv<@za^Xn~F}7-$^qSg?4t!OQ1e9 zB9lV8hNifpqkc-}Pyis1!RG0SkOP92VbqHMl~RGrny@T`61_URWb=TC7 zm)|m*9n9!7^X1fSs$(U(9}AQ=qgR1GM1df1IRF=`4{I~ptrj?uYclqra#36*;U8uTzqS}j0NgR4Nc=%2*cF;%-3#WfJcYD z4t8`QTwgjPpoQqaf?{{`vG{9QlA3G>M6hvjuMe9`#ILGqVt`~A7i6Up>6RBAhh_N1 zIkYfxdH{12-|e6=H`S19D_qgf;?%ZiNLe%?^;$H%elTGjxVjYEJol*`b$Vlybhe~o znxmT~254A;+9ka&iq-b)1}w*6g9fL3c!rsA`}%&@^N`s$weXSXPtcxE45!zCw@q12Ypb9wrQS~G5go};huuP}mf)D} zxup6{N83BYH>}X$v~gYn12M0zx}U3eRR)HzAtea6{2ECKj44tG?hf(RkT}W%eUu8< zGCdmZIsbd2>ZuDpFYGE&`920q=BPVfGq*0@ni5Jf%f8*Z6+|J&gUlhG7^5MJw zMA0}Svwgv$44%QupEzDB$X0>Ut7A887HCW$nOLj5(3xA*u)GuQnvZ)|=2)9AmH;OW z5OVO)tV1OGI~En;+pEwZ9>-1Q%excnV6py=x&C#wG*0kK2qo>EDZzm>@3ms=tVZo^n=N3yhx^G*-lRR zFVU^aQkWWTWqpGs6rdx*bMRD4P;gSvHxt^zI++t|4dXm$8M|0oslp&z7VtpT<;&G% z{C!Py@6cS-)a1KXY5fNG-?SmXVxX%PY{kS1Xq~CN>$m;`sg(_!!pqunSZenTULSg_ zhQX&lwNoI>K$^VfT&0}_#goOfuN$V!6(5|+O;NaZj3Ka zmxpCRxZp$w_p40n`Kf4c!m?OhZ1Z}GSQhHUv6H#;)-udPMa z_~!W3Szg*gVT0tlS=}!q0XOiPa;OY6#IbR4v{yC+>e6ZJ9xpiRhUv#+sOL2Z)>T=n z98T~m=c?K1E~}mW(~A>kix4|VydHLp7f6=;%vNTlOP@aqcTJrw<+2xb9xBbh;Xw@+ zD1N<1=pas?jsfwtj#*m*P7kBBR!601GRoX$-ht!!?0cBQOtXZ!Mk700mlPdS#K!&{ z<)J_;OJDmDzG~Md_1K2>%D33d0KKXHdF>nFPdUaOkah<07b|L#F)9)uiOWp z*T>uXmWQDArYZnyP1M=m4w?`M?>|KmoZ5%}vyIyUZp05UpLWPyhfFX2=A1>G1`j0? zN`leJJ?o!ImXn{O9}Bf;o$_klgOvczBwTvKX6o|}D)8c07ne--y3O>=NwGPW%)N<3 z9=mykniG1~@6+jQnL%yj7iw?x&1%ie_Nxl%E|yMt1BLlYp_DW@)i;C`4O)UwD@x+! zDS5-*QRlm>v(|^PyzHD%HMHh0Ak;R$v7z<)a&nt?SMu8h!}qWLf1ST>Kxoau_zRlZ z>Hhb(<#u0$$I27x2MqZ1{RdXqx`#+-wGUrn*&t;S(c|w3uTL-*?JW1v5aw0h!KnjR zXuhSDxL;q5blkWD!+4$a8nNxUU8Lz7jKw$e&-mB}Y>{__w$2c?vxR3X+2sW7jOK4o z0c=n&Rm}zYWzNBW4w0}u!VetXMGW0VR&egr7*eLaTfR!GZaUgQ81RbF;~6uatKP`1Vm+f0T6<0-yTv;hvpZ3NqE{KK&G#m3hV8y;S zA~zR0%jVZSxSnt+sIIwMeK9aR{g;5q$uml+@vffG^H%UG%xtMQ*FkXHnssX--oy*@ z+LEGC2~1tHfKji)AlOAJspCCrSrh+YgX%x?I(>B~6dV!3RDh`8V0R-oohMWz5rEZw z$3RW8$~%$XGoE#N=LLm{8cPf;lm32DG4q-YX{~tv{y6iM+}D^n)bZuwO$PL2?`3f~ z{>B>K()Z@Y?e*F-vm3sqkS~Wima7=D?NbuC_=uZFGlp0p*3*tZ&wmEScfH3|@`)18 z!v?luz>$6dj=^;ncp<1GqMKDizOWC2WzbrUEsrEq`1bbSphA(9UU883T9-1LxOFN_ zo%(9b$9u1jtu+Eb$Hm^=wW=^nT^#YH<2P%XTdwE4XlULIba3Zs-KI~Qf!1$=m05&l zh5=f|9DI}($x5II#B-Cf!higzP~fka(_qwYag+qRd6GoDz1Qd+}DSq!9&jDDBj zY)9qnv-TnJ@yX^u$z*)j94MF6nce& zMWU?1UyKl)XiY){wH)?7FUCRYEXPXHdz%7hRYUggYOGU#$+MvxqH5NR>_%~=Cykql?4~V zPySC{4mD^h45UDf$7YZ9vV5BSoH0pRDBe6qct3?lbeW6N!yuQ>%+Sc!3MUM@FP2YJ zmL!pH0}eBlP4gu18AE+1#Ra^aO0*`HrRvfC(NOjSh-H)E#-1+M1A$>ot)GDrE+^*} zauwF+>x_06@$D}M@0Qu2|0+4Mo#bM*mR;sWpmX5`FjRdzWKqY714)906DwDHLwCnU zOG+-i$l!GASEKuDQ>^2IWTMq89)ru6$Io)=ml-VWtW?+c!Kg_TX(6%|xB$a?NIxnV zVKM7-8$EPXC|5UZ*I-w0E{ngo9h{UO+dwb6@CC`~^$G^3%RZaDaGhbT*hUA$~ z;{gq=VX@ud(KrxKQf>TFLlkU`$HScEbG=ME^4v-1;RrByeO0Bgk1I>iWBGhPJcmTH zH-rjd@uRC4WV482dvjotcIe3fRqP_mY%TaCShQ|yCal72ND-J-u-TTv;!pW++|rY`^x=SXACqiv~p#R$TTXwM@%VDQ3mP%bYVK031&sc*JZbn3BZ)!7w&Y{ykQu^Qm zy^+;R_^C{*Ieq-{c5ppp;UB!Ot^50A|Aq{#t9%__CPA=EExYz621p#KKj>O0?K}1% zANlIq!Ml5zP-TzSLu8~^Xte10$U4w^CT@&~;6n{e0e>rRSMYrU2EKj z;jD~ww!D;u{j+(v>s>yQ?YBEwZ0itF`;Bv7L#o4I#S}ljk=|_;on{vORWH;pk650s zu9iNI!gy+$tK_rKeL4p+Gu6W58=-xt*l5Wr)Gv9-4O5PgX>>s*5?uso=q6?F4rOGU zmGTSlvbBVB$a!o!=&#`lQ#V(nsY`a6CdZjB;q~j=zCHoxsSE8>82^G<;_e1ni2fT) zPzY(rXfU;R0-N6G*S7^?_8N^$k5}`yS zS4S*&O@OZ`ebOv^z+#8jM#OIUutmodfI#Dva@DGsjt;nBMij2WxtwIT`^^zA>vkxB zDQc&rj3b&AGfs`!kjvm`$~BZr^h;tZY?JW|28g$RCG*y~>Sx9e35GMz#3*F}l}O1t zh?@TL_*&)U&lzf*%Wp_^h3^lQTGH)x$5d;`e~}RB9`x1~+xV+t47uj%(NcXgXrdQ< zJG3Ytu|v zgZ-qP1!b$UpF&fl(FiM_2iZj&t;S0JXK5{0g{>DhR`arBB7kx(1)n|brC3kA^av-SdCR2%;CZ-kvfeZ`gTG+fARkeT+L%7M zs(Y6)LJ+OFgV@H!M49abQm0sz$;W~O|1C{ReuTF-O1RDBuG;gwqp+$NDF!eOlNVV> zP(~Q_NvrQT&Wx@uq88mpAW;ZW@Yl!sItf~w54k?U!gB!hwuZ`oJ6Gd;tECSHWY9=f z(->F{MC=%ZpP5%a(qgU*g7BhG<8`a7`omg2fJn1mlGOf|;Bz>C%Rn0=8G<+SZ0Zew zz8!S^H+3f*ywJ+oy65nj=r#?5pG`ZpX(2tqBI`icUX!s3~@Y?>Ot+%Xn>I)2Ap(XeIhCTa~o$Bm^C{|Xu}6ygZ)o=hj5 zB`KH;z^_?Rqu+Blw!XigrM)w7(;`{7@W#x&X+^1GLxkuiM41_Q7+LmosO03t=)nTc+9Qj%|AF8gC$-fp`y&l_z3l7ZVc z-l;g!saFvaRKu8%6AH0Tk*5+LzLSdjfvy&G4bsIF!RRMGL}3RX(TVs|j(5^pNJ9HwI{!7}Q1^F2 zUF^crOm>-k{E#~<;$MBL9)s<=Kz0d|B|L`*UCI!BQ_d zEcFBq%X4q{>Z3Q+pH@eJ{d*i79nSM|VpdJ*HH8!Te=?f82ugja_Qytnk_C(TXxz?er@N zsUdx=K#A@(Ao55zy952toEM=zw_H1Wjb5Ty_$Aar_`E4ls3`^r)&?fMd7!`qxx|^5 zr9eTeYxg?FcDoWum)>85@kZ)t#73aPQ`X= zrD&!;>@MV=YOj4DRwzRe$HH__}S_pG%e+usR$ds<&yB7T75@7j$+%=5>nt z4*rQX3{h<`RJaaO61alb`x<|9c6i7d03|%8fasd^jmI^4H$HswboWe*Y;I|3Jor;{ zzjZDFhu->fj^`G>eU77`|KRsTZ&XJqc zBONI#I{z*W8AaG?FK%OM{j|LFuK>qAPPEk)0JO*2b6~wU(Vki6Og+m0eXB#u~rAN*AznY!!XHkYK#I2c=JcRRD?oVdZK(oD2p28&dJ|gk)z}# zI}QNed1el2ht@7SGQxO1Alh5apHz7AvLLxH{t+DAX(>-S<5U4E12J&X$5o45V-27` zQpkkZZJg~ytzl@$S8#ls(b#i<1g^(4TIjHKR)plnjG0JdT?&$(dZMxr%fR1P&yxKr z7>iQqj*7!7EZR=GZ;UTiH~-+QE(Qnfqw`SCTK9HunOE+Ja$Y|qNLJsNKX`kOc#rZq zXFRPJoB`vVVz^&zWq%Q1b8CUq;m0hCWWAdIN6D892(+2cWPuEN%NPv}Wg(4Qa%?&J z1EbA$QW*^sX|=xaPycpxVpMnry!Rr)5F$-z4~MIWDp}0-Zq6q6&?+a!HsGwGCv@!g zWQU|KT!1G7HG38%p#a;~iy6UbX0#m*0O$bW5Gf`yY^XMBf#Q%nbZI}ei@{YoC}4{D z=Ln38#_wl*E7!#4j*7qDJJoSOc^O)%dw2GOZErU|z0}M#tPnW5V{d6_zzuRDr=Fr` zZDP5=D*M>oqmBZMf=B6sT_Rf`{CKJ|YW zRH%3Ogd_%Og1RHSj%`0K`-*Kl-Xp;IxZicaA(!UY1iR&AP+RFuQZId%=>QZ5O_iyD zxcFk9{>#lr>TQe5ilYmUhSHmD$q%bXC;2z2S3zdo|E~oIjo^6ARuy`}A2ONXe90w9 z;2XX8P=K}eXsQTjpg2a$~|Tsy68=}{<=?o#=U_|=y=rD|Fw74j}!)-l1Z2HAM$@3 z_=M%>$TYgpAqk6JuP3X6a$z$ zCF3rWe!$W`y@-aNj!4;5AL~VY2%;Xm{jaf)$nJWrwMaj)`$!+U( z2OV>)?STE>cvqTu-8SuuV`@suVe{6QGa(bX+lh)CH{TB(Cti15+v5a9FGIcsVk}Pa zs3_pO;q~J};a4xjGl`<2=5yNFx}KoPN9+SNdH~{=6&Jd*c(x7bTm>9U+Dv{8wcIv; zXBdx=*ry&6#<55z>4qJ7KquxDd0@F!ej2~+yE10j^Hrz}Z)=1sfzLH3D^wWW2JIVDVNq50inT%#?)2P zm1|Uhl;F)MLOrc3wZJ9T)&BrULASoR*9T;;32-(UczZs7ClkGZFV z1}Ce#ewF`ePt3JAvFb7g26iO#ca175)gGa&L~Ck7fPOi^`WBO1qp7T3qX_?KJRH~Q zX>L!TY=(fo<3(~UCY{qIZll1SBPk8(^co7PrU?~LZ5Ct~1h~TjJCc+tI(8(ve)@8p zaRaNWz+rkQRJO)|J0?^+A|0!&AYOVj#BCM{nAIZ4A1^>7q=!QM87i|hJx#&ZbVG<$ zjz~9$xMKp>5LkMgQ+qTZJx%4}rkg{oX>lHHb2tGuQxR!hDN-{n0ZwGlJFS?!Ujwn; zxWH~u!z4piQ=h>f*Of{(R?9jg3aENx0(U$H!Q&zUx^{!a88hf=jMp1m9OtJM@WuuC z=Gd0FRe{}1qk6wYY-0?GBH5{^tY5D>DZ4dR)OKnTTa)xP7L~nmLy;0XU7Gs*wai#F z1-L;CJ(Rt%kDh?r{CELR6N$ZXS0$uj(b>$<#<}O2Ls(Un9}EiEx+#?p>@*nkmX&(> zwsHY4rGRScn5@ zM5stSe!eZaAR933>l~N_PHXv(6%AUg2w_DWb_GwyS+diuh;hJ()xSXUnM&(TD)BVU zfRzq8>WUW?%syAf=X2R{o=)LazdrueOD?jJXV`H*EE6<8&LW+XFI#(kTBR(I8Yi+0 zCURxVC_Cda#s(F;BHUf^^~uWzW@|SDyx4U?*u{lmTDd*1yPrqb{5ciixBH4L{G$@4 zv=K41{kgG$u_xAY?16Q(?s$hfmfX_I|M}>B$xRejz3F!T>u++5>|V>La2Yl>Pzlp$ zDCAkYvR}IV&-wVK8!)@tn5R9-?#+Td)>@)7=7Ls6xSN>P^A$Ea2D7b*zgQl!>xfQp zQ0H7L;&XjPzPQT%)eWoLX8bNwK~d*y>!bQydv!2dub1z* zH#$06zoG6GTy-#8uUGT|td_Y`Q;gN?H@9?u{5jt*_FROwKbc4Ok7MS3mOxo)w-I*D zM|gt-85=YZ?jXXe(B4xf$XrIT@7j1BJLBQ@Ntv@vfW}&XGk2lg5hjU z+Oxuz9Q1XHy>BN>D=<4bf3^l<&D@U=?$0NU4>6oalib>{%SPHAr_HD>c#nxG*2OiY?8$kueeWqIDp`A}#6PMaKn=)dt_rZ1NStj3xd%%1g-ctf+z`!4j)w-727L%c@yIHLygSrFueOk4o$j31iT$b>Lu78rSI@kr1lvQO3cVsZ^SF zlcZ}jB&!Gbk&ZhFFVES&*F{&{J(E-56q5Bz{FFJsPq>82GI^ zIo+gGQ5MaNfi)J9Yc&&y+e16{iTHSjfF{)*uTf>kW)CS9sE5EQ$6&J@=eEX5T0gd5 zuD$P9^;5uXZ)*{!Y|z_UR2IW6ab|3bq)!x;VzzA3FJiFTqQGijQxR`mDR67cbH-vd zY9-FLt%wPG;&Jub(juI3gRYda^R4B{K3lG=osu|}I19FFkgJ&Z#9+57ur;N;?TnSS zX+kU_>}qT;Tn&}oa8)LD#<`R^#ol<$q6G{sUdDAh?xv*a_y(U4a zLD?YNWvMK^j|?a!?r4~(NNZqrsV$j#lWLb?Ma*`aj6y2VM}(of~9{O@=Qu+ z_XY#omOS}I!4(&WtoTsK*~N$}J{w?I5re)?8EA{MSu4P_@9IpuG~(Q1M3BImKV#(UJl@kzaMF!$FJ#p^_bZ%(dIgte2-Zwe%U0u^q&c3T1;joV zW8((oa$7;znwqwzn$=NYwxNu|gQHB%m{m5m(mtP#?$06ZWoktlr;UkuvFo{R2zViC ziL{v&Ssc@S-cy)x725pC%hmOiud_(n9K8Jlh{$5Axt=#3zl4pCKhB(Qd;@LwS~TGA zzN7Ku|G$R=htEU<0&_h-*(GR}DmS(qS&RTx-A9Wo#^U3X-qB4kd@>Gp-(@gYpwlW4 zmULF6L!=e4*)e#m?fA_33aoAlyp4oJR<<=V9g^iC_QZr1czt+yQpk?Ofr$8`FD; zAaga+UV^ljAl!YduqD0u0zKUw$lSe1S6LjN+U6gfzM~>@4bnafGj}gR_Koqhcb)W| zJ%PEtUuD(0PsGz~fZXYpSfP;rI33-$KCkaW+UF8v--5Kyqoe!pPI~Wrg!@>$zHcME z0faj>!?tqoMmp}@ND-Lz)@u>&Aj_Ap#J&D90<#T!(IU2F-;Hor(&2vkS=w-+dJ=GZh;p+ zK&fN_az8X#{ZWp#AovM2|AZd-DSE$(_7yZEdu* z&7`fZjms`u%i!R#c$#CUOm{jc`wNdxCxS#_m}@oZp5Bo}xn)KI7=dm&U>d5Uy#YEy zi9Igyn$O%}*6Su-B*+X0*rQVQ zxwpXjCKH;JRqg6StH_rNP({JOCKF}_s!vu!sZN_DZc4y(WmDTZ93KYDsWq~_a;FbmX)&iU`$+QHxvLhLGHcH$vF?AT{!vc7f7;Z}w%csmVu;EoGAV@u@jN(XL50Z}`p9$u_!^-_|2OM&i@4)QGp)|XA}l!Wr6 zbD0KiRnR@wfm;=GeE7X|xl!O|F59$Bm4W=(xs0%ifm!*H}Ln0`5& zl?@1hZ*4Vs`(*)FBN?_OM;?Lp%Op!}$sSkGh{6pTu(eT8T`#!mBLS~N;-6;%>bICV z5s+(DZFQRjH|&tyyWZsOs{-0SB6-InlCA$_vg{w>ul~d2EL$?8Q&P4ice*AcTi`X> zfJ)rv_~%>ObwK?zNyY8Cv?3Y(kR%1nuq6jPK_O>yhFxHuEs21Kx;r>O6VPr;Mu0(A zFw2(c@$ysgI?AY@-7!~i)D18Z zKG`BOfR1l|oq{XyZOImMJ*$E&9k%2it;$^CPN?PI{CT?HUQLcURp7?bACcG8(uRf0 zh_q>tHlxDjgm9_E>l}}N&s#Qc!gO!tO^IR@-= z1%p2kWZoHY^a{yW{vUg99w*0DpL>71d!|Ms9gU=tM=qB~W6Nq=vb;&|V|l^Gw(MX7 zo`w*%5J(`<>5d@~V&~1meea;j@{$F(xi@c^W|RQg2{?e-0s}@i25(R$$&1F8)Y@8d zP05m4(&)@qGt+(lIMvlXl57k%-qgR(r$5zo`qZgYr%s)&I!`^%lebthpvTew82B;= z9l;Zh;Qz}cIXk7;#v9nlqa5Y0n8jby#*bOVTX>dl(g@6IP`(D(g9c(N;d;$q_IUFe zd=15k<96e?tDmRl%@}W+V{bE>(Ht{s_(n5c|Iq|yoAH{CMnG1xFPb+n&lP_5Fv6XU zaN1ut$7JP)A^)?_xsq)N=cRuWv8!uwG)Z#woBI&Yx&H+e2d+RkWvu+plYZ9#;nN6r z@)YN7C4O!t!r4VKvjyP{1ETIb8|6C_*o=|_;i!gvpG|S#9V9dVjc}epr52;)Vtn2} zGV{+7C=0OF5%gw~Y;^>J-KPX)Yf&8d5CF-{mm2nU9!j2v$b1p2|DKaT+4_0=HcBoH z>-`q|+*?Ry{w@M)>&MiCk{4)pt+V}So)6({!|MMQ!rd07B{P3{iu17?Kl?V4Cjhhc z{l0@OxnINTzl;6(|EBoiH=*Q3c-!|Q@BT5ueFAZc$uZ$PPBQaH2Q?jL07+=sANJw`H< zX(%HV*2jH8{dm($IFXqDs)f5%;5;cJKsNIi$r+&Rz@0@hf1AYF)-Z`&6r_?3VCzjj z`5#!U`qP#5w2&#A`IltmCo8)YvP*-$&VGTk6^V3_>+kt?3ukT;IjKlZDO?0O<+EzO9%}~X6v<;T&{l*p^mkY|2%M@Q zYd}`{60G|0oCykU>$${7kRSnz6NsJeNvNxT$@j3B+0;>qF&A|(m!G$D~e2zWOK)s z==c5!OEYZ~ic~^r(6*{QV^dY#rc^APiXbzdoUwG{_5TAIewT4Yw#6qEdd@l_Xq>9l z^X8{5h{38#2;5eay4|Z55`DfUA%I&|3{a%M+Rz4ZA}?B~zcZGtYJm2Sm!HMc`*-r| zN49f*OdpRMuLHWWs>rm4fNfg{hE8ihJv-@ZkTxzD7%kEtf~|6TCSdE#PDbf9KUq1Y z7#JvKLOM^HiM+wuFbF|V)78k7B|oXO33s7S$}UMYDQafz2&~|K}q` z=6_VN%Mt8y1Z#3W8~ZIZ#j=aTuM{#}#0N23lp?-_$7cjovvUv+X%_J%Rg7;jt=Z%-zGN5tXt(ASMvG>G0 zr|t9f65545&o~tB#gcE_XdxgV~toqx!cS^>3pZ5KAS-1}+FQL@;NtC<<;XZ-kJ&WNTpq#ErPM^#?HazV!Y~{a%S@;fS z;X43q4dsUe`%F4I1j`Q`V&CuFz&(%6=aJq$4Q-I3IPgWv=^ljZVt7L@`!(l1Yt)(% z0QV_@yg<=&O_{>OChj(Y6EbBt|1aHt8vSGe)@6#gy9C}*?Ir6SGl-$tvfi;!((zqI z-2H<5BjMz>tr$obaXmp{n~6O;z#Gx>#kL4=4+y*wgY1Pq`KPQI(#6^HedIz#@8jLL zO;GlEW5tS#n3$OOxug`E(To=}aaEJx?Ce~`x#uondU_hu)Dx2LZ=L3biDNuets|9k zQsE^GvSU8!psc~zRxKmkGhRkcs=5qpn;C&za!P6NZd{NaF0)Fk#6{pD7#J@iM-n$&S2Ftx<+l&CMKv@~*|qUBp_-m`)&@)}eO@#8sEe)QsEjkVAvc@&<*`DdT+_2LkB01yQwy|)V zo~g3#v(t)LOs5qL?IT-gGwc4d34_#>io9os;s!kvWp2v(?0*-utq$1#E?ATEIqDhw z^*<&#`)jaLDyoa?P{1xnu)q%3?FjO7EH1je%!1!jJbpl6*a3ST!SYhTXqRS^Z7P^- z*kJKkC_CJ?I^fDl#pq%UOq4=URdvBbn@!4B!?}N1W?op<6<-TDd==c6w^(2YY-$l) z`)5A;;|BBXfV+CTG3|hbkHXXaCO_R|GS3c}ZwDty8N*C~HV!=@a>Nykc?RB# zkU4(2{5?-K_MRxidAj-~`Z9~Zx&f4}$r8^3YhyoZxvYb+F*HaU0=I!}*ZpN%t6@*9 zv12RY_nM5c{v

    !SD`ac+cYJZo}{no%F2qa>OrF#`qJ18@R#G5d(f`^>fVdC<&J@ zZr*~}a0mRMmJ_Z5JIwX?b6u`U{5IwLZ(vSf>vSv6*#~-fa_twR=MQ=31~z{x&&2j? zxcG|u=~(u4b_^e)RY_v#_oiq#152eMc>25CR`@L0OMK?PZy`Uh-xEH2%>^p#PJe(e zhpI%e7(8AuInxgK_&|}}KNehYnPS;&pG{mtHUC4d$@*NA^V#PLhCPE8`4kJ~|6~~t z;_+?{aVPVsaEX(rWWO~$%JGK2F$x?7hQp5nJV0UfgK%S~#dWuI>G`L{Ge^^}_SHD& z+>|nI#w#}-G<{}Y-_evZZpLdm8d-|XH^*LB2&bK7rVHV;vvZ(`l8U97B*GD=!Ld(Z z^$#Q5;3X+<#fpo7pP!+4y*)vh{tQl-s04x6!g!>GBb}qs>9=6Fo&dtr6As@VD^Bn*r zGyjEfe)e_M$dsLVT<73tZw$SVK)Ab3V%}Q$@8R<%gu4^rY{ts(KZz}?>$x2zlP_$t zB>NWp+*`5wH(=$z{k(at{5Q3St@HGA^qHry_!`357MA_1+T+R56Jk$Wb1C-zw*EuC z{vJ9y=F!!)m=!JaSl{qwn{b}M>i>7muyvkjXuCgrj$`*>*^?hmJEF8p=cS_;3Xn<6F9R3&SVnVrf?>O z_Pb3ea$`Q3Hl0o!XoJm%x8SskP}W#6&{3rSfJLrVGZb@yPk*~bE}>bQ&bZLhywe&S z&bL~m+7!;XAUEx66~qu6=$~uhjMtf+1BZ&_#mOw$nq+Y_j?eO8+#=iN16G|O+sKq1 zv&gmitU9)m%?q~Z0(os8001BWNklJaVibtItr(%%WwTdEDRdjVN<^Ta_?t6+=CpKQ#wg9VQx*s^LTDllCqgPfG zsd#uE5}|}}OUNKj%xwD_12{FUNQIuXwQc0IiX@AjMBTHtmM;|owfVNNKi8Pz;mZe% z`#3Fv)TCmMBba}csvUy9&OWC2^N(#|w<9uS zi4R&l4wSEkKl*TyA7F7y*5|u<{bGc01bYzd{U^bP2a4R3^O*vQj%Lg5Old&30-Prm z3%;c23W3=*IejgBuis*0-eOJGXSX9bFQu6GQN^!*w8+MOiy!ALeq9zLvSN(7lyXfk zXdK-YFU|U#Ar+H=%=)Z%l5EXeYz^eQc*#JvODt@ z%d$Ri7$~x>U$^tN5WG3+3KD2v+9NOGnd_yHFn%%dd@`I@U3JZjJg;jB&Kk+Jjk;fK zyI%Tl&FQrEu=CXYZs!z(uT zGC26;OHx*iAq#N5pN-OgX!Xxv$`<-9&bs?f2%GaCSB4|6BiOmFm(DQX-L-U<>1QS2 z@nnW+XIWI%R2d$5>IP;hNllw7t{;?`3Yog+$q}}^^~2l^oX@xU6ZvnzBv${I@N*iV z{Y0oZ_oX0Uf%Thi|oC?qIaeR3> zGePSp8!_y$1Ptl-e`*GTgzpqI9A8X3VHlrEM_@zgaG24vS zOmuZEj$}Q47E7@iCx_u_Hiic*05!go{28I`e`+edhwyZveZc1z4iZOI7V%;iv z4#k1rBCzKnoIRN9H)9qyouWQRFbht&Y{T%%;j#V-N-jmXyTbKbDfRtESkIsFrfdw# z>8r5v-^TFD7~WxoyB)Le&~sc5hw!tvoy4Zq`%P2o`*675ZTPu&pyY+&`qLQR!SFnN zo$BuWGgt-79@)xS-+PD^D=wy^ql1M{?!fR4u=j&+L&=K}?pBHee?h75_ahdqZo5k< z_1%Gzmm=IJqJt9dV;J56y1Eu~!%~A^nR`Ej-`aq+S7KMj3Q$!{e10O5m76pZ$n8+mx@2F-05d(L3$YOn? zPvLQs`~%humaIK5z}+u!LqFM`3(81aQP^(c9oGz5Z^Ve?i$O~l%T7gMuSsEVow2g{ z&0BEGTDrK#lwG^5ggq<3ZGy8=)I2?R?ksZf;K62tG~*TNe8UbuL<49AO!9F{vrDUj+)+K2dohFFYPX)y4;i-U(K5a9Ze(0hh?&?%KzgjKm&0ZH z=UU_^E!?UgAGcU{RR4F%X+>{KH*$`mP%)7$3U^8~S-pyZ9S`s-hEAW>tkS}y87%<{ zljcmOY{;PXDn@;MN{|oqvD6r?sh045DMbH<&}r#J89N@(*IJ@5ZL+qtgj*4$6J^|r zU(Wf?3h?%%Cfg96)vu-S8%vJ-^)iOgd zgPv-g@mfe|W^HX5i-8l@jN00EvZBaM`wYcG7I%voF=X8kd@Zz^(Kd2QGh}-v%Q}Cn z8Rd0bG&4LEN+7!}f(^$8aa#mEA$uIOyzzsZO>WKk9Q%7g`|2P9G65FY0TV#09dM={ zFb8P$40d=1tI}m!RtLPH22KLP4)Edz4{tUx?SLO|Ho2mw%&+8p&igxE?n9eRZh26# zv)kaPXK=n$>~;jDPnj&gz0B;@0ZXK!BV^^atq%C7Op?oc%52PAB=-kg_`90vyW7#% z;iiJgZdY*BGgy=Jk?ArI_FLTYsN&FSz26wnLH&J&ntSJLJBVP8NzdTv6WFW=UBTXh z$%P>(T=UC4Q!0M&))ics^Vz@Nr0nXt%(er%(`6P)EqA;lZ!zW>6!X@Le*VzF*sI4n z;6!HE@bIyS)wOi#`7>BuwfwJ#D5lrxPGF!Jvo*=$S=2$<5Rety9E`F@&}r-6W&uW3 zd&@?m+ch82nr!V@m=++Mt&y6Ll1uS(w;{Ra)G>` zh4vnfJ^67awqL_FpI*!28-B>MyAE+^-#du`i*C4|p*`mUa3rvqpUe<9Jns0twVZkR z#oT?%CwTHcg_4&76)t5X`|MSG`lp}c{``L4lJ&VI=d;5R>~RIFq~e|FGRMc@*nf}k z%*VeODI)c(E3!UsaV(r~8Clm!nRjEdk3+0xf-19lgfXsY=mV2zKJQpKYK;Sj&>-#c zaKzn(a4V;U`dO|2HJ?2=>E5?C_s}^0c6Kg0N!8%>GzP!i(bm>RN5{No|7*r8cCXdd zwYb^;UZ>H>m~8^H&3H{r$kk+HckV2{WDf?XYZ#t^SumrU`PZ|oabU;ra|sNuig2qh zy8k`4V2FqRQV`e%X5r|II0xf^mNl+@uZ3_AV|Ziu*%pfH+JFlvr@K*dK4xKmnCAe( z^)U-O!}2Dv@&`gW<1;b5k*GW+=TPpsgi_!2;kH8|?JXEX!x&zDLcH8_3FY)97~V02TMFx;0a`2nL#+J$r<5_Sg`d3wSt0xc#H+&r>S0UWZQQFHD-XR0;kRDUyvT$-Z zlrGNR>PNE0PEjD2Cu%NMQa`{p-p!96O-m#iizd%~nh zXXhez?kqN6h-$_wau0YaQ1--Ft4cVdll*JY!v6jH`1J$ZIIlHMcGTxb@@94{wE13# z&6@TEPmhdiP^%hfR&A?h?8RcR;rJl=Sr%@K&=R**4S@Acm7o>U9c40=B=($u+^`Q* zL<~h{fjt&bm@-LEm-U?LEX@urw3w_ND{0TrR`B8mo-m*S>1r8!Dxhz&gqskg7ijP` z*Wx29igbG!ron49V7C5`O1G4;#{=v{fMW>k*#Yb0Cb?-JFEB_?>*I4~3*4%}o2$W7 z+t5DTsnW3t|fGFZliTZL*xSXv4;B;#_k|wre z`V)bpA=pY43R9+*D4q^M-{}wpZdk5uDQUpfDB@N$;0mzLC`KS}44|sP-omtrQx&)s zfmbzf5gP0a<%uJi;#g^hj;>EAYaELa$s60%fI>opuQgfYMvvK8 zj5+`tzCci8%f`@sw6;y5)kIF!S+eJxDw6F@ zgr6E8YmOaY*a1^^K(`$*iUwjwfTtY6#5WAy{oVk#Mew0Bd{%$S=ZI%;bIxZ1EyrwE z11`1{?fc>S@0K`ED(>yKh=0RiXScysf3CMV;u&1|wSc{!GKm47-05R{MzO#S*g7O= z`H;Yg3*L3PAAz(-JcHpc2>$hp-Nb;Kaz4YWL&&RNkdOh>)NMWkGkOv!&v~oKF?lp0^nF49@8(b56R3Jn44^Ncfd_JJywRkV#U!6r+vd)+l;e}EIX%k_3$f7lldZ?9Q{@G~x;ufg;h6WAa zCmX(NfX-b15K1m3uos}cW|MUH{`)KNA3QHQzrRQ=7<| z8$Qy{Vk?QU{TjBL>v63-u9ervZ+Ki+T*sWiCI)Yqk3=Kh{@iJ>9R3UKFLpJ#O9yUZVhH_rYM$G-n0LH=I++=qY| z`|L}ADfWMQJ%;xzx8{7D^(ITVK<-wbE3Q=h#h-Q4dZVJUG~he-?fAL(a;3eCx67xw zzhH9AGdM>oZcA_A2%lqu3j5LCw=4NNdwE;K`JV{;!x-9Eb{GxL9z_GTM}hrx_jaBp z_kb_1|D6ueIR4ha+C~ZF6JM5TN+7@RXacj%X!gHm{Ia46%r@gSGa1+Pk^Ln3!9=(vgj+g^O)K2J1a=38H;j_! zFu394QTmL&ms^99OR)0yg~xLQ;qJsNI0$D~m{tbvqnthmD}QP!>f*rdl+#yW7JeEY z$0&mvc81^IiIV4^@(pvd@NmeeefWfSI3M9`k3iXaJ6w&D%T5Auivxd5Iel%&q&-y6 zpME0~6BCSY+sW8>eh9z?|8Wn?{b4RUI*wV`$Qf#aBX{0_a0c1xijYBj06+U4itGNG za{6YjPdrQJ*B;^V$9Cg9*vdDDZotWX3MDV&x4ge&rBoE06=54c*1($8fNag9_T`Rj zk58`0r}xX*{nnVfa>K;%VR1HEcMSKoMv%$%h5nyqNCcI}8}c&3dqnRrrz zoe1QlWu}q#57>*Rs>EZZ2xe52tzY(L;u&>_gt%wTNU)6*{dlOE}GF; zz{JC#fQd`!dmF3QO`_Mz?FomIWfvH&s;;>$O&1tXgNw z*4VE$0Yfo^?6i+v4T1Q$&_1+raWeb0L8`bf(4hT>vB5f!+p59cnh$Nwdo~8xm4IBJ z{bcQ`X0y7jx-JDn1BP?12#5m@LhF-K6-d^VNbeWC)7MG{X z9Ptb)?+BRpF~x(Mv`4L74Y;nP==i9@jSDvBEjHY(LFe6$;HI3<8&YM)&W7QB!N26Y zxhe#O=Skfj_xD>2IRaZM&5#X`ZQL`MV+XX^0jqL87w3EqxPp;}7gi6sf-|K;*a5rN zYcE;x(Z zXGf$c^m4|F^)|k|+{1^9>!S7D!eL1$XS_$$EmuCaMZc&!H?RTlgo79Ut_+Xsivtl; z_9?5M*-CQo`|o2`n17$uPpgvb{mGrgfpc%TpSf553E%$10x{s?H{Q>Vz2`<}pf(09 zzUog{wL8Ea6nyTPTPWIBVC9xjvQy#7p1|t=Pt3wbeLU$hH>b+jMQ{!aykUdF{U%3; z40gMMr_;ZQk{5G>e41N%gn#Jm24G=NnPpOOFP~tXE@HqaDLU9synlD7%v1wr1L`2` z1aJfmB`aVb!kPM+FD$=)?gN`1pT9^n{c2yDXaZx+c%`r7rAyCmT1dT4qvpI> zZQaM|QmNRIONZ@IIN>~f6Q8%w@T*mF8Oh9_pOEjr7?u~Z@w(+$`EStGwU|wx{eAAH ziyIEip{r{!@`ce}MpFpqDb9F$Ba^Fk0^zmlJkG7o7w|LR;44^sB@Y%~L7gC3>}NlK zaJIZ+*PpwsKBi=E)f2P%d#uO~x5kvstV>3qY_x4jugfk)s!Nf7#3J*xy4UbPPmxR^ zN!~rRJfL$xXi(&!AoD;H=b#{)4C_#|Sar|Jdfm?Pk@FOp$CD8#E9WZYT-9jZds@bd z6&Eo)Jp8JXPi)5NbuairL0N$8sE?dfWacFSEAo$(p~viJ4{X9YDEN$F;p{oin%QxB zj4{;wGuVFZoA~_jF}j9_S$=posiSq3fy`_@_N1n?KP+?6KDD8TD`Sv5?&G!#+;%~K z#Uej#kv-~@8}aF%2w98M7Vd0CYD|N!vZDQIGc8F{EsE5HLLOCQ=lB|IovWF+O!{PF zXlCau=&$JVq)_C1A15v%zeA@j^k^Md`AzKtqpn=*5%_H=%t)fBP zguK?N-*UQ=`5iVQMkipTb;A{VAac;k2P0nXgRf}xiobyQlizeXUm5_0g+?3U2 z?{x%ArQ*E5gC*$evHVfk(=SL$MHTHS8v|~6P|@$`V_1{(AqN}#EslLbFt0_i=60Vo zp_K7%M}xGrxGCpjrrCOWpG1wn18B3I8EP;+V4$4?2K zY$*GnBN)tE9CQSoQn7-%+hZ$maaIGm7w7!Q)Anb@BB|(1DYib3)NxnW;**|3UaQgQ zl~^0&YoJTbs_50~ljvWS)t$ruOzN`5HLqF1&JeGE7mqopRZ@4X*)?<8nzw9?Eju3e zzUhXg{wSG5I7O`dciFP}ufu1F@4u|a{Ze=vuL)&~*Z4X9N9YH8zcup?`|OZK+odGx zw!h`-J2ue&$+|Mt3O~!DFwd;p{+6fr{~OnaKyJzEXVDu!%Xvz&b<_3HHXpk0M*jZB z`=as9dEkcV^wfl;$AK^W?htqXzc=#C8=j_^`@C*v?xPNzgObbfc_+7h^UL&SlDxae zXQ@=|^5FaV`b#1JN#}pCL@M4gP~@|r=kzM6Fr?yZz%zUTfOB~-bNMJwkb_)6UBWn^ z?mHY0m$jFZCx~;L`A+4ux)*GM5-zpor@KG`sT8G;DJLDs=%?{%(@aXBz7CHvHV%u=>A+mH*ZW_5D?pypT(! z;zs9Ra5g@S7`}+g#)qL}9xGN{Oj}zU-Jky|ZEbDr82D!%1nxTjPqCc;(#Iwh|4a6A z+vcyb#StVkpF+t?DGvOVo)F0V5nA%>GL*awEC0{0$o1!J7dYEbe&Itd(Ua58ZZQLt z9e95cXRjdtqxyK1>QczXiu@xW&kDC25@ZTV953ANO+_4Ekbk_so$OQ$ys^ltyH?^H z)cM@9AZ0d8_Rmu|#{~Jk7Vf-y`oOXx&T&CzTk^F1PpFN9uT_>#GhQEk@aF+#<)k7v z?vt52^SYH&Dgv%D?Ma-3h@@dRj#d~Rp2Ru27y0y7ZaDi)Qd5c@U5il{UCzeQX@-Y~ zxuLw9Y*|a^X67bw#x#pDJL2nk)Opa~X~8642LM5l~CaVql^e0kV0+B0K4`YPPP=s=0bu^OTiSD*9eq&$R1uYu7+_!pBXBh!wk` z-=Zf36ywyvS;FtN=TNc@HzGmg4PcTzI&BmP0lBlgCF!;$S=Ux zHd(yua-Su?tEIjjP6lYpj^MB(xFW2>K}T?1&gUrbV82DDRGcO2?NsxgjiF_W{Saii zEURBWc&wp(E2Y`82OYr~Qn4ufRQoOBz+itp@4Gi|;l50ggU-pnl}R&cqQAyzcN>sFm4S$)v)8o(I9P{I%Bp4)M}~o%&LZu7ZvK@ zY@=*34eO24#ucpmJ>k9m7kFWC|4aX0{PRo(|HYQg{J`qh|FKq{B}%f<>Sv9gV`G?J zi!1$X^nHH=b2biSLs0hOFi#^4`PPqYVC(w_qOqzLhrazEoCz$K_w&}jSwJmxI~WOFl`i=B2IP*_eo`d0?JfZ66 zdI;=P=!tv0-o``21a=2z;i)KHxce{*PtNe8RdO+NganwYO1DUkdD{xUS|+ zyC-bREg0U>@H`&DEVu;ryeO?+ufqiP6vog>N^5_Oz+N!J*S6dvDW_#9lf3JB`pS`T z|My@P9>pv?64rYuN1PF!a0O2nCh)Uw#?QSOW9TTwfjc5;<3`D2C6{Z~ZT?#`()Dp^ zuiE$WEzZkz;bxx1Ec`H%8@j*ugY3Na5-$1g2RQcFR#vRInC-uQ3wuBGHk7;wvv5DY zXYl2`#h`q1Sms6yPcx*2^EhVV-e^6Ux#JbR1_wS`Wax+ydCCH;eP;=Io}#eH#5-yr z&rx{C42F&w6dn(~W8YPbyku*BvTJWBL5xVcxEA)DAd)W5Ug#q`6@|Sf`KLnWm#Nrr z{UC*BObXA`{od9tD`C$HaE}SR2?IG-;RObETR`5^+h#j8+sB(UPMdMF28iw4S!~KS zHRBcSgFg$Dm6HlDp|4FZVc@n1oK`I-JTP3uZPn{;LTHc6N`PGn7#Jx=-kWwsOT2DS zgY=KL;fzf3Uq=Hf`*!k%mMPvB9OT{=*KwfxLjK+8WX)3LXK$WVnj7HIId zEzH|i(muPbWi4eK${^eEfPA3azA$A*Ub8ic;-RXRCvNnmO}CV>V*!1wTJCtDRo}Bn zl$J}52e?&1p&I(jhTm&a$2LJ!ri`gbvUmtXvskMz6xWi`E?Odaq~i>xmR?GH^8>mL zRqfZCtNM|Qu~YMyjcK`JH?G0dnwM>=qS>-TF@v6IEq7a!Hg@B>UwUx^S$r`Vn zs>>Vq8r^s?Ba)>aiW%6Ifb>+EbX7|=dohD-;FE8&v~O`-UkkMt5c$r z?(W$m^~QqlYtej(bpyq&p$)o04m;18T4slE)W^7OoC35zJpH)vsp{;BF<_EhQ*@q^ zABdPote)YQ{RnXDAF5|>ZQ^G8(+#(Zkt63{EPf(I_?nP4eJV$D&S7`^CvT{{OoW)$ zg3kK%CaOn3*Tu6prjc;I1s%?c{Ks3Xb&t5ZH3O7 z9OJp+Q27_5GzY{;Vg0t2+7ks#!m5-Z#9>&5DM}tf!}r1S_IpZ=Pb_>fUcDEn0W>tP zZ&j*7TQyi@#6rO|QofhpdCuse)qrm^_|>O?i)sLg<6RfX{=!xW|MqHxy2ro`wMs$V zD8JV0J-%nU-sX2YUHue3emKmn)7@AWySpkuTGht9h2>iwdSdk!QF=EbM3~BTzT9wd zECjmh=-gtRhAO1)Tz<>GO8toDz>P)0C+dln5wD%Uin9T*@jTWF_`yz3$}ifTG~u#J zNzP>KM+}dv_W~hI)X>FIyCiISFY~I$hA?WQnx#{*6e+|);Hog zd82P~VrroscXDeyt#?C(dn}T%U4(v;scB)tB7!Mm?8c-q=We7SmThwybh^;&NxW9!rXr!bx<7xdzFxVU{= zK921wGTasddqNr9J+>wyaF5vcXQfDznK3!W@F3m(eeRY@Lf`(qW_B;2zNV(;Ui6Y% zX131LinlZ_=i-nAE64x*nnWo9X4P5c)SAw&^al!s=3)e7ZGDAW8?Y>`mIZEcETP*6 zRqF}z0ZIg2a06-yHh**ry70e;Q^;6=9&$hrGW|01HQPLaMQ!(+o5ua(ozG$VL+1?V zZp7~vul}B{ivJ3Pl8_a3+$ItHkSf}tg&SfdI+E4bn@wRa6Mj-Lz4@_eUMh<(ci5`$ zB}W^XYyKO}fnET)#lqbPeau=%JF~+dgi29auJadKC%KJdq7n9R0S6N=6l@%F z?_X%JR5aPE9M+Yhnb&Lef|b%2Yze&?MLmSuM9FNj3YRgY7FPI;kP6sSFS;Kwr5}-? zrB4OwgyoVDOWNJgrcCXnnakhn0Poll79j?^S%dGtY4R9>U$^&>EgOgZ&A4y|YPIMi z-pT9$;IkLNB-j)j4R)Jj!Zzdryl$Q)U(b$DN2K^gHdAoN;I(KXcSo+f;d$Fp&@Q>a z8{K=mR>?rHg|dT8706C11ZO9?QYfPv+qTbByn_)PXY@~o_<4gE)6i@qmvH`EjV(q8 zt%Om_UEfR{GOQYvz0F)i*^%+%mU(Ao8^Of&m6}7=0mw)*GR(FU)n9|TlljM_u4vaU zE9jp)DX>==r8*&ta4&O2?aTUCIRz1wP=R4dh@B)i+G0&GnjpbaYzhe>5! z?|9+tiFEHwQ!qKV{uRM{F5X_dVLk+aKH+`upCgU-YO*_WP{cS%iT?QF1%e1wB2Ux0 zgJ-&m>C(Ut)SYrxho&?3xo0aZBAl&|n<&aEvXZUrYdeBO``_Y?mAaul4qA`k_f-sB zyl#3wNk{#o-#Ka3(}+ju@U{AB#q{+t>IwQ#5aaudL;b${R>4QR_G;n_urG3oRm=h` zG2cA3QC`o?LSoK%$y|Vv!>)j3r|a}nbW(Kz$PBO{BXYq zI=&LKGiiV3Q9?n?q}7*xW|?vtn~ zlc*<@oeU_UULC^zEg)E{z^>no$mivdrB5Gcu|4uqvu7NX^6wlfRr5dPP|i4^v!=$N z&raw@H=Ag$gO>gKx4>B-?OJgM0WqmtHFR*V2 zCsG(Tl~Z5DD2vhF%^`%q|9*@oTLNWd%);BR2`l^d!$&Fp0`xX#~wASrb z?3f?j=dj87?)&Ui;{)l_qyoGrFnE)4;|2Y_i}ORmwVT1&0#kY2c0^agxBH$abg@zH z%hx+NmK$WSyLpdnxCo-bf?B5d!f@tij^v}1l3R5Otz-)V;I3!d(dKDEUnX4RBas4@wV}Z^I`p;30ubUrsf)z^&z-hxE^^V@g$Ak)q+beYfhh($Gteg_!*&w8$0NnYLPEB-s(gqS5+p zN7x^8SP^r0Viq$M9-?UC;$nZ*(@I*m=)XA)H@{1os-U+zhV;V=3YeQ)6}y>aaTYOL zkKz6%@j`r$uAI;bgl1;X3Trl}hZhDUwuIby=j<^?}6L@c#Wfh4gRc$0QLi@>C+;ak03zZ`mkkhcjdE3C$S9Qt6-$&a@UyLnz9MJgkmLlVdf9p2wBxuG=9+ zt@y!B;jNXhy0DF-R4eV#sz1G_?m|d*_9jj>(>ID~Nm^{NaQjJanAJK|x7lcA=DK1x zPaA*Z^dm~RHaxwE#(UaP{7Pq`ZC@I#AUZ>>z#tB0g?1tJY9aDo@cK&U?3gM z0+~9W+op{@Dri~*v1?y`@Lgr*UFE0U6U1=sl#Vk<<~26!_Z+hpx>it2j?(7USQ0$J z<;b%8pghLyag5?3E{eH>VLt`))A}S09WmT@*`G+?F^oTfldvG^H97ERm`pGPSHvV( zlLDisfaqcKls%K@$(jS+Ba?jPvxOpO23X<8WgWkV6Yu+_f*I`Mwcc(%OOe!cCc7+ab<5fDl*eg9c`jdTQMF|>47G(hNmog7%)0f;s5{j@? zl~^HJJv3eY=C7TE+NQ(iYs2l{Z&!ocytDF-U?fSS5DQnpd%38el5BG_nDq8ugg!}> z=qHLpq_R^Vf8>2w^~oBY@J^n{=@h_Y*xR9J1h0<^af}usF}SA7am$Iy>Glai%wcM* zqmU|TyHM$dHonnAqzqa_gCI%1_Qz*eP!%}}y#m<5@mZu?MWD+5ELMNKynEf*;*ht< zQJP?>Y63R!siNs@*qqb%(ic)Uf8pH*yaC!?sH!T`I3SsD*or3%!N3VdNi@qqDS~Z> zl=pfY9FLLSYF?R8KXC!^zMTasi(TVaiDQhboj}uE1#17WzE{DiF?*GB&@cZL11cKi z~Q_3_%Z~JB2lkUE2`P0(%GxJV(w)=-*fZRbRfyP>bvqU~`{C#~SOx2o@IBi7&5nqg^P>v#Tgi zo_wSm+&uQXhf&pYE!q8UDF;G%3ghYh_wSzsmNd#>GlEST>X@(ZZx%k@o-Fs`do6eC z!zxvNrfOLr;O*Kw)gr^cpJ1TRu)U@;MsCzk7Zj%Ap{Kl26Iv*Ph=d55iR#|g zZ`Vk%AN3W=7M^TF`tvZRWr6z4@y~$%r%8-6!X%$0m->kFZ#HSnv~GOuR|ZwtL~C+k zUhh_Y&?e7NB)zmX)*dx%(iEikNXO`$L~C2e!~+vKdl+9{q=iL;!TlonNGp2}Mg#Rd zsh{Z{t_SF*=D!*$KusS7&=_SLicOZtmi)i8;<)y;#u4N{NS$d-%;% z9SaU98xInXNd5l#SstJR@|Q^gLO7&SVKQ|y_WA&aMcC6NVcuxR6U23g&>~-beNmjZu&_eH>ia0$VY~2_yyzE zg@YMU14>M567RHdoRw88?cnzyeePCnc;bX_2iEbD2M_#rKp_USqyDgb9YL959PbZa zpg(U%3C}_RBzqfvMubsOs%YHQSh1P;*?q43*pb@*Ruj6{n){W;(d<@OoF{l0A0&~o z$v3*__oiHG_+SRyfnD8h;lc$UlX2zUobv2ON|jf0Rb;LL7Q)78>^eT1)AL=XbifC+ zIerPH);Ba4&SmHkADF}}EvZq6iA8iO?=>#^gu6oeDS&-oibT_lWZ#;10)`Q&+-Imy zGWH@6^5hVegMXJDk@EW@JVK(BkEk&|>N$JKlLsVeDo$YL!9rA5pavbyQmhuNvESh< zU1PgpYPGW}CR}7l@3WE#W~*bU;N|ViR@EMeMJlfXtt_?of+{lj z=Zmiy4NO!A?10Q=jiJNTJMeRT!SA_-L%S?xC6&#rtY}U*%(psrWadD*Nf0PE0xvrY zqo-&uNtc2#eUO36VoEwQKFZ5+b)XB&+UIcMqZM8Mkm}fK#3xiXEtobLS-4D)+(5UC z9HLGMQcL_>5fC9HKt|yt4yzfV5kILelG(wdL1`D1qP1+v|C8QMj~dkipob#>k%Sy7 z1=-JA3iqH4Xg2^c9cr=%4(4FwX-mq8+&mD1S0=NPt|AtmJMP zD)#1Db0(s$dgx|O_yTqvt=R8M@urhv<#Eh;{_^Q zj;~|ft-^OB1%JGYXj32fkvZ-{M79pr^s&9&HT9S!G_g~wpc+>XT{LNpzW&uaj!HL* zg8Cschmskj;9qgAe=!*hEfug$fbV9Lt9j`dwy!1|^G*H`j9145TKI)1rI&C}t0NCd zG-0WdHZ*n*RoA)d)0m{tw*^Y)tt);HG3;=XBa*ArYyl=WcHjJv2r#hi@S&%;Q~u<5 zAbVRG0Y=i5o6XlPeq+(0i)kkk$OJg25=Q zmXskTi5H%2ML#`eYiGY(YeCOXza)x|<2i`FV>{g&bYF}sF`EF&O+K3HruH}J zI<%dojs`#gQ-XsG5WsnSrIXjvgpyQQbdPWGEzF0&w&s)f>|f=eQ_Z(dJoZ{w90Xa0 zHZP*3;0}x!5p(_R@$o&%EcnnRANO(!6_K3Ju+pRY;OGl#X>V%{568?NWoGl$V(@N# z!)N~E@{CGbI*qrurv_%xtZXTlBfg2ybiyUfTi$k_Pd?7lnRPUsto?a<@R)j*vuA{) zHnPpU&)xtG^mVDs9?Hp{uv4byT2o^&H(76Zg^#w3(Ys!C?eANz{oYv2d!vym`$GRZ z^gWrHJo=6=Af$Jp)-FDG@jdws@$WoFu49f5HF>GGFYwPs*GXr)=WtUb;BSPqzIovIhs)Gqr8=Zus250oQPNvW!kkKZ1So|JM$1Eu zHC=8_Fs)KvI31-<>=wx9aE)-v`$8 zP)l;zDLEMHJ8)24j_}Rh=p(dmwr$$gr)0*2yHs&VP7i-gzEPyTk+FnVa?kSM*&@P7 z-~F7iWybd+K5|oZWm8v`f6Q|WjCV>P={>V`#n3=<{SNKR`w4z+wz<2uF9dZOdU*PL z(e(7yNIm*6Wa4j#gW(AF%@z{EWmKEf_Hj|%gKY=^M%VDA8#De71zL&e?B_gW0WD)R z*L*ktx}u1N&rlT4)gX%TUJwEEpdI&0G;qTjE3?#6x0`2ROujVpL|xURT0i(V`1GBT z6emOKXTHg}cw-|&)k^!xTo_Pc%|VIDcZY9&in~ zw2KaAWC1~)ZQ^#u7ULIL+Dz+foXKAoJMw-MPj6bdv%=>qS*NyphJ9;)PK%4kQ#<-w zxNY%|SD$}0KuNRy;11jjjz$89UN7Rd0sCc(b+OJHLW0{3ex}!0@LgUfni=jc<7!LU z6c*ZRmFYDXE~R7;#7%-C9d0Hw>iMKTSxtUTYj#qu_bO7n?TKErVApCkdZV7QiIBFA z?_Lm`ABg{3OTz?$Na2cl_NXv=PaPp*pG>WrDtd+`>?J#=i))eML+yonG+{GZZ_hSL zd7sz}ZodX9eA`qOY}Ybh)i|eq3Nly0GC+|rY8Z;UlejtF^TuXb)4*Odm7}8M6Fg;! z-ANdjxl&u+Xl2a27e&{H5q9<>s`#&8Iyh5U!+FA9ZK(5l~h@I+pcz8o5E0{R2}DbVI8DM z#C^p}5SOC!^QTgff&G+2-Uy+z6-UIg%Eh%R&aan;TZ>o!K-G=4lme5Db24LIB8S$?HtoLKFp?e|C9RQ^yy9<7*nWb7A#RZ99K z6i?0y(;T(hcq4246TY`q_&c>AbTHvIK!B~ATw^uhoKvum9l9bLoHi%e7rA9g`T2_D zZI+z(1*<&0Na$Evp3LsVRKti*yJ7J8_ci?2@o11<$6EHa=LpDgc?5Da`3G0PVR11) za>G&Ek#o8B%$D90yg!v^zx=T~9AqcAhc4Bm$RiAc-?M;8^oMrQABy}%G z-rP%sYBLN;;MbjHc~iEO-VC*0`8^r_{OO+_ijF(9&K8JaGL`K9K$aaCUFafVp^N0N zU@q|~b3OiCnKiWU(AG26KhrliSuEPr*f5-oa4q)y$2&qQ2BrXn&9p@11%kaZ8RnRt zB*?Fv@6c}#|0+RNb5&T+!Vz86lM>Xqm+2)$N>FsRja%N>EBTr?;)A`qt66`Dq}Bj> zP53n5*1k8h$LwY}lxi%}%#kvD#@5ziaO^Il8UXW!DpF_*&8TiK<)KY$H9l=jsO@o} z_!%GALhDX&Q*un|l{Qd} z{oCese`=5DsZh(sTKwfyovZ%HQ?A(;9bXGSi8$Hg-?zQxJtqt4e80tpd1**vq{Z3L z5ZA&)f^S(}Jy2(>OUWHx)ccMpCskwqf(&d1fyV(`5E{@E1X2U6cq&9;0}ZWzW|-Vr zd^b@bdm@^+&hQ~mb7}sr-0_Bn**x|-IB9G-YWpOk);t8riw30SMJdw}*b9&K4evTk zD?FSkJX8uV4(GuqYr%m**o2K^5RzU7h`x*^qAv!Tst<%N)s;tO0%&AZq?adEw{wv$DEIHcoTgTd(Life$r1vg1Ls zjCBmj$Dz9f0wOc9M+;}#;5c2lx5*vN-aS<1N34{iI?{Mm+9&9uam)MgNEnE;2o^S* z@7U-E3f{Mbbo0{c3_`-iNe!8 zv`12#pTHJR-n%}GxuR30Wff*CSH%>tU@x;Grf#KQeV%v4_kHW0GGW@-cuM?c_t46;!gU;d;=;v<&U{M;UzFvM)Hp#x4Sv0CS#lrkIsQS;KKKR)%IGVZBq1Pk9d4Hz}4(coY>D_r~(G3cx+@81>E`6V>ANi>GsA;)% zhE;FAJv|yre}bVB7IqN^iYpLn7>LZ>{%DU}L^E?fd%3Gg)LC|lJo#P>0)b*{^dFZ_ z&i{X%hkZIe?KmrK@q$nOeNk~dc-HTyx3?SVV9?Yk zGYl3j$+_PNsebW3gzDNJ zGxR^9xyvH9jU4~rfO62R#QvSif|ETZ^5*Z8V4>%!9?pV`#QRe$`WAe3ZWw2*?QUkH zO`lA4u=!KsmcE2+(EDH*0b(^p zTfQskpBX-GG#$;;#+InGWp2DbDA+a>V$n)>1V6Qfano}gmYZ3ZHn0C zk=Vb=<6I&dvR+ib>R;cj-m~x=p)htk3uL_9D2zKvR=&obO@=FP1_x~+BTl&qPc;g^ zXku$X#e+F0o#eMsV=K2k{Nb!!823g54B{10X);u4j^@ZePN@jF@7l)4xp( zcn-Cs!Fiv5s4Oa;PtZ5HSi+}@1P~xV^Ce$|vA&%!bp&B8q_@sC?mE3JVd6?bh z20Nu#gG{|h$M#zA_w%gyR&e3lee?N`+inD{T#F5SrS+>`ZK*&i5lZ>2 zte|D-q)bG#!{nrJ?tsW4momI^sr|lKMiN1<7=7h5?~AzU(Rq6?51K^%cT_-aSC%63 z4~NB&Jgz%FBlWkA;z7#wVIkFnGC`!wU$Hkl-`sela*`*F4WA&iXqb4)-0>*|A5{!O zTcv(QyI%sM#GFgUbe*{%l(j?hT7)}_MmnEi+RZ1DkpqW`V-c-XQfpNo)=A5t!-MQ; z0{X|8E>*&GVwR{G=3hVwz=(u&;73NGMl1gQ$^%`Yd6j*Ue!{~&k5memBNd2v*G_{d&3tcwBH^e+2X%UYI z`9}wBGq)3J(`bG7;*_2g4Y%rBk1kTzwFSXFOo(nWj+OKvQFYvWXPWa>VU-rPE>VK7 z%iKnp-w4e6Vf)eJTQ7q`!&-8u3Aw{+dwjPn?yP^;G|ZXjEP+yRL}GCaa*wOl2c*L^CAD` z{Ss_edN17~npX=Ptj5P8XmZ-`%rVlb=;$I`T;T z^7dU8XxlSsQO{VW(xQCJRBozzEPIu+ooutlZ#b9E)5D{gn#w=&cGNkdbLl^}CucLT zB#-Cu=6}?W*RwPWqAC0!unlLo;Y_i@cTUH3i~xJ>mf~Wc5art%x8NT8g~|11QS-?< zx|%6V6K($%3{s{u!$@sC=_`8$#wm-aiT|E9bXN#lnDAjcvuv_LQ3&{9#^*wvL6O->h@x zKn{VSTeN?wW(BHmK&BFrE{qvWmihpu<1*39pzJ`)bk0D!{%ibv71hjQQQF^mk{*BllUE^P(Z7lPJG%n4sF_OI5@PIaQBYAm|uq z>nL@VaidfUre>U2|8XjcB`Mg7Zfi)c;`P(g*f6f;m3oGfc-1Fn#2|Ff`16(2cVA!F zzu)lG)xY9D=B*F>%xI@do_$K1QvzO5`*#GUEikTbO%}H+ufbzw{uG;3pMe5}T2nQ8nNRuZ`XEc5KaJ2e|Hu&VV+wn>^S0U}w@i&+1pxsxNh*Ulti-Au-D;|@Y{0NPebQ_K4ySarMY^e z{XbW+{RTl=S|7%yZ5IJ??wJeBoJaUlpog?7K8Tx=L+o?43`6lZ0onIsmAjyVc_vLQ zsC|H1CH8YQ1ZC~JP-)p@VHqQ`XGZXBr8%3t%-* zIF~)XjY(~6Jzc1ZiukX8PrUmK)2>yj?Dxr>PK9`m~jMDqmYvsus{;GLXjT=o# z%IsIe%Zv6+VVXduov?{*52+fr5=sNOFqh2jHRz~nFwV=)|7-wQ4r{TJsdUl^x7TI~ zcR)M-o=d#^HZv<~luh7*r;+1w?m+IwGj$eO2UD_97m{!@?MG1{9 zYGC@YzdKX~zm|n@b6B`yO>SQ9kJ-vAuvxFp?U6L8GiBG`D59rf*XG+Zc!49iYml*-{iZwJB>!p1#8rfm2_=jIz<)P zqM_OyF@>MPUm_oZ6JS$4z{1lXNP2#+>QI!6oZpP&G!Yr)T|m!2448=8m&Ius&G~zB zVrg~qiC>RfYsRRCUoZLSk_N5{=&96ul}wx^kWsj&IUat}G0DX5*q(;#nkPrQ$NW6x zb%VyfV$5wS+?KvJR^tr(LwbcE<++wkAA#^Dcpa;D+VW!I$n$&=2!dsL$c$>sAin^^k9}Lk0M+d1sWrs5+w?Xs@Cw zJ#aXW1y_PEq#`p3sd`?dB*NOnw|WbnJ|Z9&ti|5@8%y;FjtnevxE&05B3Olu(~?%9 z6Gi0_vExbnL(0GXFyI>?js}?@v3MUoSUgffcFVEw509oMhbe(DdIBfx-ZyH(Lm}Mdb?-ar!nw(e1y1uZZ{a4c(tv5WH*}8!TQ%~IRL-SaH z;TH=}R*fmU0HW0_BP96wN;u4`*L$v?gUw43PWj7VR`f04>cZ`Ywi2nj^bG?RvwIzrd|WY#n#(C6KZ6> zc%}j9?QVVt@>U$U;7s|O6+I_hhW8_CB@F6Rs(TZRshj|=++ zJ0)d%q9nl2VmNb4Q_ z;`FU(c8McUfHmQn`9GTH5y)+c<%I&T<8Hdcpn>{pNYIvJU$Us4+ZXAVY|hE#X7}ho zy-&oC744(IzgSF01RIKn-Wor%7y%!ZNtS87r0?c+@yU_(KnmPUpF2^5#Vp|n5l)2o zsGUKQeHyqd34?2BR;H#!c?)y30#A2-rRs2}w?0&xQ$G`rX$rlS63I6_c!8OaFb}Zp ziP@HH@xw)JxO?Owl3)Sb75H}Ac|*YUX}*4-Y(fs$ug8deyK}M zs5!txI4%Crs7uYDXAk2Ig03ahT{ z-Z5sl?5hO<%@;{JqLKVnedGm8PTAA=u$5FW^Vt|-fxji2=>!?uTlFv$LiOTmLe0mw zHY@Pz7}ODRHM{9P7GRB9&p%zlIIowK2q9?^5nUCUN=}9*mh?otL&DqGE6SE9B5k`2 zR2DJLdD)thZAHhC1XyMOI_5p3h$H_v0R}>fDVs$SY^%?mabM@_qiF>a?A!)r5cEou zYbr>fm%))cy z0^{j@Do9*v=-V{aw8uKGXza~MmZ~b?mXx!RNX2`y1Q=S!B@G-DhGlVRjf;0MYr!A8 ztfYxCbE*;8TSEx)P0~nRb<}p%3)+wZxw)r_J+@3%FoB3cNR!@SwG|nX06Qn)?2SwuT z>Ew8)0b$=?B7Y6k3=1GD-Mk7XW%MS@!lZ(SqkEMun~QRfmlTf z*PlO+-;kq(FLNDRzjX?75!rSmmjp6=GDY}xgMo<{@yr(H6%pYZk=3t_t#W?RZ)>!b z(`mAxOQL#}+xQV~H@t;`@A|zf3PRCex`60sy!~SSgW>@c@Xdd#aktss!rRlzbpIEG zKZnKZVqk~mkpA0BEbm*Ch-ad`?>gp&MxQ7(jTTXk*W3_n4P%>Xi+k#mUQM3^pF}ze zLZbjnUnEMw1+iy075*VO{bFHU?GkGlk-(cHg@1U@EdBm(Yz-4!@P>utJmk%LO3E5v zZ^bupv zw&}<7V~45mIi_OP8(Q<;=7#jgRYlx{>p!2j{u3i^RN<2FZ9AshVc^wt+>r*8?=xya z|87vxTEL2OFgfx(*mm9-@A_ujqk>|l-$3%>TW`Kc2PqK#%E)>xQi$?81eKF6rZlI{ z@X&j<02jK5Iw$S;?ZGqjoxZulc_=pK6(X`$^r|BQn$#*1h=DYR!_laP)&(rOLft~Scz*Wrp)2snn`T+ z=sU~JEluyjc**cCY9WR?1he>Uu1drh&u5DI$JAU0y{cFC$4DYBu#@Dld_pP4Li=0s z*hYpa&2Li3!gRwl=m1xgRR*b0l{20wor}{_7O`Y7O=^@a4GoU9W3=b3tJcTkv!9D~ z2*zmJ7?^AjJuOUjKT5eh>k3s8R(q6MpsMdWsA)ikwY5K6KZy+ap9SZKVzX5|@6V$; zi6)dJs5Dq%Q3eB{eiG(w@0?^d_%+#&ZM1^_7THO_Y8Ge)zw>w95m_?ls`V74CB^a2 zd9x#RSeaOUl;REa#cHkwD@GT|NQ65C#rGkoS6bqGe??2aAfu1qevX@;f0UHso`WUC znp6}^Xl?%BlRq9k);=jM7RuMkm^^V{LeQ^3wd>+OT(t2T82;04QOM2=MUvSz^_(&( zq?vU^sP&-t0w#ywDbfk~!V4(>FFDG)kx!YC*2)-8F^J}&WtScqiHd%5E|=pWkAZZB z!CRVFXX@)-O{{e9zjNfEvlWnE+zCnEZfpgSb$5T5Jp&T8)*R&^2C#^~`nu0;kSSa~ zgFo|+7W>cfd&5`7+jCW}LgA{2*P;AXQB4f>FDJyZIHzoA(ii-xhJB$IUdD~_mWh0o z9kGbzhJAbQ1#>#zjqk(&7H#BS=Fj-N&02l@0-*ev4#5?8!^@YlzH|4pjm0vUj#v`# z))C%Y*UK@)bb6nmG`|LtdgrD*zDFRyTcwD3_EaW#5oKf#=;@B0$(XQlwnF;af5m$e zO>B##`(fS=5~8~`-Q2n>%l67`AZt<>(hL zbbTbR<6~qus&$+iS>P=-SLv5hl%oI(#-oJz3-9XGnl}k7Gl}UBd|Poa3l8gGCiGZ^ z7at-?yqHi)O7pqRjo@{7`dHlW9@$oUaU<2&+rT^Swn+iqwZXWjv}47+#&VHEwJ=TE5nj z3ruTD+cA>)R-hLz(CpCZ*$gr~`Oc%I&jr_nDNtkGTbXM@t~&KzWNMmK)4ro^Ov% zFuh7MYWP{X=;g1ldoML^uZuP{RkV^ub^dY$+2By1V*q%rNMP?Zr=6Uy- zw@KN{`bAIXpoy^3A*-eWQ{=Zo0-umcwiM z{UQJtMpP@6Fp2U~0lls(B!vv@Y?>c+=G1)W9QL{(dh?ca_3&x|B7j44)KmLg#yPO| zS2SO#TwBV=&ZMRH3689$d$hSiVp^lXykziNvU(C?fT2bZf{WdQe!FpQrg!&qm}N)z zzNHquul4wyUi{jc5&L?800F`D)yR&ijMez@*&mH?kXD+lQPryX#y&6FzSKm!Z~zQ2 z$Jt25)%rF$Vb1GES+!nGwuK)*gl^%VCXK!U1_``(K6&0nc>eX`F1H~@Dd^ZlOYaZR zBYL*7yh^VTU#$XdF|SI6B+4-kF<04ecbY#HP9WouKp)N7!)_1 zvW;`q^nL|6gkzh$OPUVLls@n_lHtsC++!@yYR2)Y@s0UEF8~QBo#gb`{4C_b_}e#O zW#wi|Mo^;{IJe3!uez4CyE&k<`YTbpl~iS8Z0y+S1M+?1VMn%5Z4Kr;>-c;Pf!3$} zc>JS>pO*KH2t7}r=W20eYGyP8Xa>M6bJ3GzXh= z+x}lR{(@d|O1=r?=gZ6A?sqB>gq&`Yky?Jbsn!r99{DRPf~d~1I2(kmV}HNv1ZDOE z5o`S^OJtRq0-gQvni9VrWeJa{WoZ*sTAJwCQi|dW-@TAjDIm&4?H*Y z*uERGY)a#$dw4%W#M;8G%;e2D;Q&N$!{FA+P9T@&b+g=8>phY8-IgAPX^vMB|NZeD z;YtG?kE!sSTYeE`jNvTsf!l6gN8_-slDJiXsa^@_kOJk#+7h?rD!uy=@~{CQVpyTMq=do>GesmA>9y8N6kOP9}?;JxWm-KB7Co z-h$bfE+?m7KN3$n?2~ug)_(@tmL2yz>=>=xzHnT$t>3RUskE*LD2i$0O(SE04Zp>g z0U_zZ_f^s0-!eb}RjPYtIEAeGrIq0C)OMH;)?`obuPG8d>PjNJSM;0K2oc<+GT(hVFK99jlj)S7GJmap4aj#rzH-j|h^XJvYC ziXc@weuV=_36LiqkHY%_$Ce{|J&NNe@$7WAF(bE|VjL*Pdfd&1sF&~9HmsxYo2`Bo zFC>j~J@%A!oeI^0&V65f{OPA9LJO}a@~7X@-aH3h**$OJqZUb<`a7adSy_V{>>fnm z!ou%7c{dXVDT|vz5$kkG{mr~#xYelBCu}*o397Ls((C?00<>gDE&H<+)x`hvzL6yb znj`J?gME3(#Rc7BE?}0Da#7CqSW0@2-)RR!!YO~}@|>dEhb`inFk7Nn8OSPU=@&8& z`P9Pr_Xmd=Utsp=)&j=Wk)BqTp4qq|*`sOy)AM1(uXEPy^*5v#SMZo`4d%>w7LC7C zjkZQLOZnpcefs!Dq?0`ZwT1$2myBn7AZi^5xZi%w;ZfQ(S#}bgQ>G`*G!S*w)wo;D zk}T{Vjumy`Uc5$Y%42k|!l;ckP#|y@DXEQpQsB=M7RDKU*zFdmVdHygw@_OJtobON zo|w08?{%^Os?KEZn7&ho=ZXt@jqR@iJGx?9)?6op9~Hd!QBQr6_C~YC@bB3$Cy*-D zp*inbxf0nNaG9KN>yhc2IjD|t;JA@{;N8w%>A>rT|3B4OH!r#CXPiH*SD&!b1Duu? z=K*MTKtfxy8$N)8#1AUA=7i#thkR{Q?cHACRpGSiAql6IsU`i>jU0}y5o;BR_}S8O z4p7yx&ajm{cHQx>gFmDO7~raR_G;X$59h+D0m|kMWj-lR-lb&l**luuN4xK&01x1f zI6~=o)>P8dQ;ovrwTYr;J}FB#ZK>+)fhxI(jz<^aYj@r5vj4}^Sw*$k1#7rC#R|o( zSaEkRP~2UDyC%51yR^8wySr;~iUxOgC~hbJS?io!Wd*p|;hWj>zR%1!@`EOonunGB zGcZxAlw>x#7TBJKSSE{H8ptQBT=<+PBnFi%gocLvf0qZg*=n#9-X%Z{<0M5c*wxh# z8>Eu<;1&C~%+CCgB=eOYm@ZptxCOv7W$k2-k-0uk7jPc%)HyO%Xg=HsZ*o@ZuaDmf zp7PGG4-DvG)49Y1pq2R_Mfw}JK&w*Fk0aSevi*k~shCYda;%JA!A!w01S8cb8JrN; zf^16TtSQ?al~QcuRR|j_JBhBODM_pKf6i2Ws@0d@VmOhx){bKLEWkT!24hoe{4u98 z7E?X7a-k8g(8N_UzB;jJoPP%Et1Z_>AaUo!EY(qj_5dPQmEK;2fIT@iIZ3T^3sj9U zpr}c?#O@ad{pz^D=5ORpyi=cGq#|j?j{-u~0F9_-#2~V3Hpu_~nAE*;|8%JtrT^j- zo~aVLYc3h>B8&vht~vJEUA>I5yhK^&WGM8khF*P*M*kG;>e+VekIc+$^O*x1GRRl_ z7+5c@0Q{YmnY}`=`EDeAXk`i1OJ7Hl1w}&17~twYqH?nLNU1ZJsgUD zJ4%wjT111%>pCww~$~D{esQk$C#nJ)0x*LABRx zxMJ^^rt8CmYaWOgg};^XBICWl1tu1qmc@>dy>8p4G}sj;iur3N{q9_vV`U)QUT@e}5s);&+p6PQ}pS;%2OhVzswjvZ>hGCjSfHP?mfi zYmmi})bKfXa)C5qZ&*W_r8&~$k%s+raYk*h85;aurfn2}8#>vj;W4z2ntWemxX2E) z_1zoyK5FsJ5c+Yunf8wpNr-sMGce+#aO(oz>iRNHcN{mabFjhhHOFIbWaMeg?zLJQ z!6Z?^s*Z~$9*zk)#cG|b!SH5{TL^yekB&BanrXCh`K&SPyI)4c=3zr^DwN3_jd4-R zaKBUqi6wfP4dQJ_fH=noG`G9r4LgNdXxOtV&C5|hkSu9cqboYvM!lM7cdog3-UkPab+FlHKw85s$A zrwo!s(-_C^W!cRu>0o}6nk9}a@_v5*hT0|-h!^Qnz~YpjDE)6V!l z#Y*g_ac<(LAe+a~o2uS_7Gdx0^EpvIvHl{l_v=@o$Oe<5-Z+k;L_K0-1D5~#)?z3j zMg)5a1fFA?)UDKt%me08C~@za{9;i`z#@cFIH)Q}m(M*L97H}(cyRTZ9xpF{Uzvk- zJoj`xZx8u6y`J9HuihDI9+Iv;13OFiEydz>E2OA|^D!g_&S)n_E7B&}K$|9PQ{0+` zdOfRcm@C)|fBSBL>cE#2pNw*r#SAf;=~%@W#bl&UEz}iCmhy5nD|QwaQ6PN@Ov!Zw z@p;w0nF?7y)dRMS84X(-AS6^BCle0E`B z@<2jtd9AOgTTrSlo4O$bLS4NZmTS^l6!1*DZ1{V!n>4G~m21AWFRG0*9r65DC@MCZ z=2UOeNEwW9&MY6RbSb~~#;x|RVhtH{3*O@&n6Gy)e4#UJDT&sJBKc)SgI%Sm325+O z9E?SQcgj;Kbq$qCB0QY(bmBUSwwbe`_{ zX{79w$EAr_U$hWsbO=o6_gzQfAu3Ety#Xg)M#7|0BOk29HDIn$mP}8hb(&k!!&pkB z%}jw8&K{Rl8JnQId-$2wJW<@S4ud8)J*L(P>3}K{Qpgz%Dd8p(xIxYoVqxt4Q~RAE zKxDW`(V4jwM1scq3me!?Uebh}4_%oK^@K~n&m=kVFhI;|2yFWHo|NZX{H|d#B1x$? zEoy=A?;=*^(UUT>>*f+g2DFG|Zsc(RLaRoym95@_m#t@luZ5thCe?;n_(lF)FqP~S zOiu)-li`qd1_#aBf%r;J3XKd5uNyLIfxhfM7WMh}y&rche+<4n{2r%a>70t@X*IAY z&Uf(ou@_%+JwRcm&>EOfy~Qhe*vzwfA5H%_p67cJm(*VM(hkWGYkTtZ&kJuU@dXCh z6Z%bY>lC!U0)`*Bi7V?XjCB{kqTjOvnk09AFxtN>93I;tRr0I#>}odN_Z_QiTm?Y? z^;8Y`4=ZN(bt#x{z{g6Ru!Jb1Ww8W5_6JJALELX~2q z(PLcDqP$o+A6{WAE&2c!fGRccW41{++#x}kZN~aKEw-`?<|HxLC7(Wav9Ve;nWiJL z>wk%eQE?BBX-wl4kqg*1eRtD}pGJA8qo*N#-gNj>MYb=%q|1%F~qXi^WUu*H#s?wkn=8>Lr zAc6G@6A+E;ba#;MT&qzDxtQw8K$;!;)1FlxO^^eysc2cfD=w|BwuQLdU{?{Z47LAq z38yBssSX*~?Zw>gw67l3YSm?bXcr=Dcak*^)s(TJ_Iqdj(G}Bp- z`2sh#w&P*IYwT2cwR%0<+p-;NGQ)QFwKkCyl?1Tr9-35TjFhcrAhU@k&95WdISq#Ns{vtd{aq8RKXILE}Z(4 zyg!&+1iq#S#-z5|861^g$%c-Yt6tbIYyqthT^9mc&OwVHFDFfwkgwcdR?E&i(SCNg z8jsck0mt+HrRW~%A_Je5nr!$kdb>0r?dM6?kCQs z-+lf1cmrzk7=*!U_FSphtpo9T*Q(@%H|Y7w;w{+WIc(WPi&a^-Va zQT|3?7lZa2w3?{xb%o9w&P@-kik=!+HJ(!I`vN-K{6Klv#WbKdh-$zHfm@J>sZq18 zUa#*)`~xo5(2-$mSHHh#n|MK5zkUF?S!f^5ItI*tkOF4#a*rOhRf|S8}Zz zbmz^m8YnD1H(8IBE1^WvQOa#fZ$LzabIz)Uwx0`?E&@=@c&I@AocGHCE?w8shQseJ z3xwDP^?L_hOjx01W>`plD`5BewVLeez{Z+!li@KE+7yi{tr1%}I4P|#*+P>#X5GqC zc`vzxms`zwQpHmF=_s|#ae^;RYZ)_Ri~u}3n3!DA*#OrdGV@hUV?NQ$QAY{SS_!00 z7v?5OGj44B+8kKDkQ`z%C?mhBA+zlZ2Qn%R$Vh4x{klT;0IIK^qgeowE%n-zDcl^# zmSHu(^GL{%&5<4<`QAP68}`bM#C~N%~D#Kv8E~75Kx_e{1o@tJ|29)>& zv=QmE$yaYU*Tr1VvfH1~Qwce%)ZeA24tLF9bhUS%A_EVN_Ze^*E(xd){F~XkXWn_{ zxTleQl1G>=b#_OJ8JaEWcMCfgN-719kQHo5y{I^NE2?526acN-f*BKDN$`!I9umnF z!l>w*;I6yNhZ5AIP_Ak%8pa~p^rn04#&*c2i>m`Js-+j0CW5J^E%(o#e-yF$J6s7i zF8z?z%=~@>_o5%RepUU2!`@BmwJUJ;17rIVJ9v&NmRp#8*h?? z9v2r@3Lt@?`WC$b&RN5w-xQtSp}VV`T76&C9S6D>ANSw9@RFF^Bq+NJPKogGjhvlf zULO2#{U!hXlLW@4E#>vP6pj-sM^wc?A5Q$T_RUm+&15fmitu}f?NN(-^q)%V)NZd# zX1WWzG@o40DdKzO_x`8q^|*NWqc?16LzH3-vDeT0bv={U12=)h_t#ac^c;#+IvIPv zg;aZH>E=)xh$K(7L#XMqVzV=~t0htn@A2%nz*ZPN7zP`pyuN?$f;}DhmgDG>8FG146aBkG-HC~m1&~tLxFW@n(^YaVV&;Bk_5UK<{7;?lu!(YL_Wi z(22}TU9Eg#@;U6yi7%JzlF z;6N9FsqjSc2Lt*86C@u?>dMDi2QuqVr3!_T&4QCC9&TOX@4q=QHgi(z z%zEBipJ56s1`I-shF@0o*v_bt+L-2 zZaqDCrArrdrGG3NGv#w&Z8x1^jkW7Z7wM=*(uj6au8d^ykIdTalfqw{4-3k&dppi~ z-V42;AWTh{uq=RNkdRS_H4i?A!rH3VAO7?0uatI)5O;|PSygGX%1hDVnn=Yuq@c1m zEo;Y-N~-o%$SM$#D06uD^ET$nLyu=8E#n|Y8=IFL%GpG(PO z@0#6Xi+3jQ{ylEV!2EQqNG$`0pL?@+%!QB@WkG_3fAz5cuR0pE0{5^^ZJMsWX0OJB zXPBPZAz`yzxjY>AKysN{BX8TEuiYz+iL)+!=Iu83iH*-}x-3bNT*{pq$qOnif&EHB z*5fMW8_nWixmBg~>}R)27_ITjAI@*xTdO*>#v zIE#DB%uTNYKhb|Z{EGhXr+vGt=meELHHgDtka=tuc8l~}E?P&ZhN9C}o zXrTsw>-}2bl7<7)op-7?im8gjo;P~O_vL(BxYk57sK&}exm_lM9D&Bt%~V_b?cKOkl(Rmeky z*AKs%-c4$nx83kEW`1fj7ydoWotq*)B}!(*Q6 z)+vAU`}Sc9%47{;uoH?L)R`c>jVuLJ~4Qd&o9OfYx1mc%sx_(i*cuAASHkYAKLURDIl}-Zy$Nt0Ha|xtZL&C} z`FZ^c(*cJ>fj?AZ@O0-Cea8folXit`262`0d7$8l(ShfO{3A2zy8K|Q_!$Gj${G0S zlKCk|F_dZ=K5%p1`gtTKgSCWEOZ^Uor@{yX5||G35~R)~w6e#h226hTgA-LHn{{yp zeeM(rt7o;%a~#VShw_Q&BO>%k*rumZbnfx=LJx9pAm@d5YGXk7vdH6J>-rn+=5$h% zKU~DSW@L|a`fQaN-q01jrYy*9u2`U;fDrOK_r*}lnt>2`*K2?1=*W``wBo%?99Kh0 z(BUZMhPO>WzWYyv#nM0jKuTFmSFH`(fx?B z17}RX`pUaI4tsQ6*D==E{o-F4?8Z0c&8!k-t%g4bU=()Gw`tNq_S88^%d>QG*ny~< zsYN$C$WO!0C&^!nvo!-WR=v=+bL7V9kasKQo(gujP7*%<66mWJt}XY3Kdz?4^^M}( zKsTp(vg)1~L5{n&--NN5OUlftoO3Y#aWqI&rk&}$G4gj-@DoZ>xA;=TXfZ_=Zi?bk`M2KkZ@K4kCHKnaJfbE`IOZPc!ztu?T{0#7N!yMjQO5YslA6Ys(c&_6ug$SM=$_&V3lwC)2mB z#O%>AI%}n*Z9-A2`rk;Ek3~IK7dEc$+x!}>{0My@%?WoJq0<6svUxxU8!;o%AnSGV zOil+)>GC}B8T7{zPGDEj@V~$aKMf_p>bzq(8Gu{bcVN0)%RD_W9a7V*8AWiLFb6{F z2m+A?i^I=?aI!OhpRAi)9H7mjkdaQ*!Yaqxeb#zD()wt|L^{c~hvW5bQDqJ(%4Msf zF34)y_g&vxT~lEWlXidZ17nUWBZR(}G94#Pcz8HGb@k!8EqKoUzaoN}1- zwH~v!DZ~nUD(UF9*s3sw@{yRt9fc4Fpfkv4~y<%W=*L zZ7Cmi=3Whkp*o9Ieiv&@u5^Q0=RKKKCe3%TW;8l9khCz5v{{^)bPBS|(}JpVt!coQ z=q3J~99aKc!qd1CS6Zw~+mZCt<0=AxDpTx0?}C(7F6DWJf?ONU0#XysIsTIPb{4hw z6{`WY#gWftoiOhJTJl>Syi=yEInIEB1EL9oiqu!tZo{{T)J4>;*Lt0HR$_!sNzi+> zwZr8!m)4Hxh=5U^U$AJYYxHW%cC*Ipgbv%ZL>fXhufMZJpikls>kkc z^N6NRYQ|pcWJf$jcdz5lJeP+>-fv$8$GP`G(=1$=q?-G3SuIk+P(0)Du>WHL(wPD8 zGN7u?jU=KwI89#G^`OhV1iw_KtE)lysV+21-Rnd0q?~6n%m*BZr;z&(S-FOIW^DPU z1SHdgrTh*#=W&>!v(wLQ3*s9`bP81dW(-sGHqf$szs_5jFQ7reA6Py2xBTFnJF{1? zZAMSqB_&qldHkmpRl;djm(3q6D{}GzePuE1h&>8th!ggqYZmwViOAPKy(W>#dWn^P zyNOY5U?erl+!>dq`-4-0bIQ#`csIUVFE0_KXlK`){sUd+?+alg{uku$O9u e+M% zet<`wnj(4%T~EII-C{>wOHb4lmzp|iY2nW?d6ea$eht#NEq{$Sh`=Mj5=OP$$4(d zSGSghuVTjRW@yfO@4v~EK%&0a!v)1D!xhv!q2CBK@7UyP?JYIYRv60w`(UhaANclP zW%Qwv%rfS)S3=UnmR$5KYE5PU_GfoI;c5|GwBIPYZHfOM--UQ4|BLSw&wW7KT3&dE zGPI5Fqfe(@(tZU6evMM~8>8*h6Pd)qD=ni#)c7&?M+I@6lpmtT>I~~>|9By8$DeXX zUh5=m#2)btp|C5Hvzu`#H+Xy$iq}jg3-Z@iyKc&PI%}+p*sQQmwOyFuTLS$#U55DM zvsSa%VnsH;t4W2rwE$@(A562vB9AFQQiAs%=I)^JC-7t@lcpfPt(m z%2VL)YXKd9FFGVS4H!6E@nao-*d7C@CusWD56o83-}w9;h5XrbhQpi&fQ}uM=|x+F zebm;ab{GabJ9wjDE8xoD);w?RXrzCBLZ%@%9qN`;Nk=RWHQO zF!XmL!Aq|>1V3I^V&&s+XE!k54VbQH*~`n*lg`c+%a?m~9`b`Jes$kcg< z^5_m3m9~Q6$6b%tIcT?{!KLIO>DHfY%|CbKSI@ljTNLR|Z4wn%+)J1Q^VcS&heN+_ zWKKTHeKXL()tn&EA6Gc%44BuLW$)$2YP=2w1vYmAYnJJ9&e(%&Hb^&WOEb$@ebs+V zKCJjnYGieuxL0PDZ8Nr9yVwH!cYtEY-h)#MCq(yQu(q-)yqc;SgA`93iXibtJX{Zf zxr;J`L-JwqY==BGb6<_gFNJd~x%1I98DrUaQciuwy^n0_wwGr=j_$kTnkY>`>QsLa zUD3{!nro}1_FX5-njyiQZjxYE)MGg8Cc23-sWmhQBl^q!HG80pZozDPV$&TfeAydA zyU%~0RD`bnek^@H7E@c{T&pgu>|4{4WGk++?y7t%r}MQla?nX_^cZ!vn+k2i|278- zC6Hq8{}T?)omrMy3XClZm_l435DQRUyw`YbsMJ0G2)nZ1|H2lIG5;9LCro zLW=^v!yI3FWxUW>oMAnt*v8H4^%Dz@8$-5t2Tg9<3E#6?`a!pILAFx{eMP3aj5CLA zA%CJKiPGv8v+6>VL*}BGYw!3cY%4MS(#Q;6L{Q}SIh{GqI0P8f>M?Ua`E=0FZ64G6 z2_L4PBXmz6dv$fvd-UM~9Vw?@0y{O@zs=5l#V}PtGi;zQdm`5>LGHV@yIdb3i9PhF zt!#dHk-=bwhlX)41v{qiPcE$RF8 zqt~*)ABa#CnuWl}Q~$tl&HX?;XBJPvnI?&x{YS%EUgF5lyT6$kW9ua8IJ=zG_w0ApA5C?;}#w^*o7 zN}w^bi_sZL+q@k!RM1};yP@6dpM>Wv)~RGtEiqTPI`|KgRmQV4rgi1#^NZl}VZkVq z0%^5K)&UgqKgt!l@@m=vh{hAORVf9+HRo9hLKVl8$jL6m%2rJpGhA~-jVWW2$msl{ zDVf=!b?FjDgfacrz)LMY0Ijv6iI?CO&3Y1tYn3>xMMNaGQjQvTrBlcNibHTk1@muY z`3ZZR3eR9Lpj|42kl&4b-K!2s@rr4xcDhZyrlbC;Ya=Q1vwUb~>Rk7hJ*oSj2*8e5 zC81FG@#1I*)$)&3UJOKnkeoba`{PzcN7ozaP?)|>C*n^_3WyU*#h|?#<{#pReHIwL zQfkf-!~yDpwU!BDLvAWL-aXYHTAR&m;aM1!C-34<7L&(wS_>993xB~b?02JIC;|)S z-TV?IjKZof5%Fed)?&{EYo$0VZf2iTw?6|fD^eCb>re@n?^l!AMfMI{J0TTW;z~HZRwHUDTC}}YnH5DE!$ymPAnE(eWyOWYQZyZRS!^+| zlWUJkEt*c5{B?El7zMwXHl5q4u9%BfR)x`Up|$pzHCOA0cg)EzarKnd1t9t!Y{zc9 zN|QOPm-$1_UwY&l zwQ4e}^K}+nYMQdY2XCukWR%(_oceDn+jF+ze1BP(ltKbDy@?LUsW*sdCMn*Jn-<4z zV#}GIxa(!Gnx@AsULwgz4003)Hu0JTo#8p8M{z+_!x0?UiQ&FhLszMb0!S52RE`%@ zS-6ydl4ERXsn@zc^isqeeEcK<-}%>5Bi7)}uGiIF65qq18$!R}mncq_+bLpRwO+~w zrYxn)<*)%dC>2DEd)gOV6Z3hfjW#vmmO7b-+gOWX1PX4)q03I@KP5lbuEa2pQDkgT z-6a{E57v}6%j^5;H7_5G&9Cr?POr3Lqyraf@2#m1o_@H$1lEwAn5g2AFwqVjYmRZb zVH0R6Oo*V`*SH#Yv(yE2((@J`wzXhg=QIEL#N8V2C4=!L5yU`!V3OcsdjvDMWW$pI zMc`#;^1{CqKl$*ii>8)jc2gmKO(LG?OO^l1%W2r#1=tZ{v~Q8^oCafEfVO;w&2Loi z=3Tu{=yCcIjP3h8vy@*_9_V>Gu!`b|q2(TNg`hHeK9f9ux!U(z3IWE8a*g7z9Lx{% zz8`dB8a6&=L=@1>B=3C%6?`(RJd8MoTE*$l8Ah={?;90Ay}gD=?sK1R+NNNluymyP zeNKiY@xOh8M?u@X!L0#Q-N`%&jO3Gtti18eil@)v(i)1JN zE*)f4j@TvNszb%hM28Z39!27g5mdah!HKEyjZ~jCvpTaMQGCVtSoxsW#*1EbgY4rp zZgYN0Q`C5*7Q(&0D)IXQ!(*2MQ2Mfz3yLy9HN)iJ#RnyLXa6Won|m@#fqzbO#O@c8 zQft@2Ra)$y)f)+oVD8%C(%Btc+mZ40Glroq32U{ItDoZOllJ*$$5hVcI@}feD}y&k zd?alI{%7^9^)j3xd{KIm=W+w$2UcAHR-^1MUD+_*P4?5InGbdW0Rj6D{6RC!x5#C` zKVAQdE=mxdtP!re1S+cZyUb@Kx>1dDQ;7$~xrIOXdh^rRJ~Ic8h8LMO&I(JvEQb5; z->#ae0em|VOp8`2>0C$S9@_JRH$~dJE}OaiL{Me@3!TiqZ5uqpPu(jpKUb?YE|I@_ z-0aS^PkbiVU{?9NvcaKzP1J8t*XooXza+Cl(BIQ&tn|nZ-cP|1S>CX-_;tbH2t;d* zDRu5j|CT8ZTY~X!1-wMBXpFhB&xz-xv!$W~kqN!i^b0L$9)6A`P5oTI2ieJUpKUxS zSQM_90xFipxZU-5FIO?4WkE89?wh;l5q}&Ry>;PKErRbBeq?4pl_{hL>?4Qz1e{;O z+1Yu@-B*0wmvmLC@RoX5^hf*|OmYvJzGU#cta?$td52`x*iv_d=7&~|zum|kuOMJm zzFy;(k;Md(50gSKz4CJG_o%&*k5Ah@QfjY8VoC@o)=35`U6M3X^sl0j=&iIyfRTwM zU@vvmn`g8I7n$+R{O!nd3<2cG?duO}k9k)U4D!=(DN*BEx+(^F(_R@UK_0iX!usyv zsY9$<1z;2=91r4v-N@d~2+WVZ3eMV))kidg>fG1v;wHp6x;6JMOi`>O zw~1P4biycF4!{2G&BusOx@{4n(&L)PL&B&{(o$roXY7{QyViC1p!`kcl%@N-qFHw_ zR=w;kZLrH~{MgT!Ysx2a7?w^WLZOnI;aC?nCa~kw@Z25crbwAh)VWldvlExE1j{0Z z%)WK*d@~@!m_E=ocr_{d@J5EW%nAIAFTy*g`jFg?vCCW3?ZbXq@^U%pxipZia*E($ zuwK&*X*~8$k+gJ z(N#k?>~O_*ojT&}d|>@(pSvb8J%3ELYOo!muBZyzeI0uNR+~xaAp4n`gf>u8ZG}x8 z=>`9{N@Q+9;(^3Z!8@H1CE@E>Ldvv?t-rCPvR`6d|DAShVnm-O2?Q8=N!R!mH0f>6EVHJ@drR`f}*3RQ^EI@G9AM@sC=ARkyR;xGO zO5iTgA|6Iyn$B!u48ScZ)aPslZx+vs-DR6jCrOv=pywMqDzDn1A#JC->fAE{L7EI2 z8=ZeaD_<_UgFXbWQL)e)(cgD$R?n5MIa}slp4_7MB=L;uwCO#PyVZ0A`P$#(W7VqR z`(mBTBBT0FS+||!9tC^@e!5mUdjKjdUQA+$c3ZFR=*dZvz*tpgNzQe?k3BQ)k4v;4 z``Wces#VbKsLuxX3L4)w#<+8y{_G$Xd2!^j+FhIiXb$M5jRcx@5 z9#D0PNUx{RacO*ady4lqZ<6xKkoc_L4bT<-bwA;{LvH5i5EieWd_zaNqrdsPDhW(Z--#m!tv{2tq64qXAzp zb5Rj8dX>+drf)hf3Htf1F{@e=_?OC>`Luaq=d5P}I^@`z)poM#@rBCC&T9+n+lL<` z1m631(57 zPeTZ0We6r>qoc2`nmhEb+t0ZuZB=&|8?H6?l0esTG1u50W3s?bO0J&xhosMoe-YMd+{6Z|&Du%5N>J=Wzl9-}*_JK;24uI8E8u`q^Efr#G0jdF(`ctaOl_RrjfhH|EvWa9$h zgivt0c&i!rqhEV&I102@Y06L_a#jmpCmMf!>oF#;)Atw0Ds8VTF@}a41ZT<*U9%db z2Z>#iQjn{tJ9|!`7Rm4a73VZS*6q4~)+BMO)R1fAoYmiOyg8&*$0-d`T$Kw_fiNc3g?9>IeChjSILH`qCrU4$J~YkvyS%bT#N|)vCM)IOb6V3dn5O8E)djoh z$3Pw3Q4oQzZ#VFky~q+HSH9O4;n8^cfLa#grRnRvhY$0zIMfQ-7@Ef_oa-M1?>-Gw zs|K3ZbS+#v2g>Q==XRf-H_-CIKv6i?)k6Iwm1Z&B3T_jnqnW@ogfwal80g-r4Q=M# zdfZrbpN?CCG|S_H?h(3{;1%gVszX1bd;KJ6cskV2duA2shj>7DZLcK|^+5A}ILIC3 zP!XEbB2Jl~LN=CnGe+g?i)Sqa{gJ=CFWLiRkew<{t4ku;u5*kkWcff`_NE{z@7df` z$Ao#?w|==5^swHCaOs86^RSikHDYAmNx?uMukTPxO-86ExjXKi>qRBV`r`R4hmFyD zYP$Q=I1_wBx8Cqy|J%DkZQkJ*8|>`*@lFQl?B?-LWm(r7%x5OA-2#3OO-*~8a&OBy zFR0zm*_&p|EkZ*Po_1+En{VhBw4=YLOV=70w=rQF$Y%zOT^9ATRGTTir=(M~+M~f{ zu@3-hH~FUJf?M&k{cp5I;!KDb_iKakrQ1y6n1kK3=>%u070BdPbSs<8EVR zVuT)m*>`aG1}w0z)h{oVhXCKC&Af5>R~=ts-6N4@*m-)Iiel=ygX3Q)O~iu`Gv74| z`LgVV@fS1Erzi6@oi95#(Wb&@fByX0a(5>j`ZS>*;6V9lx#v=3KZ*1_H|S+DMvU^s zbt-{oovUdq)AyH7;Q9Wu?XL75yj{Me-+k1N+L>#M*y01S{nN)k}U%<5su|AYNDH z7elWXbdg{JGan*2k{B_|O?AKURO#$Awvm64Z5cB)l{H=%FF@HXW)pgYv;2icoa(l_N zvC8gL$GiJ?sJQ%kwt)M1U;X-VX0?SumtiAzFYj&ZicGPpSr0m3D5yeryKv}K-I}I* zF}54lhc%<8w}wo~ZfS)PJhwjy$MXNKgo9-dRg_3*P`(XfD9fy7?UoS%xGC%~V+Xl9 zqT9Vl!GG7K^H!~$+qjODSr#`7gMF7l4LhKaxm7NYzY7aaZ_eF1ZG~^iRWGOtzb^6^ zPLJQ|3~b@oyf|8DLRTI(_x7;+p>)L=(ba$y?+GAOvgcObywJ__2Pz-_g2S8M#|EAs zbvB9eeE>C8tR>GNL*Wgq7Cq1ZC~XSB)73E0eX;!2yIASZR2GSooB5Yc+p~N{bDYGh z&6SRF8V9$$aU=TWv@i?y%GibB5%jxXr=~1v)MrGF6_++jOO)35ts44hR~}9iGwCcf zPZ-Gdi#njm1W@KUW^D$d#bn(WQ$3+m2euX5>_Ud?Mk)s}M7P{vMW_(&)oVb%Al}z2 z(&}Lx-w3L;aeQHHhV;d4IgW)WjptR&x9AU>%MEC?6nz4nAY@8uH=S{?!^|stSSk(> z|4S?`L*ha{V0b<0nHre8dKn@>{^$7DRd3<%3>2O!9eDNmX5QR?QL9EYALeX^g(HaW z;}*BnsH4{x)sDS)+7fx^ym}AcfY$3}p)rDh3%M-DA^t~WanF)>U$x30RMp_*F<-oH zBOsCQK9`wi4_W^Tj)YFUa|`*s8khiO9gyCl`A$;ZceEDM&zNIro$;1!cipLM- zc}!bZgr(Z=wtth`6<5u&eNpY%1!tT*CDWdr=C;N$StD>%+gJUm`u&iOS4yE8A#Wnx z&hdBcsAD1MgS=<*2-40$k1yyFaGa-XjmfO*=#pLAwFGNsV58&naMlC8rG4z^y=T@8 zYI`D2B?N!#6WW5h(m)lpi;;Ofj?IdiZy0(I_df609Lc-v94!8EFR2>%50|>vP3P;SCYP9E@?gAPyR+y(^U7 zC)P_?P!f(=#mNt2AHZnfqI7!r0>rEHSXYe}gz(O#GYAvCc!Iz#7<7Uw6{rsul%=X*xhX3UnZ?d*ycUGJ<`@~V0 z2xdh)-q<1?aUrtC!V&$K=B43s*MAQjvS>|Xjs$R+7>&5{ns>65C%Oi2R55z8=pxKZ zK$9iM!VWQ^L?**f-b(9eb-^fnuH_yJ!ddKa;jjFFlMc|t@d3mJzzub_D7%ae&%zJ;=m1Uy?Gz)zl!oFgD1nyNGZy#|*vTiUk?Bg#KHgs06f$}GV81wa{ZY!Q z?sGOQvBWu|VEoTW@nkZSv2cFoCIsPC%?&%fbV6UDQ}FW)LrtCfQu1HuSp=`5^a zMSVO>rzKnE)3m?#;Lv0&E+x{H0Cjf0e5OhUNvYT4Z5_gHs1UYL(lUu*rK5Hl6}b{a zfHvgcbPa>%nhhdWKl+acm@8wy9$Mhm<0f zOAaXuzDS|)rq6ZZ8EXaApF^^8H3^FkwU|vK9pN8BlF)t3nVJkd|GgU(<;;CdE$v$K zxjEz%uhVasL-Z2R*(X_b&b46q4$qvI21f_w+~ldkPJRVgkMy$|cgEJkD|GXx;kDRZ zDS|n#J5IDpT^U(OXBLOi%7K=ta!rgVQcizxqTxe;Ff}#}QSjfm)ES_k9amIF*wx;( zzGPU*L5s447Df(bU%X?rYSfhy&@J6)Y3{6iJq%)f{}#}|u75^ZX#l?^#AF|8j0aT! zGpx?_s95lSEI{wqNn6yrZ;#L;(aX06jGb-^mOf(gezUkdK2Q3XHijb+bJL<;d0wD6 zWT6G_xPW^4?xyMZR-x&$DuVuOB>BbrNfZ8Sab7DZg%B#6%+#vXNZ>Dw5UWp?E20yEoPNje@MKBw*<7coSgFJ=mM ziJsY1NGEh~AQO|I;X8`}rkuBb2BfdMS_>wdbADZnbT@q~Z^s{=MZUi#I1lR-*882Z z5O@UsRdFnBhn%~pysKOzzuXtEKJ=Rr*B3LT-(TAZ^}&2>!WP6p=W&W34v-v%UA*bo zZoCS7y!H6TJ4s$ZlX8iYukQ8^kXWdz8H+qlWRM+B{;J#v(_>d#F*%NhO7B1PF6gbj z0+`FQQs|}E4g4I>OMuKu5AsP0OGAx_yo75XoI*m?Y5?yeFv*DAK8Twv$%_^7^Wvuq zu(FO=++XYxX2;kYFY=M;c%<50o6NWUhTi;ch*{SlM*{OXJZqswO406s;|9k$@HpjE%T2OGh z+zj$U>VeN{Pq~mf@uR^PULgUNW<&^3P|)*2@V0$j$QWz&19TBCxF++`_PEOO-@d+0 zEG0S|NP5O48G) zg{gyPz)kTIMwE5z!RkKyw`8vAVny)%2Cf*XRqEFB)HV6aU?l%@aVa-AjXNxJJZ3uj zKzw71a4;+D0Nw-N==MGZ2h!3G2|&VEU<<}8r{G4F^MY35_556ihaF@biX=gT25a#% z0Z94>3KG^8ECZop`r(89B7dLoPW%jt#hhc{&^ke`e)$89N4(MIN~q{}M$mm@x9E`c z!NaIouM~-g1iSnmW&%SHa_S;EMh3i;t~}}M{$Q0?>%=~;7KdeKhU_6;zsyqx2O^SB zD3QOSS3Ix5y*#35+%5mx?)mXVfixR>_{;~_JVyf@L7D!_UxDuXAARi(k3l2>3&Bnr zQYLAYRtkX+f&XC)rc3GYm`$j#>;&mZquCh`m{KB5M%zqD!Hk#|GzWd90|CPVBxxR* zPV5#Q={D}pPZ|(*FghdQb$Eq0o1a~gv)P_KzSd^P{JV%|>9pQxwQZ2~Fgc4Dk{JXQ z3#{y&j+nogw;JI&=Lu07n#1T*31}Jfoy$F2^|=}&Wy(QppxSWcB+a9tSkr=khtKwey0s={t7AhpH41_Fmk&K=9_yBCZ7^)Dk|{p{H<%-zC;`t#ya5zMrU)ZF8-) zgYgqoDoM`=>ru}l39-^+uvYliQ}wFg6Odg5=BWN4mGed!)925}{wF99t87y1xCBN+ zDBE0^&^(A3`=z3@x+BA-7!@;2YafaeHi2=W+mp}2q6|~{hzoMnzINpD(teq{(U(}> z#Ia;C({cyEc~P&rz!fw_wxri>+&?U_vs)O{?S8y?-iC&d+@0 zJ`dWip7LqKg}*?B+fyGI)mBz*Sl`Op2Dw`Z$^9t`EXFAoh7l?#AJV^yHmfJr3J=%*&&;eXC$ zUBsn29=#=;+eq7y-=;Q+7BDogIZmkS&6#P6U~*BlDjvF zP&pGW-+DRcI`(%uy0^qE9V_UW=@L4HPLUT+p0gL)tWnjvmr=%sA2U>O+;9mpQRKT9 z5P%S#wd7|)RrMYLwRsHY?VrS#c2(2zcXd=u0n&WotQ(u z;PEMo50@eypR&knkZSAhU-#JuPWEGOo?hP>Cgk~<0w>RR#pVj#G?81ddx z#6zCV{r|E?c}nFCF5IP-UwC(e@?Y6FSI10!!(#HE)$tFgdzJ8{NqEBK{@<$MeevxN zXSYQ~?$#jk#4CWvekl93{P-)@b>0lAe{xdgmR*j5v!KM3OS+Kl0CU{Cdx#hBo&y$u z7O}Gm>E4J^KF(2k-;HUV-?;O?Xz*vC)Q~L_DA(9{mfGDf@YpZy)AbDN=ZDk(;O&t> zSzEe1`3fpqX@<0}uT$IdIiBl0a8c)fe|!B(9sjpRMQrI}>zuL)gnd~A9I~nxL0NaT zWa0R`SU9ZUYeV?_$$$G3h87(D?N7hR^eK}CGvxZQ&tly4{}P@tvGspBZ%wffJD80E z9pTfmrf78Uv^#}8)ty?7@T8-E_rQ*J|A2;s@c)e^#c{)ATFzTGr{boB5AKroH&uf+N5n> zy?RaBW+(U9$vlI2`^50@Fe4)?2VnLs9s@9Y1w{hChKGl*Eco?(=tLSo+8^vq_m!&L zj-4)zLJKp@Ac8E?jj8XR!3;ZC)!~cE*D7u5lO1d?vuL^*s-CnB6K(x~X<&v5%GN5& ziJc5qRViex>inYj-ntkUscix3yRSyNCboAHGi)P*IYcmv?KP0@9A-GAm${V2t`S5q zr`Kr++q?QAD65tgBmDCSUm$|>m|^phP&SGEd$tohCLegJPURPCJpJt)&*!hg_Kpxc zOL_EDxABGFgoo@6JXE-g*jaYTQRdA+(Aiyw$vS2=%hh4XO7CUPIcpiJ=Ewk7yONR6 z7)o&q3f$HwKcdUlFN<@a8d?OWRVTx)H4WUAlIn4_ZCxSp zr67<3U#c>DZrD#SE2z#`ge?U`OCu2r3ky7WqQi+3C-}&z$9ZVU^#mZ?KK=wrw}Fu&^)~ zK|Y8#EezB^g+w{Nb@>v0aq~vnPd(1#v(3ME-r{^jbyzC~a{{LmQ#n^7%$Q7w4UDxE z5J_yrCzfqc^DQWw;)$gj@P=)iPE43l=W%t&!Z1*Z*f?ThiGsEcF_ndyvII75{H$PC zTPa{COr=Q0fZfeHPB-Qw!`s-^Y*1)5D6|_?v#MQ~T&NRdRoQCR!tE$a<Z!=j3X z+m$#*jC-5Jd4J5JgsX|?Z-egeLo@ zEZ$#=*yu_g@NDiWMVtvu-r0(AH%q)dHj}?lr(Cru+}WU9wV|s(t^b_B-7E=@o48vg zQ{T{v+N~1rFW&xOcC~a_qhD}oID1?KJgpV6=gsgH>xzD|h`dQ#>@Gv8Wry@D+X7>r zdv_0W?|sX-clQbo-968ljk5^}j<$KHR?BD<0S8cDie*L#NeW=aZ ztCcl;((w-ls}H{yU=f(TFt$WR?yB9-E!|uBNU6fXqbGUBc#4%j^t)6au{iSB$B{?w zVmNjW zCvG|FL|*}7nUA%ks-KCD=w~%YujxE?`Ef)r{fgV{3w!smKTv~1q{@K^@$~nG z0oOV)mMeLXyEw}=WEo*UH)y5oyoT>m9}n{=NH6tk2AE|DbBqE*Qx<2vD@XaBT*C+b zm4mpft}&MxnEm_uuoGC@Ke#4ov-|I}lXiX(Z{26AO`A3k2C=-wV*qBafaq5vs*yA= z4I1Bn;00~~X}|x+<&`{8AOW&gbx42D(kRShhFL_=>)4ZSi~8<4q}xIGIn3#c)wCi| z(uSy*p+1>I1YLx$dfTjOGgZv0vQ4C$O{YnBh+1V8(jCI8&Qq&2X%sqG)ht%^JR+D! z_zQjO-6AS>s81e21j{hPA?mwr8U+Pr6N}@h7$Gh(vR4E`zZ8^BqE@+%M&T-~>e)+d ztC*Ru#RNwL{tO^!^ygV2_9xFC$9NV}5oE!>3j-^UH9C>sa=qU*YO;$qDJNs#$kLsbqs0K`NOlQs1zO@q8n9iAami>l8*~I2O zdB_^XAl|G9vnGKlaGR3f$j$Qp8@KS6FC65r7hc`r!EH%`oB|tTEy?6uo$?Z!iRByE zwa~zADkbj3@(sALs09PM7q$L?e*HSCG))!X!wDiA6&dY zgRV$nY9Z60lUGTc|Ji%@=s1r1&i6AjK!YHQAUS+BnyV<>aGqYfx_Bv0; zHYT*=M7AZ%mSnqIq$Cm|si8zcRHI3PO%g1;8o1TCy zb#+yJ>-+s`c5E!S@1`_RJBpUV9!yoW#Icb!F4r|1+et+lh)qYDjf+KJEypN&-$E+T z?A^4YjE#3zkpCAU?h%2rHfk_tW82I4GX>6u2lNpNSy@k((Apd zVB=^+%3dgWyck4{|8H<294F$ikuh$TGLE;~(8Q#T_lb{n)D?VbD9c{Mp1somw(;*2 z4d(57CrSX?(6@MZKIFV_u}dnRGhpg2sW|Qmb{ar8G;G=*D+a7F%-K5(3-%rPkPC(l z8-uuOohb3cjhV7X58cDAx3%-F$40nKD!yUZx7$qmPPu~1zC{|?CKWHbf)5Og(B(wj zI}?$+NAcI6(#%+So5FowgRsq@Z2tZb_oP7Hu5eEX{4tB-j|KGoP7Z(U&0p8V!0a)* z#PDnQu)Z273!v_j$cH6co`Tc+(PqRJkgjRAY-*0a2OI6cPyeY8L|A@6pAHPhs_T{9`p0IpI_k4ya=XsXAyTl~};4WG2a%I|p?Cn4sWS0yfIy{2H{V2H^ zB^@G1B=;fLSGjIp?2?MLral_>1Yz&(1jQcH$JJo&gm3ZV10$Rw$2&R1gH-q=KTYIx z=}MJ(Qx;;sVFiqt&m3?Wn4+C|Z0gKh!*BY{Jx;VDX&bbn6*o$BbS$~)#(tY8*DP*l z!_`U%-wT_OR($8jiDqVIS{Tnw94%n>P5ywk0NL++To0s;8fkBD{6&N(2zzbA z+?;#Wya@9vO*$5VhN&9aik9;7FE<93MvL2soF%{<-ThUQ)(*m68{u8L_DMVeo?zYp ztLOY}D4Atdd5ks6!Z~{f<3IN}!o9%Cp`%z*Gg8Od!&&*GEafFK`4_1JZB3xFl50?M z4cW>F*~&`@?>u(-*rIzqLD+i>L2*|C*aD0kcsok2H}~UQlPB#FgsTT|wXf{SrhVQ; znBTr&nUWh(awC?1B>`>i@)HR6j5+^hU=C~aa>Am0qoa3Si0o2S&Nl#AKeF&63r`9B z$fB@1ptw3%z>)=!9Xg-989`x*_NsN~MB*na(~7}%?ZG;9DYanMsOnn7y4()(vmvP! zS-v$fi$U4;UYnpWrNK)%r?e+*%Az;YlAM(e4Zt2yBU(Or zsg2ui_NhgTW~{_Z)=yg$W&;LhMkrYtlszy#k^s1s_AE{<((cSywvBYphi#efs8;B#f0 z?=!$`%&?6awNDOZxj!E!B;*$#`+n~Hfnh8$#&)UrLfPh_V!-pR;6-!3e^v~rqrGXf z#%K1DZ*h9cqP8>Qy;())6gaCQsg93~?k4_&?+S*%Q`d4g!;7m@J@iVqkY zn2SWtvgBR`#XC*EEJ&{NLxq4nQt{!|oZ|(yBHVz;vCshQy!l*2vt+LT6KDqQG@Z<1yMp;j_AS*8h(Z0V8Yg!+tNL`Gpq0s9PZIt2JgCtglwNeDw$l zilC?mqq3DHhFQCiMH}|cBD}T*`w36`%r^JIl}s^mAcHkZ0@en_4um_8@M53Y*(QKC zlYp|-!IcEXWee7mg2=f-c4&fZr3=uYtL4w3WCxZ%k2Pvx`4-mbMn(qKU&W@qR%9!e z6HsZU!4bKZFu%p*`FV5QFBlo*m@&J~$T7cQ%EDeo2Hvq? zfFN>~6FJKl0JB=wxRyw1DY-#=7CkgW{g5arw(7Yjhy!CW-~WSvZe zKc@#dy(y7^vWGVv!J83OCbJ8evQ9d}n-j>iW)8VEL3!RzSVx1kDyL`aeECX^7sf)) zoOzjz%LTXBrpWBMhjjNgocV|==?wp^eN_U;7A^)H9IaAbrCGAEr)=?@z8BuI?;dkD z?i8ImRc*abT5&_Y%cu6<$7fESVtjm@!)K4+S|ahBZDyQ1wI~5*<*Z_0VuZfs+Bepz zMGQ_`thcf31yaZTR<}-TDq?U>1FV&_2C)X_wWnt}W7CsX6zhTZm`w}v zb0GuK2z^#g|F3I+SEA_8Xc^`n;|)5L(Z_57vj6*S?ZrUtV(+Zw+kG~#+{gLz=WmKh zEIt-qUFeSiWo24XY}4NB`AkTuZd0Du^2G^Qn+mj?vhjGWq_PPswg=sAET#h7x_&ld z7Vjt)`Bd1DJ^o;Xvo1WgJu%AttbmP% zVQT$W@xZtpEk_d7?k~!l1-0cmc{^WEN$#KQ3Alm-($vmHs1DA zB|8Ch&-qp&YkbrIqP7zylE=fw-*s0LAiUm49yhaUV>WGkjxhtyK0c&D_jN|v_{pIx zd*8O6FaEDKe&FZ6&Xa~I8~PU8rQ)J*@wR-(fA7ojP%+@5Z*i}YKCT)M+IzMsravdx zO+^1+c9ZW3DSgp+&B~CWZ)GXIFQD{!n}L6+WsXUqrH?;n z0YXOW9PS8;tkm-wdE{5&QVwXFhg1#WehVdYKpQXakC;0CKY<#Nvjz>a#n04)DfA7A zV$GI>hOcNQS@-S(``P-)t*kno<(2KvUKf}>Cp?bYWhSiA*JS>_*1LSurtU;t;62rY ztXGmfLGdcUcf#^{)+~GWHNfDRnHiQ}*v%RxvHb0fTt0$YeUz-Lf5VS# zuJb=W`EMCratA4YI{<%P`(?b7f{QQR&+4Fv6*-*RyN@X#JpM~W*&*7LWKOuuMh++m zN-}NvOc-C;rFMxcN^&{O(ECtc7f!S>3sOeV;!*rfUxM#5ZD|GjN zZNYWzF?GUGPmoH%Bb6-YeT%Sn8&E@d4Mn6(3MPGvak+siw{Z_o@;7`Cs2fmrhL};U z{bVCFD0|+Nk;^P0!lA~xp)6BxA#d4uJS_%`TG5Idr~mWjoiNbytG&5n?b>y%3H zw1C++S!~+0nVma#bN>8!hKG-}26Eqkfuj~kd+m;2%-(MK8^68~o`vu%vK7s2ZD!Ug zIY)JH5+&ymUgj#+ZF5uyXMq%9K11ZB$X4{Im|cz%P&SUBU{O8TiCvD8^902?gxkIV zn6>&yNpgJBJD)@?4ssdSY8dwpGJ5gD~sP?mE)1>?`Ax|6w4W7zNpWW@dQC3$H>54 zM9y*mvXz&wabM3Pyz^u$FPS{wNl@ImfL%Ls;6B3qtqm{QlpZk1R;me`R(PXWqvOec zeXP3)ig%k)&om<#pv~3#1b%?YNY+ADs z2kIKI?QieafNs5tpR%-7j8vOX1-0st$tMrv-_g=Cz5NpD@s{!`9 zPYIm$jsKo2*tns=kjtsduJ$y6tTDjaEO&gQ$$$1~SFqPe89!qfva!VR z!$VnqARn^ciTKNs%?2l8Pt&n&C*quMv0ExKz#~Ih9?XXfyMp6}Q5&cAF$2JUpOHdN z1791;^8RAL*N3vaBOh|Y6|8k4+NSPfzVjRGkcyA@<=A1^wL6+5jc+qxZR|~(0`AR+ ztac)X{>-NStcBd7@Gn}(t%|;Kj)R3NrGK=Mw>??!`q87)1m+xc}MgI)S0LGgWt zDGQqE7z44B=6{-Z9oWT39()g^YNV)fX-h0w8=--?2$0e-3^=HZW+o|RMEA`u-WbVpp{@|l8@M!5z0PQOqMGl=okxb+; zCtN1%GV_r`Jt&g0OQ0lIA}2{lhh64EP$UIR%{t7^0>V5{7SINCLawvV^quYn>V)~* zlY7?P|0s6(>ExInDg^xY!76`Iw)wJQuAcWT&Kvcme|8YQB;yIR8l2tH8?vIfl(+LO z_VWdvMp9)P4e9DhbKj@TvT5J~4Yuq&%a~?0kaY#>Ee6bP+O(Ndr>d<6Pb+S)KG0i> z$=&j+y*Z-gGkfz#3z&Tq4V3NMr@bv&z}Jm6X!KSGX=54A7EAWq56jP7b9v;<5#|+I z!gu*~_YVs5gn2#M*4>}RF4q>US29J|nN`yh3(pnrvk;_`3-u z9W1{M;mw(JwISRYtkE&T-f@Jt)O1p(46}9qI_X?Rm|u?N&mp{NmU@CIsaR3TvZ^wN z@Fo)`t=yz|#9qh$_~0&1ZeNX(0^us&TmLjKcfqRiQiOMjps*3)U3t~~UH7)zIQh?4 zGUYC3<>OVB^e9&3LuOpT%Kj^Kl`kZ$+cv3Ko_~>A$>ywcH)rJotm;o=`O~C5LE5*B zhpR)b?;F_V6W2ValB)>{+f6=SASmuc$+ZaYJeIG4XKQo<%by@yc@coHcMIM9k1qmY z?_y-&9Vls&t(-E)-hh%0cKNBqkG8x2ODMSk%U1*i3Dn3|j^9w_yf+&ng`yH>@gob_ zsc@%60?Gm$-gpEr68Q60!jerv!jc6jWVEz!rIuX)$`00yr(@bi&MEw~25DpI;=+{x z87clYvy2lH(>xts=FFLw`T2T;GZ&HBcMody8ag_b;9C}}uUx?s-`xR{ojZ3iGc(f~ zlxW2b*Vc?d+41plMl%+p84K6Q7Y|;pYN_Gn-MGew)~QA0qc8zhd!vwpSE_hzg8rr5 zngKf1#-@?1ZM&&mOhV{5sB3C zLrZsRaA#goi~{XFo6aI@T4LBu3Cis@y|oZo*D}O?Z8;5K)uKcOMzhie zsnVCy{%%Yo9L+qj<)MF71pY;f{5>J1f3PY3V1Rp4;H-`)eZkg%`E826KX_~TQ@(5X5TF6t z@ESm3GbsB+uJ7u8$-gKNzBkY5`{B|SG@#c$52;vwIA%N6fN|`TTUc?rjmujunFp$d z2HzTz#`_QKWaVkWmPa=7^hciM(w5k^W!7vTacRp1Ufh3_Vfzm`zx*(k|DEYGzpHwX zwMw!xDDqqr+f~2M^~BH#%U{5fJ@*=*aC6)q6xb0I6Cn12@VFp6PS|C}gqMKiDWLML zEKYaC<*)xdOAMg;_0FGXy#69Bgjc+p-j>~aR- zr4Vi!sH0@f{D$h_7)q`LIuKqB;norEMU*^_>RFF)*JGDE5nemOZ6heOqhy9$p9U&p zFgE_y=NmW2zJQWb2(J_2F6GE!2jR|;b1z&cofi?_6vAyt4{z?v5foNZV;bRVz*25f z41ST#$1Dkj#C}zs`oyp-&31o-Doe`AAZCnG$4vH$}X_W)1t+|8!%QvDqRUojJ`6|K0D-s%5x+ZH;%`7lq`mL|_j9EZarxEVp; z3O#^WnAD!LZo8nbOD`L|Qbo=x`j+RkO!0I8b@19n!km@!isEcQsZ;yQ%6X+h*_xuS zBZnJH8P}9%w6@z6Cy!8GrX`Hy7@W}qsePR}2B)gXIYp_X!I&MKty0d|^mXX8xoHjL zx(N2Q?`3elimWS2hV9y8CV7-nHszEJ^?<>8l@d06sT_rxmY;PI^pR^7m^Yxk*=TDv z>gTSmu4EwXzWeTHeEf3KSGpPNSQmjir^}aD7xbi+2H!GT+Pge&C#=_=l$o%Q){_qa zyqch|mZPvE&|t+dl!k4J9|#)2YYpA7c^c%uQkr2_L!+1%&=R_z0{PDstk$nd(olSN zfIBCUyOhQp&ZBXMXMj6_UFhX8np$U}@obEgnq~LwQ!o!d-xpA?K{^fhN<|GQ7%$cu z@bi5+{&28L4b8v>&9HsOFlX72It=+GDQZ!^MCauvaSDfKQa{gt>dv z9P3W0xYHcts4F<;3fh3H zLT}fjs2FMGol^0suS)43 zOq*s-=c9XE;GGckeC+%_q&R*5ede&={ z$E85WtS*40hygX>K8uofpyVEYDYXrNm-esYvHq7B*?$%d^vw~2w5Rv`oZdeI%$x6+ zEjz#HyJp((mtR+Y+-|P-#C7C_*EU__a8rJ4+O(PR@vG1AdOT})1O<*aZP&~=Ud%qe zAY2MR74TOFf0$*T9t7aueC|PVAHIj*?EgK!bXHGfoilRA0730b_~}8qYQN6ur*_c} ztdxhSjsFUyC6^nWDo~o3kj6lqL6Hn_IR&C_9_B^!ob4rzwC~;b->44$2uj-KzWNJ5 z*}YQn-hH|s@u5P%hl&Ahz+aSXK2g@sos#Q-IfBA2?D8>w=kO6e<=)8$`6vF02l-_N z=ygBOs5?wh+-4FKmyJm@7#lTxYIHEq5+Dn_@|Jt2x4@iMwBlxo7^rP-SI2GduC6Zb zyYGIp-DR`w<<|4vidMWzv>3BD*&swL4XX!m&$MPo+(a*~m`NL(tH0SAp*wf(T2MAy z@tqIhS=VLMHb>;lWBF;SgR=xh)7kgZg!xGDJ;L1_`&MVX&XWD7KGc0U5=Mo2sc7_3rB~PoMhy{wDzm5Sc}#zVPs$} zk<(7Lq6ZiKaSQK^;P_|L2yc>4XFS&IsPU?f0OqmY&T6vsp z@?qu~XG(U_k$;H{Fe-O5GO)ws%F9@zipW{U$br2GZ*0N( zu=f_i{4K_3c7(_g*yW>FU5k=y5_T;>b@07}`E3meWV9!(k{ieloy0DCWGg2Su8)%T z0tW6I9kNr=+Z9r|l1-ShvO_VrrivG7KiN2(bVMc6{|o5=nNo=aWb7x~Ti49DSh^U% zPg{5yf!k&P-V0SN!@AtY>u3Nv2hNY+%tm;f#usx!@i|hQn4acK7se79pYL@29jglr z40b2m$$ev(4)9G=yXBL+R`AwL`P(8`_qxttCtP6s@+awlH9Vb0bg zmf4W1U~0{Sg2Q(TM!oK!@m zJqsx~5REXJ($Bh=5%km)c|uC<8kFs=g{07I`f{88KQKRnm(sGuvZl0OEFlkNb|O&> z)JAYqLW5g%@X}gR)N3YorYM$NSJhMNpzvEf` z@wPWpEN0Y>)~)2d2nLX?3*5S(QrGXto|N`r&+iD~c3=(2J4{=knK3&CJc-7ZHtEIg zQGs(gf?4ptWs(0a&F)MXw;RA2i*P56TyZxV+*(URD!KVQ20)JGjorgSGj!KSxSqh- z5aGJ|JCy>@6Ku4j1jJ0GG=ugYsS;V^4Nk=8hq64B57}Uro%1dB842Q;A^WtEKHlI& zJk#VedzS%p(`LU98{jo&)W#l@nC;gaHtjJZa~%884!eSPROT1kKa!0FznbJL6I@xF=_csT7CiyznrZ!+6H$jdLIlaekkCx|8E~FO*&tAX^j8l z^XFOC{RHaN`&no1=g#{dp*ryl0FS+Lf|oz{N6E2XUiy2?KL4MHuB@hO`(F@V*n{X= z!P>R!m?uSQ+23%9PtE4J;Ae{X6>K#EuJy*!eQ?gg5qxOFOBqj_-w`lQJ5#JeC*3O9L~k(}Z?geyui?e&PGgrYVwW#1SpJB;2K7(}cKI^o;86Y+Ai^$%2-o

    c@A?4j2*G_pU)yXU zz>k*yWQ1MJkQ22?1J;<`aW;=)y&(Vu$Q2?54&_2yL{w^ zD62i43b|BK4oN^+fPJs*O|}^nh5@Ip&qgcE2b43~(=lP;&M5{bs_a{_7q?9yBZX@j z|H~#ocF?a$JP6oW5T>D!vaHGZrIjb1FQe|IuFYa=^&Ebnj=v$tnZ<%4h z&S;rpw@u)+33}!fJ#&h(VYte9MPVj@4x4hjjh7aQEODvHH+FEUO3D0o(}KfON9gOw z(U&%i-ALCVURoqxvc+0JUwaNWB{&=%fjX4iG%NP-{1M!=(5zVmgEj5*8P_evx{*On z*$E@D72o@I=eN@zx?cUQ>);hP^^AVkOiXg;4WqUu=s_V3tG1X4=$p&YlTwswHpSsU zgR^NgJ`}T7LE}U}ZJH@ZfeYY1A&?(dNTraU*0Q?PXs}+#fC|WWDA;3;lUnp0Zy%p0 zO+(Rh4rGs!>)oqxza@}&t3(-A-l>xPpYjCq9?dkBJt{f$5m!(&Y})@>viaF!z}*H+ z{iVJfKU2_bw+tH8O`$QHy9^WeX;<(O!=jBDvU?0;_BmJZv@7^&v;I>}?Am{Bq>cOg za{S%lBcy?e;0{*U&#_|tbNts|&#~M1-tLx)zb)DPcroCZEBNt3kT7WLXcq0?m2B=X z+duCKzEHBse>C8)e$(c`C5l%bf}S4_xaaSn^ko~lRbQj`qF9ih)HT!g%@SJ;JM`6} zY5>COYcM}oD9PpPF>mWYJKX>K`tSY!c^MzCUq-l3prkaJt67ha^`9a31l0vP25)0d z_dE?*<9QmAxv@&n?1JS=b|Tzye(16o&GHGK5cSlD@ z%j5VBh@fzm>cJNgp1^AMy-7iskFd*25N?KSvnW|7TghOJg5^Wggl9-; zzguf`8Ihyc1BAV8g!wk=bg-$vlXl<2@@oihmTVU$ zZ+cN$mrxyCkCICe-V8rsox^%%j<3m(cFxi{I!h*D?k=M`xQ#HMMIN#i)SUp?${51C zLbh@t*(Z(;sc4sqsp>o8jHRWBrIjg^ zT*=6R+libd2yc;8nDL^uOI7T06}x=$s%sB>Hxd+YBU@Q0U=rDwN;|-?SfmI{O4n<`$i)>T)HH*=jg*PYg zYZilTRU9JiyJrTYWnGc4g$YYm&MA7MFk$2QX$u)C1}{|cIs}!a*#)dWXEtKA-NJ9T zkV@fO7QSWSEfWbSd%gNQW@E){+ITkT>#4&VpzN{Md%YDm+`GNmQ})%uPg@Iq%Sdr> zyh^{&KC*tsV(?0p(X>USBa3UE$-#*#e%jKk*bbZCC`>>cuT4uC4^CDYYR^(>&r+BP z$j>%dv`#HzV0uLR({|WY+Or&*9LCECDs5TZw4irB#HmMAGT8=8c5Vb8i@x?82j)i@ zm>r?7Jx8T2i$la^rdsilwyDpEmNGyad=Jxw&k=2a9cjIZ(P6VT7x~`Zu`5r z4Ze6rfAc`cP06UG!IlLW#bO{cf?E^F-bGAVBUkJ`CvZdr%Yaef?*Iqn?Fv=_x6;6v znwhYF3+~ebf4haVLwm=%M+A-?;XW;J)|ob7U3=8ZJsN0r?5N>4TLbs7-p5%VC9K+5 z_P8`?BljuIru77=n)ZwZ&7l4Jp)9gTkxJ=m z@(l0Jhtz=w^C1WNa_o_c^S;F{sVMh%^MPW(u#rN(;9DBw_ATC-*X;f^PQ(YcgbbBz zmY;?Eu8@>nc(PZBv@#OzmHa3f#};hrIKI@$EdX2!RS(ExE{Aa{E; zf@Y^K_Hli^b?4$qDsik<-cR(*#84S+p@o*eR;^(g+00%Vf?RI0%DmoObNeF|w7B1%0W&^b_CL8}c*7fIlfOv_tt!@dr8Qw{t%)am2USl@EED zl?X2JID2@W&1jkA^9c96o)}C7C{u=}fJ>$vOt1pYm{|i%^mo7I-tF7A-Iny%ThWRe zt6$V&%zme$uCs1;NY-QB~VAk@}*ySaO9I=vfj2xK68ciq5B4>gyKSOtaCzhYW@?mj5 z+w$8W)j@SIMdYLs&{lXggg4LT{&XT`td9v{ZwBG%(Y~PAiIQ#D<%K}2@FKF6sjEQQ z>R^^I-$}MIwJ05P2ycdLWdh+&)AeAQ6GIuEzkMYa6*wD%w|4nigcp#lR0(^xAiQ%oOgWa8!k^dW zs4|&NK-oc2#WQ}geoe1;h!P1$Sy%KLK(<-BxHk%s^NNadW z${n`;U)LUSJxlL=n6PF&!@M0$>2+>K1F{Dr4X}C{?Gt-&RzGX~ZQYEfEgT|b zUD4mxO^=Z+_EVPjkxjwD_LwDWyk!9|C8(sb__P4oH?r;7)z$SKuR9kH62*1+V%fEu zu`kvvdz`ue{s{}lz}X%x@OvHlY!8vxLtNC`H(EzR7qZ;Ro!&Ebl9pOGD@JFo$;B4uS3@B@B0M{S2G@}+Rb3A&+ z!f_%-eTz*SBK%Pc&lS8)Dm(+m9(D!#_iE4p03ZNKL_t)CU4b-UY>!k4bM~xn5%?DG z%ZL1V$;NS_gejLo1G@n4&4+xVWOKo{xJxSbn9pAt2JQFfLoNk(ux7(qMqklwuM57F z$RIzM5Bck|jqODIZQ150jVJB?yq1Q3&J}#7Y_m%$Lf>MC)OqzA|5uKKKT)OhxQ&0w z;(?V4|B^-i&XCe$HV^!_fbCJlAAi9{b}Pz{+6?^22t$Xnc&Fbyth-CXC)SZ&C9)~ABRtIaIC;BJI_5DXi2L26@B62n$+^2|~ zb#dztm~8@UW5#S`9->*YL(ik6&ChNv@b&}yAq8jlAEiM(Z&01PAKi(4@-Bealw$^7 zHz=D`l8s?6_S>ef3(Rf~dz++@-D}Dtj|uOZpzPM5K#CO8COun&BAo_6{e@q75NBmX z{_c?fb?Arb9vPq`a+nYU0Bffx?3tneTyTW;E1PX(BIb^QcuAz9Gc|Mo%{Jw=OjNPk8!6|D8Q$SE-rGB z<&3e?l#h0l6f{8Dm?b-toVyLpl#gYM>u*8EY^;RQidNi+v3Bjc7769M6pQUgu4O^e z4A#c`w4%{>A0HoY<;hJLEnxNrf3TWah%K+qw_dy&Nc%>=h?>ji;loe0UI1@k2v1;_ z*DqwtE{dRVg)kqXWDUztBRs9?G<@hdFiy52h@3V?4$Kibb%d8*uz%d=&sG}0_3}DO zLf9K1Oy_arfJK;ZGij@ltwdLWvW;{tAt)|cz@`oJo!9iF)#sbT^5+N&EBH)t3;q?0 zP5l!nxs>l8JWx~83IM80S(P!NzuF+c69V6|5>WO#QHRH!i{=@i+qUJ{vSlkX zGZ80G9&c4*t$1Ufzeq7KK0;aOa=&BQ67Id@4!&{xIktyBUb~<$8BkOKmCnZGhxl1* zj>5E-B`$Z`+F#aeJ4r6i15cSlds;+_6 zz_%D3wUEY__K!+78=WWtUV05nwT_l8%>Z8<%JRN^$kVP!{A$xQ0NV3rSsm>!`?rG+ z(2?23J0AK+j=BQdi8yE4=j)q%Y2Td>`JnNz{a9a)pDG5F`ny@@MEu6VDr=mGuNemK zm%p6lw|}$BsuSRz5ftwYv{!dmMCox`U-xFkAAiy2m+lTIebv^?*=~hbH0zaL@1RwY~}gvZjbm#&~lhmu6XCCv5FQ5~di(l{SE)a^1+*h|gqn-MPK zVV?QOVH&s+IZP@^-GZp@AXd3Vbw{gCF9Ck>amKHVvt{B4U0q$wK5z^E_D+-cvp6TG zxUi=a%b!AcVRCJsGd{CVd4j;V_)iB$2z-lwsATEp5@-8f;aP7v`Je_4w8(g%t3l!HDcPs8t+@ZJ@cXxMpFYZ#@iv&t=clYAK-Q5Xt^L}&h zH>FwKgqMDsNzoV}#x&iidZNb^D$BKaa*v?;4f?X6_m)TE^Xx?R#2l z&eDDMzFbMKwrzL0XWp(^Fmwid)vu-Nj7{D#$~X6rzJ;$2eYri%xs*$f6n*xeQf@Q` zO@)7&D#xm;uuQMXh9MU-3Kv|8uN=!5P~9;$02KGMBSZ+ zi~NXY!Gynd_41`^ro~%u5s|VdIUP&+ytqY;Pu(vDWx{;Z^){EX)2)@8_`HN=YaI5R zrwLN^VotQ@Qil!um<3~;98rd<2@zkIzk9b6Ks0S?EEPW%@aso%9V@AFCO1h!)=-bc znIRvg7{ZA>N~>hQdTi5AuErn#1z8|pNn#2U-d?} zV}*fX4(d?_-C9EsAIg+QAsPgTF;igUv3xIgy_?4ly{9iJ%xOxZlPDzl5B^(lQ4STY zlvb-MSR;dY0xq~?6)=~!Ayx;kenA%`=UX9O+NHq)xDs^p%3EY1)uW((}(adK>5 zJ<($#)Lc;YYL7oUHWW8Xlie?xe*o<(>`qNDIRhHO-+RFG+^~;#w9&%2i51q>k_3s3 z#BU!ERl~n+M}1P=eIuxa_Zq@3nf%DS%7%+?4e?jGhUp})IzN2c_V<;^cK4JSWYct- zz!o@+-g^o(jYns-TO0-t0Csnsv*#kay2pQZ(DVpW()#Ng(zq&ja2vgGT-7{ClHige z&mOA4K3@N8TyEz4&fg)5ZYXrs?^nZGY~B=>TKBUQkF2o`|0VqookOU^cC5jCl*HR;xm#w! z5DLSWP^8IErOS0Gql~Z09aVJpnrH0x5p=60SQW?_`0WEf+!L`_9WyeyJPXH} zj}MEFeNNH?L>5x#Q)Jk`k$`scrdKc=3z%~%$CeV;}{rb#Mz%=4DeZ}5bNiq+t5*M`Rtn!OABm|K@7h3f5( z-kU!Gd!GO4BBw6w$}_e8(}39cYHOK<1pLk_AD$o)d99aS;FRl=%X=+v2A%5gaQv-%%W z4MM!lP~3EA4p*MVrH*z_9UrYUO)EnBKy5bS;oNMcKaxl@E&aJf8pEx zWYHV$93)3Mwcfw=wHr-wMqCa3mBdaL4o|kl)cK8+guolOah4YY^GvI47^&th(inw5HhKC#XL7i(;(l&3+W; z<8rYOa*4HEaJPD~`ROMQ1FQxg={GvRO|l$t-Cq4lNj>08tdADQjkpHEzKyqEqpZ3+ zbyVha?qcg^A~nc6OQlDb3d2)Njx344{802AB?xNjP(%Mdv{9GlQLp5i4m0=S?Qiw0 z=wm4kS0;Hihx3-Z?u9RUsTWmE7XbpQfq)Q`AH+u@ZojgZS<*9!03rOspMy-83R3In znpcQ2Nktd2A=0+iu%+yer>%K5ekM_dB>`lsdk5=Xcx`A%0R9NYzx4;A1@PD3+m1Ai29?Lyn1mwm-DA- zd&{$?*B(I&&;Tx z(N?nrI2%DF))U>>7o5j6z@JzD#U9JV=|}QnkbOVpVA_0_s46! z-$*{eCn^D7_;MwWRyiH^|nb*zj#}hEEL4qV0bzHlh-e- zQIg)fSxvws6NoF{eqA07m4bHXfc|_tz4Da7ggVnjaW%}eCy6S=um1%c5Xb^AtW|o) z>3_bF#Z9XF5Pu>HsmM%~_tH*B2ojK&{5l*@mwTsie%VPWiAgKWxfaB6PV?J+c%>Z* z|E6?V%x0poW+mI+fYCkX>%QmCfM!6ev(A%h+_?8(9{Uk z_aUItgytY>W~tx*xy};1qJ?RLx*c9q!puTCe~v$m8H;iT=`bE&2#@7HC)T2wuYAK+ z`UpJh^mijX^gjecA)sxNi2ggW|DJBWQe>u^Za?a`#$)r3Rx#zfa}?K#Lz9Bb+TM4@ zzs)S|%?duA&A#bh9DRKrzpZaHHJ6K2eCIx1FIj1#q5HC5Duc=E=&*zTGu=)nnOrxb zbXz)A^6T>zEDUr@pa2X;$+yD=F7sVaw9iO*pF(>>;im=i55aFPn993!4m&dC@Y{M( zKy$gD?O9?lD>4m0pWh3q$59@h#LDB^6F#*yby5ud_38|*I?*d>g2L}M(^X7qvUaOY zo#wECFdE}yUg4<*v$Lzv27s5kfG`6)>Gm~^c1}EPZ}rGJ!WvU=GcQDxT4G@i7(9ff znUy-ZreCJ}Z5R&xvdm5v9};D%n5pN93twVURD7U|&@ArvpfKc&ya<%1WCsV;_zzWm z@~ia}4rlpdc*Ad1lB{|*JYo^kMOJ6xF-uUw>Vwj<`zNMV*8@Xj>B%mTc4kfA+|UQN zzg@#G%{~4ZoS(-Ab^C^g2iJ#XSuTH9D-~N(=WTj%cchS}`f{=M)#+5I_|Z2`P3wUw zc?u;>6p*&OfOGTGit!k`we$XsMrHLlIeO|9nsd5V zGNbVMxY>a$O;zL`oC69!Y(Une&EkodT+WnfhWd1?DCSUStae&>-OJs#OXDf_d26-# z((^Q7Cz#j(nP`npJWiLco*#W8S*O~rkN$p@PQQ0Ke8ir%N}Yj%IM0fh`1B7-*rT3V z@&l+j9r7L=@vZs>M%yX&im&9Bm!mE#~L3(0U zF6TN?)%5o6YZlg2_G*gq-wV!YliI~lRO*8CCMifcbmPpz)%@++RcMIPR{>1ZgKb}M z*S&&8FJf>UekS@T1i302IsUSXTVh;&(#CrMZ@_uoGvh5=EPpCq>2Ag`wnxpO37Y~+ zeAw46T{Q-vGFnV%P_FL!QtbNxMi;&0`&Z9CsxBY>ilLnMNy0m|#aG+DE_ur*`uG+U zUL9bp)V5f=N((vew1qHbi*H=VK*38X3=#D@n)z|98dJu2OnmWU-8EeyzYMUVc}rrt zSyhGF{8*fJeIBz0#c5CZ!eyT)Qr2v3$4+0OKh)_~!W9S};^*9=MD=E?LIvVhSdzv9 zElhj7r?;3Zp2iCeD)Tv>TBA(@kUMN$MHcI>%Dxv&25gEsXz*CVR`A2v6($&-Tm-EZ zbElt7-OSk~kma<&3Fwu6Bcw3$TpVNfkFzfeTWxv$qy8!!$+;Y(Nye4%CQW!l8B&sr z5&FwNS|Vo0#jWCM9;_s47hDgXa(#WH(f(ZPI?rLn8CAupzm#8$H1QQ=k6?+zP)_U) zF|V8tzPW`xd~M&~Z`2r#h`vvDszJ7BzvNLO(^J&!euqiuC!iwKt{blse(`G)%f8+y z96HYkZ@+7#2_)of$6ct)AaDZuq^ir_lzF0WDgHQ&nspszir(~nLLc!zC&mkicpw`* zyAYg!QKzb)mr>xEfTIJ2iBmObo11Hs4ekFCl+XCq_;PH`|Jw-?g8$GsZ9F7Ncqmx7 z4l|E%u9&KatcEcK8|M1!ggZK}YYlXVb-JkF$|lYA;=);beFUh;F5AK3EEE67PO&Q!;5Inl(6-3qB_S!!98|@z4f38pbp+% zz__5uK52jUXKYku*BwV&DnV>x6!g`OT$6j-hsw{`E%rCo;LHF(2i zoCB~Tmn2rxrG<}Nw?bjpEMakncJVf#EdqQ-!AZ@u9Sm?8H`LkeLen6e1WOO2edfA@ zN57Y;URCu_I?ca{^mU8;aul0&JY=$h!)5cTPZim`k@z zd-M~p-}>}l^CFr=jm>aHZ7BOXi?;1h#M+TLF1fb=S&tN6{0aFR5&5l5KHV|T4YD=j zqwbl{99pfrvzFR=yeZv{(&W0KEgAKw^vca>N=L3{gq~ULWz_Bo@>DLmDxav zOFD{62zMwC{IZQoHn_Sr;j{Fha9~xT+Zqb*Vxs23m_w$DI2w!(FF|m^*!$~bQnVnV zG4rg#p4D;Cm!2lXT>H2`&Qa%3^1jw?l?Vqsmm57RCBK)8bSQ&rl}iKr&{m2@KlQWss5^6{9m^%-pLQcA zU*IAyMFWs4r1@SRG+UcF;)^|%X>=DueM2JgfT?3F2djb(3!-l=>venx3g1Ow4+W7+ zZj|$!Aq22ti=aTVjNosnRp?(zO&EcM@BjXc8j{emexb8k-Cg~&$b6mmNV=V4dFA!l z6I=%;_SH7R42kRKZX76(Z|Tk-$`&d5E+HF}6>?9xLCpBAUbUX~Mc57@H9vmx zzk#X@f%$Hqv%r49_yEU$DzPNoGVAz%4_Q1?Kwpe%kw*P5hoI}-Y1?IGUTyyvi}&09 zF{>?4e=|PS!C3x?i!Ix!gN;gSxzrQ}6f!1$4B>w_v%lGO7#XtUZJ$0o>q7kQX4}<` zW^sD5oam!*ZnF3%V5+MZIqq#03*|4JbRD(N+iCC0zRiMdS~dL+x1;TyobVq5e#jCE zO5g3%;0;9A2IqW6hK{CE)8kcS_{_Z3@rLG%)y)UTOznM_kJFFL=>X>_MXF=9Wbf_2 zw!`E&Ai?(pDVpPGp@e8BE!JDLSCj=Z2^1|>sVvoG8!OYxjZo6_&FW+~D&nvDBnKxy z=W_-?sS;`X6b1f|KYc!qNeK^s6t2r80%u8^#CS65T$D@?rkT9a;iZPXA65u9dDQIh z_Ag(!EfK~Aa|C7wxk*?0!}*(T4KMGX`Yas|(^n5^3F~7`UGp5O?Y?OBOfOq03n#$U zBjqybQcqza;v9)xUMTdWRS)KXPY6Tj4|5<#I8BR*6+D*75=eEp;Nj->Z+3QNN0wU) zqJ`sXOt2^P^_Tg1#?Vzki$fy^i91ZV8r?=>+Pw=x08YgsnO+ za7hhK73~of0I43Y zTl#E&pj?45c&r(h16MdLEi`6QLzaA-y<%Ot`ZwBrh@n8st@5R7c^ltUK^z*l&-%~o z*>KTrGJ}3@$xLh3QR-|R?BPkP#h4FA4}VVRwYTMs4`_;44-n6Plq3SGtQ-q@{G{%l z#y?kNV@#D&L7*pGN>2Nbg) z6C-9TTJz4ZfUe-%c+gbsP!^ReppSmU;w6Rd$2 z64mfnzcuVo3SQdU?qv2FDH)3MGB89JP8me?j@Sk3MV5AhokjWX>Z-`a^*cdBEoI-; z;s_z*kT+xrJ2A=C2JB<$iURdI#F$?#q6GPRYbF#Hi8W7g@BP0JB`aa6SsN<3RmRYU zW6W%Ec&pRhucP@bK>_{zNKBBd6obI7WSWqU7`WEZB;sd}Mk`aI(6d9Pz4Pe#Q)pm* zg3GlD z6{Z2R#iC|EHMy$;Iy4!qb19))b&VZS?o9ry%d)}TwY`r zkg^)S;#k+>wYTih8HGy~T;zTVxxA-uv{79cp2+||Ts4;Gy$285+o~Fz@7vNku^?w4 za&+%Kgk}t9wLJNH*%SM15l4FOmhtmE%%ky%5rVrCuD5-KrQX5R&$ras$nZxh$;?#O zU^s8N56wE$N0-;^eDVh12x|1)b+K9zb|)v5bv;loUZk3wsBKaJbI{l#%`7x+zfV5; zuU#?yS09n^uWhp>_3$qwU~!Z?8Ee*=nEY137sl^am&63aN|1xIR!(VNTl9oSPd9L;@-U~lnLq-87{l!W#G2mLNov;(|>>Arq0{{f~dwo z+Pk<1gi6TO1S>Y{$5-_!~|3tWc zZ6B{`Q617=2q$DIF|SV@_l;#~@gn!fn0j4Xf&YD7HKiKIio7og&bsWmGC^nt6qcNO zz@FzpN~Aop#-J=EvNb%}kgSB+bG)dImA~wZHXxmTq*eohu^~1o2D_ptX+gOO>@9q| z6&DVD$NJ}?eoLO!0H|$^Oa)l^)l=(Rl!;fryEW|UHLOD7;j6ndBjPD&EXhU85+4i) zNMfTa^doQZZO(>8mD*Wqd21*IHviO0A?kzz-h?+?qzeBvhi%KsgH|q|IO5SnW1$&$ zRYYax^LX{t{>)JG=pdS%tgFznJ4e;)9L^zwEFY3U*oEZ{Ty3(4c*cI^ z>j=Myc}KK;IEaEY-V!$($6-m%qHkB0I&zh;73+74mXtf&BD9M9u0gR>7>jYK_4fqr zexGT`@lKAZ1P?g`itCMC^>GZcMcei$ak0>;Ja?!+oA!QL3+s_VxH$)n@ibx_4dda! zt3lOH8vSW+zJ7}zG-^??3t9@@Zh7Y?5nTpOTV>1CteX@NBqn6b8$r_DUYZbNf^~X= z!^L*%@cr1?NYTZ0ap!={2G))Cx}+&7DYY%vM=mjqFJaShf3JoF=?H=rdFc}U`8HR$ z#3j4!ZJgSe=QW0sikh@VPX+L`ak(q3Awf4roJIf+5~wAggR?S>!%UHl(vbjaphP^- z>hu}7(%p!o-e6_L|AJj_9GT-ISKw+#dfC!LF6jJQlnb8}lULi23B~*~wiv(OZ|=4ttAQxqhY>-h@ja?= z6y9TT*LH$5&B;-zMM@9f4#T zkrn14^Fm}pcZ=RQ9OkD^O%p{(D$Ts7Gm=e#H(am&(-O6;r205kBTW@1!Y+glh5U8s z>w|Xy5?qg#%wkuB@>r)v zO3HXN3QpGN;-=emOUf`KM>fj3?7@H9_Sr9wh*Ee*I}OEhSw+#k{P;c`9|+6!1`BCJ z?l$-aE9v{d|C%WiY>)}#T7B?~wd9F7MT`%;<@oe1b+4YZEiJk&e>mPBA+^NLJnNq0 zPD@*`8A=aHrJ74BOFdbZFqPgX*p^Zi=X+*c4a~4;3oc9Vkv|F562!n^iFl4i z7Llgw6R@X%Hv-1$7njiUtovZ?@P03T<7thRyM7WN^z?cyd(w_a3SCn8OeBb0`j1G~ zYop6s&usxI<>b_u z$W|-UxDef#q_gE~ELNM&0oA*jMsyVjaLnX-qO7b6iT}prw>>15h!L7$C__r?Rc0^n zpN{FG`!fhvk1%Js!m@kDm_X!_5750LG7MIP%?k+U1VcYiAgXs@s%L9Z$f`0peN+vy z;ITcZLTHZ8s-0o`3Bzv|p^n9|j)$p?$2YLzPL0t&k#RhcUF}@HoTyvbbw9U`6{#t4 zS=g~BWLorf1)s$N;G>BXJP-%!b&NVoKPDZmN8(@ zFkutsA}3yMo%O(_V&#n8u?yO$5T5Ax>DLl<4$C1(F$Dtyd|+fB$kw!@!H(q809&)! zMNKE&Rt|*nl?NWEI<4Jzs^P~TLE2V022F@Tn6(3c;uRmoF<`K94iV+1aq!oG+u)%{ zNvit}bZf!YjwGehVhkaqTKm|iXf0{{JQklrx8)H-MZc0!c>?oLSJ%&?BMbrxI4mTn zva2mGBtGIJ`#s%XI?$S<8xRb$eQqT|)?S2wAC)WnX?fR;(It~JT>bhu$J+L=I+{~_ z=Rdn#B`kZ;QlZi0aYsC~_xR<_B-oVEM#6;9@6XIAfJ_e{l!&&5e;(gr*-Ljr^s>XN z>DiHm#LqihoO`8PgCb}DvTt-N+iBsVtHGe9BA*>E$0G9R)7wPY zJW{Y(k1w$S3j?=}ut0ljr&9$+dOJ}Dr%pr|OL?+O^;nYcGMx&mB>eGYx2HlIVTI&z zYVuxikBf=nIZu3ZtyOx6 zDyT}dv3mr+X*#<3xXfnACdyCef01dz>Km;WQ(8bKNW92DTR4pQ<>hO zDjEuIfWH*jsf^k>bVD-qhKBP$Z{Y}wTUyQGgI z&IG3-ztrtOreq(vo)`CW{NHD#yI@0e_rxL-ua5K1H$D1SG!H*P56>(PWCFCv1KL1s zf$>Mug#s=I^F|?UnK9Xa>-+;H`Nrf8$2e%jGLbQwD!;uSKM{&H@P{E1f<)c;GT#Ex zvQH0zxOA~==xP)UyX*%?SyoB5+!g^hClWv_o@~N8JTEB`#+UB=u3v!@uP6!pA--7! zb7;?;L>GOOV5MyD3mEE%@;hFF{Xdfv1+zEiB421q;s^wT5Ub%|f-X@XI*|_LG`Rzi z|Gy|z+wLzc4j)Z=H%`7SkMn-~8_VjvuEd|9)`{F5d{#L^1TDm!)o3)@P^tMRpH5^Q zuC(6P4D|(%j@|-7Z;=?Nu)~uqi!lF@ROkG1YR8zOpuL;(Q5hM_k}vaTHuH19Kbz}W zM63l0<0$I;>q75fNtP8IIy$ad?t{pe0v6t}B)?;v5uU|1#S{`@D5jWb&^vur9#mTT z>k^Xv#{D(W2^H2mCxzBw)MNH|>fa#t&exqcBp00UB<3*H-Z2U7nlG`F9aD!B89O|K zWwAQtVNS9j`W0=mHv&O&jp@CYv%K|B6Y-zEIw*j1h#I0`9H)rN_XezK%+e@%_?L&< zlEm&vxC_l_n)yijj>TFCULB;tb`wuIBxm9+`hVV;!#L*dwC}epxg>|ple>D$f2xoX zg(t87*Q)h|qk@$hdYIvU`i?O?Z3kuan0Kk~-T{V7pvYmE{ivkP8kk;-PV2^)3?<8u%=npdq_H8p z?vjq7L#tj2;NFl4nC~KG`94r$v(JwTWWW}fj z(<;RoRNWzUS?jCS1D*xnLXi$*qr7X7nkJA0^O#9B=-={wD3*l`M@ex_L=ua3lo6{1 zQl3*%vii=?1~oeb`VD+>KeP}^Ti6|g^vqPXVE*v=wpwBe((t3SLk;))C}b78GJ?rC8Kye zZa2IgjZI{~e%F0Pv8-mC>l?IvseWIbola>Y0}I7W5c=_;A6Wf<$r`D48i~_(QzR`v zJw}I8J|-+t3yh~U{Z`FLB`hu@gMlWfk^cAi3A(!31xqo3aU<~)bMQ%0%-G6OPKcn= z9QTv_T&spZ)RBNjQ&1XzOn%c9M|K?$6G2Mlp5UI?uO` zQlXE39s0K|o$3IeLK`{@!!X3~wwJ$Yvn!QpI{cm+usx$G!@M46*JZ1o5}|wPoCk3R z5td|YBonVXKiq(t&76xge_XL5ITN{WWqkBR6Bv#>K1XEqOn9=?u^ag5{puU}R@f72ahO=8e`I_@Jt{JI{8WkXc99B12)!C8b#VQuRcFGK~rtVyLMJ7n81!R z&AfimERgSOmUJjY?KRiy+$23n{^IpxW9&t(hZs0g!XRzoSLTXi??6~}K3+|t*E6AH z?1lVvykIx=G@rv|q2F8K#v)4p%juA{5|&ySfxpc-i&rKTP_sh5yXM^j%Bnb zR%ooRH=WXmE2g5_%L#}vj7AK%Uwt8{qBESbsj${{@ANU7(>U-D?s<$C9*mD6sbKA4 z`vH?a1}jlXlz7@ifJD%aV*;5u>f^xN>TLf$Z5r`Bxm@Y3aF*nskj!JWN~>P2QRg{M zPN=4pM`#Oz}DfFj0Y4u zj?l=PDKHpEe(mJ*Y{Jg9iY;`!Z-$KIIYW^aHg4h}id-Cf0OMhCSv5FMscZK5xCm zm*-EHIl;FrA{&6Th7~0pzQ_lIw?Id+!+(q0_HVqB-A2jJ?)hG;Ttv+i536~f$nGD4 zeo3nn!l-oPVZiH2u_hup5s7xIb(|LFN>?0ZM0=J%qe+?GB2E_=(mMdfhxB^kDMY~2 z-k6UeMti}~9-2|EqKR!(MpwH2D37?#)Qx;x^>Y1(^AAC1yErwq*iGCz?sUJ7Em_}C zT>H$8v!K>&*XbemHwOt50118NY`dzb2W%gG22LRkXFN;^4uM?uVWO;H|Xgl3;f|FyGn z?b1DD9RbJdx$5|>eQ(#)3aiyDPC}kG49A>l!!OL5VdK0U-9PA%6Z39)S@p@5%>1Y{*GQ@DE+#~*Yl1JI4w^r z29JAGhDG|@L3-kkn{NP{1zD1qMmrP8xzVBXZY)*##iZ-tK-cbAV55!SEuDhs{%2wA z$ZkOvV8%Y0C-|nhg2S!!`d#VZbhv@+JWeOV^1EGhhNe{pf=b5GolSKdyYgyA&jRld zdY)v%9#z9DR$vCJ@+La2cCU-JNx_NY2mq@(!gH;s!kphp2sa`l?ETHx1h18ryf zMh9`7=@fwa?}Gn~#voffe!{g~L_@@=e6M!9u=VjNWIHF89ydQHeR>>#g;TW%A4!EfV}6p71?Cws?b z7n_?&M#|xATC_l>;dH*%T7_M44MVN}nI;pLTeALnx`iXErBNndz zBQ%VL4tIHD&@KGlscod9uudof^vSKWQ7=jpzAY1gG>*m*WDsFRc7!j8OOUK(S!KdALNt9ByHxKT>% zMEX0WWQrZxy1xaJv)L^2+GmV%$yjKw(#*W!_6O7bR3IA-u#@$ulRw0i$7h= zAlM#R ztxitB-DAt^tHDtI`fy#gP_OXo*yau3if2>kiFQ38!kb|{C#~4dYd&?}aBl`~J17}7 z+`gQ5tRZ+EG1P1!RP5& zezm=k07NSqfFqCJ@-^?l$nZLe4+}q$Jx0`Q zk}HW-U~JgZMb?arkf5 z1B<6OTX7Q2>EbOtW$9V3>n=pDXhMLW4BC5tv|j`FM^Dr@l-4ki>uS`~k6SpT~!FpNZ>O4iN;1{N%s2i(J zWViCyQ+fYY7fwaCky+VE;Q3ZTb z`$;Wpg>U@XKZEBXNi}EFGp`L55K%)OQ@M=CN~q8BN%d&R03PUGYPZ}HFgzXb+xM}X z)U>Ftlo)NG=ZcK@#cWLIIcyZ7Ot>YVTCC!`3T!-NTjJ#WWBE8a|0~R4Zbf%JiMHZ0 zF37%jP#NJ^nT>DGmPFsDugEGPXCPYyAf}#cBy$4-C~X}Aur7hU86@ix&BK)WG1FDkW~oAba`k$xa9wJNx{*{LV7H}A-JG>SKXv-uL6OW9!hQ};LA6qNbb ziGMQEUyq;{i`46>Suc@NE%h2dm23Oo%fd7g$h$QJJnA;?RKZ&4-lxpVC28tvPADqq zTVMYnEYUG~DF2@LCzSbZ-v$aIQ)|IL)(yZ?>J*Sli=i1L2(yj!H7_`WSIH_eQz22M zWgVdzLWp&o)P*M9m{y84OF2M)#swCy^qhlO7kdXDGk zb@twmb24`Qypq)Krc~eSQ>vq+HJ=9<=t1>({k>gL|yn%m>^=U z6%GVTBvX@%-|6}cg=hx9Qc04&*4Cr~#I=L&B=Y6AQj~tP5T-&1z1TS7F7m)f-Spww zJZBq@RKQY?pNPc}&8GPdK@l5%Ha+|ZtVE5RcreTyY|ev3`)*PNv_ZQ@&jD(R+o+{i z%?O0{auAy_)QG!u*qG56%$lKDvfic+i>N^kj%XuJ&kI8H2S!LhfUgYyh<*xjNfu1! z&^O~GHL9(`n%se)_sYJS@V!-e6=bL^*!)O74@h@?TQ{8VW6Ry~hl`zmUVBPXNXv)1o0cbAc~vJAaY?_U_tmRD0fI91}k zHLV%1v>tKnWvPxL5Ay<9OgjjT>KGA@wzJ0rf*25BJl$}z+a89+BtL$IFp2&q1ojLa zNo^qK>$X@8eldNSDo2KTgeQw4u&EtS!!KRomFc~%lv)3UGJA#|qQ|p9mPPX1%K+=h zan%pg*bQ?34KjvkzrKMO!mxE0VhBZn2g$)C4CUdgdrKzA#8fVJv4meX$8+RHPxkozkEy!(1Wo7&u z()O6p17hcJQ4|9_S>$^hyKbAGPi7x6n3u!sK|?%xe~sPUGBrbWn7&YzLs^KgMp3x8 z1>yCzN?*?4SFe2=`qBD@?l#1K#n_*SM6f*~4^00m_KI)P^SC0Nx2g=J45?EOMuTsTn7>BHTUi=|;Qn+RE(o7VF+(aKL_>1d1d*_Ei_*T; zS^y=tB*X3Gt4^gy%QuF_E6`7sFDRd*%0`>XII#sKn?t28ga*Sg*X7QF-tMrY`=Mmh zS#Kc^FTy_i;V~xl&6i_*3yzHCqGY|7d_-y*8pLygzS$WrX6z|b>R}Sy@a;impqSM# zEt)2R3Z%m|T?M-xl2*0t13ipMi#Yhk7O?G}fx#T(#06JK+&{sh2PlCoc-(zD=3<`f z?ffTRh>gz8p%l#7fZD{7eQB}5p_PBFZE8qPq!*cNFOUZ6;nV#&QcWZ6UKj8uHWw)q z|D;gR5MnjpB0emYUAYd$`H%2dXT7x<^|yFO>dU3VlUCuGiE*;5`10@xPohsk1 zJfZ<+zW~Y@3T_O_AUmSv{}K9>x3Cd>K6MPBp=E`mLEL#V)mfxMzrK?0B0RLlXpg`3 zwNQ5O{9pp@`cDuUGngP#om;7QkcY5akcK<$>?)9{E10@HXfbRlX04fpwEg4H8(2`q zIYCX!V?b&NA+p6X+c6H^BFbkMmB3t5i8v2}PndqZCqkM_> z_LIe>+2jb_mrz#c@NX2KNv?SNAR3`8s6T$|ihcQfl5j7tj^_#F3@m4i$UEB?2@JOD z6{}g0H9HI;b5{*o$7X+87y9&%-_OKq!QQpB`MD*-;N{)fphd6AWx|kB_(7^-au@zs zIT#+GquF=ouMmpVn$YwEMId2_kp)vYWL@WMxR%y;ccoMRy5}!2i>k@`skBwkGjtF9TVP7Kyc?~%N zYJ&CljyA6uPd{nud*gN`ln(J~wN{rvbH+l_*N2Lyj4b|Lu>^;DLJOtaz`$(=J)ZWA z8nQudw6*E{IAKWukNnzn5U*^bV z44+OH550HpSWbzhe`Js}#5r>t_3%4@@%WPyTzb1Pay8GX8`>*Yk+O?%zg#d%4LMLY ztk&=?=@?K3s*v3)2OSc=K5n+glx@K z$ON(Oe)%u3$iu2{FgTJZk>3c>poy%*MsK>pR-{22j z2+#S`F$08;*gg`KeC>5$=0D9O(hD_EN6}DJ`ZQ2lWLhG!@Ff)v43R5iGaLq6BXdjy z?szAY$vMWSV**77=a015YqsH{OFe+KaOE8@RqAJ|#?Zxk*-@V6AK*sh&bH^e>cLA3 zlEb+-{!A(~G&flZ-8VJ}2P=<}QolA#=L2V|=lnT?xc4MrFfFHm71Ae5t#hf@>?}(I zkVYP#o~hCVSSZ}-Kt_fSZD7a!sqJ#^9ZRlH3)qOJhJPN`8ho8i_T+D1- z*t6`k`a6@s%?H0;Us~X|Apa3Nr#n^Khpg>a^YAprstCdB`vNX*pd<#L;NUst zL~{sWZ|S5!8amoFbQ>p+i>J3BRWnWjA3K4Sh#cLUCzKPWHIZ??$ZBL(7L1B;x#LYFHT{-Z)Qf3f9DU{`$@ZPNV@VUW4pG_oW;hRvS{QQ|UA zlG7?-5P~eVW;Wg)_)M7w&0e!S*VMj1=J5BnGVpEbvI%WSPI=Pw&WwE}bKZL^xKnez zyCc4}XzHuAxM>-WlTx>dXZMa{_L=8q%Hrm+68E}BEnm*$d%eT~lhBO@Ak|&b`bbA} zma95}fvlM!2Qy@1)&EZccKzytiJxU$#6q2`$`;X5w2pTq96*iyc3f!cnzs2~G5j{n zYCwVO-4Mn*f#QvUpovcjfxY`=Hx~JIOK~W#QiU#`;#MgCto$DA6mK>1+ndK{Vi)vp z8Go)h;Z+-|l|MvCeZ+#&_b?#*Ow;URsPEU%qGf(ietY?_(C#`Tziy@s0k5vDSWj;iY`(!ms;Q ztplGs58`*utT&V=LT(t_YOb-z%~dhwO3m!9yMlj1QN@m5g^GK6_^=;p?;h_``w<|L zv{I3^Vs&?%{T|5{Uu~PK-?624VPmVeWYT}I9^#2GSXvUk{UEO^nL^LsFTGEA;P|1V z%U?yJom_-t*j~l>_$mKm^QPmA@X3{@@hi$YB97<}fwItfaxvdKHjh4hBTs?L)@Ni^ zEs+}jkVLs;kd7-ebv9op$7ir3)w?h`cxpn3zyC3~TPSkt5AcpLgM1=8^G;vl=$%72 zGMlG49X(}jXNKgUN-u}0j!yhb9!xI zJkpNCx_6R5H|t^wSy*sc=deCWg2Rb9sQ$%5>pHE6Yx3V7#i%P-evT1fpA#7QnhWfB zFlRwzl=6~b6j{~gZ4TRWcZKH${z`btQ*d-wI8n$Ja!%l@iCPFvcEbzwcS@+5LvF=} zVpy6{9ep{$dd0kp$EUh7(emH$ z0aW!@Rr{q|=Pj+~wyk~QTLs5ebR#k+I^)>}VfOD{j&KsdM*q!^3<~y46o3PE-@0E! zq=70phNXDSlV4d$7k(6FLFu~}Vn+hbhJsG!yz7-7&+`~gD_78>BDq7}-K1{9BeSM; z8_Qku&m&O55qEH>@h8|N2OZCiF8`jg=^uze?o1a$ao&TXt$zLKw>}UP3C_5qe!qu> zVLB>E>rP!WXPzQ6u5NwVc$ccALv9Kmlx1tQ^Jw`_;tqQx81h);znOL2CPNQ?Bu08a zsL*>P6uSUot_xDjo+COdOChbcykwd#^m^-UgTo1L;zboPys2F@^L8sqYKxVG>`ybo zRlVfX7>h>uV5_|m$}__3E{mpoiDi|dG=RC6aLI0Uyyw1-CmiIx1OOL==82&pqzRs1?F zBe)ub@{zi!{a9=Ag#LTk z4&>DYgiXLd)?XwL^mX&$;esnpm2eK8pq?buh{cATX&PpbZ!Yrdsd*nezj5;bXfaCg zIblkoa$E<1^EYegYBb?@J;2hSr1}raIc%i^>dwG_l{r$nlV)wtIPiHuXYZUF^6VX; z_tC`u>QFDlkhMP!IzL6?iifM(i5~nt7jS5oNX+|3x#sI#jby?(bJ%O&M}-92?M{{f zU3n#?xnm63)UWIe1`gsSQy*x7K2O+w=AfRdmFG*=1%Uw}9+Cd==6e$1CiG}TyO|?( zL`QJ)z`{ZqCp~2D9Qe>pxT{_ zB*h%QMV;tVYi>zZt&qp=K8ik3e5(K=4iUHa>jh@14||%6y;Y~wNX!v!eiTy(u&Rl|Fd2dL;P|k~|-TmHI5`VUOytNkC|Ew5R1Y|Sl z{P9KRtW`HTwTROtTV)etZ?KSvLk6b*z86@JrN>bkhzg`fl~}YPvz0Ekw!o_WEa+7wecu3tI3Dv^_SKUGjtnJE zxjyKyEKJ>h%_itKBHAtk*-=zI)Qh3t=cMN5G301kY7?`-`@_aS&JER4E$Jo-w@f6+ z<#c$b-lvZB7fsflxD6Y?vlWlt8=_8OeP<^+8%Hjh;K-&w1siKM+$yT1q^i(xD*>Gb zpX{>wBXna&V?nwQThSULzhwCsvgx}skie6v20PWVFr#eL`G&KQ^TV3am*YEx-_Q#8 ztiFqX^^$QS?ku5Y<}$;9U9}-mrm+|0PDJC6YzK8yxuiaY{(zC2=bcE{VZrHIvnLQo59b!G3i@r=Bg3 z{Wt)F73@nJ@PZXADWy2q@!)z>#ycX#@wDWWx{`d*fOx(isqEe$*TbX=TgGhRRGUkT zBJdAm(ludC+DIwNZ#mM2^SwdN--x6@YC@-E$}hfbq37Z&DcJfgoBbIa*6oj4+AE?e z%Ms{~=kW0GZD*y`=C3*5GP_S3sJIqb5O*A)T6@a&+K4Wvyd4lA03@vwiJjCMJ01$I zc6uF*`R=(Wt3kh|FD8tr7{>z_RNHLUOsdgbr^qx_=jY$)c+U4*+(DF38jm9zg%H(k z+_n6R@3Kk)FA=t`8NEpFQ!=bePdYrnW`Jv6HBNoc@i)4)@2cF7WO1#{u%14-5syo_ z@&0-6F3v)zZaFGD9B_M|YQ^vcs7aq?<{Qj)7x4*y7VjJB4$1_o>W%_aYMU7lkXgO+ zs&7s102<>t|;wNU*nv@K~MLr&c+oas?m!UGu;e;uG-Tb~iTV1&i0WO z`nq01l%>C#qDojEJ1h9I;2;bvOXhB9SSNVX{{9Yp#>xbsD~$kTgo)#GP8(GxwepSE;UMgs++u$oB(ZP*FD;in+j<(!s zC8;%JYP76Y^|zYWa(e(qAQKBnUFSQi!xXuYx{s}p$3PW*@z1#6eKD<_=}niUWQWq=S4&g$uKDYNrzv(RDfE1wB6pe6Ol4h6TlMK5v9aYXF(hPC!e zbjYa2zF@qYA0Ffgy+W~SS9gqa`}f|>1}|Is7PL3#yi zO$KHqI>J4P>XQdHWBXbH!ehknad)MTzXm#2B(wPa-jLO<`Y!fY*(MB-zm4L?lW&_tX+(_aXsHrP>oc zQOk)WTZqxOLQbRZ3J=|PjmK=AdYVGe@Vp#>!qkE?(9EeM!rYv}Fe|~um3_}j%*)26Z4*V4!;75Ih z_HF-RskTVpehh!M!N*4Zk&tTx*;-9UV?fv#_zBWqJL9upR{@ugzi;AO7dFq)Y9`@O zA{=MePRa_>OQnQ&^)ua*B{I)3J2CqzfPClv?a2Wp2jiwVk-#UiT~UVC!+;@chzi#T zJI_v%t`jvoG22|U?aDhQFD%Ktm}q@^e|xMHLzzw9mzs5dfo$Gq+zr_$qoM6eY{G%AJ2P@B3ck$&9ByLF@PV1 z#3JBAv1k3;XjHY?!ymMfR3=+E_=w;Y3)&72)OMGJrKQ|lvWLsS{fcVfRB;h(drt#C zU*a6m*{4~&_}$U(R{PW^QbBGv|d{mXV0)q@yZ zcvUbwS=OxphoDVy;t5CCqf~L;s_oZGt=>gj$urHBX9O8kLz_8N&KAOCeU^jkrY9?` zu2u^-2b@U?(7$c4<2!e6v#~%1uzN=NBv75d$G=MlGZ67AtuwtoKXOMu1U>O$&83^C zp(XsM|FNZ5^-;Xnc_;H0Mssd|>4-UbK7CXWCKoKec(G%hcImYJ_8=F{Ayl!w@l`-~ z=t6QdYP94KvfBWj4{AMEoMK_W&K81}L_N?b@@9e`v2Qc%n`KzG`sk8NPc-oo!5L|v zo!rA>N$p;+nYguf1J*%&G3s7GhWKcHy!x}n5V0kVIe%Dk--QQZ!-0n4@di?DKSlP{ ztfRiRa;LX8to_m4-EYG1J9hgRTALT>fuPxWd#@j#q@7hrwPH)HGxb_B3})L=mY5{K3=Pf>)nF> zP2AFfGXe8>Nc9T>WJ;+=`S)tc&WPi77bID~3_z(e0oHgvFG%j%MT>t+Nm8oE&Py zjz-{%#+_^wneFujal_jw>EjMMFR!{Y;PYM3WB+gCo!r|Uoz2|*Xh)>uO2A{r*5%qR@BZYT9erA1?XQH8c)DdegpDg312_TuzMh~FM)!EAXlPu%^UtRENG z!+giRA6dT=)ig>Em2R>+0FrLR-#_b>u8n`td}tuLRjKSm!Chn&Z-u)j4Xo0;l)!if zY##A=0uGw4k%;$B14fJU2$(?YtP1qHJ%wZoa`m$0N}S2+TD8g6;6Rs;`cX2a(VfSK z{KLal|1vo`8k*D)NSa4We5*+yqn4O~`ak02PNfGqqd9J5rK;f09ZumJ2l%mPS5s5V zj=QmQ$&j5vNW+Bg1l3M@M;>^$8r)7@ei8rOl}y4rWJmP6z1gG}mnL({LdeRMjIz-7 z1sXS0jWzY4h?In6KOs&?d{)8brbkfXQ%2)gWpI;esOaL@qzTTV^jNXxKj=jqIGvCw zd+FEmmDBJxOi&M}3!3e7=VOb;`g`)!kn|GVtKuv^U66uSFy`c6DfyVo;#AF}c~L#4 z*}~J-7Hc6(WlQ8u+nimXY@)1{V^GF@Iw3Cjj`m9XA}b(vLDzw*>y;|DnJF}qnmq)j zbkTk($%SkUjDb#2ET!|cCo}XXGkp887DYwpC~cIHY5HNc{<9A&+X9+wH%Dwp3JvjL zlwhtz(8n0aQflSyv=-nXwW$3HJI+AdTw}K*EiS?o{;eS0nu*tOClp(abfdn3hJ(c{Q^8MmZJxH4w9{r#1s=Yl)JKuENyW`* zp2(gMNeg?4)T#C>BS^odurJD0ED2;Lk}AnnS0~rPPJGcv|K6xaB*2`0rLgRRDYl}@ zrGWCFjUKN;w4VgmmRXNMjTZJ@o2f(nwZ;%XI0dr>_H=2DNsic3mjpd`iBRP#ok@1< z8s*hdEPCNheeti*hmTqBDXJaRX6-c$+xDFI-fz2=sKTo$IM^?*;K*nE+R3+cqRwUo zDEp}IaoVzFA@9j1cPg`>&pqg675W39dq^mZ!{@yt=rai#BVtBGKIxsWI2E=Q9oe-b z*}vXj$AlbDheyuU>2dizlE*~kE8T|}TX5aO9+a=VE*UobD_*3(Dl31g)h9lByc400 ze(|W3ud1XVoo5YyxO>*XW=~OaQ!~@9d+q;c0m`S=;*f60c_?ttamNNZhEL#YflxqW zGh+;$5G?x?s?X>kq1RpL-0<3R5I!diyQgtH$sFT!BWR!H}yV;Cz`0m{8-VJN1in`im4qpjxM$|PW= z`|>r0H~azLVfJPD#}<5B;68`8V2A1mzuSyw_Lcm8M2zgjX|dCxh_UJ;lK<>(>Ol9f z>q|ZzgZsltV66(Qyx8_w3tq)|w3ItReGWFzzBl_E2~Ac! z?R8kEXYvtnIU$dRvah?+8;RL@bP4sa#L{zja3R(KTBx}Zy2=qO?cN|ynD^#i`3?jw zIE`H&4LtSkXI05?3M7Y!vqhL5BDNi$iEidlz)x}stEXcRVhIQA5eKok7f9<1|6{yqc zM-z2uuJ|$<8~&ZoS_4j3q?T6s$MP1uw^>6>Z>FFv9m8J9kWHLjm4u1DERo{8LVT!r zfBtmW8v}bYpeqGzS8W9AK)Pg6KRaPloArw6(-F_+f6l=PXYrIlKOPDSYqCBSuVWv> z4R|F>wWY$gq5Y&KfA==)4e>p5SbutNx(}-%#Oby&=@MtZ22$S`Yb0^GI^ER9MbYIH zz9;tv$k%=r!Y3bGyI6WVkgL_u3hStQ{Cy;}*g7>WrhXnVF?Q0x8+=eJxS68)@`(%m zir6=3&vRYi`QBA8B23aduPqOf2!6x=zGl5aQ3pu12%PyVOh@Op`Q?#Wg~>Ng=A!{_ zQmo+T`8n1Zp4`qH9QJ3IZyyyk6bh}+gS+lxi!dN}lc9v7V# zi|}?i5o`sHYydjLZfIKZGs#b_+j<)#w2860bh2V^!nM6gb0g+%e2CP=39q&mc%c_5 z@vHVb8;l8rpWFU1OdZB!z^yBQJoz)x(9p+Mom>RrEt83E{Xga;@58hRxAV-pq`END_n85DOLZU*02gAE`jurUK5g%ZPcphg9b^jfQ}gZLFWY-@u?3JVTUTuA zK&m*hSJt%KBRL{iW|)d2O-M=O<1(J}ft&NL=U%uqNf$t{8GLlbOJ|y4NSb~~f_9ST z0UD}lo|s;UD2eIRR}lE-C{>iw?^8_GF;=L`SsPb&v+-FD9sSY5`Cuxx;}nx$O_fjs zxSEM5@jBQ@^g$-G;4-RaX^pdk`CFlox=;|zt(?V+G(e*(A0>do=~(yY1HalLkfa27 zx_;;zvlkki{-2iGI3A4SZpTK{GU{{yH&fx^SGo-+@B{-o=Tm$<_bO^?3LLK$>bk?V zxN{cya=6oXxWSt#KM=*Dppgg%ho({B3a^9YVTX&d2{z-=wfUjL#^jAMSwa-5n@z1(60*=lZ*AmDyCiz(FY zgrrzoF?m`sFSqV%D0W;vDE@@QOb)9zZ*}R~s|0>5TdKu(*;GzmDre%5&n$_EV$^M| zgmXrmmrc(D9iUdai%^8S*R;r4(^SHDj&Nv*YWr`xL_d@nFe|T0b}6P8snA>5xEuPn zs9%@p;c5cLNEzm!@t3n5LMhQQJ`d(3g^@@6O{@AOy~2K)XQX69Pj@udC8y=A3?GQGPj}2SQy+48wm1!H za?xP#Rvnb1XV}xx57Jsyokmggd(bLPHgr)(4H*1sCT={+mBs07PNb!8*6cr+NZHC( zr4OlP0{&UZV8iaDxrTvCxr3-hAM5WO-?^OwtG^jc>VS6$bnNzB_V_fd6|eUV;RmSDpYts!pKP6I#Z-9fVN<9^?Wx_aWpGPvFo1rz$*1dk4W!$$ z_3Yw^&S?Dx$qk#ku`WtlsQMyYjjh;W6E3Kbe#_yo>69aBYrZZILx)HHV!b)2Mr3_= zq?94yz0OzbZ-9X=!BK#bl4xD2q=mgh_3a3#lC@36`p$DsM?Z!7_9>8#!TnrJY^Q;q zw#rvN>U#j#ldfX%dwCAhv=)n>6QY?q(SgPSYO}xm$OQ4D+l%fpc0SdX-jiqzAhIa1 ztI7@jn&}>I_6MK!^cYBKo>u9E5K*C)|26waaM3O7aB}-#6L)@vZM7$O2&hX9O#Pwl+#R{AEcT4W3?|0m& zUi)|c>L|^Wx7903zqfrE-s6DuqQ>D$;i1R{@}q&wI1QHbf`fx!kgJQnyq5>*x2`Be z-iswN8P~4aKnns4?z3p9zdi}-y5B6NdSbMvOi}g|m=tjDxlGNW??P;r32tFS8-6+C zO_!WKS+UEWCyMu7)4vp{*QP$)72uyaJS@DcTxX44T28nNPwo`oRDfo^_H#lUS{IM1 z_q}(Sylfu73{4mnElBG*rs6E&2Oq(j&Fh9i)%nvEI6ZX|wf?<(mNq?T4-DPoF>S9H zTOp6|e~lV)^}_Y$(+kfKOEEY{JevU5ktM0ik>vIuo>ZR^(%YxJGR z-A7GQl{29|e`W?uD zds;o%NlAB^3fZf~c8-A6tCWFM!ljad!{d_r4jaN$GG&^d9qBSlCe4djT}O35`mG2y z6S+U~dbDy#<>H&mVJ<2{=|s!8DIO9qUMqT5GFYA_)_K*2*#NW4%IW#dHZx60 zjqFlFPe_&_Os&iVg_{dg8Mlyii>+*0!P}3Hu8@BqKao&$xhYL39rc#R@Vu?vxWduj z`ol#>*g5c8RGB9=A2dJzmCQ&riHp(Ltl7^&NtJ*#Ip^8|QGl9&nB=QKP33P#rEQzw zF6)xo%*2x-={gz6g|4IT!aB6n&e%jNQgPRIgzBotY|EN8@#Wgz(N>K@BA>C^GGz+1 zznMN7rT06$MxzzsCRe47JQCq>f4O*I_hh zCokgwJ*{E8j3V8QO*_tb-EwDZ6x_ z|IH(Dt2LN6J)|1-ESTSzlD^vHx5flDN$ut?;N-^y`G0qQdpmnBKl{uWH^eP2vKKq7 zrWQr6U}YDTyO_G(x`qf0 zBI}y)r`Lt{cVocXD_!oKtwNL*bzyaz@JMiD8QiuGHg~48SF@n<1`ni;HBQ<1g*da$ z>CE?Mi(;p5=-U>m$vY;CUYJR|0$wFaPAE1n~WXuY$%L z^d9mpn=*J;f}hRga;U@^4SAgq^^AMuP&y^pJJ|}QLhh+}T zlmIo9{~sOo1%0xf2QEF+vV-Huvii1}f?VZ*%thHR4006P&6gFkD4)@C8Rtyb!T>c6HctCn+8H@pzfxw`<_rpT2`b<6?e`65Am@S7?)<& zVfts{wQwhtD46nYo*Zh8W29u93(5-do5sLpgj=Z`Z<#Mua7M~vDqUqbwNw01bBR>z z1WwLC!HeqM_crTq%BSPHO5L`nvcNDk+3U?NjrCr^Idl8zD3_vz0Z#n%I#_GczH39d zSnEUt+C@{}b#-rBNZWr`^>!=uzr?7M5FFxwHW#x#w$$I0er>EwPe~!6*M;@A7_?F z1cq8JC_08+j8!OJAt+!m9CJ?5uYAyQMS`r{SrLq~c)6h`CskW!si?iY^`jXf@au|j zQ6)}8cf>+s^nFY%*pB|BF5C_gn*hE`W8MmkG^{S{4$sY@=*$+4q9YB)ddm(&ef zS%-E?E0$$oz%Osmjci$~`pH_qX^*yYWY+V)3xxEip+3B&x>D8VVPJ&phVWl}i&4xd9*8Do97DCbHCmz|6T zkm-Y6jBK`;$lGiGoVgoW0f?{l+uW)E)H!!Hpf7v~c%<@hx2(0Vo>~OOUcVc+^lSd9hpDTYEMfVNlBruyl@Io*+#Y1Vr1aWI#4I0H1uoq6tD-v! zw-m!W*h_u3GA^ZopCPHP3CMWjEi_^mg`QE7bpW@*%+4 z`IiMd;XQgcIeZw{M*jDUIsJT4{x^6W#tk4jQ4VMu-Lr(X>JV)vW@wxAaBOBF9X=r$ zI1yhZcN{Q`kuDJ*UpNMDA0Xw4G9_CrIhi9Kzffu?l7J1l9~vLF6ZlT5#WZpfiG?~R zgX8`}+NY{!oErC#5s6i98}pr&piIgBsbp$+S++6eup~aUs2+$FWMIprIx@B*+?ywq{u8NXAp{u-mIp)5YN~73o5X{hf;N|Eabp-uNN&Bvym4=^ z2>F;b9D>$DpMq-9v3{0v3%d8nei5?&a~_B5?$;49D~ZdZU8+T}EAE2v(|8M<_hOIZ z!COUY`F08Tqck+VPH?c{QiO}V$dr@j)I1ZV1l|T_#2x80h@s5DdxSSD|EH}AVVoXA zU*h5yWj2kG$IqLmFSGIm_&}C54{isIb{BWF{U4L9JvxT>uJ*SQbgwf`0g%4ku`73M zS;BLOs5}K~poI)xZ3>MlRSanh8I)}p`4!gnP-(R}aDFJV4GVlBd5J_tHj`7bJD%nQK=o`9(}=L8Vaeoc?H2c>A>Xh4R>*tfb^DuAfK zV|aC@sPds!51IBbmy|)KREw^Y+pw`^Te2T8 z@T6kIDQ+G)Co-oiV~{J;qXgUWOs#?HaS)fcwwE<9cAAEIfUpxmCOW|~P>frR_UX#{ z2HCSeQm2(saegHq2)Ly38(|R(`n9!pwGtFVORn{0NnQa=!Uz2PnTq$QT}6PP-!h*v zL<~$W)|`VPsx*Oleak~KwSagq{dst^ihL{TTOL4YYw-m?cfI`HX1~Ef^zb#vSDw<% z6V_Kgex*FQu`!J?X5wDh_rpH2|0qvHr%4?PC}U@Dx`QW4i^j9lg^E@E-*Ji0bE_teT*d;#Glgk1md$Bj|Lnq_1*-k#gFzJOC% z``iS!l!#|wU7j?|;$+kd)s~*`e&S_(&h^vel>v=|&k1Yi!@rwOU%S5qcm5T}PulAULf?w`k`{w$wF8j!chZj!ZOMUkA>-c>I zzCUNn#QY}J>~E&5tM;==q{iNFEk#Gf;vr+2Q_(H9@+12vk?I z37yk4w!@Yaaz)T7)OTj^@E(fny_vtH7S`7H`MMa)E$E74oMHO$2*R4u)Mj$~#=yP( zB{Q7Guh~Y?Z>;?ns1Ky8l-k$zN3wB7A&qaxnAJURt<$hY2T5d_S9e8BPrEjmkBZ4& z@C}vCzO56P2VR@Kkn(q`ndy7yiw%PH?}s)brn!2iv=CmGAJFqb@6Y#My5xoVQfi;vT#Dqg^fWj|ZjO|wK2C;?DfG9k=Q{9UT`gU`iVVZ@P&c84)zV;BV@gmVjJC6_?}j1+ zPr<}TO#;s$p1&-CBnv~ssPb6psGzXj&-JdL9#@LccmV>ds8BL+TlSx$Kv4xe3)7RELCm0T2>!n)-DA28Vsp{{JSxC^8gRlt7u zJb{$$eE>BdM_q1VGrqR0r9V|+g|QHVJ_jIgjM;|YJ7qqcP?3x|>E5cu9>8gtp6&AN z<`((p&t2~9p`IQ&I#}E7r$i9Fdk&+L*{eu+BqO9G3V&l-C4dlCPx@l&~AlrR&fK#{YW8do`wSPSUCNngpIe6fTv>!R^82tX=9P+sy7p=K7}dAYs6o4{s zk_@`Z&ClfKzlh6Bd-yl2evk)ONnBjda_NvHygYXKanJF#-cRyL?T(uFdM{Q2Noo9d ztVyT71CBRFI*C{QTNVl#)3%%mDl3AZIdaK)+R;EmUteF@WH`24KexZLv$L)pcGHAI z?S_LVMF7u#7$F$#Bo=zmhPd{@y+P# zu%?ms+Oq_6nV(D;v8szhq&&5=iOHU6GbLOpN!)nIt}|#d^m=AYehp;hHjtwoQ(u^h zF-QsL*pQ$ml>Fk@=pq~aqWddsRw{wltJy;Za-`#M=xq|66WP`?3s3aH@`Fd;e7!Pe zwRjO5Pdt8f+B1#t3`u+OCjCjYb*7AJjOqe|gW4~dyj!K>KUEfb$NzZyAz4Z*OCO@Ej$v)t7Fs`U`*`xU{ zPvB^6OyL+{<3dh?0sUVI#05TeoGx0=)Dvrh`H>&65pf3h#trlI2NRMmT% zMJ5JQUni{+c(^#w;Z66Okn$8j7v>$mtT6&f@I(wA9yJH8%^W0WAN$ z)|0j9C;Gb4_kglEQieypLcC9?s+TPvT!!)9u9xGq+PsUi!*Wh5%#W%M`avX%zbtNk z+6jQLq1>j249?9(m}>Ko90EP*ku6ps^Zk2!nGv}i*9SIg{4#r9U)t!%nb>L-pk9A{ zd2AqCL`B-hc_5-s0|}93EPcbh*q7jczz#MT{M&A8OR>95c0gm&rOqy_H^@gpFqJwI zIMRF1S(!yWi4FC7eMvsssuXkm!JedMb^Nce7Amr4zYJ1)n?RDSw`RDXEpl+(Kh>Y-1oWxo_)$h22}fVK&WA}f z?7ga#a+YWaadM`ClQ+u~J(JaKNWRLc&MyPhLy*I{_wysBYX6@FaDIUW%KOU7MTJB? z-s}&?-HvaI1z6qF+EO_p(GJq_J_a@ZB81(gG|yLZ1K8D6VD* zi8FuR>RP`q_P8x_V_)_v#Ngloh$i!9bK<9yWM1~Bcue@ce z#YvzX+ebbW*(*3sS9#>}U-BeQ?~Wzd_80o8(2IX8&YaKb*#;Ri?P$1KiE22N$baepEFZ|Ln_BmIbax0FK__BSR@= z@!WT-n;GHH9iwVY!ITKx*O<5C!kQz3#ura#f^S1ZanC zDzEML(zAp%X98zf--mAq^6P=()EZ)LO?2c{MkIqg_BPewjd*lQ*}qI234B~|`%ffT zs*wP#z+}(7J|1F(qnp%0pSnQ8WLSbas+!U7Wx8A+EquL%*ozs7T#F=5#e+%!ihj9*HpEzb_d~-NrbDQjJt(Is!Lh%vA*0p&Mw2ouCBc{Eg^9LbK?MDg z@O!3?znZ`;kFVLhv%#~HiskmC6k%0rHeW#0QG2ZTRcT79WGY{)U@&Cd)(}dc6RXEe znG4hGCoj@Ym1Ig`t&V=aKaOfVnT2a6Mdz__v@^$K&DYu`8b;x|;tP@}ZPRG#KMrp4 zjtCe{q{WdArQCw_%Hor9>**I^tmdqD4dnc3>ioVm&2=x^$+~KSGdi~8so+)yp)p<3 zCC9I(J_m+rqH6R4P?@Yb7gY!T7}(C)rV6cRe-HwN=1<$RvKdoo)Ufi$Tghm!8!-Xh zGlNzhC`~$mYJGO}#O4j>=FNUcnSDPD%=t^|fSOOrG*_T^vTo5hHgK5EyRx?i7M5hrGi{CZ8 z27$hu9F1myD%bpNXVBUUn@*uoAGg=ar<-kXvr}R#3M*=XgT5YBbbm@5r2My65|6>O z2B~H{ES_>2M)wa9Jxw_m(W7H~fRvssPI^oMV`PfqbyJ6v<(>?{`brEs@D`!l3R2!VVmtCTukGo(w+y~i_d*a zY6-eS_VBe_9Lhb+I*W7us&jOQT)c{E1Wi>ewa(+Mc}urfI{GFxwRVhnv(8N9{bA_O z!q!W2HG+suFE0cPENkQAVLX?zkovB5%7UST`E#X^xBth-9 z22H@4oCo@)ByY9yeko^qzrH-$MJC^~bet>?P*7;y*Sd2UtaU6%>LGAOxcixJJ>}SHO(j@q3RN-m1gfqN7gz?EK+efYJ{JGYAf{hMgCsfOBv(vec~GeM*j*cxg!C1P7n5RqEe$%k*($Ah{MzF>Eamv{WLNl6+~yz7>D}qkt3mp zj9?8hp`<<{>(_wUx5^-8+h3g62L8;yN}x+W=DL{{A*cW5kf5ik3>0$ppe}F{IsIA|GXmKA4{KWaPM6N{+NR;sbuPh!2e*kISx}P!4+chyvPG1Zv z)NG)`pRtfNwh^rc@RX|&a8l5LiH<3^|HVozE>F3X{0g*ZcMyCmnI!;#*094NtZh}V z5(k$#k*ZRnW$JL%hHD2fh`Je6HlS0R|1k(B?VK3g)u4gHB~;I`d7#az9{^(+DOP>4 zLj~g@UTa+^**(-NhqT^0_`{$uUH$yZt4h&`gRbNU&7lH)Pi09%A@#@t?l=>TJ9u7| zVHGAW-?!%Q_iv0X4wf|jX!R8WZSRk@Ra`taFNG4Uz9oBp*Ab(}6W7v$v^QiK>1^-c_jI@PUA4-n!0Q#J|FhoM*5bW?37&!h z)zUe^f8hPi3#qV!NgHsQnO#J;&s%(Z((hAr!O<3{0VtfpeL;V2M&e5zDlL<@?s}<6m}Uxz|M^5d zcnlGtrponwkbC(hoCk9H_KrUHZ9oL>Oq_KM#xDCK#ee+5FM6)0K5q5UT2wKi9fE<%!Ucuq$kq7i&@xvC$!hr8+ZOy* zU*UO9QIQn;JL6XNr|)=spq%mw#$fE^c_}l<@+{d*t7D(TY9lTdo>g^IsV8l3ePwGq zaPtONFLR8A*3|1A1{SI>*QQ2lniAiS09ui(_W!;cPtKgo&Yz zVdr+%v5(qD!?^yhuf#pJf1>1Me}e5`9fjFB&0akdp*(-Z(^IKGyL(Cz9RcCbs-RaCb8McvxaxB1e<4+`?Cl(Hj?Ov|9Qg#~lfdgQelE ze&v4Kdi5^GL7g!h%1s2F*G)$k_T^0Jn8OJfG zWGaZj{#ZBzk%Bf1X)RD5pGH~>7=?9!Qqg`dC=1}54SchKHl0LsQ_Q*=!=}$BYmUcA zaJ}6}%JjM0^!dEKniD3}?LLGPOo0jB$&ci7Q z#(%lY_Wxs>%2SIfyxiM8>?1;f*|R@*`)47c1!mmGN=Tg64}TpNy)3CKK+&3)#rJaf zUXG-2h+m|hZAmMFvOVe1OFkbLPW1RuMa#?5mKHJL5Ce++dgMM4bfiIAxYfHT{nHG- zsiRJ|TCDm=c-Ot8sdd;I98Feq|Sn<#Fnj3?eoZyp`Tby#`-daK6r2#_E_mf9dKiLDKkB|s?0jGS1Iw=6Q5oMhs}mM0#c zxZR!cM2TbhOJ*hsNM#Y-+OaHKRRXn9q}0>`QjH== zf+X;;boKWA@v5pDAgFx-sJiFipu6_2e*Nmbci+8t%gDTEPh4kwx5m`Y1j;&kR{hu_ z5uB{c_?|MK<{56gW)kaZ!RXk9V-t+Dm3AqOYrJ*SEc@eeAj;E$ zlDdXQg*IvdG24M6W_!HL_ic?Umf)_Jki)&2(c8N*sHb1ZeK%$B<%}CNn`VgYe*k@ zOHghxB#j+YL|O*me3h(kd)x{)>rgW!F{&S7C28u3s5#BWkUwm#~ro^NZAEL z5-({uyT_T{ITftaN*cPUBfRT!vJS^Q1+BkKwedAuBa3uHIt zqLnl*GbC5+d4}JnlS9O5l%lLll{sYzZZOWU(MmEivZ>`f(~R#q>m4hJV+$Nx&=aZA zS88yZQQ}fVamvpWj&l~xa_P=G19h$tm}|!C|hDHF4$cjrxer3 zbfn3;4tw1qcW6C~#(LOMn^O6*n#z~mQyC{8*D>RISU@iV3=R%?>Xon^wHop3UVABm zB4i`aV;^5Z`_Le}262kUW9Vf(0{G^w%YmsIxbizR1`s3e8U&iE8oUA$ys zcHYUd;N)0vawL`^Ugte4Vt}?~@?T@ZCZU_egiYi*ERUZL<_?Yp$Gs40#l18s)6>(~9crRes^YTa>=brq%Vet#LH4A>o{4eH-o?+_zpjojb^12ioE$Y_ zQ`bsFfSuD*m>YB|-mwcO)`DnQxUrN{ z)V?8wD^hS0WYS>EnGxhqo}jo_qi3}0O*~b7CaB}4>PVx`mXR24s*bQ?T>I??)FAVP zro!L2R8l(Iyw8RIrd%KFqTu$cCK;~Ik^d8&JFnCzIdLBAi?);ll|QUer;P^fH0_IH zC`;om6j8etl`s3$>(s{BAA5PF+X*kk{y1#2gjgx%HbjV*6TQ6~fk;?xS149BG27R- zng0H3IeGFVhYmdw7P1hl*GYB$aKyjX$#hyIvuv4 z!)kVJ=M0Indz?zjrNb7S**S%7>WfsfQ#($3v#QlHY0NRT^BltNShU@8aIz;E-=hYZ zs-x?evpZRza`|X#hO0_3k|m9QGj$erp5v|*oFNiq*EW^2$v`!mG9=d&p5_kPIdDfW z=gjq7nLEV+IuTYPAZ7uy36Mi&gspj>qr%kAig(O7+C+q&(P*HcbyIc5_xS4m9GDd1<8)tDGXO--T9dte^!G^y1vmw57~;N2;1ZqQn*Y+wSeqR)m@B+Df%#Zl*m&IGF$w`Lu# zGb9gL0=>n?*iWAKX{J`Pwl#b9n|Ji^;0h)h>|+A^nBbD+39jra@y6tn+;qwP+!ylyJUr1eSK+}j;?4o#8&mX7&No!r|! z()Hcy|EQ&MWc{1A_rDd%|GSR)Z#qU=QaYuPyG3nVI;|=4_MV;>|M?n%RK$fEj8tDb zK`vW}*Un{#*Q95~5);-1?Tmqdl+7+U?3Km90>2dtPL`@Pp4Aq)Re`%4Iopti3Ilah zo<;Kc+w5rE3BqFEZ*9TJz03P@e4FAbO(M18mHbu<4MhkI=P$828$LX79gH3z zRdE^ZUR*9p2@SJX=k5K1t>61jK*E+18avKTsq)}0i%EmT)D8|dhWWv!BcxncStNVw zw@+TpWcfyQpL<5BYb8pa&GEh`4{=}jG~??YqUzmGV_x$0Lz)&1CVW&~-dK8|iyy?$K-Ra`3Q`6}s*-`^_( zb%sxt*?IjG_PC&QPOaN9FvZ^gQpDWvDdl@yuKu~R^jwxmkyWy~TjY^-0>UC2EU`A(`1d z9%R%4#3wZ3B`vT%p4*`Y%X|ViQPObsjMHHW){gd|n>y8$8>nriAvv~ZoHIM85Vk-o zX$ZR$VRs;`&gZ@{5t!O}4&CfUD`}i9X>6H@v5<0k!kFV{Q)L!P8f$6rFR3VLYUmR& zq<4N{Cvj61rgqFA>~>~K8mEcz_|63YF1HiBW9LZ*tvcf^YFlYkC>G8ljS9ln&`L3c z9Y@%)Kr!p4Y7`5z-g)9^r3g;0hOnaN5wieOJF1NDi69L;mF>mT>F?_5;?SW-!j5%_ z7d%+gTL1gjXD@b;##oT&sdju))~HEkwdfI-kN2jSyy2}Jdh}texeA3-MN&1Fk+oZ} zHC5N|B`Qmi7HgIXmZ&n|H7ho?Wr`-t5pBP4WY-50p{0U`UI6o9db1X8^ONlA#4OCUL5(; z?h&tXVO`M9I4RJN!@beh2rI#n ze_4k;F0h_%xpz+q?59ManvK-q%zIpRU9pbK>Q%&@aUQ!m!hczq<_qm@2rG`8QluJZ>SDr*=$nbZ;>rYcB*vp>yQcBoCz;x*h*_URZIsL9718MrvHI(OpOk$uwr9qIq%c{;PKrh3tlcIU?d-w!RIPqn_ZP3Y zlz)BvC}K)k1g2^(nGH>{qj08(QITZUsbxk*lB&BZd)CW{HL4P$E-~A6b}UQDWTH?67BUJWw?4o*$I&=J zRf1~`$uHy_?jG%7vZS%id;j*GQ*1LNG2nwa=UI>8TNiIixjblz6|a_E3j4UgJ}!7m z|0WI}U*L=P#7V7jNv(0Y>ybLs)6;z9y6!i9}jLW1VWSwo0rg1f?mB%xBVM-{p||2~ROQ zrC~q*((hj>qG3jK_SFwzMFb`Un`+}sb4_6w@Pwhavz;<&^mU$<~(aGER+3218 z)%3S9*EFxIDh(iv|3$Fl6FofoX!Dv{t%zHRR{!@ly0(W@#igWaUR(EC z4m|vyu%7yBe(1#2JR?riXt_7O%2so7L|ql#GM~;cy0(YCPkY3zcdVMQ8Srvw7yV8; z1e+iI3*Iohfr;{sG=xp-3{Io^7?&i!N2=m7AvA80m*Z%sI5vADH?I36KRJ7b$&OPz zxo{(8Y0$0b8Cx^MZRIicSBAMgx{v*hn^Z<@n}uu`5Cgs4#EqnoF+)jCeg3?MK*H~C zNYOKQ2R$bh8GmSB1ZhOjO{JEd+BuJ(`Tq-Gi zq=fsCR9q4(DshzX<3hM|p+NiMs#UHn!F5UkoJ80(2-k5R` zz$33iD`Q1;CReP$W~u$L-v{u=fkLA8^^1_04Y8W*-7sf%Wnxtjv#o@zuQUt`Q;5}4 z`T4fRp}KqZW2utrVkT)@t62m903ZNKL_t*jvg;FD&sOI~4T)AL5;Y{X7E&}~i$$a? zK*NwU3PnZCj`k3d78q$!=8qyIC2U&{Mnwh$tsNIwalzi1BBhwdh}c5mT#<>GvNE<4g6x9B z9-pM`P)-GV=ZfUpREF%n=|hyF8X3_fhI6jNNZS^yn81igb~dIk<2rlio2uDt*XwJAyw4Ld5xR#X;krY%h=qJ@R)qG>Z+5l%i_MVKsUe8tq6^x8v@*n&41 zl8q@<$6W7`v%XsPK}!Vd{1o~x=5_vfWD8$3b-p>ex=7j9vRm!Cj&I)kIQu?yh&vAT zFnXwmo&8g!x?M*8Z40N)R{6-#qwKiqC||wj3^UW`xbey=kqFFpZs${XUrSq}jjOk` zll|dGAp*C2s-H*$hAx%t{cw>x#(Eg}$1Q=(IQPz`<+1gIAoH0t#^n+tEwPWjJonM4 zNvxW{j=l8bm8C)aS;)|nhxXxmYS!h*+36Nb_7`Ng{yN(ZSkZ{WUuFuVcgRYdF1Y48{J<;j3jk_g})gFI=yF zGrRVAs#%|yEu*BHbGVm|BZtSB*!5ZD@ByBBqo2_1Z&L$m#8LL(8}d3`qdn&-QT=O; zL?Gq5yy4h~m~d|-LWGhyMM=}x_xK^z54q|Zwf*5uM5Vz5ms0B)4TxF0qj`USsZ!v& zHJ{=K`jJJ%?LPRC3lo3{qp3yd(>&o{j>tnO3bdf5m+@qwT=G%YdL=WSePRlVpYLc$%bY3;)MUb-h1yo zL4CD-`;GMVZ4Mge7em>7KEzht5>)d#)n)9M;#mi+&{WSvEI}l%6KUBtW(j3`Y{*5+ zw7kBEuuWKk`9hKTtV6|+xI=Q$xw=iA7|QlI7)bKADGy0HEWuTS1Lr;L<_yW{oTJED zl!A6^CXN0a_EJOMd0Oqqj#`4pY{5TRojhg<62M9CubVnoQ6~mG<9#k^%p!+o061m| z?#b(XFRvpkHCXU2vzlhWKXdS9Zj7qbf%(v^9?K;^7hwOqwKB+59Vp)VZ0V$hx9SRFY zGVRTQL@Or9$91w52Vw+P#<{A4nba|Al3c~XiV93kr%*0p)Fqj=bXbrsvNo@pv=Fv+ zR}-!?B-eRunfGNK-sF+7k640QvkC!V(6cm-qExZ~AILeu{;Rj$&>gfF2LF5j^ZPp1 zae;MQVBVu+9rIiW`XqyYIDkDa`1o5Nrapa?W8=rD9RCI*KYBOWA9axR4gBu+Kg@TW zcksV%P4FkbcorIv`CJ-mkR5i&-RwXeGG-d{PMyqOrm-FqjQ!!km;JMuQB?twOO@q=TOJ@T~`?lQ|-Va!R^4-E3Lj@^8$Yd1s)Z1I=kxk%YoRG#C!bHxJF2gfKo z*BZUH``9$Q>vGuGRXu=Dm-5 z{{a%-dS8L-ld@$rl#){B9PXVhue71cWW(sMbM~`@V?)qS0dWH($MZL7v8cS;7fTu zdFr0O`CFk%2a0GaB*1@p_cV|x_jaij#YjyHHQ|B#) zL^ey>Y})8ELo(Yw>`DPul9H z1}4jrw<{gZJlTgsav;QO@(fUJ3SD${b$jKpd(paQLviSBSP$LL;RQ9In4R_VVTG

    OK})RKvU{QW*}S*e_Op%)2LD*qwbn5~=F91Tu+6^J;jV}4*vBeZ z<4*%m^V4r#M=7F_{ih$JtE-#2_H&%5mU!RL5eEO~KyX~+GD#s*B>yd)OgT{lTvYd5ttkv_ZT|$mdw-B3UIYe>^Nv8=5eP9sjWD!gDHRdFR zV@2}obT*GBNe6SIe%|+Bb)J9E?M^`+ z9b;Clk2+ZjwHz_WKd(tcSX9%^`|A_P_s)Er&$uTTJZWKVIZi^)lRb9=yQ7o4Pkfv- zpmo`-iRO9J>8qhEv79WIr!z=7gq$+=kx2PvK^aP$AY8iNxx)xeWEoNEL-M(=-A`xURh5GQYK2&J4b0XKen>I7hY);sbZ5e0)-RwphWpuOK8-&nsvgf?_APpBMH;b?mq^+eh z#p|Rq0w=qGlUqQ~x1pPDtLAstBxS>iTp?D@;7sel%=Ya!2G4+{&w~E`ZL02_T_7tR z3|Err@$zF`N#RV9Oi#K=y3Q)nHQ(V`99JZTb45k8`pVd-B?<}hH zjH)D8_DI<_J;b2{Tt2$(oX{?xFY~i3HUn3%5a?FHIVL_2N zW+GIGTugX2Vk^YT$4?A4Ny3LL!GJdz>|sj~MOhUCd?@EoN6}DG;QAIa_KT~STx=!%@|5DZ>9K=zcwzPTB` zhRf-Z2l1_FmBQ6mUAkVW_w!`yD5B3-WL5x)vOZQsZO8t%vgPK_19187ALHx4^F8kv zk-!=}3H;FH)jaBv#}Q#+_UaU#Dl#-H0#dahEIypNg!^Yc&VBk9n`N$7r>}1_h40+W zZ@ZOc3D>0<+@^l(5l?yB5EkerR;OTSR+61`ur6ENXB&zh;J#&!H8dwNW+nGj4gSJ4 zU<%r{43f}I5^Eeja^`CO-MQN<6M4FHliqcbzj^fWX1ix#kj814Ic?ya&LP@uWn&E7 zzHJ|e=MMAb6JD9@0}>!l8|pT9ph8;PL2ejAoKoe(*m#zYf9WKqv7Up!H-$0|jso+_ zp~&dL$(=#ZuY2y__;~Z4?%$B$%l|3L>@)4$a#sxFCdu$Znf+~1FlK;SpoaA)u*B6R z{(F(hr4V9VgZBD>@9F=bb^ zF_R9IwE&x+Bll`+NW4JgEU-kog!mfvuRg4`un#rJv|+gvLROVz)Y)sQ0uc`Y1^SSbI(U!=nT0s zP|DhxQn;9%I)yVuh(W$n*%`N56r1gyYIUZF6&C?1>yxyWmoW>F=}aqSZP_7LcF1(3 zmCALtsH~0Kbh55PHdvNT$;w1m5c7Dxlw2AWfscU0q$2G>z=> zV~YsYe0_w2r+*o{Q!G!|`eZQB@H!FZMja*{vL_r&-J~IGB65fuBKx_I<~gfQmbh-J zog+~9jurPlhf!9O!2Vo2-(vbeWjJ`<-qj@9MZ2Z4W$Q!e9eHHkVAo?Kh=he`vyf2( zN+8~7A!CO6I(mQh>#L7nOw%cyo6^%wIl}dc)JKuR#PTJMg#n!Fq!0zq%@#A3_afnp| zzx*bXNsb;Za`NQK@TP<~59M+>u=$&wK1VXy#@4M@ENaxf7WJNAe#_-DM~@a?mTPcF zd#Em>N=@#VqCKYu{HnH~QPQZ5_5|yrh9t3PoJh*0-m*Mm3nI24YDgL-jfNp<>=}oh zQ-LLN%oZd@dx(}a+^j=+&$zNY_Kwpw+Jk0`!1}miNX~k>x4ycz%@T-~^8zdwlGD4# zsij=nmibKUO`Yx~`}nwF_c-@>#O?Ny#zUh$P|~=?kj$lAqQJ?~9&X(|&W$^#h^JgG z**V3;9X;sgCWa;w%z4*)wxsctEqHY2S&kZWe7F?jgxQO3o`3FxV~-<^d4$~&mX>OnTGPr_;wG2B$0p3!!Ml|VP!a8p&rcTdwZ+P>oJ-_Sxc#A^w|mF$?GT9#0~ z(4dU}Ea>mQmRhYA49s+Ob#r)jAvjic)?v@gIGJ^6Y)xRel07ryjC5@Ywn^1pQn-|& z8W9u;JKENB-eCMl=N62rWY65VQpUC`Wo)XhvZzP39<_d9oP1IzRd?AlH%>;R)w-Hw zPkEd>54!S3=nrKpCf>FlUZsT|pu2o$j?)NxY{7XyhE6^zDv!UA&_z}p;WQg83{Zn}0~ zL)WeWk_X;E?b0*UE}f*ABkNlgS7|?RCGGpKp?&{0DwmyLVfbNho$LKV=9nA)7DQC; z?8N7@K!pe{9e63UDVG><=HGR0`_2LOp8N{t<W)yYzGa@3q0KNLN{ggC|ao=-8h;Rq3Jf;TrFW7f&? z)cjldKk-3&(izpi1;&ee(XDD@~5$M+&<4f?mX&MT?3(6Xze8=25uvT z`_7aiWh0idF^;2HPfsmN74##EiT$3@1W?6IRd7>rpn|X>2s=r!@H9^D6kA3vc|pIW zw}1E;#Oe&6uCsrAj4yP@5mpCUDT14-5T!voij3_*#o)%h_et-6)Vu5?ic>ye369vW z&&g_CU0o!T$=Ch3nLj?X+_Rv!cOzT3Ug6!VwwL@o2=VeEnM~5v)g6xehFGQLw~gN3 zjbZs+VR+ly-o_i=@CNGj`gu-{ulNJm4@CEKWW$F|h}8t&rZz0UAztWU%<<#LxcAJ3N*iQW`RenQ+c%d-d=IEWY#~h{XAKci?lpQ;D5L**u)+h^ODn&pLIk92Va{9MrjuPziq}j>8Z)T}*2aFuY++t0VC|@2Y~~O5!*9`N#IAG8FY@SH=UC>b z>B_Ite^4kBaGqvkW%nv`vnUT)}(|1y5}yV3LO>GC2+V!*n*j<5up z_ulRl234S#%6gL~C}^S=!*Iq38KX z>XIOrwiS8roW2q^zd>inJ8q-pK7aPo~ zKc8}PbO?)1Vd0!o%S4A25V8QWroJB~E%t8tFvxa8iI$Tn<};ygw{Kw#;ACfUa?=UVM2HYC2BBhh<>OWJ zE$r{#)}oLN2UJ6>w#H#21$ zQzu~wdIty2vplXCk~wd?PVZVaUBJ%R7?Kn|TjZxAV0q_l#rKC~ptAk>!2#Z!b$GKO ziCTj90PU9GQA_amw%~qCaNHxZ-(?GCfN$k>HZ8dazm=WfGc;(k1bucV7<0>9S=}2< zS~?b^h}v{UM;Z$(B4IttV}OCdEdc1IK-k)%?N$n2F6-?OAzltxn!swwgS9omkVn*J zXT1ErHTrpV@X|WI)ylG~tBZPPJNvGBGY@RMj2|jKfU_yxfG22*tJ()FW zvU7_EW3zJ(MomHtG977*s${4tl|^yVyS4}zHHoR|WXq1SK5kR5jha-Jn3}GR6K!q} zG)Y;v7-Y%<*fBw_=8y?3j4vwm^=%HF3NA7{;I%g%umpcvko#I}H?> z^r4)?kRiFwklbep{-%Xs_;jJjuVm7USz<+(-<6z6-)eW++CT6I=36Z;U&?RLLNG{k zl4G{!@Vh5RIO*g#>EyUHouN}$WG5YRlMZ=Z$Epg&MFNNP!+h*Xi6JF}Z&C#8I^E=5 z5g3}AWnFik+!+Vjy=O&S5woBO*{ekkn1gjXHLxAUo*<*2PtiEdN1cn2*W> zJhH?>-k6oxoq|Zq=g;V8$xbe|nFd7$7oIGhXLW3M3bH31OrYZB(0;$`lYGAX3Cv!d zL^=~(hu>!SbmBeOae=X5@xiuVpi|E?>*Uac#c3zYdfjA$_uV*?Ih;wgfBKCXc6+@|Ff#K=>3{M{5ll5B^IU9#SN+Li!**dzT713tEDnLxrEG|w*(V;ovxfid`Ln|r+8+`wsAwUrck76iC|sL z)Ty=`U=*1*B)1zy$fP-J2~K1kHkmron59^F!W*Cv2rrLT zy>CM|m8G#9n#IYTMp*5nGn)}s8+yJwP}ll!vS*OS0t16@Trt0sl|G;v;`NQ}jDw{K z%r#0dX?iCB03ZNKL_t*LnwxRRKMzv26-Gr;IC_xG+BCnP5b(qVBchD03F2>iGw(ce z5^?qve;>aRd#+Als)&^oWY#t75~C(DYLblbmPOUFe9X(7^>bsBdXO<|w&|FFQI$c) ztWlHXTqhu9v#!dY9b7X&w(L-tD=LMpN5onl0h_Hl7s zZfVD)se!6*D8$~KrN zSe=5g(~*Y7^#?gHkds+miEHS#*+ufSgYq*w+xYc&LaxXIk|wGT@JU$c9ZYj zv}oCQ7#b;uErdR;l`5Yk6Jw-dBKG?{yrg(jdadoA1OOKET|_ z2npa%e+NL)2E_8p;pfjABT8sH)6B#Ll&!Ew%tnPxT+dT=awKoO6a9$R?2mK`hCH%$ z@Y;cZob|J6{cT#e&u`SJNdr0$2g`@%)c4s+z8Z70WG-+1#^bt)F)tZ9Ey41d3VxvF7~}R)Tb^9-u~0m3 z676%rxI}XEPbhk|abFGEK+mgQ-xGc$4vipRHi~js_H$(`mSC+RgIw7tuo3vzyw2BO z*NWM$unqAtJP-VP=(o#MAG!NQJrhEN2=RKVN6yjJ)fLtcD-^F7F&h$EAufi2D8C~g zHY7v5(r8sqy<8;iYpF8qD-_WT$+RU%EVF)1)*)#~PG!4`LhlYZ+*-X)Uyr^P%7FXHCRy_k^wOb1UaKDDX*3@XHwoGLXrnDI1a}fxGfL`)t8f zp}0t0{J16P%j^92oI?dQH~)!3ky%4}M65v1Z#<8bb+RXLa+9Ppmm{psfS?t&Qqf9d z4rxpy?F7Q=Xc^>4B0LMWl>nd63Q5@zD;1gb%>m4;bg+_Qky^IDe;dOmpW-i1&IZd0 z=Zcse%7!>A9ZaE zQ%!5OE0Wc>AvWq#<-aDC0v1&MV0J+ft@&h=umu?GQpC*I%)wy4fTZ<~k*hhuAbVlH zNTz+UU9nx4VS%_v+rpt+%(6@Ex|Ezv3Y%^{ z?-8@hvu-zceTv)96#1gQc#=>nS=qEM_FZRcDCKLlWx4BZS3~T+6{z9fWZ@3qO_SiQ zqFBQQUAsp}?!QU>(I7dp3s3}I3`m-a9M$wZu9M@&HJ{`m?`no-rIM+8hzg6Su!!p> zrNlZ6Dfwz^f5cbWo^S#SWS_8YC3t<@JM(eAH*-5oKr)>nCM?WewarH-ck}%wi$LlQ?7d7q4})8vlV8`6)$4XlmpG*z{)SEza_ z?908}<3`W*OjvH)5FtXmp6lU|ms^R5zx-cz*P@x#;TIob^;KBmq=FDDqp|&BNm{=Q zzt)77YY7%iovno;3E;$%!Mmg(Ng9%}w;h0HNL-JYjC(|Cd`Q_GFK2rkF=SwI9I*ru zD^0|ZG<>_`oFZmpg99py))tFMSsyh+1~$j-rcUqk=*$~~l1E$K`<10WotZR`Sb}*&a(B)ln%CKt zbNKItA`5w)A6SA;?{nzpCPmf`2{yId<5r?pp^6-uL0BEgp?Rb+kHcxwt;DRYA&2Hy zOg$W0XNFj9u#(OCrN4h0SDr4BIs9FI(4~mi?3~lggmoo3kC^qB70wpPtW7hxp_wat z!;?iaYtmR#_we(PvrMe(MXuez_Vi^OKYk3ODj9j~U_h=G=870K8K_)yWrs|sB2s)( z)@)Omvqn`i*gc@Ejy?Ng>MEPoY||MO-Z9HXrGQH44AmqCN}+4TT2wiqeep$yzP`v(Jho|p`Y1kOav$1`7(sWK5%zJsH>z~8gcsa#vo3LmT z*0Q8*t6FsMngPZR9VGL{bU?^Dxj~vtpPxrsqkZ?=0hjraQJRWapPa4Z=Ld*g9|Asv z(@4`)&Bll_M}jgPt%GbMy8^;42E63}#AhXzu!sqZx32jVg(r%EwX{#PE?b5-Z|0US z{SCi$?fHF^+@vCA%O0Wqm%_%rZ2x)NeZMgrypDOqsWB&mJlVKz^465eTTVOd?NIH7 zIVa1UljBeHJU^@*01nfg&QOs<08A}IvUdm@=R_9gL=JsZo`G$H6ekMEY4x3_do$?C zJdT^gadV`T8HzErZr3Hd$v?9RYT$I`)a_lXZnb_qk2t-U@D+BFE-Q-BBf0DH7)plR z;Mnd7Z0eL%h1rgwXytM2HYe>xeL?dgbC}BW6QFHpImMKZi3c!y#5$LwhMn z+q!(|;EX?z`dXIZ<1K0mC$FkzX9+A=Fr zU0DYgoqIiUdJGuN>-<#C;myF)rq1y~k#|7IO4T)}UT4diPjai)BB%p{~ z-CU2b+ZU;20g8p=-eAZ1>t4+ce1HG7;l!8_s}7l-X1(%@={IuM^fX^RafYw1AHb-{ z;4jmi#&9K;CK&V-Jz42Mgg`k9keyc~OTJCViYqnk@a$9M7Zxz5Dr6rTL%-}AthnHJ z-}zzQIem`9asfGcmdw1D73<~7T5-YHxr0HDtWlK|=8NS0*R$%inbZSf*RBbym{2yw z4M{%kk+Ka*KA|rnWkXz?ZQ`&!yfX0qti$_6opn&uf86asLXlEX8e~a{1*97(=~lX7 zLAtx7ySqUN>F$vA!a{4qd1~vfZlm zT4^`Ys%hnp*HEv~lB+iRYTaeFu!$5Ezum#h!@2Jka@1#zpK>_;{KDyEQJMLLfv}^q z&iPHan_1=aE6$!n$9SjaK|hHVK|O++xLlt7?UG`P(VK%Mo(sDa-yV-|ZD6e$%71M5P%)NdkSe0)bWN>PY^^ z3aq;N!Oke zzxeHl2Dz3>B>U?DT>1*t*czH@*tt&Mv|5gZ8;Sj;(^A-`=76)mPT@CTG_HN7uV8Gy z)Q&#c9@4x8`Pf3pX40&l+qWz9GJ@5S#P=}wyf1&+6-xXQn)U+|vvmj8R}Yn z)P(Lhjarpwc3se^kHRH_f_~msYG{oE@x- zG;NoS1^&;HoK?$w_g^rh$GYXXUT5NGf^t!hOZ!D8{#nkk;USD2NT+kV*A4)3DqS*k zJrlEPh$un_NI=`2Z~f=z1VOla!mN!;P_H-ooNVCVn3}e5;s&XVjBYAYSX+UF#qdw; z?YM9Gd0*hMd5dqwf72!Bf&3wLXp!ne;`K4PS8;v!BC!hr-^%h(ph*j4v^7!6lM8-; zyJLX<*-Xq*n0*^(@r!u(_4iu9c$xE)EJ~f7W&zUh=5CbR8#^CBaRkR2*ADYW04@2R zYxi9ZiV|GCD(+ih5u4QkzcqSR>Ug8Mhb$M*>zw4FqA`BfMk&h1;m#xr@;$a2pND8v zCpq^y@zU$fI(YZ3T)JN^S~bgUT%J2MB&1liEceJ|9Z%um7ALdc)Xx|Ep7E4RQx9ti zT^vqvG=^4VXyAZ-DV1K)o&TZ=Lb!XfGeP|&Mr&u-AIA^BSnGnI`gaYdI_zZJw89xu zg<=c_r|&{ryOA`KaSKLMOJ(L4`!NefO;k*m)q}!7JUp6I5cJxDm%>E$0PsLW8M+`d zoK9uQ2WO(TymE0u8jaP6c{EZ>VGQrT;^R=<-pY7_jkI3ujz>K2yCYmrhXa!Ql;(P@ zq-a)HQrD5<)na>-R5b%ry(y+8qs)0YmXTHJ8s9g$Sdd9eR2Ab#gTr}@1v_7*_>g&Y z{>Da;gG;+-{T+frKG@kdu}$Gq(&AtXRxsC+m;v43&wNSe-fgQ)uY;SCcw;pkSvk`j z8l-=Cjn{_fei zk%^hv5@&Nvl%K&8Yff(-7N0vBRqvzv*Zks*gozyAq{kH)6e3fa()zDPAzW|i)lgy5 zN4JI_=<4wtn+`NnVOfFh?D7$G<{nVYTcRh(t#tH5@9Ry~AM=qKTV4|H>uaVP1W<+% z*~Dz6lxd?V4knXw+7Dg74&O@;wP1Dk19gt_Xwqr3eQH$DNqzn)_m0C)YNFD3@P)x$ zY|jMTZ9Sv0VGKUXV9lr&rP%5GuI>}QnWuJLebX%#;J2c)ob-44qZyh~dG{inji6u3 z=f4c9@Hz~F+1{`Ba@3OEs*=o zhzOk3&PXF;o4?v5hgMD-3_aV{X=Km{Fj@ar6Ot$18Sm`L|*r-^~|E0WYEG;RyPQes{XwcK~apE2h+nr#a?jqX@w%HX+> z9cQuxs;&VC1e7TsFIykzTxda_DjO&7@*f^S7V&P@RwtuCvn)uv|A!w}`&s0Y>t-Kn7F!FnzV!SZQq-VlH{G!ux*gU`}nUoTwVIY|@ifZRs_QDaEln{$(1rWjF$5CoAeT};^3Cqw^Gh$L(%JXh9V2K{O`?snhu;m+BP$)uy`U|g!Q3gIEw)skO zYYnEvjVts~j3$*KDrE$12E%gx#{Y^xBG#-H@e(WN@~Tk6VkD{-%{0y6Lw6(W_HibSL~PX}?PaIbhI(ZE+XaC3u?*CYdBP@>$kxUxONJh_vI7xL5Axs{VZ9 zOqb0d>u=iff-Pg$W$<493ekE8E%L|pU%3Ni$Tjt?_ws#gTMMo~z~;K%&Qj>VW7dm5 zx~nwC!%U%(&is6}yX5l)CNm6-&waePk;c$DSHxV1SG>CaL8xNdr|88iq`(;KVv_B;&QWI~aG4~G|$NiD`w7WOaU!geJo>D``P@iKMo@6;c!V_HH#X5qmk(BHV-3>2W%CgcdE;)=XKdVY6`#45WiEy{T+t zie;)&G>a^{UNOe3QrAI+11qN=IzM_Dfh--D#XMiv9lH2!Zhg+0`()_=&Tz5Ma5?{; zCoDY&mX=l2sB_pBMp#+6GcaM3nD&`szs_bf%twwcPdCc6HvCS->~Xki`{*R_xvn%D zTT9}7?GNDK{qts?8qSv8d9}*ywn~R9WL(*N%x#x5h0}UMmt5%5lrdkBHsY)gS=HTH zy(FKI42Ux7|C`Fom7)4@Qlicv9|cjcYYrFHK7B^|>O8+aQbnM*|{X;SDQ#~g#df(x)usn0F)$Vtb=lL2zq3yg495$ciuv=7+ zoYxgp)?NIPoA?>;>B1~_Fanf}QR|AP!I3a#gTcB$pjjIrOT<0FZ%vPGl{5QxAi}qX zE?Sl-@^%&TZ-jCSm@cH;o8F8+4E;BwcL3)B0nf`aK^qez6D-pQ%u zeeQ#M<%Wv6qc7U2!7zU}0`H6OK`IT+R5C<~t)jzx4Ri@94d~+S1w<{9K|z|%l;d?6 z9Zw8x%=?^{57%0L%``nT=z2f+1O&VS7yn%!H`F$QOJ@YN;r)Hg{U8x-=yqeFsm#Et z4)ssfVL@6$SOZv|CO+57F2urfyojsP6VucuurUc*rC@UBbkR2WT@R7bY33fPF(FdEY=>WLk#kI4BQRD?b?n2my=iC ziGV&U;Uzp@l=Jxd&T5osMA{21Y@`p4c%$ZXxPE$W$=z}oqsj6AOnM1f{_+( zm-`r6iyw&}4bFXFr0bB^dP!sYedFvtv=DZa$>Hi-uxg+UcfD~5tHneD$q zYyXSt*4^mwsr&qJwzkMLQJHuGQOR84*7xtgsAw4*CViFZLQ*~Y_h9upx{?UFCgwJ(=m z8BFF$;t7(Z6RCA$@y>sq`IXSNv@)rO|CNd0XQ*idk@M*8=dAOP=IO+q5{03mFyCiJ z^SLngzpi2_IQ`9W{mCtEbN ziSjH-IkpW__j0w=mv_d=0it?-=ao58fb@ss)b$1tsl|a#uHnO8zN4?3qjxovR+v0=@b~<= zkEaTVREpgi<6<>?dO1{kH3FM(me&7HrILpCt|B??f#>*SqqZenf!X_4l~bhs#dUAL ztBvI+y(1o}(op1VCwoRI|9YBNZF1_hXyF=W>=+YcI+%PSTl_*msv>W z@LL!(YNK#ii$@Oy2C><8z0s9w>;@^+Fhl%Yn*wFl)oBOoTht*6ZJyeN_o#yp%5nc1ruRR&M+1`Cd+Nxa zFbInHKWEqIyc-WGcRsvQ zrnlP+GQxrr~Qez~>(d|H$ zr!}#-h(Q@9x)kFWA^RIMNrUL%hg*$>x=!zn9L|?K3M+6ft2v0=c2=YZT7C5%Y*xBO za_|uT7z1*XSXrM|54zGw?igx*H160k+VrcqX?#2;p8hp-=YP=AFHMvNmQ3ZniNJFc zhiz{LZ4qZ_nm99xavq)&tsQG5XCpk@NmHs$x|(?U6@!2)_gUPxVDMfg%3-=BOkC97 zxpv@DKNXM!4bYV39(2D@nYL}Fxck1go!SS46qkTeVo*5`LAkN9wK8UaxgT(#&-2~= zlqopcJ~TZvXPKadV5+gQ3Jof{*yLo5fVsEuNrNWa5)3tS3hFjr@zKoD(tfNuq%*x~ zgow}8?;jN<4KnjYP_qd?9}WDYa@N-G6_5GCm!OR6ej;@9X0_Qhv_e*AjdNl&{UF)( z?@O?ogG9nCtvNpd{GU@v7(xhI--h|8;}m`R;y~&7!%H$ZcX!^>=nB@yX84k@e@y=V z6}<&+-TSp*R4DMk<}}rbQl}s{*L&j!+e;>Sd{jEJ6CQLsV>R_~udkiE(Y4{`o*hVx zM7Rrth4Qz{_$wvONeQ3CbwBS@m?V#`H!0XMIz-U2Da55a_&G7b`ACGkn8VM*Eq30$ z;^#jj%m^R)t?F1R+=`l4T1WE*os6!f>9jO#KB00xFWsUTl5XdC@r9x@YrZ-yA^|5Q z-4VEjM}+mrqa7uzW!p5qzKe1uGPWG?xTT-}v0&Yt-P4}!J3!CSVr6qz-7rdD`PF{4 z0$1pg_jh5v@}gHt;&Sj$2@U)Q^Lc`p5U~)XL+|~~7Um54|78IjPXq%Fuk1X}XYl+| zR7G$(>6Uw9a72gn-2gr1M8G?vCQ%yd5)r6cU6*G@p!~i*c>BT4^1Q+>zsn*yo1!4` z)wz=fk(dBZqbT#~>$478pF)40lA)-ooHxf4#A<#z-p|HqqM9^Wm@%)TihKr-XDB+DtLcBjoG+bnwap{Cnp0|Sgl%P>Squ26P zDH6b}s(_b$ML5+s8`jB5Rm6 zUd8O*e={X6*z(bPQ?E1agXcc3mIfJPO`MaN==-vfgE^|OkYkbK@@zJ(ixnG`_S0S7 z==Qt|$P~bAp0;oB`mWaB7i)HSoi3}EoBrkmTBNiOPZL)i9Fj!@;q;v@a>GFZmLZ2l zpyR_9%33g%-H3~I+RVyWK8c?E`atI7bWJZY9JxE)1+*i7ZpE-!3)Z#Izf;tY{dz`SMC+xQ_WNk zeic{0G4fmfgbtUB>I%vWWiU#`o8(M$3iZf4Js=`I3;~CHBad^^8d&@hEg7lqry;{4 zm}CGS0BTC$e@?M0Vq2XF9ha%^Bl_-`P5j_@sdd)_RMANDNQ5xrxZ{FRN2$#(TBikF ztS-hn*AN|ftfUD`;o7{|TI8ZC3}{eZl2a-f7*!1XPMye9HWRZzekP`t>#1V96ndne zIt>XpMpvS>0i+0A+OS*;;SdX~{1iMEP&l71^u(di_4jw+qR~d-AzBjm+-98)(kmX3#X7_=`|GE~#Sp?F% zlT7l~iq}XpNJ*n73?1S|I76WGSwxIZUjjd@R5xv1MaJ%4L2$??rtogY$whH-sk^1Y zilSxXoGACK%3-x9ik>y+!^A%kThbNUjt`}J72=QDD`p@q;R$J_7r`x!_J$@Y$RUHd zo|z=YN;MzmVC-&H=Ge+wTw7P~V>rG7>CWn+ZiV@L#-aYSKyT?RUJ7Y*HFJ53G?-Y) zYJ5$EkdKZ)2Evj=HJ=uq3L}((+zu33*Ne+5g;|8P>e$W+sr4L<+nLyNv${ro^Jx4G|gLuP1muMsk>zU=iDVs^BM%Z$6qC3&QneSm&c&ktNi`O06F>;;Nb zlvZEf;A>MRxz5m0Zz_~8a?DENQli4eS;1sGSD8Gz@7|MGdv70cF7ZdpveSHB? zD1FQ=HZv7SO{J%}_fP)uxW^owvu+PJ_+3376MP)}G%S>J@R~~||K_Gr#qW#~cTU7s zUi)WEXX0BSyY(-n$!G=UMDsk!?@i;fVS-{!gBt`Cl4DHGT3n%e&P*ml{*BhE5UhR* zX>rofoZcDt_>(u9wPG|peXwbk=(1LSW^jA_`B07_kJ9V%C4s*Q)#ZVUMMsfH^JXMV zks8iq&sKd*keDE2p2IkLv)1hrq7I+(Vfb?v6=JDS42a`;S&pd26xmrrQPaE{5gzM# zSqg=T-#!-isXYhdW@zc5F(|%T`6xqP%_NmzWfvC|=PVGGaEv_4&sf>7*W7c|7n%NQ z8xnGeos3)8&LQ~uOXrob4+%~UsQmS9>MH2d`Np5rlt`bJu>K0qe{Vnc)M=mHav@7Z z3*xPO2x=^V+Uu>7j>%*$Jw9b+f%B%!oKKcMdOnNH+)eDf7)i?GIhug;Wv_%hx_`z7 z2fG((bE@y{j$04$Wcc8v>&)VmLg{{-L==gZJGsqFzvp>9i`Ro8wG{Jxb}osNya>?= zXdbhmv+xI@i{cQ2tIg34RJ(Z@%n$Vc(XG{jLU%}3W;>An=&`bE_C(N4UaK(2SBfj& zY6OcYDH4NmJ{?dSq8YAi{^<01B`8Er_$j8*Em+~BqoAcE##*SK{68E=4NSf*KzZP> z(Mv+58Z3B;sYa1OGVd%tDoSBnv6BP@s(Y8ppOQm7w6~9UCv$mI`-jeJ>^(9_Cenq# z%ig+8(Qt3>C4W3m9VixKon8*lM+4H672FtQ7Sq`EG@aDyE3NI@^D1eiykZ~eEEr|- zBjonfR~}k{tdm{WUMq#}h%@Q`U}qxfQKTx1)f*H8*&{z@I=y{%qx54|&tYr_aYo8@ zi0(S)#rYI3$J-tQ<&8^DHwu$&@BWy21M~l6)}N-G0xIR(n{CrUZoR*@QoyeNaQJuV zbe=plLVt&U?PW&2p_HpI`pirBFR`h%-5k$m-ZZPwd4&jHz2knvgzi3mutIIi0!y?= zw=~84b!mV*SzF!$0z*OR1-9xcwiI{#V}iLtbF0JA#~?0ovHqWNFKmIv`toLAjv%Zy+|4V~8SeE#e7q0Ke>=7^>D`A* zn8nF{sGZ5>tBzj5Z{gx6-kZcyg)Q9fmv*HIZ7Z`fg!cc-#$5da>AjvS~TfC0lfj;54YRlISpnltvxK zhT19rqo8K2zriZvl_L5u7FB$aK$l}Gn}HG&jyh^cmidapfUd;wD;47<3N9gWr$)Bg zqbo_C_2;B1<`Oc~=7$Z?u$j|v0CmW3HZILA5K_Hl=0}od#)-+X$MS>H)V`|wsRx={ zN~C8eB3++SrNM7M-_=;LABE!v<&{;1i?wZ=!RJ@;FUGnDg5NQdvbX%WwW<=rJ8Y@H z^9reC2I7<94w2WFmS_*2YJ?jWPNQBT*XzL@WMqH{bon*D*ii&9^6T`HW^(o~fQlDI zs$)5x;Pi7WT6A6jVF`Y4sby3kj#G=kYeF_grBX=cm0;4^jXFa^ps&~OoBnvW5Wp!~ z&9q8x0!@Zsm<5TsLJNc4H3*vRe|1$-tU2FnNLQXa3_bnyUZ1cUe>Gf% zNQNbmqvd5m6ghOpLl@PszB6JwvO~b;y@6n#YGy9}#A8gAyJkHe5d?6suE|r~>8-@wo_8dw zEuBY`RUBPke~4V;k*RyWG%RC#`G>Z5wf-iRES&OXEl&N5Lg4zCj-VD(Ga9H}Ib!P1 zmf4>=dU0aapr4PdDy=w|!}ffOd}GZ$Y^wCal`{RY!!sL z-10U_iGI#}>Z8&h&POx2^tseL??26N>UJ5e;qlowNl1(+d6pTdbm`|=xGTHy57*VR z(y`xSx0OX9a@}#62^eMgg^bKAJIaPYVZBq614|u;-g@CB_uDtI?GH=*yXu(FzfMg zo-wSl?R`%?Ud_t&VUV%lE=xFt8Q%pKT_*<>K1L`z6&Hp;0~$piZzu=lZ4i@NX0qeQ zW5uVx<|}BEf$^PDX539x!gKdjmP;PxZcetyjdz}NS@~1@r(|c;QP79C-dbgSna!GS z7Ai{tfb^fC^$8B3u=BrDBh)O7VAf@fm!;`$ZFo2Ph`DxSenUjjGozkVGIN04_~smRos$%SSNxumkP=hD9z(7X-|HRhBVH^GM_2Vkl|7 zYdhj1LmnlLYcG}QpyoC?z#xqCVWTQA{Xt+u5%iR?(37x`4V=BewR>dIIvxD824x`u z_B#&@Pd7HGBw7hHS?cgeZ9bszJc=ENW+kpXcj_O9P2__+NkK}CxfLb!jd!` zqvgnAj#HxpR48)0?td1|Y>O}>gjh8lpmrpd@NShzTm1+#Cn+U?G+Hqf6rk!}I0Ykx zVtmtybD23jDuzn_&|peSTQLk3;&K^;#@=@=Yy`V{Ppk^9WsaS;>ilquFy+Y@Y|fe} z7D@LJg4J4I*hdEW9jc&Yk_H(=j#B0rW5GSa(DE_ZIQ}E8#o^x?Y!GLhqJWWF#wgMU4wsyP~D{LEjEbx zn@*(q6cqFu(4^1m;5Lw%ui?qS9X-DhPd(}WxaVx@rn>dseJifZLa$AXH*?33etA;$ zL-u^MHal=g*+_W?DT_S8_Kaf-mvs2~pM($_X|D`UqDZig!jBV%v;?ZHqY}$}Lf>)T zfCT}49Mk?sWY~}#saEnj@#>y|(+#1j%cnny2|B-XbF4<=%aCLm=OOwZxmx@tOJ;x3 zPk4369GzOLV!;c%ZgRhVNzI8BC`Oc6xgzQ07gD7#q?*@d>4r^bfC~~4VNi-iO?Qeve^LT07M*}E6VEu9oLbDsl`q3@_ra}jBn_#}Dn6iTM6ltt*zJL^hQBSKh9s|#$q zFdO;s_nH?x9`J;Vb8x>k<-Fc=~Jc zaj{|b-+$1D67~e^N^KI*l$hP9c^oauu=#El=`mxzlCk5~Rh41Wwv)Z5F2ZDS!#0Ml zrw&W6?cOkP8=6=<^0o-x>uv(WiQv+BD(9lgL;_eiltVg|-O|FxBhI{P?skliGKy8m znOW{mD_VtRQQznwl4p=pE(kde{jVta>GBHCu-_w$2!S7?5 zl0~6BR2Nt?eo-w!?oKl}AKKt#>`qu|L&c|mT<}thx=XOpZlkd(-2U{C;FqeGv9;-0 zpxrZe;hai|;?$sY?2Mpt_0bM&lRhut$+91>R-5iGeVLZ|hokn_+yW^suvN67fg}ey ztx=tDe3qXv^uxXVV5hyEPvpk$-7L!ey|rnBLzoa)je9CDfP>HJC{G{2Q}{MSr29K! z>?c7Td-~KUqWij~0s4>skVSRcy6%%H8}iCGpD(fO(Xo)61_8Cbn(dk~ysWV^tVCNw zkIaUV>wA6s0jJ)N)Eb08;pQ=nin`#B1|I>m<@O)4s))Wh?`9%^-@O@FtV2~zTSQZ& zFB&g6T4)-3LupYi*rV9mqa+i9fQmu*uA=1gd127+c%0AlW{Ift2Zt{J`68Ux_3?(f zvk;v(oAc_hn6V?_kXS|~b^BE~>Ad%fQ?A5Wq{UiR{XaybYp_DU!s=opv)9hDr@>-bSI<~B z2@AKgCmZg{`7(+5W1nBo!8?*g+XzzP2fNYTcklTsnNh_>G)et@!xl_IjE%BtEQ)5% zEoWGL>x@fY2|;pIHm2Gau%hmEJt}h3V4(>1;?I4y@BiZF%R9nZpkFO-K&rtN-$%ds zHi@?Q>-m)2vdD_QY($akakz|jP0PXdX~HKvxoPdJJy2dVm&AiX1YkV6J>Dc>6pA~c zS96F?EZAHfU{t~tZcbyP8W3Y9@*A&OL=hEeb9DKfUm~^1 zpG8j}zF|f?cFcD#g%&>2tO+lQ)1<-2aBsi>Er4l8qxFpnw;;7s~exgnApDYH2F1#A40qb7Anfg4gF~0vOcu@25U_JP0|8##$ z_=xIf5`w57NGezRO)+~ymDyTQ>y$`eA#l;Qx#=)R`!DQqZ0F|ld)^K7pBugr*to-l zq5(Xcv3i){)3>yrkMe>WVZ2-G2r40mh-FO!YQf7TK00??L#xbE9u}kPu-0y_Aa}w~ z2UZ}1hHaAiZBqG6O>#6qx}&^%8PoN+()P2M5+@VUT-jo28q} zXzoZ1aA1cOsWe&MHBV3gmRY^{R~VD4*xq&k_+3oZNM31@LkMA9FUL{sN|r<8NDTi4 zN0$YLl(+IJtrj(m(r>_m>b+?F) zd8reCacYpIY=m%=F$t)^U52CU+TO2bJ)-ZPW=EJ4FkM343H`jhS{^N%qP~w7dP_`{ zceEE#9PbI;04n=zAu{Eb)?G?sWx*3N;-zAgDzFCjYpY;p3Gcz&HOSBo9_iIe4c#c1 zV+BbaEtl0q;2+S$em^A#JDmt}I^T@u#5v#xxzQ|W&>_pr8Z_6e7h{b zqxYH5rIML**w#z$^a1dn(7KS|i^4Ijk9C5#Ytf(WuRDB#`lf^2H>EI5BEi2PPwsxV%Ul-YuP2Ag>U!}RHU;kiM4tK5%co*g>=+tms` z%+||8nnj)IqEN2?%dYFq>*i6v!g3CJT=nY2l;aMg*Ie0+>8Uj5GbgRt6Y<3WBDQb2 zI5Acl-~Cte?S<}i7tzNcrC1W(WzyEwzxbL-P!vj6FfSuXs_0M7wq?uZo7`W70_8u(R1NHzI|{YB6GRajqM}A&BNz%@)q?w;A6QnBmhQE z!)v4$gKm-yO?W5p-)lExVtXI&Oy+%iNFs1gkYmCsID5VE8_cac-t-gA1l$GAYR1)v zsb-IG&MP_rPvJ_w^rTY}<1jhA64Hc1SomUxJF* zw8oLBtz1S87H^TQbay>W{wAm9uKY^4ie;fHY8AcNOH7irpo16%dBQ9;5zZ*%gfw1j zu7I3_jj#UjGKjWeOuuQz|3dXCyc4eJM;qks<|Mp}-v)=XP`MDr2_dPTW4+jU`l)%W z%A~nNhfA74{;&UPFPPL>vc)Bl>x|E{PeZFgMeL+4yP8=)mLFYRH}N;pBmgRG$!FvJ zXog!*E~ak#VXG+6rc-vE-E(T6yI2atbAfaIDR3 zw4;7#p|v1fN^;_ZDu+O<1-5O`*Rx=x^CyxMpqV6-#L z*s&;t^nK+kB#uGFYJ7(KrH`LRti;(gsvUNjfMXo{0bi}F?OV!&^VP=7AWu&l6h^Cw z?@Kt{=@Wb-`Deh7iD0g<;B|ajW%GC} zLc>r9dRR(RPB7emcB|!cM7sTX`?`HroeP}uOIi>nt-9a&rd^9Pe96`i;63*IFFqcDC^%~ zMX~zERizB#|p}KmaXDdGP`IN74mh!n(vCp^Wt%oQ)3SiWkMOOJvF17d1Gpg_uoF z^%qAo)_a*8LLAb)dNKW(_D8FGtyQ!u7v6}~S1mMMyfn9L$P7VZHDX_@3mJv+k*Pde z8p5A>UU*NbZ9Is5w>;Hf-`)6wL_9lA#a{uM^5}mn_2&g(wEnkP`+om>77uy1x_tFP zmsSm5lhx#t`(AF6c8p_l`2S}?F)cz$$|+BFRWo=TXoll3?d1Mcz^^UnHy6iZ%}0qW zM^VmZHPFMUBg4tgnjLBflDb$ST9xXP>hxyZ09uxIuE_v44ilM4uI!Or9npCe$+^*7^oJ(<$G}d8q;}NQh`^NrC$76_b&W}@c(nNAgoo1k* zESbI89xL`umnp-_#iTloYbFcTzE`|h4HHz(*nSzWv0&6(iV_%t;PuO>eoe2BRm>N& zvw}wZepi3|GutU^vck&lyHAWYhUlt{U0+FQuC2B`r8a>=PfCD&8K4?f51NVlb~ol& ztwQvGG5B3-^S#zultQJsBv78DJP9-<#TCd~N*fuhQk7^lP$$DA7S)65t1#Y+VlLg? z)uw?%1Z09vY7$L_hXU!N2t320 zlEUZG-h3!(3hREB5noB#SK+CF#sPj-6+Q7?g$(`6Oc>fx<4|}WE2Wa{QoUAIbZ`(u7Sl!23bmANl&Bi^M#(&H3`Dj=Ua2RL^ zWQ-F;@Diz8Iu42~aK@q+{xsRd$`&UKLml$|3HD*5dI!z^KRoTMv5YZ74_L$ojYr~#?obGv2PX6vE4Cqi|pRNa=ooD(H75PAg$|cMh77zK+bx! z>#uZa-kPl=*EV&cI0HL+?)=>Gs}`NptW=3cT6ZDm;7-98y(&IrBOStTB#AuME^mOn zK+xmaVNZufOrJg%<*srbg5M%q=iBFJY;2C>;2%{*4t&3d33QH5*m)iTU@Q&}ZdkqW zZ`!S2O|G@}`m@(QnV7hWd+=RU5xhJ$bNz?KciivjRWi4$9Xqs;KEl>4Q*TVYahm?V z*?yV4CZqV3h_l7a-Fj%_v(WMi?-!Bhv1;Q3TH}M#mEb^9Sy%m3<-@8zT*BZ+^z+o| z#}7O$A`$N4nyl*r56HU2k)`wBVcWxs%pN8~l4iC_+Hb0LZ-x^Hc{WKEq8+^s_Jpy# z4`~OQp{=o^UAw^K2`8OCR>IK_H%O;J10da|=VNHs2Uqh*~jPy{*UBbINo?5rk1x`J({U>#pc6HZTy|mx4 z8CNnKQ%AbOsCQZKUMv$yT@O(mOW@%5mGCeu^r~=ak6^~;HhC2Ok*>tAU9$DBxyz_b_O2Isu%)` zg~02Sj^Ll(d=E6xz_2Sz-aTIQ0M^lFPv{1RMpkxY-jg-W6{Eb_61#eV=48rs$iE1X z+jhGYZ#5G{%XZKs!-7cCbLMBPm0K|2iWlX5u|Ws;7~3{1H_lz#sR62s`nA@g*TD3G zV36DV&sYGYsYJN|_%t~Ia(%=FjKQE-DRb&bb6nphOZ3{(MG;s%W>QgdEuJCgZCQq> zyD{r+d9=$G2~N;fjcD7^6J7AXUB}WtepMC5pLNE+7aXexwX7UhIt&=};RGS}_T+JA4$i&{Fu&kMrrf3ZGFxJ=D*f|u_x{7(zC#MJ zlee@W@FPeiEU-)i>8aa4+hdd^s1lP7o-jb(m)0*tZs4Z27Es$5+hHIPa$?43UPkLo zZxHBaIMFn*t(R4hX5r%M_n(hPSOTV@?^O~UUN2nz_)BoeT_=Yi6Bh9V&j#iTihrOx z#I1391p)u~KzNATz#wL;#Td>3zsiqob6oX$6G={#$i1fNXAFa^=dE>QRk`IoS|GeJ zc%4_0iDRsj9D45YDt&|Y(&&vrypxV}8t?Vp1=fy9rn5o(xO6L{eHfQ*V=opV5tR*v z#%}<+`6%`5C;D=XIdcSzZ=s705U9VCvfm}S7SiciDjn5u*+HO#->iCGn+P(We4UaW zKtY-?D3YBo6aBy(u>q_3Sw&axjE%G=cAjwP|1%b6ds=_(siar>aumxg6UA29%}E`1 zt$gg&S~-+c{bb}TamWSdf@~;2kzys8F`Jc|=%`{FOUjx}qe4q_HZ*wKgPW~hqVaiV z5q-|=Do4@0@3^!JqR@fMw3+0=SK4>bW-%qz-Y*s9S2H!HzDAv62wbj^jo=2!;jtjq zzNx9*?yBZ@LX}mYJABr|hY^6x)-)^ARogY&f9b8IC2jRAQEmJ;v_!49x8J+%OZnTPQ>I@ zGvR}U$MjQskDJuEeLAx;{eA*~(hUb9jKH&h!+QdkT#M!RR{ z2e}s=)8Phk%+y)TO#H{$T{(nUpawAzYBL(qiW@1quNb`aQgrKR@ffuFHZ}2F;wtDj zDwp9;y@He~C1bc)_x>GPdl0l+#K=w{&HPc!v`A@UU&#mS(E*_wGx36B#8;KAMEM`r?6=ssQClGHu>s#t4qg z$Lj7iX+pN#cn8t~3L>L345PDQ?9#SV)7A(7&m&er9l9aAyIFsL1X8?7IbsHbSt)`I z0i#F4JIk@=OZTuUUfW@uJ&k16umr17L2dMGy1iMQa!YQsqj?aH^Xd3+X&y6L6zA$I z?~~Izh0hxtuRM%XJ?BAM4pj>%v2P+O9*Ghm{uSjuX-}r%fR-JhondTSE(>$I>rS*G zw?KX1y|#DmF8oaW!3{ku&&e38$0F_k&>=s?9j4hYtLZSzQ)X;i;cDEY0FG}A}BjsuR^6L-v+RlVbrdBpS+3pW6MR<-;CkS;rR({ zv-)qd_PfjgmgKZr`w-3Y*4o6M1a?fVkgp#t(YtCJflSQ4ocHG2-m>T?+Hn3K%e@V( z4$?|3#ZmqhF=dkeC~(Bn=OJO~v_7@^tUNxpZ_;yHqkIt=nOg;OQbWlJM5?PlDR?a} zF=<9Uqs}+TCppG9sKq9O)C25w%4A4bW08O`91W&%x@q(>%4nZwi~?h&tvFr-cris| z!=ny;?*1n1H1gZ`7h}6hSyJZeUYzge#ijXJ#v$`#R;;NLG=wevkRveDw7z1qy52OM z7g*HOIPN343EDyplU;&xeK%jj7q~_aAJ`NkatN=Vmg%rm=JkX%PG|emBc;J_gWmz;=<=Jd|5U z^mehDdhh%qQ1)sozFNxx%PJ_ZhR$ctuZR*Ol!a;%CoE^A?s+ASdM?JHahyHIZP25w z_8TX#MdUKTD~-{M<)HYj@VvHC7>`On(E+6U78#nfHkGu-wQ}?eRe~4jw#gdeaU_V7 z5p82kABXz|R)hJo9B#F8Y`&h$sq7kwwq15e8$LB*iDCst@2kHLiNezW@0H#^*hu26 z*y((ss+*vw@{>QR_FZrX=Gq=iV@S;qpGtZMcP)L(Ix<>s`wHw6CYt^7Zy9ZJ7XH$I zEGqne{2=?sn6xCVi(SxQb|{({(~QmQ3l7XXA|TQ1}zVyj<_8xK1Y`E z*aTvcGOTNmF}pT-=m4bQUphX!>;w+;xc?h+17r(8-w;Vx9*r8suZk0a3~_e(*h~wg zZ{z{v3O?ZQI)B$7BrZ88tix^jQk2z27z;U#UdMCQryz`v=QSDE4rCRxR8 z%g#FBd7C=2_m4`?{7+4SU*h&&@`b=IHu_I%h&dB1o+#y*IQnQ zbc+~5n@;i88?f@yKV=Cyl~Oi?d3FD(7A`S-yZVxZ#^bL(aPB|uOcTg<(zN|jdP3;) z3qVdeOvt~)Z*$_>rzw~QJcPurY+U;!+O8e;KDs5^W^yl-XiGKSfwy`IHh(PLv-7!mR z^Y571NB)&B_+g2n4lVACG1Ef)zx*En;y@k03q!JgWReI3D%=HAXUZ0|N%;3aTIOg1 z9{%|<@vO_uf2?!*A2Tdlg4h0N88I@66NNh>@SAyu3&8(2B(^O$G9VfG1&6)wb};Ue zn4>z`I-EV2f&ZVqHxF;)y6?R|SO{=ABqeGaK@@FAkRnsEO$K8}al9zYO&43dPTS<# zX`41_Z~?bBN&VXH)84ct>9>8m#BQ40cp0v8I#^o z6m(=tphO)m072mXaRv*u*iPcumOS6*!2@9S<;J$p z+Mal*v4cpdKsFd+sJZUlsK zvy$YT)WmCp&Ov*}%owRgoj*32mqf}1;vz~m5F%NS+}qFrW!OHQ0Uw&MRT(1X0{u;0 zI+v|$XKaOxYQo8(KnI6?A=0xM`omoeHM}-*Pu9CHcxu|8zun>G;XLQdT)G zA6g~5(zVq5X3C%hL?Q*sXfo)&dpo$qB`JK=c%1*dw}ZzVabA__O1shnsIp1Omp$V= zSxg`olGRdl>T)~%w;~Hkb~S9p2@CFCaR{eLmzB2srToUs6YOf(%E0U(cdr`f4mpO^ zVK6u`#$O-Z!?!!XjX9^VPJRq)nSt%Dn>;45mKj8f1@4;sS47xh`{9f(sD2m{9r%3E zcQQwOZIo>%bC`3Ac&8>}%~?gHsAZK-vmiOCEtQ=nL1I#}J)0pL4C!gjf_y&DdYNU} z{$+glsjm|bhXEh+HwMUVD6z=4_^*E*ezX~WbeVoiuKEczwQLEPgZnOr`>ukk{|i3$ z7x*a=qD&K1$=5Kj=FbNS;$!8tyIJYl88@N_aL(ES

    hbOaAV}w=h;&Jl3(e%x-@= zL&`9iy;B#fhbl5ejL`fWvNE^wKXe}1P!?l_ zg`7%|na~!t|Y=sMYt5+;<<%g*Wx z*zx4Onz(Io6}632y@J)HCgNF#_V+%_ye%lZIbWONQA*o#W-t@$hXB=r~l={@a}J%eqNXL zDyA-gjX}6+LMv(?3sI|}7vK>$Y21h{_;7Czv+*cj0z^7PLsD|{UP1gLQEW#L>rtdX zmEnpWMYux7+Jf>a*EHY=eCfr3`d~atAZ6fpmkrv2azauV9-(xG5$WCCn*hAgb{@`o zBu`3GtwvQTyXwG`q;nY(N>-Jy2_;F+NX$a*Sx8JTe%{lQ8Jv(HzQheK7u>wE6_R#Z zV%O!NHRtuVoS?vVbGlYY*@{{=nRov;8YJcJxHEsGO*sg<>jhJI<(we0N%L9(#; z_);z@o1V>(&SyvzB#C*6-B8>Axl(U*cWHjZ-d5L<}uS>m)k_Qb{jxkakMwSw% z&8v{Iav_QE+o#PJftvEs2-Q@ziQ|&59Q!J(!YPb!idBs%C~Gw>J~WBCM%Q!K`R)QA zHBxr6riuli3{IoKc0cusTF}Z_b51eXG=QAZ=U_Jp>?TpQMNTa>aGC`2WP+RL4l~#= zz)dS}#H!nmwcKELV5?q#^g6_2&4~7F?I0>j*sAs%_~U;>vxG%zs@XDp>~CPY1wJ+i zED)qjfGV#{h+3Z6H~jek7ykJGVQNa+Wv1eSq@>MMSSt-uD-G^yy?)Von@W*dWw0}L zd9^%Ss| zlZbh}pUk>6a(Qy`KBGyHASP|ib}pcq&ILWcDJf}oKY6r3y9oFkLD0S4K3fkaeaY{# zWf>Bp);4<6^T2U<=sO0#(^u;QRooK@+e+wNk`iqH%1EN4~IB9)PZsYYZH?!J$3pXq7d24~Gy7Ni=isbj-F8Rl=8a(0% zJ`hoiOof>Lt1(*oa^xMsFSixw{*j>Q2(r)XeRplkvD;K+ZNW@`7e&h;dpN|ziUQwl zfIZs{M%ESx_T>O5IRb_{XfU-sYB?Liw=IXyosWC0zHA7;OW6AQa$0d4(Tas&-T7AB z47~hq9?mtSpU)5}7H}FDKcC5I$pQ0felk1H`1nDchtH?;!B+Cd`hdRq97ByA)m*d5 z8Lf=X20|pJC4I9w`rEsz|L-_ChV80r6D}!RA!z}29@lwh?FOM$t#eZ6e{C{|EEKBy zwi>l{a->wyxn&y-5_zdf+pvKTxMNnUYMp>!aAu7D<}R$TUd~)lSYbVH+d>YrtcZuB z+K#!bxHs5=6A%>dThF^Vy#-*P(fdBKbZ^|KE4L>er;Rb1f4S z6W%lKLX}O%N_PMtd^WJd%IUiA~`I>=&D*3B{NQf~eW zo^}l;%Cu4=W5e#Jl22CsXe&#*o~_#1R-U*6{au*TiaQRC@zH4qHDgjJMi9*o*-!{` zTJZ-hEj;S?b7*=R`FsL3ZK9^#oU|>qd*%qi;Mf>X6|N*33Q;IT_@V!8TJdTu?vvb9 z{2o78`wT~0j$#%Rk%a<7tsPbOkCD-uGBy;__gzh!y1z3YA$n0Y+6>+0&hc$EK& zM>$$In)&K4JmxBB0XC;IbR{M2rb1c< zPsO9ix^;!ASe=xJ*kYAP-VvIxJq5G2;9xv@M$-0+#{^BLqN8p->)#B%(FNaXhu%$! z2ge1Q6-=cJCgM@@w&2T4pzUT!`Y&th)=Po^VGDL&rm%ibZ*R+oB>O)iX-Y~)f^gXb zg1LBvIS3j&rwgJo3JwfbGX*~|Iu;haNaN~>M#N!i4d z#LO#h-})ZDR17jceh{;uNGORVjHtW6-@VncstmCR#Rh%q!9p8De?G?%-Cg_uUD=Kw)rkT{){TXLbGi zrPbpYB84GRdRpBw_#nPEiqU3av}s~@*EOrrYS{%e0b3zx=isV6?*9rYTOnx6K#?}P znE+*cKfacBS20^5T`TI@2KRsNzO8(-z0Bxe4G?sn)s~y|HLzO*t5<&(05xkazRs%* zc3p50y^lVk&ttlFPR2^BI;}F@oK{>X?jjnEbK~lp^f|9PotU&+YWL1miqz8D{ge}R z%GjCMqWwiLjMKBJw>mBJe45PjX-39|tJl?NvygeMd{xET`3PzxvRslx%sUvf79;Cj zQg#l_um*H_Grp3-cq*kY;BmBXuxk$>p0N>6+q5Pmjiw@RDkgy0l)k2AQ&j_*zL$_= zHXKu2Fg(IXugX9P?1JDAuFdfH?bPn01q|rUx3K?6mux>pexGhx4dIq7{YteBLY5KP8Shf~lz~P96@CxxazSl9Ksjtwc)K z(iSPOaM++}LzZb*0WxzqL`$T=UN>+#n+XH2kXF_DU@jXX>nc^3nu^VXV>Ctz z$e|AAvLT*#=QTzOMBRB)Zthv-2y&<7uI=7AiZB(*U8WwzYzSd0)((yliWHc3)u^+M zVAc_wtlL(TsTlw59L=WUe_mW*<%R-Rb|^mer%~FsUzc^NPMguBxWZ20|p~v}Lg4 zlA$|Kj1q5+G8ESPNvjO^hB~V1*uG+pdqW-gfWhf8`dhjf3Uy!>72D=>SYd;qh7Qsy zL*IOk>sq@>7c%tC<*F*$^mL|5*aD>IGGzTBtOkQ^#T?0^B-LP?GiuqNrr(jz=Lv@! zPaD<#dU$tL&etQb&JRpvLyS6tRgnTKA_Ycl!LFeWzUH=jHkyhjY{95omw$gqzc;== z)bVqxWkD0N_Tz$~AH2FbsJpv2d#Mx7f>V{Ur$YJ?D4)5AJUbO5rQx$~E3>ejT@72Y zS`AtQ4v}(!zPTKBSa98%ZvJcGpQ_7th5K=u1>2@|-dOx_+ssamH5_HC@liJL0Lc@Q z{$*V_VZl&K2N#x~<=WzI_O4;#9;8~7?Jq`pI=epsl)%kzV>~j z4`pzg1lv@OK9%F%)((c+I!H`vYh-gq@x|Y|h-WVlXeDd`ZCkvcf8X^%c%T;^h{2Wj zyVDndIeg4hj?4nE@TO;&`P%{f_-K9WF2dAu%r>G)y9clTApmQy+Rd7)cQI!RK68s! zS2;p(tJ=xs)6?woZzZ}mPGUl`{kaS~doM>EJ<4rQJdR};+%)Z!d5{1AAOJ~3K~(=e zcFf$)-4`9IDp_}CMs*(9IJ7#ZXzOaU^{$1R0 zYz(JK=crXPnox~i7(Z)yP;(}^X`L(9Xip&;PcIiDXp;$SM`0p-4xz>@s?h{L6dEFg zf``d1?bFQV0vP!eTnH*?qUKEqKw+t?mYsJmXb{A>jX0!jm|K&QfSydj76g6Zk16c} zR2g{kB001hO~sroXxk|mD(Lr^&j;fN1)m;K*pq_3i*kJShh4O}q--;qs>i*@OQ=~@ z2hoIVBe2w+-*FOt|IebYd$nw(4dS&wJe*Hhv0~+E>cUg=)K)l;%JTKxhc{Tk!)p;< zp4nFq^@`cxE4ky!%c>GA*s|rystuXRUp%6Na#OJp$&c(P zleS>;6vfC=Q<1X;Cv0(=bwsQNDFm4%0cf_`O0VRqs)oJr*ZNVE{ zGW6+qlv!Ia?pkntalPV-RSI*1;_90uhm(?7TW~ZU<>)j#@mCpQn-unwg0QIwn~MEq zuoHsB2PDq0;M0E)r8Ob>rm1lLFbW^8DfEJ-qU;DtFQT3aCL{qfxM)9TwGmu>k3#8E${ud)PZOwr^TMw8#dkYTI~wlvr7jn3LFLZH;U-8w}5mkP5gtVJiw;H+QU6mpj%DibaH}9n`;L zMWqQ(YgeCN7_|ihc9i!fB=1Q|%D^`)gRfZz3uxQpdfaWje9yJ@ zRpT{LuDwA23q$&~64EGHXPD>a2PH|*LhtGG%dU#Dtd}!)6Y9*uXrlu)_j#PLV#E(c76;*o^|w zP*c+~B{Ao51yL(7HFG)Nv ztCq#`m_GKw;1O1lT6E15&r9&bF5k7N8Iu7_`lkm-tW<04i^oNFqty&yUnYzEeJS*#&m`PZnog~OUvha z!ZJt%C7HNl)tfTh_yu^R2mWBC;?XkL-xXL-8ML_00}bx>i@-@>v-@AT_q>H#?(Z^M z?90=5YFR4wm?yj!vWM3tPHm^OwY61qd2ZQq<)UT0HjRf@yPsScNZ{esMex)o-kQ$v<2w7}Nn7x}-k$2dV(AQ%w!n!;nX(1< z*UdW>?WSVfqH1^C>2~19Eray?Gg!L~?B@i^7Ch41L)%&GwWjOH(OFxtG9mdk;6EZL zuZ8ZDaMdCBD>vY9AR+0$0N$IBn4<#Q7F_UIgA2-F_9(9Yki@hF_D7>6ep~Y87I-uS zANWtfV~y}+I#ad!nuV_pecsTd* zwYUDtX{79_utTD1R}7k{bwWCDTAenpFy|HVwkU~dNpf1^goK{IpyyjH298Ut+J1qV zSHwjWJ1DAl!xanT>b`@5^ob01Q_XT1w3V^5Ah2E1wzs_pb3qZCS0wY2SXhxnlJXmx zm_?FU(7|kiVEPq_qE_#keuYz3*uL}sxjwc3QK>)9w;)MnV3>#V6Qho(jOSppsn`@# zRpspYipoGS5Uev?zp%Lr`!C=z>vXJEFh9n=K-G&I*q?Q;AKRW^eh_8r}DO{^}@`)SZman1Z zm=)FR0^D!Httq%G3AcXIonA)MZwpldw){r}RdwX@KN`UA2GAO)5wiiH_fH16@=pe; zxo3eYDQnKCs*^sVK()SIGGVIhoh$mR{@XD9#6V+U^9$q~JU+n|%RJ5-@R7Uc9`3XIoZ$Tq3 z@8-*gtSzdfY^SMM6;s5L5+`NQWhx%C4B#MdN=Wutx(=D!A7N6q6Oy`PywZG0!JGv}%b@7SAMMXBSzK%yv#EeMh`l6Y&hs<;KPnv5!eYX=1QAu%g;4%#N8YE5h|==qfod34ab zvz8SJva3K+HHL6Mx3x)SMP08EjMt5@U@%uaz=}VvBKg@GbZCiNlfV6z;=_Kzhm}Rn59a> zCMS<@XY=A*!)o3{&BrjBEuyV))V$6~tI9Dlr8I`m&21cV)v$mH$B=Ca&1%kpT454> zJdWy!A=f40e&7U%DI2=9BAapd;)OvxXESFDj>MysfDR-pOvO~npa>K!1I!G5Q^8qM zCp+cSua#9az;$l^<&~0Pn?A%X%N4&l79}0aU{4Cdx~W76XvI~-Qf)F3LfafS10C-F zR7W43o3_2mg?OBZhgSmLV47DS!Pm-xcq-c0!vkNlE%wxe z9?mD|MpT*g5EoNNdImId=hJyvB(Y?z`RJ2c!y-idN}+p#i2UF_Gx!Jp9366u5JE3uaTsBDHMgoxQTNful%@mVw_^6fJKwxQBBe?|kEW_MXzd zGz+Rmrk(|{d9}!X7$AKjgVk(cHS1@?YB5O8OVTQ%6|oJ1-sPG^F-zKln37hxCgvq( zK?j@dpkVmu2=R8kPCB2_k-;+92$E$+ zSyoy(3k=VX5D!MNdUzu;Tw+vU)1XhYIV#B~mMj*HnkWU9Hzu z2XRf$n%FJ7s;XOn{?Z`H;?1mI_Mt`h$8Oe&+vJ2Keqj{5MIf4On1SR`N$vL#)mER&izRx3<0 zD@=@*6uceS4Qh>vT4Ta50Y`zy-HW{%L{{&kE1jVTOaaqWF9#*}nlG4&mf?}A6VRgT zP!>9c#Mv+d-8TFN@MtHrCnVNa4eS$w7E7_*%-}=2GW+X36?JT|?$ZqTj)DD@N6c3G zkKX&*gNK)nQ=gZ!5w%`h$ipw9>{ZH}hgT25*J|N7lZw`R37xy}a&CG!UppR^K&Y2@ z^B02$EQ3y4G46J_FN&#Z$K0_DR@;ihb)E6vgyhoX2oI+W{{7DkqCb2SA$c)dwzSjy zd;i2rQ}Kg%lpn{V96O~Gf2EuI^_U|#W{WBT3$VmgT$GeLS8ZKfYswZ}n2=Qx)_zuy zyi(#E5ZDI=5BB!3q)r`czCrP2+kkf|rd$AoY zgTU(H5st;96l_r)Y%u=ugUoz8N-(BqOiKK48iDJ=t|(>e(Yxf#cIdWW5D!Kn2#I+KMYPhjL6Df2 zq?(QDwtAa-FpG)=QsC!Vxq7Y6gGn1NDsq@cCfE$FP-_{ z;yUicYBjLKg5kp>i|Vlc!XU|GlHN#dxxXLpDzo;ML4v>=ZW$m%)u4g^@bH}j0Q}co{rG?zzmwv!W0HHe zybZfa(CxmbQ{T|U<<^B=#HLkM;aX9=Qik!BcVkTI>Gv$Xhw&LV53ftkS}P2a$0S?J zwOq6nSSt;Z6SBIjJf2`zqeE)BA~7McPO(HbmRS1wuUp)9QS)^w?4}f|Y@$jrjDUsV z)AwJ7lBkf03?=EA?nQ;_);XC1zb0=9f%GMz3}UHW+x7^sj#{!_;oc(Ps5?M*c~TMv zBoHzcftb?ye{BKgPxt;Y%ZeBZ8ld|ibRUHqJ_k#XJmExH7LybmK@*y;pLGwbweAp` z-QR6)ISH2_;Dxv9;v?-$O?hz<4<3Hren@@H(X&7H@QZwBdw6vb_{c{-GT`_7$!4?M zci(-lse`MGVAnQd?bV=&C$&D89`ZKUt&0*4hZ!Dzn0!9(T@(-J1v)#|vToga4jjlZ zF)`s?kY7|ikPR{J)B+AyBqbtJV05U1tSva~2-cX2li83CruaZa3S@>lP}vZpu;i9TiMD0zYs`LxD)N zK*3a~NP&Dd#7XyjmzUw>ngZY5T;Q>p5RZS+ppXsm|FkLkuE^m$CCKJNoaiiY?8A~L zLonkAa+bmVe=vBm5gzz%2lM|+(%P3}&Jh%|A!dgX%8 zs4g2>C{+LNe0~%sEXW2zWCObVCuSr*V5qUSPGVMK78On%QJct1w$Em8f`V;@9Cyr& zk!=X+e0%{xGA}VvmgjDH{YjeDJwX8aM~M_EcM28!J|<^ahD}I1kHqd$nKiN+X}oFY1p>O`RYd zZUkW6y7koo^_6K}%-zFJQ?}aL+Q{egUb%UNam_W?ux8B~N~O|kQ!#rccq-a+uTfS% zdfy|`J)BSI?%o8zo;~+_7vmK`m#OWG?@Jl{OFT-asd!gH@=Q!H1H3sYc`#-0pk;8_ z796%~IBDZZFk(Akc_$n>@i!g%v2n+ z1;=f{`h+CsDry0qwG56sdR_&o`wgu7_4>!%^-eg8JL?@W#RW;pihmbae-Z@?T1~}C zcRT41W}po5o1?rjox#osF3y2%8N}BMHl#C5{gH%tlxbV=OS=W;rHb8A1yRM=6^iHH zrf7a#a5x^N(NxUY0&}Cn-m6L3rAbZ9&bhY61xFB_c{5W?k!gOA4pSkJG$^3)D-=X{gC+5Xw|mZ4hd4isQynM%V5qcdJWfp*v%PxD$IGU(ukE*HQ(!* z-~fiyjka(O;2Ztw?wgng2bFw%~~M?v#3bs zsE2tH*c0g1WMd@OuW?Nj6m}N!WAN2~t%g`UGpuSI1Kkt?9n{;D=JwTPM%dUYb;opAziM<7w$f7{`H}|u;*&)+J1rUuMH3) z2%=;&JgqH=D>>24qQdkm(kCWu0b$QZ)tZc;s#@^zkH)>AsQEp-7KOtmOuB)-5-)Nkqe7txPmqY@FH1 zhv$o)5N;?BJn~D-z(fU$xX*$Ed*#hTF2Ddzy;hVn+ z{X)_m0kQ`FJ6UOTAR7JJ0Ghx4zq(MEUoX0L3&!Wgp!&(#s1GeqLfg1OXXoW?*#cbs zeb&BDGT{iFYql4A7Cz z5Hi)GX&yYBE2xmN?Er~CQlE_Pv z1x>0tVS&|jdSK2D2vT*{!zP+Qt&p-#P}>&T4LZ1O2Ly?{tP-qdQIT|sS+lG#(ZTMR zYfbF90dag_`V@9qRp%|*r%&%EUCLnl1(ugv_GRspRBXoD+S*>xzDalYCT{@b>kN)9 zxZE8m^_xiEmz4ZXI>TkA;t^Z0*;M>-JoIRqhP(DjWNJ=zPofea7jF~LEFD3LlQeINHoD+C$DF3aqsEn z(=Twsg3DWfn8kiBe0uJ ze+KPFfzu=yA3vz=e5Y(S9MNjme;q%_)%oM3TaI$;hBvWg%ax?=`3$}#X$IOqKzjTO z#8*eL8wIf$UC-aydR^7}_txnh)q!Gmn;=$D*sJ1vBC`Z*nL+*CGG`ULf?L_qbRE4L zb$KwF>dMOuB#%i3muS+LW{VHau4hN+R*ZnfNNBjasPH)$vngb264hj)!X{$cMohRw z>?#xE=@iB@7Aj(*mYWa&b(yv}regNsGNEdn$(q;>ggfwL4rp}WXUZ~YO^&bt9Dj*} zQQF<@w3~_>#}zAtU|$rz_71S~g5GJjpO%GH3CXm3C?&U)i~-$f61GxQE4gP|fuB6) z^@}`s@bKE`lhns8>-#13%Xs$39!@PgI&FyOy!2`zc&-;9PeuFMLA^@W%O&gKd_%<| z#4Fpc4(_faH@i$lr>S_x?W8~WA{}#S3ocJcvX0=8Ef}#3WRH-2`A2X1{6 zGhcZl;UgEbF1Utpr?!gez3X9Cn2O!;D0|M3o3?@uQ;|v;WWH*UxLjhcQCL5LE7BP{ zOvOX-C^>iC6Sm+{m)u>KkR*RqQs@K+7_-3op-~MYd`dw069y+n1oqPcbDiRL2kfUH zj;pl&uw-=um|Y6{34s|^96Q5xN!?>`bgv=`jdTD2AOJ~3K~z2l5mShmqVSasbapmy z)K*Bh{#=sK#Bzm%J@wmzhjRt>q%5$Agf$C_CcGO;O4EJ%a95h)&B{107uGikSs_{zqUb679@61Xtiu!*3`Xj{#d73 zke=7uvi*X@g5FMVK$A7Y#Sv0|1KTI6YS|P9>0$;N!1U`NrB(LG*_R9Tqt`2KhDzV0 z5&(I*10fZgSFhjmI&K?T1~(=p-7YD6iK!^V&qc~sU_T;A{Ej63cNtP&FtGmV^!J6c zS72`x*n3~zwn44U?FETWg)w8DRViCtCU0TnUw9eWlE9cg^D@?qp)HRaV;FN5v7jQ^ zEMXSRuy&F7YVj)oT%W&_q5SO-275t3362C^b`ad zx6(hmi+FRCREw?)0S3b@)n$f`-%js}9_*md_2|3-CCOJ#`WS2+V3j|G9TLPlblsht zlkE8L3SbVdcnJ2r6&~7z&NI7!&Kz6$F5{z&|Dyx=(4=e#Xre~WR&tB_fvJbKvh0do z1l(y2?svuZxI*fF|C0lpXj)8+n{%pKzVCVDQ8H8a0`Qv)+qmuI4tm%1u=nH~;@DBH zo|t5?p})HBuE170ZzwS{zd+~I6i)^H#G3_1z+&U^U6`}ei=W>XfjO(NmclL3lo_rTu9c|X|g!H|7LFLx{;B_N;yhm6jM+JqoB!I z0At+J>}3TZkZ(+2JZX`6mrJTY53E6Z1?Sw`;RkWRX3aMxMc}9{n6Gmbs$Aoe+gEuh zM@1#;kyakg#|}m%_~`|RUVVHp zo#7cuh(|n2IZsl0&xOkV}S2TM#i7SzE9wrm78C zIbLG?pJ4sl4+3lG?%qsT&NBYx6Xf?BOifL(!c<(GkWAQuC*6QR&KCSzz16Qzt7R+m zDxXtvxl7u9{qus)e@Y+QQd2SMF5B)N+uJ`V8T*QX{j?y~srY0soLJD?IB5&ADTBk7 z0e_jn>{fic9X6yh98MYZ9RceegC~1?FxM-Ny8CW%t-yTuy@RojA7pAOO0%ixOlK&# z%Txj$$}(tl6zvJg3CkmMJe(Wo?%u?Pi7fX_OrCMR9THU%HdY~NTWgBi#Iz0&+jTi( z?FNCpB&yXv0f7}Xu-d7TwC228w0s5Tf_|2(3fDSV4F=|d!t^N;3v$u=PH?em&GPH# zFBLGb0CrWbBa*j`6`?NyV3K*Cu5=fk~7f5_1`zB`!g#0{x6py&_P{Fp| z9{x6+;c;8=s4ckrWvru}5kabKXj@}Ajhwaj3hcjr`7P2twd{*SgQ`p{9~Y>Xfcim+9Zxkl9Q4h zn=j`fc?3C=sGj#-;ySj@?;?@YmcmR*lE)?1MXvRf$q^EhlDow9sQK6;;`Of9>*0j{Z8V=*eeEZsJ)Pd+_jDglB*3;f2aZ zMP2Q2Ij;@^ANj~f2K;_M*=&~k?z`{2C{)@~Z1HFiuYmoc8eeVn_QtBDm6tHu!})~H z&b6#tx1IwBGE7WNco*a~fZo0w%OeG@?8|YHsd(BEOlCv0M+%JDg2#tCs>|M(&d?qy z@WfCDSx4}bx(@v13CTO|7z5y8%iu_z-SH|@vGvnWFf}!W^X*9{96|o6HEjNsW}4?a z>A1*G=lk|EVGEAdStu_z6~DZ56o6k3C`>~UX)5r&od!AQ%p^#5sDnvI@V#&8V_TPy zY<7=p($TqTPdI{iFE7yd-*Q-Y8*INh!-H$!@!1g1yXUJM!PCjWc?wWfMBpNMqe?f^UE$MA{5xRki!brh*%Sa6)?#9Le*_JKE2&- zz8rnN92N!%pX3hz828e_5FK72d4+=^6<421=Xc$@^|ZCM5e_&0RQ;67y2HZ{dl%OO z07gU)r~1;%Ja8&|B!u&bz`R7!_s$&7qk`;_&>5Fa^huI^lE|_G&iN4Um8Z& z>_jzc<)O$sr_Gllfoyg2eij@;3)$+t%+l@E-(4sBPg_?7O>*Hrz3rlnC^}?IA)J!H zDGH_vk5!k8&cx{pXCbm=10l?!BI^$k7g0T632+(&PJC{pa_8oI*LGuWysSzUG{^9!~eZm7~QX zrP&|oi|vCh(NEvW9NC5tPLsAeHs=(PVu5|_`!Ga}P~C7O%hp5B^2vFs^~uRVfYF{e z)82KVTSv5W({ua52ScKR@2l^jiYBUP(h(lg*ENu3D0e%D8$wJqKSn5^%g4yvFsft{ z@*QTw!u?niALC^BF`jL?kX)dTT`gPrjpI*n?es33)>cBLEGlGTFBRmP`t)UOf*PWW0V#{3*v&vLV4Ze*dwjg}-@8g>~L1*WggNN~NMM?BX zlD!gZ#NdYE5sun|ADtoJY|a+EHJ#z8E%>#7V)8J2x9)tF#S~xvCB@f2Wsta5VjmDZ zo;G;=fT*f#+f7ARQu357i2qF#J0oZ_72k;|oWF^p_6n3ONZA7Ul&IRfPOW;9Xum|J z45VfJU-sTUK8~xt|9$VSc2*BZlD&Q!uVuxFWyi5iV#VVS98wg@b0W2r^a3G;rc~Xf zEtK9Qy|=W#pDf+d+ZF=1Ep4?w87PI+n9)q~{_D0#3mpVw<&yE|ugW_ISxnRC9M^Z9%^o75S%W^&Umi90M!C}Q?> zYXjwmB;tzJ`U$^Ew*=MfBnksb)x&ERBu4#0&~r!wu{k+pi+K0hB#*d4p2ZPD{Eb z(n?JmoJoIe1q7|32DVO1;su9fP^T-ah-X5Oz@d{_?PI~WFn+a+QDCm+ak1>@S&D7k zxS8JG=lm1tql7QN#7-8;FY6=$^F>&88rMpasb79yb#<%#zW2|8j2JI^U466@;m%dW zZaLG4Qx(7DZ^V?zmUE3b<#F`Mg%!EQT(u^GMt2MGG6yR!Fv=u^z|0Bm3qA}hz#JAB z5s8@-BmxeJfKzl4rYF)wQ@#g4Ess#j!4BYr<2d02-P7%?$jvA_<2eU%>bdKL+SngX zAcF=Qcz_LeKZP_RUhlqWIgy9t$JEEfCn>6Ciz>(pVB((@iJE=7iK=b40V=0xQ8hH3 zWmKD8w5@R{THM{;iWewu1&X`7TXC1-8X!>IX&|_}I}H@K;#S;UZoYfY86$s^KN)W_ z_L4cDy%t*SR?@1_O^ zh9cIx&^efem$?@P*;SAZlllq{n=3^E-op(a zi<4ZM@?5%=z)zVGvK^s_lpS6cN->%Fg+t(B6d4(NfZ=J2u6-fqT6l`&5#5z`eEi`f zSJf4ofY1BAWx4&VZ0Du?N8PM%$5U_+4<#n zRT>}(0K>R;t2t0n#z9oPVclHHd`@BAUNSC)TKk_l zmK~W1tbkXko}>JF5W(Al`^C+I|*+6GuKU`CQtMI=Sr?>f5egC`XXHigVaffO5J_-5+`AAir5mP`#~!S{h3n z097VNRp{jVY$F1137ndK8E(>Ml&BDP{g5=+WL~Ra@L|{sV^WQ)`8=& z0gW9Zg8Fs2WmgpDusYo45@|Y)^Z}qF@3t!Qq!mg6XuQf(yR?gnV(CU@g1dk04~O}l zP-@3)$wdRuh2BQfN`l)&GXE^{xEdWed*b)1zNU*J)0@az3iiYue8-F*3HboGi=xJ~ z7hCl@;3bLharLg=)&R?j$;y&D$&o1f@7zGMxbwkLwx1%)G79fqb7g*rGFG2S(4$ae zi25^wgD2QMbk_B6&J%gIJIJl(AmvB_tQe}r9If23WJNMIB&_|Tz?W^{D5b+U)4wgK zGtx*33-nxNPT(v0v-kIiAkGrRM5yO?d4GDq6XS->J>F6rgKo`vQCV4}0I6zP9_z8{ z>i3MlBRx7@_;9d|AsD~Be+oRzj@@4{w#(?;;KE3wF&91JJ$(nzrmv=$LDx6`%5V~_ zLvYpt?>=_=zKAo4+$o?GYSyRMsf*6$D+89N!wd+D|BZ-($L{{V-vGIpbU zk?Jq3rOBY$woO`DZ`|7L(uc-POLN? zPGMQu9pC&r$NJQ@Q83IxwULfurMl+IQ)lm9!lM3bP${`(2@z)LChoy~d5Dse17cK1vF6DHHO0C$-qJKI{b2ydQGil?_5?uGSQV zLe36kDn~hrGQ`~i1ASq`7i{kLJ1thVlnGaxGzmRH1+ZmQZgB%xRZQ#N$9k1LCw z;BdGGosVt2@T>F_ehA`EmZDJ<2{Y~FGAAvp$FAgRb~( zN7&UyQg-IPw|}qZ80$JwLsqO-!U%?ktWJwxk6QM4rJbTqIQ5tyvi{Bax_v{V3h^Lf zksaN2`cfJ0WcvDfOxwY(96!*vwCb@>vc>@PV}y`qc~NcoT0Talg#;O0iO^6@OO7z< zb!q}v1td?aP{TvUNF|V1Xupq2o5NP5MFyP-ZxOMcGt~sf;BNn_d&SOZv>J_{&A>;%)k@2??tBmE zb#G4i@8TUGP53Ti_;rujuPobk>ii29{d~y~w*+{+w7fIM-%w`oug;nbA2z-O}_)-TvJ4#~+6K4nqfR zLdXUaVKfk!pwk)%=9A40u;Q9;)6yDcwwr!MvgbE}ZH)~7rDwpW-n#A+=sx0oQhpKD zF44zsw8}d0;?n3j2ttSS(@q(^jOH}gdTZfZ#8u$o?44WG*1zj9+Zqn*?hyiHp zE^?jsaw|t5UOE?-a~sQVAUipy1lk6a@$|@&HrC&YQdd3(T{I3h%j5!_;==-ALgT=A z_nTj)Nw3a#d3po6i-`^0Yt}EEJchG?t@!fM+$8!ucWnW>0pMnPn9|~@ojIu?&=HX1 zmthH_CYF~`5G5S?%)GS7_^^CG&%GjLpMAjIC!|z+9w%J4j~<6HhSeR2Cg&&cD5?A*7^_EF14pE% zAXk<@#s7*#OH2DQCNYh$>r)C@KIz4HIj>s4iRkCYBTzGjtVHaSif z(q|V|l~IV4U}s>0VwuJibNBzD$K*(jJQ4$%tyrX3$h4k4$m7E_+iXYX1A%kj!3DkO zsPUa8w2P`dVBCog`gAAo=1jVBYNl5$nxc?HL7IfN>wdQbG~>dDX>wI;Pr=F~YF4ix zV0OU&QLom6K?_X~FWh!V51N~w$BmJWmL6BS8wr{o7)g(4Z=XlUzslq)8bg1YIrh*@Ny^`?s<)2+?5IDVH;f`))n3;8y_f@+=C6kgW*vc~As zdLqX2g8;{(-1oXdgN&on)YcY-mer18YMQ*0@aH|mX<9mBKhLDnkjdRk-LJ%vF=}Wl zt~v$9;H0T%vhYZXp5DoEoSwcYmIyJ&Fb90hBjgudSV#>}73*KEY@ctBOT0Q>&9jlR z5>k>QwRO@}^if}qAyioYD#QCPD|eJ9+?Ic66>_>w-iJ!jy)VXt&pyfnZ)i($vNgJL zI=Y86<@iGM^oP!TiN+&gT#v1W+tq?wS0khW)^i4xN+oM9SV>QzCQigLJ1wUsDpV!c z2>H0p%qGjtbOz7TOAho_C+oP9%L{TAGl$J+PVrMuSBnRi$Y=zXEu~Eu$%?Y-^MHe- zcUb+8g|3&;<19ENOzBs0@p`>F^W9l$8X8j2vtRRP0wF)MOL}@h=MP7K2S2~_ty5f} z;h*s6{{jfh@&x)Z`WW)+Gcm=Se0JC|hC)jQ?O~N$)V-hO4ljs_k-bkZ*@} z5BIf1jx7?-wQpf*DaTAhDH7XY$CPEffc_UR9c}Y4@;0WzK^m+Q54lX87d6}(dV)I|*3D7W^;nxa+M2y_wmUdu6i@#Yz~ev~79 zm@RX;&R*qtsV(@E4Ex+U9DUybd%gw*cRY>kj&LxGfm99-@xI!_i7gP%zg;L&H0)cI z)`6YdwG*EhoC8Foh8dL_K4a(rprj37H`NCxDw?v3B*xw!#$PEBNh!_W0L;} z5)Kz03sKP#Gg5~@OsGFV*W9mf?otYFfF z3&SlIXJ~{Yr%f`dn6#EH2N90j8AYveq^yIU-E&Ej5*0 z^=Y7ewEnc(dXgGFGfzcFgWBF#Y`pLIGmT$uxFi8Rhrguuu!!KxLO)Pp<-hlsZm=Ub zpHNE{N;d-w(~@mEyj;sF6Z)#j*}C00`RclHgbe8HgIC(Z52_fRsu=nabk9>7hQQ6x zQxJUpTk}ueD|AZB{WqN!5{r3n-6GMb$lqg|qOFBQ&P``G+KF&kA zy#1D&aZ%@H*S(96>rWjp(`Alp6-1!-&V0_lFC9k+R`4HLscK!zE$m)1;5ANNa309apVf+ z_K6st3A4F*%L)aFf)xbuI)%T%&J7ttU`D<@T04AeULdLUL4_+e6=Mq^-O*zj)(CiL z#o5Ab;KaN>O^UMsnv-s=Qug@OIWD_XZ6-0AFgy&N&~H}S9w3E6TZDqLvIRzPfZ-p{ z&p0u)E*rc-<(oVMq*=V3h4fOx3qGp-W~tOakrH*ob|{v8CUKyp0%VmWcskwMZPF@V zZjK_eG~(6Pn=>0@OknkhxE7(yc=@+mREy^gujz*@1D>2ZJ_>~+w%9iMQYX*JQsI5~ z?+bS%JD5HD*aLERyV$cfk4x-JrT@nQh}ZbWM}ZT*B33TB&Z4>x@MWNvOli-m7#*8~ zlhI%0FI4lLsIC|k-cegwkcSfh*S-&DBL^$CUEQq87X%8|(P$m(W9!wz5cc({%L4=p z%E@o7T36*dRuB3usJ{^5xr7|@Q!*!_nFWtu%k8CrnoY$(ChU3*PMV%nEJ{v3=#cPF z8EL;2w~H}5DvRhU4_03FvY0@ua9@=8!?{b-eucu(^Ev$?;S}39jhuHmDYDATDCYkt zt@klQrmjB>n4>;Ua6Q~?^NfF40kUAKFl+H67>Qwy>I;b^*W`ptX1N9ft^q*F$iIb5 z+TYTEEy;bZ^xSFg{COT+R{-hWLfQ>go?jNb^wwXJ(JNkuUDMV1H#aIXSV>4*{Q447 zgd~!FuqDOu&c2#PB~4V4Z=4tq^}txm>v>>u8_<~#wZ@1AxK%IXJnEZGb1k)-wgrj# zj=kE?^7l7=)QdZmw(s+lhDh$RZBLNJv&8Um)DBzkS(t3Q`dC(v&oX6{3>PhFkSsLn z>)0dxys}=1$_s-V?B}SW#h{ZCUT7>R6&`3FWeWWQlOj+TPU5t4i%#%Kxc`-og}l8# zf0Ms1s!L#ghH&+`dWqZUe{Hgor#``6v^V>s z6pyyD;Q1Of3Q&+54j}qtxTrQZd|uE|Ul%U>vO>a0Db~07m_${(B<2|re5$}&Nvf<;kLx^BGdgJIrwlas=$%)xqQTB$p<^LMx9TxA#* z)b#w-sKR!DlRbVZs*GKVk@C|oc~lVm^K55X@zzm@=PAhYOUhWVYXD)7$RknWouB<8 zr!|PESom{%u1OLelIR}>2mxefda>eav^rh_A(GZ+dF|dakJ9I3N}a0=x{XE{r_p=I z%Y-<%8yD!L^v%Qyo?t7M}`JmyJ73YFbF+V@w-cOj|^#40lFqt}tPzo3Z0c z>5k;POrR(XEt7(>3^AMScp)8)R^kqor5KCQz1i4({@mkRs&H!a@P338%CEa>&p+Mm zwsxI{XtY9tfjaQWU>L(lSh5%|oZk;EBZ67sC7y#4_HH z7j`EK&AI4$>hll=D_A&K-9>kkfo&Rw{N%M z>l>}3f*@ITQx~<8>r`@y7eWx;d@HCpALPk#e(J3k0Q=@E2jAw&A?q)`6Hc`h#Naa|i0}XZn*z0E*UUPAx z`V>;3e$NTdNsBd|KqBw_u9GPiFx4{Z9OMa3_6nmj6!$@FXiuTcM$k$Z1iGE%p-QEjWS1=~dqli%5cU$FaWGGqqPN0TB3D_Yd#G5_I-$Ql zS&CMNaCp@+%s+K0b);nV@jJ!eejYoEVFFf;XR-1?B{VtJ!kD~oxZ#Ki&*SZNXe6M2 zOuKzd@+(qKH;9YV-cJ}82Tn}-PUr&sRbuBI#7GvKVCuEjjCxZ4{oRxV7^UXBk91#* z97NLVx&eynQrItQ)EK$EbFSRxzIXjmx9ujA>@Kx(%>YWgC} zvg{PZ@VqMq&%fdJaj(aG6f-xw1wxK@*28^15A^%Lnx-Uo&2;hj%!=W6~->;Pu^9-6d$^bA)g_j zv)ZAKN^}*6{(}3BRAT?8aVEbIt=E^rVte?Wm>dz`3>&m~mVy%6zVfCj@uRaz`~#C~ zIxqXxP^1}!Kx&Rkg2--3%k)kKH<51w4eKsqmQBbxtbz@{!(E*wnY0NT>*$=T*82Y3 z#BJy?Exy!O`vcMW_yliBsY4U{2neKq*h`A9s_RR3Tw-~Y%%zd)2dgRM!dnFdtdc#QGb0#D8k0!GoBf2b{kC?kqRfHDH0({un9^8lWr8(9(K0 z&GVW&tl@e41om%jvhirG=*OfX)-rwqn@NBb9|Hmp8g9uRCAx0{e6O27{&tzM=hD~`FZ?OGp!QIY=k?;_gn4rh?;s-vEh7M2hTaB_RKUmb6fp_x>6CDg z>K7AI#YZRby>twomO}4%V1)G#kW*TB=!(Os>6Q*6M3f4UP-bN|wV@R|OU`ta*FMy> z3IjSKL3{jxAvRp-8(rhS4M4d`f|glrJ(GI6vrJ9&bUZig ztJ{%ub`f|aSU$%O{-A|Sk=#N{i^OAoF=k5UAoG-zkh{-a9SWPGUU4Jc7Q?ozO%5LY{i!ZWBB4WgXTw0EtM3JD7v( z18Y)mN4NZPf~aQavB|*_E+KnDc$ul%b+P8q)5pn=_1M-|lLQ;I4M8T8oDPKe4ZtJ# zMoZoRuX&qRuP0{cIu)~Y_5hQB66=q&jE|Ft0t(t7v9^@-?>QQQ@lpLIGUi`kib6F( zotaA7`&vH@qA$B&o)13uK%G7<>iy(;n19nMPyG(bu<%_4qt7%F4pDsV#rG9!bs@l( zy7C1zqT}MA)&zg#_Q#{F9;Du?*vrK6cV$mkB9YF#?sNy+;91N;;y7CqRNwT_4kn~j z3Bf|@ykL^5$v%t`MT$Q~8+1>tPbLzd75^^i{sEY|dZ*DxmY@qRY4>bC#w7{T$&w*W zd_oE*0ZHQVa&nc?k^c-rk+N7O21q7Pc9s-*M`B53QXS*=|u7k-G*8 zUDD&m4oouoD|qp+a>{(J&Rlfo@ggr44)E{uplg$c(b0{2sQ6rk@#47yoVkMfmCnk7 zpO=I!2y+~rOndRxaJ)xhE78ZG{eNdmzEuYpW9+o#LW<{K{M-U1oN{4lXu%t{uI57-s( zq-Y=^;*nu?k#jlsu+{L@{#&Zq(j;f<+rM?zqu_C9^1Yfk?33#{-iZKdD~MHD7?jG5 z$e1d8pgiX5u@y3as4-cGbG@~be%Qb^2PCa7VNEULTL~dnYg>;0N}_?=D0`qE#K`Ii zu4Mw5k!HA1i~UQ^{BCR5_#@EfepU~Z3eK@(+)h;)8*j~I1j4ZR=@>E|PZKXdbuJ?d zyGfo<5OXQ(H}yLr-xwj*FRS_sA;cdC%jd)ZR>H%LY^NjWDDh$AyasfRJHAnajZzjq zXqR?!dPGs*@7kWZrQmoEH;OY@tyiwzDa`nSUy9E1e-oxZUR+j69(doH6u1~4FZK|A zU?h;!_AXq_J-jnS1UK-g`EAtKxNU84>Kq^1a8%{t@9a-DIHtoRT7?G$Q(cCQFw{4A zEM^TB$GR$8e+LW*3)|<*{-CQHq!t3Fem+=!QALSxxOzTVR3q%l#xGO>Ojb!*t8lq) zNi<(j<`b43}3cMBE_?Lo1dC4TrTxtvTv2U zEmsvWYuWqEjD*nT=k@za2w-%g!$*}IQ#jELAq`a; zH<*U?Q}~xHbtDjj}F-c`9qcGpVS`;P?l*PjT^xn@W#k5Pm>!F3Y%b^(tw8x zsHI;+)?lO=8#uU4B%6?APfXnA`bStSz_9wi?9DUEEz+w-XU92$R9Nlo$xIosQSjKR zu7>XVgo{=E`9;|Qp7b*f!RA!^j3XCa@ajr$@Fa~rR(4oq6#z-9>x~sOYbrlud|^3? zXXqmDyv!nGhFZ-}*Rz#k4yCC)dUX&ZymgS`l~b#}={I z+9@E3A-?Kg9N_<@hGDox{i22{^lBOaZp4GGj6do7In091UtmhaK^m0att?xv1x=x7 zWvVcbKEAHZ>I9uRwb(KdSrep(Br2=`4`8WVz$6;cR09+LK$vBl`V@&!5)8&v)nbf7 z6y(bHUMiV*W?o7Sdse>`F8ne_%0W7ip8H)nV8!B&`T6HRrze@jp7ZgsO!+D+|HcEM@$qtJZr#3gTu=zpEtYgJs%`I zbxg;3nEZ&kF<$Y6TjRymk3&mC9iP>h7GBmL^!EKb+L#(SEt}o%-~K=qtpQm0>R`B` zqP8C)w!AKAV(8wqDv=xXL~s40!0nU(%5;99bA|iRyi1CWh#NY#S(r3U zJg>m<$Bo7<$6cm7k3;48{+80hYw?d8v>6v~~qD&|2%+=?%<7>RS8`6=HSl_3(~ z9@OcVJJn0q*+9XB5AlW0vejsP*}Se_dVMh<#VE5V-w>Y`=YzIw$P>SI96sD#=6^X+~V4gUX)}jNW^E#PP#w>N-<+)B4T1@X8yp=m&^^F9JN0cZt<#f zZ%2>@`>8<2>ZpQh>z2!_Ss*U9eQC(B8qfTIP)jc!%&z@&dF|ZbXudfKuu)y zd`ea1J5H?^Gv@fua=ew|-yjk8R{Oc7h^{lE#}|i(@@sSd1ctHTs?(2u7{-X!PM9@K zc!3Rfa0K7i0YYOP*JhS_9ium;D0t>n)8y_v&6lTv;J^c}q%sp~1agvPCa4M#`6@Up zu}(=XYU(fJsbJQmrnZ$H| zxVTiG^AJyd-=>mP{@#JB=VVv{M4Zm0Yxl6D2L~}chAA%72pL2Ov2bys+=|gq!L(fW z$|x=@+kS5SfuS^iU}?Q|YxyG-yrh`%fRamyN4)CezW>wO8WBR11e4<&MfE-L=wsL} zVy;iAl)owR^YO|O_g_fwg${vOrucK1U(d6K>%B?gS9_y^FT`ATRx-fIP8~INVoALv zf)ERnHQ3(iH-@8@6L#$8mC53K?^k1yjYmn+^T)2cnY-%uA`M}5R=OqMfvATGoAp}P z_d=gH(S9vXIwk($=bYE^SBs!``bvhxbh_?_O@tjmC=nMQOk#2M)@GG=q=#pn1{#i7 z(RLpj8fl_g9c#{(`y+?(zxT#5y_Tgu3@6^q&%$TPA`|@Kas5#CA3@C{}SiUUT;8mso>W4H(l8#0$b%}2^KpTjoua7?c2KQb$s?yw&Ej(RCc1@un0DQX@)rSK(-k8#jWg4^Y=>^-Z)l z-pT0S`cJPqDSZWUhgQH~rj+`jhx?>{RsnqmHPBl@#`;W&l}+)Oo`L)%S(_zERgh)F z5yc#lZ~{6M5K4U86MoWPL)ZRUAe3!(V5`5Eh+#)m9nm>1;jl{&^@LGBv@^_lG$Zo1 zS^h4d(sot&QFMeKkHgxUDIrk+D0$u+esd(i-h z&`@rH$X4%pW^aC&{(25h-YhwWpSDDXt;ikB=tSC@o6kx<$V6{sA70m9|ON?0C};Yxiac@6DCk@TsRJQ6cwJ8btzS? z&AJMl;UdcTa8zUjbAymQn*Y2#^e(}hd=MlR*!C9X`bt5iMEr>JPg^!*EtH|cc}eLO zgI9Y9f4u|gFhMlpgR6BgE_-k=snz7t8iBY;umzTPP-`x!v*zlr_OZP*W*=+sG+ZE+ zZVyn(9miplmkg6)7_-~8i{Blv)Tng7Y@7~9&8VO?d83i@Er)jN^rXtxyz3bcHgh)E zJ?z8Umw4!B0Ui6R9?eFLT!{qgw!eg-9E+Iye8GyhSNv~W6Grh@nZd@Pdtg^j8lkSG zG793fJO4`K@5l?Jr}4#2?V;)Mxn`0)XBiIOht;IWmQf;~3A|nE=pj)`V=Rd)W$gX>sKX)a(71ZDb!hVnCYQ zENduCH%z9EuNKd&(2(6HojfW;R6LGY+Ef9{TJU7<^>bKJ6_ymG_x3{+4<2=o;689} zX6U6)t3gaIbleUl4~e1RnpJqLxP61k_uJz!ZP1xAWlfA&d(CiwXHjOk*PAYq_0?QO zb46!kchZlk9VlE$MBKKSUz|bI;4%3GZKR2oet|&j*o`%jA+k_1$YGKHV~q4t%Q^A8 z?6upF`OdJiG!1qlxzclZ#3D?jV}h|#8aNJifdnAXWa;x6fA8Aq7JZ6FvxbjO$(%!6 zMMmk-riBO)e1TWkl7Z!oI+8$X`IduUS+>)!MkN{ zr1u7(jZ};4;he8Fe}vx6mQ9;iYKcYqfVbE2$#IN34L*Hxc=dfr+x}nTybh8?3cQ@l z=s7n73y(E3D3=J6lXXj3V-J}=B;To}&urvNWV{ukJK_5frK@D!7oaK@&`IxN}@ z^D1sEa3K9VM!Asn+W575e7;~gtjst;c*><3@<4hCOR;W48oihNKvp@B&%Iu{wTwos z9a0{n+(B2l4``|DtVEeBny)JdvY$1`myyf@EOkdvnd=2gL8mw&z<=nVT2!JH*ruvw zA#)2vZ&`(7VFb9?uL)bw$nbq{rbJS0vY=o>d6p-ant0~lc$rq>GK?;4pXrx@F91~8 z*YWR&2mzbv-hY{q1R^6NIkLVVA@c>ic$*s1{(CqLVi~nvc%iD5U(8t>Stf}^OFLC@uouyr^^xp@3!}y?T(9N6c$?~RSt$!V zqCA_syzz9(9#Vb(m#I7yhtAKmP zP-fFuu2@Sn*m;4Q+THL|&A-!9h~w@2{qg!dA=?-_e0LYa{wqp~E9PR$iq?)vtX=mg z)3cz4Ci;P3dd~&S*3lKK(ue8p@gyEVuvgzPalR{;JK)`BOkw^VMdra$nV8$qE3r)J zj6y{(?CY-|(75n9;3;T@U~y_Wku;hb9!Uh!M9amQb;D2#%?d9$1OMc6X!llAtdJbs z1IbV+k-kiMAlZ2nwX{ zfS9a$6{T<_K;}|khVj_q+R}KX#us4t5K)rgc6zC~^6_;C-Xi8`poF#Yk-)=+Tj~95 zp!wZZZ$Ock>87ULi+YZaKH2O;s_MaioN!7Cc5u!;&HxmgVd&J?Y?P5~hI-%*X-F?| zJ3Fy~(O{$1-qBH%k;Ky1s4)i=DGKbTx7GoUB)S(r_3}kpj-!qvL5=yRvIG@vF zc^n<+?oSV(P#tuhc<}N{uaJR77d11Ci;^HTD!lKd_wZGtqOE=XX~rpv#Wq^alYOCTI)8r;KKsSkk<=&!m`qR;U9~xx=hVus#7HNcVzfg zKb~xOTZlgO{V4wRng7l4S@1`;|6z?_|MoeCn=M*=lFhLl2XonFLMExoR}yh>@&*Ci4qbOj54@k#?8dN^+` z{5>Can;2@PaeZhlL5)DgeKbjJ5N9jCF;!R9a^)oOjRa-NWXhFZRvWtk#>i&2@vEi0 zmTVWy!DRd21HW{*($5uXU?#-V6VF~+Lsn}BQeCq`V`}bVpeH$wP!tr0JxzTbgyR6Y z;)(piM)~Db(ytb8Co_x`rs!m_=Fh}7^M5RW*cTq~Y|aEUZ#3fZ5Xs{pMm2vEMXLAl zlm9C89r&+gyaTqBx1&7 zCmtk!qnh0gcXxAyaeIFE9pUPZyz-wM^y!h0fK+{^roP04r1K&D+>3pftG|;OtOE0o zvT5y^&viy;ruS1dNT<6bk(tr$U{_LbKZiOT`LMK5=)~30PD40eE9q2^iL?~ipGT+Z zyi}yLiODe6c}5^hc{5NZWaa7`#JCx9eQk^)d{9HjT}Qz)A;>fvCB^NOtmUICGmi>ix4UrVk-Mqgl2{M- zYg;fxIi@(03r`PT;Rn(;Ii?ic3d(%igtQPGLZ@B;MP*QQUp~G3jR|7l-%<-8jC-wp#|Akr+DHaPGmzAKc7B`rWxHy|9))B}$*=U`~=wH9T$Y zlMj7jn|Ds3rPX;=r;;d^JF-s+&&2XSGnqA6jI~nkT^{(9y6C%7*Gh}E`vzwUzO(I7 zzSYMW&z_{9qjxFi^{}OTva^{?;a^OpFZDwQ@lZty?DI_3Mqm7i!n^G(H+>YEuuQNR zgIn`(RU=_-e@>?5d=+MRvNLQf{iFs#HCap495GaZ8q^r}@yjGF=U+3b-7Z%+}{BS3P+brrv6Tm`HF>T-vz!;kf#f3$(q+ zp|^D&b5-r%DhF;hR$V%<6GKak@P@g(^F$Ft8~LDCk#TIL+6~qY(X)%f#Gs&@*m`JH zVF5ISdhTQ%zAkd&Q2fc7W!%?*mc&Eo02?5aexj=JM<{l=qJvJ$TR}zN9O52gu!Gsc zK$ZtZ2Wk=EfdvBi^xcrcVo-kUMw+3AcchJmnyizR|L68|BslyyVw7ynW=wS(dHwv< zlNG%wr=p|^4dQW!aXmNhNO~RQ){A0{M#u32{Nc89G>o;2e?bdPOy=4vEMK4@WH0f| z7)T1}*0a3aEg05I^2w{^(}rFua)<@&arct8&wy10(GB_;Z318VYsZJs6@;hqd}fE0 z14IZ5js~%_MtBL+y>pcz1VuX&j{vmhg@gEuo?T(%aRy^ORD-GwDVJ ztpCJT<4Qlsq^SsJOd{$CJ13PiK~0w0b{i;Ecd20IzouO{Ma!R;$8N!j=H5 zZuLiK)sD4t1QjLgnphu|crt`3rOnB#sY_xC`UMpp*aM|M(4iOcwtb_d*DvQAGN_@n zPk`RdEMffzR-{kH)pZF;I-J`rB1Fff?l43P1SgeK`5~s@l<#ZHs@wc7VG8-GknWE& zHLD*&T1|08c`cj_>1=N`6pEw>4JZiNEqO6b`V#YN2ZM+!1u&LVErL zOWzoxDxo@4`iJb=k+06z4kIqK_CoBU-Oyeg0fRhI(AVzr&x2oT9RGAzrbZ7NbW`*A z>ijR85*Gynz*oeR;7qB>VMz{cmB4f3m5CnY_2JMuZ1v@~DG>pn6p4_}p~Xc*w%PTL zbSB4MGCPaSM97wrNM=BF4B8Z5-HWGasV5v$X$jKF<0PT)4ez^RGR&g!hK9O2fs<>` zn~TW9awvlehEo*G+T)gU(7_ZvR?YHoUft)Zq{I{g5v36w@pb+KpVI=_ddYIeD~7?w z7@MP8emZ;&%2ator}kM+(%IpsuLCwNU!Wp_52x9 z5lPUZj@~nb7$fRWT6MbN$t6OO7I(15!RxHWr>|Wpn^{fZ@s1OtAinK>J;2`6R8vfM zQ&&DzDbE%w{L@YUyC;7^&+1pV?xi2W^<-pb9Zxm;7atNh!jRPIM-1}goDJFEE{jo- zkOwzeXiL(5hTEWnxi5miZW(Mywu-kHT=gGSmjvn=%v7EPK9=w7$*9SibdI@n`}*50 z*WAfgFrOAf^+Iv^?H$x0+sW!<@oUvl2cmpir%lhuT|JG9*{U!H3Sbj%Kv=r2BkmP_)R%P#U6&nZmkRh*zcpr%qxdxlsd|N0$nNbW^yQ0Nt{ays3S>>V<;9a!0K4@c+s5mG#?9T)S|f>e zUc~VGTpRP5D+9IO8*z5?G`8@&Nv_ezV#C&NfW-^RU9_yxU%SLpR36(E!S(L-Kk2dp zbb6bUU<)V@u$1PyG`rH9-10Jp2-$(^o}ADMg1C_*7o;PrZ7z!dy|lQ^N=u85o=20X zRk8F~Xvs?>FOSSi!^PKx@t<8ss`$9vY)x-q1d?C6h*#{)Tm?U5t0a}2wkMZeBg!vV z*L|{Q zG<)b+c-c$PgaM%Y6T|6!sGnMP*~ad1EKyog4vs-qo%B59Vf@iPjOeQUYiCh)N;I$4 zmFts&za?_MaexSoc@dUTz+|p^x&LF=4V%3r<(c%%6KwJ-H?B65)V`rB{b5R0o^nA8Lz>oL5roDW|Uxj+G3WB#uE(lZ^~!1N=iZ+9=@txko%2TK_}a6*$!zEsyG9eq8~?Jq_1tl;Je}h4_Dc zkDUitfC&c zw5^ZlraB;%KkPi;RG&@4ao&Rn3P+cj-viwch@^zf^WlyS1tD3KaUe@quK2zP6zuKs z;S*owZqBhOr@8+A@i5=t^NKTAn3zbG-=p&}B!^C>9_8{)(l2K<|Lkkk%OzP0c^+xD z`mqmc#kDz!N=MH&4`W11C;6XDpkP`eY~0}&QW_AR zXRmcS4G0nb8OFc{q_?NH4Nd{IMlw9dG$I)8fm}+IRy8^X{w4K7^e7c`G4elJ`Ol8a`Vf_lf=xk*BT}4u97*gH-}}k4~I89gEN+F0+B;@ z;40-l!k%~(UL%DxP{+7d#Q|d^&|+zAi|=G6OoA$D<_6p1&fl-dgB~B1(#|#a!r`B} za~}i8CtOyd_~>dQ3F^Emko^Pp^Y}E|J6-+--EsKCxb>l?wHLULk)Y9GjpRwA%3Q=y zdt#2sV1iJi7$eO;^LS#NZ6mlBhOWDqC&YbWN1N_Gl)#L>uXvT?iN^LsXY{48^Kso| zCd0PIEd%!Ap^0QrAjx!`=<`tM)xEK3w!>qJh*9A_8j;3)4`Jn@`PlnlZJ( zhlO}Dn*@)Z+W$n?JnoC<{?V|KsH_FGGNR2^Q=o{HhcfsveM_M738nlQlv zJc}wgvr*pIRo=+8wKu4YK|Ct+=3eNy)@2O-bK48`9fxno$hgVQPL~rIhj4sQ-=JQW zG{?95QP!j#4%JONHww{5G8;vt!|D|U)c|&NfsZ!q(!oeux+i3Z!$cI@4d;*Opt2Na6>r2iAAF zGKfu0|Bt3`4vwVz{(d$a+qP{R8*Oacwl><>*2dY`wmGqF+sVdy`}?bUtGcFU=D+T` z_w+d*T^*n>kTZ4O_;@;r=`NO5ZGr_y-XP!KN@doMc-Pj2Y8;hvBbkEhAdG(V_m^L1UUb+-ETZ*;lGrgE1zxAc9eZ~#*5jzfjU%qChiWurwldp~t&rE>an zvY8&R3pvR+`b_coE-<~7fHJ(ykUqRpTL^XJbgm`3UncDl4?&}5$zX@y?X=YK5>w;O znPIs6(DeCfr6?OJN51Vl&X*3_F4nPuVVmxMY+gtec^&oP1=uX)=V>%M=Y5cKksBC$ zkL{L$aI>O!^2&l>=-@{;?X>vwn8;4D$n;BD$(v}zDG6A`l&J@iBsWV3vAbHq9_Jr= zek|XdD6rpF-IIrM9k+H57TJr=ab^`c8O11<#_}pwqF0R?E&5GD@TQ{{HFAL9?k6b2 zvU~TLRr38x_%Izx?0%H#qz5lK6I2x5aAo0Zv{`!4ugDi`&S;lIS+7Qw8OB&igQ%>| zBO%J9!$8I&6~##z&dgC3Q#3WHljtzoGOp35FU#zMhXgwT6)r<=rNzD`1DZ^uu5f3Z zQowbSXW92lKKmC3wS$bA)kkRT%fAUWhWqcf(McY!)29L&U)%$$@q?@J{j2fDZ~oV< zmf4lFp?<1mL=Pqn=mqD=xQlI^A$~r7aXXc_f2zZ{7QMP==Jf~_5=$oMb#@T!q*O6Cmuad{bZHe zE5p_GlvgQniY z)o!#35*K*FLd!!S)?ZVL9ceZ4Iw)Up&{%9quoeO!r{>U|6GSMNrv#vgNK|MX%au>U zv`4%3Xv~Bjh9C)Fuk1NDZZp{oDji6a-^9VU#j9K8?C>C~Z+ix?%xQwhA+|RQRUT>( zfknoJYvXC7lM3)`4=y)Ixw+SCNy&(znMEw>Y&AWjbXkL|e$@IS-P>7ttulM2;6=Sv zG*sIQtw#{p9pVT$_fI150PwHqWyjc3w9jR4v*Ru*|z6W z81oyWvL?zg8F>3F9KaO213r5)dG&Dm-VzZFSl#~Yqk3eMyc9Ike=U~Z_u$&B>?GB3 zgdPMm(@U}jPEYWD)JY!i!FMWB%6MU-7MC;i3CFb0D88gj-8X-^G=sG(^opMW6@ow%V{bcS;Ei3%|WuaUQx3dmH>qW0cjp^#rq|P({me1%Nt*?$6W^&)ZMNZ*F zU@mp~!o-x*WxwBC__oJdK8CDc?9geAMQnbc)TEE$ zt}&WQ$M9%UfSHIwn$ih750a?RmS!rekEkaQbL_?6Vsx7?2*pYJD*?!K8w<@S{U08v z2GuYcGcR2(hVS_+f07$x%u_H76Y}a*FO$A(WTlmpVo7~J_7AFJMOLxDYodra&wX7D zaTx8li`H5%TB}!Se}rmD@pua+mAFc#@Fe?YLBoa?HBGKObIM4L3&k*~ISM z{lzun93Z$D+;ByLty$RJ(~7Vp<0(h2?v4H9OD3deA7yk@JFN0=W#~hDdPoh1Kh^U{ zS_A)ScD zg22_Rg-xe5Ormtymxo6x&5o1GaUR9Vja`68lbM%Hf6+Xu&*H*qhS_)r{gsn<|6z}8 zHe0iV+QxptBoAQCV`~OI&9iK1xr2I^QxD}}(klNKodXb*PBOJy@$XvR7KTCaGbS*< z-s@LWNAfKNt`fMnKhIdInFIzl{d2|MBM*WpxGikxg}x<)u|qEPhbqMlaxf-^aqNxr z=X`Rxz1LjNcuLB|s-zmuEY&jf?Yc$-W*`RXu&1l3xt9s_;clHs6Bv14Gdwzk(d@X3 z!}g9y?zeu*SbjF~Tng?ZgOUdX#&w?%+g$&cP`em$r?{3TGcBW$Jo|8DA=qf8(L_5w zPb=5d$-`3R9!d$_3uA2;i@mHrIzsp7(dGpk6;rYN5%S-E(|C?hPZfD8_v zvv_O|D|8O#%cOEaFPmt(^L?s(7HVbia;;($*`K)L2v&B*b}dM5#**wAV-jgROjVG>LeMyY}gFEqtP>;cIy|uUi`Mc$XuOL*>29^ zTafwEz34XkYm^UPIgQvn#yY}RUx15DxU;|DsWa49-()+tyK)2R%2jHSPg8)j)VoNm z74sG4eoh@^vFMJ&R$7M(H$J7+cb@;2(=wy*C)@>dZ6$iLwoWQh`}AgIcR5*&H6ifs zT|kP#<9T8C^S5V{kMa_A8oO$%CK(tB97A*vC(B=>nDW=PRy{{uZ{>p7DiXC_WTx9% zP;&d@X{3X3vh+jbPuVgP1uN_#;1qQK{saiVmw}|?{~YlciDOU$VcVJUogqkVl`ca(0nhdtlr2s2cC z%k}rcdP7`jcoG)iT9$MEmvVhu1_uY*-JyX$tQY?uF=v)}$udE-%3XXBBoh2}K|v=W zOU|y;wh*K`XlETwLGy%+(zw5WZlRSTx0{4J);v#c&AP`b<)|+bw!UuDbI8dJk<4n5 zkRNWh%sXAL3GcrTSvupvy+eYrIc*QwfBI-749()SC;H83HT1D9{PGVnatpaD1K!y| zuC~=B-jnjwkW83VoHq{0-xMlU;9DyC?qL2<2P%haDG*ntyIV6L+g2s|yxB%W*OFf; z;XH9?qhvLM%WO0707)5*;2m!Z*dvuQL8|C!{q0Odd6p_faUXr?K`N4MyVb^#|H`G~vPRO#9gB{}Ho-arb_+yeOrqy+jnrLx+32Kz4|Jtd?43J|f(cOg}!j zjJscYb-8?GI)0I7$2D6lKXaVDI1gV{2Lasz#Cz%6+uQMBepR{l)L05#ghT;}G{znR z3$%7mcW7N*o#Qvra3UB!_)!brqKks!sS3e>*2#EVPVyRa@EYwvKb`$wV$N$zC)bPI zb~dhsCJO+jXf>sT@pJ+V0Q@v?jygf(b}(r`ed#Du!FbZdd*8kKo_EFADv{eH0r!)~gA57KXanVI9Bqr@7qW)Q4c{q_P*{XnmHI1vFE*OspE7?`FRZB3=t zU#$50Q8>h>%2EbmGX#Z1T;~x>Fd4K)gOgyZqr)(SGX<%XC$%UguIhyr^)gb)`)`Ua z0rKQv=Bh~H8*ObSRj2_ti&jaiJD#H`VGE^VytoBk{F26VX2bcHAnNw z*~#@a((u&;y~HFG)1AoH+FBLXBpUYKSYVxg{cFbJM*S;uoPdi{0podaFE5GZ%8~IQ zZ0_o1&wSb00r>3@VHqEO#@r&d4S9qeBS?D`t!8i}3%St1%S7O7P^+T1|JgWR2B9$_ z>iF-+N_|%&lRq=D7Xq+k+-#?bhCz7Gi!l`_7Hr>e%;M0gPf`r>YCoheU65v zjTvVXDiAskojUj2!Znc4_#Vx!{Eo)yD|98M%bS>0!J|aJl<8i3KEy;aZLwV=x_3x# zv5c`3VTcKz{*;Fre9Fc3oGIG%>Q^^pgIVSc0YXQ&_p=)0X7<-!d z#=Bjk_pUA9bM}q1F;?K%?Yq{8{93}?L~q*stB#PST084S_tU<}#$jX}w;1777dTrt zHWT5Rzqyu}RJMM?2Vp_-Y;FT8lyOB5eBU#9U@Ft}_F&QxbPgnQ8Cl)cXJ}+aycJ{N z`>mdU$dS;#qw}HvLpq^_xH%Gn zL5wGwMk}wh>8H3Mhb;!2cBo4vIs*oKbQ?BWq7;g0WJ>=MEr!VN#Xs>t?=d%v?Zh80 z+|Di0&K{~pKZ0H{9sWZRb|n$}6t!qdPL7vf315Z05~<-wi5aV;@fw8+d2-cVVL_}8 z`T&4H7UO69EQbs1C1KoVnOs@XYz2D>17|XaVk|FD4YOXOL+3K+39OrC(cjn(t5Zt+ z6(&|wVbl>aT^?%3NMpd0**@U!{zhK)LckH*Fm3Z^da{#ColbelM}C;s=^>UcOHLZ# z=~BHM^)3(ivR1*Xlt^f{?v!$LKjY7AYEJh9#=2H=LMaxTCYCOX z$+V}p7LoFZxU6(CDU?nVOI@Xh@MGyaW2iLvf4tp=&3Mb=DlCE*R#vi)*x8Dx}6>b zuid^vuikoM*h7CylgcVXI+hY%uOfX{e7G{FwNWEn;jhyMmwl)y%0B}y;X5z$Hekb0 z6M%+|SoYXnmSsWN@-SedOM6ljJjYftoV+8{|Cn>yQdt#Hkuv`|r zVOE+Mn*EF1tG4Y>?`oko;iOv%=V-5;!2QKu^v){ot z_(RRMGzRiGCcXm+Swg)vDy>M=)vw& zIxQk7fkrxr_l<-FZ?7bPzlCjCfci^T4Rb{3YpBe~+us)jwLya#*i9>S1+i#UzgBv_ zFs5?c;8YupYDotdL)X?A0%-Yd*Gc?zFYcv5ykd7)3_SV`9IpyiE3u%kBt#-LYWVHAuudF7H zD{0>Mc7;&F+oz{j&imLm^*IlFrZ58@qJ@?@mP%K6lYl}qGemFQfhsk#ZB{o#0yKKR zp2EA2#BHxpv%kURf}V#qEPG~z<}I-;^CmHW>3f|&k3W9uq>i-?-wS$Wx9~v%A!(gm z6vGfY1#|=^HD&YnJ~X%9`g?2Zl+@ZTS&@;jQ(d(*C*JPl1Xq@$vop@@q82b7i3%tt zO-NWzkf@MK*|1DN@S3N`s*zgqPxsL;em~zmXf1%&B=SP#(5tjf&7^W(L5Xqw@sXS5EG5TR&Yus_ zW=2L$QKeOBBFVnzNnWg*5m_-1>XuF>G>aJYM@WB%RCQjzjauIaE!Y1Je2GQm%pS@l zNV#2G65_Ef-J&4{O_N8&I8){*xSo8`lV!C*(2_@^}bGc0o~6d8+k1x@=K%X&4P=>1LlK;aLfb~{#PR^iT-ft&^4&<>Xc ze!Q;f=_20SH)tCY?`H9vJwjZSNcO5Tqfze+8j8Tr9KCPp?a<<5ssE*@2~@7l^-W&e z6xWxBg-lSJaU`cWq15`?K;0g)y-3}Ut#>lq;ppt=JV{Cm0dY{(N)zGwKx4}8&7+Kl zI60n)jlXWd&6ttg7=73(^!QD%>vjAhM&LJg!we<*-yD3ELR;&F-GnjkQ3fj!i4XT( zE$iJi2q>3?SQf@p#_iFtY5uYQH7(JqmAmxPw250n#q?avAaVgSo0s0Yx7Cg_6CbB@ ztoQTvsH;E7;tBNvRpIxTU!L12q$KZ2zemRRj=GA`sc(Duh`;QYl>4Gz!EOwCK?m}iYmDqdEGA$`Sh)x38g{%PH(_0 z%>N7e@*ne7KnTB|xk&(o*~(MtimBS-o#S7va4vY!eA>Ztp6yYzrUqaHic;|>d>jTC zwQf35>eycb$UuGB$+P%)#RZBCoNADeJmVTNNp&MmW(^_gP+qISK zZ}{qUu?Y}a#EF*(q;Fg_2mjLhA(BC5((!@cSfO5Jep$>4L_I0YKdmV$<_r(7)kmxM z4Ja%cBEZG!1a_Tbb9A3I+eQs1whp%u#ylMJ>v!NR*(Cvbs6oP|=OMPlh#=hDw@%n- zHM~Tw5`5C$PuFOb)SXwzG;1;EIaJ-7o`ENe!+wO3wLXy?%gWtefBM4w{KO8zx|Po; zIPM#yCRJ6{`lq_Y+S!ojfZF`P1OhHP(VjO9RwXl?EJ^2?K5Uh5TNC(0HiB`spWLaG zBR`Ipza1UweK&)!#Ijh`E6G z76z$7mr8{e%w}(kH0C*3GAeBV5NfSTp)^L*nc3%L$;opUQfBuybL-)g>ERdnHYP2! zlDh4C{t@TxplZOLPXs06;uh<|n+mV2p&(R91zWGu8PoR!_`W@cV(n86UgQmJq#T~% zhQX;aQ30qJZ>zfd1W)JL;Kq=(dw(7KukwIyY;#cCjTtRlvK`SFNS|sK zLYY?=aazxlXGZ*|5+)>h-73Le?GxD=jeCLTLcO6)5_ zAeq%N<3hPq3Vk-6kJ$oHcCjRr2h+;JothF-z(SQAPCfi@*ypbWx&xPc@T zNMXzt;QF0(2C?1Goh!r%ASIj%&6sQ^7Wm=`&c1pN^!iI;5nui}$&=SfpJR;ez$|p4 zD8OZZMZNMRCE=*if9UY_((wMVrBHT{n_gompEhV|@JQ^PCiojohC~90hwG3USa974 zK^S2bZ}oebDDjF^iiVLMw~UR>9q*RZ!8@qHFu@77K>0QYXS_mz`-CJonM6f&goKp? z2NIo1B$uZT=@{8|SP+fYj7Ag^S5aU)4Phx{4%E2t!SxXT{%fl6scjoXtMfy_mZ3T) z&wEHd95}KJl`ruT55Y5P-?e5vf-`T9Zh?O-yprW66=c+?%91A|f^kvyX=K0t02oikiv5AWV`GItK?KZ-# zgw4H?E$iU4^%UFkC$~`UyVeSkWPuV;8N`eq-9)7(^o^3%9?rSm6$8(d+bjo&#lz|9 zCN+S8s47bAeZf#GFq%TD#6%H3rf1)AZOL<5pef++cK-4L^F_YzDZX4Q$KJ9e6=paUjoaC<1-E-%=?2 zFFXV$QpWU&vYVGqN7^U1m(e{YXBSUB8oqP8kI4hpVt0C9Kwtwn(T!S@7obp9Igam{ zo+=bOl*sJfpSPrYGc1iHJJnqI3jPyzzyoEX3i;A&ZPNk{E@M4Iqu3uh%cDTNLG;hTn?`J-s9SG@Q(7+e88Klca7HmID{DNJCD zfoR*lYYsv%u@^qT-A_#Yi!Udd(2@|&YuipP;j>1@Qik4a1w;=0h|jpOi;RK*B^Pq# zLmXH;_xJrt3<#;yDo>(86`9hkkUGq5A`RREV39Qn!LsCfr%vXU3yj|cd}k*Y{K$|l zeq-OFRxu45uu4Nerl+x9yk}Rvm{-hm7nzrS?nMb`_mm}Vc_f6eweS_%dq{N+^=UG( z@VQ1WCbloKmL>_7KH9A88CRxiQdx}Xc;B39=j9`;pXgB<_ln}>7|BogBHzu>2@r7FPJyd`|3|G>I%iUArB zswvP2JX|G7fB?qfMLGDkpr7o6-qrhUg|6{U-HED?iRL^QbkoEOZQ zlec24N5Cg5?b8N}BlA(QsWMF2@EhCNih|D`4x;;FLr+D{wx@@SqCWhIQyf-KXM~=@ zr@})v7B&zVk@NMms+NniCG@aX173~WCxF)=74tAlaz^9!1=}G72O>3BJuJ=5uHpPz zW}LOe_Ne;_;Z1w)_3QKl{@0rYNFhN=c027ZGA0Y69a$pH2{30t`z4Y!Rl za4qDn4(#qS{-RyptCkT4@1$_b%BDH64mz{QxWODwc%lz&U^)0DR%Rw6qVq~Rw*pQU zwJ;ejYP*dV?i=!S|Mb)a-|L1(C}yK-y*!{W=sCLp_@^q_$boTX#bYNfZh4}k+PzEy z9DpoPNox5&Z?5P8DP&lg3VHyAQ(Tc#9EpyJ*9P3k3K>oxhf^FxZ$675IyU$(;Do5* zoCVm|9G_YrMy1Sa|D7``>-%lC3mdUcC7^d8@zeivPU_0?wx8?%#m31AdVRnX)d*gO z0RXZgSxcL6iGqvumM2NVn_${CWQ|{$M1amht)9g1?4*e!k;tv~5%xkqhH9SWmt72~ zPz<13sZ@^3T%*(20`cHSw_m}}OESyhq_i+Lejhr;`E$9E_Ua)pLNWCHu9`K2$;njv zN_dn9`U=J#AI@qv@}7rbIvzgezNqQR6*gB6ZTb?b^qiJe8X z&~%1qx$HIz2k94sh^?J z?GZMF2rO7Ku)Nz#vAX8S>9Nc!Z?quMh&si&6Eu@64g`L$Nil9b<<91>x~LqT8v{~6(JwfH!A6%)Hfv8t=e?};J|@#kmh#u7^~LR z45>4}&t=kovI|0!BT%`8(KtmmG?6|6N%qF?6WWZf%MC2Ey229@0UBQ}STzLIP{hp_ z;F+9m;Oav|y|ZEuC*$&twG}xAUx()QYa1xY?L)o0(T3YOZnhlcQB*mH%N;oq(WZ=N zrhjueSSTrq?@Ky)1w3az-{e>Ox-1Aus)k@ej145?2*zS;%Va&8@H-XD{QUtG*FzCS zGkW41)@YosTJsuXw0DbobH58p9RHy|9T6Jsw_VqjoEvZpzQa#%l|mory=A_P=m-sO zO(NwXtS<0xLz@xTsFmwGh~pnGp&P%SFZk5s3?#WOUj!@1;~}Uy*a&6SC{wi~5B9SAu6q1;NZ((K5@uz_F9wGQW1)qSFYm#?&iD|nJa>P-}}-DhP{tfa*{ zO)WhaJjw&1rR@q+jQ_5;Bccs6Noa1b%Q(T{zx(#K{5>5hQW2k^u)hD8#_O9j0uWS@ zFFXM1u(Cyqr4rL+bje+P9DeycF0u00RZ{8$pthAG1E~MOr^vm)i~gU#VTs?~{{K~t zxn94ISA@SmIS0=nO~MKfr=15ieqFqdTLVP{4?$W*CbkQw&%eZk`?ERC*Ji(Djs;+W z4Pf^pN+S^vXwKElEC6yYRI+WZFx%*;sQK|3$?f!xjleKmtI4yY5x(W77$ z`}`B)<&)Y<0eXeAt*xQlgk?rylu80|$qb&9vLnCaIY0;eYSkz)^j8((N#?@vRX+v{M%Mt&TXsa3#h%35X-FrrJ91*(u_*Do$&%DGb8>c^fPj zbI;#b;(QSg0wNzbgcmf6*V<@-s_8)-B-s3Kv}7P;+Y91I()D-MV$1)&pHoK)`y3b0 zciV$PTfxQm^gGIepi!3W)&@4O*B~ZJjbs8m)sWUXJ#G>_xLg_(#-kH`#tWfg3hidr!`LhtiNNK&yNc%|FR;u9d3PW zzdNV5hdCDo=vw9J)s}gcqeP0RznP6+|2CF_&p8yl_gfQs$75DUOj4??5QYkFzu6Ne zVd1m1N&c^dEzkr9?P%NE;O=T=Luz( z!b~*Aq0f);<5ay}Iy0F7aTR17u+ZNoGp~WMi%fp`pB7j6C)VddNA0A+&`wQc>!lS>lVAnB1IcKf>1Taw+$h{-mNf-k!6B-DRpU4k4nmXs3QH z0fJ3#?=P*H8+k07+`Q!_OE$O1*Q8J21;73FbG665ym)$P#Yl?KT8VC^hb2tcx3Me9 zA}9RTp?IoK%gfZihG$p@mGR5|41NVy9L3CP<2otxB?LM<8*1f^K)Q;gtw7|k9D>`# zhTrH6qR`flulMQQr`c;`ZpYcC|Ins*D(aJ`c{9iCBYC(DqxR1GX7so`BJEe@Hi=Q1 zX%`9485GTb(U5622;xgQ4IJ{CfdYa`Z^GVGHVC71F5O?5Nr*kod@@t0S^r?PRx57d zCV6Q02}|CACovc5o}|H)c%0=mwzN9^Doo?OW%P7PZyq8T=hzg*5stiqof+i{ES69W zshp$H4FEyVQ|wuHWtRY#is3GlAovr!Y0;oqsM_kqCu|}*=S~vELSY5Ow;8Gw$bVb4 z#-eGmEB;|<{qx0I_9yDTeO_=Ewst4J-0WHUD_S*ax=iw3^U%1_5Aq0_G>|0%0ve-v zggg_jU4hmGsvLxCRPv$IxM?h)+W>gjb zcoa*EKeS@bTOhyvl_3Eu+&V*!^TM`4rx`~tG*JHtsMAjT)ew||wsPDg{9>K0`h#IU zzI~CzMHxAw^hp6f+9(@!kdFUC1mS#P@!oc#TMotY^;6w=7|z9I>@bwn45<;5+B{&# zU&~CfLGrM)sjxTkY>hqJ;fRvu$MP-X;P3KG9Oc9B$51mJ7_;6c(-u;Ly4r896Z6)# zr7Xd>QRKUnOH<_-oun9?0C{qylE|-rMoaRK@yONnY&kRGX`b-#2zgKc6NwNJ z*$;&OtYmSs9}Pjgj=|r-Ipz+!@-r@(Z)7@G-8RxSOqRN!iLro;Wpnc9Ga>R}RpjrN z-I`H0Jar=&^bq{H=tdy2wc1I_nM>t9S&YbOm!Z^eO?|w{AAyzqkda-{jL%(v4Qb!q z5OzrS<~gyjs-iXhIhtN)*RhO4-)(*C+-S`^S&@k>wnTB=)<7@q9;48SI9-!QW%kWD zs9dg4VxhlgnX&YZM8e#8<)_h1TifQ>H;EYli&fa%o`q9DdH7$vr5CUILWM6BgFB+T z%U4-RT|U^ZIr1@Es|^~E!b<<2fC;I*mSqs9b5MY;$xK}pp$zodv~R!_ALqafs@q?X z(%?nD^np%uUgj5i))z27Po?4mdyZ19p85(U##{A`b_pSrJPoDt104SZ3qpMe%e%Sp z-yy7O!!Rot0P+`*tez0Df&DWDr`yxdt7puGw1dU|#=m1Wf{&(Y;df^-I%NBFKRrs9 zU8>h)?bdoiKZpnWKXT+}*7r#YYo;ZrkGwX;KNgPM(|{TCgi7=~T=c-iLl ziV_z655W5I5PE6J{-qT=D8P6mG$p$dgGVvxpRiA~hAzE+g%+P{H||_O()N|J=2b}F z%PDr}$_omJ-qA=z?8$I`Hs_U)l3j?7|m@l zD+5Apa#D2M0bI1>Q66!!PWbBaer{^ZeUM5x4b-*c>k|;RTBPDJVzP=Gr@68Jfsz)a z)#srfj^a=F`GJ!S6woN|jX#cBs86-;*Iqy~1xUbU_6Ubr*-S5OD_N2S?50rZW4*H` zplSCA`BV@~SV@V^fx8bOzgz@Rh&gA)Y9(J$<0zR|!|39Y^6#WeycE^6 z%9z62LIuIuHWu`+4F7_T_?4UUI$iv_=MR2{E&L3t-q%}*yMlq%k%6^!DE3FQpuccJ z0D5M~C&RykkLHDfCJn9;P8i|hh{fC1+;;(cDqiR76jWbKr3<+Dc^Yj{!;~rf8relUUt=odeQ0zP~ z)r>QRR#((Jlkh8*{t|{h_MY4(!r-axQSTsjp~1`qO8k>0AF%u0e_g#-SrLoE)H-P) z4GC+F%DoQ}$tHMpCu1ppb^(uDqDrF8%#!z#j%ZLTp`|aOcV)-q4w;}d6IsQSF(MA>+w_fVa4&@F&{WC2 zUR9;v0M+lA{R?jb_+ZnNzJ?aRoJ>&Y39g{*MH58o#q9sr0hgh}g;-pQs38_p=VIvt;F+?!kKzjb07;qv~tZbSbz%pgL4b=#MUKg=2k zP#eaEMG9l)A9jaHipf;w1Uqjt&!UqGmmd7fznty;{^f>V9!xt&qs2%J82W~Dp^F-G z4yHsC4S#YQ2u-lPy^;WpLIaHLR{z67nTk+Dm``aw!tK5NlbYJN*!do^kPG?N8EVa4 ztv=?8FD?inkyk9Sb$Mu`YTm{M+buB^601XFppN5FE07@cKq1qmGTQs%9%i`2w_^V? z)YNNZAGn)gA7`~V@6M_|gu8ja(FLRDBQKuhH@g_I)SXpVdc_4WfJCidjpt8`#fY!X zgdfd)F5jxw8nhribaW9#QIMn$;2^FI;~2z@tB;fUdG+u4dXrafxZ)+KbRbh8!s?v8 z$-~*D|1e5!k>3t8k)MlFcWM=vpjck%M?%y8++sDwCbl+?R+gg>W2@IM4@~C%{CFhN z-fn%2v&>lM03F{=U8*=*cBJY0X3d+?t!en}|snZ0R=_wAJ9A}29G!(XP zUIr=qP~7*;!=P4jjsx&qCze7={EKi{*yfnh?eYNSZf)_v!NLmYb<{56uPin46@i=~ z`q@!*m^Dx`FQ*{iGt_$skvas{_AlEA4;yeD&*f z5*DvFJ)P&^38&CblO~3azZ;{C5YGxzxd&zV3H9zs{LJ>bYC+)rO;YOALkvlVh^O4= zNu~~Ka>39`t%in{hDVi**BCwF;4$2yXuaR0diSYA)0{*l=QbTPHjlNo zR!C;(K&^E7hPxH%w(kmJs+*wJFA6RG8O9LV?h9As$k13 zFkQ|achO|$sm-r=_|u5k6p{x1@!FTjy-woo6>8L84g4l7R%k3NPH0T#Dh)XZlhvHq z1d@R6+==TYb?F0hk%^O}h66w+zd1TcQLE#X3a#~l$fob#A7pMNw&0J`dNnaBZLmw*%8Fi6xktLd#x;ekA@pqKBf1a zgeKfs4W67u|2IPP*oJfA=g+d{&(_y&hP9p@iN5$zZy!%kTGP?e@^~*HV3EHkvt<5Z zfMFV*hQh$W=sUZ>()av4{>AuWX!R-SG0wmjWVbsOj$9+zL4=PF?~)k&+?IFShZ~JY zo~{8tio{bWcrf!?D!=bgfiWwQT{x*~`qQL7bb|iQC5&V>jV3G4pZoMCA$j1MYw0G6 zulc)U7s*SZLe6Jq+5N&kUfZo4o#uTpA>qf{U$5hZbd-%WS86cC=i#r&GM5ol{ET}q zz==YIYjcv(@L?&Tc)pGX0Gfyv;1aTT{#ZN*Ie}zMuoGGG&ShfzySUNfw5_*I>e-bP zrDZB#78V2^9tG``9ux#y8O|%4ngdQfKG`HePdqY?qy_r_wNMdkWjT9Rs~z(l#TB1q zZZ02O3Jr9h+y%3gul+2(fP$*P-RF3JZL(<<>PQpnVV6=kaiQ6zcbMpQ+(FR@ z+x0tnl1zoxva*zfjn1L6O*ofCVYuj*oJ{y{t!k5KnKKZ@5m>hDDEw#!uG@$#G;5S~ zpxqDRQy%83`PNd2mkkyZ?~PU|Uv~*K5u8%|dh=6RJ_iORSgqtz$O_GP8uftHb{LrX z8Em!O%q&Od;^ag~)sJ=>9BR`TtB45RP!@_ZF=Z|amZ*Pu^5Nr1Ufw-7ZElAUl;+!F zzjf?aM|XC-dft7oqu)^0KH{QeEPat6%V!d^sfj%WP6_HMf+;6<5t(6MjIL8m#6dL;1+O3LT}?E` z%G0RIvno$tU=0IhowaDcx#jrWi~aZhc!a*R%r)^ZjwP)7T)7keVlHzAsYcjCE}B)^ zTs8i7be*b#h?d*HMR6Dx%@hQCy~@}X@s*?}jm73$%~PCo?#uivG#3362)=TDTv>L9 zaGNqar`ehbfXtePb`?uJuSOcFc1K)y2*zD0lczv%Mv z#9s_}_^@H180}8I~p~ur{u48Tvj+_KX4vvQ?9F@F742T!Vum>{|gft(euc4nb zrA#toO`ph@=M#etrbxGK#OP1dL^OhN)zS|!TZ60DqxG^{ziTRFw7Vv1Y1g(J6^0DD zY@NFQS8%na=GJlTe8p2ji~yf!8*Kp5Aen{o5Pyax_i#>1BnSj?-p1|?y1%a;95`|g zXiRjEkE~#(rOLZO**)g4EFV=^`gYEL=frVqtx0@v;x&4(#Kw{lZNN|Ycvg)cgcNz6 z=iJ=Hy}-qTpF8{*Fa>kIqKjX^vaMN3#_M( zgm=f%Gf@q0dfchOcTh1R3mM%PcC8w({j;*DNO=);(cr~QX zdM!F~w1wYq-}%e^E_rep;ub+9|9rurtc@>|0dE_1aD%LrCJp;g>#%aM0_7vy#^{>X zXdtbfyqd!DLlp}2k{Ft+Zg|D_=FfJBZ$?&8aXD&7* z4#q*%g>v-wgItUA5HvS(?GHcy;ZBH%=t)P8m}XuXA$TA1;_q`0!7a1ge^iV}CfJAU zpg6wfbHYN$Bk6h%Tk!Wcu^%WxXK|Tu5w(}W#QaCpWraaun$nzJxf*hOc_bjS*4k1% zscdKfKypK`Z=bGQUIOT&>6 zDlBDBQ(nz%57ZS`>+Xp)t?P& z7ZqIJ7)n0g*{>>dDzu;Kl3C?f!X3;ae>PRY%C)}A=O}miOH#&8P9sB>j!f^-V9r+c z(+>L%>NiRr)HBDR2V|W@&Bk8P;4_uH?YZ`b>c1Ff2< zZ^Psu)=|0KYSkZhDTOaJ?X|Ws&q*Sc_6P;q%KmzhGw@*`|FI(+U#ir?YC-W0g5Rq< ziA}k&z#0-9ddla0V?bbVAZgj)4Qqq*A0Yb@n5fwk;p{j#au#FdJD4%CB2;?wK-jkk zn1;2NP|TxNyj9mOgN_3}Isc zjVgp*_^89lCW`3)5zl)~7Son4m$p>GZEJPG43V~2qStUK=`<}A}d z3cw9Pwy{uU)iQPKKHfopsg}e|pvdHhg$LV$Z&2{&)rLUI(xL;10VpYO>w2X|7^TiO z@KPCwZeBmC)JktRytl^pzGEU4{pvEwf~GULXEkNZoh02wDf?>_R!pWhNM+UnL)5^6 zAED)X=gh&0#i@^vZ^46)Q=1ZUi+yN!;fYF@H_Kgy-=L@{l)M+wPdsb9N#@LETBCJB zYyO>DW=~Y$IBS;#k4?c4UM3EJX(Y%KNQ$Z_HE}~F2$)nb^SoN4sP2LWH`8zwk0YT1 zgB^joLJsy*z$SVuOGKZ@LW1w>GG0Y+YC|L<;_eSEU0U|6deSu|@TJY|Vf~scqXVMK zqr?49FYxAP<`I&68T^&LUH`-?JlHo&KL@N?4cC08b8Hf6AD#G{BFfOdo*8P zS5Z0>Iqeg?eCYKbN&BOMvnKftk#{GJ!|6h;c=wu*`oR{f{FHEB% zf2Rao^3xJZZsR`KMvG-633%j+TWC;g6V4fZhVJGYY-5v9x={EflDh$2jwSc_Tzb{!0;pfv28bYnq*^hV;hZaCk-3hwr$(C*%*y&y!-plyq|VvXFoi%^W5h?=fb%x zV%DWSd@f*?yZ1L26#V&2f9BJ(yNmNn_cyTsz~e9d#J42JD|&h~*`lBy>eaCUC_XD>t4kjU1Vt*KYfjYFp zn=|I1d$Kco+e>2RggrnQynD09k_*8VVb-c73Qv$9(wC{k=q_X&y7!`ZLkoZmzJDbK zBhJj;JCz$7Amm1t+?puPg2@vKksPPw7BLea&0D%ao`U0|XD8=D3y2Z7u0fCi4~NPl zFF2R|UIWe~vfp>hYWv$Zzx~8n25(%Z`Du556K~}{Oq2MSC_FrznvU*?iZI6z6pGXF z`8}JWcpA`@Ta*8A<2vDET03ml`NpaI>tcnu1!k`Y4lVs+_Eix2#w>u%r-{Jnj}@sF zL)eElnpMOwx&V@4cQWB%I=W*mJ>mi(^K*?xe8!pb@4CEzt2S~A%{3h?eT~U1-xq2* z?kN#QP5AJ{4^R5Bs0SKAdH|8MQAL@l-S*1j5UUZ)OjYr(3a{*q0YHm{wa;Po6*J`7 zur)qoT^goi>zPy1Bpeq(BU@xy{1JsN!A8D=^`GIlmQw4rbvh-S9O;`;?yQSq5(~Ib z`ebAAQ3KFsW%WHF*VKTZ;DhEPMp}fi1;wl%$-|7w*WI;K!Xotxs?*g`r`Gm0$Eo<@;Yszj#^F%%_~x=JX@f|~^aWiU$x{g> zX1FN}c16;HXv8S)#hAj-W9T|?yj{{Hd>()m;HNeE)Qrz`sZkZ^{Vv6uj5_)U`VGu3 z$_)H#&_kr<8B>0jcb6~gXD^GZ{kt(-u~S)0Vi+~o(s#hzvC0R!AZq=xBE#`rpvx!= z;)0T9y}>}S4-jtuH}E6KG9ZdY!q7G61)_?cb=GqPz4Fn-AijlKtYDQRJ6Bd$BLo2# z#%gbKF8+}C*H)s{zpW}54Ws&d$>riZ{5U5Saho&46r3ycK(>%q3mQCEbrLgt^AUzg z{@gZUCyw5Q5{yvxm6_y0CTSl2QngMMrL>ftGDb&dhXC+WI``aQL)I5{@;Rj zCJ_v_afEoRS#C3+QEDfpnGXUxK3G*T+b!oQ$;qEWiQdG% z?vmE7Nq+j%SsuF}d|`?V7OfotSDCRH?LIP$XQ0s|T7G(8 zzZAGXpIkM9UdeNo0*4b@hH|+Dcx+Z1BEg)oa?pSNPXRY}ruR1Re#$ zCF8~SL{PjqL`=sNa4+>JuGmi`0lrK7f&4lmfUqz5>vfOQ_Xxx>Ly>y#$%jphW=(6! z?lpxzU%A{PUGvhuBC}zh_&O?5YB1Lh)@?URxvibyRsT>K??eZeQ3Sc?9xl7PH${5$ z)GY5K+zta}bnUA+wRGA*pEVxwdjL+Atc=~5=lq<{FdoTyvCYCkyxANMeM zn0J_x>u+HkkMOth_8V!H5HE~&?* zljRyluF->*>$eF3U&6frfc!%_ZoKSFb-tMy10RpooZr({ZMb4R?P{dS%`#z=^_Jqq zv8_t;=nIwg9h0q|P34E$o&b-GQ7f>C6)j#=xaphPjOvPIBtZyjDWihTjd?e%mt%O` zhyG*JLGmuRkk>ZUDOgtrBn?8KOk{_d(VfYFHz3X@;}lnQFq#}z=PiBRR31L8OR;>S zywtM}uY*3b>v#e291`_X2PLoHT981lRJ|rFvur%4i)^wS({_z>TW}kv=oEixRXwCm zAl94c@omZB(2GjwlY7;H0VKN`Qs4wc- zP@=h+^6lNamqw$rAEQ%J0+=pJlvm3kpk%%OAdN>*DE1Y~PpQ5xucyr0>C?3N>x~Y# z7>RBZD3W&}8e&kX_i_6*5d9nPY_6 zHbD2*psLd=RSz!xKo(nN+f)^rq!4G)QJN&o$rKtQi|F!-=)C*QXsv7`c}XN<%a5@H z8W}5fb^_k+>n+M`#72eblk=b=h#5ULrPq?0n?h0Xa?gV< z0N9o8YELUnY*1;4rg*W4n3gZ#Mokg@v|lydfW;d0=*`D7`Iamc@%Bakle{L&erl$D z<&~pBzM0Ie=0Yd z+xjjjt7XW!*4J{ai2tJsYH5-zPNW|%n%tEW7%|J|$SyJ(J(bH2b=c}%AWWPC#22(d z$8m}Z3J6wm*#b=x4Y;;6b77o}|FjDes4-5RNS?A6TL=GXMC^&?U5Dy})3P=f36_|O z&MT$zg|Lu?6(x}0Lc&({^XN%uUn0&2huCP{I^zUimwNF*wtfE-=0|dVG;jKN=kThi z23Yy(x`|_D&ZfbR<)Quz0XR@AKW+nY?#RO!|HU=+AfqMs!T`yFWu=8ncEiG1KeN|U zLh5Q10#iPfCIUB3dhmO6f`?JOYZ^1}pWD|0PSnWtABt%s$KsPwvod&krqd~&ezc=E zp0AXpkpl^4mMi!exy))pa~Jkd8+LI4b0XZ2L*c2~$_@fv#4ml%Ush>v0ybk^&DR*J z+w3OQH3dPUS_hyk$~^@&iwZYW`~iIZ#W{r$&gZ2Xj|o;j{Mf@L76S<2z+KOqTgqGd$QzeF{zeNB>9p`-jxOE&rK2OKI{8{8xwT` zX@v(z_Qw|kc?KRV21t+>U6u_)J$B)l*h~J{6sTr&mg991Cx)3L@N&0}PjTL!&BjnV zrrEMPaB;Gs#XKMXTyt5-trC=J(+k%UsrxIob5-!m27b>ap}ePTxSKz6)g-=?su*wz zcH~C#NEM4|n?^q>(pirx4j(o>>-3pHSiJKOD~m=@ckpP30}{F>7(P3J_sJn^aa#}s z$i2pNHt~x(2T#9yQM~l3Z}~_S@ffhPUTcD%zZdUx;w@EA;0v1U5J9)+Q8+xd)X0f1 znhsz5waq$^_j}kK2#Ilm#=RUN-u5-y0abcKW9tZM>5^=h=Ao|*@thp7Goy1bSxTot zWauY{;vdWi59&oEhZz_7i&WPvjor;+IPuG z$;r2eJvmc(AJES=$@|XQc;Zomr^~H_v6HY|&TdwEpDInHFD)AJ$jc?Gzu@d%pwE<4 zaOWqg2qWZ!F-aHpZQst^WA#V=;6TP}Sj0PHBK)iE(Y~XPwnNPG5P@G^eV0W+hZI zBajjVaCHdcr$}cAnG#>ULQ~`^hK%|}X;RnTvh{xe@=!wri3VSn2H{u*G9d989Bnc{ zdlOKBjgnMa`Ce=F;#xM?OwIzx6PebUbh)Sui!67TbykNK*@nw-=Goo`y!sc!xXn(t zCT9{#8s?%J#6fsoIcFTDN_b`n( zpQ>xv|I~wAX_Q`)&4(XbN1bc}g(+Z*(;^4Dm-C|PTqkeoBOeCc$>g0gPE0Xi4hYXZ za{pfoa4@U&2hTJox5bLpvtzt$N&^F*0?kUYs^`%hKShpvx>#B5bm$58ED z{TS;F{jXPz9AkWH$QK4H!^y?pNLQUK0bbpUoD+2C%QI15b~t}9t(*?M)$FLcWwW`~ zny_`Fv(?|C-gc8heYK?j+JX7s7HT|$!M@S{-56|yU++X%1AlV)d%vaQErJe@RcW+* zzhzFn$Bvvttc{?;WWCSI0Z`mu$4SXOk7fl74+&o618iY!OzR$*GxSe}*dXUhql3iR za*ZOTu!z0m^e3`H_3ol_p6bF@B%pNFGjTcM({)2QxqUhghAQHe5f4=UNW1!GygG-U zkP|XgUFMvqo~}$DBXTtUD8b)!s?B;Cacgk>m9l8D4vGdHuo z2l6Xguzt;u&xtn)^nQ~zN+YFl&9QjN9S8;naFK=t2<2jnP4dHsJ%BqsBTuA}FGz6P z?+D6eu{j;lV=?O7dmR?NxmNQ}t3I1-kF9*R(rIdIu zzS!lYie>z(e8XI6o0l9rqHbxadFnd$&b(p90$O58p=AX;-_cqnE1JJIkH<%DS{gl= z^WGT74%?NQ)Y*|+d`2)%Mg@Sd#hApY_eWx``s{6fCKg$tXL;*%br*y5fMrkt82ppi zX3V&QT8Av^BG002BH6vTDF*g@2rGI73MxsN(mf#!DH*PO1EB`BNM9fE(@%QyFD|^J zKGH^Qr2p#JKEJjAdA~zq_!P!=xl?`W2Go>M1keWY7IECw3MzYdhiC%6Cl3ofwfkT# zbv<2`Njt=mYA)p83n2ehaZy(@;Hya7`moPmg*K zTJY1lV*e103a?1I!%5GYxOVOVSc$hxdxDI0{V{#7Ehq53$zGiz6Y28 zFNzUxT}GcKLHc*|vb2eb)7Dtq)wxTC?w+sgcy<-an+&xIMCu8i{OFo`&{8|!{>qpK zlw-C3Di6ypM{?p+S%>KwP6EYQ@lrma@Jo`!?X$YjA$@8$pR{Ym4 z1(Pv~ks&ML$yX21F>JV^9Q#C#5*#H3$(?ee{w=sA#E@yjkH(jaQIo0VbZ`8yVm&x_ z#wbZ8HR|bc#iY}vJD7A$d!q58S)e37C^F)3ym$vpKC~S+xU_z!%dKP7kfv1$;pDw( zfI(iLWa#20TE*KT8$gZ>i6^ zi@l6pr4ALSYK8|f3-CEPldn@w7IykG#Zw-EraT(W#ZVc-NX0a@?Ma>hEGJdZYCP9J zG@Jql3hF8S&Z-UgGJQ`v@O#n-W3nzZ%NhO3V?IqRUVNa%qEtTs_~-%p-SLE_puN`J zr`c9MAp`2!bjO#;jMY{01~SPq9!U9bE|F+sJzJ^92NOt54>Zl`;h9^eaF%CE@7qg2 zZkay2eWB*G0PH=X(*Zz^&1L=q20=ZWQnI)Y82`fJ5IiGS1{)+$`Pz|JGKjRTt1aT! z=lW{G=RC7IQ5c)@~ z$wtm$Sq+8a%8IQJtvTl>qN1=n4k^JN{$ZHrk+2mewmke>OqZKT``4ry)yyuXYPfWqHGMB_-bDyzGAa#5LJl#UBK z_uap~YNgF%H1#+#$=FWamj~4ZfBZD`3bgvLA6FjL@>uHu^H(${x+KfSCTBZE!Iwds zTJdf=$DMoBcb=9VymvS~EkcJLqyzB`?3U{w;;C@K!q@MJFyJGb`Ed#LfLCnNQo?C$ z@xZ1c?r@y)QPdIOab|g-gXsqNyOe1OMN(rV81;;H9q3Z@K`%3AGbitE%PEO@-;K9yE_zh6M| zpk_Zi#NVB}ibf;pt@N-V!qpBWQlc)M=eK)hx8JcNJ zQi2cBvA@5;_YyE-NhBu6D*5l>q{As`+OfQkHE-h^%p-4HLHg1>R{o0UHu_kYuP-pC}26J%j?GCyhQ4 zx69)9+oExpP}7wtU@6fA$L%#WV%G8~Y{Wkvb|XmmwCh$2JUCe=TAvz-O`4L(@tn7S z!32}QaT~K7nv-TW5Yb*V)90;UO8)PW)fRqZ6RXa{QzSNjyZpD-9ipRYl+RcdYKFk8 z{}fh>egg7uT0;;$M-9(K(8MxE?`Mi%n3 zEf;)QAmOi{1u*ZowT3;zYbnKwEOc!c~ct#JO|#N%k(IE%T}P$ zP;IhQzf-OR_b2#%)4FMu_NF z0xP+DAyk^`rtVB1ZklAXyo{0r*oDco!k7Oph@o>0>;Ne%)v!NAq{PYy8(NvRq{z+D zW&Z`1tTn3r9eGTni*wR3Y~2_nKuP^xE|=K8+hyx<$gi670LceQFL>)+VUeLW(Ohj4 zN+d>!hZ(PsB+|)x5?62N8z5JaaA#KsieOU|R={!8=<&vsXtxBqEGbF)&2|E$dM6^L zpu4|zw7_n^*Vdm3-TEulpRTl-;pCPGtOVOG^^IzHj1etjOIQqi3?HIXumqp#ybZ_J#GIooUXf z9-F=Sdxv$#N>%7ZmEp<{f0zT2ml(XcoNzMN)b|7UZH2FypWn@f$r`(LIg=Vl6(D|m z8%&1i$kvWvAqkTQHGpWT3H3AYce1*RizTDbKKF%}vY!x#lx&A|_V*!p;yr`3i+^KN z5fQlpp$M~i35$4(Q9U`#u z3M&{Wv)L85O>Es~&f}epwpY%U3Ew&amR$@`Vwe0kDQW4l>S``3n~1NLC?0*Ww-D7& zY{tsmmX;N!FaBvMoCxwb|Nbt%(cyl9*za-8l zfW>kQCe&AkdKSb7W>uPRY7@)M@*<9kzig0JdqR_g z&q96=)rhyRENA>GDSK!lw-N5lA%h>u8R}juiWv_bkQW`0IY=9z@QV^1uYC|Mc;w*U zfN=@B<9`Wk-bP4)F8}k`fzxFqKt{kvvUmv12{WWeug?>2O?%9C_M>;{Nqtw|5K zxIFvSGAz(s{^jxHwejgLbkG z6B$5y_@F6LBXr=!H@xEc>3?B=mWL!fFwGgjUXUAw4b4ITJeQoG$V4P=fJNkqt+5Vf zg^R0u^CYj4PQ??6*U*o5H(>6VoC;&VYZ$Z~tn0Fw1UG@lVOWNZj4ha)vLnOc{|!saP6Y$WnMCEm=Zp+hBn{oDSge7@;j+Ix z{F?u24Sqs2Ni5$CwkRWf{}(%e-HkjWUtu!b=~CEk*>;J(q6ofk9RUxcfZ|7Sx2(w3 zGo?I_)xN=|vm*NK8)MHe!W8}4;os`Inh1sMDN5Y`Nc6vYw;-UtTWfbjjdb60hPnE; zjb#-AXkW~?v3x$;rOPifpFPaKV{u%1B?cb|%z0F@nr)r>lQX1;bEH!11HO9+r7lxE z-R&g~5q--bH9mCy?!dXraHWZM)TBwLxlvMYQlRYI=wqT!A5Br4A`#nwX#GQ&gjgIP z&@1`&-T2ePObRAkPz`65SP8=B+N1~~IVI$mJzO+VKP+QV{|{ycFtHyHIltrIe72-M z>J|fW>lTEOq!E(P-_Hr#TYTC`+j`m}K9Ywea%3D9I>$j~J0aADoY!1gudp5U8IQ9@H-}L?juh6~|=W?8|A|fL@J==%x?i$qCzKV>= zf^-2>po^M++U5E1Yq5{YbX!eGB~ZoUpNc-kGXT$}JN)rn48-7>PG=7N?ecoRz1r6e zVNq7%5D4C{7s#bE18~iQn_kGUHS&Vkd5k{3;gAWf;wmiXBMT${JN9OAq z(|Xf05yTFlbZ?nHsK=*fKrZ_*NRKn7kONGC8g^J8$JXgz&G1fLz4h$v3=eR=e~D5Q zmuxID1x83Q#!VNRGlaY3NF04}k>j^vFJOguF$>3I-&LKk!M0;gtpSi;_R1{vC9fP!A9%UjUz zdcr7hg-k?DLf4Q(Y?`A;En27`n1*I}o3_JTluc{vm(?kjZ^Cjb&(%!Xi7jqC;tPsW>nul=%#R*SC zlm?sVSvEX7zk{S}py|D~&`05L0(8!ojR;dA1KOR#kM?!BEHR8E=XqzvI+-QUH9#l= z?ZY`vJjb8cxWp8yvobyS`Y)%gP^BT$#M+zRMTLmSH0(Z&g6eB612kfIZ-eI+Hs8PT z)12+=)@1xFJQrP#zp@o@kE==cPKj+VMDp~jj${P41NY}IC#*!IXIy^an(%I2zRC4J| zXH6NmY|B%XVrMOmlx|{Bsz}~vdvB6@#VY*};N~Axt6D3S!!)p@CHO?&G8M;8c?!6W zzoyu?&EC$FR;9_#H$J{M`oKGkie5zulL%V+D@m_BHs0LdZfN?x@P&#{a-_%nygpUV zPH8BhgE#Vs^VcO7ijjD^71)v|A#Pr&RN=5PhC4tM*+s#0+lrcFBK0#f;l&~jTRkC# zMtq)3QThu=!%2CuLE=jm|2>}ZM11P0O#d8a+(!B$q;d?cm<7s?Z6Y0m{%p((;Q3L0 z?nqFS%2%q#(6h|q1sd1zSH3CZ5)ru)5>dK(j>?eTzRB}{&i?N#n>=$hlwcW!t$}~J zzWe-P0YN-`(#XVi$Z2n>xH_$S;YokJAFi&_R#BK9vXcZz_V=B8Q)$AMXe)NiLq6Xw zy!^@Q=vo@G++|U^#~wr1P9jcIcX@11LXvY%M1A)d-$JKC>@wx7Wf^9wH?kMzWUQz8 zY@d-bMhO9kzKS3UpRue%7`18cs(hbfz2PlTzz*F)VbIzT)Tl2?8qSf!D#yZ@nc3^B z{b*ygzN12HYiQpn+KCs4$3X^Kx=LGCR4~I~_&4>(g0Af-*s2<7H~ zYCb(ehsrIJg2nlylxF6mUp9o@ud&HYB@e95kuxMX=O@U0zQxwDLz$re^b8D#;dE;A8(#NQz8UgB{a@wV z5?Z-i_kd+gw^&a8w6|BSFv=K^b=gu%g$>HjTQjxzAKx#5%qlu) z2nGq~$;Mv;Sr;cYjk#2dZ39JsI3;|M1e|no`#WmB8g|r-1~}UpJ@tnz)ka^F?|j%2 z)I4lyqtOD#^&aJ(S>@%DlzB(iglozZ_iZ)@`>_0DZZQdpbNn~&wEUh+v_F-zenQxq z=A`J=6m?Z3_jG$=2KAD9(IEVx<}Xd%A=TL5l-Nk1+{gdV%y`Bn zF~c3zWIyH9&R6-!O@}Yh4fSqoH|3iXzHP=CYiwr$kt2fo_(R=_RV@Pf)eJA{ESH(h z*dKZ9ilVDF-lrmr(encQ|f73`x!%-ee|Wex#p6xo*bg@m|?w} z?d{75?)l~BT|BjGpSYjNUTt;ZZ?LJdxy{?qSI2zJXWVLuWwy}q?)fu#vj_kRn zBLTq|u6tIYuL}{=nxMfuU!NIgsm;+Vo=!gj;V(Go(suL}2`VY~=H>Q@-TP_}v{sgh zJBYeG_O&eC`3khT^@|SNF;m?7Ve;+sXRL?}LV5`#-f*CXpItY_*B>QFb0mPH4H{p$=GN)M#L!diz_CpUbMfadx zn8b-2gi2_{I9aoScZpO4BF3NY(SknvX9Rd`Z1SR`89t+~9mJR9)9Ta8a^xyIK_&xLM>GabGU4i#a3i=G}PD6!B1*3j^1DNO6^n#$5$S z6ZLZI4b=!d0{|OVCD~15FLnIjCpB=Qfjg`$LDT8x1A?(TXJT`lOQajA0A|_Dr_j-m zsi!{7szyhwyFEp>VdQz;DXQ>`TktRS zB>$DF*eRlLg_FSJJPbYL#}d}PdI32&SxFVC8P4e4B418uY7=&l(}ws^JCCAF(~o=O z34DG!Z!>4%3S%!Iju#NZf!Y5*(Y=(ygD5*O6Kz3rM^u-v*;FOodBjpfvJ)bx{ZCbN zKh-P$c}TyXo((<5W2Be1up&Cfy#82)%BdIZZ3WTMh#yXIU?s@H;d`bZN>EqUog02~ zzX{Maq90oh{Pou^@0f4ammNU|F_NZUHQ3l3%upXV&s-8Pn4y6yp#-3T%>l0R;w*X8 ziXCs%ks~*sRLa9tmpW|Nij*F6LY%8wY7*Na6$NT1a_r?LWOouSWat+G5N2R0c)dvM5g%og6$7+>KT%@(XYc%PK8hta}ZBn#gB zf?WiEbjz(-27Rp-zg#j-Rs{@#AVRze@;ptX8#7(6`H}`KovIk;Un;=KC{WNLXq<)d zU4NvH>9XPo(t6U&SlX5|Y=+;n3K-lMYL_3i&_zeC|BLban1dFbJ`O9gTH#Dh!ettn z>vt)m*c(oM%gB6dr3RYx>13rN*s3v{Cw&x8KR{nM>z?1t-V2nSATn=cK~T#kuc&Py zc?mKzH1iL|=m@*1jqdt&*nzq86CLEbxUSb`Pq>a40oSe-GnSy^Q-=)uCp8)*-P;<{ z9!wQowSO?w!LcDo9L3ff86ZeSk^(!aPrPlDb;pT3B5hc{@!l@uBrcXH4@Ue!U&qaW z3~=9d$M2jC6*<>XI-HLlD+szFx6{ElYU8D638t7M+v4f|S8g(e4znW&b}FG9D6aZw z+sNz&#%$zZ4artSiyH@`&w~@kK_X7FKoQ=Z4V;|mt6u-_(C@CXF|6G_+;eKTDoct< zNfYnZYi_9PsPJ_gqUS&7qBZtcx@_}nBIL|XDhZorb9jK_7m5?gV{(PbQ-bF}>L&VM zkFXD?*g9UNhz;^2$9TWbv0DrfEh`zNJr_P!WNS0WLCerOqG$O-sJQ>&5XbS>F-YE9WL*q_ zz%hg)y=Bqb%Bc(v)o`T=qAlf#>1g@y3jA(_m`)qiqFgsvts4|ii?^rQT40x7vu3lS zTDaKX&h%>zM>3XJJ|9mht20)Ht5>Q)5rMC6@C$Uf<&l4SjCXZ)eY*9IXhIq_4{~R3v^7VU&g@!Q@8Jie z@<2MUhSn*dMHmCM6b>pCNi|nka)1l8FE4iBdQ^=MR)jdx4^cky zq|q1>20!_M9}hI3^Znc)6lpS#-^juNwflJmq+z< z8Pp_#RTarotJv}`+v-UzaT0#=I!l8u%5GkP*5aBS_UpFY&MxRd5a#Wkn9v<5WN=7i zQabqi2Blk@!Fnh~YWgF}R#23k`YjK<1L?B9a*g)Wt-m$=?AMPzFV#M|ag}XC18!_W zm;Xj5R5vh1#?sb|bTh{nj81i8hoBKzWVGi-Z*M+(ch_B;26XI&eo($9Qycb#@ox8~ zp$VVM$7<=tWLAu>D14GI@xRQx{~nn6mXbIH+Oa;up$*jigk9&?5WG(M64vVm18+AR zX;QS*_lTQ~9q9WggT0z+caN<=7+Z`TV7``&m`-N-`17Tcb$}+~C{{qONX9JvxAThm zO)Z3}(E9Sz2Qml5RH@|T(;w8{nD{GFV3zTR*0b;<75d4dTp<~9`QV>T4F`k#EPo&U z-dFh-SGiA}k4oOIZ`A&qgWs9N39FMq z`*KkzGxlQZZ`lC(dG}@@SU5n=noM^<>l$OI0PbKtdw)(NELd_?V)IdI=epz{*^eoj z$t(DDvsO_%t=YxJp-nEN?Xc5I4oLQ3mGBKPkjC!4MY`LEF8Sck0}aUXTR(=ui>|(M zH>H8bcThWr!HbW4Yt1_fnm_7lrw~E*mMuFA=SWiXJ8*ju@9^kAveZXyJP;V6qn)!i zGABSVQHu`UD~}Ddx|go(SLP_ixNLe^?Dy!L7Z|Nb#*>MBAZLkyaEOy0AAZcy5rU`X z0f+>riv>Ivl7J*`?m)FIZr6-VZz_cet(SDACMb+BkY+tS#>K#L4>3&BNP*VH+JBvK z(`?~)CwzqmP}liZbCk!i z&9=p^s;Al>?CT0W#If%dI$#mGRoqlj!S+6cWF%0M)*kcnfN0UZ&JZr_G-Mp>IPgn_ zeIhl)#w$71W;iASI`Jqna9kLzIaJ>~UQjagC0Ec$l29g{fxT$I#60j>OD;|8JLJ1N z^n-I5zWwE?i3&hn?XjcL5+Wx1BH^69O_du!rekh_1N8j9y_z|7j<3n_Wz8zHL2r=` zrclck-zw5CxU(;5scfqG!SiB;aoO30&$ZB-h9OKa$v;soo&IgMg+{D;SMu~#IW>K! zX==OZPNQT6AlBfbY3 zC`FyiFVP1Aj@%{N91~euNf6$xtu*PwXvlh|wp23)FX-(Z4o>p9Pcl5j$dVy`I8Fri z2+ot|Akp?Ea!;8GGQ4u!9A}jm{ES9U^BkeF^v(oc|L1Mv203CuVsnsSLBI6@08*vf zF+bPa?~=KmOV)$B^Pb$SzVGlLOgl@+)KHi^>ru6y|1S%UGKJb}7Af{55j!=;HcR)N zZ8sycKK9~dO86>oxxpo>sBaZr(gnyLg?3+<;uvV@^E!!yM8GL{9sxXMl1KIB3jL44 zZWEmkLOaV1Zj;SoeOv(wA9MXRbE+U=8|dRM^$@jrSMMXJXc!%_5pGD@axhO8*+Qh5 zoTAD>wXKY0`x3(@-O9V6J50R@xGu4lQTM>NLqv=Er!jy>A9RAm-isLn%_7^E?jCzJ z7%xf&fK{&LCv~5v(8u3QJM4M(Jp@PJs zDk0pMGHQjy$Kv1|QoZqda1>%@{F`^QK@cA~P!>4_wKfg!dyU@CGVGp|A#q9}UU*JV zYkVakZG3TD7=Z&tSkS~$mF}M|4KCHk_0Fw2)~U)`%xD?&q$qW|P?-aB;xVkzjpv*3 zGcef`Pxky+<+G(zvG0$e^wv+7Vw%x5#$*y+j1ddJ)KEHw;ma`_Eqy6tfhEhw`*@>ztTB-7h=q>dO(d~=Ex|VbI zk|T*Li*I3!_3BMO9#yr-Dkvi!s-9+-JdvS^ylN}0U5t|DCto=6Yu?Cj#qsYXUN_ac z$SjKU;JBHz2N+sT5LWWKv}vaqYNGCPDu{1ngf4oXPs-xQ5-cmV?m>Pa?mA`uqn`A#{ZQ>WV7d8g!a85BKEdSK1#;za;0y>>9x#X#Dkq8@Dj;U` zU*(9pFG#@#f4#gNEWrRKtqQJAn??@-hO(a&J)PqdUx(;rzG-t`E4cr3D1DtC! zh!Sq6LpmcAdQ~JIQ#l1k8VDvXAK@vT{SRANm-%O}UK+k1e50xWl|SsRnaDPsG0FmO za3X08o6M~V^1if?1?hz|dfP}Y*BSUkh6CvOCIeCMYdke;HP_;!V&3w51bc17H`w~# zepD?z?(1S+dCJUZdjw8DxQf5${G+Cl*zaL_Ib-*3^yQc+2pM3iNc~XyDH}uAx@!u_ zA$08RO^!|(ZDgsQkGF#%X81^QO-A0F>MkL6O>tj;C(5e-;L*Z+o_U)c5D=#n4kM0>#QEGA-VkvK|l(+9`l2rhS_JBa}?<@INx31e3A|$&=uBE#P zwVa?WB6s^YJ@!GSxYZO%!;FH~ntl>apQPVw-sc$LC82R|va6alznJyQFRaE89tf7a`r3_k_m2hiRI(5@1|S6akf`Gnqo#8;@( zqQRou!To%ogH5R6q^xVL9w{`cAH&?7pGWAWm9Cq^w04DjqLKl41sth~Vb*%g-|(Lh z?^{KW4ZtQG^YwYX+kCxnQ<_O{l+9nQfHE!Bo2tUa@>>%qtM)X*&;fP94^GF+Ia_9z z%|+6!UfXI!xV)1MQJ)R2D)FfnSkVTE75&?`x`)lY1O|J!`LR?R-1)VR<+rZ`bM=#& zbS08RatSD=n#tC?trW}sRRwS@Y8ZE>C8IS_#3{<_lst&(_fy)qEzxB^4VUqhG1Kgd z4ukAFQv6+{;&_Xw3b_u6sqDOX72h|iXkQ2e4m8pSX&Pcp@OPRnupb_65oyVK&(IRa zmgiYiyQ9i0DvTb_x%!@;RfAvnpzB6N&YkHdi0&9HN@}?PzB@8ypruH!hd8J6%Vjfb z7nwKdixg_Rc6BxH?JCN3lfStY|1PsrpVuB3ajdt$OAOr}@NUgSJxFLiA<05*G(eqb zw1%Zd?jfZ#c0GhY_;oH1XFsvXmPdh8^|i~)xu|@7?F}O(`#2*m_*wTC&LyjSukL{I zyVSvNN<-Aa{8v0~SAXX^^m6nzG2?n2X0?o=(%=yQ`1UoZT%a9J!~N?)9B0iR22xpj3n>^Ww1HYNA@E5rT$ zD`(Xm{&{%?pZpSkUMj$9#_m$}b5TfoU&48j(dl(Q4|h8$O{HNqyU6IwCufG3g65e* z-sQ7f5$#`hzc%0Thv!l6{^m>ew+X4w%IB|SE zchok!7FK)o-G0Us%kE#I4lavLMDIGMwMwh_C(3?0;8~TCJ{Q1$6GcENyg*FMbSb=Wu|IA$woNKkHZFPyP0B5)2~hywBIGCs8_?cr$+2jB<*E|k-f9P}P{^SljLoGJC|66! z6r?x4v!w3U1dBW1QyrEkqtuRlvekLa^*exW+$@!#F;Oc~OqdO&_{9oz`_6dYESbXg zU=o(C#pI#hwBp#RIkGf70nid{%xUL_%1wUKCMj@pSPtw7sZez*6@#2alk)$g=__E` zV85?%cinJzch}*z;V#7;hP#d7KHP`96&Y4wxDG4s3>fZKzU@=u;7P1>|+(tDqC z&pr2C!=iW~ySP~}rB7;(pv2EYXlh-=M8(Tmt^gi0f^q02Slk`dQW@tzqoe*FL?twv z*IZKlDwM!q>=u5o$A3YLXc+->c#_2;`P38mq%1H09bV;P3Fe=qIvmdHp+2Itqr^c` zhJHm*U94fH9qWP5gb`ZPh}@~W21KM~O`1LDxdTwBaGcP&)g zZK1noQ&N?;R}!3m!Db&N-9v;5a3>0EYW*Wc+3embi1zQ?v;MZHNH9BQqa{jxy{It2 z)E{<##C(UrKjJdjPNiI*u%?`w@+bG7(i#MRp`4&sZ3mmfkgj8G0_tXE)PdserXT~% z!TNt}IIUi97bNe#{1sGu)ej~uKeb#Z!(Ops9vb^j2*sWt?U%ifO|2Eq?9X&B`fwhO zyYUx2A3UE{f_NWK!$p^aeH|t&J-T@5nbE2AhGF$FJzs$MOE{In=@&-EN+Pavbnbx4 zw2(kw{)?{Np6924q~JF$K2+8%JN#D%43fT=#E7RK!ASG(dKXJUUZfwK8%Zmli6&o( zg`R9GP0@4~J-0gIU)x)$*T*6DZ3O(5muVFJf0vk!%d>vOhkOE^m>94 zBLE(tOu8pV!|P#{NK*TnAW`dw#!36RI8I1&V-kNxP5WTX1tU!ufCEwkY%wVLS@0OZ zH+*6y{lyj4rIqY2UnuD3lhaCh{(Ftu^X*g`{)9*FojPJPkE{w)BuyY`vE9lZM6Yrj z!*#AJ{UVO%ST+#Q+Z?=mkyiWqqmaC7ab}H-D>_6 z%`}N>zM+Bs?Mn=KT50EiXW4*tDO>2N;L*&7Kt`R~EuD;?Lz?Srv)|apB1uL+M8>a% z#rGrcred$AGE!pRBwG@FwVPRLb8vHOG@sGQxkJvo4|w$a*lY^L?>K}GE2?#0md_{o zu8uvCoC>t3Ky3sQnGNRu%)cilXk-`=F(S`(&_l;O&dU7Ebk%Kpy^WVkJ#4YdT7$0W z(7RMy!-8Z|tCyadD<(1!FEOO6B~+{5ZVUfCx+_8P7fw?Fb)$x&vyl@4uf4eJAL<-5 zfx#lBm3{85*be12HlOHn8NZir3k_E>OK?hgdIyOts~!eHn|NQr6e+;8p{lzF(X!}d zT0*qFg)Cp4@WnlYT6Z}pbk<{!);^5Ro09}H>x`C6X_I;`Ag2cr(6b9GnG}zVY`AVR!dAq@@>?gTL$ypdJb@|(aXjD{ucx54Nmw${XzRR0q zOy%gpB3rDb3*T=oOs)HEyi8jrn;O&Ur2lbPvMbGPH_VTWUqPR>aw-UQ?(N8};XFUE z*&6Q107%riqg9XWT>pW2Fuq3o^eRmRK3lAY)_L!`8TT_*2Kt~(CA(rpEtZSM=rWgT7lp9PJRjem^nFLzlAE& zjby3}lT-IW9T;wc@Et2?_-O-&D-)r2u;Y87q{J$d9Y{QGvEG-D5bPpXV%Ls`h*A9U zRqL{nbXb%qxy6>(R$EW+!O?an2f8GPo9C&`9txJMiC(1x2)8qZ4 z!e{z9qi;kk1qzD|^z=r~H~#fezIjDc#oeEZ61LdRph_UantCjw)1MJrS&)f&9rU{e z#te3T-mwl5j<9hB^{sIN^RGg;i#N;Ipc5caWA4dnXV1+|1uGk@2951AT&u)KglQVN z{ctj7&iGdS*{1@DXKYd{EXP#v8hs-XD^CX3l#KEo~T)sm^L)BHpu{0zb5c}2R)8eG$_eRzwPPGXE6p?5b*RgV03g)sBv zJzQv(X_Ll?hHxe|yv<(IvTm*N)>IP1Ua*Z^#pP<4|Cje<&glw)Gd~K!xxjqtkSX1U zDLAM=f+mY2mk$(PYMM73talGxS}2-^E$QtnJsB*4bGy8gujte&BmU}j4#y`;~1 zhHoIo2a92zq%3ZKayThJ{PokY$0r%#)v*EQ=;V?hnm8@;<-7*0_ty6wQ`R_%qZ3uWK=u$%>unGNOW6-9o<9=s?_?$eoBfV z)X`TVFv;Bd{k=(GwYrl(*B?#@PH$o0_k{VHhoi3{(EZ=Ki$k$gBe=w;0g+-2_?<{A ztznUXuxYU`#L4(~`I~@C-crJs>&_fhl)qA#Q#QY)av5wK?*~2%g5}4^_}nxZs>m&P zqA(W3&}9iv7z;_wjxtr51lj`OsN*h70zUx~Si4DzTWmO8EKgFmV{R8gb!=YW4X?280Tvr&>`!mrSCGr%bnHKkTWI)@4HI>**fM{D@)Zdmr3;Nw%cC z{Y0+~Nin!WPTf2@bNw`gG02x?T+|U-7sAOZpNOt?oo$^YcFmW96V3$%s0D1trV^y? zJhM>X@uSsd{w!S01pf44J+UHb=nYIM_&D~37mM;ef@!H&}TH`$=_pMxwkH-4e z&|O)kg=tMdF~32v8dq+ggJwsN1gb|2&6|8om&W!>ADgl42~A|H{?55>N7ri*F>5NN z#$GvM6X&sXFQHC{eOQ-l@?%@fO=Uwtm$AhbvwJ)G`phFf9R8o1MYX{<0p*FcT#bOU zbE2@WA;~wi$deiel@^DI;|paSoB2imbd6}|h5Hd`$(;we^AbK$B@+)(xQ?^0t$FR# zDCjLPVjsE~p)Zk2Vm%U;m0$3v--gm@)J8n8PVO@x!eg+K+_hBB^3Y$u#=q#Xu|%m) zZ4P!vOfl$_XgX|CFO7pFxZkXLpoT)1X5G%IR94q+Nb{I(kl| zT9Gdck>AM?)h`bu;i$dFd8lN&ghMDW3=UwJ)DO>phne0q9l#1Po!{GvA`JVDKz3{GDS_$W?$uzURnSB>?-*k7?@bg4xx6 z^cB|Fr>u>08XB>E__^Ret-m7br^sK7L2Zjv=VaRc?b&_O^@Ax!Wm**2u{! zPVF|t66GHtAv4LHBKSnsf2+nR2ehiW`Of*zao+=Q6B3tcJXxnMSE$rB_~j-wIym#_ zeRw(8PL%TXf!@<>?t5nkoovUJ+@=++YxC3T5ANFd%_A}^;k*itraDoTfy5}RVQB6aIsrId!W2l;V_&)JG(6rX*Px}h+za8T1_5)!npHX$)WoY5#yHAcH9Rbgfalb>!6Pltw;(OYcp4`_fGrgN9D*3UcVgdJUoF&Ejs_JxB_P-{9O zrPG@)>%cz0g~4kN`;D{kL0X1s+98Nbk1=6z*BSztNA9{|j;_~YH?X8R*#9jct-g?d z7ETyF*|wCSCA=qV=zo0YKMHQ-dteAk&HwfR2EN>09Rv9?k7KPK#OfoUG3;n_@j+YNu|iLxnuS~N&jY0DE4%;c?rWPoly zVLz!POH)*7Z|3I|b9OO>lGRn;YoO~($6y^H;)%r)4&ov!V{7cf_`h1c&Ul{IGC;lotHA1#;q%ONIac(YgUc`}~bIV`2aF{cG zpnvLRf9@o`Np^UD_K^C4+dc8fyWucVt&{Q{Z++IsmD(%=)*NRU!5Dc`F3ny_VTxoq z;aq`LdWmI7f9$Eg>nkRsNk4`P;g4n{Xw+6BxbU}Dw~=Ip9UQAaTKlvg)f!wXt+*#g zWpMip3xJ*8kYJnv@K&$Ek02+SD@1%oXBs`i6OAdyzvq+B&E1cWS^JhX=d*V-CeR6Z zO?_&)H-?3E0C~fc5@V8T^-N-+ck@o)cbS8rp_X~PkyGZ7i$$@Z$+n=4Q)Ds=nuZul ziJAw;H)Hf`XbW?T_RRJ}oJ8idsOaZ7wmDwll>3btkjgdT_%N+Wu84?w%a8QZ zGHVl)4bjGup%*JO2+DIBtSmi=8$HAv2mJ(&5UTQhJ|YbuMPz@_IELhF3lZl*mrdmm z-bc~LG-L@qWV>thIWH85Ih33 z@b1%oeJ|k?5I`clQW-c|9T##nT3;4Qdxe-`oEpLtFyKy)u&w@`&?8{$jzCR?0V!L3 z$IKIFNXa3)AHs80OdiY653)Zf4Qu&5C`xza2Vq#{9NQ%)uu>;5D|Ax9&o1~)T1(~> zCDYh-z#uO#|F{vUfs>u`d*a81?UbHpZxuEJ)%|CJ8Acmk1&r0)7OTV$rTzo@=!9cQ zkKl>`#7!6JgT^qgDw@9zkmiM!-ux>(x$C4kDD=-N3-d(CQx~=!uI1W+_~Y7jlKsZ|I)7Fc-3i2@ zX%bP1Hf66@KZmamFuT)GtKCk5dr=-#5+T-)8C)NY1y! zKuh?EnesZc{`5LS;jR^Yj67TKVcTXvZhT4#uI?RZbZ~P+OjtzS#3aaIc$xn$23_tZ?k218Tv_4x&JNNI5N6V_5Y%e@1lb{K!XFHpj`BV$Zp*!qEzXY?C} zvz!=g)vDVcm=}_V6eMKih$flP8;YAl&P$I!A#Y7G{|0_`%f0W{g3K|#`j@^>&V+C5 z;JsOtl{FcYGrrn~6z2c6s_dps?EYQQ%=S8R0;Ffx-d`GTA53v=g&yvA9|uI}XdTK* zjh;sK7uI|KeU5n5Yz=g(d%xQJ#R?BAkKp$fjcsy#wv`*p42nloQSbA<&d;;GbSnD; zWNZi=;R3T$IrjO$rm)DboK6u60Rut-sxE<+M0?K{E!X4fL^B&w`loWAzAk(L($>Ro zuBsn5)b-LtXUl2I^p`Zs__F*uK+4UzJiNv6!YhMM z?NWbn@cmM~R)sLB(*i}7gg^{?Csu18?fjwSt#^Dfj3J-G&+c4cori;P4D{kWJ{x- zJG^sJrtXix)PXYosw%NPv6R3;Fnne0fFYgr}6C;ob4sFt2jE{R+={U*Z|dJ zR6f){e4}kK2Pk83BF^>K#=tIIUZfF z;`ohib1RUJlEU~(ZIhaA;iup8)x(^ z-S2E>*#*9%dh{-YgIkPETbwbkas)nct`(gIIPal@oigbw)LpqRH!o4|&jr{1UsalI z#r4eVG++7^=qluywI<iupy0?YH^08RC1ds)7|jA@B0+zvD|dT5AYVd{xKb zBlQOMrR1YMvf#(gAXHwKZc`bD8uhtPtlD%Ma zeg(r!X0NGX=EOS}iOIGh`TE?D5SgOLzFAyOL@B@Zx|<4ig_=;?<%Y&&X7nSVV8Q*t zHGpUI3RzV{&l?$EbMq*1rH?P7*WSd2_NB*Ahc;eK#Dp3_+odU$Jm^qA)ON!^;y}tT zX2DL7QabLb{hfBln!O``=S(re^UYS%2kvh%oy)r^8%fEMIYOW5z>8&dh!DWd2x=wL z4Qj<75PpF1f_2WMo*L1yA^Ku%9dPlE_t&1Ji>%3=X=j5O+Mq+jwO7E@Ch9o8?yh8tTDUF1QLuNsG>|g|gsS?J-1iJ{ZUV9lts}!gMntn~~ zdu|-qC?(ggtz^+R_aOU#h}8cP<=FyOeal9z?HGHt4hpvsm|myFo;%&O9(DG-Dzc_( ztZv5p%>M?2wwy)xQ0M@m8Q%QAmZdEedz07N$0|BwU35?Z_Ae7rd1#TU`nj$c##Seu zFB6ZQD}Gy*IZ;&g?1US7-<27x5?imh*-^J}7z`mg;D>Z9{5~P}^c2*ov_>CUCSu^- zXFVZ$G)RLWW>ZHzCZu{@sHFLGsE)Mfj*>B(Mzkwz_fWY#pzO9QfqN&+_}|0(*62sA zFn3*3eK}E}q(^st_<}|(>sZ}{wne}{0f>54`vucV@GqJt;$A@ex4g5bXNFqq*aa<% z?m9Tvnm)sNeF$<;#~Q-4tj*9j`2%`**SNk;&DlGt1_>KegEiXd_xiz35#eV})L@dk^| z9F*y@a=_?T!Z*AsNp(D&vW}X)Y)-pi#w`bdskAKr;JQ>ZwI_`+FE+dXO-lkCD{(gH z{$MuV8=)_t9$#oOS=o$r_LC9NX_&DsOa>;|r8|eTN<&@39gT6bM+p;M6IgVyZPCGF zk(LQnXl2faV-iqCUQ<3xHN98|Xlc;xAYDG*N1_F#+MI4*hsxz*7WNy}nPn=dwD|9M z*CjH_f{ZCE#53u&tO*p&9gSzbezvV}$K<2D$d>ghf^cJA; z#Q73}qb_52!z@7Ny2twN7t5Z@QmBPKG#%$k)#c>%5!NtP@;N%Hdzc}jU!2n$w}yF` zqLx7=(@QX@y;e?+4P!CMT@^&B9x*26n3sRky5Zn!TU`{3h@)B9u=h`0f?4qR%}6$D zv#T?CX?1;LZHUoqee{9h`#<0Aw2#PQ_ohG`uNc=tW9${3vr!}GNk+0kilob70zgtl zVT{P=R8n%6P`E=ARr|NmPxyd&bd0-t1ruI!8Nd4%6nPuTfi(jvYZbzllqX>*p$tx@ z0ZM^JP(yGlmuQc^`Zr~;ibzyI@~(cTdZ!Ql>Z8*V^`d0vH76KmubUt|Q)uom1Mjo_ zKBC&8HXnQsLg>-=ru#fmaQ5P0VzS{UnE69*0SgN&qt(cdIQk`v733OvW4n&SwvT}$ z6+$e-bkqfs>2@J(c^V^hmctbzgAESuHq{1}{Ti31@(DFl5JFZXqmnQJ%%lw7%e&u0 z;BQKPs5b0R^T6y0er zb%!8Mmw(-5=vCfz;&TrM=6 zOJ{KPL0^a3(B;zWYU4s=2pDygtbU0iG=Y+c7Mdf^))1RO2^q{buy|Tlb8Q@YT(Hwi zsu?T4#*zAeX zr}JMmUL89lvXh&eeVLi2?s$lEJWfqHA&DCD>^@{k8 z5g)1CS3ZgAb_0Gx<`XcAT7j;#qvGLsCqG=ZT5S`sfUEwx!BHDZIFtOeKF$;aV1C&Z zjxl0)tH=yV`nCA;5`SB7UQZ;KZ3+g~^um{&k+fp`X`&`IJRZbr*{s=C>(mp`&71h7 z_*Vju85d|ocC%LD7o_vI+&6!a!dT&Se#4W~DOZ!-QKCGFF=QU98EKlqhN1$e$q{lq zUbRzny7R_9a-zuw&T}6~L4f-MYAq=N(>9$arDKF#=SvI3wc>sHPG65n;sR8@sd*Zr z%qmd03GPo|JeSjt%_Qn$^8}y%o@s#H4m%XhLJFKS{Ed(!pNF;HC6~$A=4qZNGxEak zL}5Ivb0BE(L4>!nJD>y8qu+b*ZQNh+``r3h=hXAKHE2w}KtR*K(NT@JraNw)0pL1u z?xGVP<6Z4sI*l@=Z>ptbI#VnFYR#tWnMn_902swYK#83cDr^9~bFY&~%Vb5et%wP* z^?r2kljAq=6lk5h%2#*U+?cY3@D=AKI?4f`I&{@01V_GP8bp(G+>gR|ygTquv*ACz z30=brXv;o$IlF0*elTa~g%LwwlY#EUQ{aTTJVtDzjQLVo!FeoE2Kmt^lcXl5L6GN< zhn*WKL?k6T*=G;wgSmQ8uC+#+kwl_I1{W(Wlf2u))#XgVcA+Y+6xK8lu;pY|tBoi9 zx(-ha^ed_qmmJ3K4Q*?EE|lh3Ip0bK}q&wacd>f=~rEm{~~g|04q^ z-Vak2=o5ymG2JO3C{6sl?a*fn&zcAaz|qaw8B2$DFGW zGF9^AE_>*n?$C{>u^dNYBQUSk>X z-iyBCLhDU1QA-jj%AlC=-D~>vu7>qTC(JG)cGFU>raSAsZ?rhY!CnsVP99+z7vELC zedI#)>B9+eU{0GoDVMi(V+PYyc_JKV-#}1+0WT;m870N=-aaTEOxDHmM`kp;FTBt= zR{vMngpKR=aZRrVf1?}kzUtJNGpSPvQZggab(xV1vp%^X4DTPJ(MR zEDl+1@=w~7-@e$@91pK?EDOIPC6?6>=i*qYr^kyYLmOrJOSQ1uiG`aJl0A>?BGoyK ze;k(E;7L247u?sAx62scan~5Fd8y$Ut?=L&x*Lu}CORV5SDQOeA5bo8wZ)A}Vr$-y zKU6()k#ac8l3k)zo4EJU-`{TSOmh8u)hDhV+x1Nw8duxeX1vLux&I}X?vy0a7HeqL z;G!VM-sx($ml!3XvJ`b8fBH^Tg`Bb?jQ5aT+I#pw8Dazg$)>L2F!1WHhnR$roRre=TORi|wrb7> zJ7y%#@Y`n=VWOSPD@#%_&fX6(hLt>b$JnZBuDD$eg@Dg~PY$f>hhG00cnP$yUn3Nf z?tX))K-+MzhdA5a3MMAxH;00V=*(u+rh>66FUmflo11mgCB)l0{n{+6fe|k!_w>NP zC$vzhSKRHqP@Rg#3KcvBwc3BN`@4KGuq`wAkL}Fk_72(bt;73U4t8RZWPQQTh|(@u$Yqu%_NW>0HlEjnP58C z4OxSD$vf|!FibDK5}xLI$~&8Sow(ouyNk2;59bEMmKjxel*FZHk_2~L2nGSOv23eQ zDeWwy+sxSEQ|W++L6t}%W$Lnl(nKoYAWKy3&sV>j35t1V99wPFJgl)Wz8H&0-U&9K zNgPLavX6$K?{;JmS0vA|=SNeQ{Jy$4K!WyWE^mn#Cp3ng=cs9gk>}##cv|i; zOETJjWl7B4b6~zBg15!J0(z6q@k{=cpyZf7kk9my@*4p-%q2&1E4-Uw`puTIw9N3~ zYFCks09EzijZJzX2*FWi%l3r%Y#5f{M{BuY>#ex0~zk1qOe-q93e5;Cz2O)N#eo$DwDEalbcz5}ybn>aj{MRruV%N-NK@~s3vosT*Y?zJ27@z;TI zMDHA{W0zFd2Q?1t|Ec-NpC-?wq~GH9^5|`5bmCTE4uhi{n@vh}jb0qsRY*ul4SEBu zFa1#5)ceVC2TfxgngRMaYve=X5|NlkSmMjxNl#V^B{aXp)Bqp@=}D0;)%TmmqDJ3= zerTTo4La|6B8TSK_U4X^2qu#YjHJ7_LQPrbY&KUhxb(QRc9Z*WGx zCTVoDeeMX53;TiC$f2_gqIQ2kSr?xjXnU;lH#)s}Ym-B3A4C$q=cGrt1jspR+iMD1 z@1Ff>8`ag`DMy?xd27Ri>;+=g-C(AHt*g1l5Vs{b-3p2ICw@#92Q3e-vADek8n)|g zJ74L<7%4N9KxrDv+n6$BwOUrftF07$R>GJDUG<-Iy{BtBUE%+!mKErmB%^m-2=r?R z>I2RV-T(dYTPqzqW!hg3~p9**d20JMfSW*Y~*5 zqvqy&^w5&)zmg4J>4$lF^d}_YgBbX%72|ag>4Wz%E6fdDKNJZWOx2exYn%3Ovh;?Y zLHYl3PJtRq-Kc8SaDz7T6=J<*OEB46AK0{dQW?yt~qq? z;&n0e+-?CcLxn!dwG)I*)8o-Zj`}-Tg}vC$AeGcdSFI!+f5dKlwZVg1;n89xgV5jo zK5sLUGkj^q#Z)9G>1`%jxUFSpx_^i<{|nq3(!;#;rZ&S^O+7sYjhW%lZ0t+cGpE1K zDny*7nvHAzb%kS3H^f{4_j!GtLVdz9iq47q#%fu&*rcD=%}V}H3t+{-!Y;)t9HCm@ zARP!-O)6@)jur&U=#ksk7p~3b#}e9zS0?Hl@Q_rr4a!dbm`q z{1e~sk+S!CBd?9+uGQ>mXcUeSw`@*W3>u}?ow4`Qne2FFpS{SpmfA|eaB|n;&zsjz zEmx%URfhw<0f^ISas!OeY9UA`V-gqMHA%u|>HXj0(zDFpPlLyf&C9O$9y~ti&R#D> zW2@NrJ7;)S%}Cj@NMJlUh7+Sk3O+Xq?ik}AmS-0axWAYbj-%vQ8}{GTEJ0ekcW6Aw zm^_>x^(P3&u!69w&bg+Sroz*?rEL28)@T%8sh~mfD%c|S+`~2f3Ki<7*Fu~~TwDG? z?onhaif(3}M=?k`ND-^*xxg%PJUeTou3|n))v9&Un&mO^e=h?gt*zJ;AWdvl!(7>h z@F$;U!9oS;tDD}b`BzpamPL(b4hIu!4SsiUj-OJhxU-<@CUE1=-$AKAP+DFG-3%az zm*o=~a~oXvgauQ7pzb;uzb5@%(3X``s|3&t>WXw)(%SvL_eoGUeWlMBQGTaHOJ9Q+ z3d@~TvIL0R@jF2j+sv)=-nZ%qg}(n+bWkXrcxa55PZ^;<=zY{$#Q^O-bdC2_33?Ho z5h#AN(EQ$O=BSGMab|}vOUu+Kbg6!30V>6U$~B94;1HyYkTe*iW+JcjHg_NI97vhl z{0K{(ik-Ujq{lNd(hWakrk_;;xg>IV_C6zd^h7LIJ;cyLjq7Y@!qwJ2D$!l_xqxTF zgB;j3rYYH6M?&Clf*fcpD_v%%yJ0C6(b|9AMiARC3=?0Glw8CHUU#}+I$Y);C%eJ)$zeXi1=k9zui#5PE3A6+?f&e? zcyX5=If~Qf+j%_bcf~~dRt@@fsDFri1|bT z9eNPba&Bz-hqMqFCmQU_Ir7||T#dfBh^BdGF$mirh1MXEV!hGN7vdv}@r0CnZb!N+ zm$Z(EixTEe_j_us>*^Tc=L|c}1yoMq9RMw^dfpczp|5;DSxxqlL{4~5I1*Okn5!)# zUo5Kcigki?eF3KfU!gDzTdWx3qd9WnL>lWT*HOG*Y!#?0Ux1NUjqeZy=%1Oq zM>=qDhW9}Pni4|AUJz5-PiNZAXlZE|78i*D2-CJ}ZyuQciFRw_;SrdgTyiBtr2AyM z;eHr?EYuo2g$g{;1mqzP7ucI)Fd%_6gfe`DCozy-mu0$HDHjh9o)s&ykZsDxn;T^f zl+*qnEjp#6b6I}bz9SXuyQ?yKWP2cxO(HOpcMWsRnLplT7 zvI!phx<(q0Im!1Ts#ZZ`Dr;Dt5zKDbu$w#v%~V(Qd5WoBOac$vI=|TZhudAHo~bp? zMw-}3?ug0cu!o;icikbFg370YirvJmL)=m?3Jq{ z)ECSv*$h04Q4fJ*S2l-7FQ3dT0*;%wHa*_>jmy%L`~XDeceyRVcU>Z%66my2{Tfs* z*{YoKPjK2EKvZO6J+|-x5zuy1CLwYlumg3$jnK56P$&L0{I!<+bp98R{+Gdjn!wQa z-tJF-Cs3tXS|hLg#2iuf^cY90n&+i>@pT?sMke>%QoC zYe4Op_Za{F_}J`M3uQF0C(r-_eU4Et2>Q_L=YNTWQ~S{?-bQ%sO7Cqo>U&~_+SijA z$W!havV86= zCT$;rZ!k#YRkYJ(U`9Ol=%&0Da!Oc}BDmVivsgoA3KcXPn$O;DB*rcslF(Kn5*=vZ zMZf+%#6cFDEEKV-J`t+KB6^mAxgHj(RyxGmx|~zblTXXf+$?H`RonVk^q|o>+6IJg zED1sOaXs6$xRB%qoos)Ey9vlyp4zO9v2IA3|&+i@Nq#Q-EQDx$k z?!+B%PZnxE_nH|$wsQRBH@MPri16u5_%i!{L$iFx$H#U~c^`qe4KRns!%pT#WZTAl z`)r0iaIZ%-JUc1xst7CNu%_5f|_w=kfFoU&RY>&x_tlLJeDhEwzlumiv=Z3<9UwF3sJ)>Nwj%zII;s~Z~@by@X z{rta9#xkYW%+nd;kMO#iEkGBO-q32LH3!LQf_uj#x8{3)-rGoq{Ci`X#-3K)hAM;| zjY=C`(>gd&0AqIja4Q@1(XT25K1-!ellkGxTMF(zXsHi&a9rN51U|Wa8w}APwcWrj z-*bK2Tk9=Z$1)b1*NpbY6HNhd2_`qNKwKcfLX6LMX>*-2!U&VCJAbkoQnIF0# z<5gj+cwIMGYUlR0$@QI=>yH&8iqX|?`Gpz&X?akB=E~G!xYmgA$mthiyE?%tWxFX3 z<#l2E@U`v4I5U}W-&^P2>DD_<)6*9yhgtt?*P;61+~)1pZAZv2uA8|KzR>9}-Jp%! z#I@CiVe!QEOc)pIS1VWm@u#M*v5$>xYZ8Qbm?GFai%{nAh%Y1kG*}w41Qzr*w`r?8wi%@wJ zrs36>=7RzP%ICLi--B$*!kdRH|2DCV3yxKU-1onE8;+YgKrDgxiWmN;)77eG`4 zB3^T6Nn`95~wnt9fy3cfX~-o|2%#E}w>x`g9>n zhOuY91?h)afrF{;F7qfSGxpZMPVhNWqzWxn$f32M*W@?u_X&#-^~;J2^&4Rz8d2aJ zVMovyiHn#&r<#hkh0$hp2T|7D`%1vgrBJo##{0aXvT34qSAzTO@_@O8(+UEq4hlCN zN;6(^^9;En1NE3)Cy&bY1doR;k4FQW_!yg@#lfbP&CeVL*{pADXApr&GhZ;Pj;-%AW3yEul5BVl>yU>o7)oIGn2)|!+>d{3kXH?Kl}KdJg3jf z21Niox#a{|S!>3gniIP-=VI%Bx^m-*5ndW^H?GffHoB%a)Jzd2Qat4-4gvn&YaISg zgDESAzVmtld(KMJerLBMY|yi>3~#BaDaqW#Ctj;1!s#G&yMJRnWsx*>=rqu^it*rx zcyp(~=Cbb1n%{~!x;P{}z}oPHQ|R<8wzV}sHj8|Lp=5wkFN+m?>9hYZ`U2XD@Y~*a zYv@zIy*COKq)AXomS-Q(RhI+<^7rkNp1(jjd_C+K-Tng~C(WR5A~8KCL*@IQLArp= zquH0F>JUwBqeR6Ve2)j*(;gbvke87@$?9k#%QEc|$)66*_dT7@z4E@(paxviJomwD z=jF-3JG~mOkZ&lsroYZ)r^DC>Zbl{yxsB|M$X0;zzGbgcJvc0@*}9vvX@ID}T^|y_QN2MFS zl^I^mG%vYYQ*c?CzH~&7rAY)#A7)ZYH}m?_Nx=1?QXAVlx6J9attQxn!1IrowA4x$ zNl_PC7h`{b9C3FYiO?-fd7SpO6M$Fc5n(pPi^&UCB)W`8ee7d8Qn5*-q}#+6qovM@ zAFoY!D&%`KN-Wu^>1{5$zx8SDd#a)aH7OaXJn&V5)@$Vf*+~JKzfqB-HA7O0{~fbU zn|`^jy7ROpgZ>Ik%Ln|b+_>5OvNL0=);?$qy zKtT+THLxr-NHh64?!6TRtb(clreQmCx+C z$5VgkT5cUk$W1dfE2bOCOn-ePbcqzGDRGTQL_5G6bnv(6uEgw`6(3#LiFi4ES*0PI zlT^cMboB+6PPzL_i%q6X84yJkD&ZF!wjDu?WGq&XZ0)aG^l$DAZnSvt4e>BFb1|o@1rdC zetEP`4`-`Uyv%MDH_mPcoaw6`ZWmh7Jy=*WJ>`g|T6n*vi#(j+`QJBxIy^E<{~V~W z1|nG&>{rj6%bEhH?nPf#RvEcCk{cBXLHTKz#!xGI-KO;Kyx5KYa_ua!EmD{rgd|&! zr?44!BS!|LhyNJ?f#)xA3Az|y>E0*zx$CJiI}Ww1-5A%F?K~S z(Av-V>8k4e$dlf#DLaAyXhFHpZ|lA@b%7VWTku68jg%}@H@~Eqd$y!qcq(5ZHd5AT zwvtR1yPDP(#=;4KzimpdGPZT(Uh2(0uf4QC8G2}cKj&`3tW-=F0tR&|h}Rn8E`Ka> zicT<8a>eP_Jle;WW*~av`e3|8y^XOPfG}_Iax{ap)!~qa^&;POa&RLvq(Yh&^9H*7l zI!ogO%dWIA-m*58ZdW3P{*4!}Mas@650dM>D|eG)S~xW2AcVXKqj;>r`=K>8!*yx< zRBs-dC0s!yAO49~&0hWG$O~d|^=2^44d6Pan=W{HS$H4+ev>1!?V@t8Pr4FO+6|;!nm6SGv~iu>`MFwtnse_!x9w%h#?KYWK)o@{ z5493slR$5=_6RWw2vCfNShP8DKw8^1OYDVIps665Zpv#}1^2UhI+N0PMvhIq(j+g% z+Hkq=^@7xLBIeM{j`qeu3l`esWE6Cm@s_JhFs>VOsezza&8_&=O?~J%!(J}qcS10c zV}ZJ*x%H_w8p#Nua8A88WHhB&Dr+JGA}PE(E3jU2?TCJ_r}!-Jw33X0B)5Msx;^lB zUT1uBg?&j;6+%}YlvQrGfx;PF2&fOBk@>cCEMA=F;|)5NJW-t(U5D{8*%;P~Hz}pD zUc>FOP4k0BzAq)$m4x}vcST&+pA*vW#X6}!2m{ClC6H&WGxHP-;vXZVgO5Gkdw#wz zpuIC(b+BjjOK<;lFFGV0WC5IRv=TSX^h*IW&_y!5EI6)~LH_7I#=+ zn$9w)&2Edr1&UML-CEp=yA&-}+`SZcCrByo?(XjH?(QKt6et9j;BfQ(xXfgRNrpeX zlXLc7>)Cq^vq{7JD^vYG2jn8{o%y?hYM5_5_0NZ@#N8;5Ua4(`(UPBP*^9}DU zgQD-{!g+r+mg8YbEg<-c{(G!`3|Epvog<|3#;q!{QYHbzS?}2u2zrO=A>`7J+DQa zRx6~Xh((QCSYf?&v&U-)_SC^?jHhNFsBF*k z?qLKCoKDH|lkYC0czhou(ozPJXkY{McW^<(Y!G$=0AC?&`z7hg3C}eYM$xClFu6M} zYHXAvKZ>Hj#tInQaYgrfF4>`pkENXsNr9iuuj6G~!jX(Xv zVENWUEXi(7doE@r!FCsq7CtPZ6sHFkVqw>mC+0PG>Ii%RjqXD));r(t!hltWJw9br zRsWQJpVUwnu{8?8=Z|Fm>+lEk+-F-vDW<8iQzSy5cX_&3N78-l^05uSPp!3lg*^Cy zLtk@KYM0|)gp)sOCMkCgl%CxP6Q;`9Kl~t@K^MQq5Q>`onWpwEkxx^I0Lls;ewK5y zkbMxD8L;@Gii0B(jx4H{UDFkMTwFRKD0YliOpZJ&+Of%MY(gkZ>D~Ew zzdP>uBkzYCz(9i^5GoTnYwln2Q@WZ#*j8~$ZU-N$4kkUFc)IKqC`VzYYC1is_uL$P zyQ7YTofrU1^J4)5Jx_kJ(1Ux^gB{{mW&u&&E0*9m_%_COF+P!QW(d>c|5QRGhDFYP(7 zI_-vL7EZMOD--H`Tdds+1KdqptQ#j!`ksAp>eth`dn>!)F8tGWdo1#qr6C#85Vte6 zvoGT7nlPW91=d=g<0`n#gqw!FfkI8loQL%S>(kL5+Y>DYp+M(fqKd0O@d7kIsY?W| z$|*$7I~OD`yAE0ze*jUeTD{Hc*6=TlgW1Rm8XE#IjJ)k+$5IM$>xD~6Jn6^6xKo7s z4nJrAgW^4<8JkWO0WwP5mz8RtUT&UZRd`^`)qZ0bx(jcUJyAk#r3L7S%j$ZPYOzW_ zb}te`nsxvb?==(l-E%u5GkO;BtIo~h?k+gj5^&uv=)pJKU)ClwE^9dEDVi*^#+=t> z5#$%Iwu)r+KAbg8?!;$5UYx7k8Quc_Vdyp9cb3ID(7#&u3q4I%WJiAULViKzf#Y4g9FuFp*;nx0N8cHh{Z@B( z;V*WyoC=q?#Pja^<};0Rt7*CWEf69OL(FA2ZptNF1`9~dyAPVkRAj!XKc7!-Xi-<> zqi&y`o}#uOsU2H*QEndkJ+f-S!J0rDR2v47b2A`9K*;xPCGYqw|}#Z(iq_=H_L>5 zh^xBA-Q^%IV?}o6Ky=Mg325~ZW~!__J^>BW1)<*b3*c3CGHXMAIvojn*|Wcf#c&5U zHYlTJcr2MB7TH#a1lFtLA1svAj2T-MCt&;78gAL__2n(zIuZ1p2Vm_m zxEUzUb2{aAGJXUi-pA&w!?QQa3tbr~?>C-fI5e4Fym?2Ya-T-EsAL8ml}~A#35_jB z2OI;qP~DhUe8?;$2GV%JZPZUtR5@?vvn^-tr9L%+MFl>k*2*}%%LKV(oXL318CIKVfPwvk ze&em4gxuKRRDrvYAt0>@U)f_R)twg6SVa_YfO)&%O>JdR=wNyxP0{ee#E@dC*aN&| zgj;5AXY4!IJ0{G;mq!{;Ep$%|UByEwfW_v5D~+9GJ&EFCRp>4%5ro7x70%BY;63u<3TK`P>eH*wIXSWJ z=y2!c;gNn)$huAM!k!iy9VASA3tLaJ0m3v#>7o&a89yAm$p7XaXq+WLKiTHTS z6N>?L&ead!Lz2lG)ZwIoe}j#2RMa5JGZWvmav!I?vv>_A&f0%8CsW?>gk49K?Y*J3 z`y>qP{&U+SX1<<8RX;ZB1V4inAXs*7x!4KEw37XK$p?;jCD6MpMbQus?T=8=zANg2 z;2t4&!pN$*6RhegKdmD=eC~5nh*SR1Q?L^C`QlYD>qa8+im>;1R;gpJ_?scrmR)u^PCpBZ=Q}wVpZy?L61Zsaveh&K$4}ZnjW)uEsjrv-9cR;lh74o{k zLLvFrbb?PvJ-FJ9B`G~UJ!K&gnE4;v+(-&Th2?h+ti70xEGXSU{Wj4)O&F_Y$w5~-kGIKs{@F&pzj@mZROtMCi;PCC z&>+l44NQ&yvj81rJuUl2j@pv%$8S1d8#vazy1=(QJYAxrlZ>-MLC1-YfimvY-b-Cu zMBK3+cGzC|0bO%Q%k})pte6#M;>*_0tM=lg4f9IvVS!4QtI{=ULExU=jtJ#aQeDxG zfYL&DHN%KyQdschFa82Mi$(=+-j6z%R=7Bpg<)fN)EHW;t5HRg6_E7m0FfRl2Sw zS13o**^kDi{mvrzhuQ+5Av%@4P(aaf^!s3PHu~D!2;NSI)k65l`SyGLrGGnhgIzSH z2~R=R+EGkubh1;vos*=9lqXB!T+Gjd2@TsVTg=$e!e{CM8+@hy#p7;E+7ch~3SU$+ zGqV@-ci|?MlYXLEkA_6*u`uD{S!#2bh0;AL22|smqxiDx$kSLs9yb%_go!6lF5o#M zhQ*IK5&T^9fP*YtK00{F`0ov!9kZJIx@UN$UP_%KlNGNbj7r}&)j>Y31y7Td+eN1; zI@hc%<30u|j!zit8Y`n8MjjKE0Ljj?-dsPDdZ0Q44=;?R;X%CiY2p^%sBpE&x6xc^ z|3&G99yy2JKKI7QOPLV%%tfSg8u(|cN_rpMnE&d8KJHO*lhsJ#0)fWNExo7a-xq~s zF3XCNj;=AuzG{S&@R~Q$3Kj+8P29RIFsMUgfhY-$*vQo1uQh<^6Oc9pLm9}*kVBS2kIm< z4vEOEl6dBo0@H^1>N!iY(_LUX)f;$-0b026wdZ9_6Bq<}#0!jUQ1M0JRIAA`cw~s zs(5tAfV6#UO!n&GZwaktc{Z9cwhrmii$S1Vobq2r>Q(yf5%u-;vSgT00qD8lhXKy+ z+TFA>+&WwEK|Sy|sJ4CQ)ermPUeR2+OCGBRdQM#6OtiE>P^TMLuI@grwQ^JEFvfrD z?7Z!15+QgEji?iT8WeOgg@uz-W1jrQQ|~crh(`MiZn;cn>!B!AFdd>rNPx(Z*+|em zf03f}bGaWi))&r8)xHQssBYFf&e|3`DnMWr@=6ozO<&Ct*n}T`^_n{ofAE2Gag|3>;X9u-a3Bj`h58W{P(1#e;o|e;#y+tGE z%Po8A9QQo5z1UJLBE(k{#og`7d&}OTAY; zy)P(=-(Fn}mofCC5=c^E_DMTD*z|HlDq^_H$Z#Tkq4(W+E%%fLxqhta_-Ov)WHVvM zP}c}exA3+_x<=vQp5U*gAu|8v;A|{ti!JrWdMCF5PE0%cMoI`5@*@Q}ns?x-cv}d` z8nq?}?G1*y5@~Wvhq7x~NVL?}&|^R%Xd6F%_}*o7a$v#}dOqZLYu^^)Q%St_l+_qc zLCzjybZ3+*=R#!qh$SEGKZ0AEK&wWQr#Efl6^G%GHA@eR7My4SFw`@G>BDz8($rl2!pI4A+w9D z#f>sg_FW?_uQ%b*_hc1-gmG0It>C7&4jU0FKcz5 z&70wy3(=AMiPi*rse8#MXY_KtufR>%N;M1U%4sv%S0@Cs=plZ3bsk*frSDT<;nS$T zH{E_e)|832hir04fNoTC!jc7N)4RTw@*rZw+Rwt!MwznGzxN*(MRrX5`Ua70g@d@HV?8fau9s0T>(fijG4EZQ5odpmm zhmBp?3$u`(snW~*%?EVz{bE(O!iA=zBad0Tf^D#dJDZj&bY>DI zS2g@p<>g-YQgy5`aSoIyXaAnF4y*c=x9s(wVeGq7RdI*6(?67a(eBV^89E)n0*mfZ z)v6tW+=)60XnyeS?0bL#Lm5S?i~S;DDj`mQ288sP-fJ7W-LjNL(SUdHUN*)Xn0x|i zMjSeyI&0QC*4BtOg$&meQ#RN}V&DnKPWCGJ8PdAi z-^mdEW*|QdufRlNMj}3`tSeXgPTDCE-=dypox_nG0+$^YYkQb0(ka;-KMFtc8QVMH zU{19M@5vbanWgICm*9^LcL;MJ;s*W)d)X%E4g4w&TANSd2(~t>kB7gwdr7r_Ll^W9 zsbk-Dyh5G z%!y8|0=TOeV`k{ymD%?4qWyA%J-tUBedVz)s=sXMDf+#Gd8yFX(h|wt+xsehy#WUW9}|*Fp$=)k8QgO2k*j>`1|@$y5FwRFL(&a5aJ|${S^Z|{%6)*!8nVqTvXXqIDhe_ zaLudfb1c|L?&S5mUFTzECc7p+j@9&gJ_196!?pT|ZGWEZ$v#ok4egl+7>Ecz5}fc9 zsV=Sly!muWT1H8?vPIxi()=~ceiJWiQJ(f!qRg{_z_gM2v(js@K+hphGE|DFdl6%M z%Cw$@7GGTN7u%bC6Z%EWWl?L8gN}*R=v-kV_nQoCNgrsah9J($S28n&lnuHv1)zmI zLM`;l{2NYQ(t(knPsxrbl%chB*x3DNW4-HRv3m&P-BI{?!2JmJ zDOYv16 z>MknE{Vk3dYJAhhO62)NOFq&>3wgD=y=bO!7xb}zpJnG>mR`}4RZX?{mu3CCn;y10 zp=CHxPrOU}@BQ8^+9s7fjA zb`dYhHfVnr-DRf^WmhHiUGi`i?}1&GI3r0F7ze?RLfWryd;4>(I{((0|DNm#8DH4R zb+sa*97BGALWMLpR%3d892}h7>zsPlX0WZ2j7_3--DgmWz55A1-LpJ|cdR%E!Vt?A ziqQUo5vT?Isf+z^Azp5-3=6w^ItbNw43m3*Nkkll2Xk63*D zfpE6HV)Zt%W&<#jG);{_C7Q+QY)4dB`&1=uu#J4za34|dW)gI?@QeAEBRla=e-`LB zQs61revw)-?DE8xlUhi$%TjZMe|_)dWSCUgo3_CMTDgyObMW!;S&Uq-HCWPg{zj_R z{I5cTmih-f{b-{Ip^hp%n#ad{(Re!M=i@a97F}DC*feN&x@GN4lq0yxtuF@*+l!0X?Sq&P56G2j``qEB zB^E$)h1Zq+lv&zh!pmbl{kns-UaY|a2yHSiQ*`)Z>`qwSZ1Gg``BdZ`$BI_r4_tRQ@Bgg zu#Q77K8W}TGqc1}*ISRY^bbuZdoK1U~q4R(JH~z&SH_nSJ~|3ZQ`TJ$||<# zsCm$&IsIcN=gN`<=`?ndJBmYY^r}Y3ee6T%my$JJu8Gzsg!YmPOajdm4(GMx{N$CX z(#FJZTg-x{X8NX4@(VY6Qj1ma0!qbsZgrt0^QX+FD}<><2!Vin)gZ`dyIrx8IeTbw zLHk@n8+$3w%NAnGuzh-i$_xv^ZgKF$>;~SlG#2$#St+&61pz{^HK@Nopn$n|Lu}ch zQUF^SL8l-S&017&Jw@BFB#h_1OHy`#@pF~8)u_eKadMCOUc2Nh0(BG1(anVR7U#kM zk4EZ;z5DH8;DPZFZELbc-Q3!nsEE|j2*O|Kz=syDcc*J{kT02quCaPq77%sYKWv3X zkH6P83!zu7zJjJt)tI=(_lBo~pjz4$??R84mI-YfUPrsBh$LXoL7?=r{j zUR7MgtOXYMnns!b%*A|MBn~bzX~6N}^K%v^9`t$cL4iI@rp#>svm1JY{Wv&(n?xJQ zLc_i?GK9N&KhOHZm8)a-3gMD&V{Iz5see~JSUMNt3{%UuM&>O!`Fz$C>E|DJ2k__M zIPVq?*Eic?lcz)%fL~O6@r3=IanZVC`6uSy4}Bssxp(h3b-1r^zLIuv2Kjaga~x-D zNt_;9S(>!a6^XSjXvrJ0f5J(WifExuQ+icq^>|g~-F#*sObCs$AW{_m;4Mbqx!b1v zEG!Tuz6fGI{~fZ(>2bE?`9*#)-Bx9!s$O>ivPHhJs4F|eV>dRCumiwFeS-`dAnx&* zsn|h$)}za&!$3^~SEB^$6YmH7?j$-yGGXjE&<;D`gA3(Jps0M;Kh2T$($!dUVQlVm z=)-Q~byltu%^dMP!~w-e@C;PGZjG&((2fdEA;%t8=$3tGTnLo2q*$(>xc)2OFfmvb zr)~CVRX&{l!`vnt1!+u*d?qdLQI-Yb=oH%h+EydGmM;dwNPFl-9)k;1HD*qroxQI^ zgion7%SFMBs1&NA5m*r?0~`AR+R;D~OSv>0t6tgwx8fv&+NF=vy=B7?Sn!URPUd7m zGaUAcJN)>Qg-9qr>ffK;GS7wH91NLpK$(wcvH!GtQPiusv2UznA)#(nb^;^t(53!) z{CL__6xh2>5`>kX?`&uf1!3{_y9FR`JDmEYz>%#$RXW_hC${Xr03p?P&TluOOCc$v zAIjN2T7!D4ho5GTO8B@!K9|!FWoRwWsMeIABd&MnrTpaK+j`iD0B+-tFZPS1{3E2n z<^&!cf)-L%UCQ+=wn&1{0yr4UDU!A2f7ODs4mfEMyAmq2JFU@4b~wU0G<6lNSr(is zhN`?=?3h|N4Ea&6kz&n9ANO7GRWIaKwG8oEYDK3KhekBTd|0Y6!hPC22@Eol@ICY_%z#*6M?zg ztf?l&cuhdgc?0lIO&NV6Tgl>Y?dEH*0cgXElIJ9B7U0_ zF7p>brfKSQNy&76vJ+NG{sBNQ*=6ijBIdl|+ukgFVjZ>sFW28xBQ#P8EUU;56uP{2 z#hmjWD1J;fdsb^>R6?|QX%ED#JAz9+9QFez^>ps`-D`NeS%GIB*w57l zB88e{Ol&-t_G3(dJ9Jb=@%M6gvVgDd z*#TY5{?XkSbji9YV!?KARO}I3ek2`t6vq8AXR9ByK4?|U8egE>e0S+9?A9F>8ZGSB z8g&ZlXn`}nmGd-!c-XRa3F>%Vy#AqcQ`z^xW)naKW<3cLI+y|p6fkoz|Y^|WD! z`?Do^WiS?dX?KBJW~j9lIpdgUbrNCn@JfBV0_cg6D4}6|7@jDB&h?ZkfJ2lLPdNJ! zt{M21(q$&;2WQPSyOtN>@}uu(wo6&V9TT#-di0Ob0bJuufLjJdPP~7oen^q6bD+!# z2yLW2pxU{X(yLtNq#C9^t!CKS70tl(pYx1MdeuEUSeTHmNld9*@Y~5IQB)8VdHg}t zG`(Fu?5$1r_$78Jlrthsn6?fBIbqeaNTi}9c(hA5;mH$WB>&OKrv99TT*&H8mu1?h z^0QaB%!wLN6ll+kd;9nRaRO!T%`6*20R{q+;6V^U596v-i`T8cOC=E4fNrrLqN<>; zK;5?m?McuL{PfYPgwED4zAh!5*rZH;umz_wfV9>?wDKlXZD9s#$t4$cp^d{hKp-Qu zhj|1uoYH?eDg5I&Y|y=m8XnEKea0bMWJ|M6mN5*U&(@4t=DxwYUSEp)EdsjA48S&R z@qwwm;Y>4n95$N}_~Dcx&UZwq75u}&!=!4?*!;LDH!kkDG(9%{(|F>vXHb!ng>1Iw zvt0Ig9O+d7#Z~Hu_Ozt3S}dx8Qvgi|n<4RE^6&nq^+v&~c{TQCK#NJN)>(utx`dx^ zpNC^)T4~sLe@(CUnom<(cE`fwk5TXr-tTtl{qdsUls{*?QD*3h%@~`ET0m5fpRI2$ zanqQDIWrevd2df9>G5Y8zs?&8lT+12xPgrg$x&)~{ioYv4^8yxuV#;G$c85j4ORyI z6IF+FvlucRE|ZT}3PanNw!S!54DQR@A8>hLz}9qf^ApE3<($yx-ch}Wi7R|Au}lPj z#}5iLdR6zzZ3$cF3>wr4%lGyeHzOyzv`3!^viBCU_LkeDS)VV%F|`gBo1ek#ro}e& z7f-ZXcjNrER)@-Jo)=ld+pGjW7i!zXfY9*!m<4cTpu38lnHCbXI5y-GezAAe9&Qhq;$!-6*I^6Fpm_SwRsG-OlWCtw?^DDRiP$PKaM9 zZQ7-H*l6Cl>?dYUsQ0RpHFP6&8>bhfx*e{1rt9X$t!3CA3_V5XJ%0uv)$V58w=Xqg zp-j{eOib`uh?o1d#Y#IL{zptkbK9_%)YirZB0~2pz%ppjYG|?jf&z3$O+itZy9ZGc zdKc+|VfG3%2Jx*dZl&B=X_RDPh8@K#x+l;^V!N(45cf99S^{u#RnI1Dkz{qkME^~WU~cv+ zHlx5NtfW29lSY$ezN#mmx|kHMW}aAB-;e0(p4o2^o!TMAZY#Yxx^DS(r?-0Dov{a( zr8%+oBv0Gw%M;jWw3D;s2+iJFoO`M#KYfLT+B2^|ptMamK$XU8VQ|Vj|Fh$Dlg#=! zd6w6N058X`S=5+LO8<-mmM*Da@z=^(s|Tp7{sgdkz;4ygC*PWd zR@knZEWegVCI?#V?0WTz3bNa!+BgHBlj0l1?sgr3~LL z_Zf9C#&A%{DLkIMwiQ`1>lNiG{s-4!m#WU`)$FENX`?1bJ9jXWzozwmbknH$_Mcvo z?zTKEh0!79X~oXNqsdj4twy%IY=^eqvf=z0D>A-2ANh9%TT7Du&(Uw|Fqnc_1-;IV z;%B81EN(ZGz};ukzvc*Q9u>ZJ$Lq5@G1-lfzWQZ}crG-9rN3DAOL7jI8iPGRnzWs0wEBq65Wb$FbUt`Yk38uupSGcLInS8}* zHaIe)fqAi`{c%HcBK#`erBxLH3710;uj@1)ft;UCC8d1opwwL1Ih}2>(NNJ`x@kY~=|Qrke-E|< zidsMO_4zOOMDglA>Yi6KIA5ou*5@H8v8gs|JY;*yj%qWQU`L4~YyEj`qO2d#`grzX z!;LS76SqB0sJDft!6y3hbiEnslokM+q3tybaiWmTI{qdJ7Ihcn4-E||x4S+1mRp^I zxrql4r72AVyfbVLOB(EEC^D$qrd^ZZ^6q`uWifA-@45KCO$TK30 zOtZ-LWZ?H0F?O37Naw~fdlB}iX-toz_KJPglTSx#=?j$lOOd;Kj|*8OVD<X#eMfF<_>Sq|sBalDZmg9R*Re37>l7U@oPF5h+TdX1JZhB+B^GFwBN1T)^4oILmMIDTh-7@s+`yPNMUkUTe27~ylnLnnmOXx^aX6ois z0=>m#PK8qow2f4|ncr-Tl;_3f8v{5JL`%{iTlu9-!H5{xQ zp~4%^(a;Rpb-W3CJ_9_A*vWEr6rKM-y+x-Dp5h z;QM~Vs9Rz);IrJ)KrSG1>m|Tum*-*zN1#M@c(@CQq^)+Z-KkK%D7>qv=4!*Jdy?dx zc4vX=H`*tQkQH)hYyZ5mInM8ZXt$EDre;u~GAC?J{mX5leTuk8J&}Gp+nYe%L1Se(Xoy`;PeG zUvHXSC^H)mX8PX#^;YqiY5NN0n|8)qfS*0L{m=Je2gy@6OaL6UU+wf!?!P=2mq6;_ zN%5YU9bf-@{A1B|8o4!il(0;;XY;6vntQ7>rSo>s&-A0oXS z0M%b5Fx#y{=A8XM0ed^5{?7u8^8yG-KD$fLU1t+#mBQbJ6rF7fr=g%Zw5 zgvl77%G2IASeC@MFTr3*$AzXCa) zO>5O%78-Q8pQZAVnI3HRrT;{es99Qn!9ATic472dQtuiY1B&sK8tufCxv4qK%(;rE z+?q&@b*R#`_wToWzw-G~(;B<{^E4t*gsOnb@F*q*3s(WGq{`*Lvdv)kh2)?*pi(X6 zCLY};9=#2_dY4) z(LJ{0iCL*cTg3*7R)bfayq~!@Y{k;f2>71ikBx@qdL{?EwgR2&&KKk`M!%`@gi3s! zpYo>t;)9*|<{&jQL+dkmF<0>50tFNVygQ(7+h~KT1;fIhLQLUp54Y{V5eG23 zAn=2^>8>&q{~jP*#kkH36)HG`&nXs#3?l^%^vyOru6wOKD-wN`&-V$oEVUgRazQW$ zb92jbRjNAf8*l!iC231u^!zqx38{YJug!WN+8i(0KUoM^d3A-f*Z|mF<(?A-a^GkW z+voc>oU`<7{Gv>}J(+Nk1t}g9X+j^i%B%G`E?}f{PAvkdu==}DjMoCJCc>^#8k7jX zAq%;semVT&s?sBAWZdf}m$z=Ox$ zDL$3;I!ZW*wA`yDG|muNyXR#i>>>;^|05K}B!UinJsr%#_PUt5mvGy-LS+g19#Q9_ zMfv&PGK?T3w)O&%7jteL%`k26Vq*(>Zv zUbGWF3;Xbz{mBU}QZW1i_(H<9a;irkt%XDhamy08BA92=kmPjCdWN#+l2my}Fm5by zG(-*`$st4mYH^A-%qfJ+*p*Nxc|U&6r>fMgN`ZsnFiV|h6fzErw+l<*p*?ua2Ha}L z-q)Aw5EO|_`=rs_e>(zV4q=tEz^%8*qLbT<>*s?Sc3493_MU{u<+gDiOsXqJ8#F|ybH*J#AlW@X3 zl9gFRM}8j4JAe?MzRn8GCDgX~Qe0*cse(<@Q zuar>dj!syVyv3ni$uC9-`km&-1!2!hIs*&s%1UK5^gM0L7l|^Y8>L2Zc8kRgHW8kn zLtFjv|7lAUBs9&ZOqiV2RPs9H7rn7!DmTAk6e=u;6yMPJ(sXV;zQrN&OwfkI_fT74xH?Y`dKf?dk&Lbd zE;#Q{Zftl^aF}wriuQdHeL-OXSUZMtSJAme9VEEaU)AD%sdkr!Vm7Y(2YAR1})wh;dgAf_8Ri~St|ZB6D7nN zY8ZZ|RpOtmT+|T3$2SG99{i0fH*-ZrW_%FCWaOs?2lXTA$&QUCu!y~2;;s#WzS7G) z*VAnEA2YSd@NS-@;W1mqUEjH)r-fA~&jafxaRsw<^u%w)r6)(W zI$T}yDzBCMAv>8sKOn5QEsE~B8rYuK!}tQ*kqT;poe-x}w7L8A4Z(NI@kL{%mGzduo2w zCs9-oed+woU^C?M?ZGad#$Y22K@Im{zD4OSu8+v=H?L!Rv>7|v$0xvDEC=|8j1x@tUb7pO?U^S+u#7V<;4oCa|}A@Yh}gEwws zaoUH8+K2n3p6<$hf;Vu@V4naEW`8DU9%$`lnsfaNt13EBCu8QP6MoW{fW&}59$%aU zIhk59p&i1GrsYdRErmr-o)x|PB>#yJNnt|E+m4_IzG(~e9o?aNxC4iLU5_u18ES~U zpDg6qex$etYYvTblDB57>om=vHQTCsr+p(oe!OD$UnWd;`8D+gwJOd9OwyzNecg#a z64OqHYu}J%mdOw>$=wpIRPSNws!1oxag3vfjj`VLw=R_b6mJcC_Gv5W$5;u%S4R03 zeKq_!c*ro8A@Tnix=(~u1ElvdHHWd66VfK{cDA-rgRMUQz0laK5`g}{Z|J@Z@XXjK z?Y+i_-^+a2LpJwfCPlm&+PAd7sImhyNbT`^_+*q^Gp`iIU?t|m^4zdRwBfDW4Y`N@ zOb^vLpBE`NQ#}4z>oD}(HbF03_fA4v;Zv;53|EqO^=fn&z{};>2%tC%b&L9b7e^*G z*rP<;A=qxBOh$I`Z(w7`1 zgd;DA?5Xy}DB8)F<-D}Sj%RL0WiE6MJzMX*<17Yv|Z`e(Ly^s?#_ z!H3JOOxoweFMpq4hmXIZH0$@f z93<-vSV233Ip{R7pE%;D>Iu`YW$i+_96u>J%*f9cVUTr8atvEbB39)zy$KHzprB0^ zX8^oo@DLPD0GvChlDkVAh6@hs#bml4#EPo&jh_{LcMBaZt`_c`*bHUu>oRp zFX}9izBNSp1RJ5KwjqHu(V3;>2+FOO8^y<2j~H4vjgUhb>v~k&=5m{*hG~o?)B6MH zCW7ZSZ-;x7gxVW+wj0ZyR{TlynfWgmHla#4$~Gnxw84l3(7YZAgeVhaEpMneIW0=h zxB3m+EP3c5C`hKyo3<`Vn0`mmdX5#bQM3*H{@;=jZMhLk{afclMw-KYo~jP%`fNg0 zGaR0E1s$K(yC~p-oI=J8=esvoJI z__3koFO9tJW{&90sVr0VPdHZI*^8UC*y{Ei{>H|m>&)$o)+)bi0g)4GWk%D;0yXkl z6D!|wWSSU7L-e)Emj(sRkt;jd-Byqc(w+h9iULljZd{h{iERz=#d6;3XKq2gvZ9ri ztrqerW9?RqMI94-{hErRWQg>Q`I%gp9DkXywo#)Rx07JH))Uk=0{{Ij;cgKJ7oly3 z+o_6qLG)Sm?7O(W*ESA^?%UNU+tS+IbM8?g>MyfpXxVP3f7EB2z@{eIq4Yq0+oruZ zz32Ri{uCzIfFWW9-t+lM8@@Cc8oiO^C++vVzWovJiaao9=p44MDM8ZEXP#oz&BH@Q zr4@;Qy*FNxuaKyy!il@WskwD~WFAtp5&X>SC_b3I(e2x4e?R$^HdL_+EAgq4*zqDN z7UCu?sgm0+Ht~f~@D2ekj+853Sy03F>96ny=2Pq@5X5=@yl-{8G~n`1Zvhf~ z|0K5=Z&PKd@LK13_jEoeXdRF@r<?6T~w zID(#!yl;|+D4@(d>N7BqCF(V*_@6FdyW|}H7>LbZn&eymHV3VpHbmcktu>kDH{hG8#7wpB7hmTU$dgQA%CPtP19ED|`Z<+O`8{;~ zkij>8T5mxe3X0E#8oo59or;G&&-u0=Bz(&%3tdI-a84_T6~Ll>e-uu9>Ae`(1G#(G zrkrfpg7OZQ&wvC-4>XQ`yU`3WNN4W*ux@crp3>VzN?~^1zH7A&T2uhMXdC$PBgL$$ zJf|Ls84W0(c1>K|t48zm=1l)kjfAv7lobV?%#SsHmvm%}RZAcm0jRSa`(~2LqdBwY0L*U^-mU zIt@C0Uvdy3tCJIh6?hsZ-UTXdFZpEg!x+PJ zU7c}7^GNnSL@pQUIYnm;2Ch`gn2hY(xq_CrYNd=N*eqXGij(iVF~Az+IV3gnL%TMk zN4Mp-E04b91io>%<_tcdNh;zWKtEMhC{brT9%JmTJ~X$J-fGn0RA zQBC$%+iYLdL;m99fH`muzuipRjoskR1ekW3h4lNW#Jw4$Jy3Lvm2Dk1Vf`61_LJZ_ z1BU0SR;(Aa2 z2Rb%Im*i{|4V{7#pNJQ@3lEgFY~;6XgLj#XN7r#;r$ZIBg5|VA<0z?hT6cd(INgnY4Z3P1299Yo*GX-&WEo`KK`C>GP`9UZrn>F}oA6 zD*YnTki+uF#~_G%M$=YuJ~9eS4(c;E7uNTGUkyV$43Cy<{>1)gcJeW6^$|snRcBDm zs0&@Ev?=4Ntn~&-|6WVE-hWu5%FCQ-pkA&u)CnE=FRau_AW@8OS@`I=7w+%%w_8NC zd}L6EYz|Q$uX2@zp5G^Ps#=ZICGjGD;Rp-t97*gnAeuv=4@p-?WADQR674V z>do16$x{ZqZ?>f4CqgUT=p*sA<9B55kNgrrmi{lh38U<}brEkYCobqrA-q;nmB6Ei z2%yBwsdDT+m7%K-tUI&wg^~QBzx_}-u72CIPS*E;$8X&R`Ca9LZyAcYU5L%9)b4_R zr;#3mvFttnfj6!tec6R;4OFqQiN~_So*BA^NuPE{2eb_|T^veY$Kh z?W*>N{;0fp_dnLwo#_ROagb2?xr8JqUvi?WYRRFcwc1xhRyA*dQ z?ry~$3dMrEyA<~pcXumN+}+)wSVEBE#S6jp=KE)ECX<;kkV(k<9NDvb_V{QK&Jscq zngc;DCW$$OtiP}t=vM<9TH+PHQdIbRx>NT7W#_a7jo=s=TV}6VW!qfh=xa0O0U99T zad=SbclGr#4o^F0+hL(!_lX=H$sXy2`T#1MJr={96L&hF9C1y6qz;K5ScRt5H>ci# z7Hoz699n_dH#0h!kRb$i!VWHstl!1wWtJ=(RI74)?!oe?9{@o-Ag9iVXhyq!j&yM(+hJyYf8Bl zC<3~c%rXk0W%SdZI>a38t;v3eJoTinA9hr6=>CooT*)uiZ+$%F&$C?u`>ic(ZqA<2 z)^l%ohY%g*Njo{QE&e20&~#qF;Xl5(U;sE%A!!%I1R|9d7bmZ-8V#CqNQNk`W1j=@ zDkrz6Z8u*8AETTrB9?X&*Y396dB`c>U>FbQ7_N6=4}Vc)u=h%~|9r;MfUNk(f+0Ae zDe-46Jt=I}^#{}MFG9FxnF&(E!Jq~&h;>>TZ}OgjKZ}|I)uQ(}^&ir!e(S9vUs1<) zi^RA)tPD>I8OQd{opF;g)$;Cj>dscLKy$BSdI$}SBNRLp$<^YC)M zPNCOh+B^k}iQ2D1EH53c4^H++73u$eaW3CsH#uJ=HxA5*4@u_*^`5DBIzKRfrlnrh zb_@-g@G6`hR@eDAO+MT~nOLf$xco`gIN^uCN8U@A!lV~MRPWs~ovD5$U1PV-wAAsmetB9QjeU0_@5HJb z?d2P6Q-7sDO2ha!kscfZ+_o~UN+pF=6eXvV9H2x}g@b^!myyUE67}zZ!l+EyzWJvl~Ht#Ck-0#UbuWirSL-+J4 zr}bmB!zn})bwN`N6}+PS?Av#h145q~5>fXJWg#d0`-YLN?OAatkek~Ye`l_%boRL& zxAA*?4DSl6Hs7=~Rm1Xg>--w3AmC^=yMo~kZq;n+)*eoVSIqJ(iRzTN1q~51O}_7! zdaDK#LQA5Pjmn$526gAU*Wo;!-+n?ZbFfnOa^Djy5cT(#Q$>@d6942zWU(t5;c*S1Z5-6rXKD)57qQh-LXzFB=Q2v&uZtwipo|ZeUu%ULQnpqKimGr1t zvdlFC-wF-BKdyo4LyX@=rZ94zJY;=aB42<*13?ez9|R$U&n_m@u%nmiEH)QTNz13Q|$(5|hcx};_N{LW%-z%6Q z&{zyXHG_(=54al!yKNZVhBUh26c3=p@2*&u5uQws4Bm-oPGvs)r_{=_N@0sCZXJQSR z7(O+_z05m!jU_8mEy7vbt=Qe zON}PDGS-LC$BFD1uRBs&)!aQN;oQ3<)8XfJTVW1)?`Em}p`JD_9ov#NdWk`9;epdj z2Lzo)*ey1XjJ@b}X#K@BRl(NcWrGU)UnXAudwF@EM-*mb`6%bhP;N+@7OXi*0g|qIY1lcd=-}&;D=fJPTT!xCtYy zLKx;8;J~z2c=Codz6_0*L`RCC^Dv-K3Gf`QQz7|D=KDSm!=x&MT5nPEVhrp4@cNNI z$h!X~W1M>eLh#ZX3oT`RziJ)yJgt#Y^!9!Eq}^?hch`9SQEE8ywuKCsFk>B+k4L|f zP2EOyLRrzUtzG80)3Y~EE^(p8RB@(NCd@rTC>Ptt0i^h#ff()FK0)}{Qjq_7>`YPj zXkd=L&cmTgC^>>$gAUV$k)P!Rj8~E1@7oW#^%1Hw#GRsNo+&xgGv&2dC7#V{ji}-= zVTpyJyu@SziT$P88W}`iY*H$m`dbbav+HD-v zQd*QYHcb3UAI7X5yY(GT;4K^F)HCP|MyZbCT-&cd*ZF11G5MC&BhlOd>xpBlt-W7q z^YGoWUWlk$cOj|j{=OT$r84x!;IL=%bJH)&dwv%vXKF@6_Jg$VijP0=j$+0|Z$!GQ zFuBrG5i{F!jQ6?zQoB!0)M9w<6MMZ z_Elaj7C)Eksi)0Fi;nh_E~Dl^G`7qide28DqXi6{lq$PH!dzWOtgz`h9jt|5m-8LS=JzTU2J=W(qI_h%Ax*X+`2AppuM6NeWAO>3!o@C@R7D zCx_&toGJHuIVVD{rtl|@)|wpNZpd=+q;mnA7vo4zpk(_Y;~?hHUY$VXFEdNE5$+26 zaX{8tk`1Nd9t{h@se7#3)7ZhdcjV%BYWn|k0TiKwp)ECC;fgkSmv&!S7S$cH1YAo9 zqWgCmujGmpG3o%)y>IydOMgSjli%pk^z3SDf7{&KXjUo{lY?fpAjSp7rE8{608HO6 zJ1T4A>))&ppOZ}UwO%s1mzZ15-H>y(x8-E^6)BNZ#mthP6uzIqeW(WCq?cUDWyU-3 z2xx|#Szs0o3<2|35ly>Fj+o9Yx#AJ|J%bE0A@WpTA`m<1;z2@&ZK`$n0`ADwT*{c>#wVzp% zMNda0rQE9OXs3JWBz-ZhFb-YEE~KBq1Om6}Ell3%JE=|F^|lxGv~ItDGMn_Af5&r@ zwKob5R;P~jNpS4kNgY47+dR@-7@Vp=iCo(fAPC8M7xOw90S4LTN58uD-n+86IrqzS1xe6}UEv5vix+_M z<-MvlU-7FK0WC*=n9L%XJ#Dn2FmLR}`e`885=qLEZa$v8yTb>J1w1;li1tr9Y~pva zAqzW;3guxHOc4vK(G+dC;?Y2utchOXTGz38>yNKoF*xq@T5ngBF{;TF{e8{jwlPol z?JmW?qr;p9GKERApfiT3fv{0tKqC@B@qSN`o0WkCCX^X6khOCm+Gw_Hp36Rm`*~<4 zX7yyD+X#mC85+oY3o?Awz;n}}@togN#4SxaE$gx|poggG-dc$P6qF`n*0xpEzIS)U z2VHd)jhUEU%tI`;)w8WB=-Y4cSIQ3c*UFoDiZ^~|h_G#qU2ZH=)W2VaKQUMIIaQ(H&%;*32|2z>@uO!jPBVxrjs~w1MZv z>XyClZHS_&8Dq7#A?VcI)5^ePS+ zU3Lu`^=xa==&0t2Mqzcny+n{{@?w56@6|jjcC()xbeobI*2*kceovftZB)wwK5{)a z@)+d>g?d#!^fbmXP&n}=@QQO;ZwqIR(A007k3NIPBj2ww$?@n+xL+shAAE%qGwg|c zWs>tm{Nnb-@y46QDC%pR@=B8+_><=hs|mXh2Fz|cf0Z*X%gTHLAbElNb!m=eG6&Py zIh=n2)#Bfi_N^aOZ$X(Omz{J1ITPNIqE!tJ@Kxa3pvivTMs}X)dN;=X#i!egb4Ym~ zmQbe59KE+1{^tc?MU3{ZJKo}zrsChviC=&7=K)Mw0wANAX1cK{{e=kW)kbVgKZ~y6lwUSqyxDmw;oWwSjKG?|#)GoSsMJY|6YLU>H>YzjzK40(NRac+PXrrY6DnR zXLcr5RSnR-8G~ZMx}0{mgl+U*Ua@dT1u(GXlBQz5-b1PzQh~!rFa43tg#^Rp`Z|G_`<=#%_X|CdiNUI-@udDlSXW2(Wm;$Ao zjXc*X#JoX1(bGVCL^GoUzkPb8ds=x(<07C&Zvop_YYp?Z(&nXcN$+bU%DB#Le3a20 zX&2JrJ?qS+>e)|yYE|5};CHhUQPIaYi3ZLJjj3M*xK~4jxUcLOt+#L73-+5&m;7;C z@2kJp8pc3F<-pAjpKqT)#~Sx8CVQpQj15R#N%PL;vzPphZxEAxJf9J}Gc8XB=aD+x z%CT6W`z^9-olgs_X%@nyv<6nAiA=JYtmsL~h64?eUxGLXnrenH!*6Z9Zq>5}zs=j+ ziOvSHefLNY8B7%L_U1P8it&Qrj`{!=R%>WCUOVJ?yc1%<_>NIh-g;tnVKM8LR0l?<(- z318)shyBc{`F8b7G3|%gDcqBp%meWV@*4N{qBx}qlAW3ilCus{M4iq3W7f4tM1oeE zdFwPsj=DzHOL&2!Iz~F((MxO%%1qX^x}w*&WVMy8>d3o7M2|T`!brQZMz}{EBL(s1 zJ}6Kw`h#ZX$lLkINr~RGs=?d0ZuV)OpH7MSHIj3>Wp&fo{-2c27&Ui)7ztvb){SIX zn8W_ohSsTyZ>tgRRMjZj6>@{>RNmY%uQ?&^4Pf|HGrS752Y81wfaXW_PqoVx55;aU8-U07PKR06H_>)y?$8c>>{@yQ1C>Q&%w4Rjk$ z@iQ<6C7fxc;x+E|JD`i3gwI|7;>BIBaPw`PTzU>pkB^~AWUtx`ZTz*~@p24v|3k`Mt#t7`v^)u! zd^Q}MMzbMOIR(&XqWL3n#x>mLCDdr}X0X%*;Vt=L3j~4b#{CE0-`j&891Jwi>f;~m z4Fud6VTi=9jbKs^7$SHdZE0Qie6BiW;$~MR77GGY3+3K^Eq}LxOnD1)+d_Y zLyMiucFxN+vE7k$_QuW9Kp_ZhY_(5N{&cDrvdiwtScLKzp&<=HBE9O{xDn~YcHrrQ z`K{l?2WhDG6ZTbKLY?JnX8u`(Zo68C_kF6{hB||*L^jpa`v^7%eroPTt=k3|Hw%lA zi!xiGsH=U%%|+2vJZB`J{I_rZoza zhS3}iTZHu2V()_Y?~;NM%0A6vkCu{))-v4$Wa?e7GWMhw@okuTEq>VSAc2%;dZhmlkv z%YZ+5Do!i(CM)Aq#bxZ{<72w?k!rwhCVzQ_4K*)74Nq2QOkMoZV;xGd>2wQ$NmU7e zX0-R32KFG@{M;~dLa65leCmqLkw=LlX!CNtjm{~;t$dT_occUe>t zW4w)>;YHKp#Gg1@0LOxF3(oaOSBd2hbjwH@5yvEQ-i9ufJTBiBC{hEG8g3Ui7U7X! znjxE0l=2>+65qDk^Ciinc=c)9rgHA0Q_1wK0}AWRY48?q%awgne^MX@RZr;H`vWSb zo4v)#?m+>vEXfcE9ac`6&52bs#K<c5`?*ylZ7CGCl1k@ut+CT zr#O%#+oq{_k#hRdXdhcp{9C;?E%`@}v(2FJPJqa6V-%&A-G$?DHbcPl!51by{0doO zP`&M3>yCE(I&6hagx$#`4#|vq1NqjAy~83G%$u_TJxD2Bj2y `ovey@N9SnLcA$ zeDv^6XPe!3$V(gT_tLP-14s{?yEINBU&G+HL6iGuh~M3`#JufMCf8V8ZqT3sPfZ<- zh%MEZZ>J;DODA66Qu;-w$n=tbmC)h%H(CHv^bkMnoT2}2;7@{MkPpDTGy>meqVn^ZpbzI!^~ z+!==M!+x^K`7Ff#7L@aW$V7U6rc+cz6->`@EHbyW{lWm#F0Afe3*l{2ky4QN&_G-Z zJRow^_hM6}`Qb{|6kh7oZlBiTycJjT)$+Mo&;7b_@k3a4^@iI z$A68}K3AbJY%`8-9bL{6#ZtWef>8{1-Bi3}VbodRCF$ow6OS_ghKDYWqLUE_tt$WhIH7sElCIU5886-CXV| zn!*vIA%?#}oX3vPB2#LYCR0J5Vv6cZD&yS}6Nn|JH zYLFI~-el?5CSBot7c&NCZkGb2w;eQO8QOBs*e;kK^cXhq5U$^hRLE%HO*af`we8J&%yBIaZ<;QieloO^rsGwWY#cj$U9X-B)`ZM1M(B@}=prV%wT8dh#lH zsc_Hx#ObDqSw-SZ`m1R zW(E$=WKFpnTE`0oMG^9;jcle>j(OyYnk56I)_R+LYR+mJF#XO#O2Z*-V6hP-Cas zGR2pQwY2axv1Z|we&SvmN9#b8{tF4&o=|-Z~u(>1E2amUfVC|R{+ZK~_;$0>7kztk*>z8E%#=?H2oC&kQG2C$8Tx4JKIN}XWyyF`C5J!B zo$BD@WVJMYxp=;LPf=d%x7=HnL|U!GZyw~+lBqY5$VW-?^(w{)^N_ZS)jM(^eeF8S z#>g>nng-&+Ji<@f`05*IblDtr-@)3w|GCZBn_jV7@|xx1Z6!6}ZO6a2KM^MVt#hsC zLG*ZARNB!d?OS|oUTst>@-9(l*{UUPFgW(mm4zy(Px%B+*3kyvKQY9j;{Daz-g74U zwPYa%lvlJ#b321kiosK#I0axou|A9f`4arnWHLeQJo`6IQ~<4*Isqz zx*l7E(LiQyN;YOpHfDscOZ;Qsm-nYjqk5W^g24iYs1;eh9p4RlYq@#i#_W@YyYa?I z&5gg;DIfX-JU66CEcPfof)>u&_YF&nNHRGrl3Ta4g+j_s{$=@U|M19wV#4k;iw2BYPP+wsr(s+<=!$eNMfb@_;v zj-hEWQ++rv1t)!&S0bdo#bI~@ia>0AsEwoW>dOuF`cl7Ki^`0dm&9KFJM3xyg>j&$ zcvU)AhygQBH)DpX5i5?!t-DaAEty8Z1ra$+R6hS=e}d{67?WuOyyw_;N-=^-3fbo4 zLX&*N)<(Br(2^{$$}AYqV1a&A5u7`3(-4_U2bK2wtK04BaaF@2mXwc@Zo{Shf1bwg z!WcW$JUe+=>(&C_9k?|Rynj%&(JLvxdNY0SmxLmNKMxMh>1?v~n$_!FK1!UV2+q@! z@Hb-SjLdr}vbr_4Bkw;diLiDj1%O6=@rF}I6kQTf4FJNh0{;%Tv|SYZ!?okwLc=!2 zhr&cR#yVKv(!M+l5%ocjztPyAKccdNHr*R<+0?ntWtbB*Hz?4q zIiGq|(g#)O`P1lnCOG~KhgfW7rT;fJ&Z@m^>(&%h7ih zhq*5N34L4G*DCso{0xBCeU+=}F66vxt#T?N3pI~Sgi z9%=H3IBQ*=g8|e_m+geCsp&P0AG-nfd_8YxhdVkSyN!QdfpaH}zloawAMvX(`)7&| zbeHVde<(qhimv?(I?uOxjyU~~CPN0Dr34f!YYF~1$Z<5@oO)h$LHzt;VnwR=Q8-F6 z_w3?I0c7)i_20t33fOP|Mr@*HrcUEP;-=Vbb9%!W>wIK!tIZG7c(pN`^CNB&sgiu( zbcVrkx{8kiX*~!vF-P6y#c_B z%Ey!lzEV6x9qj9U=ESt(!nAq~gdQ@>iRN&Ra-$YzEB1K5ermcT5UV}i3cCuf#uZl$7I)sE(!Zte#V>9iqA~&s%wW-@OA2fj*Z zz78Q|BTuD+iGw7^!Lv8d4Y1I(K?XUTt!VXX=MW|#J<_3a2=APOu@Qli%fdSonK@Ud zI#??cU|`35l=v3$^@s|6TiW{#Zmi!4bPd0z%@Y0DjFi+g{-_fPl@zJtPDn)(a7Ra$ z$j0b90O^Dr%@hAxG1E%-4Bf7cV`O#|zqdi)L^uLOy7X+)^p5`0MR?87WyGs#%rGQo z0T~gh+R&l*>$0H>9Nr#{L`aO}YGuj!IUd||guJX};@$PwM5tR*XK_AthjdF4==|FBt+gM-Gc?hAF@0 zTm&95Hgdnsl|6SxtN-m&hy*O(d+xPAP%G^C+aJyfTZSN9OiJuK22b^DHJx|}Q z&YF37BYo(9CNTjO(0lVvNd#W7Z27*|Sb{4oKY#&2;iUa|`ah$rN=AsffaCCp*c^a) zzGAi>TeR;BpEst=>PUe@3NBF_Dz>H&_87!8aG-7|xj}8{$1jFIctoE!#8QhPi+TPR!U;apL}W6KejQXl?$!^Sn=PI-ji7D>l*6T2k9tUSD5fLHJYy%$zP;FOqDeFd?h6iW?*2ICIW% zXJ!%202V80Q_I-#CLfn~gt-PuV0VZAIER9E2b9}xqj&GbP5Mqj&mjlw#-6Jy3B(&_ zKROG@R*)?K7z3xq0_0L#2uwY@0%%ueaxzRH$CMH!`KF)nm9NKrAM_B`j6}ovM1o}7 zZm~VQ&zbF?VW8S-sWijcH|6?2t^V)fa>biQ_8gN-UVM)G$^kiy`q-0Nn1&N9X|TF= zIuTE1%Fx9w8Aj7N1-0v5?L>ko$sk{Y1jDJmxsQI7el3=-B+i5oShU4m(+-g0seZN9 zc}k4FSCx#>C$9c<)~cMZnF`DFDKBBjvHiw1>tBhK-Gdk4B_AdkW3-#iE5d=t|1zD} z4Bu<(_q36ltPoGWD4x>h!YbU7nJSJ;^|@^mHT+UV7l;M!G@LiTW8Bxl+qW`=ZAv62 zC$h?5dPB~nO)QSgMw92%;?7t${&6VQy=Ojm?wC+mkA?P%n!d7CU%qnzGEHQ}-EoQG z-3MGAff9Y6&HJYDtjvPrG?q;+cw7@u_&FRRaTrF*dnkBKHW3;6Jm%MZg~SdQc8$Ja z6c8itVJ9`)z$s@MOZq=o4|a%4hAa`+tMKbESI(hX^j%!ALo-RBe9>nx(TqRhxBAll z{%sdsIF%8-QAb$~a#%Qg8%xAbpmxGYff-bnWFxoHuTq5PB4p5F4ZR?JDa44nfdyVI zvLfbun(7DsUDCiW{@1hFF*Ag4Q(ZrByk)~R17T?@$z2hZH_eI7BL7EJyZ<=w=OBu4 zn~sT3kx+)?tCsqg5fgVaVR2s(iq+!XX#8ouMneUotVKdA@ZiVak0w6DlDrcNXtQEpbWOjPKqPX4pNSGyg&!t zN5hmX;P{vxg+Rvw)*PXf=&t#}*fL;tUI_b9n_caTpdIzX!L8Dxl4gJ8fhWo+acT!y%$4w5O zJxWN1QG}hCTF-`T2D4>$Npng5{vTUXBdGuM%zkM{G(hf|#5ln*0BGg0+YIB_#gag# zVY*o@7Re%60(4#5ta(2ZtJ!|wBc!7oqreuF4*Qm_ybE}jY+5TTUn?W;czb|27Ih){@R5RBZipOd~6_#i_)f9+uWMbZ9Qsm>p{$s;oJKKy4 zpiy!~T`ij1M~;{VSD7=uB;`m1_}!6a0uss7hO z5^JcSKHtZCMg6fiZ3%x;5gGJtZZw;rp(4L4IA_B$rP8z2VnNgu6FCbD9d`4HB9WX0 z;Tr@wsszdleBt4{>x9m^f3|ru{0Bc<^bhqzsl4rd?*@FN0qqrXMOhfwDz3|H*N_>w z^fU0b9g23#r6GP(=Dg1CpLi;#h`>lkc?Fv==vd#9N!>3e)4_njb;>g#Qzm(UJ~k8& zcVya-Kf}gV4!%vmm$2T|47o-;)w8gol1*1njNv-z)0Z?j!N9PV>ucM{Sl+a`uoJ#U zoDm!QgOhb>A^tWS*K)gbyOTWh!e3K`k5kk#t+Xey`L5326XBHv1kN4rQ-`Q$BK12%(+qj?F#oP6{- zUd^%$a&TKnfoNu6ObfEQM*mpiX&1-O7&cZGsAo@&*m0HnIJ5O@-o_G@)!z6f3hJ(6 z|1{qY3Mx>Nz~36&*Qm7KT=mK#$Vn!cgwlr%6-2;AcBB`%kQEh05!_vri0bEaJ#(cQ zCP2>v6MQskCQvfXWyE|xr_Sp1Wcu5qJou%LKE&1A%pmc}9@I)J#EacA1i}f&DD3?aUN17^3wo1UM}!G zA<07x^|#5J>36!Bw)M2+>aR*4Fc8a^os{EUM154q(v00r9Y9`3>&gqTM9isTw^?58 zK%{*}-SIqHew}JiZU%kdq-{vRzc;a}zqqtviA%xc-D|x1h0dg>+n3e4LpDp)YM0Pq zNW=`XLbM0*2#(eN`h|Kp1P3oT>o!fAkH*4ek3}hN$a|M7;1ZNv($?S<0&{7NPZkt* zc`Xz7bp~<7F{ByV(0JOV{rdIEz@QC5g7A_G%6~^o)rdTR-Re8Cg7Pp2(a>GsK-}Ri zIAdJ!t2euoF^&qU0EEx{8+^+|Vjy4GjY{A}`8pX$3Mz&&M5(C& zcBbjMP;uoInqdxy-LUwlC^2%`IbGiVdJO%a4MA2-ZPY*hYxa*%rwcfdXCuz45xrZf zdO1|?BBXi-N8QxL%(SRVc9vHM>um-QbJF4|eeA^7b!0M#=2ik^)HNo9^3g;xcoQgn z_^yOe>`t^%Y79J-zT9gk1#T(BRZv-ffV-=8cxG^T-< zArMBfS=<>;aCXWxA9HR1+0GfYi20v5VvX*HN=?sX z+x%8^Zb$wrMke(c(Kpjzg?lgS4nscosG~&8e}8TTXy@w9r7!gF?p60j_tv<21DMk# zd7oJ+^P96j6}iLLJge+0oeMS}{?%Fa;gyzPJr0ufh&FO9djFWvzdQsfTpKyFwAU9P zl;=~rPDYlKCv2?E3h=s&E7einChWi$I(^fJUhmF%o`I)6{Ch!iM*}hE^s5qGBwsnW zghgVI*Jq#-Gct=(R&T*5a?G8=1l(SPFN9Ptd%Vss%}gMLx4cMV^7Du#iLsV1S*zhs z#CP5iy&udj={`Cje%@#fM)Q8>6~B2k!OdPB9zPp^!yBEZ{W{RW=fh`k^QNW54A*P_1FdxyWHzF z2vKyi4*-@PmwlVM!(hQAl2E@9%Xod6xpKdjFRc7xF=B`3E)KvE5)BQZuHc&By!^AG zg+gknp7~K@x+JDCbqSEK)R`^52#3P0RYP^_fm_q`$O*TZ+SMJ@`D)&x5Fh9S2P%o; z@PNX2iWJ<6q7}6@#InFEUHuG>{A0&boV)W&8_E+w@uNvP2$$ml#Yznr>AUI zcGj&qBOIP?38*REDrA6x&ZLf!l~bRSr&yDdl#XS3IehTlS&>AF6ub66+^2OVs-R{1 zWRK_-*~SW#FZm>vg*0tczv_=wML8^jOKbF>UiK30bkRO$*ot&47tfTTu6@fCk>Vr0 zygo5K%x!jUw$9cYq}B<(OCRpJO|wgo^VQU2XQd;hDd1`cdYl42lEi0#=W z_8o=Fshi5_)vowBwB7KBK8H~`eeROLxqiZQ^JB)!mDJ{2BoX3ue9QCg&Urq91(3v%g~aeMOX_@)e2yTC;CN;@{D^1dZD>h3apw(#XOOlA{d?(&w=4 zjzVbP@Ba;B?igL->x?j0@4vrZw+UvErgr$ybM_0NbUxeUcz(se9lNd3?#;V?>+~6s zZzr|MCVQ$&p0V%D-i<)jd&Ej(qK zGZo9i0IPJLo4cx8(_P%bd%dRrR_+fSKrdn+nRB>$gWVK~JQz~Qo5#}{?`H4(-7+)! zOpEu9xgYDr4_o47$dIbKKa-8f`JR1(c1t7y*b5pItjd^Qi}Ebu#26p$e#B29Q+vO&sT36jiQ(0wshs zuKJpHb{0p3klu)pAt*r^@|*wnk0GevAjUK}YI#3edtcFquyAP-g>3$$qf^SIeNJCx zWG1ysSo*Ar={Vf1N$knsvt-*iRp3CggYiL15VMLF0P`^}jQ&sB#725As(%iZ(P_Fb zXFWlCh1sdd9kB&l665rnhnmz)dBqP#$31N{8fjk%jy44+aD9OPK8%h0^S!b5Z>XT8 zq`zMx%McnNcndQJh6D$`F?Hq{F7d&z8Ve|$bY3xVlS*KPxZc4od?`n%tBtSLbSH6W z6XMNmHA_U^#?_fjXX?b|c{GYxGVrWh*7y#-2u^x+=ZjX#l=pdyx^d0&8jf|te)*#u zJWKSpww=o40d2^4zblu~B+9s@`-hOIp#`do&d#+JEcU4x|Jg@SvLE7j8BxcX!xV4e zAEy8;d|RPDjG_(rEDAqhWlyPl>$o?-ves~$O+S;bh0^P4aZmI(Wc99Oi~RRT=O$w@ z<(oaEhRe&HambEYKhZpwM~WE`vY5QGeb<>gUbQ0{3_Brz2sb>@vpa0| z?S=B~qmxlj(kq5?4}}*AbWJuA(Q=7c`1C^DUy8f)n%#-wlga0iuQ6vu0&{{njEe_- z)aE*OpKvj9^4NgX(@M~Z@8>oo^Ki{3cr|vLra+;92Mx|uDA9oTpU!%70{MpoN~DCZ z%ZP!)Fqbm;_{}y-W^cxy{}-WU2D>_--&@0sKN0OjN#JP%G!(u2qPQM%7NjA#eu7W9 z&+wO@pd#f~(EWbQBruUdYKiedgiawd9@kBEzvZ@3Ae%4;QT3}3bTTnZ?xawxuxuN< z*SHUz1S^-ULnVKGn{JkV1?31rxZ{R@$J$Ahm%E?@l)Rp{XD@qrwZagyzr@^8Gt;RQ z=&7@$f?}omEwk37jVkzHz+oP?AS1kYyH9*CqN;~`4Y)nav7d|jlo#w^d+lvd-~}ea z%g(6ypM<##Jj6TqHR5x_P6|Kq>WRTZnd1b#&ale&G`xAB$&$r4-Cg9aQ&r?ie}32VR$ zgK_sIku1l79k;h>*se|jQwCqb^kTx^S!VU)iIE#kv1oEYfhSX3N;PzHw=mw|)3_EC zso+~M!b?Q*WrBNDRpN!DvwT}#P=u@LM@#}o9yu|&eq4fDoFn7(&s}vqb^=@R3ztV! z>LR}fIsxrhY!B#8yHy?YeyVS`m2|If>M6C^;~7HzIG4z>s1;dhJsmFfl|eU{Ezm5bPWxEsaZeQ&rwbaVgewe{ZJe&Xr= zMKOo<2SWtCELA>?(K3QQ83t8}CTA>c5vlO~qt2X``crV=U zTzKFizU{Kt+rPih2KZZ9Wwi%Rk;I@0i1B%UfaNdfCnnxKybQ`*VS{j$oH6}Fry(=F zY0FXM*gn_UaDTCeW3xMVC_}x=`80gYmJieuRI3=u{i)!hxFEbdas6E_&sbIK)pQU; z6|3d9URI^OFND?bTh93KH#2HMs=qeu;536|^~!o`k58-;Q#(IOGR`%Wx3(p(uKym4 z*ZGK6!kYEcGFXX1jAyQ~l6{VHFRm*ChhJpQFF5%;o-k7ahNROI1Y zsXyA3lX8kDy`w)nubG>9%E~jUiXho-t}7g-ki`v5@u3x=I=jWCu4Y%EnDAf%?mcDy z)zEbtVaq+*RC^DjZcg^j3+Q;xUSK(AewzFM*0ibfkyU5BEEJ19!yjxWC#QebelmW3 z^{;IGpq{aInK!=2Q}Vu9A^Sd#wXN1kkjxLSf-_E+D9DVMYb{Uh6g)?({)%3&gdlQAu_#A z!I902-0=41vedczMdprV&dx8?S{~xa^!Fr+tKTlEYf;mgtPg7WJcCL&duh73fvFZ- zZ?)(WH0l8Uq2Ksy*Tr8jcGc)KQ~go;=A2hk@7J%thHmsQXgY7wk?ty``Pzea!kT$2 zYN!W+DRTtV$%C~7m$DbD=;7l6uyTTIAc=#9Hz*aNkwwr$;C=HG|NADJ)hXj)LZll~ zz3p_PJX^*0vFpUHOml zk9YPt1bP6*0L(Llsq<+0muQ&i=rTh!$5@Av>o0AD(*UW!SNy}7YzMC_6d+l1hQ;@9 zqQ}CUATZ*AzxN1od%(s&if;Sk;{6d~m1lV167=jIb z&KWvhDkH`1@W7wrRRs@u4^<${g?x|v!=l)ry34L1$iq8mt;nghtFqQ$^CA+_9pTG| z`f@}MQiBMD^c$xHDkUZ4_0G9{yu4vjU-$UEKWJ2=Ady4W%caTnq0G`hD)maIREi2gS0nL=rcrm!6DeXWso;*)NVzm42bY}Dro?$=@re9UZXA*g zw2*5Zd~qTUjux>J??2n3kI0skp@0uzT+!-Pt_)42V-i0|l~%33d$39zg>M|al6>7N z52)ag9z3j%+bv~WIiBl5(Wf373mR^chgcQc5cv>fiXYE@TMvdI|QIo$J z_)<7`fg>20Q%)aFMGa<~xWM(iNu2*x?}xx$pYQ_*^9MXAKWtUEqW>z-@-qnbqC$ZqpaD3}>GEdbRi`-`-yEKw3sTolM|*<T!uT)b}#rU1acPvJO>B z$$rfDk|z5TSZnMj%7rk|W_Yj#BDSx;V?ZVQw;cGGk*~-5Hku=@a`wk`C=XzZgCz0b z46(&R(E^566Ap*U#S75km6Sre{JI7`tHfaXJcXt`%_ulRke$~ttCS&RgvNL7aKcYx zRgiH^iYhRosVDWuel0~us(O{Z?b@xGt|4QC3Uz~u64OLZQeUew$%IY?nHf2`&8YYm ziN?37!{N1&7d_^}{U2EWG+G?C<*8HLTQ_4sWCg2RN}lW7HVoq?3kH%c{(il6vfC@ z2ZuRdd=3gv{R%lQ3-Y+@o`7z(!? zH5(oh!FD)c*_pAe_+4zhdb4Ios1YjD&r_TvJib0LaB*;$2wM?M28eLul4B7}O1iba z;jeK*mScx?!9a(M1=lDS+}MWGV=Cz=6U#p^7h`_d=PWQL3%H;79MhNYnLY-->JIGW0!?$n%n0qy?gOhVAK}4jMg(il@Ud*B6xZn>KO<9 zZV#0WNshaC!RwB{Jb*mz`pl#K%fA7OM5s~JdVu#Rv3@eolSa9>{5%|#C*~NqlObV5 z_{+HWmntP6KRfGUB%<(;>N}ZMTC>jmTXwxSgykjVma?)7#>)G&yrc5Ic&KlO4^ zd|x{~B0_UZ({faPnchYETd`Wj2Dt4HiX8`g9MO787sg)*9Puk2$8O?!MBLbqe5j}5LsC|p4%eG@e}vR2$31*BL#fawExqJ;IF3vZV`YHl1?h96ClcOUd`uM)SOGMm0RV9Ck zgOx8vuUbmpQiyQ1i#ZBMdmk55Bm~i3d2(Z_Zp)T^1#n2 z0bJs33Q2Nc7ZTpT1~4GTE@r$uprrv78J6!fdG2cVAn_ty!m5e12EDM`RAC?u^wsn) ziUNVHgTG2rqf^e8xAt9|D1lZ_R9{!9P}pO^H5YM5r-ObP$O{odb?uSY9!jni+h+A$ z@9yU7RvG^0M8~mPqjNJ~(mXlm11lXci8m6_F04_pG%{N>zXuw7uiJ1$8r!$1Z=pbG zLBkOfm2!-$v|qwTs9n4y_0RsR`mkz)Q;f7s`$j2q1aVyzlmz*O91B0vLM=p6`F+{R za~fKWJ=(-@-&w1D#dPYuqDV!+H(_c^+#J=O%^#oG4$O9Gq}tFt7(p+T4pX5Gz0^7* zbpil#X|FC^tg_`?;>DIdrJ6To1>Mtq!>RTKgK7b`5$<0V>VXRSYKVJUrnI-MUW#*- z7eo5Pc#6x!njG~T6u3R=tW9Wb>z;8Q!Yes@`{`0i_7)Mw|49*?&t~Y zvR#on#hLkkUH~x^H0lA~xwWn1ZW6Fj5a>`U@Ik$DeyNIZwistpjKM0}1)MEE#)3?AxEvI%c*$gj-HicL4b3c9@kHRo~Urr${!F!$35T|@s` zU6trup;ZCn_XxN`1sgo9I&WR~N8NlCXO`=vKck1a2J?R(!$1|ODZ(bwQl&$-M$Y>| z0{WuE;9?)QlIvFk->RML$gw-hwH{~A@BI}OO1V1%7w>Nb+)QOe08-}&;tUtVfeQ)G zUv1nle;Cge;>YoeXt-J1oH~glClw-Bf_)2*D6vZ%i8lCDA-JY#?tJ>}D1|qZ3&}S6pjTax$+(->QY50n z_vvL`f>_J#y3|9Km(Xjrsy2fP<@lvuQsUR24*tIDy;N_;G!251kA9}@XcrQ~$dUpS z1cHKP@YWio`3uSK-HgugTsCw?Jl8RT+b>W$Pj^txvb)RUCCK3tsR5YSza*YLU9kh< z62BbkkIwyuuPT4jG+kfM+%#`GW}13|^1BNmeUv{b^#eOnf_I$_U{&rjjWT`x=R9B4 zR-Y`d$StnOp(qjyBsfCn0jJc%p4(*hdOcZjIuy_DO`pE&}k{+uCF;p_Veh@zu}beA{9r-e_`h+5{mCU6^Tv`HZjy9Y=i6MuQEGF^ zS-q^!a~qNVS(nnRBGIzL`z0}Qo~fbBUWX`(wPb1mwQM}`D3gAFI*N792=M~YwW##N zLek)mxksgjol5k3+5H1@-ix(5V=NF-UM6q9h@#OCF*Pqs<*8kO0T`9q720e+H0TGp zSGQzdms<6i360E?Rc`23RVw6d(=a)*^xabgrhqlVOPB6jPb2E3Dfdy zHVKZq!6AkqUC+b z-qGXBWN>3>Z~}BE1#I_($+lt+{cAy?%v@#6Ogo|(E4cDG+vpu?*Qg@(J3 zse7_&)XR7H^CWh10Be0b2d~T z;*hyIY34u?$d-rN3Jvb@HYaEYij19%vpO7%$o4$9U&@(fe12gwhEhbUSBy`M5u1Wy zT{}Cz>?&!0H&(#HK*{q_y2|-*_J>R_NaPFEYG@nSahMxaOk-$aJCiS*xh0C|0q$WficUc$E*%sCk{OXl0& z-OBWt>v#vkWJ$SkHqJ6o^@1zy0rVZ>65c$B|B&3zKHakg4xgnPz1>o8VOb~~tWAaE zlw-RgmTW^NeueR*a#L7BK?)ctmlY9T4yd? zw-v7#8P;+aWu5EzK=YPe^77!wxc2K-m_^!qS$g~Kh4C`9kLuhJdXmDIXU&cfOF|gk z=EyIuL=>;v%8aaW9jmxrq9TIFD3M06Rl{pKw!yU9O9Ci0eyZ&APkd3{QM~jjq^ZV% zQ+LQ+GppCZ7!5FUUFU^3N!l|n>ao1U;9IfEkUe2lFVWcx>X6m2tsNfH0ahk`wWaF_ z*;y{-^{ET8ejd4>GN}VyA$qh!9p*7b@;C`d1K7dB3fX=?rDir<#tu3>q?=v;I!*Rh zB^7Y9O;{ZsTy@gT2*oq3|Ff14*|ajDKf@M4Uu$#nL=M@UKk(jE$HRGwBSQ=B)y26W zu$bZ5eawSaf)e2VCWi#}LuxURe%hG@O2>ISem%uFzcW?a$8-w4sRfc{c?y z%DPY$^81?1KfeY-_vJ9a*TnX~4PuGWx+pJbu*SI!-S?+^1`=L=ffucF^y0LB*q%O7 zpV?1_$9NFgHU{|-zuJ7QIP>z}G-0<;+i!NR zO-`(9x@6~SuxRz*^U_p&8&nf;o9b2wk zIFeoRFOp6d&PXvEY2pn_x$*oc)bMEKA5ZM?wN>_G;0I%N0vRJNe|hFbipk#OryG?f zb6EVkfogEnK!iy%nS25PVNL#&i6B-Or|AGOrtM0pix1DPMliS40D0sB+*Z~&HvZzo z0F*ueLmPK)zCTFPT-wYWROHYgA;Mqar7rMw(~1jFnZyia+afr~UxV+FUzbbzi=>MP zLuznZ^|P_YIO8EdKX_@T=%x%}lR!LiF1@AJ=RpFv^Y%D&duJ9N2@AFD)@%s`Z)1@zNeogbOjomB*!+qt!btz{l;m2Mxtnjm5SiXK`M zF14gR=D@LQw4eL&WOI~uEYb^WBo%f_i+eN?H=X{gOD)Asc`rb})^JS6+!NnW6c zaBz)-0huk^njeLgaCW~N6;ioe1E=X13jUDw8kc*UkX5z!73hTq7inInTCNb=ji{z! zZ~Z~FVD(bhJ(5q<$Ov@GH6!+_VS~W1c(@A1{V@*tW*WaIiSa!6vOk{<`T=4XJ{b&{|fMhZ7$|Zo7sKz+BO(OTg}% zmn|5w%+F+VFN2y`0T^K?d8f7*iz?w)Mw76YM*WH3iH&@28!n&)>~cSsMiL&ElAym+|$Aeq)~Iqh1@b-AVa zVIK0e<=uHEAWL}E=`dE)*qjI9kGU!@lEz?zs7gb{rNnEPd;3lk12yWc#A%20SJ&x? z)LHY@5eA*^T&cODu)5@Nr^JKTcPo7vu^ z3z@?2=Ii#~@<1r+p_ggr+bMpC6Wz$kj=3&M{CJxx`v>Vg*ilmVwou>fK2CHJfDL1B zdyShOsGhKfCk!J%R`p}AE^+4pe+fJZ}zT6VoL^`DA?B8;t zVYF&Y_@?V~1OUU&b4Sdu6raANpCESKp6yt$>Q>ERFGz#HR9$Bwn8%bxJ1k{SewYy| z?n<%t1*wrKm6qvaT-4gqG6t_zi?C+W-$`Qa^E#kverYS6h=aci;+De2Kz$XH`_1ke ziNB>GCGY{MGmh$Hh-d3tcrOEr?FRFer+nAnpDv<*SCKbZV~XtkTsY4N;PgK@DekiJ zesS|r-}5NU_d7B%d)J8_=JJjtH8C*>A{TDyb!sz@9sa6!xpFjgEseG6O5KuT&zIQ_ zjolMB<|G})PU!eT6a5WJL&eA8FC>TZ*I#gZ#5^cfnN`v|6FTXsm0cn|J52`P0XZPn zg+NQp$fa;~TUTQ*W7-|kzFglSG;H@(1HF$apW1=nG;XjN=E!22QXsOTC4Uf+@`-vX z=!Rf=|14p9kY4BhQRZpFHS=oF*yEyk>U-ew_fwQ7-B97l<@V*`uG6IV^Rb=#iI>i0 z!Y}lMn0%xAu6vuC0;I-_?h6Ur8vSxFbH_Qo#@}YwQFddMyxHPg+G*F0PHdD^ZpDbm zef{w|yr3445Ti^D8ceKooe*1S2DFp=`|Tk@{y9@KWV>YIb{aD1QUC6{z&mCLqn!@o zIxHEj)!RCir2E`K^Nfn%yHc?1=#pUikEbbXF?V-h*e*FaxybWzX^SLFBtD=N{y#=r zOQ(S>0$+h&7<5+D*%|x%{4xAD89mEy{TE->nM;0v$92vC7bVvaR-dd*#q=n{n8M9D z#G6PZ662wk%jI!$>$I8`;nt2K{UC4V%rhjB?#m?*G>!al5i~%`k+5{D1JkOY1|Oz5 zAYh3IuUup0?av_I>N?ZGjjz-kDj>|eMIpsUe_R=#e2(38VF$-?1QWtGe!ZH%0g_HQ zqYxi8sXkl%c!6Y5k!224+RL?`P<&1ss#xZyrxlXt?SmBoO#r~L9#uA}>ryi#HyqpX zj5@P2BQFazns~z%($0$qDbp;~cS;Vy>jXlq0V$b)=EZHihvo%_>ycMOyxN?Q{7>0= z(S{=h)MSB&3-j7!zk(?Itbur11geELL`3Re2gDfM$wb z64}%8B`lVyLp!lnC$QU^8u89qq@F!BHl&5E35?Ribiqc6*Ha1>h15&+-E~et*vBuk z9$`Xmbz2;~!^@S}2~S47L}n)WjRq(A4MVTRV#a;}AFVka(;O0N!T-Wi+Y8Z3^JJyz z%+MJHk?048qFn?r5jo_Lzp=GopRQ26IZCb^GDEPz-H1`t1FU4rw^TXaSy&@a+Pro6 z-j|?q3(N$L_4_ZvN`s+1n&|W5aS8QATR{VbG|1(0LUs1DCdT8-Q+JsoTzwkniABL!w2)(n3vX9Ff4PpsffOuD*)E z->Re$O`#Gjg>O~ay|r&h#$C=em0bH42vcFaKmC;+(ed)}>`8GWj059Y5y`Sb8TTHw z!5uCS{hKNWi~xF0oeI_vow!Aj>@aWKm!JJzk)nqid}-f@uSXaQ&@`qjb`u=Om}1Lr zpXvp(S)B>;?U>xBCi)b+w6}y&3Q^aE8Sur9@|&^?$V}s@vS`#Ugw?jVzW0(4i-d4j zBik$a{-ApT>Q-WXu0Se%R@r#lESSXszRS(Ie}pB2;Zavl*Y+Mb#~LuiB04$*elmO4 zOw6AO!1?M0T-cs6RDOCpvgm_XGx^kcdoWk+$w5kgC@oAcolO}ykg9&&w>{a>l1xGe zqh0)PxfqVRT8*(}3>9V;vP1=^`6K+jTz|vb<+hwm^OX38Ze36JXe#%%Qh$6f0J5$$ z#A-jbyn>DTLIlhBu-34D$OWmm%9jMOay{D4J&3|%_sFuj!=5`9CX$S)SGsk~O^vQ- zRG59CzSnT!4=u4?B2K7gF#pw^8KJm*uRp=E;F>8Zdj=kzE%||!Q_Syh==3sH0cvC<-UnC$+hG7 zQX{OsJFWRxD;KgnGDwO@4&VrLzDAD7UM07{&GyIx!DgKVzP*2sV#o?w-Q7 zx38_#E}j@KVbVOIS;qtO>p(=7E|ogO`Z;92*BXyDjNt#?Qu+ z3kn#c8Yf8Vn;9L)x!x-Xi$ir^&5TO42?cKW(hEKiLdkxI zI75DZ$^ABp$ z12n#=Tx@a(hJ_0vO(#LVo?aWlIZtW6)pv;cH^3~GJxl%OTk0zuGBY(A#!JBkKg@T} zfvWCeayG)WCJkE}Rd*Ql%D2fDzFa0dtCV!IU`1ms`u&LB1%W4f*$qyeZoHh}g^F^o zCAY?xgURn?jyXJcFX_!49wO^~!xBra*)!jCBr$^Nw@lK+^EF^q30L8fCSteSKW( zX0`s3TTxPgca#a(5Gn|%RbxY@LiuwTJE?2479P31$2jO6PtIcIhn41?(uP4Gt^vj>`vI<&9geEMrl~)}j4L z%3GVZ;dI>coxbDp(sTnpSG%>U>2c$}X-!|D|N z9nH36TM^rWRFb;JRfoNr>V?2G&l)r}ZMJF*Sh7+42`7uK%_uno*{^Ng9gMH90s|Bi z+=Z?3|99`~Oa@})GfLb4xzrgnEm=AVru;KcshbI7o5Ub#t>&*ZArUAQoG*x4M1VIyi-^9D3kJB=@0b&vSvAJdWF4AV%Gd%n7dKi(T?%SjWgq5S zsRsy0AJE9UgwlB~dqa* z+9i|zudYO@0gtgAWyvU~pCLcvbufMhD+{W&1lTfF7b zc~Ugkp|FVb&SQZ)J4V+_ji*PKDfN3XLlLHW^a+*ez^`K7*GoqE=PKS7f=6y2jeN3 zEz&3&0*I`d70AzYf63_&T$##E;l8f(PK7I~V+3X%yxU6c##&3PFjq6$*PqF}xfcm{ z;7YCS`OJfUvdXOAn5(PkV0;kz6LwAZosuTBuFe1<@UyUz@22*1Z*7}MW;;fZGImcG8U=kdj(~((OblndvHFLd2=)>-zGNMg04+rcO`Ot6x7kR+h&wHF@l2M{^+L z$CsIIsn*(ZVZUECf&21&W-LVboh17S@TuwqisB&HT25ZPDGamwVj=mD7!Y7rSY&XA z{YSbu5vo;v1vV*91=xrG+mt$Sn;TO-htS>Ww*Lh*zqd063+jwC@GKvs0crf!Zk`+0 zBEpU1PuOo*ml2+=tPpBh8R~}y?r_~D#2FUc0)gYimf8g`b-aLzFecga-;e0HlDbqY zACb?_8+7iYB{)A;wy`w<$H&Gm;_SP|WU!?7%=c5b><8E++3ipyVU$VBDlAfu{6wc|ZZ>P;whtjopFs`p;F;6`cN1)8o zE_^_)iN4jwlA<{jkVrM^L<16>T(1>E43he!r{sR~_0`!h5{bVk9~XO{{(maP#4gKJ3Q#v<8T zAW*EMKEqAG!3^(j_oFp+ZUnprIGguR^<+zMu5vygGsr_Oz1*xK))Ml(2l9Sc6jBx3 zdsY~bHxhPy=Y=TzBk{lg4+`Hco4kAW}`hNMY9Ks@(P_Trx@N4x;f zX8I)q$76u2Rc7~&af2cpqzv=fJ1``4gqY81mC9}EWHI_!0}PpE9fxQhX59T!8<|=~ zuR0N%n2x6`J2}VfX9Pg-Go1_HnJ!PRuh7@(bta{NRn|TtxV1cOgonA5TddW1{8_`U zt`tVV3#_*FV&nXx(&X+lY_6CwxJ2eo&N_~nEL)p*@H(q_(t^KQk=#!n{(E?s@lt|r zS%=I{_xY1d*evJs74C-neO!rswYac%#TieWn;81vR#^Y8u~nN2imZXQP!Pj>hh^e3 zC=b{fGW&y3l^g#Fv&N~XBV$?jo0I_y6JRJXreRB5Y+ZuxB(*c#OkrS&$CEA#{t6*s z&Ge{)pcc|;i9!9JklQ9W(}M($W^C;RbmR?FDLaiMa^7DXNpKfQ1EdWZ8)iV&5bN^@t4YEQXy# zBbVG~%F`Qv1hQ9m-S~#-E6_IDFa#^-hamB5Jr>N)r6{T}btrGN;IvO|!z9T<+;!RX z!2wWUf2h9@G@_6Cg_EzBHrs(Lljc<$Rdd+@uve_ z@5QSj2dKX}W$t;1r3QsNO>hrk);I}lu$XRFZN)QXq zs#sCWbuLYOV7JC2YaX7_iv@o+CvVJ<5W+H*AOwuaOP?zbN|fl;)sAJEC-f3nuS-~h zxGfAC;zAZ`T@iS*^947YXjiOW;NIT!qMr?^m|I4{$A*&VKi(S|U$ezN^SeW|!I z09aufSv>`$?6Z!)=YN6>g`_Uc3^kJ_4DGwFV>Xa!q-lE(=+dcah1CN3A12PkNhJFdWP3QHL?*$A+jt`TFLarylYVjcE$KE# z77IPX68kKRb%0HutGUtLn2b*&p$wdBUGN8p{Y*6st2x(VQjN^ct7u?{n7?+98> zdjDo&B7vsI0xbRtZLQ|POU4uD^5J0_U2={C<;`?vW4sq{g2$8|#yFJZdvRmqAZx~3 zZIhz83G%;3w3E}*XrMV;fN-6)Ac5R0m)XyC`|BwLbvh(V`e)ee88WEgG&tGM;;hv< z?wq%S>FWhU+2#KpWCz3nTQ@Bk4xIly!LQ*4!fVI&!RCu`&+;2JhMe3?f{gX-nT$a& zaf2-*3u3HU=Gl9R`i(qU<7yVwLbiE2bQY#}Jh zxkbd&N0mg?y+P8|N ze)Vw62~k9Fwzk4GAJkV^`m}nq_b5<8#ofDcQb9UZoRls73EU;+V%R&SqSGpZuFGOZ z!DXW?gwsOxxsz~Lq3MG*KHSkYV)JE5V(ALv$y{`((T$X61znA*L z*Lev8p9*!B?$K^~o=6AO)V`gOMayQ@gkd}J7w0d~<6EZt!cTMp$|z0pdn?Lm?e|3w zy@{TfM({F7h(iO(RYbSV5^MyGMmV&eabQf~HXd^Y-{fwWHu!+;mYpc+8(-A5A1v+m zodemYLi$oQ_HdChALmZ=yy#{w26@(Y{quio-m6HzSP=Lg-ZHZ>+v6i5Mw`QEaY_rk z<-s`F2}SR;tMAHAPzOh&r<1_6V4DaMjAO!-S0o-4p@$6-FNP=iJg|#of(P?O=IYUZ z!oNoiopQ73Au6pf1I37PJUusWa*gc{!^v+R{}{oa6c?A3pb06=o_j&LBIcB>n= zWc%osA^sQQ04^}!>UPIkt%-86ANTp27~5Q+_4q}4)Ib@3vi;t?budRXXk5JW+W5kB zQjvBE0e%0R9w3|088ZU!XG?AjqsDqdkR}5mLLM+Qe&a~L{`64^FxcoJI-CD-ny$4f z7}vctQo!#cI@@T;ayM?v)zmhcJvrpo-Sng1ex7h<$_Q7^4?}XdoQ!vQxswamcc0dl zUU$l~c+->u`vpGvczVx0FEw~f=m+0kvg-5Ck>_GoRd3+Kw^n1v*D|hMK&ScYrZsvl zwuOaae>;%`z|jc$dici!wIU2!rbHM{MVo!Gk(I&YLHEfLl@*bT|2UfZG<5^^!&60$ z{l;N`MSW+jlhXAubnpLI{+$B}LPFtJpuB%i_GCDBG?Q?Zpz8Gx*qPOO&oGbPBWr>( zRZJ?#E_(hRUOk`tWOk$~J~WMiLIh>4xIc^+(EFh>rA?Eb$8AZ-iZufVNGOsthsmra zJq5D%r%IFk7o@ta)nJp7{C3$u)(L$*`UyL0wh3WaqA$<0X;BSa92k1%WX3ufB0ccd zs+lbM{{1uuIV@1whJt?7?U(GC#a-^n@2O){EKv=Med*g?QFYP)DrAmnnCM0VXJ_^t z85e6~1I?}&Y+sEPv}QU&XJdtrg}F~29E{^^djz~VRH$CyN1c_UfV+_XZbx4K`q|dwg1&WK>8Hx8dBik- z>{MVcPCv=Kobt_LGU*f644bJ|up#UeICdgcBnS%*kOUjEk1rv8;SoKLjCM5+<=!FprzyfGPUg{ofnN#3JWc@w2)h$IMtPh{ zZ8Aya8&6CP>`EXE^?D8K&iRVB457I4N$!p%to#0*E0*D*{I~mCMpUT-s z;`Q$f?B)zYtIn3de#sf>DTgkw=3HV`fs+~9NaY!kboU6;MP?n;(7Zd+frz{*ic@V2 zA=q*P^ka*;y$i6&`gIxR_kuz>KY(?Y(u?&^V3DC2!AG4Cg(Y@iWFg!I;rxx{_!q)_ z?x{7t{bbMp)jkD22s#~Ly;8)SDH{JoiWGfY$aDUa!ZK{bPAy8cWW&AGyf6~2pxR}L z8X%XGH)GsOBgEs(K`jx~$MJa$fwPhAuIob2c10f_Sn5G8KY6R(ZwEQx>=bE2WfT%v z1_*8C0-(?H8kVn9-fQo_W?Ui^(LJ?KoNi8HuaeRD^*H2@i76;FG+zq>7OL4F`3t{) zgwqY2d0pu2&;0oje!xXB55ebp#OIJ#xW2JDT4d}!8>biHDcX<%ghisLp|yRE;yB-r z1ddh5<^}9ntIu!0_+wvcTP{Sp>O*&cgmb;bp^F#OrJ7sIorqt&Bs4o(4>$>ec&?bh z{Y^S7FET(O080Y1(P6_n3Y4ix7o%}Hq)U>5cBeQ3rE4s)WR1I7-k#Dt)cde$PR%sJ z^eCsS8KrlELIe`EddW*}90hbQo%Li)-+Q6K=`ju7X`MvpQ}oFJc-R+tb=xF26j`1l zRKik4`QG7d(`soC%A_0a=t<5KW29BC{M?eLLr&)`q!$t=-N*pl{m-zM-B0Ps~^5D7m`Et zbPM&E(@Vg=|C5aeJSki!6|}67|7uR+ESXF%t|KaTOoR~|!jX&VeU>Qy-wWGkYumTy z=9a-Y0Kqt42sSvfP8Lfd0LF!L%gJVL((@_4LiNVU@KqD^2}cB~M$t&_qJPO@yL>=N zCDCq88(N{1`$N`G(+Tz52vsxi2{;6Z*u}Qm?fx-Ta6}(ja&L3qJ`K>Apb>Fg?rQa? zvh2Cybanf{)}HB2Jz;L3&qDJXedIi0(wVBQD+Z}yqa_3qTjFx=%#a}9nQ)UGy zUJb_4F4AT$np|M8dm*!cRr*7L+=J$YZ>i%JDL8f-|J+kbgC0|H#lCVU3rHgXtw<2g zfdFQW-C~D{_&oztL+WZA-|H#zspa(;Qa zLd?asdX_}5PkUu=5zUC2cEE-@3imfT4BwJfh8K`uR~o?h!e0Dx)~ic}8E-!_9by2Q zmOfJu^Y0PXs43C2FOgpCSw4AKSsSTrSH`#oC=z)7j2s_*g+2`^(ZJ+&nKtIX@1Kf(^2@d(-p* zvON~Ar>t;Yt9Ic_1MO*+?fB(6nS=C@{_NrJm*c&EzV5neVjHui`Kg>{Ke5xw3VZLd zO#oL`*e#`uFwXfR>_RYG3m3WoGLZ>iO#ULY|7Z5*8RkX!3bL#1J&R(}SO!7zs;4_( zp@+>@GkdH9Qq+6i^V;5J-xHod{q=GG1+`5QHSpw6TsRgCC92>YzW-keky&rNl_n|w z3)o$$m8?`Sdc|>gWb;gw0Bvb87h29*BU8wxhS6SdqL5DbuM^~C){kK|rYR$OHsy^~ z2ZI-Ac|V?(31mos~y!SGvIZ;xV{<^@igwGr!hr+f=xF->wnkl)4HV$#Up z<;MlOxS;D4-)^IGve~yw-LO%^5msRsAuyDbxMTmA zxPzeyA_P0~#EK9qOHq_~X@>?vw|iCiX5^C*#E;zFR-d_nhepmp!%GUI9Dweoc+c`5{HytlAlSr>OPm&Y zq`775yXq_|y|XUb|53jw-dK;nse4}8$0l8s0$0{U=M}+N>`fVwst)h`<{sermiLh1TENdYfkBDiW;!>m4 zg7?i(ALc!&2Ie8dG=9;NkNF{=g|W}OdVDq7Gf7+lTZH6u3-U{$JX@;tbFZ|8F$-$u z#@0OqKTM1Gwd0t=kRbieiwGVABIda;MygIMd1NU z4aD+`V4un6H-gFBQUSEbUA{+0!=?<{dMBp$^B%R3h=1Z^0RJ^phwMtGh5D)|*HXSH zg|(!!Tn#?1&aF=RwsWFdM{{0pz`y$9=*|3lMzM)IKF^&#`gS48#naSK;hGR$=3Fw( zmt;a8?laAs0F7Twoif5{Nz(A2wobf$mIbTp{gj1FWhr6zU`S!NXJX%c_IPy=GIExiE%okKJrJtpg9Av|S4+RB?DKlJ$^!#P#aB%WjmD#ouY9P!BHE=b<7VYNW5L}C`j>CSo!c)UC*OaC zMZ`#oZiYbxKlIzWFSML`G0Kg4Q2mOaU#r7gRf_N5*5gVXOpJBxx~O`Je{$GAv17-- zX~Vp5u|Ud*?_G7BRtc*dmYZyk3?LwM2LX%w6)YNn}fNHB; zAo7t=5^Jk3h!JOXWIUCD@U_qFS$*P(NBwJ_p$_9z2BUs_>D_erwmLe2%xTW#ntHre zzbP}4La+|YOpm`WF)3+kEN3jNMXJ+Ji9MV6VR}~|WWv~gcQtwMLDJUBzzP5PFiT@!{^YFn3v^%Cq~Iupu|r|sBL5JFJj zmZHGFJKNLlsOyVCdHmrm?f0`xcbI?TFut&Vo&DktOJP;D5fxp=9UsifFkHtSr4PFg@S>9sYl>|MouQ8prF89tQs|)Tbm^C47A(# zK{q!yciV(BUAnlNnP`*K`Mv-9waXp&6jUz1v09eIWTFcDJ!H4Op0lHqe<^S2wxzW@ z9-WkrLr^fA8G!~#lY?e{DWp-wX%B8UezQx8W__jA`LZOZda~2EB@nY|HT2a4;s8@-2?C zi0)i@YVK5(yKefOG7#rcE_-TFd!^7bMI+~`XYGII2iyXxTnAwUta$^f!msaPbZz>Y zc!S($He_^v?6;p&j$W&1oOx;=h%Wj+fj0s_o&`zsK!au_ z2G6uVJ(?G=I`86XtrZ7(&I8xR)SEY^&pw~v6^l|isU)zBgO#0N={bL`K-0YULRkl? z6RBJyag30BGEuTKRY5+4U-N${_&9k|@Bb1nNu!VYF$rEA>+sT7ZsTZRk1RH0WKPy1 zH%^WaDrG_^%k?WY9?H06KGl?2px)U>nlgf#I@RX|gZIKlz@j{ts=&G^8;Ik%{W>!D z_W=P%AyX?bWmdIq1@0f%rh*hqA?+=La>;zTdh?{%JG*NqF0E*V)LnCP6-on7o?ojLG+Ej-yk`G_;hA241 z-c6=B!a?9)jX@3=4fvy5;qKt!ih3l{89H6z6GD@_(namOUL!r{t=Nl@qTN10oPG-> z(P0=mb#3r)8f>}VYLK5aN^}`_YT-IAoH&++h~Bdg=OiK;1_r^&{?gC;4+*-(dl9TS ztMZI^IGNQ{Q!vS6THI7dCU+LwHdKIYuiu)!j<`v2MKzBxyLIl)Y%9;tErb2WpZt+LIwjeY9oA&=uK3 zJ0RO|JrFx^iiTH>X2M5I>x5(CX4Y3U?d37f(Z9R*Q)!i!HzrQ}+qTY+%&L~mo==8e ztopy?^?%T|_~jxhEOGN%G`r*acLzEEv%iVQ%${mZo@Am%dScut2j$7Xw5uE}O$w*Z zraRbkJ*;DKAcX~i;#50%M!vt?pQr2iP<(i6q(TaDDXzzx;8vfq6shq*>=3XDk3kOi zf4QGf%BAYs?N_O!&-)*mzB(%E@A;c82MkIm$TP`tRlkpz)zQAZ4FP^`Q*lW{@FY#dBC*@y8zwB5Ho=;j3|j>L?$G zK0g-^5#6Y`WcJ>4T{m3?07+%hI5KHMI{{E&CQ)dhkF8kR5uSU)* zpoJn?o@3vvr$a6>2b(v3YkeH5*u2~<6>q(-!aNBIaudi3D_|yTV$FrQfR}*mer9*T z#qD8%-2+5sR?6fz)8hOP--{m|oCNNg=wCzaw^X#&Lc31TcZJ@KkCInR4V)%u{J5J9 z3|+d+{ugWLHQVeNaY}dD2H0?>6IzA}wKUk{>#@oF444L&QDA@n=JF0^U3wP?n-xq-OztwabJ!3ZwMM!e?y#CfmH-Y>DwfURvX z=(o7-#@^rr5BQM?1qO4Mkq>;nlLrosHR0UAn{Ul>3WAo#AXVDig?6uKdm;;UQ(l~Z zU98HY%-#YX5mG<+)*79s{_#~=>i_Qh)avcehVx2gxWJ=b#8j(t3bb~1#Ov$)4m zd_V24k-GU-I>g0j&D#&azE4{jwG%eD&D#Z2=S**LGG^<0v-6XRu=`*`)+ZI;w^o zQhZHMwYA3J_t-~w8LJ~p`pvixd(Hn|beY2eu(|}v5r5Zv^P8?=Ry6{@b2r2iiz1?%z zqBR;pQR~Lddfhlc>TfEi8r(cd#Q5ars+D=k^t!pVQUnNhOO&60d2+h0?Us{>Y~Ah_ zqRZ)Y&5!Q10kOab2}m6hMV2TKTL0Lxt{dIQF7wv-GPMFSduaIR=z}&UtZjK<^x`No zp{A)(u-8nk{Gk0p zPnPRo@h#i1vbDJ!`%2awtyn7UQ1aqQ7Sw%R#qd#}u+}X_yC$ zB&X2F#kL6Ax(w@_It@A51iZ;ZKFpQx12Td^@i?iyZ(Fs9fg%)%n^ZcvO>O3+J_56K z@{r={amIgRd{?LM<%`?nOcLvyCUe1w3^r-#aVoez{&fBVh$Sm2W);%}Z-YRZ)F*as zmUv3gM?_MdPwN{Uayj-{BDjnFOhJ3$t1q;FXzA^3*)s|kGl0MWRAg5#Q*yadc{W(* zuwI;*x>;i_P2AS|6z6Q$ZIRnym#hKOSt^U+Am$E9;62a@Uq~UU3Y=nvL@~ zsk?{dIv4Wh4*Ub>m#qOh%gY}x&tmKKcMS(bK>FTa-j89{+Sr{*HX@`B(N5*93{5r0_tUFfP`Vd++ z^?ed959hx_eO|_Md5h8r9KEw%PNGj}mY3FPSg+LL3`iVUt46)Mc0W0B591DCB#0I8 z+8gDXV9QxF>o>g6B7q+mmgVoZg>@|6ehR?;z6qb;ZOk+v9uv2VA@AYxYm;Llx9BIP;?*$M@1Ijpm*V}+= z2Y-{1t}ScVN=D%D5yd*A6YA&_+PZvV7Rg$%{{&3L@jnO3jHT;sT3|J=%lFuZ;)}D* zvkXI4Zq5B$q*7qJZ3m&p%RIJhm74_mi_Z-4D~^#Jd5^+N&9Z}|V=mk2)iM#y759|ho+R@-eLm()O}tqPMDEWP zOG%GTpsVbc7yDVhp9*Su__534-K?(=9zfz%skzs+SxD?VRAg_qEY^GrTv(HA zP<5$o3!M}8db!>EVa{0<5F`pblQWCo8nh@Ue0j!s7pw~uIF$WpJ7+FhaNzSW7hor# z;+pSSe-=enRYZDE=k(;hLvKrq3BI-=E$%Bs{Nh{dnu9yiYKF$rqL`hN^uff*5XfDciHfDnF+0yIL(el6LDpjXeU?KLIskMOnG&QHOT?KKKN@g%xb zP?|G%>DQ;~R6MHZqIKnrvN|i9=}(KX z-U3moPmy!>I2`rwCR@c@9ge0-q`p=2X2bn0>dxN@fr8@QN3QTOIV@$Ef^&|4mJUpxnS7tz`2(&TO7oOPZY<;ZRTBi5$Sk&SCYN?l8madqvXaai9n3d$; zqW_`^_OU2qE(8j+Y1iji`2u6-ktF;kw=SLay}iHSiR#GKZdW{a<8votc8LO2P10GN zWh2*zdCQ6^!<(jl)Xy)ee-r=89%-|S+e3#0tX&-)1QVAGOLj!xBEe6NiGnX@rs38l zht6Xs!m*?LKk$de04s8YS799+G3fpJ-ydg`EnM^$9d( z1yiAqqTK9>V4!8aIBj5ZCZZ1od{c*B*qU zv-wVSpN!ya99;eL;BC=7_o6?u`21JoC2&UVnO2p}*of24!)j0qqte)p@I8&x-6rYy z(OVzO-FIU1I~d)s@z?JtJKS-?ht^y>`?XNAv2i6;Zr51cF*1jF=pGvsqgCcUm3OT0Ojw`0JTtO?k@T|Q8I?8mzsRB}Mb5D*FORUl&_}lv#T0&1>c_|*L@Yr( z$5uv3A;C0=)3bQNbA}Wr)y~v@d5yy~F*;QZkWYi+YMHwCv9nvY@ggd<>+qf+ALo zrP7yjOL)r=1REbx2RigIgClyY#!R9iGlh!)3iO>jF)EW!4an?%W_c6A!Z*v0yuFN# zdK6A@!dSC@he_x*&n$3LW50xx7nuZ>}yLnFcjbQw$$>>O>I-vPX@$ z>*eE`XuwYXXtIO(Rvd&(#3|>IE{{2h=As&*f!-t)MFvRJI@=SP38_rnbnM$&fGU7y zvr>oU+O}O<)A2qr*1%eR9oo?^b#si>Q;GL9w~+nC)JL)V_7y6rj73>$+6GsOs|E-? z?QhItk2{|zx&GltiPOexr^?X^ta>#xqC_-HS3=C&p68n%;{c+9=l|+?x>OBQd-8Qw z2w8GdottVG@fHnCrW-2NWwdgz7kPDyvbY)IJQF}ud;Ev0 z)syXq_awT_Z(EhoG@kucfSqb)LUou=C4bHr(YW%`WkY84aq1r#_+!&Jm!VKUv79?} z-;WnjSM%w)!o@n#BS|jkzCJcJGf;(ABkry@nbQL!tq&h`T-y{f(QDrHmv@?f^t{q* zr+}AxEr=3y8j#po5+n3{rZ}r95EsPoz3;S>M1{5NobwaXM;Ht_ElCW^Q69a^$)G$v z*4cBGu%%c8)E2sw8z2^;3SRtt7eIE*?f&rvTV`P*B&7BIx47SdFo%)NOQY7~elGUNO^@DFw~e6C4Rt?6^+W(U_>X7JG_-MdE)w5zH+uSPZAfxzF&MX|gEa;OiCQ zt?axKVWisHU2n~R`kS3O9V; zF65SYrkg`EmVeyAnqLBDs^tkJR0fHN8E9l7NhP{3n)Hhis|92Ny79L5Wm14O+P-Ql2OOUt2ZdHxc6h($XM)j z9&bQPo%CqUl@#uH3voAK&h z`FW+1cncZDL66G6L<;LPQf>j4?Uw+tQH##+-SD#zH+r}Kbl!(7s9_H zU;4^j`3k{)6!GVAeyj@yc7j(af}V3+z3mmifSkaqah(p28hmHBQ8X8yZHGR+j;|U> zS)6~C^P5K;<)jfgV8)H30%V%X(+=IO<{Z@L7K?Cds=gvmy$hVCt{)7rRR)k3Xu;N1 z%`5_PT6pTg{iJy4U%_LReVwJSYlV>3tGh%STry`H-9ooT&@n7|nI10b&>=YE!J_dV z!=flD7P6Rf&yn%*CJ&m&Uli^a#?;=V_7`Zs64d{9l|_E8t{N#6XlvxwW7Ws`ddf|d z_zTv%SSU6%(7ToekKSK_cK_9WJ*T6cjHwyAiR;9RAO z+P@zTsKgHEy(x+KYG^#bdh)608=s@N2Wfh#1QX%EI5+I4M?Hn}FP~BAK)Acz8f#Qg z^MdN0{q8|y(f^%bX0Qt=xzsGv_+iq&-e`8xNTef^vMuy*T9#Q}lm>^Ut^hRzag z(9FJ*+S)IkF4^X>ht>^lx-N()86RN^QhPS(l?RW7<>uj|NdS2!QvOnNkq{5DEf>Or zgY+}}AG^l={h9*DdumD|jvw~>cbsylR3i_T*PpH;{j&)LAe@;0669fwV$)XV!e)R* z=94(+At3lgY{R-D1-W2{ZcqzHyCidXTf)b;9Z{!!NWSU%?K6cn*;1tvdCoSa^|9Tq zEa`wP+Vj;0j{%1d782siY#xd7UmN1xPA{%cQ6=01Ueq9(Pk*seXs53Y93VlqT>87T z7Q165SrrNobKPcr-`}N|hN?lMhk}v59)+pbWTo-2hb8O>w$1`;B39|^U+vtt4Pmbz z2uT9V5YF0XU$KiJ3xRCY?xf~h>l9Ma|BULjdf(YC1~-!S+2)ccTCcFyl()WR2U2TE zZa*gqFq*>iu~xnv7g3ChayHUY+8S=)3-8K$a9-WG)M`y~a$p_0c#M;>1XC_}kW(U~ zlw>lfp^kK?zW<{1+)iz&fo&O*BQ}%uwomYoIC9R`{n*(uSd}nx?#R4E+23W@DTW^w zLpc75aO;^z!R%-#a7rmkL;iP4H(~0AuWFml143%!8rH>$$vLHUcj~$h%8+&kiUnQe zK>3UN@p~bzW0tNGO9Z+WNti{(+>l9qd#$|b7RD%Py5sRHSDS4LsNMEZ()n%%dp(^qeqzn>ZP{%b3_8@4 zjqY3~C|tCweN)Pbw%Bc^M0f-YP@@2pW;*CHgr_3KXMjAZ68FF)3{u5F4a;~x=3TL2 zG*MA9{z1q1npq~%W6T!*j^37}RN}X1ywfEqzdVU`#SigR_M!!Df8HsL|LS*Kn(_B! z-kyD?0`W4Q!eoYFy(eNZMHdF%`8cw!f54~puldc9h`gbFEySPJ(3z=H>YRc5?Pp!; z>`+BhN_u9COLfYEnQ{aB(p%xAX7wLFz_X-?<7VpGepD;Y*PgE^BHtb~cwC5l6{i>O zscWBI}FqyV43BiyYO7J!3oE)z@_K3 zY|n4ZwbbRFkBxVJMIQJ^E&I9qIsRGA1W=3qWD?(Cn_D2+Rr+i0(CJ1`zs~JDjUJpw zfdNZPA|bp#U*o?uUBPP302Dp7G<{}guA|=FJ+|sWmyO-;>#l9vTY%GMY%9@0Z`$RH zWJ76r&Q(}X>*5e3o-mtYag1n<3C$~0X~oq?sQx&TNV07Da9?-;mv=Oq;Wm7co*MZa&a47pF5 zgn79?L>Csh*4JpC?2@YM5ZWMHCFpEqp%>N)-1^gKo3*M;jG|p@kk6M{i{<{3(uK}| z&3NYzeC?5T0U0L&1CA5?RmnYw#An~sh|uh8(+SQwD}M30b-vL|6VK$xJ~#po8hkBb zoELsVps-EKk1YGE=yu8PMnqluR9YPMabW$ja>^(*Ti%bItLmi%pX`x$-92)+FK94` zZiqh9LjuwH_9E!O#LT4Rqj-7ywr79s_wV4D(>tz6!=WSK(Q(||#WziwZT(Z|&)Dhy z6U1-*%nOsYTO+#TptO`iH5&Yxj^&gh|lWrJ$uF+LiM zM*?(6TZw>J8Kc}&7~gzzSEKzc;?+Cw+Cvnn*BLK!D<&a14#YH6R*#hX%-croWY4o| zc9Zl|aWzF@ZJR=X6wRLp@YnNNB4DLWJNLj^PRx8&O+RK$mwVicpSnGXF+e7LEjPWTR$CvJ4%AnmyG~c8;?>L^1*x0esFckQ{@wu-0d&& zD%dTrD+meg`0^#YdexGHkzvHOU_(8|K?Nf<2QlC#eF?u)MaHes z)Kf#NoPQ_v)9?OL<1!(xo_!P+K1$^EaKcE5UF$d1M&CZP*xUVAlU!pJn?BmJaEHk^ z$5!HM6p@Lw)e!DD@RxnGp8JblU4K@d^^;`igyv)Tp)p^a8BOL5-62J9#unSnR=x2xwW|(<9a8Qd)UJcHgNMNy1W`=7-w* zNi>L^W$X4%Nits0rCwlGxo`CY#}maY^2X-g5H;A#jDsFo*`7fSmqhqF{e50m&e2~E z8d!RwM|tn!gn>LDN)T>g0zKv;ekztSa6Ds3Ok1>nDc#-PW&TscnuFBo$cfU4fvDxm z6!2i-BKw^7m?jODZ`3Ez^`7pv!peRDPgpb+wf0gq`-G5elqqmu&mFXWCzCGYUvZ0?v&7uhX! zv-<$+(?@UO%c*Ls?P9Q}Ifna{fpKYW97Z+r5Pg+@m3;g2gNokMXl!<~oTfvf<3vJu z0o4pXA~C=^ioZNpZCG^Cz_xuftfO%AHpg#z3{g_FRge=P0&RoS+GUL|^S6{h_USM7 z*CZy2c1jkcf6EeLV#+9dq<4RgwD8xC@40g!G(s4)v?bEIJ>27&mVhS7AEq8>js6*f zxYnDy!Fxl4#fE=0#={g_l%TvOcOQcWBDh6!_CWL3L%vf+qeQ`mxT#T3!ZM<9`P+6B7WE3}Tw=!Gw{mti*GJtE>6y z4cKm2K&FgWx5e$bU*sG7siaV;tx?3|eLmdV^1>XfPe@L!Dom&3(PYP&G2c=p*m#l% zO>!^Q{o)TF#rXBayQ*S@3!+&SGrmqxUObShpX&Z5vPPUS9L%caIG2PC-$<;UsD1fckLv+g}4LS0?Wge zY|S=Y^rGhM_Z{AQ;t!Uqdsn0=H%uoo<@grt>VV6_z86-Vnmq&n;Kk*zt=(iRbLkzX z^GD466H?IUEE!l_{|-tQ1p@qclhyDM5XX~FpAo}zIj$Jy=MOrB*z8t`c@NEVo3NEEHBCJ({JlUe7oQ$ZT-d5Z|I^G z3VJe|-&6e;*>V93nMdvmKYb!wKEaz<=Q0vDEH4rMWK8b199&m%Jqpag$o(Y0l6;Q$3yQ_hB-BWD3LB3m9v2})$5%l# zNHy#z_ZV?`-7&3QX9MMHPL+!t?Jf8|U)Jr0K0aFn<>^Q@w@)Q!D}gRJeCl=u97~IV zHnFdDMUNZx@$1){;-j2Cx4-LsPMTh;f1-_UmSL1xq4`AVjX&riz*p=6yf5M5$LfEqWF6EuB4Dq+r8PCHEO}fsg@tV3INh4W%`P8pkTfow?>7~ z>npb})HN{Kx!32}tapYbtE#$cmrZ=oO|MenSnZZSRk^okbYDID|7hY43RTTRw{o(8 z|LxO6itWlWBGRCmwccO$W%r4)A^IY$xV$A9;~10YxYSJ=v=JQPOEYiekZ763k84qk zQG1`fyEm`2=E=6E58C?<*nmUQYo6ZD1sr(_U%@^~yPnj~9hhs#u@A18dsfDSE@c<4 zUh)Ng5=#ptRDow04q;xucs}6oS_9oi;ycbMhp(O2e+ZHqaI~V`09PQ7dSbtn>n6n) zws@l&4QP_-+j3j$$X^{@jaB`)rw{~-kPM^dzapww|eGN(cOk~Us6~@k)V;E;w?lMkv2$}pr_>>*wyj5 zdLbK*9mp)+lRzTJ?0hE%hujLwwjlbYUQ#3#b2-6xH$5AygL`6wxw~#RB+mL+MfsDTf})yc`n^E8O0;l6hZ;qLB`P?Mrr zjd!%lMR+@=Em+VtOxC8>=F9-5W4dF&j2ErjGO zgK~~qx*BGk{pxw`b&vUxO?MQ12G&P?M?AwsM3NqvO=CSCf^Lk*K(kYZM~={3e_Dd( z7kDJNM8cLwHgjAF9K5{eHG6L##o<(ikY7gFYhD|TB8PS4blIVjM+9;ud$F(!DOx9G zuWY!p&mt@P2PIES^{}>9+FU;~Kq5IG{{m*h6-H&Zw@g*t-9cglE*`JvJ(*Y~&^sRc zmyy}EVbz~SPPLLo-Z1{J2Sd6#+#$MKp`LB`OJr~nhUF* z{*`0!(s(>d7ZqNOwPPl}E>W-PQA$ zf32TO`Xr#hfF4N+9yuyl9LJ9~PRTMAE8^UATHf6?Z-orb`;V<7nR;mZWL zPY}ZpeM(3^!cE}C^L*Q*=X?;;PRD=Z!yj~Mj{m$>e!u`xv9mL&C4}y`mW7%NzkKF` ze2mmR1NS>y&v9UlM)f}d;$HifA({cpjr(!SytIFHx_tJPAC;wQVQ%4quHO)D7bb)p z(NvhLa|mBB%_OQ5LWapq4&;UyMtk;$DRXz#zUwGkFE?oIatFHm<cSx==%%X#cpsyY-H&il+XUZ7htrxHC(*Ej9slOca7CJ zl#KyZY6xvaU2xPhJ_#b%CYLZ8`=0xoM1SDm#)QW^84R^SYoHce*7i2eDM!vpJdEj* zetd@lCfsVO2E4y4N-Z@UnKJV2nR#^N|3G1Nb*v#^sG^TBs5a98%*RSF25v~IQ$cRN zdMdi7)!w_P-#cPP`*SNecwch?H_eR0-ZU~*Pi)ioop^80&)s?5uSJgMLL^3cBC>vV zdv*50s$JLi$lGJ(DKXhXt!+E3-NN{Msu9iN-L3}7mz53+B0DjSlOIkwb&0@bMBK7M z8{U631@QAu<5P~A6Spv{te|#8zp`Wc@^aUx^AthlwQsg<;g_!gKS7Y;qkEcDUDLZ2 zm1_ZX$^~JFT%JxlV0XaR(lxk!F!_9y_O7(ZkC{i?Iy@G zd*nX;^?k|<_0Pz=VaX1&+Jxj*c%v`}RzxjuN%?h$f6M-nhgdOUsJ5*(%+A1D=kdV;*rrd(sxa8RIxw(e#a@Z1~!oeUKj8G zaNW~Qq@UN*Vk6WoaXn$Y!STShbpOrKbZQ_6EGqP~HS+JCsj7vTUIRJ=caTSG@AjqE z397-#OQ6wyZeNhW#R*TNJ`;b1V~}6p*dfpbQp#_<4r($#FkC^Mp$L> ze5rvY^(yp1MNH3Bn82*h{-Yf_N1ea$XG4*Q!!8p5d&-E0S)4X-oK(xSS%NeShd1fh z2MAtM%>SzS*Z6e>Y5d3Nbm|*}0ba~3rq++2RWae(i{F*UI5PMf3Q z-B_)MKLfW-?MxTUS4^JKV*sZ|3J6-7@LJF3cLmdhWdAPYk&GY|Spk41M{YvB(>ptf zKyEDL1TkPK$B$U;{z`}0dV3-r;N>sA{xSYq1ofw0b6Gn%LtL68M?lxrEBd3SNj3Px zjx9snidC3h?ew#jnP=w8wk^O+op79W2Jd&S?WwR zkJ*!GY5*mdh*=|k9lF5mYqF#}8Q?(P0YVr0f=pBsO&H$T9S_XxEl5of`MQt~Q-IfkKdyEbMang{DcI8W0oz?&Rtv z?iJOZH@1vZ{}-k!v(w|Xm!9-5u+IL>@}A4oy{95_h>8lACR?3NgE9T5NVQY^isq2y zw1X>)uBMOc04l&IyPFY?W@+|6>0eWTaVko{1qY6hww++O;~{qo@r{%gYqGpi8W%kP zo48@-Oo6Xg5i)$5Q}xysXvS;rKzJ1qqq;SFrcQGYX1I?(N!Jujl@1o{ozZfg75(PU zOpFr~59FNC`Gs`nI>*EHr$ZC^2#Y zk9_O*t7dFffOK*PW~tMl3ng?swSCuV+VEdFWh9`*?zz8gp50KVNY-zmgzF-olp$4j za& z6)uuW-Tk6Y#nu1bVHFS-l(+=NYq@YTT2uk3RVIl-j|I|zrtBTYgB(Ot7gev50ide} z*GHYs>zIKC7!!ovBX!LQ7COgy?Cfr~E?x>b*P^oV?|2&kLm%~itVlmA-8W=^{z$0V zVYHyEFpCK;O%%HH{H~{r@9gmL{nA2BGiMv0IePQws8cY8p9PRUBWv*STDg z$U1_3e6K~3E^AiXi2yR-S3M;oM6SG_ou@;b+AP(NQx)xH2bt8V#RD#s1#v$g7!HEq zMC(x!1%{nQ%UHu+bFa!xPp57&itjOkIx4A7y}`|s^ONZ%3D6lXrnu$JBLZLCI$1hP zNz-jx*Djg^^@ZCE0}~TFN-}-_Mx=9wOfg>sn8HC;WFe09lT&1p7Y~v8Fy}S?I)nr* z)-Ak-bihv1|9o7d=c5%2*4oEyN&Fhg2tIO@dR#_Ij%>vMej zM`%nB)g()LRID9p@cShW2a79q6^Z*14cjHrdRMdS1|fO*)B}m!zDD3(?1c}IQP2B0 zU`%#*GjUrq?Z6zQoSEy(5^)iuYSZ5CfxAoMBS6+&+VsNX%bU z&PN`q=3A&jP(;l+8a|?p!vQzAcB3gsX}kLLjs)6UP$d13^J6$kL>~*E{=la5a0)-rTzVt)XgG zV*|puroOS?%~e3-_9)Blgn%jeE-028~F74vXyV zU0t1H&6aFGxu`NMM{$u!`!4Mc9WN2#_@f(s` zf%ob3%pVjO6$+jKX;)0$0mr&pUSLVsnDe)$N?K9V1r3jXxbWqQ(RD)kci!rh2m5W( zP8c!z^$2;DUgyKY%DCz^%&EL0cTG3meI4v%e?awa8bKp55S%FTbCz9UzhQpOBz+-| zCeo{$)SWyyl^>-9Qm1I0_9D7+ie=pJA%6Q?ino2~GlZsoO#T*iJg{@NVoGuP;?Dmi zhYubzj@I#b(Ux`M7OZL=`o{E|FJK(k+N;Pd%s1v7#W+bM?&u{byBWDE@v!Rq?;^Kxa(PYW`nLPKBd*SK2c?t+LiE8wA^0R;np^v%ve>B_F z8>H#;^bSiJ-|&zP{oOQT7&35J@68i_*}ZzqX@3+g0B_~a2zQOQYK1de(7N87QdYVC zdadWvj&Y(oA-%!TOoY(WG)}zf?(4bhAZDCA?GGFH?mDNI zvSIJ@4ZtaPc#Dj|z2lQI83l_131 z-!nD-GEk6q-G|-Fbq;AGQyTv z*q;l!onrJ2${CsDISg|H4hWN++Nn2{LSR`6WM1=TI{=R0%DV~>th0L8G7P&xhe{!- zKcX0hT}`UUv;SlGlDvS?SFE1<^VTTA^da1aB$?Y+j0rb@XOcM9+4OwFcJ0D)7TwMH zVPJRfie2O(vBZwsl+d1WyTn^hufL*9BOtP{va#WS6qxm!^b?{gtW8+VQL6(}RBTN& z-WkcD>tjGFO>CPa6a^AaIQY@}Wi4|G=c&s4>BbHB;$7#Mj8et)PFyW0&=-K_CwVv? z#f8v~!>G$wH#~!f zbF}=pYmETBYgzNwv_8SBajkeYACN{-QZ?*>vg;Eg2cQwq-(kQ*e+GwB0!BRO!#;AW zTsXg$M-?pK>mnHF!LMLZ@a@;R4bu~xgFk5+<+XySecr5Tyzt-oskG*?=GuS#PA*W8 zLCSYy#0VT z6A8m|+kZpS)RdsvW|ZnDu;qjH8LV7K7hmYmfZeOdMG!C?K5q<@{^FIcNvJ7ob))1l zd0HCN$2N#If9k#WM-z44fg$Jj=-+R-X3$Hjm33)s8voIdk%mcSVPH>wNCInrIzj*x z3Ca4SNiq({N|#j?7FDpA71{*{l8&&^R5gf%B(B?xjw?zh2n(pDb8o$o*#Y}b%1k<~ zBZo|6=S2dzb_>SdAn;hQL70`KI_i{%KQrTR^dtf16tC( zDU-iuS2DNq$x{Q_wgg4D)rcsCTav%+3ND7s}WFiJEc?Z9`H5zcR3>nb2QrBqbO(_U6cNzH70 zEiF;zQ6e0B%OAWnoTyT*gHTKRJZzt%uKDSXQ+xwCRXH8y0k%}qT(y_so>%rE1mqR47WIe$g zO~S>6Hs8+RRGjraFQm;5YsgL6FRiCaQ*$#hh?q++36TM^OZY14Wv1d{F>8H80ms*LdJ8ndS9&LpJT?2r>5tbov3+$>qvN}_C_OWhq0Az#w2A@3S;zdifghiBH(^?}(J9#hX>=e}W z;Kk={;pMt@f4-|C+vL^_M)b!U9ryUFmeQbcR zaVgG81$E5jd~KR=ak|k3rYr%>OxJ#DL&y4S>3taLIPp~lWUv=;{xr4>Q&I7p@mZ#C zJba^}=5;o;7=PdpQEJEk8P=UR!V@Njh7~E!f(92GP-rmCMysF8c{kuUhVgl1V8~UJ zFMB~%?6oMj8Wu~1m%yh_7TuKbF5kZhG}+$lN;Wk(;Ly^FpJmOskd3?8py8eM!mOL1$>4h~Pa=-xS^7{*My`6$Gs zx%tqzcqA*%k0_;PwS3->*Xp!cyZOxs`jgk=^sILl$K%rN2nCC_0nC+C3p#@srFyf6 zAKdU}*W&a$CeAZ{NdCC@R~sCq7cYDs8{E`0hGudRQedbDdeN@uZD@ zxJL;^2f{@7k%!N{*Es4BzGorG8aNwy)K$D2h$80l$+d-C==@^#RZ0#%n$Ak@&r#sj z^(Y1k|a#YphVmRiF9AOM;rOy{0#@j?1Z*k zpuBk=uZQ{j(Is0HV}*uKh__nF2MhOyp8p&Y`k;bKp5#xylBNsMEx1X&jUCe&+;}Hg zM#&RNXk}zPbB8vgo1b7(C-<|sg}5+zoTZU4Vf=8jkj%>FHfz@or}k37jky^V+mM~K zAD;xG`S`6s9Q?{~)A*o{1FYdTx>dNxM{I-4`!0yLO@@AC?pOe}pLuY}J@F6}FM(ml zN%*ouG>+LWQLsk3m*NN~560$p)?#;J$=9ob8GYUL)4zoIQNC>+%Kjwlyy$bwk6(Rd zXX%`HGp6+ejc`|`m5pZW$5>v!4<8c6-#yuyO(9A<$GJT#GGd!B$WEuwwJY`tPcrr2 zo>OwIklxtZxXZEO4cHmHwS>CoVE^-c{SObjnlmA_yeETx6kG8xM?FmLzq9b*e#iBe zxkf%8e6~kVW?i{nHV|(H=6y{;BN-m=;T94WP$qFhm3dBg_q8D4rt%>u@OO$Xr2ayL zb$Etgs8}j-z5WdyF5|E1gb);KMBg~E@$SxgRk0jRvGz1tJ)x7DWYDV@Kcft-&GxOZ zTJ57+<})dZ_9zr8T!t6aYgL&Jwit-5zxMCH<(O!itF7)zz4-Dz2(r14NLpz0g$dcL zBL6l!^(etZT|i0Z6SBEBFF?XQ=IUOFL^-GieIR;bV77C!+IzGX4nZ{}`zf4luS1>Pkfz|X^E5UHu$atdVy zHX%dtCpf@S*A4dn5C6a`7Tx9G3TGdRbJl zde6jQS_13uiA}m0I_f>xI0RHc8^fpp9j?m+?fn;it=88gVWc76U!LmWEi5V0ZDV4u z;u9Aee!$yRJdCjzMJ0GHAPP>5e>kJQ6YdFEy!zgkN4VGh8Z?C{BwHVRRZ0+5zCJxm zYQDB>e1%!a<1@M)2d=gcdoOG@!+l-I9|C~+q%RScv)d%B zKk?~>X+81WuItto@}gQDGVdxZ&4kc3ptZ$e!1DWK2iu}R*-(!oFTC~h@ssz#$)_7Uzg?Z6Ns4AO;c&qD}@RzsO|x;jAn%5 zygzH4R$gz9F+_&cEZaH9FJiVq+|(n)hkmr8%x{>dKzr8AFl(zNRY1K>W&tz3qGK~qH*?!3OP2eKqm*mj>w*TZ&p@+g^)i)Ek?TWBNEMCKm#p&i zSrhB0SJ$STwIcynaf|g^m zyp3<52t?yLObO-6Io517fjg!q>3d>@m6@Pwt@wA`+OYNal0m)$qKuJ*$i3@-KfGRp z+DFQH@546`7Vj5an)y5@%w7N^UaATT4HLw6`8F~}EC8UZCFhk>CxMjE8MyM-Z!dLMuP&wInoTyV~L_E|gD z+WR;f^k1Fr=vn*dR;TVdfNLliiVuogdAeq6<@lqEm9I*+p+B6}fr-wHk zOKEoC_r7f1mvU~LUSEv9EzzlZcZdppN^Evpa=8>`X=gM?S)y`YPTi8AP8U|vb6DNR z7Af|=;t8b@1zxZPpU+oKO-qi!hv%-mF_>D*tvSbiiKrtjBf@Ixt*oq`4Ka47Vw-~+vUnU&u9m>qIdp)#S=r=k zTe{)Z^}@oAXuc}qauyNnO}fN{8uGH*YJ|Wt+9VMt*9~DTj$5V>m`wbWOm?vm*akmZ zaeiSb3R>_)+C7^;c^hl<@4Fp_%DRK!(1&lqk!_DMzNh>r+UubpBlH!qV}N)BRzjHd zt#NDdZNMqO9*a+LQ2VO6KS#ALBM7TUf3eknh%gTLv!nEyL7+?eEjbBWUi{zUKFA{yKL@opW=YG4Ov4&i$}bz`A`D+n^m>w^sN&c{xi zRS!Ci$GBSmXJ<22gMFi1EHYKUzEzZN{QGU05ZT}GnfA+Rtp>e|Q;?f8iP>IzG?@%@ z)RHvb#YKl>%fsYQ8*UAt6Ng+r1O3E@)HV%bG*OS4Y17^wske#?wCuq&*%$D~iS zec(J<(AhWBb|RbodtJA7(&3c*x#iARSW@c?e`|#(ZOgrrNoo*6rt1}mvxym~V14-5 zP1NAlFF2SQJ*Wyg{@V9V2&2CdHnTT*E&fkWqYVe-cKqH+7M$7qrnc zHNjSvDdpI|ticj|UVF|zv&jL%%v}ov#LdJ#n6fRmOe~@_=2ANGl7@UGL@;Hml-Q0M zR@wnGBwl17q>eCVeHbdHPbcJ6trwDINpE*UmmEJW@wda)+6ZqJ`Bv_mnckl&9e0N< zOI6se)D0UEwogo7Wnmddlur*!KEHg9RUG!s((jGMT4VpzVl}bzhJPhAb>O+ur~KS} zWQl_XV0chuMeE}iGVxjD$Rjt>klylTGm5{TAfFdSe5Yl5nOfp+-!t-V6OY`=eM2xt`p$hApmFo+DrnpWz*XSg5?&x;l{Cdwh6O~yfFC1!JM{q zP~A-vXP{9|;7YL7|JMSTbp(&1Qc1=h4cm|s4YSFtBps2$=0v~bB@4q{Oc^_?A=`vZ z@QEAEMVsH~c40=Wp-egTzZ*V?HO9a|%DYP1yJNNGKT9~@mc>vwR_7BI1U;;_{K3Qg z*(!y${Lp^YIH~;S!i~@3;m{u1;NdvnEt%pl^VET7-tzKSMZm_i|> z?FrZ@B!@nl0{p58)-&Cfms)o6nF5>-yMHz?X(BXR>-yrS?&p=2EwPuJUGxYR;#bMk z;M-XXNNMWVSi_=QBG&OcdfQC%GBkfU@-H22-(kug)5rkFqoG=RX$c4WmcDyZE!zORP)Vz;T=y7BBFusfF z5)+45Wpzs#^tDyP>Lf>pW95?aJ~Upm*)AjNsB6dvOl>NZmR8k2DajG1hi#eR@n|V+ z)xY2)$&N|2NY6z_|LjA!{m+P1i+|3L^=llQ4}yG61;kma%`W+plM>-V3_mNd`*=#V zGU>oeEw}D#gmBeQ*qSj!x#t&(iLr)G$?`?IMa1x6;kPH?0|-)i7PI-gJO7LfKS{3j z(ve0pwg@{zoI^6;k9-3!z))bbC) zw^p%(L(&rP*^{-s+A&mIYjnWgrtL|78fSW1A;a{MNn8NUf!{j| z7x;P$sLNfrv8omKwI3*an)_6UA%DmT%ud=fw$n)!+s%>mr%*eGS37yZd+wm`UZ9J& z^6jumUMa=iBOHmoyl4Q=pg?TFD04oYS64R8zbk{!{FVDzmvoN;|GLRjwy^Vdf~VZ5 z15b>bls8w>EAt;>oH9EeAI`XEUggY}@Mpdt3h#TZL-U;nvTfNOmL?|ui8hkE+T^Cg z)iiKVpz~=+&lkkLO5T3%TV*jTO=F;T)tW&gqAMeGrh?bhWM%jnInpX)aS=_(JdR?FOqghm zvRRJqUcdTP_~?ttb_0M|0r|3iVvoJgQs~wrlAuWg>~9?{}&{`gWGYajUm`s@XM5HV~&{2wshaw3Nv3~ zRd<}nz29-QJY<_c;h@_#1+~!tk!PEyjXnJu6qU?W^Z1F9(S)}QRc4uD6E_12MNB0|6uVek*8W1LrV@ zZ=h`$jb?~;jXYcVrNXyc51a${zjLT*#pL@#sX^J>6ZcN&-#*jpol6-AdH!647xMLh zW8d6>(ak}PNiGXXnP2QA{pyla&#@7;{g&3 zpW9c*n5S2@;t7oApgd#%&CeK!;hznY{l1w2tU1V#{k*V-OysMgom8~>i|MZktv22+ z*Hu&Fl56ntIc^TPfn9=>jR=L!X^H?$YTt~@Ft>5HW=<##erz`UhekdmTOoOY=**u+ z&+lDcX_4PBHTY-Gd8yAko`CMCV1CdO#um8O)^P{y)?YpgFZP3mvq|V^ zskSiHH%P=xoYg#0u=h9x|AF=Hm}$gAjh^JJS|}-5cF$jF_~{%iQFZXS+2uRO0qDCD zWfMC3KylfeHepBV*_}OYt4t!0D+5+DYy~~U(SrMoh!KHr=S`}4sFN-Wdnp&oj(V+X-iqbB^*UC=Bl(44V{|Ts1g>Mq^ z;@3D-vD6g=Ok5O()GE);e%Qi(R5kJ;F-^42Lmr2pr>VeK!p>XTH>ky{xH6TcNR#+Y z_tfuKGD(f@1e=Xj@<-S(Kbi_p(ppSt5MxiM{pFg=CF1=hS}jxu+W?B)M0JC)P#9~b zNzh2E5|sdZx)FwEhf$S@nN{>!4|!aR%;kM9H_a>Sr3;)wNk;0&EkF5O(UaCjZ@ix_ zHiX-gMi?R~Fg5x=YqLe}1!NM`$H(O5JSwP>!ft(Jb2&GZG^Z2OQC{ zaZ$vhHv}>6qcJruQ2^Nf!40R_o5%OcaW#APr$^7OiY}80{N3;6vr>*e>^g&vQc=g_ z^iNX~wxmqu!yn?@q`o22AoekkQ04YKqSUgYIm}S$u#9<*HjcI=K7pj)Ig1v?Wq{OJ z#n;Z~aus$APh&|r;kaD8=p+!JZ(56e(eJ53ye6rGND#AVdfta?G?>PUu`nfe(~ zzj%DLaK?V%mnY0{QJ9u|4tNOU7Bu^T&&FZ=P4W;)+UzYOUU@yPm-N8@A9{awPXSnd z^wKEXjwRz_e#9TeXt6?LMlwONn=a-()y2J98+hS*!)<7bK(~x{$1y*Q&!5h8xQA!Ec#`S5!OWNHm+5;qpPK&ATMf?>YCDA?=Gvu*0-{!M5-5L&pNHxAUaDGR%ZCgV)bGls z4_A+3d#*dDmkhCkL3?9{O392~K|PDX%%L#)3LpiUnpD5fu={xXw1tMx#^S}^TBB{4 z6mkKPg4{iIOkbNNKkDHHdH+FX*>?{S6o0N=c>F_D{vJtkd3c%`a_zT&BQQHuZMEg| zz;eq6+PrrP`tlcazMsbSz--GTRZj1jY;4!uaFXPh>X_V|XD3B0=0|7eupV!Ur*K!p zTi%pD$gv%>T+B-EhbqP~iCv#+eO~BtTRc52F&tK1>r?5mB}Ph4E-~)cdR|jueYDs- zFgTc4G?f&WDVV6_%1>bZFD#e>H5?%4`uY4Krk$Q8z527$>CQsq4OzW- z@fD&w$bvKC9pBRjprS9`tt9=k-IM{@8Td{ynCV>nB)%6o(TZ%p;NY(zeiOLXQN^L zKhB*Wl$Wsf!DJ$B@uPfKf9v!>V9wN_eKVHq9w~4?OxI?4nBydGv`UC&nMPGU_9mC0{Bj5N<3c zu2_a{(6DY2BD$S!@D@*AHFmPu{mDd}>&>lm?f{W2qA4>@^R9DUx>Es%Q79g~Ee$5E z(DG?AS@TUUmt1m4%KF<|BM@DQ^&U~P?aHT-5ODg*&7vDRD;k-WsmasBG5hFHlp*Qv z(!(zU$*$%{dO7-7&kXXEO9yw4ZJ(Z?;)QI2+;Lx2=;`qR&N37B!zbycL6l;Dh-%GW zmd(}aqX1`-eb+KQWifz>Ymm=xd*jf=na8&|{na)RYya-&mLX41`oJ{X%H#*qo+q7> zkXSSL=+Pqx%nDS>bd9r2SUHFGi?sY$PCbo15I{pT4CZy+D_{w?`%T9j-_6(m&|Vfe z1|o6AteJ+_){H+j_)}hIN($>s@Q|U2=+Lrp6hV}Hh5bm-R<5e9e7H2ext zkjwR9jl?4}3iK@Frwz>f-!m%hrzV;7Q|>{Vq3{uF`iZYh!R7H1cjuyvOQLvf6jJ27BQMBK!Wru1mV9zn3WRe4eONBNqU__|g>v)E z%XC6+kfO>YBM;BAeaWu97sxr>Ttr52<2qZ(nGm(ipWbOyb4FC3RbQoS@v^Sys{)XdVX`5qjD-v3!beb7h;6EfD&n&&KLGVP_t|6%Z%P-hQx zcZ)tub$&;@5S#s!BtdkOu0dAGXS>T8?>(OEF5UYBlQ>@*=kj5?mo#>vHkQ0xFAYH| zoR8o-tG>@U6KLMqn+b$ZJ3-+B;WM5X3Wd%e1^+4ViEqY(ia!go?qYqeD$)LV&DpTX zYr?WRn+MLLK#$TSFa>DPDuSLQsU=Lnn-Wo*^#!zCJ({#2fyj@GWBgWRv-Y1vo$0Uz zHl3I+5B~&VX}Cb0XMAjeeYxbc$5c7KR%JQiW{_ z-i#LZqoxdnCFXDM3<=>xJ?lClxP$g7irqg;Vsy2fR$ z*X|b+bN!lffbRRoOqwk($7NPMssKGJ}t4hReT% z<=tuVo?vN#n5hjV{~!*hd%19Dj|QPvqbDFi3);lj1?G(rcFo$Lz7(w(^IHcMbPUhP ze#xuf^@4nR^!|eM2i-88zhiVZts()G2lBPfrj`oyd&XMAiKBDnTJ_rOHzw?oUSx$1 zx#=WOC*PYn2w0pu=~oE%qiFcS3b}eR^$Fmy(AwRRu#FVO*!gP3=zdgpPnl?=OUHi4 zy2l#HOG-Nxc0}TA9tA@_|LbIPa)1X+afSj#1G1!EmFRex-&();V@l{Vj4sOPgGN(C zZI3B)ue~OhyT<`m8(q&?`d9`h&WI@HTB&feICZ?eBDj9op7!_5hr@^*?;zrwO7#Wn zx~T8(`P-~mgda3v)8TV2(=tCGofo0HAyXi_yWk?FDKJAI)4v`E+TiOBpdMJG{#$2`A?dZGd($E8%1nav2f%Dt`+(Xa zj*Z`)ii7HjJ84_e-0$z~zy^*PiJNtwPwKk_TM#A*t*-%W*# zxE+2v-fI%G2kFQQNS$yXVWC^5U6FxhOXSg~!=1B+tU_orwrwNv#OiaT*Zz-?%6dkpnktZ*Q8?;5L};>B3!Hxtp*v%P3F(gIQ^F6Uyhr(qalo zXtbjQhP0(4$wig<+~yJ69;B`4-&s`GEin71tWponuw#ySxTf#9YTL4z>p02dl$JV2 zlHqhEtRSQfX?Stcn(>e(i4cQ}D-4<XZE$-{`B5GK7o6D)d<906jft_|5TshS zD(h~c9B@Y_U^~#q4QTE^n|xi3Yjg#O_5eMv8y-}0w;tc7X_}MD!R)V~43qRl z;9_JlFn09KIQ7m|V>e!3+x274B34U#=bYMYd8ur-Lbn{uL;)Htw%AOa3H>x5-tZ43 z{JG$>t`t(L5(rU2`b(9tRpgwDMe?q3bPby+Q#l^C;<#EsGWT4au$-wK(se1g8%;LO z{0~tR&Wl=p8I$Do&J#Qh{GQn%pCxYw+l&8C{EWjSCwUK5-k=>>?3eRvn#yM^ zwgz>jBuuaiBSp#`2L!r$_J_HWmU1{GD2_vbBWZku zAM8FVF0RA*c`$iGCE7nB(IEj`R_wX(JSItewSg{C7=U;)Zeywv<$-3C9J%sgs<7#_ z6VT!=hLO*>NrXyFCiDed)$W0d_!sUDW8-P`mC|v*X#3s6MY)F>ZIFka5gi*5^u;j& z<~i`pLH#(s8vebpLrgW!H!$v>f;iR{%(Kw6)B}%xv)Jf!YuvR_b~XFqnQE%lG1hm& z*M`J3DaEn>BjxC3OUjk7Q}Jw+rjDB+cAON}tSt{KDPHCn6vsvQvO>_?!ZCY56Q-CA zEtnm>#vodA`HK*dQmiYsV@EL(VXF6a}H@NXk8M*qebl9t0yTbM)x^_G)orU5-PXF9|s_-)1pC?L0myf2l zBs!;Ru%fs^V@KqOqFM=`LcedMF9$8%`h-3hQY!DYp;glGrx_E*hWMmDteZnSPJYMZ zHt%tkF@gllDa543<<|GW^N9c|FKMMd#ViL#H(Hx-DV!wiseh2cqON1cGoob^#HqAW z!|y7(MdyEgoeBjAkvu6|(LKy_KbowS;HN1!$ci-M`z2e#)0npefilzEY!Af2uP` zBsMO>Zxy&XkzKMOO54%RbnIVX)F7>>)q)d{{FVt2E-;4JyG37jLXcQT++i1AA`o-O z1KyWgoyXyLWo;o>dX}Ke-kMqCC!NMaJ>wL#wT;1VkHk3*pgxo2xO4O_vwyb+W&jvi zWGr}`&2J1BbFk%OteIGKdRB)Vm%M;i(ztFoKCltN7nM|28xokxj(3<>EuY(QTbc}` z(lp62#NKjIOa0hDZAWm^RHn)WCdyREZ=g^t9Z8k*j{^r-ey*%QxX1H{ z`C-Hmm%I2-b-N>3c$+@ALiW(i&4u7~pdabq1(LiaKE>SQM7prE5(UcCXH>QsR;YKR zT!qWmr*7>Zjj}#QT_|DZ+HglmBTQnMT)5wFI=wdNu+xr+mJLeT@t@-hpKv%q7I(nu zx%$MV3ikEmA>vdTy{T1g^ulX&rm}p#rIapQ5ZF{oZCXD;>#)JZ4`*VFrxW=Hq!kyV z)(&&TqtRL{tn~aywcAnd4QR7XAB7^QKxc2DJX(nFft?q=Kc!vw1lv{v1$v5;qtE5= z5+LAae^7w0#EYQ`cI)r}s--D+$_qhw*XYbF=+Gj91uh`-v(*e+^Pu7?zHE!SVI>%S4^reE`*cNuY74vr5G4H<6$eH zuy^NInVD6JggV+Ma=SUIC(Y95Kw&RdwN&&vFJdO*Ge4069}^)^-K}}WDz2N6jP>K6 z(aTX-`{_i|vhMyfg_wBCC94gU+5Keg7H50sF`ePnKyIqd1{!3@s_Q3I63Xg(Ud#SN z)JT$W=FrTUbfnUgPVK0NLjfc-wYEV5Quqwpc#9^_ik`|m*pJ)_v-OT3$iREut_@pm z4q)o+re}lL_EdJFrKs2bL;$aZ4TwzT;??PQn#@YoEl*~}KnFM-B(3@E->b4@dEHtD zOu*l$0q@q4?EdDIjZHiD7?6sb3|p=N*!Qoc+6aicf=P0`{5Ohkd#%8;TV0s$i=xfI z^#W&C*Ft?>`$YqQ_b~Ii7fc`5J?NVt#|BIwh3$blVa=;i-xH?wJo7hsAVI}w%;yw` zBrtpT#WwUOIMBNfm37YZ{GIP0N#1hqTf0D6Plrt@4C?u3TCazi2CodRjVSn#c^T< zRN&@lhaolPRi_Qb(rq0=xO~ttOMu;4S6>OGO$w)1P>UIG9PU5HqN?92MoTN^mDc^a zd_VI!Io2CJ_p`i=0zJVAKwt((Pv=Bzb-iIDsL$q&ylAVFgHCF;O#xIT`{N(H zEyf%!hehgEH$6*H^E9#V$(b)emt;9KmV)iiMy1*w+`O+FA(@gRxTlP%dV#4p{whdW zRQGsU(|Enn$;B%{MCt7mGTq!HCsr!sNwlU1sihP?LgQeDTjj)f;KWug7T5A?@!0Gp z=6L|k55@uE0}?vObe0`Mvwik$2Aj*PKd|j#aS1iO%j^$omgk=M^8SIj$jSH zPNx3Gng&G2ggUm$Z2NFX!Z%1DAUb+=1Bm*po199e5&VMtogDoV3}o3;u5MgmhWfQ{ zCVXk~TE1}ey?2TusJAo9H{UfS)(N>au6YGF0SBI4Dy{{35d&82b}vZ4w#070wvmA! z#U0W5!m!5Ks7ELnA@#0u`hvRi^N+#L&zeAc9*^7CM>1L-EG@ZnRWx0>49Et`KCoZT zaW#<~dUuFJdb7N7{7LS(I9O8oi)tMnc%cdlxd)Mr^$_mZK6hdvy^xMPnwryHd-ead z0P0>%0dCQwnVKH)d*ciRA}x|%zzvaYGVj)|u9^nT;@4DRQ=EXr;&o=cE>)87Kokl# z4^_a*Q4w+^SV`jnIYJ3}*_(*6HQb1Cv*MbCd3p#Iv)+m$&EljMrOQkqC> z23r|Egkcz_Uwx-`uOQLMInd23^@R(|`zOa59_U8L&kKm@a8PYoT!Kr(4yk5dFs-)R z#H#TskC^8^Mlf-&@4LsWy?)sE^7T?vZRLSt`znBRf(`QB<1bYuhk7~b?1_;f-xSpM zv4T%r2{Wragf3Ss0|eWzVZM`;-(2dO8|7)`98J_fZT0ku*7_kxK&HsqQ$K6Ef)9Ia zy+tzl*JXAe7|U6l8kAv7Vamr7TS>hoC-EhZ2hzurIM*@dSuZ~vRk1_*)D;>8qoUcx zCD9=nydWI)h05<9sX|*C$XUXTcZ_F@V^ho3Q#A|8AE@6Hk7YFD&JOl=JVVU>1bl@6 z$6a(v!s%$J)~9+})#MYEnfKvEt*L(d(~t%V@EGc9`{Xqwh;vW$h~A|;Il{ztwyk#g zBy&)$W%aa#9CPMsK|x}Xh?d&N3}AIy%`PbAruu14ZqcLMCJ}aya)gaA2x0iN9PP>$ ztmE4SHoorC1I{py!iNMq{Cxeu@PC_n<6scR+w|K=rYSY41Fpg)C8Z z2EpeSibduzgEHTfV$UOLHO<*scM;|e&|HcdNKo15IovRIt%wn&Nw`gIXa3Y_K`zCDX83;dJF`I7cE)D(V$P6j3!ph9~B2eOnVnUNC+?rFFM|7sigIZ~|E~ zS3pBYtYh)JTc9hY8?zg1Lv=*n>X6M}E89`a8$M)K7(YeyB=B#Rctm+O*n(tvV_&5> z;Xx!}CVVWrd%Pv930=0ddD=*ZU&)Mgdq^kmVSc%)BN-?dCM1LR{`9ZFa1!;Amxyap z95nNA5VKFRPzi~+TuULQ*>V?O6GLiKgH%1llf;l*p}Iphc|GTbsAR650x(id(UA>8 zGf|}ZVSw!sjb*u|Fp!WveBoFEvGXFGs+a%P@n#CUn(~LUJeQ848Eg7CYVcYQrVk$U ze;UlL6ja}bszR%w+MkmOPeyP(J}u32jJSXRZfobv>Q*qKNc34>jQ^A0y(*2>&JIF+ z%5vxS0pkJ@buqr=UxFtD{*!yT+keESIv5*h8h<5w4%~kDaz|a8=akD{L)~;BF zxqr$)BW<`Oea{faVx(Fi?)~h`PuC4EB*_hkqNgGc2Sp9?K5*`>)yY>7sNQ~h zw!gN|`|=HenZ(0d>IWqIr3bm2KKeZ?etN4?D8u*?IKtH2=a6ZNjM_5DKv|nG&eAm~SR+Tv0_S0Dc zX;>CJ6YJzS>m~K)wX6o6)tQ)A>zvb0tWxI5LkfGIDw@gpdSpC3j zff8K7HKh=>Fu_V$_flD^1U;nbDAwr~^ zEiy`Y5LL&23V-_V8ykO4CC@;qFc7^k9eAc3gw%|e39plWze@Lh4>N$hRH~KRxF<=l zcyG{h>{yEx&@Z<8rvk%?l4ttiA+u)kAy%F?m?^jieRZ1|zlM=KJuXHNT;-PK{BR^5 zs%eM4@^z7^mdBHjQ~f@vg+t5wtrF+Li7fl~98l6uX1KZWNRjk+Ps98Q%02a*M)-QC zO&#=Mrpps7I!_t^@LwPcZn03xJRrieH0B*bVj;34iv3%3Z{?tU2%Nx?)zkdjE6{ybG4Y;MaG0eB75WDbe4>4E3ESu^2x<{3!qoc|NP+{!t;B7PFIst@ddvUm(8pb%SIM!@>9a zFM}^pt%LVhkPJnJFqs;hKn8(*lCIv27NX1toZp24HWXK{Mt;iZvt}N;kxE$KreB{K zMrS2V6)}*w?Iq?v>zpzb)1_DQGDCfP^g^xEqlCtq9aUnG(n0rqf#{AlpL%O*1-Hg2 zX~h;H5;>DO=z^-`*MMYt4&<3OO4tM~y03H38FF(VrhU0n;1uXr&Evu4jC*PqF#yxx z*Hlp-3^$qE@&^G!7pu1|YU&d|A(>?s|HmRz5$Z$%hr+;f*!eNmo4xc`ynGV4kODm; zKOr9B3(e#;o~Mn8p6OM%>Gzp#64*PHp4uYF?k*-Ct=Rf$t3It{c7M0F{{F&Lz|-W} zp)bjlywmXoQ{fCfr**vB$^J|4gInp^`@e+jqQ@E}W*-&)j%J~$VY9lB175@E%Fz=I zJ2owa2LW4d=s?liqvHGO-QFG#%pcYGpQ8` zPgYTwQAqM%$zLiJ$tcC~r<67-S3RIG@7vGit-HNIh^*|z$3B%y!C*b|ubv2S?AB1^ zBS;9F0_O);3=DVd1h{mtZc-`tA z185Tg#bK&I zNMG*iwFy;5&>B!U zc9ED>Y3pY?_MvBVSiNCpJyNp_lkUzD>1f;952OSHQIbz%@}a9`8>#NZ>kgyh?tff- zf`Fm)_7_p$qv9}qzt&w-q#zR`cpfoLb9lP0-~bGV@7h3pe+>bJ8`lemoYB?WfAZUA zuD9=wjL${G!cE}&WR3p+8A|L-yxh@=DB7}YVd-m1-GIoZMv)Uwe!@!oBIJ+NENH{xk_=I6$lJ% zVE6IMc?-3!A)N&lG+@#1R6UBNq^`sfJ%R=kGMZQyoBQe4^FZ|3pm-x=P+7NZ0<=xE zgnSvk?ZjhVwDH)+k*BqAXAEtbT=NXPWmzEaoT*ss-H)(pK{OL?4V7PR(f7@f8bp7u znXi&z)T43!_Sm+fA7e)QzJ$xeyEI>XhYtCH^c6~oz|(es(n_4ts3Z&dIJ^7e`g%GW zO2D{CP^qPjX?c#aIbgPE;m^$p3L>IS2TY*qrZ5NM_-Nd5SL*>aO1i2Yeg!0WpW3Y zix+7&3R1Z~O@Q_*zO@j~)6E1ZOt|^e7l8?Y;U=;KNZXEKi|wteI{A>2lL63N(~~bp z6>Hii7;c<%5|aG4u4+8DXDKhSr62v?*07_r?iYh+IPPo-1mH_I{Cz0{!;4TaE0s-H zS20-V)jUnkB==RKQLG^I8Xea6vaY?DrU|s)AH?Oin^kAmUlbG%syHvN`|RiK};YqsF&RRgEJmG*UHAv}`l#}dYd`ot4TOr(UMf5Z5ys{K9+fC!A50+LY8!q`pg>C#e*Jfe zud()a^5SQUfUE{m+=HiB3R+5lTHK-TUhB#cYU{^>a`Wf0X53pt;4FkFodJ* zGHVHIRC6)a@d2*af4$ia@@hl~u!>9HMtcnIthLU+_&W#-1ayJX&XOBD(mG2AaR-tE zA7%H^L@*85+MczD|GJx3SlInfFstpih?zU{pr$>WoOeXHvl77*$GQJ$2geScHM;%*+SV(0-#S$5ix`7MXL=OG( zl3)Jg<_o9Dvr5b`eBN{6nfyV-q;^T^->!<7lV5!|*GP8PNzzvw_mN2fK2P5nj$yw_ zi7~J8?c&V%?N8iKac5zcyz``ou*{^KP!Kd3{au$sw6V$em2Z z@@5w53h-~ulc-k=TAa%bs8Eydgmm9=bMBACuhRNsvmFn9M0}Uuo1iedK!e+PUsz;C zN>V!866&(3u{nhp8=b3fe<{<-Z<71xEonbjN<`lGA3R~VGBopc`XyXUfquhYcQWZA zkM$8`G%*)$oZxL*aZ-I%-gt;nXG>fjNE4k8xxd9Ee5StoLtszl-zTv$IG-EWmA$fJ zg~!Ue+mr<)PT&p913>o}i~j-Zr|!=4K89}95Xn8sE+Jv&5Qp(DeKJLKtQc6V8Y)7m`3dH$-C%TgwD9$Wh; zV$|7^yj|&tjlwP`>cvjg6RENDkJk@UJg`%O!csCB1J1LZvEVK<`jcCeFUT<@TO{9T z6}X10SC$a*y<4-XrI@Cm6=-(vjO^nUqYB9M?fEH|?8%B_SR1R14*V#-Tze{;hjXYp zWq766?VhWmZG}%a!TOM`~EnmD5#JjHm$)C}NabJywQE8h+bRrrAzi4n8jlX)w7jg2s z!M=5J3FT$dx*xr;N$0}ExC+Qn)N{SlSEC%p(*fHAn$8j5lTqO2))4f*(>EbL!>mEx z5mg**O)Vmw)_?0hxW*n;*pCL|8!3cAZxtU&C}_yLHS7S-T=LX``8w zdY|=v(4OYn*6D-5dB;7nOn{50>DrQ^@*Sx30l{X9ziPDf)8l`Jd5aG=+RcmCRW8mV z)@fB{18PG6INqls(jFX^Q_>v`U~ZE4P8)^G2kxmRu+idDqyb1+C1qrI1Zu3NPN zi135CRL-5{5igpT1>~;jB~Ko^E&D82Fjt38!A3T&8K5X$QoXU zxl=$h0<5a9!8I<}Bd}r@-N=qAHNIdtRE3VHDh}I}{^V0;NB(c^+9BVoIvMNj=H_I$ zQ#d!;9_I~xHapn82W%Z^NWb!o_v}78I9eMjZS8t>EjPUC)^lu8l39K98`EaE>GRaq zn|Qt!m^^Ug79>gjZdh?D$!(dz64@r0`R-{LREq21b-fMXDDTIYYLx@=d_`ELJgQ|M3;D6 z*g=H?f_T_W7GmUV|7H2${NVD@oDj~AeCJ{i{;9|`nrWF-=wS}VFeo}{hjh{um3d+5LN~%0+1@2pi~UMg3Hc+D^e<(egQeB#0aB64dB&wHsRo3s z%Fe6v)hV|h`_x!JwyfKkXMYPf(fKAZt@_9=-@ocLf?N5P+>N7;c$7}RP^E027K<Uob*oGYy$sc1|4L&KZSjS@dDIQdqInZg!LEXkDYnLvG~;e_d2^1m*49*3DY#N%+nj$QO zBa?&0*-1O3bQmChg@|8y*qo_ea-C$S|J;UJF}ft*e+cVKhG8X{ES*gyMgSIMP(%MO@R4=XR38%GJDoO`xYBcF5aXGhI03Z zr55Ef0qZmQ>&WT#B=M(pkdLv~31isL<3oMM!CNw)Jb%lne5dAq00E})r;6#XDbK#H zjXN~ROYEuG?FX8gVz~r1pdx9dGQgwI8NpzY89kpZ4lBdw<78gVc(dEh9DfN%={}kM zpUuRt?oB*IveA~|n<$oQ<{0zDMHtJOhH7s*$(tC=oo!XgV?Cu;=bzc4wmO(Ox*Y{W z(QhXC{E}{8r4Qk79K($30!V3nl#YbI6VZ|Xp$*V8?6hcnohUBwGZ#aU*K*w@hk*fW z;zg73qC_Tcarpl(ZZCyl-pC06D`MQ^7*W+?)>I@KCB*sPf+!QO54)?UOa)9eU5Mb) z2L^<2=_bLwQ~9Z_kj+&+;`=6sXv9R`!C5MU)v4+2L@vw(k$;QL&zPFbG zX$gH4_xlRNxUzkA%k};fb6@K319B+=NiYB)rYQI)>`qrY5Ny!$X$`@3bc=2F@~~PR;NrD zdd|Qzr~mVM2HWUkDX%wp`{g2&tFkU()-y4A#_k}Un4jW~pE?c9&G-o4QF`YO%3 zRpmPbY6lUELDMrTHieElHNJ8#vnJ#Ht@^?N{Ow|VBoyc9EJ0r;4o+DIjI{ zd*o32e~knkZXdnzX=2;K>%CSeLIn^18P)9l?}ziNZ~w2T_l~FXf8)n*n}}p@m2rA= zjARp$kTM#^krA24Asjo7NXiaL*?Vt}y^_7>v6Y#foq2vQpYQkk`2BzG`*odbKCkC> z-S^Fl*Gd>_a7z#;bRmSGKl!w}fXlS)XV0eFZH*U;W3aObQPTWwdBc|R#i_h`-{V4J zImLU|x(JWW3(L|FFC7`-5#geg(Vgx0YWVPJVVttK`WHJo>Wz!CMhWGS`|hTlF6QS? z*D5+YZ=e5~x=jW)` z;ay2mXyP?iP7`O4scG76&Q1*ed}H>VL(hd#^xrqGj1fsBf+>O#!lP>;V>saubdM7w zyx1)&>e(%>GR47ag$Q)LXK>2$+#THE@I-0)GRXF1FwGGWh?nk1}R91gx@p@|w zMGft$1Rwc?AJLQB5I{EZSFh%bKAA!?X$`Ar6!>Zqm%(Pty42>-6)4##$smI1e25RY z0^hpT^C1<=ea_0Wb0YuB{UjWZday~H{b}7PQAy0b?{yLw&%*UnpI0_dy5D7Zwo9~? z(O{G?wSyLU4jQaq_v6v$n?wI3(@V0_+sEJ}lH`^&&je!2mb01Oj8~xOQGXvo(m%Xm z8x^_{k?g5^;#8QPN!JX=UXJsBys;`a{HhBa+wNca`1s0ePNbr4Mx+G@T-s^*?63|! zGpIsY9`?^vlEt*xmWw(Lk0~DFh(6(3pJAx|)#k*8xAL1fn)9yR^4eXOsr_~qzoS3& zU>7r0$v?+q+Z6o&b^$66BGCJd>dhMOOV4X671e@U3LI8zhsP}=ul;ibMyn&xVbc}(Z{BFkzZ^aJ-88hFFo4`Ohh=jqD zlYr@P!y0QHEaF?EgQ-+qVJ>q+C#lP^(T9Z>X80t~?3L>FMYu3B* zo<}!6%I)E9-}@m+p8A{BS!S!KPF%=2Hr>2#+drR4W?S~!kXfaR5QYiT?(@9i9iD-8mf@%`O)aKqSSqendxBdsrqo5+!k^od{P0A}D#|!0$M=kmYfGQ~ie)v6UW6f@Z-- zx*L;THTNGYQoeTBxDN8lvk!Z>S5sAV+J!JJO@BvxWS*bnYLtfpCiG_mmEaftoHM0d z)C_M&BiqtX+7p(?<-HDdMlW=S)bm0ga-RmJ8}b^(>^txneVOjm@5Y(;edBQIH64?{ z8riG|-AIQYAtW`dW(lCuXJWA@ebY#_#x~DQ)5o}t>~$fao80jkhhk+#%0=f5!j86a z__KBnqjFdf$X+!T?{4ItqhUomm_3EThA$;YxX7^a0Lk_%7uoWP2R?irs2wgX$@W4D zx4LkiA`%nZxBW5cQ#|s?Jn84rCV}gMVU{j;=!E=f?gyY*KtT z@Hk^|x>BC`ifJ=70bC@Pk{8%S&vGNi<@W<7`0h)|y~-<8;YU#^XC~|Q8O8YEF!b|W z{LvO}WlsDnx;GOm6_%=2(Ma1>B)ePq9&y&oQ!anhua{1tj^jB`O#hnR>hNT5*$TP= zhoEtXnF!9i#|%xz9@1FEUjo{?K(xKFyfEVQ~xgQ;lZU@V{za- zRE@8?iBhZ47^+Hd=Qa9zwk>7%D*k?LKzUDZtI<*EEXl5{&pW{x=ZFzq**DuMZuMUR zoGsh`y-4oJ9c58pJDqR^%KAQ4n{dyYk50<~QW3DHuz2@&vfE(G!bl{e@Ft0*44XeUlbh;tyT=5N?m$?et zf0wP|b29o8z00eKI#-9So)`3KE703-8vdT7Ty#oYwzGb{o#>y#(Nj-Wwj_F>eDsgw zz@Gt3&XNNPw`F8}8bQFvwB&xELXi>Y(9B(n~Pr3Wds&? zh1^mHR-l}DutuF!Dq?9+o=Iv(zlDW!s;YXgI z=I+z3lYNSiz#xBJL7G5K+TRkSLX5?UJ=%Ubwh3OjRqs8Y%^$We?KHY(S4K(Dq)GWy z$$)zsXDTCqYN8z5N-IuGD(}-f$LaeU;jTP=Abr$a<#A{yyyD{mRy`X?aTkwZ+rqq7 zJ!6>B&$ToECg>s?xNS6?<~Rl1{lX?v$7nJ?h^*g!rmU?BLB8iB*T6X`>mOl3ucy9z zP88E<7rX)ztPZ`(H`!sKnfq~xKdW{~$}i#3!)&oC)*o-vgBkrfTk`T&JZ|~kaKt~3 zNB{Ksp>r-aV^nf5=Su(Fd{klL9I+`JV6@7rp>^$d(zB zNJf9qQ;k)jbs;_x{}7cXSw%|JQYymHeOfZhQBraA9&y5tL~)e#;%2$JytKv-zk75w z9yV*wo+=$T&Szi5h5kJV$ou71e>wKSJvT>{i`%NR=b_h*Y}CWmo8|3Z zJ?6O2j~cVJfuLP|)mX3V>QaWC7I0b>HaiQd4ZU@_3Gm!Fak(k&BN*kPQH4ym3-UGP z$L!<%+?-E6p)Y*+$F<~p=O{&9R&Y@))yqcX4O9>ME6B<#8n1Poe%21g+asD0ZXa3W zE9uWZjZ#?*o4fCrXypNobT=lxO{!(lDEhkppL!OL_p_mvr<)J5m-wTS{GD#4_x|`^ zb!QhvPXI~v$bZ_O92&Wizs-}iBWfwjjphMU=0c&V>*@^BX^u|7edwvYcvyd;_w$M*YdiC^+AzO` znC0z+;UP9$`eqwbgXR@Jc(p^wQiJH&**tqA`F=hxxlLgBfe4hGUGbnoX6gWOSlFVD z+kh3e6PI-`I49Z-+TY9|n%uwnk>py?2jD0Q&IR+VUn)pQjLOI7q?We{nF}Xtl{^&a zZFka!uO!;g7$Y(FCS2VwxLgA>D{$|f=Hl#Lu*=zqx4$VH-eQZK#qB(yQ7h$r5gjjl z3UVA%Sj=|nGsfDvI1w({b&9pdi=t2iI-+A^Olav8b%!$i6(@JUle}o|-YkXX=Quxc zgSQU@jLFd#4htXt3z7)COzvsjLM8{qKp-3TXC{PcWq&8D1Y*DNY^y4%KRu_B=}Y#G zN`KOcPYPRWob!YS-5m81j6PaO@k^>m=g*jQhiyB-@W`-fnxCC4Wo(hBW`gz4a`D&} zVTi0o;l7&e#{0PNAn4}$0(ESobgGit+V~9Cqz}^np2!xS* zf86IXm1{=jYGPAKgnx9Ws9$g)1HP_E=q-jz_x6usS%0toyCCeFoMPoDQJ6}*b(oM+ z=N7Q5u!0UK-CAE*#wSr*@bhQw?dS;BY?EAo;PQn#Emd~`8-0Ow(*ufRwc7S#<`1S`Px7# zIVjWfFQcNeSXkOU3UB{OwP4>nCH2fh1@79vcd9gphdt@8r*-oVt@JK7)s3vHlx#TC z*qmFh7ob2@Oq|P876mWWi;c`YhA(TxT()XkhYTKdZzfnPm#4Codhurk>DP)+MlzO zTw?cW2W|>eYAP8dGvgLhx%joQtu#jEOYH6FZbDhZduE+_0(Y;5>3>(4oc&$nj`o~W zs5~6gp8ckM!IV&_J?8Bqh~Mj6Su^?LzFFaD*ly=3NVd*I-(%p!^^xJs2WhyN(TyBB zU#8?msol5BxyVjCvHHhhUVQW)AAc68{i>=^%!cZZi<25(y#cy09F{z&VAheNawmJRdYjPXxL8gq~ z%=(Jb1gspQo(?oncFWewkVamOp zwns?8LR{I{l-Y&k#%ABTMPVlZ8TEx~MW~G54j$7EASRx_dKBUOm!yAjkzP`#S)X)3 zuk)EdsAZ49oAc(wEI5my4-UT@^tWi*uJ{ZO?Yet$*X&1yhK;M%)auuZrJO0eDL>=L zJJR>@Pd`#SX<6LcbL+KP-TlrO_R}dVstM<UzXbwZ$slAuQKcvXn_r<) z`bAXsCjnG!QeR^eMb;xgR^vviqEmLuE%vAc<9|Jdo<&J)P zs7GX89r7m?EU)x#Q!!uNhKIu63(H)2+H6;2h`q4(5;62b?#gfFnU6MZphK4?r=kiz zpDUot&mQlJA@!6<+66s|u4HU$oP;f6CI+h;D^q{*YBakE_TtN=eQtC-Mt$~ydeGHx z3IJC^mIEI;C@sg^Pr@ddPZ|?U8E@gPSa=|cxyY?W{{zUd1aRNn$~9P#JvpQDW43PK z`DrEl=E$M1JfXLxPsPtCy>N?w5O5kV3D`-xx>U~_jVDp<#!S}Mj(VwHpFRnfx{_G3 zXy3M5_+jY9?O5 zO?kVNsQ9!#814OeHpe{6i&=;M>iK0i8uI*q%^$f1*gM~vYDQxj!l12|&ddcmbLJ!SX1IHFIql3Fg zH7x@HUS^=fEI)gBglw+KIL6<_Im^kaCPv6IbSDIf+2KpKXD=p4Ey#Tnwn6?qeEXMDrWR`w7Fa6Juv-eOT%kO?&UzufVNY88ArL) z8@O8-i1_C^eNew*E07C+Z#W-J^KNpwZo58Y;SLVxGQju~^+#ym{qPx;sDQ>@Lps`a7`#%BS1Bv8@BK zWgS3}Eb`utA0K=f$xI#tF;!|GmdUf9)EB1&yOx`O2eN(j0&hQEiGoJ(AJTrAxiPQF zkC0pGvBNbV3ovUnWFEeO712%$`PkO1pI-d^ggVCe>zqrg?j7~y_~cfIJHGiDIV)5x zR^s;}@7Q7BeR^6XW^7fah_RzgF0dSg85A*dViwC$7B3o{lC5h+uksnlw9?!0C-sAv zbxBeyPl}*6`zl$M@BI;$<;iA)@)ow?y2_@%@Oqagk@PRipPQf*hAR#;wP*cP&K#t2 zlibqHb8z-FOU7CTvvXvUr6Ro}A5%ac2c=q@B*$ zm(^K(eOc#`(8a^`14R7Wt@S7?^xRI71|9+WT;z`X`dkIt;z{$t;!6W>tw`Qg+o6&? z*>q=xn$*_0gk`4Sr#M!F_4K9Rw*m7<+heAPn7VoW*P_P_b4JnCEDeJP(R9F;a{q?{ z7ReO7(@B@3V_5&nPh~CCe{`#Lk#Ji?mK%BYqF2+f-Vk**i z6mPEDd{l$ksy-^{xXdi)hq&qWlG%ML%|8W|fu8^Rgf;Nb5obliLykGFx1(!0G%&hO z819(FsQt~w(=*_+TqWfq--uf@6aWE^)ZErIN`7!8(WB~IWc&OE>avWDLQur$_gDJ0 zU7%^-mdY!1r@Kyos-^|;Tc_*X1C=5i)KY^FeHUcvy>I!RPiesf)G5E{&*mu~_sf7% zee105$!_DS^>M&f()#R|_gS-XO1=24ms7~#O09J<1g2e%wv?p;7>w08Q4*+10A$Rbdvgre~wX}?+zaY&l? zyP3+zD+!5n>$4o|!-Fi|ujjuWFyXbltYtAP@iE4=d~Ra8e>pUoonz2Xog6}6U{rRO zS*QNP&&S)A-IytD5)xOfxySih4LOBPwf2|fgk9T;B4}kB287+qGBVi)3d_Mt!lu#|^5F%#AMXR~Wv$oWqgeDVWzlS(prP2ehub7nw6x3@(bGLexEmo=UNx*LA zkHoo^S;orq6=Oqoe4ZQUaF&oPw&dfY&$ajNnO!+x+*&k&`b@yju0idZ{U{!2* zo>$g0++orC>fVsb6tIEmzv*Wsb*DA{xPV@LjjvYUj`bU8}gHZ9O$gP$_N)rKZG-$+j7Wwunf!kvnwNTdTWS$KUhL zglDT<08*m0-jeQh3d|+&SXRPC)c{G;CN9FNQDhiZm|b9qT@{a%;KeJs!3=8^qVWZb z&cWToMhb4f5A_Q<*5{Y~oqSd(s&UU|Di$J7l^vZ5^V3_mwfL<%6C>{O^(MtdVP-!I zNi>CNaC`BLH|KTW)JmTa_lLAsv$YtoRnO-RIyQVK23rUVu5Ap5g5lQw{ z&Cb#9b&>(OKveEh`Uf#FCfv~^C!5?iHhpT51W*&K=zuLWL5S216K~3RYBq%hz0P+P zSTP;pRV5ce^N@h(vb25#}sC*g2X3oZ(nBg_Hm>9Iw_$&Lu%&lr|CIQ`Y(l48< zFz4u+&(JN;!f(}Qyy1=#(A@-NZY4*(#ffqK-Z!iLrq;dhl~IL=ZChBq`jCGl-a_@@ zs_Ke;z8Ws$xIh{%U&VJMUgEbRIGSX4zA;Jk3de$lPLNpdaA0}Jx(ejgC0rgIZz#}wPu-8#8=_WN!nevgk1Q|s_7g{RUE^$v94Y) zycWl5c8&5xREb|z3GYtp*0xcN+Y=dH5-=qjX_ZCKWgt(cAFQu4W@Wx`R;mulkmW(C zU3^|Vm^4b6P78$xCza8^?H{VHW+0IitUlsP;*Tf!aEoIob3Gh3Iq>r*g*^Vuxeh#8 zy7;;PRk-92SQ>d7l)u^=e}64&8{+Z_MHnUh>0~c8Q}PAOm-QkmcsJurZ!h+laCG?|34ZDYMo%Z-(yCQRRiR`?~+h;zIbN98*^tiDMr; zi|T<@WIv9rd87Ip!>V*AW=QAUMz!$E`;z5bzWF0uV5BJ4i=wUmK-Ai-yQHYoerVeN z4dAIlsW@tX{bU}m3O#ab)t7RYps(IFYvm=>x|*60A3wCV=HZi~m<05AT)9teG_#{m zNmo+$ECp1iQQ-=V(I#lB3sTB&!|&m4xub}&ku`k@fK8cQ^g8Ef_dY4)ihk<+8QGdU z!`0O|KyEIKM$gZVk(+FPUb`G(l<+E`7iVdaJKe))PVYiSxR(DBI7i{oL)V80k1hLB zh_%a0IIf;ub{5nBud@KF5QP=JGz6P(E-PFs(Tk?urRw0ZGudiaqH{X-GJ5v1MdR(Q zJ4P~J(0QbKaJY#BjqZ$jNlX!9s35XI0A9zgp*lK!y;_%IX(HupVD-dU-O1t8lF4K6 zZXP}M7qa$eg43+s@(cnW1>ucD=5b4?PRz*QZcZ33Ok*pd#I}g~1tta+@-AQGNO4H~ z;{%W!6AEgFNz(9_VL#y&C2nVq(Y zg18t)VHdX~p@~rV2NT!D2IlT5s-?Mkn3Sc>YM8i<;6d55nbNHX`M+{AGEUj1_=|cw zv8V~xjAQK=n_JqmGwPL_yWP5bA(L4A1zFTKPBPtt*AP})SsEZ3(Rv~mB;h&6y=*?~ z2EKZp{PE~Yqx?*5QV^Y%2hc{HK52?3wL=c-i}Wpbm-$LLVDG&>z?s<2uX0jbF=lKrTnyZ*xg zCHe;ix=jYM*SlmB-=|)@P(4^Lz^#Qk+cLG89hamnA?2~ciPq?Hd;WydEx4m|NSyt@ zNmR<&%9Qe`^G?v&LfBe6$0*33Gjz5)J3Mza$;y^jY@+4_B35L6zU4_LflTkF!Xi<6 zq^_6i5Z|kQ`wI%Gkz1eo0}|&#e7YwNI?)S^4Nu!j%`jwSj?d6zHN2jLUi>enjTh6c z<6X-TRwHQ!4{63NE(Ephn^DhsW~0bI300}x~UQQIamv*hkYK*o)& z7$Z#=EQlrG08WzT-ky7|B&r3kDHqMv$=5NB3{|9nIxdhNAW#u&Z1 zyiid0sEjxpHrBjja4)R57VWn8KB*QEX-gWoSd(Qj+oO(c0q)wiI;m z;tY$eBMMP5rPN9NBAndn-JQ`}SQMQ#kI*CpF@92iaR2!bAv9p6Q+{I#OSW4^VW|<) zMCxJu{@TEuHUb`5Tcee{3^K-1GFQNjkVBzp^7vfw16+P)*tv9Y9cIU(}r}4Af(}e-s z7$XI*_Mr0HB!;?r0JP7dLY+}2PS5Am8X8@1*_~E5TWDywwK;9Znlg5LOs6$7PsVes z%DjtUgnTbVS9+)ko9#XYw=BvT5V9>Y5p4DWfZ_DAdt!&MwWfIZ7 zho_#JB8Ex@+A({tb*SnI0k;K1ajU~9qZbhN%L>p$zB&&_u2700W5)+mITs1LTlrri z!wig~-bxQKtWJMnIOYc(k%r&2v!TFlCC4#PhHE-<#{7&wtRXwl#OLWn=$7`FJZqk- zM((g{+AVZ~^;sM%p7V$~p%j`#M()3jqPFRN+erK;>%QwSK}XnPojZVGO8*yz>5K;i zRfjR(bPz7ndDxmGE1;o= zqi3&3ckFzT-@3V4xLw3SAujIv_{c{x1~a2`?&+3XgU$u1l5%)R|ETfRE4i_=0BHb6 zb`M+^*3)cAaBv@WMN-fT+qfLOwOqTt=K#jzaY>f}{%aYhz4yySfwm{+Jq5C=*}wF0 z?CK`57yMz6T;FA@BDTP;c(Hcf#=)pu?k&Nh^11c;OT;idFE6r|1$pr=K1Qe@C$rdN zCBtX>vzL5~BrW(}Y0_Z7&r*1LpR-Lnn^9>fJkq~63>VI?&@ao<#YV~S68l{C_VHJC z4}N7Z>@+XMN=UkVLQR!!Ub&={YndNdfoUB@?3>}IGv#?n$K+L2Zx&ZFJX(0_e&m1hCqOR}_3_!tP|c%; zepyzK8nYWlXVnd5IlE+MuXwtsTxk>ZP>ob{75%=P2piFD=CQiE3y_j-~f5PEYm$Ke~?e=zdyk zal6Vg$EWvmEd%oR13^4udozL{#3{kJv-c$aGS+_IjD;8L!n!?5eGRnf;mKeGSCvWB z;f6B1cS&WwBg=F-SbI@p`OYsp>G6*t#e&TM{5eM%qIT28(|w5!(677v@nhBHs_BSSM2Zl%vPm8$?*ZTM-j8ZIP^3LRLv@TE!XtTIeBTn2|wT{^eVKH zZ{Bh64W|;9FK<|1!gRZ-O_!k)k_42Ucime#7op7(>CwW# zA<-Py0@{xM9%E%WH5wXOx*j2|za%6I{C#MPvuYhnP@x*h*{xG$Zm+YA!?&o~ z87Y&)B@qg9ww0liN~v9}^6^yIT3nc|Ud!@f$L#0DIs@QmUXcYM!NY=s)!l)Yhzb_? zzae3xs9dq3-BY+(ANc;Z zQ}*$*OGajSW!+pIwr)hpz+M8Xv%*$(L$5>|^dT6SOk3iA`TP`1%^wRNAQYDN3e#qk z+L-^*VXLSClF`cKEYhA(yJyFzY_m(&!53`1(d(Tvsva1!S`CL)DovFC`tT)Qosv5$ zlC6?0@RJahTA^~>@`GH}I0T8r_|%8wr%PcLu!21TY_x6_ccF7rQe zPha(g6lqE2Y7N|=d<~+|@wl*4HlTd9p9qRjUA__Gb0fA_nr`UL0weQu>JMg@|HD^RbxQ%-#ua4&KH1QStLxw#g=eiwJ` zg1muhu@6}n_e580!sg-AJT){BZ`UG;`_iWD*toc5oBsQ*1EA?x zs%g`h4uQJvE|W>muBMWd2CU0!Q@^x2k`x|Nr-V9&U4p|VuFLeWJcmeYBVyy@*SyH! zDS}PnoQjU^XT^ov=t05>=Dm0hnrMHNURA?kim|9_)!^l&lP(Qhe`0$-*}6Q8ta?TH z+MRZ=|9^5nR!NW_i6CvV{w5Tm6XH>0{cbSCqi_c*ZuGQpIoMg2XQUgtJe)ZL7IXr@ zAV(RC)f6^&)Sxep$f?{{%I;DEZK354a8-I}iFGfnQ15a{=UsErYIPe?hzEP2rKmW4 zLOJAnlRLIoWRHh=rIYaZr5roYWrpZ-E3oPz0+$(h{kmgRre-?^=gS6_1#9$bMZi}y z{NAYG>h~bvt0F;2oyZA}ErgaxoK8X6GAQD8T4P>UtwH+VHCnHJ2SqzfTOGu!UmhLe z(MAJN721nBqfWBPIfYt^CtL#>rJ++Lk+{KD!|PqU?>V&7Ra$xpf#rOW^1k!or*$t^ zfW}WGx5`dLNPRCfu%ffSLYZ}D00CfEn`-NVJ@&9=qGH9EC?2=fq4cQFoyjf5+TM#z zXOjfgo2rqOFH^Bz=G`705~xdTd5?KuK!uXsewuCoT2jJITVG~uoy&~vUps5Ze)8DE zZ=#3Z0Vr~!CqbITRHR2A(=I!k@#zxrK zXq*#n$Q@3!F~gXqu+@x~1NJxIjbc#KMWKLt`^KwlJ(i{=G4Z0RAnMguzLl;D(K{32 z-U7EOJPtu7$D2218-5*Dq1=$$Vj)vJ<}n0Qf8Cf2T z)nOWgq|xeDu(*ecl=Mg6wN|LK`$|kc6m$dqdWL&LOOE4xEFld(pD(rH@oz*fdrIwEIXLcm&Jkivy@4Fm-} zYl#g{aCv;<63u4#jmU!IluQBW-}Pg#*c8?vnSd8P4$jtzptkNcJ`^PN-7r3-u=I5b z!xZ+`uQTs`7D9*|640a0oYCslYs{Y_7z>>F2%=FNs(~_At|66g{$6h5&9@0^5A7&? z{Dt;D_q*Jilio?X=e?{w#Si@vc21PT`6R!6EYi|jT|at6}d4cq2@&P{uL~ z@xhZ6DrS?hB&&m&Qz|Fdkur3-3Xu+tvtH}y`j@oy$s;*^ylvmK0`OL_HhJGGG!_II z?5F=Dg#8d7G!YPN;tVs8N#!>|z-R%oBmsr?(-v|IFE}w3*jOxIz=+OofNvl6LfRJbxCnfLqyiMH5N5B9YOHOHaf+wh{X54 zA|+K3sp;ika)xjd%_DcwgEwgw6oMq&Mc81sfkO+u!g*#o&!~ZtdCa837JBRIVI?(p z?B*@HjyKATup{<}48QNbjLg)|g>p2O1WT`#3<`_<F$Hkk;S$c3uj@Z}W1Pa4pVJX1{ee;+10xP(??(`9WYgt(y6)#OWv$LT~6Q+_*X zWu83xd1CDnh4s6O5yFIEYiOxiVtFDT$rI+#^ae?A(dT;yN64^6VaDwenj?<-zu5~U zjgA=qc(6X=^|AFUQ1E+#NBJDfZDX20x|;wtTmSC7r#)WO3j*^X9>-gZuwyyxa_0Dvi2fJI@Wma6HfK5{e>(NvB4m~YO05}%O9?6moi`Mp= zA)TCZ-@KyoJ-=-RoAMA%0k=eP##+3Dc&)(@Z{-8Y8KA1pKmtD z)HS?`pq3)CL;tV|`NopVTmUlhVi0Fn=HPwGeapVcG)^d%Y+OcY?%=98^@%7A1QV{Y z_)JnSV*`Lenyt$RRx;?rU79#&%cCH05230ax}E8_1YLQLQ|wqd$`!qyn6{DlI`xyF zJC_<8M7cmFgV=xi^hXhq!e`WxV};-|AU26A8lgncgkt-KP!H!hm@+>qA&J&EP@cFe zV}1Wg#0asVCBZV`^1JylDJ<&Qif=UpX@5Lv8usgyV6tu@f5L@l*k^FDSs^Z(h4WsfuiIh@$*I}~2 z=tWR<*)x9l5gPjS2B|hxxN*F`8oT*lt{r#;1MN$|9X(^EGiUH~uOS8Y_*%={-KLjK ztSRv>VFvubQFM)po0VB1-yb8=2?^yRGEgx_r@Ulk<}SIVETg_Oi;RVt|DbpAls0&`b^Jqmb$Uovx#HE?kFpkLjav;Cu zZ}8H&j08&A_#Ny)h@j7q;QmNpx=d7P{wE&@W0sN&+Xikuxib5k?O(dfiKwfE2xbOL4OG zoR89$34H4vP{xy{V^|bWn_MrI;`Nk`;w%5qib$cSbt@gLoRfr2Z+-oRf3Bv&cjbwv z3X6vsecR%-b?8O8lIw^BefbL3uVd9F79`wHS7HrlF^{(YKJb#2-@Fqd} z3Ncos?UgMjn8~FA`oB>U>h<7Ibn7)=vjXvLkw_D@v9nC$@I@$AoQcf77>XdbD0^C^ z0rsyRhANU1am(|+d7`8+pkf#={f?Eu_jQehr28#jPEd)p`8RyPzxOksYbrjt=DQ!S zs1uuzYIHNX75LL#s0oWwVx}tJN(q+0h!Zw)K{gvrWE=HcqPQWn8k-7R$So+KfW}qU z3QOOdUtOXE5jAl~_qsLxKRxE5o8Lmz?DcpeOH3k6~k1?Vp+rxVuv-uEYy9YtjEWJeR(nA4XO>k)R7W23G_<2&^ld3oKRO-+S zk{m0p8nea)t`-&kTTJS^&uS)YNKZJPG@~>rh*QYtfY5yuSflDyTnNJs#=S!3mil|Z zwJeh;O`I8;G!9S=YJwJI+WxxKc%4Xhs4j&16Qaz>bg+8TjvjnUbk#xAR6_-_LAMgL z6kvM3pYN}Vfvz_D9hjYPPDP-mWE+gL!wiOxmHrWOhiYTpdxj&?1M?z#ghr0g5Lo{S zJZaDOT21BPv?YO{hh7|-TnF5|Hwrx71hJAU>aG;V$@jd74Fj(IqM*;onNyKXX~Hbc zpOLIt`6cApONm8^33E#Zzpb$jl#~<^hSbaj%uUff-guC&Q6D%!@6xgSy?~gb3~Yq; z@7)#f(;wmV?IVKJZ(xc06sWIDxf0GQ4Y?tJeGw9EI`3vu_RE*@#m?rrfI2j0}x}t zK&&`aG$LFkyDTaOL9Q6HSZXc-X79g96eX8Q(Tt1e0j1Pi)J?rBq{$y;YOQ;TkR!^q zWt&%=iF`R$bfM#jt#ol9w@8n)byhW>TeBS~+)mC6icCrd(;G@^iiXC^N4?Wfva>xH zB}~}f*gNWb(mAt2woD38;tR^FchZ;0iJ|(H53?&h%m2lS(=CCDm#9rN0Jed>;6Ev> zyIbQ``oRsn-u;~RbsAFw^M7Mm5lMiCTulYclik5%S5*-)9t4Wp)i-R%XcC;9+dxcp zu?Rylv|aPbD()v#h&>PbK-5$`2Zd>S1xW=_cA(Ik3sz_Y>8+zf?`U!zhLC@K?i7Qv$o8QK literal 0 HcmV?d00001 diff --git a/ifm3d_ros_driver/doc/figures/rviz_ref_frame.png b/ifm3d_ros_driver/doc/figures/rviz_ref_frame.png new file mode 100644 index 0000000000000000000000000000000000000000..befe4de790dc333c02f9e0583f440f42e943ba35 GIT binary patch literal 57878 zcmafaWmKF^(v-4-} znbT5TeO1*})qRJ_$%w(j;J|=^fx(Oa6j1;J12+Z(`xFZW`SFjTkNN7y*B3`2aV4ma zj~A3t=*MqtrypuginbD%=?kg%u(**pDH-gIcm zFTi!sqVDgR%|Iku5vwu+T+Pxl1YszmH^-jd@3mZk?@+AEwv)c9s5T_d8mM^q85=_j zP(*=9@8T^WGMn7@5ocGp!KRbN3W;06CJYyJQq zEH}BHoW%x-o1Y~tYDJp5b43DUNO2pg9VhA7Dz*FOHumk^#_!u>4I~o;Yg5=Bs3Bb{ zqbe`pt%&o`s9{{w2LR=oK*JufJ;u=!zl~T#=gv>-;mye;CjW@}{gfg~8H?%E)1uYf zEioXa3HW=KD=M_ny|iRWAzNSb1Z_O5aozm@?k%YHsj<#l8yTmL(!VtUa-_b%rUPAz zCnhHHl;UaGp`g*O*UkaQnooPA-Iuqk1+vmZ7<;A!X?ZQZy0)P!kRz8^sL6Ntd*Oq% z{{0F53#!Q%nqn3Mh|R?Yv4BiTNA832gS}xD=TGdF%06;;vSDx}S0d$Biizlx=V*<-6k+{Z>gKcZ%5FltZG z>EckJx2v7pTEj*QCNO8_YDK=-JPACBY0h8Cn|v>v)A*7fBi$zfLq@m>Kj! zwYdDkmpr^4T__bP_8SO6;C~m5ZsUsRrpBJK`Yg69pjt#2ZrVtcHqceC%a^me7XGJ@ zR&;kQ;rOc$bf#;2KsbLM9eqK9JhBYZC|_wJaYk+SF|z`@Ii?Gv^JZ8kpx z*?`5R%e%}$*A&s}y1{NOL1pPGd!S!t!Cz-mIZkpY7Lmr9&W7%|YhehOn8TCFysaEqg6jFoAfi7+4v52Y3^-u8)&Z7!ls}Q)3sC8r*9Bw9qLhpXWp3(i$qQ%$Q zYK)bA$d5GO5{gqwpID=A{lB{1;lPWC&WC!KLV#PS=J+ICzj!mlwChAO?y*RAnEi+> ziNwZD#)e)VotyGpi;h6l5dT?5l)9_wa@7TuO>8<}0wjCzoZC`trt;wuh}@l7DA)2F zFB>T`5gOg(7BF?Q%Op*!k9Po=3=Zp6-H)9l{}T`TTBYo>J)&iys;2#L`tQ%ffsVdN z1v>lYD-9@|QgH>M7-*Ml$tIlR@)0@dI*cKtUxn?8*TOE~9Sjpn(c4qY@)vV8=@Gsl zyQcPUzKn#afhCY95zBviP0*%McT1>B6XXeF&`YZ1%iyC6Pn*beh%DLZ03lu&-(27b zKQh|hNmO8g>T3~y;JW6tNO}Rxy}Tk%p|xcUWvvZX z&rQ72g~QoQSxZ2)TO*|4X0Jsmyd9^xIIfA~nzrpMP(MW-TLPj7L0?n7cxImE8VBY(cHug|hEKR0DNZL&* zhUnNVHob{N3*Gp?vNR>y2)+t6Om>pPGHk3)X5mg2@U7$kbr~ zf|H%lR~=W5)?H+N%~(jYV7<8-&3F9W3OVmp=O;0@4R7Vy4=wrV(|PEW-M=u5VyR4e z38w>?EP_b~PA`qS!wPyZ!m9;$9sdu`lt`((}V>JUFs^i<@@a7@*x z7QF27mW3VdaxC3>o6gUX9ht!D>q=D;V@ihLbiM0j`Iok5nOGHi;zjoIU8TV_H0H$} z<#IC6;VXE3Nt`w;mhf_`4SDozZ3fH32Wr5%Q|l{!_(l59cfJf4Czm0J{}adB=vm0f z%!u%N=S#8jdfm|89Ekn4hZW(Dn;2ECMwqWcu379Bvx`IxdIF$*O1f7l-7yUNk~wk% z*@lrWuy0?Uy%MB6RHR9rHaGDiiUgE#9RVs8KT|x>?PmRO908rKYm#}MInbP%zCSh{ z9?a&j=;*P#1J5a)#3MY1@<*ZLTv%ne%OhPWQpIMqN%V>4!6tZboPTRnijWqjMfA`;Bph>z?OYtc!8px|Ub zDC_E2HYs!-Z8fOwK!D4AIrc11+ucr zp{F~-D5Vf1WX+f|h8J-A9A(c<Y>rwmc!CXo7tVa ztcz=ESI!?}L3sVk6>Xl1B{1?xW>&suI4u@G|5M-cT_Y}>KqlYLO~HIpl_~!E*VD;9TzrQYq)dE1j}- z+zJ8p0o2RhdCQDXm{EUr542cuP;ro1mY&h`fAaA@W}Vp8%kUXeB+;$)%8lTbi_3F) zErU1ch+Xc=-l)sxK}UxQ_oMZb_(ea}?@a%4#%ltFrZo~XKyqX=(u+U)TTh?+MiiG) zZ~J%FPMU)`7P1a1!p4Mo@OqeQmNG5tgB&Wg#p%zkhEw9_7Je|!fcol@L` z{}kRH=OkD)$tNLnXq2t5fyw1X)mohI*L^*9BY)(+&F9$Z{OdxC6?&JMEm6{7BeP}L z6whE;b5wK4ipOvVCQ?wB;%&b;*QOaHHDa9KE_l4PyrFc%`tA=U)Dcq5X01$2WOK3D z&2Fg}gT9|lW1o>SX&X;X@tv`g z`T8Q|s}z02CJ?!r9`n$tBp2kh28m3_J9Y>gpreKQ&jsG9_Fw{E6LfoJD-JTB+| zqZK#Lxe#t(ho$VmOGm~mJK-(Mf*%nZU@ALJi>D#2vmtAL*;S}ikQ-~goO_dgZDbg? zTcqz~dNAh%O$Lk??^xXKm_BS}B|{qd9Kkgn-@tWW!d)Ms z*>De6THQzd{+ae9D46JeGZrLF^pV~)OwJBZ;ru zi-#i1<#9Y6QqdJuw+*b}&AK`v#Vx^xC)a|ALmO{aTFFs`|7;ae_GZj!YLHROMfNv}1OoNUW-@>Ln@aYjeHTyp z3o9WbBJq)b^X2cb;tFK{KC4skQO4!`O%wx>zDxd;{GSf}gNu^N%IL~L$wycL91S9s(f0O2#-*g~C0)F>cbo>7b^Yu9Y&lxZbRUJ9x zUzxmq|9Q^+|H*e6TT@u5_Ovbl`RV}aod|Iqr9f!Ebyx}73{B8tH*#ipPmJMSEnuvB z=VKex1-srn#y-nv8quQ`xVEUfhCh{1J#tucuZ% zn-2b0k9^ULcGkB%2ej*>k;#ufrhnBlJil z?OF)cJszBVm-`yq_C@@CC4cDfJgPLDdjo=M=BX523m{RWcPD?~^Mve7g+?0P_|;~D zuIU+4uJ+W(WleemTY>a$?-K5{=rgFMbvKika9_i#duMjr+zD36-NA|P-BJs{v%F^K z{77b7ymF`Ml2L{S+lN$_#R;A&$0f_Qw(d=#l+U|a(JpmIoy6o|I&0R_SR`Kj(&5(9 zymgR}7VF%~WOD!G`ybyw{{RH&XQUvhZW6ZNlio1*?m(X^1aG!JhA;H&i zEgvp2ZN6_>MD{8u!%Bk_z?PJ|)MSj+kMblWNfA8Rl8otA>GPCoFom0NS7&UXp?0uY*rH8z|_<|NYk_{zK^kP zwud!R&FafgK5BnKyVM;Gul2LJe7bAhn_8`T7rD7)F~2?sjY=vkfrl2~&^X65z><`4}c(7FgVn$_4wsHi6df-vG+2;Jy4~&kkILXQ|h-51cIa zvtU%Or`|I27_iBV?^x#@v@tv4VSGULR^hSY+gXVNmRcWSF@gQzOm#SrSHEOf=Jv|5 z5v>CwUJ6@$(4xbXbN^;UxlzdHqIRkq@qU}K)Q2ia3Js{u8@sAB zJ5S-EoxZ&jhhjA0q>vwj*dOD)2rkyk9C0)S(C*`^^t*R|pU7wpsV+f0Nw_cLEgo!_ zHUwZ_I6f{TJSFA_?$Vd>c|<%9pt$8%ab=WJN2Ov#RlLR3vU1CJ9Z2(BnvlGVaUEod zpWl-N)b-(;&aYVhE~JO|CT@0RXW9-Dil?{gIq?qRyheMmn(1_oG=zXev>ush7*(sj zfdhyA(q<{${4XF{q*@N=WAhe0qS_3yqwBDnobMq$46#n16ZBpsD=qCj?>KHdW~Czc zX9fsCV$<2o^?eiLX>Ip>`?pcNpr#ttouTk*c6MfSpc#e@_h>*N0RKVQRYjxi(c9DX0C$5gm1sA#vkvcuRv`i&w7>`|PZPy_ zV^fbiGg)W;Ql%ECj;Ogw!?}?tpid15M3|{_xZ(}|lw8b0!^0ZnmvzN428I1|1dIj- zlep3bI)qM_6yx7u*XO&*?L1jZ0b{mi#$doicqp@RDc#NDnd2LCN2;5_O6$`)*7j71 zmCJuY61U=P)We^tboqp@n{?M5MUI!uo}MB$Qw?2?Q2x2vLg=ADUT$i8(}ib~^~S3> zJbQqPd_&_WXZ|BxSn)IPK8)7FP<&*`59KAeD95KhBI6^DdJ&X%4;n zoy$)0vQe@=TaWVlC|sBQ+irF|wKFmCq=n-Lkx2_f<5;Fta}^oWq9k2tjVR?<3b~}- zUug?;N8ic_I8&_4O%xx;c`cHdVCfy2%ozC;>?;-0Zc^^<9qm==?UgG@(_|mUB)k5W z!relQ=exYK=W~Vk&DGq5Gy%UH=egopqV+GMcb6Zo#u5Fq$TAS{sj6l3e)3hlo=!b2 z=Bm)q65$pyo!c!@2X`&z%>Keb7IgzKQ>yKo%iPwm6~!Pzj{q3=qyY+riC@=r2Kqpl zI-FlRWC|fz)2EVL$WlXxNNCON7uDGeAsUBe#PcY&MEF&9 zAF)GQWl=<15t&Pb2)s5x0Ws!O!wYiBB2{>2UR0sryB$><4nN&l*n6qy?WmE)CeGY2 zeYI{0#@JCT?^i_PuG*{V8mc*%i!#`6MQv^%0XHn?*P!?e{Hgw>JKMc9hLWL-{B z9t4j-r-N3ihC&z~Q6bk|G2>dcnVdC@dQfdLN%(?h(l^!}&O@5IU8MR6qN-q_it-Nb zDT@DXqd(#D303b{Fe(|pEVVt6oDqj6y`6FfNL}DHo786e+SNDP#BT6pq6&!28v51Q zPy-YoQR9js*5w4O@K|ap*;#S|uEii3^v@w5)(M0g6`<+O9p#E`Y=k~1UEc<%(eT2~ z7#-<#TnzLImsryCH~41WsjAyHILQxd)^Ts={Uph|DaH0A;$E7$aDLgg3IMb zds*n;E>J{#Kj}%0-`?K-PhzVhF%ltasM7Z@OGY9jaWDAa+*nRX!6d5LeF5_C@PSB# z-|>^M?}>z327u%Pkt^P~L`tXwpe@Y}gJtJi32Z*O+km-wHlg8HU0du`5)e9bz1 z>uY}hMqjVK{YI1MJ57pqoQ;jLqfHMF zmq92(ZJH`&YTfszi`Nei1wX@<;5^-eG9Bx8m zHZU+KQYpt_WMovw2Yf6*duB~9#Y9mhgh&LylC(2L13P)but7~TVUaBVAiMKL0 zho-8!*k^uy@u5~2X446ygRvB_yNmU-jdsu7!^5Qhm@wD=2yEse`3p3&-lDb|`4>V~ zb7@>b-pJ@^Su#r>KAMX{)5o?-r2>hm+W##47)s6$irpQ$6m*Y+Qg>E;1@SN=)r;|Oqo`n@0OI+@Bo)@U1 zC*%O1wcd4_B9Xg6F}XE5_Y9Mu1aHoP49|OSlM?3+gUCW(o0oQc25(|~B&D8r9GTiE zX3iVJlF@i5^temmsv&3CxaMsUeG;1xOq|obNOs!_uaoHL>?UCujTf)5y%4sCOPxKt zqP{);z=Er@Sx?R2cHKER z7|7)HL^%WjccY8ds=s?b-RUn?>C>R%VF6UgwvG7{^=5ft_8awGg0dP*k@sm~ih~@|ode2;_3D1X(%6S477HPrqTG_> z6#nx1;>pirQ`sE0qs5AaO+K$&v>J7KCv(L-J}=3T@HkaIuO8_c8ONKQ{G*Aq!j+4P zReIfMi#eakg7}TQ`wE)KGWj4BA79Ki^KUBo^cNT5L1s_NZ6~hVwZr*W4fCj8APP^q zAOk5?5YlX+^ufqHZe@L$u8i%|Jz?_I>a+adyJ~Tf6eB2dn5+|}r0;Wek^OX8M6$5V zC?5Tysw^U-;gyz+^2Kmq$6NCHMo(P~>d{nhg79g}Zn=CIH1tk&4xI2}M0SZf%{F4C zz1J#=&xKA3NOG|1Wsv}_&WjUccXp5mt~UGONZCt8Ld;4H>HSQzFTN7zdhz(j*;@`> zlx;P6eaUA4`28TAiNG}p`#S)Axt+DLY*exQmer^39b~)0?@4=`CsWip7iewz1i3+n zE>#d{z{Ckh%7Vi{Dl?B%Jp(hEj$vExRYIlb)m0!kj=fbAM2OQu-oRBHR`?9BwM!h$ zod3g66t6x{V^AjoHx@N*No=jzE4E84CONkHw(Ju%K&ec~CGMw9##+`%L3_mcI0mi3PG1;}R@3hwSWGgR_ovg!N&=9q_gEBkhPg&9 zUO&t}scc72eEDMJwWduwFwAz$1QP9LaC0+D>&Mq>-fdK15%nqdY&*2F1X`|Mm_;4_ z!`H*_C{b!-<`@W8Vy^&Fiez?r2+28sQE)|*6O-+U*tJZ!IrYPh0@y=#tvOuc3D9+<0*SpkQ`QE7R+2sS?P&u(zHhhBoG5)fAo z_I=}(H0K3pzB!}4)VoSqRhC}d7HE?}g|*-aHk`$54-`*z2E#&zgHaH>(oAa#1=l;_ z^c_E6lzn~J{SnX2m@Ei%U93bhH15r(ohjlv&3~B+(Wd4&!U@o@vqcto-+u=-amLa5 zDz`|jirLM`E_|Q79-P96zjo~%UIy>nDNpg_%jv@*Wax|`URYRATSYfG@^{U9{i&?{ z864bvrH=B0wB*X?iH1$Of3S1Ao ziEuWe!|4?q%};V=+wW?2JZC}7_>R`#d3+TjI z&9}0KmF-4Y{j{sWsPx4SXYxD*+tTsu9>%1H8~E)RgJhA2U3|nYv6CnnoOoL?qH|T# zMCVF3BM@FYO*h6W_GUlZf5lQPW$3VpTH^NjUDz`iu?cGH*YrIg=USwa_OWG8KRdU- zrjxm?^xY}6TE_sXrWZa%wWB7l%ahK&Li}{Y$m0hwBO28%lRNwvG$7>GC$L3YomrIKtNkep`iTZiaXvnS9Wj)5{8c62@$$ygSTO z)3(`Vps9Za4Wf#;D*koU@%`erjyG#GA|fIIni8VmV#E-I{u-$fShYmcy$!>%jH$Fl zXUo~5RSq(zYvO|;J{hv|85Ws6I_<=oeQL#0aq^DjYfR51r!IrjB&Q6obR}*Yih?Fg z3hCn+<6^a1M(qwzMwX|WjJ+c0C zh*tys-N=vWpXSo+IIcHnd+$380Ge+z;wN<QwnwKOp?2?O`zNmEfq_w;<8Q!Nv9I3E(MXnxe| zVb8B-ro!n9~<%w&T*F#k%TvbZPKKjUDCcT-;Lq7|n=Y9EtAIg1bLJGQt!md%x$oy_sV1r1KD~xIdb}#;oTlR!vvHCk(F!jrwyA23CYA-1NrG-CAVbfQ7*Q(e%xU`!y8$F<~kvuIA zI;Rkm(ZGz~!yVmp)zp1zV14Tgxke`kyF#nu{#9u>rBycaNR z8@A0joxL>E@$dqn8orD{w}a3w&orPuv&gVyR43--OA9de4iD~Gy2y@W^3ZHgea<490zE?|$ z0IiA&21PJM?#?%dcc|35^pKe|OB49X=!2|;i1!9~_+N?Do)Yj@6=V6XoyJEV(x%eP z{8B;{_JcfPFU}tx(T8U~TkO3}LHMKgY7t*|nsGM=`s)MrR1)Mh2joXTqm}b6OV8TF zOHLlUjZ&>qg|;dHNKY_Ubgn~`(BGs=;5VoW)j91;lCuxFcW7zqv#7;W1gGL*BX=__aGOovcJK5wXG znxR?VupAL?dQW57XN;OhXrxR}W1gR%+dDh|kVm7T-Cf0zmXf-mudSfLlaeNl!y7pHrO(7UVf}<6 zS~{~dnAz=sX;ez!0^z3BI7&1LcZppI2KAO?QeWkU4nE^*zVug9LzZCr^yoTbIuh&h zFUXz*U&0>J@MWoveV~-uwS}I_cIAUxsI|J#y12M})GUHOL%>Ycn#!i9r=uKFDi**+ z6Yv`J1JKjCU89EM$Wig|q&}Dl7N3_}j}{~W1pjAG)e$FLk=bVL<}5s3CPxXa1LQ zE|%Ot1d8%1+hwt{RYz>${$E%K6YkFG`Cw>cj>>;@=5LZsC=$!AZCmO2@~%(1?%Xj! zMqOYdhglzoS?9-dAj1=M7oo3x1OSJN#IRiw{A(3|~GS*o+de%V4MQadTWWSZlst`qfB7X8HK|F%SUD-H`koB} zaZ0UO^oWJ~n2NLm4Hfg#xx4dInT!tzxMa)w&Ns=c&%~VzY|>;rAODESl9H5XF!JmP zRsj@iOOz5#jRkI?2pfjh~DI$c3 z5Qz$+R>^6Lh8%ITb3a!x*{hU2B%5ahA6d>Y`7xe<##vry-oM2%8qEx*QIljY5DBv& z{!3hpM!iVhIvVcPYuR${IwmdUdeiUEo@X<{UEj7UP+l8C{wYf0`XXSbPm4MOe|y*8%c&1f~sq%o?vc3i2 zD^sZyTKVC_{Gdpw+Ne8yMZ4&ULgIl^Y@1shy zrOLdA8M3C$wA)g;&{zeXO5XnQi8@g(kwqU>w%TyWn7nfKG;2D)A5t6*LHPa`Kf% z+vxIgS^>c9D_Ocgzl@nkfFUyufKQk(4J4Wb3({T7rJ3Aw{ku!g8e zlz{t*^@V1%P)h&0!g0+5FQ7Ow$}WI&x|-^U-u_04MrVBF_b$Hmz)v3;)e5bYB_U3O zKB$Rw&fYfnTaFJ&J{aJat|lG`Y*p zET$_pZA!*oV!R1mcaQ3vlN;Xx*p}-*-Wv#Fj&`?_tM2rQN7a9bFURv!H^{R7N~J{m z%Vd{PCfLku^$#V8Y{Jl6kHp#HWVzY~GZ55+ zDC|O>A;IMbqZ}kPBS!YEbv#tImalz@U&nP7qwqL6JRfL~k&)LrywhGlx3wQ7A1`lj z)YG8^YSo?X?e2QZ#j5)H{SSV#*6jEd7ZmIHmd}N?9;0{PyO<(=?Dt~Py@Tk z_l2XezQ0I;Xt=tX=EuCk!HdTW2m5_Khcgh)!oRZkD7KBy-Dhl$WKy!t&PR%RcDJ^s z4o5vCHbi5lSP_$pg)Z3g#*-!wIZqzqhx`65p2ZTh4=yJlt1*2?!w${Fg)9)8CKSNd zVTUkpT5Y~Id{9BebVMXy0-(%pYTE8WB?!Tqk@rzb*C_#?!5n=)*_^*7=S0OA?mDL9eT1z-I*n74(9gEyL=p-9T4YDdeI`9C9BgtNeO~VNND3Upz^Ca^& z#Oo(yeY7X8>UDp(8)sy1??1&pmUxv6=2n}%fLTLn)%%3H)MK&|YyK`TlU+!f3|y?D z8@zHC=2Y`U^7f${$i<`Q69$%e;I^LB6`7BdpRzmD+7j02u5|@d>#(Hi;Kdm&lK$t# zt${;!i<-q;HZO^=Ndm^BOVT>u*ah#(m>z`arT1O-JJLe+*3pDzLD?cs=? zcJFpFi?>t1uZV2zXWJhBlNoWC>AF}JrCQZD2v`iG$xL2o?|>Z5MjNFvwd;K2TI11& z7fjX&@*KT$^B_okPzzl4McG>fp;Ppz>1Uvm4JnO$bwhpd6nS9j?>*k6v0KCZ@%4zr zA7l)M^90`|MQa?=Vk}TkcXGR|l_BD4;8s~8gB!##7xi{Q4)2htg!~Q^zV=UJ!V$&_ zHnhxIZ!vV|!kURlbOs;}Ov_t_pvK3?iMD7!N}F2nqA3i8UdI@Sj_hkioz zN)~`-<_!(E-*W7K?%0&w9yf}|)7Zc6j83O>I-0FDF(M!!C>6>1cXbJTWF=QuSJ@w# zM_@?E?&alVBCY1pbe>qrsZv>ue6|^5P3ILE14_z4kdpMzL5nn?;`5u~1 zErI4HPeb3*$P_ zvzUbu)AfSqcU*A#v>s58V(YOY&lkm>Mlj=Q`*yF7pr_C1JaF=|t3Kq&U$%dd(i%*6 zdHdtjFD~Rgc1^6x(2_u|YC-r+P9hi}p{{3g?q~X7wUkCWhMP9>l@f+T2Po}0YksX? z0#Tv&c9sHH%pWj(epqX7vA)=9LPf>_`YKnZCc%rRBOm4V%Jn|K_*QokICm+#8FEuR zhB#=^Wf)Ns!`yta-BOLDa>2&2o#|iS)_s!_sNT&t_GW{r+++YHq=}h?4Ij^E60&AYl6X;bXkd519|CRy4$FO6sC#W@#iib9@Y%cN}O_3 z+ZB?*AejlRSfIsI7P7pWoyxe}{4|4q0ZBY>lhe|2L<9SE%Qob{BH(?aql;23l#$O7 zg81gs#~v#Cad;xWpJQN1k)yAtZ;b70csl3jgDl|@#}6M0FK_ZHf!K*jRrR-BUgWG$oNQq;ACEUBh&MY%eLd*k>Dd~30R zfZZ|C8eU$VfV0|3Ht8>+o{KO66*B8Dh`6w%iQJS%UiCKmvdefDI|PeLDy<^AS?tNa}G*)jRIhfZsbTh zqc&xAAvX{9WO9kA5c8SG0dO=z-QH%@7}I7meQCCnBjHo^r~iC+u1ADJF~nuk*kGC{tW5Jf5!6u z9a%yQBtD%MN*Z@}{@6LDK5aRF9W-Q%K3ok;3wm1&jxEN|3M45q6M(T~9Tuw=;=;IG?}Zm; ze5nHyy|`E&CzTdlLHnszY#<&5bB-;a!;0@?_VXCIR{h`bZK{We&|lJ|9Vmym@0DO|QKD+y2nuWp}Q; z_llk_M)IjRa(!jwgkecg}u=o zN`B~!2k%P%QF58vxklrsxSGY|4yd*{t_QZ{13Ce^g4^eKViGbBpjv*09*H z94(}S)(fX^YdJhvX#pX_iWfng^35*#FE9uFM#nHFG-H#4?&uf%bvZ%-u^gSmlS!X= zJnll_aoMImkk&_3p9Mb^`{FsQlP!uukYiwO9%FYVMY&=~5+MArwO%VDM5qZNX-N%* zNIC|lw)jVP6U-v=RDwMO*@@D;KVy6rXi}cY#mp~$R9o7eCr*CivlywrS>oohDv%IZ zW24c)?L9)LztpwB!FMFR{#k}Xw!)r`%`bBt_Ik!sSv9mn5wa$K*lk6neVCkALxCuX zxn)VO0v~ZtCnpDPRMC%T1TsM-JOIT$?zK}|udq8@X8*NH>UPQ8 z&dEijy&(X7RbyLwH2T1Mm7)CJi0`6|smPntK~2Q|eMdVT$LUW=2;^)H?~$errS8KU zzvm-9!H;GLJ0SaNtd++l#8084A0Cx65D;IeslGh`AX;?rtv=!!IOpj!c%whft;zFJ{0v*q#eX%>7C%h ztr)-+bfiYkSTrp=*K*)(-j+|VWgDjnH{uvp&u`vG`^Bk;FC0Zi8N6c)_>cn~9~b_< zr~lM`WOP);!A9Ewn=Tw`i4WJo>BMQwk}wA^Ba}2$OfqcSMIuODiQOJmw|4#ST>!_+ zeYRE8WTtFv83=JaZvE`Z_-z))u)*p73LgZi1 z-LKk1-23kZA-`ZVo^$!UJvLD}zedr=K?fhd7yw~etADG;5p0EBd0J)`Gg!#C^;zBkj4o6z7A)xK^T!|7(E96@Tzvh9O+8&x;F}G$)^M$ z8WMJfxU-KROoUjwza^@eTB@ zq0qP~#hT^#_3c2`ySalj!vFjj%PlyobSa7@QyK5})CG#S5@Ya7n##F(H_gHOq2w=H zXfk>({C8Y2_LK8j1|ou9dNP!Gv{;>bqL;7>XUii8+pJUpo0MCwQjg8SlGyK=^_(`V zPTLc!#6YVFr(CD@6y_Xr^dAcmcbV68if?U^%XwcNoK{!{oZ!2aO?S>ZtCJ}SF64LJ zD-#{dQw`Os+TMcc3-a@0Qd0qqjjra5(W5_B?_6};pOEOsd^0?KKPQoayVcz4tpr9K zoZHs5y+0Isfo7;s99TF&Y^FzdL=nYQl)e7`%m+71mbTZgwXRI;V*PrT0MA*MFP!M` zUJe(ppLMcyTA_P0u;M`@d`5Z%Nip_Rj1*Gtaz_%<7SWCYr4{kRWqAQD@?EeKjOS zSzk_n|M5N1RP%lRMSl+Y1&`-7HB`9p_1UX06rG*iM8nwl*HpK9%PE_0Zwj-Udg^bi z+Siay9GZ-UW%e>Ejzlzo+-xdYoIcbyVAenjk66HL8A!^vF_RU7LO1SbL0L$7F7 zK~jXd@qp|kolomLXfl1z-h7NvMX!%6jlPM(9rK~UzoXCNT%}e!3p+>yWWD?l3X;st z%hPz3(^~h~C(16~KOW;0EWJG&-m%iT7=-)|s`8d}7Dg?tAP};7xV&FryfoG$lb>-b zr#NoFlhzUhz)kp$Pr?EZIPPs!efCF2fSo4&M0T+`%iAm7Ff(2o5`KE$aQl5WULr2) z)gb4QCEjV){RazSy!%n6_P|O$<}btcN~Hu|29`E*mSxl>E&83ah3PghXw z=!-SX7VE+EI30vinjNV7T@A<{Ca@DXl{-Z$1bu-MzEn+jylrs+~>|d4X@?m7}qY2XZvko^z%<-AZ%VZl?*R(kCIaF zZSFnO#dFo~^p`JL{4NA%`<6^CkmzcF)4ux3jf>rjdWy*4!Vx9f(l5JlDo=`_9hF#@_yltWCs@a>6gf%g$P) zzN`iwwO!8$;>N%y=)|C88zJsuC-myoxffm(vRU}e7c8Xe#}&OFO%+?@(A8)nnE7<< zBE~H;Ht;MdATP6rMP;JxxCsXs~DM6GCk zvCR_BawFO8Iw*;_D0y(NY(fK9)E_mSwsX^|-}2nGCr3ya^^H*lR`$YA4@_0P@K&)bkwQvTJc zMG^6;?sI)d2gnZGo~+=pu7@_l{2Lqv1Lh3Yc< z63gc$G?sL0mIXF7pz2$fHTUgE6e9n>n$7a^d9-L8H3o?6zp`}mHhcvG*Z;({O}9V( zU;i4)|A|J;zx|&R?QNVe$pXy(eY<>FY47+r0%Qnf=rn;E3J97NIN>0FAkazVe|p+t zv5G7uRRRVEhVSCym>3xTvSxFIAkkWNI_UdtFnD@0=O2mid(u*axzVpsf)HAlv_D>C zo}QVhSgLFKF+M)t)YSBmn0WpFbL7ow`QBK%R;$GSuH8~12kpPt=HGD1O|%-UEkge% zhXtqQTj5N>BM>AW*BQ$aN9V|837`g#roxh? zKg2q55n%DDYBcq`6cie&DlJ}(IL@cpnfB?ZTC4qSWiTQZ2}yK%Izev;TGh;x)qFXW zdlkZ9CAE|{QpCZ-8{%wSbM=J>L~U1Chkl@a&?=gN;%==A7Fc7I4hKIl_W9_Z^axKvsJhF*Af}Zv8xS{Oc?4dIYl5A{BmA_EQj6c%f z_6Ys6ySvM5y~w1jQZe(?8;oMq?GL9KB^g>K7nDDmGyH)a9|igZK~pMps|NJtB{7*Q zRKvUVzs(&twY=C>M%sYfKBXLmb?+{F;>pZ4 z6+cZ+{(fBdNzO@v`9ere`cFtlG2`FnBsWgt!z}5v{%kSj=y*%~u4}Q9BC~NdbYv3N z+}ei0oQ#X>z7|B+msl*lm*34??XioQC{gFkL*y9%+uq?Vm#SOEC^IbiQpV4pvmj?` ziRN=in-q~(4mp<*Sb8F5v?NTuvnE-^f`Q}Rc&|BY;qY%%5J+C7o{br}lN$QEA&epL zjN{~riq)A3x#MuW{T}CaOumk`s*{%THB9>(ZZ3zjh}Yd`Qd$xMGe5e*SxKttqnq70 z7N{s(w<-xr0K>m6?Y5udH&L153SxD9kTM<+?7{V8*cnh*OPODWNn(Av?_5OCs2xGX%8}KW)xGK1YYsLkQp`zQP==g}=z&Uuz-D1UL}z*O7|gfWz`GkZonZf0y!aBdp#b zSLKQA)~9}!t6DIkCh9S#zIzRO)nV~rBI|eVmyO&%6O5KuKl~2)?hC<99%$eaWEnUyUeoiEU=y2kI=2r-I~Bvc;X3McPaV+Jk&qU05u#o+cljjJ zV*i|S5kaz+zUd!Oo_dGj#95G=OIGeAu02P7d%_*m>@0wE5gSVm7E5>SHplSW?qu{H zw5vgN{=^)+LK%^7#>#7r5;e$9{`aA0Q>BndEiENy)QsY8r6xu4*!Iv4LFsZa_Y+?C zhK2t1y<=-doGNP0=#ROkEm^8nJ+ejm!;%yN-0?$qI$R1S{3h@Lnw4s!*^Ga_(t2er z6(}(U*MI);$T?tW_(N@FQ`Z6G>Z|K%s0d0&s+nHqcOZ?Rs`wQ_=H^8=s;EQ^_iw*- zzhI3{`kn3iwG{U0vf-V<+m=@M0_ib~n|_=&t{a~Qn^g(b4I!?E17Y!f_NN*f0*6Kp zQu(*V8icEU7{D3?q8^u&1{*WEBov)20BFYNgu$l%pHW+z(j>m@xE(<#$Uh$o!%tnJ z3v&i0i1o}*bJ;2hc$ZCXB&*K^oFD4BU5g>c1!gh( zpM;PE>GyWX6;-+#_@7%^4FoP2wI(#f3hB9eUV0&m4TsWJT9eH!;QSpYEiDdN;KE*3##P1@^&(7!`jV~SY|ZB(*U9kh>LhNt@fP= zpa7veY4C;`ZtZc9*CN(bJZYY-v2m8Yw$*zP2V{y-@!ket5w{gITFUOYHm1c6FUz+h zj(z}Rh+bL9EC81EUHVtaZfoYx2ipsenHUk=lmR{&n)X z?Rf-&ug(pQ2myINcuM48$BwG^AOHB2d7?~Z#EE9y&4laqsjYhy2`KeW5H37y;9kMl zW?2s^cgbzH zx=MIev+I2^atO{Wr%3^GVcUrv?S{J*=xbk-%a}Oucn@u(xi*iQSe#k;?424~N8Pyhe-Ppc%kO6Nn;sD928fd@& zGl^c(N{kZ1-*g*Y(wiSgVv!dmbm+xsC&V;w@S_h1`4}JMe#9;5M@@4*S$0@MVw^3x zfC9#O3jr9X2Ln|>NU4Ba*wPn;lvYXR+`2~eWq}BH*iL0yHO6{hPZP(p^>JsTeJl2XkO?+LCza|%p$O=sA8779OsO6g3ENoGm}iIaeK}e%zV+-Q zjO&Ren8z0@D&XO#kRDGvG|eQ_&^mW-q%y&Fw$890HFYQ9pO)KgwHMl zBxf^*Uk6E_S0%oXMaNoCZ_nN6X8N`1VGp6`|27#Ku>&qt&~FLI9v~`m*SNe@Fg1g( zLlHs(fdmnk1Yd=S7pEc{U|o0mjyKPA98v;ojW3J4av4M-sk(oO%^Dp+4s6sYH+X+V zowQCZ+fu#yaskx7v|{cVgwJR6Rg$wdC8CKs9QQY&cRxYaB)}(LPHu9I)8ylIyFQuf zX)+^8LQN||<4e!h53~e6@eOs(NrC_Pv?7&2x{RRypEIFCT#?03t5wH!P;jfji|a!> z(;a}IQE!Po5Jg1mV>1*-alFx)1vRQ*;NZ9_oZxA<+vQ57Gu^E~ zpq^kN?->*$KE{?d}k z-l(52WyOb^o%c1G+CubEIT17<#JvB2zL5hc?ajr*Gu`RuhqVhH&sJ91z1#4k;^if< zv$KO~fj)mE25%-i{a!t-v_cyvv*|iPBg& zv~-T=E3l?!>t;c(YC^qII_X`M4Fo`fW}NL}(c{wCK3ey|hKa*j`){*-RNdU(e)|n7 zu)^oUAg$D`C+?vB2kG|}#B7BNE6Ym$&vf|x?f->y;Kz`g2!~pl7#p)WzyIfF)aoUX ze30>2b{q$w-7g<*+aR7i-DJ6Up-A0-CKHdqwcE=j&M9tVPoO7qt@qruR@AO~ zfWDaB$IdsywH3UcvmguvSKd7J}Aq8aMa?8M^VKDqenSY!GEIM;g?fIp6|)`F>(B$2c^ujmB^^e1GN(d3>lho0KAusO$}u{`usjKqwF|)D3rK z^})v-Z-v9o=;VrshH>}5NYrB03y(VCqE`OuA@lo}TpMwv3)gxR!>pgv3oYVJGyLGE zN8ExJNZcKd`Mp`3z9>N<#ZJ_>BU7*^}4fW;j7DqBOu155qW<(#R{uC39!4%y*cC7u9-n65<^lNC z5Y zh~IB!6Nw1kC-2^c7{D;`4?U83UEX^|Gwmk<+U9e}Nfqr|E|5?en&CL%zERlBID6{7 zGO%VnCh@Au^vk`)@BH1?=?#WNe@&4r(8aRVo0lJYJD`c!`@Ip{Atmda0w9K?i zA5gK)c-*Xh+b-Fn5=#o7Y->FvZFk{$Lzdo$%}4#tL!zAaTSnu1xR%j=eRf}!T2?-` z;5~IHMB_-Xdgy_z!foy7GU#HZyU*u>X9u{Txf(B0A>AKO;2!WT2Cw?fpL>-O<#lL{ zEMQutSN`kMb}*Tw=0SlatsjPwOe8lwJw4sk?Mw(n*1w&me&N?nIKWOpTC%53ckw&h zO@LL5py${oLNsXvZI@&SX@16RC)J8-+@({zFctigKwo zCNnJ<4h1#pb`A|P1Mj3G&X@o_MPx}Yk(R2u9=;q2A3F}q3`;dku)qY1n!0;#Grh$edG@*_ui1$rE1WjY%9>hM&f{);Sjyt?#T z4kSPAak+3o@Gpj_Sw}1jX1F38`VZ4Mj_yaOrN@hktcx|fAA>YWG#k!~w^*^DMq5P0 zVGx`Vdzfm7Dr~rBhN!6cWvvD?@9W<`)_!C;Kme088e5Kx9pN zAv+rdCHLK(pKmUiWwq}FmVZySR|6|usn$_(?&TNtnIV0?cOAmir*b)=toQtc!6~Q4aeX_6$5*OU>)nlDx zYyN$qV|jqB63^{O4jWFIQus?$l>Zu@zZkN!zhDTbY2>3a{L`*+#bbA+;`@ni*O-8r zI%JjLDa~gJ<==d;sbce|w-Xz3uBVHjd85Y44bxk*+v(!z+B*snJgH#1mm0y}OHz53 zoX+SlC_-)m18XwavOdf~D;rCajwpa%JOG?oMb3Q<_qsA|1BBX#uJO*zNbU4RP;<<&q+X#M(R$|ixkCk6}NZOP@vD5 z0zVZl?`&QtVzo^SKb zB2U;V@5d>Wj?CwI-mLVvjHWv>GB~}A1n_GgUXDKU)p@cxksQhnup51vRNlQ0-Yw_X z{+51t#@a3dSuYwDTsQp_(7A0yN6zfXPwUJ3y>KGZ`(e+W59_n@r@ZC1;Sr>>e7lG5 z!S%O2szzV_RADKn0ixIH;pm^)pBfC|F*8*>-1gLk>y@*+&ypZ?zh#Y9N06H8PbAk5 zW|C2Vi8;!h8C>o8^zFA!Z9_!8J-t8(;$_Bk?cu6AzWU!MJ|chM)u?}xlU;J&ztM2p z)Z?q^Sosm`Nxze>Ve|=|Ka9h*giv6!o6Ksx@C?psbuV{8O~z4mUA&6h;`(3-Ll9w* ztL8UIYP#BDC7PHRg{}X;{CnD|Lu~4Imxhi%hRPfsMoMq_4dEk3R1` zUGR?S`2@Yv>+}>6bhUdh5cAU*nmC=|~035DHHxJ(oX#^;o14Q3bY~0Z)3F z9v24i@3732TU_~Ctv~D)>Fpn(WHEbL!1Cl_+Ug29<4pogDaa&m_}%y7ak*~$sH}Bc zqemA8R6Bl#(eh_$^=88AU7fC0-FsZw(XFS1tkZ|i_Y&`d#50W@JAXx9!T^rA#^d9-k~Xnsy!{>UGrnHNn&I5GJ1N2X>TkP)xm>EYKXykL zI}HY7NKuHAi_I*DaU-rnSN{e#244^UHIE6SH1ua5k(w z5I#qb@pAIA)nyjQW?3S~qocjGJ4*Qfp{Yqx{RY{bf{k4-etK85#=L&p;j#)SrR9 zJw4C^WutCLY!VX_HFmwk^7y&AUA*+m$y;zs*}fhz?Qe__g?!A7y<{qi$>(4B=S)pK z?Mp4bD}oN-dr_IQ-QBSy`qx<{w&bkV){wasXIIzCOMYlt&GE^Jm9!rF zm(Hry9_{YRD9=t!-?FQ|VkuDF+E%W*12}bv@Ohw%UShR<--2$z$#|_QCyMi2;=c75 zWGE!3_Gn#&f&Z+NWA7()e7pF&UT>rD`D?S~gyvARpRaVckO| zp#g_)#<;h-l9~nItawAMX{B^-MLc-r<9%T62Fft`Z50Vkm z#ib{6IGQxjT65DK<-Ity*oBZ%=G>|1e0@A0LB-n))(Xcy#$S%WMsqQCl@bZ?A;Cvb zgGZny&-!6tCiE6=D)ex5tr^&ka3aY_tXz{d7v`__6QMV4X}h33tig-4d~jssG51Um zb9acRjqUW57@UHIlZJ+EWV{UpKtqN)@Gt73T{;A(~z14O_-Qa(NCqa_YDm+nbPbR&uFa>yUGCy8@atVQjm2(k2l5@ z48e`RE=k#mnkH}X?fHJNzIcxg3fIwRUe*A}2-=lS93uW(9Ugd=f=Jp5Ks}b}e)Y+@ zhQM-K-vtYAOaFSRgwNaNuYJTM1cO84+Xu1gnd=FXe?-geqG3pgkGEt$e@v!-dC0E zD5U!|KNv;9o!joo^4h@CMwuq@qAs_#I=P_<2E*fB%$7juaG=GAgDKJQTQfA>PsHCC z-3YXAVv+$Pm1GWWcXAk1QkPPIx0ncUOnoaqV&aLZ0K&eu3@c=ES4$u0-|~7gf9?vc zLdh@42R==h3vgS|G_K9=rJN8SjMSmpI$tw`?Phb?aX(^u__zAXQ8aQm%nt=U;vF0; z*MEplTfzhzcCCp8%v2g6MQeCy(&_!GnZR3>%BWHj227gEZmjWQ;Ie*3hCQthET~`7Mh1 ztd#UH7C%7ik!g`NYi%HYF~LO0%Iq^U@L+&vA~z0@Fg&~+l)~n@9O%L1Di3v3dwJ~H zD|qvmnN^~>kiS~9Sjl0<6iv;vq!M5TH<K zTFDGEw|8OL+|m~xNP1b_)fw#U%rX&A1xi|-s)eopLSOKh=H?8S5uXWV{RPZRZL-G3 zdK(bZU}}o=7H?lsy}byA01X%3^+O&o>z9SpHkbB$YS&e69{&(Nq(z4Vx-u5!W5N@2 z(+2I?7^(f3j{-y|A~D>_6$&5vunx>I4#ect;A$=LfJ#d^DyaSW@$*yhs4orX<2y;2 zgS_{=m^sWq3LZ?%`qgABuD$HVNx@ZE9o08S+v7#Z@Qi}%BqY)Z6~EU8FqcwLWXBs) z#y|r~tSOGQOP`X3(=-D7vUvk|gD^@NH}`HtdsVRkMEqph7KwoFDunRDDJsTIO853;{$L(S@|G>cDzJtaHy&f-E)m#~h`z(pjxM@qgon_OAIllY4KYjAm}tL#Tef0_m|u_zM0TEsW}8wldx@sfhNihkZA?cY^oEC2 zByqp&W`u3upnyiorFMSvLT`}{2BWV}#29F%8N^|>#H1D+ymB#?L`YXJV4D0cp;zuG z8v9N?(E;5-GdwM^=XE|)Z{ZYu>xpYMvZf;9>3kvR4#hKsbGN-?+?Xf={M(OZS3uff zEKZl@C?+R7xw7^PiM>oxpPD(wpAjO!)9^EApO%ygC_qJt=XE8fOGBJdH*GPa#Mjh! zStpfETau7?>7AbACW}~0vqbJMXtDv6u7L{BxI`C zINdU}l$yiYPEX*LxAH1C?^!fKK$VSa`LKFq#Mmw^Y`puMi%RmCg@v`0+7!<+Sf>S) zvP2XgBr%1#qgZ#!R%wfTsrn;SmQqov4z-O4WwFSlmQk&HVF6aIWYT-A?BrItlqrC5 z;rqoOk|K2srEmI=d*1A$Z?oclm)Gdcg#|~A>0HPIAr4ZK4#KKfkH3f$P4n76BypLq$m^=L!!bjcuZ#+a<(0XewO(#&X4`dFT0wSv7Qs zoh#)o*i%0ua&PKp$fQAow32>W%9N;<_-KKBQOR^K8JpL=GEA661z=|UeSqbzm;gv- z{gullt{K#e4m-Jmp- zjTYm7I1&Rh^9D3>?uXl&Oy?ZEXx5}>y>G=SYDm;OjtJ8$?M7DTyH^QPd#t9CriICp z>-6S=bEyVJ5ek)~RJ~Qjd{M=xmEl_!(Tjg^DIt>BNf*w2V_a_=N%WE>zuc|_K6&$W z&bOOtifegeC#LLZL$`8c+&L?Db`${|5|kV5<_J3rR9@T5FSXWFFVziqlrQ3-=!`}% zayly<8IsHAVWg)hvAwIt@T5{JyhhsT|42sc38#!i3H0~(FAOH+05l$(>B}SEy}3Q~W8$5F6ty3``X|36+*gTx ze{Tu;9d(9mg>YH)1pLb)&uoW_y-4P6=fR21qE0y=S;0qO_aI99n*)V#2tDXma`=jN z&Z0je4GnWFmB*d=3!ErF9mL~@s5NZ;Y9@`!VA3Ggc*AXu&QGG{1M5+?RbLfV$b{-| z0sDlDnsH>iv)(?A4nC5--V=loH5CA{2Vzn7yRM5u*7GG1D% zPg-e6(awtN33RPTxB%(7Es{uMdeiI=#MytWs)t zvMmP0y?kxi@(vEX7pWpTOF&hd_(`_~5(h49M!5sSo%Gd6TbG8%J`309=ZE!{Mey1qY8XkTuS7*PB!8hX( z1e+5#Q9;%MDTTXR;$MR|iD^=ZYWlzcGZ-UQSHU1y`foR_^|_2;bA z06J98H5h=nR1$@|*87JCWaflt$Mg8=SrG;bN!zB@V706o7{8OLL7_Of?;;p=H*6nT z3-N48nCwu7#?zM7U4Ho?r!jUdD}8wM+e?yA?qoRUBbV3bGzk6jrE&7deq!#vTsEYY z#=dGE@`zX;Eg(5tBK-wq$I|)U{gcEx@z8NRPFK&14VA_$xxbcIy{W_xM8C|Df&4ji z4C8SBl64$1e##&n2*WkeV%pu45?6{zcP{hfSdF*EiIm~c-jU$=v|R*A{6J&T(Gc5h z5p+WMrev3>A{AZJQb;N!jHPtU@9}sFqdjhF&($8|9hv#j&y1(pLW0}XAFd$ziE+a> zk;o_PmDtr(HJqu#=|n274Ye5K`lo%Ntr9vz$5C_ZlY^-q zJiu4L$wmEfsl1cM)1$>hBog>GeR=BQJ5B2h^bqTV%@X?(6X~l7@@kr;^pY{{YU2ze z$Pf#PF1VxI!NsT=x9_CG{@_azVaGFB6f7r%)kc`Ng-CAuTOnNgRMO@sknd6sKON(3 zQ>P1c))M)Zn<6ZvR9OBeyIY@1%mR$_xOw#c(hA4akV?yWZfK{pdGlY7MirMn>B8H5s&_2)k+i)lIQ)DM8#W40c2*bz;nC<} zl`(;IL;+e4EVE+W8G7GFo8PU!>|@a~7@Cdny9Fb3j2J1p=>@;@U}9DdD9Dc4iIC<1 z8Qb3~2Ip$jYIHEh^CECz5TtfhBK8U#buiKf1~y|Brl?~jikbv{0m=L&_wq2eM znu_BWd!}Tpl}-g&RZ(tVjykjxS@zFQT9mGv=>tE!eTJN@sNYI$p*cWvT3L=_p`bFP z)@Ee`8V*8stlbz9G}6d&2CVY9{i!tOgh*QXfp`xquFe*PD7ZD2_6BMe$Jsk)4&! zI+D98x0~%8{WAPLIi2~S^<^|HO;?K{vxOyPrL`X>3nZSCffPfx{D;>aBU`?Zb?E)7x+<)IuSFL%AKdO<&P^($p^Tb zv>4dpLT3RjpM{4~_5(3=D+U z>7XU`N_(i|qGI8;AbIows-(Q(;^K1L8$G1iSZKdHZG}2!3^{P2`6=ropVIynDb16% z8_!dS;8u*7v#Dw^i8h)|5F;XuK~-*1B!aT;P00HHF<>}6S|Rysn^gd0l2iJ10wcoBdu-Go3WaFg#1yd4oa5XLa#e-C+uAcY2|$R5JE0ln}^ej>`$3S4yWzniCKb)o$t8KDu|D zs=6jr3`Lw%_H9Mfh`ZmtvEXxXXR#q}%8*D+-7XW{45&&&f0z!}HnMuIwcP0N0qm~< z&7!f%pjvr{ivM*Ly}9V)=0C-KjP22~W8Mzzf2J(!4r~DDmdn3>H45}TbxtTOPLk@* zjFO){Bqg5_eoz0#83E5P*7!~HF1_nIn!|yzGiMtUg~IKO7x{WJ_og{{gT@+RDa3cP z*#Ypup}x2OKz7C!)7=AfA?1Alr7k-N#j|At)*?4zRkqeVA<`q=oC)~>c6Vl^&wtgX&kzooaK9+d=3&$@EZd8I!lc~3k9`PCdWWLtezvLUZsWOw_L zm!;W@r~UqDJ|rE!Sy+?pv7yrNl#VlaeGd0E7*$Ezb#GBr8t;nEk6cT>jke7V%xZhe z8@Z7nyXv?hRo4)1w7rmZl~tn^s?ib@3T@pQ^%)0cD zmEPpjjV@ifj;fU8@yA#(Xxq*SjO|8Nreoc^Y^Oo$sM`+$k ze!b9Yc01Z;rO$Xg6rvmrE7%BVv_Hrz*xleD*$wCH+>h8;D_?#3+N*>0ZTHtpyanf; z)%vTUV7x9gV`mcTT~Uuj)~RD~bBorLDLS0WgU;s94h>&F(?XQ_L*_nx<vtdB-BTOlYf9N4aLX%ceX|o&L^D_ z>hQZo4R%KD9ausQ=q8Rf?M?N{Hul$!s`8H1@(KnU*oC)?f8w`$L@Sd`AW}CmT%t!c zKkl!kZnajgY1>$U*EuJ%rlIy6@;;X${xlOEW#HSiw35BB1SVXJWoAu6cj;EI5FWSn zO#b>zcJ5jY8fQ-#=WHKLn@I}8Oj4^(_F(juiD)2W^}Ww1F@ai4Bgtfhea5q#aWb~< zxRpLl_7EUw@oJ0ku)6kt`NC?&8Y4wv^yfYkiuV!bJd3ju|Tv2{zZh7QOpGXl& zyVn3<{8gQ>qi`H*xG*h;uc~!ipn{wxttlKv{8bE$&$X>rFX-CaA9j4l54p!o_fpM* zG9V{T`%&#$7QWmNNQ>5XJzU*MHDYU}RLTM!J&8Aoaa(sHfmq$)Wz5X!oK?1dR@G-b z7fRw)pL57QIka=Wo{~DOgbEw0fv|Cy2VaTz{n9iaYAxgN>o@DItA;&9KIn z>u}!34=TeXA<_g8;SICp`j^r3@qzkHIKvmL$w?PGk?)7`h zZb4LPjM=PiPe1VThi3u=m5v?@0uu-a#x3R?pqrD{g?AK`vD{+aCzOkY<9}7~w{vu# z;dx2P3KQ#OBMZlwH50%00UNsV>=tPPB=c)HFYXIb)@|`W`-ih0o$D0Q^WD(NjwPu$ zxLECqyr5DDzl^$BUu?WHt$0hoDZb#6W^9)eWh=LUh00787(1bsmBN?Y1SRx z)>=LjS#sKoy!~W%YOp|oX)6;JuYmBezxf%Vi3n>n^BFhvejOnkt^dvY{p+TAWNxj{ zsSwY&UdI9PhTmXjvPygVGj{*eHIs=$ea}6|2X~3QLwqORTT}70j$`6WB3Cm(Mi zW9m$*0arsXyV~+3HvljD(tbi#mf-lS?w5rSA=$s&xgOD4!&<9uW1k$c^t%m6^holU zLga*p^UbFtN>tN%7k-LmBzq#p_})M2zbHYE~`29u2Y`W-7vb4hd z$8~G((cp#!B`}Tmd!~8^*LYWM5MF~ZPP%wPQBJ^{;CSg{_V{p|g8SVr$`&(^)ClB# zJQX^GXTfHeG7RrqWHl6?TCCyd8QeXbr~Pj&jLj0I!BX5!)eOX%KR@!I(uock1ROHA zGOV=bKi{+e>X#Zl;D`u7hx^p#Mez1gtYf(UMao>g7!RoxrBDH)_ca|n#z5i)5PjqB zkP-{<+l}2I?4NTGxe_Wvfg$o}K`xl86{EAfA!2;N`?jD+sd|0T>wA|(N1zOE1yg=O zP!ng-Tp8D_&@9)H9E>z`z;a3G5kg#G<4NT0{EIehfQ?qN69hcx+mej*%zAH}($wCB z@a*O}Z8L$kQxD#b3}&;iU~a;6DwEAN8wz{k%*LG~a-Ht%wHz&-FqGCYJEW(9?tD4^ z3 zjf4+Gqo+`thS%(L#Ua+^>_S9~8U$7cqOA!M40hQYVcV2BZ^?x}JT>?t7ZB-XO5(}Z zI?lmK6G!6Bo~V2dzl{gSzDhR0X~>s)b#fZzZ7QFNx8SgDUu4lP;(tOITA@K;f1b|s zd0{MK5Kp?oW3)BB@*o?p_nc%HfmXEfwT>0NPZJaj;TAG!3Y zIa;Cu`^Sc}da~|%qQgho{CqTf5w=*hWcrf~pO4z<|GGGzz_=2(^s27d=E5u4rs8Fu zSx89a*;tT2K&2Ws$4hs@n?ZKi!kXg~JfWL~U2kOhL*?4b)1^|nMXr3cR7eW~DUw-i zz!%SY%F-fLt!8BZIdoE+yShGdU8zE?<41=;b~%}^^#Abn)=_me&6hBQKoT^;o#5{7 z3GVLh?(PuWCAbsZ-QAswy9Rf6ox}4!?{C(8-@`|U#PA5uC9V&9i?J;SI_XWKa5D=_XL}tsSS{Ra zBBGUJP41ALFHW_LGuoYWd;6QW4JN;|S%a9124i~QB=-$L+F@bl*-VX%Os`KFKXSEdAKXYA}~dAE#Fxv74XJrF8 z#C1tjcZSfWnG3i&%UznuK;?^QGIqgsiRB-Gl4YJX?SG8V-@E-`8b%A;n;sCqwaI$Y zm;}w`3Z!rjXUe2w=T_0Vu4v&wrXv$e^Jq%xcYbP>vZ4dNs{AHYc|{yztMi^o7gDf zDx{%kXl;X#MEO%_aeS34=}A7EhixP z^Q;TM@tJDz2-8j}Wpoqse+=@bky!GDU`Gc(?1_g(Z^g>nMfbAIh(T65MJ{|}ENPI; zO6zkqg4Z6Ed?5J=v>9XD*oqRfZba%!NrAY$U!O;?d>!N>b2rksNwt=kHJa`5kp3KN zHw1h#GE8pL#kG_Z%qPBiB}Bbe2bF+UmY8^QCovlx4z)A3MhalinH!%Z4Rq&c6fUtu zGu2K+YrJ{tR+)8nA`5b$dh%*Cn0~aQw-KtfGT!T0t#lPlBgn!ux6jJG(iBLq_ZcLI zg`3v;d};H;?Q;q8X%U(*=Vi14sF+!}dDIBeUU@|64km>4wQIP%6fToSE4;@Hy8585 z2k%4Ber$<7Iyl+fGm*YA%CTRix|Vbqv)yEZYtDsx6eotvkwUbqL7+*ek$luX)_Uvj z3_vn=`NI~?(^~;}Q+{vViJ+X_c*7CUVEgwYNB>jT! z36vqh+lEBrF-Ez30W+xd#_qgjp~|6K#IwAp!eFpapU9j&8aQ(X8`NLsRwC*RQ)1L zRT;DRe-=#pKBgIuE8h3cN-bS07AD*nducKLwiOnqr|UQ|E)SEdq-F81gZV%v=lrcK zb%*dMq1=FBT)3~AJh{mQe@oeU_s;D!W+c&!?e90)h)>W`C`WQi9Rbu^K{aJ_2E*)v zERQZ5yy2qmgf^vGnb7diIzsgx08;3PRigYVewS(2+Z+=x*T7MC37>toqzk(!8>%hl zUEI_qtP-E=euhYO+8p~6t~thNR>kb8-BX?c;#UKn?rBEoren$9dK+-Y!1C_-Mbfd6*y+K$GxA^3gxdUN(vFAQcp_)aIq2TC*t~mD;S+&J;usuH z+6v?KGnBYnkFwu{k@t?{Zbn|$a`3rcBq5aLz^KECpVJnn7j;IC&5T6YF!S( z)7EMdeb$mit{BcRtj~1sAPJi-OfN!T?kM;^Uq}KZn;v_6*9VNf2luj?7s17a8KuIC zGBPsZcXjnrzl3sJNf*QlB~^y#;@URO9(X66Gf`*Jho{|@+3T!HgDL`aGODZq$)!#%-A(AIdM?o#T=vNalW!B92<{(^&RE!WlYyHsiF}Nv?1{{BzZG^8MZ5z~dr<)GC%`YBLZBUz3 z*71E~!1hA#+Ds2iZXXIxjv%yJ>nl`hM$e#U8xoJ{;C=nXNbfW#kYK6ZJyZ9`q!hkdtq6p)s07o(I#hLYM_7>muv4)st-p zcW`16ONEOOopIhG?oAh+|B3bc(b12hjk$fad~CCU3EsKty8v^U9urA29uJ*b<4q%ZDyLj8r5A&Wt5i4pez5x(|oi_8=K!L)Jb^z_lq zn|H`&`kcI{V`g>b1RW~XeL6JC@4s-lu_?w+`^gQ+)2k#ly6(nJMgl}Bz_$5&a`Mu( z6`CDQsa%d8<$k$6gw7NcLIXkiX&3*^1WV|(B}(f6aRcx70g3!bZqCz*)$x-v6J+e9 zvNm9m*a7)DWGWT9wSHQ~VujX-7wVB1LNt8*uBmOpNOpGit-pUUc2G3fHAOyTSYwI! zX7LWe&+Yqy^N}MLK)=5s zO*zsZM9U=XGc`U&==iM%_htltUB``}3{bz#vH5^2XFDqRvPMsP^bUa|hDJnKwgNvL zQ*lzJ4lcW<1-%9MoA0MI5KtG~QLA>*0|r@UM1%ORDyxVQa3{aAv9k+5p@RMIKLQFZ zThD761ac0kz*PPf7yX^SpD-VCPyFX!K~w_)F|;jZ2_<~uxc{`=#Dq6C=Kh}Qb3u+( z95g^4me5GO#z77By{vkp5~IJ#C$A#K;HPj-Wa*mkf=(Cm%bwJ;vWzl+^iZ&15AGYl z(+xk34wMfsNy5E@mT$VKYo{W>E#%^E2$Z#?jNyzRoI_36U#*dQe9~U9T|V!c%NPEX zywv;=BTZh%aPMdN;miHjRG2_g!~2ZCSAT*0o);!6aoHlBtS2SZQLk`4+y2x@gTrpw zF}KWA;=k7M^GEa-?GBK_h+e=WLG;tSbhZ71ObSiL_+wLx$`ldx5^dy-+2D`z%$8w7 zYf*zu%WoQ*>}iwgwQ*$2NpiPPrx`25j}N>uI|6j>@NguVeIt_m(sadUkWkol-<9i( zYUkbtGAV`RJB}q2a5O}4?hLNeqk+N22mnqHxn{U94^R8#Y3t`9`Z(R6Yf2q-Re^np ztS^Tu(G{~Q{p~j^8JQT;b%<@MvscC`3feyumj%)??xB)mYtC@3UQ8lxN;+^4313Zq zN4QZYR9$X^U82l@lUUI{gwO}UZ9lmpv_NflL&rbOszq0T^d2KEh2y{URY{B%y!Y%8 z@zc;0H98#V=}B*;qQ+v`jVRBa(b-z>xp2%qMp_i5i|FbG2CStYYqDG-(`jl-q-H0d zS2lF7j3T;MXegZ2#o1d2=x!}OI26kIt{kk|R@QfpazWB0k4zeNfk&32OVr4z+RUr# zWe}jKQaBke229-TW+A$G(5x13_x6AgDce3RQaT#G4iyyAy9muKE>Ac8#yQOKJLZ0> zZXLBrDRR7w1t~`5C9}^-nUc#mf5oZ@@UHZ}&v=UwdaCY~*B9QZ)4gDjzCfY(ri=zB zb82i^&dTDy<0xD;z6wp}l9c^LgJZ9U(u7Z=*gVCQ(_P1_WV7EBmHNItHe-PBm=`NG zsmzC{C%$@|-p=rnYV&f%3yuIRErK5Owt#Q z^oSmJPz`6R+oRew7z|e=riZjynx~20as;nCXVbd-45;5TU(^k|nyHWn_5DoyM5R_3 zWaW5Bfh7^}jhX7Z2aMR*!8B=3n>GWip>A5zdZO0TT6?otkaPr(1DO%hLkGxlU)X`kKI^l;uWj&|g5f_4AMvKQubDrXj0ASj0{;YnC3KDj$4 zg4#w7%(rNohckYUN`Em%7x@(g8@>lfXuy&lV^v-c5*#)Q1{UEJJCkVlC5OM?KV8TZ7wS@V$6TG>B^e38_0mTQY`8MSeA{%PLY zQ^qM2Ekp8tFwoHw6|gxRzE>6C^AJ3wvzGi#Q)i8_KjSiyvaPtS^+p+PAMC6dkp5hA zo-gxDfvmvFmQnB?zuJmriQ zdHp$^;zM2+`ryxA5?Ng-D}wg=^tMRg&fy*h`nusaTz$&YvA-#LP`6xON%rn4^wy?y z707P=d7Y&5vuk`YF~tg@Lz{?E&t7UOD{H}S=xO=#CKTVV1u}ZeANbjzp&|DE3foH< z!%*r7C0?BiVJuGp52yKab1aNC`|tM8()N4F-Ng2$PpikzeJ?s z>9dUeQKz40wZ6Top?WDo>+xD23JCgxKB;GDC`1MwNOld10%pb937xs=cuo#qdmz>_ zT(eH@)7eO(!Se7q_vIeb{$#BMSF3xEqDYon1nn0+(reETi#x#lD~z&&Vkq}&+6^72nZ5sa4#f{#Bp9`BIZ zMz>!I_qsQnx-?iN>&J!-bu@R4Fec0oFA*JXDcPU3hKN!C!{MMVq~&vYZITl#!@@0B z3s01`;UMw?MnXcuml4?7vN-|+0ww?Q4o1!F4zQUA3x$b4O6WdaRLTdjNp45rDd1Y9 zbZ5g*tkoULPCOI#yb})+XaOknb4`7H^OFwLn7L3$7L>y9u5TVm zxcC!p&L$S?r^%h{f!^}c5|)f_c{NpI6$AmTH(xzcYrKz4b~}7Xq$Zo-h5g+9Y=O*Z z`fZpyW38boNy4CH9mSeNGDjq4p0!+s0~Gey-@YOw|F#-)Gm872-1T2OwY0{1^UhZO z>s+EbA&XR}=<|RHg4i&uHb{Fkf={%l>o) zN`U5?+d8%Vw6h;?J@2*d<Yc$7cwa7aZO7xLjQv$up^b$PFrQk+E z5h&LnY{{lpIp;*7PzY|pfW~h(13Er?mX|pJa||?NQtq9dNdugcTb9pqd18Ib3)+l$ znS-I_lmLLUo$Rr!_rx(WKl|?T0yt}qhK8KzcX2Qlmimv7kbN%RU;ZVa@$dtpl_u{u zEj?*M)nLh3g#VcS_ixefZf|2B(G&ga(_X*<4z2&6`6K-{0`mWQzSiM!G+vtjeFR?s zwy%EZlL*w#Bgh5K^j>f{^HV{FSN=}uBNlKgS~NBjWkeC6mHxT<D~a#5Mc@#oK<+n{vL{-;bfTLO4vLSU&r$20;mbgr+@uB8K_LOWsqr7^?yVsz+m%AZLSL9R>$L38m6UBaa`AEQykIOVGD zf?SWFD=JBeJQ6zERNuYkpfE>zMBj&4n+ENdOfve;}+bpd89%xx|!VO#HqoKrW<0kpbGULM6Ij$Hc4X zg2VzH5694`K{S#644!X(;NjC z7j*u&r^)dMRXT%9^!VWY-3|o;aavmGN^qgAt!Q7KIGR2;s3GRNp6F3rW+aRfW1$aw zgYxTO(#s#~7bW8JdyQtrp^%_-VkI|(YURV>=U8diw$2=(uiyUYwLZfHjG-V4{*)aZ z;(VqO0*vFKWRZmyTRz>uXg6vD)y_WM75cA=PoMQ2`LURk>Qrx!%lK2R=$iZ?o0&8h zaV`Q#b(=>@FHvcu%5*ZUKkkLodkPY;EpT#kTy;O&J)HdPZftjiT~7r0mXtvnp|Y^$ zfyBObpoTBK`Z%Muh9@Skw}SD2$mv)c`l!_*n?byN(|5{!n+|IPMM=EgJb?6G=h#>T zi{%p0tpl*8!3I4`OKQLiRf;at zD+=Z7k+pNWT=&kO%p0hH?qP&$n%Lj-mfSOYAF;Ua%bjGgXO^*-8h;g)QP>P@ejLGS zZhK()zP3k=xKyIZ;M4B;1b8m-gN*MD=ZLit+W)Nu`27j6Zz{I4+Ym%?ZGv4i+W6J` zO7_p|-mW?nzk=K{OjieNy4%6Uqo}gWQ=w!Y{;0f0@)wXgvtU$4QJRFEY*`(S*X{rTT;gZo1 z%nQ6Oos~x0a2!rl`zzM7bzpYN%F3$5@3svwI*x{k zwJ}g}0IpHFl;3O1^23J@pFcMWR$9|TvlnUbzPq+2*qz8?8-77t_EaLe+Bn}DAR4jK zUyve(k={`5Kc&c)4typxl_Tw5#siQv-WXY2l zmgnTVZ)_jm8tUbdA?b8PvVZmI(D~{GCe!5CC1BPr4PHtss%>~9rLb5I1Hz&2(tasujvZkJkr;CGRO;fe+RH$-?($2vxu1Jf!d5!XlQg@x9|EsxNbqsaC<)U7txx z>Y_T5@_@WtgLn#ox48xig!+oTPDb}bnuX5ml=>J1EJhpMDY|EE+F0^^oNKav&W|h1 zzC3O_zl?T`vI3ECakWi_{Zb3CFt_MInl7O!>-177vAu7tf*w;QOcKcq0f4Y+rB2s} zTD6lS#cF^fllb-;IQc}3K#ERwjip>FH}-cU?B~sq&Fc4S6Qc8cgN~7dMQ?u+;9Nz> zk+u~FtHpRZA7S#>Jrbhd)xiivofGB^H*w@Zp6$Fc)-7D{((`7l-Wds)tyorRyVP!e zi}RCSt5z-G4;rq?DnJLbN48j9sgn0)x4&e7>L|T9&o{H7RsW^2+wx#OtPnYmDWU}w zdL(uCgvfL;Ea{W<0%IRZq{S;!tJ4FT$VbyT(R}c{?td!1vq})LAs~#CS*P-N2C{Kl zX{09&1n&Fyph*kXqx z)0OrQq=NB2CddMYSu(4m@kbDGVSNYY1D9MD^U7ug7-3`EB8_1g4HHg%e6pXo{Dujf zSbmK#mQ(7>9^4rbZXZ6QDi@Q5=6uwnry>b#MTGSq3I&Jcfipt04d*h7#j*^WS3Kip zD_rph={({d_Jr%B?x8zSdRvEMzkNqQjQeVE{ z)&h2M*Dxp}uH2PemW%P0)>-))C26ArHV99s(q&IC-f>-jqa*6DA7QMlO=x^>a14kC$ahfQfq?vt1>)Yljm;%&@2)%a+1j(rs7S4)_#&kFA0n8lGIerU%#Y* zyjytedGWoqT0tO%5kTH~el{d;Fc=*GjY8q!DveL~jjjM%bvZLX=FR(AZ8ughag!1_ zjm)iWZQu*-o}7S`ddP)J)v7iiDKI|*D8~Cj!t^iS=ZSf4i|-h0C=O-Uc1x=OzxH?H z4}>jCM!Dvm6tL;_b_7$x+4mFi#na$u+VO!ZCe!6GoF%44fbn3CYj5qL&0^)6RqXGi z!=uy(RlALijZQ#ALBFo!AK)$WKlz`eh3T(V*Ub&S2M>}UyjIu~bK+eO0XajrNc?B= zw`0xj$K_xCW^&O}oSc0vV|xSbl7mJG3rNUc@TD`7G`QcnI)m@ei-}|~?TD!G@YdN* zT0c*D$_m7*N-fbYi9Ypa1ik+|e=vfIs^3^bq>+tQ9G9;z(SY54_rSEl0g%UzT9u%( zsw(1&{=W$JMSRFnDq2|Kdmwp5NA+KSzd}M|y;X&X=6}KmLjX0m?VX3t^RISJYJAv3 zZ?3}_&HrR}?HtwEl@Sn&(eTLC-CefMQl!DRf;E4qo%2fsUvng z^ga&0UKJ0AHzZjkZOS-pLo%2zFuGUC)GO|8yph5zm+SdO5}J)+C4VLn49(8rg&I!! zgW=x#M1$r0;A?E2spir=e0qZy80^f?PLx{j+ryv-(*T7D11#uQBw%wt_AmOOzO& zr)6~aBE3k94yWk2w6fN=pHrH6DO_W0u>i3ZnC#~ZOCXx+)z{Y-2eQLyQ6)z=9dF;v zCUo|G2S#^d*?Rdj*1m2-HPfDn)}<+;%R4K?-7!Ly?s?CqTpoq!P_5X>w#s>~jQKX% zzc3iHNE-S}s;VVO`U!G@xZ9JgsPkMe@=IG&KdkE+7AY@cSc-rdBfRykIOZKJ7Jby& zoQ(Hw`nE3`o)d~Wcw?{Zx}DC1sM;I9Q(G~Y;%cm|6Ppi4T!K0v>N=X|*OD~9p4oSW z$)LZ*m10OIeO&Ypw_h&?;LmBy&COld)mUl%A`lD?rqf}*-^&|ry%2X$P>Xz86O!jg8S_|nZRqBfEZ${W8S-RG3Py;A7HK?& zV-Fp*Fn-&@`h>9eJ*n)L|zM;Jq`1@a1XM9%5~6Xu52vomWs5rM!)SB~N6 zr6JbRY&vLT@-ZO0Dhnva1MJ3(=z-p5@c8mqlYGg{vG8Ph^cQ@cEw>t>}Kev=VAf9jy&HxOv#lhg3?rBpbKPV`9v5tYA`в9_)V;LQkc z=R!Ckqx)6$M-cR)O-)^=*qLZK#cHxM!+E+Q#q?}nEqTfp1b52OF{-M&VZm7~adxz_ zyT!p1A5L^;@*#D$t<)b-St@_`@3k<$XiD;9LB8{V;+VFa5q{|WzaafKz31F-gb}wp z=$M?C6>t#UDytJv5sH=xZJM~I&0X7wsQXh6hR(euXnW8{P%|Xnn4hS|s47L16IM`y zs_tC3uh@Cp7&30xW-{D&kme_gR#Z9sMGFYdO&G$6J=dWPz?R~W58C_}sau2D7~{J- zK6yO4aox}_w-^qH?MaQf+S=n}y&DSwkM})`l-YnkakAD12MB;Deh%ZaT?Pa;FaUNs zK(zgFn?*`W>iTFN!Pt0DMcU@H-4#}aGgzV=14Bb!=GsXqbECrnCJNcQ*|EaU9acGF zhIDyfwU{Foq#83;fqODl{M_KlJiQdJcb6A&jH`**cIjrG@zNGK)fd6>zPe#%~;^wIm7V8Ib= zm-fZ*P1qWXDL?4F%+B);bU>4U-D8&&wMd0zAyN^&A zs?|^)S}9x^sJLL%*v-7s)rn2yTjY7Um^CC9;A!iAfO)f-1hYD$3dH=PG8=i==Jdz9 z+Mn4kOy{o3hV%2!(b0h5z`MLK&sJGZ@yBq#<&#YJaVUe!;#S-02C zU@LIVBj=KYu9%pkJ`^uQ2l0fDNQ(R}nAzD29GmA=SI*4Q@>rfXXhxF(Tb7rp1U*#JS^oe7ouiMZUq8g zyo-$xzSHccD!Mh24XLyhTk7Ba7_4ZF;mU6Y7q?(MRFNOAn0EFjTBwP+dA>EyeD%#N zGC9Tuitg;G%5a4_A>~Er@XuP`~~{#avaw)=H_AuHUm(bXC@_a`c1#)K@zi!*%|QDR7zIcPJH zuRrldQ1equu@+L!T4=YA3sBwp-nKR+35`_kVouunNW)5-220;7Vt2+HW|Y&0l7=89 z?;Xom!qY_V>mp!_(?20#iCd&=*wowS4qH3Z>Gqp%u!NOUD4x2ok&&zI4lMYi}OvG+m^XXUa|(gyqp%+KED}tKTPVP&76;OOH(PveEP0qv3#2pQt{s008Lz5 zwy5AvieME{TuCAX-3KG1_W&F9buH|_*_#%Gkwmxx``9Ig3fZV#6vj5R;ZZtP2xhLd zyC5*g|5lo6YpG2y80Ol|4_Q3i5qRHF`&`@;J&rg1h(p~$CLNxq2q?Sw5SDNCU~(ru zLu!#;A8jv$B{o+kQQV-d(D!Q-f~Dppks%2WOY$YZrU^Ygp5xs&4Hf_@DAwzV9GNA5 zW_~cZ8ie|x6jiD)bZ}<}Ns`Z$YjsOV?TKs!vX+d!2y(p+VDwIxf;p7`klD_)%sL{O zzJwuDPHS*~3}Zcv%sG~-brx$Ex{xxxuL!?_PPAPPwM%P@vFjQp(<=ViSG`1_RKY8!~Nh=yY z*V~GDj$==cV%Wvy7pb7uH}QYKf%v~nKw0P0gB-}&$v#h@=Fng&xzYO$oaFoSqxR^% zAxn#u=OG4VBQtvMn_bGc%0f6e;j_K2n?qeV`}!jQcnJiERW>^JqU z;nT&>ODhq9{88T<{%JZDkR#3u3mNb4Psqy3a>3#qas+>CH-R}WyACgBL{x4wFCCCS z9%gXcVY5;=>dRm26JgDvBZe{V9)sdL&Cp*bhS=A(EbC!aC!vD#rq6R!KOT7DDaovi+`)H=zH_{xacmKuYBr!W{=uxPi4t*(mA`->F3>0Wp%{v zt7*>QuArHQ@?Dd-*a&Yl%XN(G+l-IcqDJM6zpd%IzJka4=<5Fm6_9LhNL4S4Qkl=8 z8+)xLm9FA55I^zHqmMTCKGPW(ayMag$P&g;Mn<-~SL}8_7Vxsv$RMqQ**HIj9w-_} zQJpPR>Psb;ACS$tmOP9H`Q)&-vN>+9+T@8!LUyEGb5^F^?noRzf+EgSNxx9hr}p7^ zivHiqDl4qBjJO796;rFH%ZMI4(&!Lc28!Uq?w6B(_Y>Fr*XL7gP*=~<2W~dqG zN?c_o-KcwuaR{GgT~SC>DcrHyyU;GzpY7b=eCD!C=&O*Uv5Th?4y-ImZE`5w1|+tpCv`1w$#fKLhAb+C_{bD`Rh5R2t?D3TxTvlF>k*f)C&^>r+9 zK|ecdypp>B*<49!%w4B@1NMSBdaT)$S^Nr~xKGMbwkB`jk?AddUCem1oRNC3E8ub7 z1%5dpJ{|e=XO+x`oSxF(gyHrz$Ygp$SMAYi9(}}`5)3b%FFku>(>ptV0PLzr?wEjo z)NTjpDdJ^hWL&Vk0TZnko0}JZlvEyOP~{ zk<1^yRvekn7miI%Czxw%Ya!fl?`Q%$AYKBEN`-E{l}MpTvDPmo!NU`ys9?vfx@l`? z*Wc3<3n-TMFVp{?Vg5G*`8g);Kb7!XH|YOUcbA=eq<8uKzo-L|NHYxy98jgTS$9S7 z-|QlRC;;+G9+L+rZr1!Cf32@inCcS%l9!`bdl%lq>i@+mi0FZgJrj|@|ITp={00(~ zLt*~a)+u7=O=F`NyndDqk|Ep}?>7JQH^KMk7Zw)!-QT}*D~hj+Z^2U&;4XbOFyxY7 za#gsq^CLep)wQ&LC|Xu$`!E#mV8WQg9q-=}-eUrp_$l4@TF8IkXJMRnJO4mNteT@| ztJ2Z3_R6{t^Vs$tK3N%_+e|_7{52+BH=AEI&VG%yr@R>?Dr8}yUlV3(AMaOCAZv~x z*iA)_*+YpA77baV&LnPp4@3-&1M(sm*IX$kjke7|Ug!AU4`%}Z6oZ|;QXFGx6DKt;D|d^ypjTJB8!gA zFGH>QrZF9S?}K9`CEfd|{_prU%48C{mBNAqFS(zT{(ndUyDy}x`b&2&CTiw=8*zqf z=qAQ;NI#k;$st1e4|6o)Dr17*%@aAWWvjlfdpB`d?E!*qVSg_VX+ti+KlL-`fTF}r zm0961;3Kjo3Q$vLg^%~;ewXdJDcuZ9hWfj~149x(%$q;TbD+l%YbQVEuK1uD zkL^YO*+4s=CnG8|52_#`^)m$D?JZGB0DP1XWz${r6lI*g-=&UWLc&}s?$x30R$H5d zm3jhIIg5%Kdo+nP_2Y|e%*0*fHz!9Vek`=E`5{agbK@x#%h3hys9?vsT+H6d#nmEh z4m4BwB|TH4UzWuZOj-^|NE8SxH~9)IwAk`V`bN58>IrrZNv`3Y4e%CRoSE>1M;yV+aSsEv9G<=BSrz=4(e2pmnoSq>2yWRNRD{;+$RI^a|1H@KY=)5Q!$JVIjq5kM9)AysE!vJ+0!p z{RXX z;zb2Bm-8zVOX-_4TeTPSv>LKuN`GK&ABB9Lt7>Ca>MR!NWNSXVX=GG>rQtR*A3S`v z#>3yVDq4v)mbMG%x1gJ_{K?{DLxM=FTuHSDFZ`c{Q47s(pSqS{9S$`x3Zfv%`+h;= zq{f(b**KN0jJC~L+Pb@QGAHTlAIVz|e#6EbHNL7fYaCgAkHt2&w_)GQbp`kmVo083 z>aU(@`YkZRlIOy|!1ZtCJBR%h`JZCMe2M=QBi>fY7>I{-$(yzmAu_hWW&QjUnRd(+ z+JS>rWhbGS7C%Uj5OLanJhJ9+$vc=kbsO`uOx+Z7+oJcf3I;=_4DFz9e3Ab7lhUe~ z=*dHn$`aGf2$lre zE{@{I)2;g_kVO5E1QdgAcRP_q^-z1GkH|07nb2$$vDpGa*|6E>+Rdq*qEMKn(9qD@ zxf5ArWdWE_RKXt~RTVz|8f-Vje_|Q&d==^Zia5wHG)j~?&z`{_= zR){1Wf#;2P7WsB@)Hz0&v|tV;uBAFWNm*W638AMy;V8{;R-9n?({dLgjd4SYCBikW z?o3nj6`VI}X#U2q+gI7u@uV#r9Ru>UjO*bkXklU#T1)kbAhE6rjKur?K?3US8Uxqs zQ2cf8kM5(c6>K|>M@`*FY(Mn1g2%JQvUwY*7T9{Lr@%AMiQW70@I>k>8pBP}l8}yT z)dU{acpBMR8bShssnSBnss}TcOnu4e?W^>Xq>JvGYl~GsRx6iue)gb7>mdufu&ev! zKJT4T_?N?rk9i(`ky^&U~DF? z`YRFaSBy0%wY}a~?HW~Cx~X5U)%(1;yY=U|_Cue6@vgokc7Lz})(FD!mJAqTnIfLm z5laF+`CX;g8N%_E-!jz3b{ai@NctPivh%i1qy)kFi#pZgu<&vT31hFfkLS}cnh1B$ z-_rtD%M&&DkAai2E!1%1qofs`y}u_Am6^{d!IaQK<{R|T{#y(11?pECz>Rf(LHRco zrR4lmHhYg%-o1lOILGVEA=hKnSTXA#l$C^6I*OAbr^4pU^BeSrNg^$goehFKrTU{e-n`jls-;J)fxNJl( zqrl6*N2Gsxx%YC3o=nH%dbr-FVzB?vY30RsJit z0ZpSn4UCjl|E?%0r4OH~J{>mO7TgDn#qIlFhfYl&*s;f$tJu=mq+GPIH6HJeu04-f zpKk(6*v~q36Ixv<{jlM*n}dTz*f?3dG|R%qX?Qswq>U`tjXnQ%g$$nPpfD z0Spxa0&BIx%QuMD(s{}OGpq(nQ>xCKuuK0)EHi`tJoComqAV&5O7W%R>v{sMN}@g@ zb0xwmC61mXPgKjAy5RVccYplbGak3iAoDm1#{X49uN?ANlYDOQA$wD#s@^-n$nqozeX#>Ikq$p2(&yG;0>=w z-LVBEDZ;9^+b|w`&UClcUx<`vTg;CJ^Tw$La5*EzGh35G-ll&`1HJjA0p{PnndWn4 z7yu;+D2EKWX{%PoSGy4rw;lsINtETT9+;R33~@Xsk6;rmn$|RI_5^|7LRD8tRL|aG zu(XE_1~sKGp1#aq_8w;3d%PVcJ{o=_=RravBzP?)|I&|!936=O}Nevls4lN)c z&@Cw@MiCGY@P~$Gqns z_Vxru!_}i?TgV3v%@^lWSJSTzTrP~`8n5`QPIdOLt5FP=2MSt^j%=Q5?LM{;%SdM< zM&t9Trk+pGyHdfBdgxvQTcgh#dblm-M4mj2!6E#dUzJn(=5~0$X30aeeTKM83S*mZ zigPxO+{_-Q)w5}FDQ$o8XdFjy#4%7!F5_)@-g0iWpUheD_QK-KL{JVcwVU*P1i^wQPikyA+F7mQNv; za_H;_1c9!Y`Mk4Ju28fzG~1ExyEWT=!Y&;Pd>VW(YIV51h4$lFf-*dsShZ|#y01^B z+NW>JNK}v8#2KR(NT~}kjDgy}md$;6`dN#CS>Nxa{E|qy`z+mYi(j&)DsA;WW4oL` z`8LtK=_G&X+IIGw+cslNJ2SO!VDCBkVSat6PkT(?LUJ4hH~=4Jn$flRY&|nC`cGa) ziNd=2uMtP(@VE=OyY4Txq`mWlnP6I+PO|OyK){9qjQ$FMGGMS+sQ8ufx?S%>skh+g z<>qeMuwmUi60_IE#VLSIO*yeF*{l7gb8!}=$=r=+S&9t}20kJfbu@u!K|P{C;wgux z;N($I6*&of)UUF-(SNUi`S2?2{V67OGfh}tr6l;@`P4b>)h6i6#viCfq{vph}fDZmqw2tA1tNrR?qh?ABVBwedE95Gg^rySp433F(yXRyu^CLy#Q0yHg42&Y@H3K|&-{8ithm4&wWM_x|qu1t)f_ zz3O@PIcK^2oX8%_5==C3>PQy#Ih*myo;q>c_cVY0qCFry_M9M5kF1;WNnEN<-~1}& zTDpfv9a|F$y51hf_FJgAgeC;}Pm`v20iU=)X6389j?;b$f7eM|f`FFu3k#qhjk#7L zoB0HORID&wrq>)h1;)7v){{Bo6?%1Y3LgW+tz?Rei^tM=!|++PxqxTzYU}D+wleI9 zUO1AySn;FG<_{l^l{xFUay@j&w+ib;8p${q3K#lFNR>++_b#ujA}Ru0L_M6) zO>2BSw~_+~V_C-0k)zIf{KtB%_||^gfi>{jDjp#re8uO08@#IznD%mywoUg*@ILi+r@_Uv4?9EAWOXg{;)!-4@4-uHgE{o^^v;)-_)|1Vt_y- z<_k(SbVUP7>x#KE!SQSP3)vX-$k3w7z)Z4Q7>g(NgAE-PPw-OW64RW0U+hUU_{{BZ z6+;n~pj0&$JkzMc;iHr5*^^jx+-?Vza=}7zTHQfbtK4?S5(O+6a8RS-oI;x=pmvOE zJLVUzEru`KYTS*G_eQS9#*_%ybi2ttmefn(jH)?fKz-sg;MsJKB^Okuj#GkfjSd!z z^){evl^pMF=FaP5#S-Pr0ifov&2$Ooi&bAZ^E{v84PKIy5iyvQoh5|j;LJ!#FF_d% z#b|Q7Co8{(@!HQdGHeue@D_yGf1-UvXRPfwUfPFD+xocankPgtTcTUOCxzCYO%uJ4 zPZV+5ayu(_Au&gFCk0$ZzKUMft~jUocj)*avWYnV!_-6kdbKTZTe_H^clMdcTBe1*&=N*XS<;=M;9NY6ao5Y(kS|D9pKh}&6 zn}4V*&}Z`08kCLV;ozXLg4?pkGhc+ZVw4B{0};EI!LCTuP2b4t%_wyYT^>US*b8K1 zDX!PB1MZ9cZSFO#0%ly5Z!s9tezs`G4?GMZ-JhT@)+iR2J4zTv;yFJ;nHSl?7tdfb z70!VnCtvWnZxHI_C}NgsKcL#6$N;#Gczr^sNf`sDT3*ko#h-Ms6h z=sAM(wDJpXv)&Jj?3NKfuXAdy;c_^)64acWuu0V_Th#;8nA)bkFXhGWXgTKhl$t z3d6GcJyo1m5@9w&|BL8Ev`y5ab8({9cj(Ftd-^thym`n*=j*>< z?C%Y|z1}I936)I0&voSD%H6rIL#8d2luhiP z`WjE25q{p2qn4q-P85Q1k#sys>}@v(ld%+lYUrhwqfOrPwY%@k&3?j!Zn|=N9)73N zrlX<3&G|2ep_BaJ&ctg?h-f+yiS9z5oF+Es*B<>%oV9zU@cBDVRfbuTR#)Gv^LIDb zNV{l6C%JJ${nSsaiVZw?{)EtOWDrcW*>g!PBia zFTPK1o+b;Du^@H|4qg59YOYacpX2hgzi<^lD8fGup6{LB;IN%QfD^w(Z@BMAUuxa-4c6{uQ8tROO+3QG!y~7l z@Kl?f5p4iV&mW9~ijH(K+J%Mu2#+A?b79^G^0qqNdZBo6<%1rpN?V+d6<`$i`lA&v zt5iBo3O9;VvfRx$`Ai2#BRZdKl*APuxwuL2v1c<-09~r*TQViN;*1iQDZr8 zGrn>Do-D#KB57s;^!G4-PNuxl+m9|s)JFga)=w3rS%a&);O1Y;#VTX*>)R&utPr80c$ckQ@F-3fn$ zvS0urUJ=Y`tYJtezVvNq``~|rE6)d_06`(iF~i(_#9p4y4P1}%Qru#hH>b5wFX(tB zj(VVMORyY&(R#=fo|hkDj^Qz8SS|W6GaIJ6AP_5~8R+S?Dj_&jOZrMX_#-^Lyul=6 zwuNViMH% z)+&QpK&)4Q1k$BIab@_v$`NibOrXY95Q$e-X!w7Ai%YzoIQ+n=YNeN{{ z-t>|##ic6S*}Yk#iE`V?a;3){qY+0kQHE*q@xRx*)hQXiww_g>>DRMFBk4W%G;}fK zuC*&01x(6D6978_YjfuM2U|6!kLzCV#c7E#5V5(a)4>op(^e$((9QBboEu+-3cpDG zE;{G>lXdHpvJb48J(DzG8L}g!`Qj^-&dx)qIv_i?y0@^i*IXc=BR2Ca<#=JNDyqE4 zUGsfA+lngO;t|0c+<^A)eG(|9(a{B)HiRE1cgkaiJ5N`6_r}?HkT$WsAV4W3P7(~# z;0Yy>wWYD8soH~BGg?@&8I|(a8Y7;-9sjw^g|cTVJ@*5*v^7da53=;bg5S{-;!Zo5}-kBdi<#0Ys}{- z)imOQk2JN_K=9;1}riJ{E%&yv< z1+_9#_|0i+$=J#9VwW~te{&F%^bMwy3}IoCj0rjYATl(iJGyIoAUOghP2P=Vv0It6 z!xOs%zVaS?-MMU&1Jq{x6dNW_j&YrhWPd&AC~%2nzibj7OH{y0K}tTFzO3(T9Wwr5 z3RnE`W|&j?c1FpB2RvF`!4K&a-GT9FDK1|lj9tuzHx zp0n)8$XjGN62U86h@yWDhQr^_x(=Ii6oC zrp}OK2TJHbVA4hHiEYZEl=WU?N(H;Qjlr!E2m7&lVm#`rq-2Yly1Z@!hcAM~DBhx% zvWg(vN1-oc&yE;T#%%E@Ktl(&mq@Ix%AfmP*EV>Y*<~sr@nhyhOP()H5VkmOGiU{^ z?i^Y76O@Tz>`C+hW56dA%a~qYpAGO1Dzrfk>JW7f^~jmRUiH1O*X^-@MtSK6n=Qw|2l@Os zuK@k7$y}IpipTR}JbLNwli8rhu=Ta(eTqHRUQ|@%x-qn-mP*b4%uz~=>WQ#b4~At! zhe`!l*p9&a%x=(W!U3ApBOkS^$sDKm<5z~IDZ={-!#Q$xY_gKr>ZzwAVXyn9`pG}s zkV7Tyy~qS0?UtGuHck$(pm(C14I9PqF9~c|+BrUyhw*;)OJ*Snk%~xG#1$#kgTy*w z5!`AcE4$m!6k6^SX>?PRg%iIsv~wz9`MmJdm4*ID-{)*!qcUe8KKMf!7!TPhH-@K$ z7Kuk!``Q0bR&mP9z4wwH`-JVLZ3pRfR51&a(?-Hk8#lg^r(0gRdR-UqZD1=?35W*& z6!1YqP#<<2Xux{K1SzQd7HXB6DxprG$|)%KGBP@djFSASX>Au-I5k#bV>Tq+G7S;z z-;#{(LFcSZD4g?_X^7Q)v`Rz)@o*S>GyM!PxI5A4k8?d zflAY(Q&u)bTWxY|Bb&~}`vYZIjsuOLK8PMedgfFbj@H-)$Jfu*7e#YpQ%0y>{;DuM z`8R{wS(FAtk?i7*_@p&17(2MK?SF`9wO1z`ImAm@(Z#>@?68h5@>@sEa{zf5pLj+q zksuisk_|KNrhEg&1GD_h$C;=q(0`L#vSXPQr0>A6CrqUY^p zDv`LqZ`sZxl4c`yXSB?K44jC@3zt{sC6 z#5F^IpWn~ufv_$Esa8bv?_okw%U8@oT1DW{f3Sd%`c45d{dX>z^ z;iFk*_Y8>AI1xgLF4A$?_h_E&)F7}P^H6KDemu%|6B}&*9~V76g-4VmfM*&+M2woZXVi5 z^!KbY!Nl|HB5!b;sC}5PL`eLFpbyrwPNS5+1Iyn8Ga{}D_o#j(*arZ#Boq9n<=axF zzp^CZNL9R_*ix8p;6Ex@gBFlWsH;el-j6+9DZP7UH(V|a0A?Fc&jBb*oz&mps2GGZ zqH*7VbZ??QA+1g`_GRFDK3n7p)Z1L=L85{YgNYSBiSofU2+db2R#S%?YV&`GgA1lH z^Ul>|*Vt!$a|O+%EcR)#EVvQF+O$XX4ryh0m@N+4^c7t#4CUN5Y~DcnPmHP;e6#GVm*U%FJ92cur*CB=DF0 zYA3s86Hl2kk=8%Wd_{*55qGGWDPd#NEp&f}G);;l5jhOlNbEq#;$!#+h!toyOQ0H} zZOatg^FJO4`Ea?!A7DnAnbW|hR)0mGT;|SQ+hSN1-b$hNulGj{910e%AG(TXpic<( z4SX=9AvC~RFKKLsQ2(*?WTk)x>SSgLgrPrliDScK$f48s*zVs5TmijNQ+sIYWhF#e zrU>&tCW>PtN#pR}mJomozo`GcFy2}fxH9-#wzQdZCGpu@n}s(A*(D??PF(_e!X`yG--iGMY{&;^u*13PBWg47Q~ z)Xcuf<^it{>vR#1{M7J~Vus5|ubySNeSG;9(3ALkXCYeWSP z^d7zUtv%b@*l{}NzPnVvakzrt)fCXTb;`l-gNEfs#E}l&DaVsEmB+g6YsT40p8Ck_Qhw9y*w)q`x=;qAT HH0b{Uiy6aG literal 0 HcmV?d00001 diff --git a/ifm3d_ros_driver/doc/noetic.md b/ifm3d_ros_driver/doc/noetic.md new file mode 100644 index 0000000..8c4a341 --- /dev/null +++ b/ifm3d_ros_driver/doc/noetic.md @@ -0,0 +1,64 @@ +# ifm3d_ros on Ubuntu 20.04 and ROS Noetic + + +Our package `ìfm3d-ros`, more precisely the `ifm3d_ros_driver`, depends on the underling C++ API `ifm3d`. This needs to be installed first. + +>NOTE: The instructions below apply if you plan to build and install `ifm3d` from source. +>NOTE: For older versions of the `ifm3d` (`0.12.0 TODO: add link to installation instructions for ifm3d on ifm3d.com once available + +You are now in position to install the `ifm3d-ros` wrapper. Please switch to the instructions [here](building.md). diff --git a/ifm3d_ros_driver/doc/rpc_error_codes.md b/ifm3d_ros_driver/doc/rpc_error_codes.md new file mode 100644 index 0000000..41615b8 --- /dev/null +++ b/ifm3d_ros_driver/doc/rpc_error_codes.md @@ -0,0 +1,9 @@ +# XML-RPC error codes + +The underlying C++ API `ifm3d` supports these error codes. They are only sent asynchronously, e.g. when configuring the camera. + +| error code | description | typical solutions | +| ----- | ------- | ----- | +| 104010 | JSON syntax validation failed | Internally the sent JSON string gets checked against a JSON schema. This error happens when the parses fails to complete. | +| 104011 | JSON does not match current schema | Internally the sent JSON string gets checked against a JSON schema. If the JSON string does not match, it will be discarded. No changes will be applied. The configuration state will be the same before trying to reconfigure. | +| 104014 | Invalid configuration | add | \ No newline at end of file diff --git a/ifm3d_ros_driver/doc/troubleshooting.md b/ifm3d_ros_driver/doc/troubleshooting.md new file mode 100644 index 0000000..0399b45 --- /dev/null +++ b/ifm3d_ros_driver/doc/troubleshooting.md @@ -0,0 +1,50 @@ +# ifm3d-ros Troubleshooting Guide + +You can use this guide to help you identify and resolve problems you may experience in using the ifm3d-ros package. + +# List of contents: + +- [ifm3d-ros services provide no response.](#ifm3d-ros-services-provide-no-response) + +## ifm3d-ros services provide no response +On systems utilizing a single core processor, you may find that the Dump, Config and Trigger services of ifm3d-ros package do not provide any response when invoked. + +This issue can be resolved by setting the "num_worker_threads" parameter for your ROS nodelet manager to use a value > 1. You can read more about this parameter [here](http://wiki.ros.org/nodelet). + +The snippet below show's how to set this parameter using the [nodelet.launch](https://github.com/ifm/ifm3d-ros/blob/master/launch/nodelet.launch) file of the ifm3d-ros package. + +``` + + + +``` + +Alternatively if a virtual machine is being used, configuring it to utilize more than one core should resolve this issue without any changes to the launch file. + +## ifm3d-ros nodelet can not connect to O3R camera head +If the user forgets to set the PCIC port (our standard communication port for data broadcasting) the default PCIC port argument will be used `default_pcic_port = 50010`. This TCP-IP port (`50010`) corresponds with the physical `port 0` on the VPU. The 2D RGB imager or 3D ToF imager of choice therefore needs to be connected to exactly this port. + +When these two port arguments don't match you will likely see something along these lines, being repeatedly posted to your shell: +``` +[ INFO] [1628860557.703261704]: Running dtors... +[ INFO] [1628860557.704592043]: Initializing camera... +[ INFO] [1628860558.705489893]: Initializing framegrabber... +[ INFO] [1628860558.706352595]: Initializing image buffer... +[ WARN] [1628860559.207288723]: Timeout waiting for camera! +[ WARN] [1628860559.708197339]: Timeout waiting for camera! +[ WARN] [1628860560.209029697]: Timeout waiting for camera! +[ WARN] [1628860560.709553855]: Timeout waiting for camera! +[ WARN] [1628860561.210310005]: Timeout waiting for camera! +[ WARN] [1628860561.710739497]: Timeout waiting for camera! +[ WARN] [1628860562.211714793]: Timeout waiting for camera! +[ WARN] [1628860562.712752207]: Timeout waiting for camera! +[ WARN] [1628860563.213765790]: Timeout waiting for camera! +[ WARN] [1628860563.714424040]: Timeout waiting for camera! +[ WARN] [1628860563.714658175]: Attempting to restart framegrabber... +``` + +The fix for this is easy: just remember the first 4 digits of the PCIC port argument will stay the same, the last one corresponds to the physical port as marked on the VPU. diff --git a/ifm3d_ros_driver/doc/visualization.md b/ifm3d_ros_driver/doc/visualization.md new file mode 100644 index 0000000..23a70b0 --- /dev/null +++ b/ifm3d_ros_driver/doc/visualization.md @@ -0,0 +1,28 @@ +## HOW to visualize the point cloud with RVIZ +The included launch file `camera.launch` will publish and remap all topics and services to `/ifm3d_ros_driver/xxx`, for example the point cloud topic will be remapped to `/ifm3d_ros_driver/camera/cloud`. + +When you open RVIZ for the first time and subscribe the point cloud topic to it, it will not be displayed as the transformation chain between the different reference frames is not complete. + +The first option is to use a "dummy" a static transform publisher to fix the missing link in the pose transformation chain: + +Open a new shell and run this simple `static_transform_publisher` to map the `ifm3d/camera_link` to the `map` frame. +``` +rosrun tf2_ros static_transform_publisher 1 0 0 0 0 0 map ifm3d/camera_link +``` + +The second option is to pick a different reference frame in the Rviz options: + +![Choose reference frame in the global options of Rviz](figures/rviz_ref_frame.png) + +### Change axis directions to suit your interpretation of a robot coordinate reference system +We have removed the rotation parameter which have been part of the `nodelet.launch` launch file which move the axis directions around. This decision was reached because we believe there should be only one place to change the extrinsic parameters to keep things unambiguous. +We suggest changing the extrinsic parameters via our JSON interface (see ifm3d) and the mapped dump and config ROS services for this. The extrinsic parameters are applied to every measurement (distance image, and point cloud). + +If you would still like to add a `tf publisher` which switches the X-, and Z-axis please see the example below. Afterwards the Z-axis will measure positive values in the direction of the center optical ray of each camera. +``` + +``` diff --git a/ifm3d_ros_driver/include/ifm3d_ros_driver/camera_nodelet.h b/ifm3d_ros_driver/include/ifm3d_ros_driver/camera_nodelet.h new file mode 100644 index 0000000..d048909 --- /dev/null +++ b/ifm3d_ros_driver/include/ifm3d_ros_driver/camera_nodelet.h @@ -0,0 +1,122 @@ +// -*- c++ -*- + +// SPDX-License-Identifier: Apache-2.0 +// Copyright (C) 2021 ifm electronic, gmbh + +#ifndef __IFM3D_ROS_CAMERA_NODELET_H__ +#define __IFM3D_ROS_CAMERA_NODELET_H__ + +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace ifm3d_ros +{ +/** + * This class implements the ROS nodelet interface to allow for running + * in-process data transport between ifm3d image data and ROS consumers. This + * class is used to manage, configure, and acquire data from a single ifm3d + * camera. + */ +class CameraNodelet : public nodelet::Nodelet +{ +private: + // + // Nodelet lifecycle functions + // + virtual void onInit() override; + + // + // ROS services + // + bool Dump(ifm3d_ros_msgs::Dump::Request& req, ifm3d_ros_msgs::Dump::Response& res); + bool Config(ifm3d_ros_msgs::Config::Request& req, ifm3d_ros_msgs::Config::Response& res); + bool Trigger(ifm3d_ros_msgs::Trigger::Request& req, ifm3d_ros_msgs::Trigger::Response& res); + bool SoftOff(ifm3d_ros_msgs::SoftOff::Request& req, ifm3d_ros_msgs::SoftOff::Response& res); + bool SoftOn(ifm3d_ros_msgs::SoftOn::Request& req, ifm3d_ros_msgs::SoftOn::Response& res); + + // + // This is our main publishing loop and its helper functions + // + void Run(); + bool InitStructures(std::uint16_t mask, std::uint16_t pcic_port); + bool AcquireFrame(); + + // + // state + // + std::string camera_ip_; + std::uint16_t xmlrpc_port_; + std::uint16_t pcic_port_; + std::string password_; + std::uint16_t schema_mask_; + int timeout_millis_; + double timeout_tolerance_secs_; + bool assume_sw_triggered_; + int soft_on_timeout_millis_; + double soft_on_timeout_tolerance_secs_; + int soft_off_timeout_millis_; + double soft_off_timeout_tolerance_secs_; + float frame_latency_thresh_; + + std::string frame_id_; + std::string optical_frame_id_; + + ifm3d::CameraBase::Ptr cam_; + ifm3d::FrameGrabber::Ptr fg_; + ifm3d::ImageBuffer::Ptr im_; + std::mutex mutex_; + + ros::NodeHandle np_; + std::unique_ptr it_; + + // + // Topics we publish + // + ros::Publisher cloud_pub_; + ros::Publisher uvec_pub_; + ros::Publisher extrinsics_pub_; + image_transport::Publisher distance_pub_; + // image_transport::Publisher distance_noise_pub_; + image_transport::Publisher amplitude_pub_; + image_transport::Publisher raw_amplitude_pub_; + image_transport::Publisher conf_pub_; + image_transport::Publisher good_bad_pub_; + image_transport::Publisher xyz_image_pub_; + image_transport::Publisher gray_image_pub_; + image_transport::Publisher rgb_image_pub_; + + // + // Services we advertise + // + ros::ServiceServer dump_srv_; + ros::ServiceServer config_srv_; + ros::ServiceServer trigger_srv_; + ros::ServiceServer soft_off_srv_; + ros::ServiceServer soft_on_srv_; + + // + // We use a ROS one-shot timer to kick off our publishing loop. + // + ros::Timer publoop_timer_; + +}; // end: class CameraNodelet + +} // namespace ifm3d_ros + +#endif // __IFM3D_ROS_CAMERA_NODELET_H__ diff --git a/ifm3d_ros_driver/launch/camera.launch b/ifm3d_ros_driver/launch/camera.launch new file mode 100644 index 0000000..a64cff0 --- /dev/null +++ b/ifm3d_ros_driver/launch/camera.launch @@ -0,0 +1,31 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ifm3d_ros_driver/launch/nodelet.launch b/ifm3d_ros_driver/launch/nodelet.launch new file mode 100644 index 0000000..c48f03f --- /dev/null +++ b/ifm3d_ros_driver/launch/nodelet.launch @@ -0,0 +1,117 @@ + + + + + + + + + + + + + + + + + + + + + + + + # + # The IP address of the camera to connect to + # + ip: "$(arg ip)" + + # + # The on-camera TCP port that the XMLRPC server is listening to + # + xmlrpc_port: $(arg xmlrpc_port) + + # + # The on-camera TCP port that the PCIC server is listening to + # + pcic_port: $(arg pcic_port) + + # + # The password needed to establish an edit session with the camera + # + password: "$(arg password)" + + # + # The PCIC schema mask to apply to the framegrabber + # + schema_mask: $(arg schema_mask) + + # + # The number of milliseconds to wait for a frame before declaring a + # framegrabber timeout + # + timeout_millis: $(arg timeout_millis) + + # + # The number of seconds to endure timeouts before restarting the framegrabber + # + timeout_tolerance_secs: $(arg timeout_tolerance_secs) + + # + # Flag indicating whether or not the nodelet should assume the camera is + # being software triggered + # + assume_sw_triggered: $(arg assume_sw_triggered) + + # + # If using the `SoftOff`/`SoftOn` functionality, these parameters + # control the `timeout_millis` and `timeout_tolerance_secs` + # + soft_on_timeout_millis: $(arg timeout_millis) + soft_on_timeout_tolerance_secs: $(arg timeout_tolerance_secs) + soft_off_timeout_millis: 500 + soft_off_timeout_tolerance_secs: 600.0 + + # + # Time (seconds) used to determine that timestamps from the camera + # cannot be trusted. When this threshold is exceeded, when compared to + # system time, we use the reception time of the frame and not the capture + # time of the frame. + # + frame_latency_thresh: 60.0 + + # + # Get rid of the errors when running `rosbag -a' + # + distance/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] + amplitude/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] + raw_amplitude/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] + confidence/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] + good_bad_pixels/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] + xyz_image/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] + + + + + + + + + + + + + diff --git a/ifm3d_ros_driver/nodelets.xml b/ifm3d_ros_driver/nodelets.xml new file mode 100644 index 0000000..15ecf95 --- /dev/null +++ b/ifm3d_ros_driver/nodelets.xml @@ -0,0 +1,10 @@ + + + + + Interface to the underlying ifm3d camera + + + diff --git a/ifm3d_ros_driver/package.xml b/ifm3d_ros_driver/package.xml new file mode 100644 index 0000000..f2e8d8e --- /dev/null +++ b/ifm3d_ros_driver/package.xml @@ -0,0 +1,31 @@ + + + + ifm3d_ros_driver + 0.7.0 + ifm 3D ToF Camera ROS main driver package + ifm CSR group + Apache 2 + CSR ifm sytron + https://github.com/ifm/ifm3d-ros/ + + catkin + + rostest + + rospy + image_transport + pcl_ros + cv_bridge + nodelet + roscpp + sensor_msgs + std_msgs + ifm3d_ros_msgs + + + + + + + diff --git a/ifm3d_ros_driver/src/camera_nodelet.cpp b/ifm3d_ros_driver/src/camera_nodelet.cpp new file mode 100644 index 0000000..bd4d7e6 --- /dev/null +++ b/ifm3d_ros_driver/src/camera_nodelet.cpp @@ -0,0 +1,628 @@ +/* + * SPDX-License-Identifier: Apache-2.0 + * Copyright (C) 2021 ifm electronic, gmbh + */ + +#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 +#include +#include +#include + +#include + +using json = nlohmann::json; +namespace enc = sensor_msgs::image_encodings; + +void ifm3d_ros::CameraNodelet::onInit() +{ + std::string nn = this->getName(); + NODELET_DEBUG_STREAM("onInit(): " << nn); + + this->np_ = getMTPrivateNodeHandle(); + this->it_.reset(new image_transport::ImageTransport(this->np_)); + + // + // parse data out of the parameter server + // + // NOTE: AFAIK, there is no way to get an unsigned int type out of the ROS + // parameter server. + // + int schema_mask; + int xmlrpc_port; + int pcic_port; + std::string frame_id_base; + + if ((nn.size() > 0) && (nn.at(0) == '/')) + { + frame_id_base = nn.substr(1); + } + else + { + frame_id_base = nn; + } + + this->np_.param("ip", this->camera_ip_, ifm3d::DEFAULT_IP); + NODELET_INFO("IP default: %s, current %s", ifm3d::DEFAULT_IP.c_str(), this->camera_ip_.c_str()); + + this->np_.param("xmlrpc_port", xmlrpc_port, (int)ifm3d::DEFAULT_XMLRPC_PORT); + this->np_.param("pcic_port", pcic_port, (int)ifm3d::DEFAULT_PCIC_PORT); + NODELET_INFO("pcic port check: current %d, default %d", pcic_port, ifm3d::DEFAULT_PCIC_PORT); + + this->np_.param("password", this->password_, ifm3d::DEFAULT_PASSWORD); + this->np_.param("schema_mask", schema_mask, (int)ifm3d::DEFAULT_SCHEMA_MASK); + this->np_.param("timeout_millis", this->timeout_millis_, 500); + this->np_.param("timeout_tolerance_secs", this->timeout_tolerance_secs_, 5.0); + this->np_.param("assume_sw_triggered", this->assume_sw_triggered_, false); + this->np_.param("soft_on_timeout_millis", this->soft_on_timeout_millis_, 500); + this->np_.param("soft_on_timeout_tolerance_secs", this->soft_on_timeout_tolerance_secs_, 5.0); + this->np_.param("soft_off_timeout_millis", this->soft_off_timeout_millis_, 500); + this->np_.param("soft_off_timeout_tolerance_secs", this->soft_off_timeout_tolerance_secs_, 600.0); + this->np_.param("frame_latency_thresh", this->frame_latency_thresh_, 60.0f); + this->np_.param("frame_id_base", frame_id_base, frame_id_base); + + this->xmlrpc_port_ = static_cast(xmlrpc_port); + this->schema_mask_ = static_cast(schema_mask); + this->pcic_port_ = static_cast(pcic_port); + + NODELET_DEBUG_STREAM("setup ros node parameters finished"); + + this->frame_id_ = frame_id_base + "_link"; + this->optical_frame_id_ = frame_id_base + "_optical_link"; + + //------------------- + // Published topics + //------------------- + this->cloud_pub_ = this->np_.advertise>("cloud", 1); + this->distance_pub_ = this->it_->advertise("distance", 1); + // this->distance_noise_pub_ = this->it_->advertise("distance_noise", 1); + this->amplitude_pub_ = this->it_->advertise("amplitude", 1); + this->raw_amplitude_pub_ = this->it_->advertise("raw_amplitude", 1); + this->conf_pub_ = this->it_->advertise("confidence", 1); + this->good_bad_pub_ = this->it_->advertise("good_bad_pixels", 1); + this->xyz_image_pub_ = this->it_->advertise("xyz_image", 1); + this->gray_image_pub_ = this->it_->advertise("gray_image", 1); + this->rgb_image_pub_ = this->it_->advertise("rgb_image", 1); + + // we latch the unit vectors + this->uvec_pub_ = this->np_.advertise("unit_vectors", 1, true); + + this->extrinsics_pub_ = this->np_.advertise("extrinsics", 1); + NODELET_DEBUG_STREAM("after advertising the publishers"); + //--------------------- + // Advertised Services + //--------------------- + this->dump_srv_ = this->np_.advertiseService( + "Dump", std::bind(&CameraNodelet::Dump, this, std::placeholders::_1, std::placeholders::_2)); + + this->config_srv_ = this->np_.advertiseService( + "Config", std::bind(&CameraNodelet::Config, this, std::placeholders::_1, std::placeholders::_2)); + + this->trigger_srv_ = this->np_.advertiseService( + "Trigger", std::bind(&CameraNodelet::Trigger, this, std::placeholders::_1, std::placeholders::_2)); + + this->soft_off_srv_ = this->np_.advertiseService( + "SoftOff", std::bind(&CameraNodelet::SoftOff, this, std::placeholders::_1, std::placeholders::_2)); + + this->soft_on_srv_ = this->np_.advertiseService( + "SoftOn", std::bind(&CameraNodelet::SoftOn, this, std::placeholders::_1, std::placeholders::_2)); + + NODELET_DEBUG_STREAM("after advertise service"); + //---------------------------------- + // Fire off our main publishing loop + //---------------------------------- + this->publoop_timer_ = this->np_.createTimer( + ros::Duration(.001), [this](const ros::TimerEvent& t) { this->Run(); }, + true); // oneshot timer +} + +bool ifm3d_ros::CameraNodelet::Dump(ifm3d_ros_msgs::Dump::Request& req, ifm3d_ros_msgs::Dump::Response& res) +{ + std::lock_guard lock(this->mutex_); + res.status = 0; + + try + { + json j = this->cam_->ToJSON(); + res.config = j.dump(); + } + catch (const ifm3d::error_t& ex) + { + res.status = ex.code(); + NODELET_WARN_STREAM(ex.what()); + } + catch (const std::exception& std_ex) + { + res.status = -1; + NODELET_WARN_STREAM(std_ex.what()); + } + catch (...) + { + res.status = -2; + } + + if (res.status != 0) + { + NODELET_WARN_STREAM("Dump: " << res.status); + } + + return true; +} + +bool ifm3d_ros::CameraNodelet::Config(ifm3d_ros_msgs::Config::Request& req, ifm3d_ros_msgs::Config::Response& res) +{ + std::lock_guard lock(this->mutex_); + res.status = 0; + res.msg = "OK"; + + try + { + this->cam_->FromJSON(json::parse(req.json)); + } + catch (const ifm3d::error_t& ex) + { + res.status = ex.code(); + res.msg = ex.what(); + } + catch (const std::exception& std_ex) + { + res.status = -1; + res.msg = std_ex.what(); + } + catch (...) + { + res.status = -2; + res.msg = "Unknown error in `Config'"; + } + + if (res.status != 0) + { + NODELET_WARN_STREAM("Config: " << res.status << " - " << res.msg); + } + + return true; +} + +bool ifm3d_ros::CameraNodelet::Trigger(ifm3d_ros_msgs::Trigger::Request& req, ifm3d_ros_msgs::Trigger::Response& res) +{ + std::lock_guard lock(this->mutex_); + res.status = 0; + res.msg = "Software trigger is currently not implemented"; + + try + { + this->fg_->SWTrigger(); + } + catch (const ifm3d::error_t& ex) + { + res.status = ex.code(); + } + + NODELET_WARN_STREAM("Triggering a camera head is currently not implemented - will follow"); + return true; +} + +// this is a dummy method for the moment: the idea of applications is not supported for the O3RCamera +// we keep this in to possibly keep it comparable / interoperable with the ROS wrappers for other ifm cameras +bool ifm3d_ros::CameraNodelet::SoftOff(ifm3d_ros_msgs::SoftOff::Request& req, ifm3d_ros_msgs::SoftOff::Response& res) +{ + std::lock_guard lock(this->mutex_); + res.status = 0; + + int port_arg = -1; + + try + { + port_arg = static_cast(this->pcic_port_) % 50010; + + // Configure the device from a json string + this->cam_->FromJSONStr("{\"ports\":{\"port" + std::to_string(port_arg) + "\": {\"state\": \"IDLE\"}}}"); + + this->assume_sw_triggered_ = false; + this->timeout_millis_ = this->soft_on_timeout_millis_; + this->timeout_tolerance_secs_ = this->soft_on_timeout_tolerance_secs_; + } + catch (const ifm3d::error_t& ex) + { + res.status = ex.code(); + res.msg = ex.what(); + return false; + } + + NODELET_WARN_STREAM("The concept of applications is not available for the O3R - we use IDLE and RUN states instead"); + res.msg = "{\"ports\":{\"port" + std::to_string(port_arg) + "\": {\"state\": \"IDLE\"}}}"; + + return true; +} + +// this is a dummy method for the moment: the idea of applications is not supported for the O3RCamera +// we keep this in to possibly keep it comparable / interoperable with the ROS wrappers for other ifm cameras +bool ifm3d_ros::CameraNodelet::SoftOn(ifm3d_ros_msgs::SoftOn::Request& req, ifm3d_ros_msgs::SoftOn::Response& res) +{ + std::lock_guard lock(this->mutex_); + res.status = 0; + int port_arg = -1; + + try + { + port_arg = static_cast(this->pcic_port_) % 50010; + + // try getting a current configuration as an ifm3d dump + // this way a a-priori test before setting the state can be tested + // try + // { + // json j = this->cam_->ToJSON(); + // } + // catch (const ifm3d::error_t& ex) + // { + // NODELET_WARN_STREAM(ex.code()); + // NODELET_WARN_STREAM(ex.what()); + // } + // catch (const std::exception& std_ex) + // { + // NODELET_WARN_STREAM(std_ex.what()); + // } + + // Configure the device from a json string + this->cam_->FromJSONStr("{\"ports\":{\"port" + std::to_string(port_arg) + "\": {\"state\": \"RUN\"}}}"); + + this->assume_sw_triggered_ = false; + this->timeout_millis_ = this->soft_on_timeout_millis_; + this->timeout_tolerance_secs_ = this->soft_on_timeout_tolerance_secs_; + } + catch (const ifm3d::error_t& ex) + { + res.status = ex.code(); + res.msg = ex.what(); + return false; + } + + NODELET_WARN_STREAM("The concept of applications is not available for the O3R - we use IDLE and RUN states instead"); + res.msg = "{\"ports\":{\"port" + std::to_string(port_arg) + "\": {\"state\": \"RUN\"}}}"; + + return true; +} + +bool ifm3d_ros::CameraNodelet::InitStructures(std::uint16_t mask, std::uint16_t pcic_port) +{ + std::lock_guard lock(this->mutex_); + bool retval = false; + + try + { + NODELET_INFO_STREAM("Running dtors..."); + this->im_.reset(); + this->fg_.reset(); + this->cam_.reset(); + + NODELET_INFO_STREAM("Initializing camera..."); + this->cam_ = ifm3d::CameraBase::MakeShared(); + // this->cam_ = ifm3d::CameraBase::MakeShared(this->camera_ip_, this->xmlrpc_port_); + // this->cam_ = std::make_shared(this->camera_ip_, this->xmlrpc_port_); + ros::Duration(1.0).sleep(); + + NODELET_INFO_STREAM("Initializing framegrabber..."); + this->fg_ = std::make_shared(this->cam_, mask, this->pcic_port_); + NODELET_INFO("Nodelet arguments: %d, %d", (int)mask, (int)this->pcic_port_); + + NODELET_INFO_STREAM("Initializing image buffer..."); + this->im_ = std::make_shared(); + + retval = true; + } + catch (const ifm3d::error_t& ex) + { + NODELET_WARN_STREAM(ex.code() << ": " << ex.what()); + this->im_.reset(); + this->fg_.reset(); + this->cam_.reset(); + retval = false; + } + + return retval; +} + +// this is the helper function for retrieving complete pcic frames +bool ifm3d_ros::CameraNodelet::AcquireFrame() +{ + std::lock_guard lock(this->mutex_); + bool retval = false; + NODELET_DEBUG_STREAM("try receiving data via fg WaitForFrame"); + try + { + retval = this->fg_->WaitForFrame(this->im_.get(), this->timeout_millis_); + } + catch (const ifm3d::error_t& ex) + { + NODELET_WARN_STREAM(ex.code() << ": " << ex.what()); + retval = false; + } + + return retval; +} + +void ifm3d_ros::CameraNodelet::Run() +{ + std::unique_lock lock(this->mutex_, std::defer_lock); + + NODELET_DEBUG_STREAM("in Run"); + + // We need to account for the case of when the nodelet is being started prior + // to the camera being plugged in. + + while (ros::ok() && (!this->InitStructures(ifm3d::IMG_UVEC, this->pcic_port_))) + { + NODELET_WARN_STREAM("Could not initialize pixel stream!"); + ros::Duration(1.0).sleep(); + } + + pcl::PointCloud::Ptr cloud(new pcl::PointCloud()); + + cv::Mat confidence_img; + cv::Mat distance_img; + // cv::Mat distance_noise_img; + cv::Mat amplitude_img; + cv::Mat xyz_img; + cv::Mat raw_amplitude_img; + cv::Mat good_bad_pixels_img; + cv::Mat gray_img; + cv::Mat rgb_img; + + NODELET_DEBUG_STREAM("after initializing the opencv buffers"); + std::vector extrinsics(6); + + // XXX: need to implement a nice strategy for getting the actual times + // from the camera which are registered to the frame data in the image + // buffer. + ros::Time last_frame = ros::Time::now(); + bool got_uvec = false; + + while (ros::ok()) + { + if (!this->AcquireFrame()) + { + if (!this->assume_sw_triggered_) + { + NODELET_WARN_STREAM("Timeout waiting for camera!"); + } + else + { + ros::Duration(.001).sleep(); + } + + if ((ros::Time::now() - last_frame).toSec() > this->timeout_tolerance_secs_) + { + NODELET_WARN_STREAM("Attempting to restart framegrabber..."); + while (!this->InitStructures(got_uvec ? this->schema_mask_ : ifm3d::IMG_UVEC, this->pcic_port_)) + { + NODELET_WARN_STREAM("Could not re-initialize pixel stream!"); + ros::Duration(1.0).sleep(); + } + + last_frame = ros::Time::now(); + } + + continue; + } + + last_frame = ros::Time::now(); + + NODELET_DEBUG_STREAM("prepare header"); + std_msgs::Header head = std_msgs::Header(); + head.frame_id = this->frame_id_; + head.stamp = ros::Time(std::chrono::duration_cast>>( + this->im_->TimeStamp().time_since_epoch()) + .count()); + if ((ros::Time::now() - head.stamp) > ros::Duration(this->frame_latency_thresh_)) + { + NODELET_INFO_ONCE("Camera's time and client's time are not synced"); + head.stamp = ros::Time::now(); + } + NODELET_DEBUG_STREAM("in header, before setting header to msgs"); + std_msgs::Header optical_head = std_msgs::Header(); + optical_head.stamp = head.stamp; + optical_head.frame_id = this->optical_frame_id_; + + // currently the unit vector calculation seems to be missing in the ifm3d state: therefore we don't publish anything + // to the uvec pubisher publish unit vectors once on a latched topic, then re-initialize the framegrabber with the + // user's requested schema mask + if (!got_uvec) + { + lock.lock(); + sensor_msgs::ImagePtr uvec_msg = + cv_bridge::CvImage(optical_head, enc::TYPE_32FC3, this->im_->UnitVectors()).toImageMsg(); + NODELET_INFO_STREAM("uvec image size: " << this->im_->UnitVectors().size()); + lock.unlock(); + this->uvec_pub_.publish(uvec_msg); + got_uvec = true; + NODELET_INFO("Got unit vectors, restarting framegrabber with mask: %d", (int)this->schema_mask_); + + while (!this->InitStructures(this->schema_mask_, this->pcic_port_)) + { + NODELET_WARN("Could not re-initialize pixel stream!"); + ros::Duration(1.0).sleep(); + } + + NODELET_INFO_STREAM("Start streaming data"); + continue; + } + + // + // Pull out all the wrapped images so that we can release the "GIL" + // while publishing + // + lock.lock(); + + NODELET_DEBUG_STREAM("start getting data"); + try + { + // boost::shared_ptr vs std::shared_ptr forces this copy + pcl::copyPointCloud(*(this->im_->Cloud().get()), *cloud); + xyz_img = this->im_->XYZImage(); + confidence_img = this->im_->ConfidenceImage(); + distance_img = this->im_->DistanceImage(); + amplitude_img = this->im_->AmplitudeImage(); + raw_amplitude_img = this->im_->RawAmplitudeImage(); + gray_img = this->im_->GrayImage(); + extrinsics = this->im_->Extrinsics(); + rgb_img = this->im_->JPEGImage(); + } + catch (const ifm3d::error_t& ex) + { + NODELET_WARN_STREAM(ex.what()); + } + catch (const std::exception& std_ex) + { + NODELET_WARN_STREAM(std_ex.what()); + } + NODELET_DEBUG_STREAM("finished getting data"); + + lock.unlock(); + + // + // Now, do the publishing + // + + NODELET_DEBUG_STREAM("start publishing"); + // Confidence image is invariant - no need to check the mask + sensor_msgs::ImagePtr confidence_msg = cv_bridge::CvImage(optical_head, "mono16", confidence_img).toImageMsg(); + this->conf_pub_.publish(confidence_msg); + NODELET_DEBUG_STREAM("after publishing confidence image"); + + if ((this->schema_mask_ & ifm3d::IMG_CART) == ifm3d::IMG_CART) + { + cloud->header = pcl_conversions::toPCL(head); + this->cloud_pub_.publish(cloud); + + sensor_msgs::ImagePtr xyz_image_msg = + cv_bridge::CvImage(head, xyz_img.type() == CV_32FC3 ? enc::TYPE_32FC3 : enc::TYPE_16SC3, xyz_img) + .toImageMsg(); + this->xyz_image_pub_.publish(xyz_image_msg); + NODELET_DEBUG_STREAM("after publishing xyz image"); + } + + if ((this->schema_mask_ & ifm3d::IMG_RDIS) == ifm3d::IMG_RDIS) + { + sensor_msgs::ImagePtr distance_msg = + cv_bridge::CvImage(optical_head, distance_img.type() == CV_32FC1 ? enc::TYPE_32FC1 : enc::TYPE_16UC1, + distance_img) + .toImageMsg(); + this->distance_pub_.publish(distance_msg); + NODELET_DEBUG_STREAM("after publishing distance image"); + } + + // this image is currently not available via the ifm3d + // if ((this->schema_mask_ & ifm3d::IMG_DIS_NOISE) == ifm3d::IMG_DIS_NOISE) + // { + // sensor_msgs::ImagePtr distance_noise_msg = + // cv_bridge::CvImage(optical_head, + // distance_noise_img.type() == CV_32FC1 ? + // enc::TYPE_32FC1 : enc::TYPE_16UC1, + // distance_noise_img).toImageMsg(); + // this->distance_noise_pub_.publish(distance_noise_msg); + // } + + if ((this->schema_mask_ & ifm3d::IMG_AMP) == ifm3d::IMG_AMP) + { + sensor_msgs::ImagePtr amplitude_msg = + cv_bridge::CvImage(optical_head, amplitude_img.type() == CV_32FC1 ? enc::TYPE_32FC1 : enc::TYPE_16UC1, + amplitude_img) + .toImageMsg(); + this->amplitude_pub_.publish(amplitude_msg); + NODELET_DEBUG_STREAM("after publishing amplitude image"); + } + + if ((this->schema_mask_ & ifm3d::IMG_RAMP) == ifm3d::IMG_RAMP) + { + sensor_msgs::ImagePtr raw_amplitude_msg = + cv_bridge::CvImage(optical_head, raw_amplitude_img.type() == CV_32FC1 ? enc::TYPE_32FC1 : enc::TYPE_16UC1, + raw_amplitude_img) + .toImageMsg(); + this->raw_amplitude_pub_.publish(raw_amplitude_msg); + NODELET_DEBUG_STREAM("Raw amplitude image publisher is a dummy publisher - data will be added soon"); + NODELET_DEBUG_STREAM("after publishing raw amplitude image"); + } + + if ((this->schema_mask_ & ifm3d::IMG_GRAY) == ifm3d::IMG_GRAY) + { + sensor_msgs::ImagePtr gray_image_msg = + cv_bridge::CvImage(optical_head, gray_img.type() == CV_32FC1 ? enc::TYPE_32FC1 : enc::TYPE_16UC1, gray_img) + .toImageMsg(); + this->gray_image_pub_.publish(gray_image_msg); + NODELET_DEBUG_STREAM("Gray image publisher is a dummy publisher - data will be added soon"); + NODELET_DEBUG_STREAM("after publishing gray image"); + } + + // TODO: this casting of the confidence image to a boolean value image needs to be tested: + // inv cast might be reqiured depending on the interpretation of the binary image + + int const min_binary_value = 0; + int const max_binary_value = 100; + cv::threshold(confidence_img, good_bad_pixels_img, min_binary_value, max_binary_value, cv::THRESH_BINARY); + good_bad_pixels_img.convertTo(good_bad_pixels_img, CV_8U); + + sensor_msgs::ImagePtr good_bad_msg = cv_bridge::CvImage(optical_head, "mono8", good_bad_pixels_img).toImageMsg(); + this->good_bad_pub_.publish(good_bad_msg); + NODELET_DEBUG_STREAM("after publishing good/bad pixel image image"); + + // The 2D is not yet settable in the schema mask: publish all the time + + if (!rgb_img.empty()) + { + cv::Mat im_decode = cv::imdecode(rgb_img, cv::IMREAD_UNCHANGED); + sensor_msgs::ImagePtr rgb_image_msg = cv_bridge::CvImage(optical_head, "bgr8", im_decode).toImageMsg(); + this->rgb_image_pub_.publish(rgb_image_msg); + NODELET_DEBUG_STREAM("after publishing rgb image"); + } + + // + // publish extrinsics + // + NODELET_DEBUG_STREAM("start publishing extrinsics"); + ifm3d_ros_msgs::Extrinsics extrinsics_msg; + extrinsics_msg.header = optical_head; + try + { + extrinsics_msg.tx = extrinsics.at(0); + extrinsics_msg.ty = extrinsics.at(1); + extrinsics_msg.tz = extrinsics.at(2); + extrinsics_msg.rot_x = extrinsics.at(3); + extrinsics_msg.rot_y = extrinsics.at(4); + extrinsics_msg.rot_z = extrinsics.at(5); + } + catch (const std::out_of_range& ex) + { + NODELET_WARN("out-of-range error fetching extrinsics"); + } + this->extrinsics_pub_.publish(extrinsics_msg); + + } // end: while (ros::ok()) { ... } +} // end: Run() + +PLUGINLIB_EXPORT_CLASS(ifm3d_ros::CameraNodelet, nodelet::Nodelet) diff --git a/ifm3d_ros_driver/test/gradient.jpg b/ifm3d_ros_driver/test/gradient.jpg new file mode 100644 index 0000000000000000000000000000000000000000..e2d788b633a7ea0e3fe6450e3d191f13ccb3067e GIT binary patch literal 1363 zcmeH`K}_0E7{^~*XrWpGL55(kxS}{1nUjc1x(udsbjBEW8aER-NaEb$smm@9)R{#V zEQtpX#uzTUO%6*;c0jif$u5Qyn`Xg`-FE19*l7vtdrgX-mfiQ-{L*}V?|uL8egD_0 zw;I6wU`m(*7zO~QJfL+7R)CSD3>4X8pbRu^)H94;ufW78pSB*my~kp;I{JL9!|8Qd zt)3B&ci0~c2Cwvwj*kYyzUx6hM$@#irb~JKz1Cj;KaW-!SPbAbc8$OW0B*qu3)cDo z9Ewb3fc7ACxPems*v*&Y$_yN?uw9ys*1@Rd;vQ=BGw38RB^6--cYyqR=~1O=^ll1C z<6yp8?0{f~(n5ow($R(qf%fpeH1AuH_pnJfMy2Oq)D~@+MdDCHw0I*$RFe!Nzr$YHx~PD=RP{lG8|0H)p|pjBt%g*^4P8>?|gD- z)l8vE+Vb&r9yb9|!$N3{VV?zFPP1_Y?v=oP8LNzSxhvl`mLd{NE2TQOBPEEMsM`T2 znml>WdbCcUO3>*e`D#me*cXJ5bArtCTlc*A0D^R%%Rg}?T$CxXTnV!ROe=)eX4p7H zipOWcf+kO#GoDXks1kJgs(jQEH|z_7lksF@?&$&P*p47vm15!CelGiB{~+PYb1*Hp zJu#RMK!kR%p>#--hin8;B^TtQmZ)Zf-eSo7VbKIl*@3`qRykLtUO9YUKikh8cf+*Z zGoC`s4&j^yg|btVr`iZrazQ?7iE1|JEixOMuTjvHdKIyz#C%;$%%6Y%e + + + + + diff --git a/ifm3d_ros_driver/test/test_camera.py b/ifm3d_ros_driver/test/test_camera.py new file mode 100755 index 0000000..3f11705 --- /dev/null +++ b/ifm3d_ros_driver/test/test_camera.py @@ -0,0 +1,240 @@ +#!/usr/bin/env python +# -*- python -*- + +# SPDX-License-Identifier: Apache-2.0 +# Copyright (C) 2021 ifm electronic, gmbh + + +import sys +import time +import unittest +import rospy +import rostest +import numpy as np +import tf2_ros +import tf2_geometry_msgs +from sensor_msgs.msg import Image +from geometry_msgs.msg import PointStamped +from cv_bridge import CvBridge, CvBridgeError +from ifm3d.msg import Extrinsics + +# XXX: TP debugging +#np.set_printoptions(threshold=np.nan) + +class TestCamera(unittest.TestCase): + """ + TP: 14 May 2018 - heavily adapted from my old o3d3xx-ros test of the same + name. + + This class tests the following: + - Getting data from the camera + - Computing the Cartesian data and comparing it to ground truth + - To do the comparison to ground truth, the computed cartesian data + must be transformed, to do that we use the tf2 API. It follows that + this indirectly is testing our tf2 static publisher which is publishing + the transform between the optical and camera frames + + NOTE: The camera h/w is needed to run this test. + """ + + def __init__(self, *args): + super(TestCamera, self).__init__(*args) + self.success_ = False + + self.cloud_ = None # ground truth for cartesian computation + self.rdis_ = None + self.uvec_ = None + self.extrinsics_ = None + self.conf_ = None + + def test_camera(self): + time.sleep(5.0) # <-- wait for rosmaster and ifm3d nodelet + rospy.init_node('test_camera') + + self.bridge_ = CvBridge() + self.rdis_sub_ = \ + rospy.Subscriber("/ifm3d/camera/distance", Image, self.image_cb, + queue_size=None, callback_args="rdis") + self.cloud_sub_ = \ + rospy.Subscriber("/ifm3d/camera/xyz_image", Image, self.image_cb, + queue_size=None, callback_args="cloud") + self.uvec_sub_ = \ + rospy.Subscriber("/ifm3d/camera/unit_vectors", Image, self.image_cb, + queue_size=None, callback_args="uvec") + self.extrinsics_sub_ = \ + rospy.Subscriber("/ifm3d/camera/extrinsics", Extrinsics, + self.extrinsics_cb, queue_size=None) + self.conf_sub_ = \ + rospy.Subscriber("/ifm3d/camera/confidence", Image, self.image_cb, + queue_size=None, callback_args="conf") + + # If it takes more than 10 secs to run our test, something is wrong. + timeout_t = time.time() + 10.0 + rate = rospy.Rate(10.0) + while ((not rospy.is_shutdown()) and + (not self.success_) and + (time.time() < timeout_t)): + # Make sure we have all the data we need to compute + if ((self.rdis_ is not None) and + (self.cloud_ is not None) and + (self.uvec_ is not None) and + (self.extrinsics_ is not None) and + (self.conf_ is not None)): + + # Make sure the cloud, conf, and rdis are from the same image + # acquisition. + d = self.rdis_.header.stamp - self.cloud_.header.stamp + if d.to_sec() == 0: + d2 = self.rdis_.header.stamp - self.conf_.header.stamp + if d2.to_sec() == 0: + self.success_ = self.compute_cartesian() + break + else: + # get new data + self.rdis_ = None + self.cloud_ = None + self.conf_ = None + else: + # get new data + self.rdis_ = None + self.cloud_ = None + self.conf_ = None + + rate.sleep() + + self.assertTrue(self.success_) + + def extrinsics_cb(self, data, *args): + if self.extrinsics_ is None: + self.extrinsics_ = data + + def image_cb(self, data, *args): + im_type = args[0] + if im_type == "rdis": + if self.rdis_ is None: + self.rdis_ = data + elif im_type == "cloud": + if self.cloud_ is None: + self.cloud_ = data + elif im_type == "uvec": + if self.uvec_ is None: + self.uvec_ = data + elif im_type == "conf": + if self.conf_ is None: + self.conf_ = data + + def compute_cartesian(self): + """ + Computes the Cartesian data from the radial distance image, unit + vectors, and extrinsics. Then transforms it to the camera frame using + the tf2 api. Once transformed, it will do a pixel-by-pixel comparision + to ground truth. + + Returns a bool indicating the the success of the computation. + """ + rdis = np.array(self.bridge_.imgmsg_to_cv2(self.rdis_)) + uvec = np.array(self.bridge_.imgmsg_to_cv2(self.uvec_)) + cloud = np.array(self.bridge_.imgmsg_to_cv2(self.cloud_)) + conf = np.array(self.bridge_.imgmsg_to_cv2(self.conf_)) + + # split out the camera-computed image planes + x_cam = cloud[:,:,0] + y_cam = cloud[:,:,1] + z_cam = cloud[:,:,2] + if ((cloud.dtype == np.float32) or + (cloud.dtype == np.float64)): + # convert to mm + x_cam *= 1000. + y_cam *= 1000. + z_cam *= 1000. + + # cast to int16_t + x_cam = x_cam.astype(np.int16) + y_cam = y_cam.astype(np.int16) + z_cam = z_cam.astype(np.int16) + else: + # camera data are already in mm + pass + + # Get the unit vectors + ex = uvec[:,:,0] + ey = uvec[:,:,1] + ez = uvec[:,:,2] + + # translation vector from extrinsics + tx = self.extrinsics_.tx + ty = self.extrinsics_.ty + tz = self.extrinsics_.tz + + # Cast the radial distance image to float + rdis_f = rdis.astype(np.float32) + if (rdis.dtype == np.float32): + # assume rdis was in meters, convert to mm + rdis_f *= 1000. + + # Compute Cartesian + x_ = ex * rdis_f + tx + y_ = ey * rdis_f + ty + z_ = ez * rdis_f + tz + + # mask out bad pixels from our computed cartesian values + bad_mask = (np.bitwise_and(conf, 0x1) == 0x1) + x_[bad_mask] = 0. + y_[bad_mask] = 0. + z_[bad_mask] = 0. + + # Transform to target frame + # + # NOTE: This could obviously be vectorized if we exploit our apriori + # knowledge of the transform, but we want to test the transform we are + # broadcasting via tf and the tf2 api for doing the transformation. + # + # I agree, this loop is slow and ugly :-( -- mostly b/c using the tf2 + # interface with our data structures here is kind of wonky + # + tf_buffer = tf2_ros.Buffer() + tf_listener = tf2_ros.TransformListener(tf_buffer) + n_rows = x_.shape[0] + n_cols = x_.shape[1] + x_f = np.zeros((n_rows, n_cols), dtype=np.float32) + y_f = np.zeros((n_rows, n_cols), dtype=np.float32) + z_f = np.zeros((n_rows, n_cols), dtype=np.float32) + for i in range(n_rows): + for j in range(n_cols): + p = PointStamped() + p.header = self.rdis_.header + p.point.x = x_[i,j] + p.point.y = y_[i,j] + p.point.z = z_[i,j] + pt = tf_buffer.transform(p, self.cloud_.header.frame_id, + rospy.Duration(2.0)) + x_f[i,j] = pt.point.x + y_f[i,j] = pt.point.y + z_f[i,j] = pt.point.z + + # cast to the data type of the point cloud + x_i = x_f.astype(np.int16) + y_i = y_f.astype(np.int16) + z_i = z_f.astype(np.int16) + + tol = 10 # milli-meters + x_mask = np.fabs(x_i - x_cam) > tol + y_mask = np.fabs(y_i - y_cam) > tol + z_mask = np.fabs(z_i - z_cam) > tol + + # we are asserting that no pixels are out-of-tolerance + # per the computation of the x_,y_,z_mask variables above. + self.assertTrue(x_mask.sum() == 0) + self.assertTrue(y_mask.sum() == 0) + self.assertTrue(z_mask.sum() == 0) + + # if any of the above asserts fail, the test will error out, + # so, we return True here carte blanche + return True + +def main(): + rostest.rosrun('ifm3d', 'test_camera', TestCamera, sys.argv) + return 0 + +if __name__ == '__main__': + sys.exit(main()) diff --git a/ifm3d_ros_driver/test/test_threshold.py b/ifm3d_ros_driver/test/test_threshold.py new file mode 100644 index 0000000..7d1d7ba --- /dev/null +++ b/ifm3d_ros_driver/test/test_threshold.py @@ -0,0 +1,41 @@ +import cv2 as cv +import numpy as np +from matplotlib import pyplot as plt + +def test_random(): + min = 50 + max = 200 + img = np.random.randint(0,200, size=(172,224), dtype=np.uint16) + ret,thresh1 = cv.threshold(img,min,max,cv.THRESH_BINARY) + ret,thresh2 = cv.threshold(img,min,max,cv.THRESH_BINARY_INV) + ret,thresh3 = cv.threshold(img,min,max,cv.THRESH_TRUNC) + ret,thresh4 = cv.threshold(img,min,max,cv.THRESH_TOZERO) + ret,thresh5 = cv.threshold(img,min,max,cv.THRESH_TOZERO_INV) + + titles = ['Original Image','BINARY','BINARY_INV','TRUNC','TOZERO','TOZERO_INV'] + images = [img, thresh1, thresh2, thresh3, thresh4, thresh5] + for i in range(6): + plt.subplot(2,3,i+1),plt.imshow(images[i],'gray',vmin=0,vmax=255) + plt.title(titles[i]) + plt.xticks([]),plt.yticks([]) + plt.show() + + +def test_image(): + img = cv.imread('gradient.jpg',0) + ret,thresh1 = cv.threshold(img,127,255,cv.THRESH_BINARY) + ret,thresh2 = cv.threshold(img,127,255,cv.THRESH_BINARY_INV) + ret,thresh3 = cv.threshold(img,127,255,cv.THRESH_TRUNC) + ret,thresh4 = cv.threshold(img,127,255,cv.THRESH_TOZERO) + ret,thresh5 = cv.threshold(img,127,255,cv.THRESH_TOZERO_INV) + + titles = ['Original Image','BINARY','BINARY_INV','TRUNC','TOZERO','TOZERO_INV'] + images = [img, thresh1, thresh2, thresh3, thresh4, thresh5] + for i in range(6): + plt.subplot(2,3,i+1),plt.imshow(images[i],'gray',vmin=0,vmax=255) + plt.title(titles[i]) + plt.xticks([]),plt.yticks([]) + plt.show() + +if __name__ == '__main__': + test_random() diff --git a/ifm3d_ros_examples/CMakeLists.txt b/ifm3d_ros_examples/CMakeLists.txt new file mode 100644 index 0000000..bfd7203 --- /dev/null +++ b/ifm3d_ros_examples/CMakeLists.txt @@ -0,0 +1,19 @@ +cmake_minimum_required(VERSION 3.0.2) +project(ifm3d_ros_examples) + +find_package(catkin REQUIRED COMPONENTS + tf2_ros + nodelet + ifm3d_ros_driver + ifm3d_ros_msgs +) + + +catkin_package() + +########### +## Build ## +########### +include_directories( + ${catkin_INCLUDE_DIRS} +) diff --git a/ifm3d_ros_examples/LICENSE b/ifm3d_ros_examples/LICENSE new file mode 100644 index 0000000..7a4a3ea --- /dev/null +++ b/ifm3d_ros_examples/LICENSE @@ -0,0 +1,202 @@ + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. \ No newline at end of file diff --git a/ifm3d_ros_examples/README.md b/ifm3d_ros_examples/README.md new file mode 100644 index 0000000..7a455dd --- /dev/null +++ b/ifm3d_ros_examples/README.md @@ -0,0 +1,41 @@ +# The `ifm3d_ros_examples` package +This package provides examples and helper scripts for using the ifm O3R camera platform. + + +## Launchfiles + +Please see the list below for launch files shipped with the examples package: + +| Name | Description | +| ---- | ----------- | +| `six_cameras.launch` | Launches six nodes, reading data streams on ports 0, 1, 2, 3, 4 and 5. Provide coordinate frame transforms for each node. Note: you can use this example for less than six heads, but you will get a `timeout` error where no heads are connected. This does not disrupt the proper functioning of the connected heads.| +| `nodelet.launch` | This is handling the nodelet manager which makes it possible to launch a nodelet similarly as you would a simple node.| +| `head.launch` | Launches two data streams for both the 2D RGB imager and 3D TOF imager on a camera head. Default ports are 0 (pcic_port:=50010) and 2 (pcic_port:=50012). For different port numbers input port as a parameter when launching. | +| `camera.launch` | Launches a single camera stream - so only 3D data or 2D RGB data. This launch file is comparable to a single camera setup (O3Ds and O3Xs) | + +### Nodelet launch structure + +>Note: The O3R platform can handle multiple data streams.* +The `camera.launch` file only launches a node for one data stream, on the default pcic port 50010. To launch a node for a different port, use: +``` +$ roslaunch ifm3d_ros_driver camera.launch pcic_port:= +``` + + +The launch file(s) encapsulate several features: +1. It (partially) exposes the `camera_nodelet` parameters as command-line arguments for ease of runtime configuration. +2. It instantiates a nodelet manager which the `camera_nodelet` will be loaded into. +3. It launches the camera nodelet itself. +4. It publishes the static transform from the camera's optical frame to a traditional ROS sensor frame as a tf2 `static_transform_publisher`. + +You can either use [this launch file](launch/camera.launch) directly, or, use it as a basis for integrating `ifm3d_ros` into your own robot software system. + +> Note: the O3R camera heads carry two imagers, a 3D time-of-flight and a RGB imager. + +We provide the `head.launch` launchfile to handle a whole O3R camera head, that starts two nodes, one for the RGB image (we assume it is plugged in port 0), and one for the 3D imager (we assume it is plugged in port 2). + +## Building launch files distributed systems +>Note: This is WIR. We are currently working on Docker images which will allow you an easy deployment of our ROS node to the VPU. + +# LICENSE +Please see the file called [LICENSE](LICENSE). \ No newline at end of file diff --git a/ifm3d_ros_examples/config/rviz_config.rviz b/ifm3d_ros_examples/config/rviz_config.rviz new file mode 100644 index 0000000..e4054c7 --- /dev/null +++ b/ifm3d_ros_examples/config/rviz_config.rviz @@ -0,0 +1,184 @@ +Panels: + - Class: rviz/Displays + Help Height: 70 + Name: Displays + Property Tree Widget: + Expanded: ~ + Splitter Ratio: 0.747222245 + Tree Height: 900 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: PointCloud2 +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: /ifm3d/camera1/cloud + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /ifm3d/camera1/amplitude + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /ifm3d/camera1/distance + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /ifm3d/camera2/rgb_image + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 10 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.7853981852531433 + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.45539799332618713 + Target Frame: + Yaw: 0.6153985261917114 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1016 + Hide Left Dock: false + Hide Right Dock: true + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd0000000400000000000002670000035afc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000003d000000c9000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d006100670065010000003d000000e20000001600fffffffb0000000a0049006d00610067006503000000000000013800000267000000a3fb0000000a0049006d0061006700650100000125000002720000001600ffffff000000010000010f0000035afc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d0000035a000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000003efc0100000002fb0000000800540069006d0065010000000000000780000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000005130000035a00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1920 + X: 0 + Y: 27 diff --git a/ifm3d_ros_examples/examples/README_pointcloud_merge.md b/ifm3d_ros_examples/examples/README_pointcloud_merge.md new file mode 100644 index 0000000..cf5623a --- /dev/null +++ b/ifm3d_ros_examples/examples/README_pointcloud_merge.md @@ -0,0 +1,6 @@ +# merging point clouds with `merge_pc.launch` + +Three parts: +1. one node per imager publishing data under it's own namespace +2. set all 3D imagers to run mode using a rosservice call to `SoftOn` +3. link ifm3d optical frame to map frame via a dummy transform publisher: `tf2_ros` with pose parameters = 0 \ No newline at end of file diff --git a/ifm3d_ros_examples/examples/dump.json b/ifm3d_ros_examples/examples/dump.json new file mode 100644 index 0000000..6ab7a91 --- /dev/null +++ b/ifm3d_ros_examples/examples/dump.json @@ -0,0 +1,338 @@ +{ + "device": { + "clock": { + "currentTime": 1581092244602229792 + }, + "diagnostic": { + "temperatures": [], + "upTime": 1599000000000 + }, + "info": { + "device": "0301", + "deviceTreeBinaryBlob": "tegra186-quill-p3310-1000-c03-00-base.dtb", + "features": {}, + "name": "", + "partNumber": "M03903", + "productionState": "AA", + "serialNumber": "000201233338", + "vendor": "0001" + }, + "network": { + "authorized_keys": "", + "ipAddressConfig": 0, + "macEth0": "00:04:4B:E4:DA:9E", + "macEth1": "00:02:01:23:33:38", + "networkSpeed": 1000, + "staticIPv4Address": "192.168.0.69", + "staticIPv4Gateway": "192.168.0.201", + "staticIPv4SubNetMask": "255.255.255.0", + "useDHCP": false + }, + "state": { + "errorMessage": "", + "errorNumber": "" + }, + "swVersion": { + "kernel": "4.9.140-l4t-r32.4+g231628d3fa15", + "l4t": "r32.4.3", + "os": "0.13.3-188", + "schema": "feature/O3R-4949", + "swu": "0.15.3" + } + }, + "ports": { + "port0": { + "acquisition": { + "exposureLong": 5000, + "exposureShort": 400, + "framerate": 10.0, + "offset": 0.0, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "data": { + "algoDebugConfig": {}, + "availablePCICOutput": [ + "AMPLITUDE_COMPRESSED", + "CONFIDENCE", + "RADIAL_DISTANCE_COMPRESSED", + "RADIAL_DISTANCE_NOISE", + "REFLECTIVITY", + "TOF_INFO" + ], + "pcicTCPPort": 50010 + }, + "info": { + "device": "3101", + "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", + "features": { + "fov": { + "horizontal": 78, + "vertical": 105 + }, + "resolution": { + "height": 172, + "width": 224 + }, + "type": "3D" + }, + "name": "", + "partNumber": "M03957", + "productionState": "AA", + "sensor": "IRS2381C", + "sensorID": "IRS2381C_105x78_4x2W_110x90_Csample", + "serialNumber": "000000000186", + "vendor": "0001" + }, + "mode": "experimental_high_4m", + "processing": { + "diParam": { + "anfFilterSizeDiv2": 2, + "enableDynamicSymmetry": true, + "enableStraylight": true, + "enableTemporalFilter": true, + "excessiveCorrectionThreshAmp": 0.3, + "excessiveCorrectionThreshDist": 0.08, + "maxDistNoise": 0.02, + "maxSymmetry": 0.4, + "medianSizeDiv2": 0, + "minAmplitude": 20.0, + "minReflectivity": 0.0, + "mixedPixelFilterMode": 1, + "mixedPixelThresholdRad": 0.15 + }, + "extrinsicHeadToUser": { + "rotX": 0.0, + "rotY": 0.0, + "rotZ": 0.0, + "transX": 0.0, + "transY": 0.0, + "transZ": 0.0 + }, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "state": "RUN" + }, + "port1": { + "acquisition": { + "exposureLong": 5000, + "exposureShort": 400, + "framerate": 10.0, + "offset": 0.0, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "data": { + "algoDebugConfig": {}, + "availablePCICOutput": [ + "AMPLITUDE_COMPRESSED", + "CONFIDENCE", + "RADIAL_DISTANCE_COMPRESSED", + "RADIAL_DISTANCE_NOISE", + "REFLECTIVITY", + "TOF_INFO" + ], + "pcicTCPPort": 50011 + }, + "info": { + "device": "3101", + "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", + "features": { + "fov": { + "horizontal": 78, + "vertical": 105 + }, + "resolution": { + "height": 172, + "width": 224 + }, + "type": "3D" + }, + "name": "", + "partNumber": "M03957", + "productionState": "AA", + "sensor": "IRS2381C", + "sensorID": "IRS2381C_105x78_4x2W_110x90_Csample", + "serialNumber": "000000000192", + "vendor": "0001" + }, + "mode": "experimental_high_4m", + "processing": { + "diParam": { + "anfFilterSizeDiv2": 2, + "enableDynamicSymmetry": true, + "enableStraylight": true, + "enableTemporalFilter": true, + "excessiveCorrectionThreshAmp": 0.3, + "excessiveCorrectionThreshDist": 0.08, + "maxDistNoise": 0.02, + "maxSymmetry": 0.4, + "medianSizeDiv2": 0, + "minAmplitude": 20.0, + "minReflectivity": 0.0, + "mixedPixelFilterMode": 1, + "mixedPixelThresholdRad": 0.15 + }, + "extrinsicHeadToUser": { + "rotX": 0.0, + "rotY": 0.0, + "rotZ": 0.0, + "transX": 0.0, + "transY": 0.0, + "transZ": 0.0 + }, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "state": "RUN" + }, + "port2": { + "acquisition": { + "exposureLong": 5000, + "exposureShort": 400, + "framerate": 10.0, + "offset": 0.0, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "data": { + "algoDebugConfig": {}, + "availablePCICOutput": [ + "AMPLITUDE_COMPRESSED", + "CONFIDENCE", + "RADIAL_DISTANCE_COMPRESSED", + "RADIAL_DISTANCE_NOISE", + "REFLECTIVITY", + "TOF_INFO" + ], + "pcicTCPPort": 50012 + }, + "info": { + "device": "2301", + "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", + "features": { + "fov": { + "horizontal": 80, + "vertical": 127 + }, + "resolution": { + "height": 800, + "width": 1280 + }, + "type": "2D" + }, + "name": "", + "partNumber": "M03934", + "productionState": "AA", + "sensor": "OV9782", + "sensorID": "OV9782_127x80_noIllu_Csample", + "serialNumber": "000000000094", + "vendor": "0001" + }, + "mode": "experimental_high_4m", + "processing": { + "diParam": { + "anfFilterSizeDiv2": 2, + "enableDynamicSymmetry": true, + "enableStraylight": true, + "enableTemporalFilter": true, + "excessiveCorrectionThreshAmp": 0.3, + "excessiveCorrectionThreshDist": 0.08, + "maxDistNoise": 0.02, + "maxSymmetry": 0.4, + "medianSizeDiv2": 0, + "minAmplitude": 20.0, + "minReflectivity": 0.0, + "mixedPixelFilterMode": 1, + "mixedPixelThresholdRad": 0.15 + }, + "extrinsicHeadToUser": { + "rotX": 0.0, + "rotY": 0.0, + "rotZ": 0.0, + "transX": 0.0, + "transY": 0.0, + "transZ": 0.0 + }, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "state": "CONF" + }, + "port5": { + "acquisition": { + "framerate": 10.0, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "data": { + "algoDebugConfig": {}, + "availablePCICOutput": [ + "RGB_INFO" + ], + "pcicTCPPort": 50015 + }, + "info": { + "device": "2301", + "deviceTreeBinaryBlobOverlay": "001-ov9782.dtbo", + "features": { + "fov": { + "horizontal": 80, + "vertical": 127 + }, + "resolution": { + "height": 800, + "width": 1280 + }, + "type": "2D" + }, + "name": "", + "partNumber": "M03934", + "productionState": "AA", + "sensor": "OV9782", + "sensorID": "OV9782_127x80_noIllu_Csample", + "serialNumber": "000000000094", + "vendor": "0001" + }, + "mode": "experimental_autoexposure2D", + "processing": { + "extrinsicHeadToUser": { + "rotX": 0.0, + "rotY": 0.0, + "rotZ": 0.0, + "transX": 0.0, + "transY": 0.0, + "transZ": 0.0 + }, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "state": "CONF" + } + } + } \ No newline at end of file diff --git a/ifm3d_ros_examples/launch/camera.launch b/ifm3d_ros_examples/launch/camera.launch new file mode 100644 index 0000000..78ae71e --- /dev/null +++ b/ifm3d_ros_examples/launch/camera.launch @@ -0,0 +1,31 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ifm3d_ros_examples/launch/dump_merge_pc.json b/ifm3d_ros_examples/launch/dump_merge_pc.json new file mode 100644 index 0000000..2e8fa74 --- /dev/null +++ b/ifm3d_ros_examples/launch/dump_merge_pc.json @@ -0,0 +1,338 @@ +{ + "device": { + "clock": { + "currentTime": 1581090835576664320 + }, + "diagnostic": { + "temperatures": [], + "upTime": 190000000000 + }, + "info": { + "device": "0301", + "deviceTreeBinaryBlob": "tegra186-quill-p3310-1000-c03-00-base.dtb", + "features": {}, + "name": "", + "partNumber": "M03903", + "productionState": "AA", + "serialNumber": "000201233338", + "vendor": "0001" + }, + "network": { + "authorized_keys": "", + "ipAddressConfig": 0, + "macEth0": "00:04:4B:E4:DA:9E", + "macEth1": "00:02:01:23:33:38", + "networkSpeed": 1000, + "staticIPv4Address": "192.168.0.69", + "staticIPv4Gateway": "192.168.0.201", + "staticIPv4SubNetMask": "255.255.255.0", + "useDHCP": false + }, + "state": { + "errorMessage": "", + "errorNumber": "" + }, + "swVersion": { + "kernel": "4.9.140-l4t-r32.4+g231628d3fa15", + "l4t": "r32.4.3", + "os": "0.13.3-188", + "schema": "feature/O3R-4949", + "swu": "0.15.3" + } + }, + "ports": { + "port0": { + "acquisition": { + "exposureLong": 5000, + "exposureShort": 400, + "framerate": 10.0, + "offset": 0.0, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "data": { + "algoDebugConfig": {}, + "availablePCICOutput": [ + "AMPLITUDE_COMPRESSED", + "CONFIDENCE", + "RADIAL_DISTANCE_COMPRESSED", + "RADIAL_DISTANCE_NOISE", + "REFLECTIVITY", + "TOF_INFO" + ], + "pcicTCPPort": 50010 + }, + "info": { + "device": "3101", + "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", + "features": { + "fov": { + "horizontal": 78, + "vertical": 105 + }, + "resolution": { + "height": 172, + "width": 224 + }, + "type": "3D" + }, + "name": "", + "partNumber": "M03957", + "productionState": "AA", + "sensor": "IRS2381C", + "sensorID": "IRS2381C_105x78_4x2W_110x90_Csample", + "serialNumber": "000000000186", + "vendor": "0001" + }, + "mode": "experimental_high_4m", + "processing": { + "diParam": { + "anfFilterSizeDiv2": 2, + "enableDynamicSymmetry": true, + "enableStraylight": true, + "enableTemporalFilter": true, + "excessiveCorrectionThreshAmp": 0.3, + "excessiveCorrectionThreshDist": 0.08, + "maxDistNoise": 0.02, + "maxSymmetry": 0.4, + "medianSizeDiv2": 0, + "minAmplitude": 20.0, + "minReflectivity": 0.0, + "mixedPixelFilterMode": 1, + "mixedPixelThresholdRad": 0.15 + }, + "extrinsicHeadToUser": { + "rotX": 0.0, + "rotY": -1.5708, + "rotZ": 0.0, + "transX": 0.015, + "transY": -0.18, + "transZ": -0.055 + }, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "state": "RUN" + }, + "port1": { + "acquisition": { + "exposureLong": 5000, + "exposureShort": 400, + "framerate": 10.0, + "offset": 0.0, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "data": { + "algoDebugConfig": {}, + "availablePCICOutput": [ + "AMPLITUDE_COMPRESSED", + "CONFIDENCE", + "RADIAL_DISTANCE_COMPRESSED", + "RADIAL_DISTANCE_NOISE", + "REFLECTIVITY", + "TOF_INFO" + ], + "pcicTCPPort": 50011 + }, + "info": { + "device": "3101", + "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", + "features": { + "fov": { + "horizontal": 78, + "vertical": 105 + }, + "resolution": { + "height": 172, + "width": 224 + }, + "type": "3D" + }, + "name": "", + "partNumber": "M03957", + "productionState": "AA", + "sensor": "IRS2381C", + "sensorID": "IRS2381C_105x78_4x2W_110x90_Csample", + "serialNumber": "000000000192", + "vendor": "0001" + }, + "mode": "experimental_high_4m", + "processing": { + "diParam": { + "anfFilterSizeDiv2": 2, + "enableDynamicSymmetry": true, + "enableStraylight": true, + "enableTemporalFilter": true, + "excessiveCorrectionThreshAmp": 0.3, + "excessiveCorrectionThreshDist": 0.08, + "maxDistNoise": 0.02, + "maxSymmetry": 0.4, + "medianSizeDiv2": 0, + "minAmplitude": 20.0, + "minReflectivity": 0.0, + "mixedPixelFilterMode": 1, + "mixedPixelThresholdRad": 0.15 + }, + "extrinsicHeadToUser": { + "rotX": 0.0, + "rotY": 0.0, + "rotZ": 0.0, + "transX": -0.13, + "transY": -0.1, + "transZ": 0.2 + }, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "state": "RUN" + }, + "port2": { + "acquisition": { + "exposureLong": 5000, + "exposureShort": 400, + "framerate": 10.0, + "offset": 0.0, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "data": { + "algoDebugConfig": {}, + "availablePCICOutput": [ + "AMPLITUDE_COMPRESSED", + "CONFIDENCE", + "RADIAL_DISTANCE_COMPRESSED", + "RADIAL_DISTANCE_NOISE", + "REFLECTIVITY", + "TOF_INFO" + ], + "pcicTCPPort": 50012 + }, + "info": { + "device": "2301", + "deviceTreeBinaryBlobOverlay": "001-irs2381c.dtbo", + "features": { + "fov": { + "horizontal": 80, + "vertical": 127 + }, + "resolution": { + "height": 800, + "width": 1280 + }, + "type": "2D" + }, + "name": "", + "partNumber": "M03934", + "productionState": "AA", + "sensor": "OV9782", + "sensorID": "OV9782_127x80_noIllu_Csample", + "serialNumber": "000000000094", + "vendor": "0001" + }, + "mode": "experimental_high_4m", + "processing": { + "diParam": { + "anfFilterSizeDiv2": 2, + "enableDynamicSymmetry": true, + "enableStraylight": true, + "enableTemporalFilter": true, + "excessiveCorrectionThreshAmp": 0.3, + "excessiveCorrectionThreshDist": 0.08, + "maxDistNoise": 0.02, + "maxSymmetry": 0.4, + "medianSizeDiv2": 0, + "minAmplitude": 20.0, + "minReflectivity": 0.0, + "mixedPixelFilterMode": 1, + "mixedPixelThresholdRad": 0.15 + }, + "extrinsicHeadToUser": { + "rotX": 0.0, + "rotY": 3.1416, + "rotZ": 0.0, + "transX": -0.015, + "transY": -0.3, + "transZ": 0.05 + }, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "state": "RUN" + }, + "port5": { + "acquisition": { + "framerate": 10.0, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "data": { + "algoDebugConfig": {}, + "availablePCICOutput": [ + "RGB_INFO" + ], + "pcicTCPPort": 50015 + }, + "info": { + "device": "2301", + "deviceTreeBinaryBlobOverlay": "001-ov9782.dtbo", + "features": { + "fov": { + "horizontal": 80, + "vertical": 127 + }, + "resolution": { + "height": 800, + "width": 1280 + }, + "type": "2D" + }, + "name": "", + "partNumber": "M03934", + "productionState": "AA", + "sensor": "OV9782", + "sensorID": "OV9782_127x80_noIllu_Csample", + "serialNumber": "000000000094", + "vendor": "0001" + }, + "mode": "experimental_autoexposure2D", + "processing": { + "extrinsicHeadToUser": { + "rotX": 0.0, + "rotY": 0.0, + "rotZ": 0.0, + "transX": 0.0, + "transY": 0.0, + "transZ": 0.0 + }, + "version": { + "major": 0, + "minor": 0, + "patch": 0 + } + }, + "state": "CONF" + } + } +} diff --git a/ifm3d_ros_examples/launch/four_cameras.launch b/ifm3d_ros_examples/launch/four_cameras.launch new file mode 100644 index 0000000..6ee2d6f --- /dev/null +++ b/ifm3d_ros_examples/launch/four_cameras.launch @@ -0,0 +1,110 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ifm3d_ros_examples/launch/head.launch b/ifm3d_ros_examples/launch/head.launch new file mode 100644 index 0000000..fc45542 --- /dev/null +++ b/ifm3d_ros_examples/launch/head.launch @@ -0,0 +1,60 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ifm3d_ros_examples/launch/merge_pc.launch b/ifm3d_ros_examples/launch/merge_pc.launch new file mode 100644 index 0000000..13bf287 --- /dev/null +++ b/ifm3d_ros_examples/launch/merge_pc.launch @@ -0,0 +1,147 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ifm3d_ros_examples/launch/nodelet.launch b/ifm3d_ros_examples/launch/nodelet.launch new file mode 100644 index 0000000..8259ed6 --- /dev/null +++ b/ifm3d_ros_examples/launch/nodelet.launch @@ -0,0 +1,117 @@ + + + + + + + + + + + + + + + + + + + + + + + + # + # The IP address of the camera to connect to + # + ip: "$(arg ip)" + + # + # The on-camera TCP port that the XMLRPC server is listening to + # + xmlrpc_port: $(arg xmlrpc_port) + + # + # The on-camera TCP port that the PCIC server is listening to + # + pcic_port: $(arg pcic_port) + + # + # The password needed to establish an edit session with the camera + # + password: "$(arg password)" + + # + # The PCIC schema mask to apply to the framegrabber + # + schema_mask: $(arg schema_mask) + + # + # The number of milliseconds to wait for a frame before declaring a + # framegrabber timeout + # + timeout_millis: $(arg timeout_millis) + + # + # The number of seconds to endure timeouts before restarting the framegrabber + # + timeout_tolerance_secs: $(arg timeout_tolerance_secs) + + # + # Flag indicating whether or not the nodelet should assume the camera is + # being software triggered + # + assume_sw_triggered: $(arg assume_sw_triggered) + + # + # If using the `SoftOff`/`SoftOn` functionality, these parameters + # control the `timeout_millis` and `timeout_tolerance_secs` + # + soft_on_timeout_millis: $(arg timeout_millis) + soft_on_timeout_tolerance_secs: $(arg timeout_tolerance_secs) + soft_off_timeout_millis: 500 + soft_off_timeout_tolerance_secs: 600.0 + + # + # Time (seconds) used to determine that timestamps from the camera + # cannot be trusted. When this threshold is exceeded, when compared to + # system time, we use the reception time of the frame and not the capture + # time of the frame. + # + frame_latency_thresh: 60.0 + + # + # Get rid of the errors when running `rosbag -a' + # + distance/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] + amplitude/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] + raw_amplitude/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] + confidence/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] + good_bad_pixels/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] + xyz_image/disable_pub_plugins: ['image_transport/compressedDepth', 'image_transport/theora'] + + + + + + + + + + + + + diff --git a/ifm3d_ros_examples/launch/rviz.launch b/ifm3d_ros_examples/launch/rviz.launch new file mode 100644 index 0000000..fcf2c23 --- /dev/null +++ b/ifm3d_ros_examples/launch/rviz.launch @@ -0,0 +1,12 @@ + + + + + + + + + diff --git a/ifm3d_ros_examples/launch/six_cameras.launch b/ifm3d_ros_examples/launch/six_cameras.launch new file mode 100644 index 0000000..b8a2807 --- /dev/null +++ b/ifm3d_ros_examples/launch/six_cameras.launch @@ -0,0 +1,156 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ifm3d_ros_examples/package.xml b/ifm3d_ros_examples/package.xml new file mode 100644 index 0000000..f8db7eb --- /dev/null +++ b/ifm3d_ros_examples/package.xml @@ -0,0 +1,21 @@ + + + + ifm3d_ros_examples + 0.1.0 + ifm3d_ros examples subpackage + ifm CSR group + Apache 2 + CSR ifm sytron + + https://github.com/ifm/ifm3d_ros/ + + catkin + tf + ifm3d_ros_driver + ifm3d_ros_msgs + + + + + diff --git a/ifm3d_ros_msgs/CMakeLists.txt b/ifm3d_ros_msgs/CMakeLists.txt new file mode 100644 index 0000000..df3e3f0 --- /dev/null +++ b/ifm3d_ros_msgs/CMakeLists.txt @@ -0,0 +1,55 @@ +cmake_minimum_required(VERSION 3.0.2) +project(ifm3d_ros_msgs) + +find_package(catkin REQUIRED COMPONENTS + message_generation + std_msgs + tf2_ros +) + +####################################### +## Declare ROS messages and services ## +####################################### +catkin_python_setup() + +add_message_files( + DIRECTORY msg + FILES + Extrinsics.msg + ) + +add_service_files( + DIRECTORY srv + FILES + Dump.srv + Config.srv + Trigger.srv + SoftOff.srv + SoftOn.srv + SyncClocks.srv + ) + +generate_messages( + DEPENDENCIES + std_msgs + ) + + +################################### +## catkin specific configuration ## +################################### +catkin_package( + CATKIN_DEPENDS message_runtime std_msgs +) + + +############# +## Install ## +############# + +catkin_install_python( + PROGRAMS + bin/dump + bin/config + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ) diff --git a/ifm3d_ros_msgs/README.md b/ifm3d_ros_msgs/README.md new file mode 100644 index 0000000..6f5c311 --- /dev/null +++ b/ifm3d_ros_msgs/README.md @@ -0,0 +1,24 @@ +# The `ifm3d_ros_msgs` package + +This package provides the messages and services interfaces for the `ifm3d_ros_driver` package. It can be installed independently of the driver package `ifm3d_ros_driver` and examples package `ìfm3d_ros_examples`. + +## Standalone Installation of the messages packages +If you plan on installing only one subpackage please see the instructions below. + +``` +catkin_make --only-pkg-with-deps +``` +Please replace the tag `` with the name of the package you want to compile: ++ `ifm3d_ros_driver` ++ `ifm3d_ros_msgs` ++ `ifm3d_ros_examples` + +Some of our subpackages have dependencies to other packages and therefore will trigger a compiling of more subpackages, namely the packages `ifm3d_ros_examples` and `ifm3d_ros_driver`. These subpackges can not be used standalone. + +Don't forget to switch back to building all packages afterwards: +``` +catkin_make -DCATKIN_WHITELIST_PACKAGES="" +``` + +# LICENSE +Please see the file called [LICENSE](LICENSE). \ No newline at end of file diff --git a/ifm3d_ros_msgs/bin/config b/ifm3d_ros_msgs/bin/config new file mode 100755 index 0000000..470fb17 --- /dev/null +++ b/ifm3d_ros_msgs/bin/config @@ -0,0 +1,12 @@ +#!/usr/bin/env python +# -*- python -*- + +# SPDX-License-Identifier: Apache-2.0 +# Copyright (C) 2021 ifm electronic, gmbh + + +import sys +from ifm3d_ros_utils import ConfigClient + +if __name__ == '__main__': + sys.exit(ConfigClient().run()) diff --git a/ifm3d_ros_msgs/bin/dump b/ifm3d_ros_msgs/bin/dump new file mode 100755 index 0000000..396285c --- /dev/null +++ b/ifm3d_ros_msgs/bin/dump @@ -0,0 +1,12 @@ +#!/usr/bin/env python +# -*- python -*- + +# SPDX-License-Identifier: Apache-2.0 +# Copyright (C) 2021 ifm electronic, gmbh + + +import sys +from ifm3d_ros_utils import DumpClient + +if __name__ == '__main__': + sys.exit(DumpClient().run()) diff --git a/ifm3d_ros_msgs/msg/Extrinsics.msg b/ifm3d_ros_msgs/msg/Extrinsics.msg new file mode 100644 index 0000000..7fe7168 --- /dev/null +++ b/ifm3d_ros_msgs/msg/Extrinsics.msg @@ -0,0 +1,11 @@ +# +# Extrinsic parameters are SI units: please be aware of scaling between any extrinsic messages returned by older versions of the native C++ API - ifm3d +# Translation uints are NOW m, rotation units are radian +# +std_msgs/Header header +float32 tx +float32 ty +float32 tz +float32 rot_x +float32 rot_y +float32 rot_z diff --git a/ifm3d_ros_msgs/package.xml b/ifm3d_ros_msgs/package.xml new file mode 100644 index 0000000..39f5fce --- /dev/null +++ b/ifm3d_ros_msgs/package.xml @@ -0,0 +1,26 @@ + + + + ifm3d_ros_msgs + 0.1.0 + ifm3d_ros messages subpackage + ifm CSR group + Apache 2 + CSR ifm sytron + https://github.com/ifm/ifm3d-ros/ + + + catkin + message_generation + std_msgs + std_msgs + message_generation + std_msgs + message_runtime + tf2_ros + + + + + + diff --git a/ifm3d_ros_msgs/setup.py b/ifm3d_ros_msgs/setup.py new file mode 100644 index 0000000..412b54b --- /dev/null +++ b/ifm3d_ros_msgs/setup.py @@ -0,0 +1,10 @@ +from distutils.core import setup +from catkin_pkg.python_setup import generate_distutils_setup + +# reads package.xml +setup_args = generate_distutils_setup( + packages=['ifm3d_ros_utils'], + package_dir={'': 'utils'}, + ) + +setup(**setup_args) diff --git a/ifm3d_ros_msgs/srv/Config.srv b/ifm3d_ros_msgs/srv/Config.srv new file mode 100644 index 0000000..81c8381 --- /dev/null +++ b/ifm3d_ros_msgs/srv/Config.srv @@ -0,0 +1,4 @@ +string json +--- +int32 status +string msg diff --git a/ifm3d_ros_msgs/srv/Dump.srv b/ifm3d_ros_msgs/srv/Dump.srv new file mode 100644 index 0000000..1399d5b --- /dev/null +++ b/ifm3d_ros_msgs/srv/Dump.srv @@ -0,0 +1,3 @@ +--- +int32 status +string config diff --git a/ifm3d_ros_msgs/srv/SoftOff.srv b/ifm3d_ros_msgs/srv/SoftOff.srv new file mode 100644 index 0000000..f8f830e --- /dev/null +++ b/ifm3d_ros_msgs/srv/SoftOff.srv @@ -0,0 +1,3 @@ +--- +int32 status +string msg \ No newline at end of file diff --git a/ifm3d_ros_msgs/srv/SoftOn.srv b/ifm3d_ros_msgs/srv/SoftOn.srv new file mode 100644 index 0000000..f60f193 --- /dev/null +++ b/ifm3d_ros_msgs/srv/SoftOn.srv @@ -0,0 +1,3 @@ +--- +int32 status +string msg diff --git a/ifm3d_ros_msgs/srv/SyncClocks.srv b/ifm3d_ros_msgs/srv/SyncClocks.srv new file mode 100644 index 0000000..f60f193 --- /dev/null +++ b/ifm3d_ros_msgs/srv/SyncClocks.srv @@ -0,0 +1,3 @@ +--- +int32 status +string msg diff --git a/ifm3d_ros_msgs/srv/Trigger.srv b/ifm3d_ros_msgs/srv/Trigger.srv new file mode 100644 index 0000000..f8f830e --- /dev/null +++ b/ifm3d_ros_msgs/srv/Trigger.srv @@ -0,0 +1,3 @@ +--- +int32 status +string msg \ No newline at end of file diff --git a/ifm3d_ros_msgs/utils/ifm3d_ros_utils/_ConfigClient.py b/ifm3d_ros_msgs/utils/ifm3d_ros_utils/_ConfigClient.py new file mode 100644 index 0000000..1f5fbe1 --- /dev/null +++ b/ifm3d_ros_msgs/utils/ifm3d_ros_utils/_ConfigClient.py @@ -0,0 +1,30 @@ +# SPDX-License-Identifier: Apache-2.0 +# Copyright (C) 2021 ifm electronic, gmbh + +""" +Mimics (mostly) the `ifm3d config` command but communicates through the ROS +graph +""" + +import json +import rospy +import sys +from ifm3d_ros_msgs.srv import Config + +SRV_TIMEOUT = 2.0 # seconds +SRV_NAME = "/ifm3d_ros_examples/camera/Config" + +class ConfigClient(object): + + def __init__(self): + rospy.init_node('ifm3d_config_client') + + def run(self): + j = json.load(sys.stdin) + rospy.wait_for_service(SRV_NAME, timeout=SRV_TIMEOUT) + proxy = rospy.ServiceProxy(SRV_NAME, Config) + resp = proxy(json.dumps(j)) + if resp.status != 0: + print("Error: %s - %s" % (str(resp.status), resp.msg)) + + return resp.status diff --git a/ifm3d_ros_msgs/utils/ifm3d_ros_utils/_DumpClient.py b/ifm3d_ros_msgs/utils/ifm3d_ros_utils/_DumpClient.py new file mode 100644 index 0000000..3b45a8f --- /dev/null +++ b/ifm3d_ros_msgs/utils/ifm3d_ros_utils/_DumpClient.py @@ -0,0 +1,33 @@ +# SPDX-License-Identifier: Apache-2.0 +# Copyright (C) 2021 ifm electronic, gmbh + +""" +Mimics the `ifm3d dump` command but communicates through the ROS graph +""" + +import json +import rospy +import sys +from ifm3d_ros_msgs.srv import Dump + +SRV_TIMEOUT = 2.0 # seconds +SRV_NAME = "/ifm3d_ros_examples/camera/Dump" + +class DumpClient(object): + + def __init__(self): + rospy.init_node('ifm3d_dump_client') + + def run(self): + rospy.wait_for_service(SRV_NAME, timeout=SRV_TIMEOUT) + proxy = rospy.ServiceProxy(SRV_NAME, Dump) + resp = proxy() + if resp.status == 0: + print(json.dumps(json.loads(resp.config), + sort_keys=True, indent=4, separators=(',', ': '))) + else: + sys.stderr.write("Dump failed with error: %s - %s\n" % + (str(resp.status), + "Check the `ifm3d' logs for more detail")) + + return resp.status diff --git a/ifm3d_ros_msgs/utils/ifm3d_ros_utils/__init__.py b/ifm3d_ros_msgs/utils/ifm3d_ros_utils/__init__.py new file mode 100644 index 0000000..c928a3e --- /dev/null +++ b/ifm3d_ros_msgs/utils/ifm3d_ros_utils/__init__.py @@ -0,0 +1,5 @@ +# SPDX-License-Identifier: Apache-2.0 +# Copyright (C) 2021 ifm electronic, gmbh + +from ._DumpClient import DumpClient +from ._ConfigClient import ConfigClient

    Q2no|BODBhN%1EBaBC;O!G2D(MH7Z5C5`1O8>Myj z^4f{3wFrTs9#&i}t`Hsk9Uu2N?&bf8XCd>l6~?le=j~0=tnXS@5eNUt(G9!Lt&Oa7 zAO?e=)ap;TX0PIk!f-Ja$S=BK`{~|;N~6((&yV9cP^{7&zS9~Ok?BXXo#2NU{ zBa2PU0I^+D4l zm!x~Ltc=d~J&$Y_LR-Y53%IzKp&o!xZ+@sl#$<$kyM+r{6ShK$>Ev+C`a0 zMm-}We0hYDcmtBwBBkgo z=7A#o{_yr!{BmGifrU3wl%9IEx;QC`Zxcso#V!A=jFsfdE`yPa_m53WK_IvXF^k$` z<}OBCf> z8LzIm(S6Xv%a6_ZT$kLGrnvKTe9T1YM1%x~3zk-@U3NF`c9DE~#scRf3mkZR6!7_G zDDFJmSTl}x0v9=xmE;p}!3ZG7Np%<`fyw4E7nn8MGc~IF{OJwF44t0$G|VN`rVohjn}Cl87Wd z!0uVQ)pX$q%z*D(D%@ahjzyd^IpN(-7qbP!c6aycmd@%E>u!D?oG}4G3^QN1o*H`1 zlzPn3dAN4;xF{MvaVeB*lE_3tr6{Fa+gINoPEd{Gq6ai-JlKH}wGBOHaar@m1N}Hg z$GcxOQ^`>W2r&$elM^Gz7^Zer+PwJ6$WBb|wT3l|H}RBOJCozhoEvahrj_aB@JmEAhT%;L8Kh^~uw{xMGSlG)A86Cxqb3CipVQN` z=n;8F`O!!5?3-x9gXDc>Xve-+Lg=HsSNC~7W(c}te#X!Jjo$p?Mk#qWD|ngpzW%d$ zTj6cPHmLSM(qE#eHwOjB|78OmJ$`k+PjZA`tM#?hY9po24(#56trt;dCYnwLwV1A} zm<rP!Ha)Gt4Q=dt-1;%dbv?i?WTCL4={SjkD{E|ZKM6f z1V8`*_4b8ypivLd6>kFCKeWi=i8aqTu6(GB+-fd_*pBn{9-DIkQ|m5W8OC03(7M9) zz`Q=JR?lOo0tjgptgBWw1S07UEX!J$`3(kzOvb+up9%{NJjz^20%F2O5XAtN{r+YGfUL5!vw`a_+^nMHcOg;SA8zg*U6JSlHfB#h=({v&ebvc*ouVR2FNzE(F^+5? zB?=stNIyDPN5Hj}2bNQ*%VLIde3(-*?AEQ$ou2*yAXlq^ppWaj7G!I=+Ao1 zXOl_8Spj19cpm~h_RbU18CK(Hy>5vxct|$V-06u411hVrMnv|Ubu$(=8bBxePIy-# z`}@l;y3)<5FSRpi7xe_D!Cp+J}xJ2b)=L?t?84e=#%fTV;Q!y8qm{? z{p`1ZN+*J?eq;S9+m&u|1Tp?oV70bm9{Syq_bk9}?St zx;~Oumf0K4L;%+13}RHT{_Wg8wrl@PjU2z5NRg2pFLjV4z^S5CW+^%5SMlAB*`ANF z$Dax$mWq}4R|xhL2H=wZlc91+Q`e`W&cR`)JZh(|9VK-ic-DR2CGM*J3mWGe;Wt%_ zoqAsRmUT>hU{6zG%QrR$KhN~rN<+WArHv{OMCwgrq85=?vv*&1;d{zTtvOeW3(2mK z%fgoRid%UhutL;g#V_ig1Uw5|$nsArsAA9IYkNvu{X!jn)yu)ft_K-u+nMhj$hVcI z&3-(*Etu?6=XTHp#ZAqr10I$Wi8-wJeouT>U1{5+fn@5o@yuA zz&`4;DSYhx3x1Ia(0ObEtNzY~a4wbu#kiJbR{oHkzwQ7kJ2Z4GV^QW|wsyh8F63ef zJRP927Pw}?J<6AYT>V2wSHhreGIK7_2Tk3bsfO{#y)ow07NBa{C)3*WChp=9t)_6f z-v4NO=qs~XztksYDgdv=${GfA@&Yl;9pjBV8PKm*{#D{`lJ{n!fL+_sM|I|O!IRa= zO$_r{(ePLfto7Si_KH>_6gWno7)dqs>a`KhUu3_Z&*m1{61K_o|l_%*Dqn*RMFeXpH4{pjoo zxok5TWLMen64}CX2i`fJIifE6R*S-XnJLtav`ha7A>^*`c+ZW&n-)@&{{E1y(|inw zB313U0Nl)n_@ub=BpS=rUVA-^z+6D()7o?G^;alaSojSJR=yYD)%chXP@N|D$|Kp{ zJJ8+8MOBr;JUKaR`yw8ESyA_d};G~PljYX@GuJy0VmE1 zDOYOaerbVK-!e|hU507Hy%#mKuKMfOv1s|ttZnn==$9RQ>q;0Wnw(Qxf*SMX)kXA1 zhhtV8{8#rBg-hqb13$gD++k~c$zppMsreWZK8NAC6OrU5;`-HEhN*5&ONOE5k`!{) z!6~b)*|Rl)(B>q?9Z@d4nd+rB335a~;$0Z4q!T{QjJT7ZK|jQ#LY}FKT`s&kS4bkQ zAO%rMg3w5-xpF3>f`J8?UVJmE3mAJ*{a;CA86NA}i zgUO&Z7juLRBwbRR+CV@+dKdH~uR6`dBh;c5clxUM2w@gZ<2^;j(bVncF zJf~j!IG3)v1s&D`7mMECeL;P;pe^#lmtDgTPm8~I>Z{GBsPN&6%7u_-{_#UZ%>R;S z_$~egn*qV;D99*Saq1T_xB_Z2$&ZDWfHvvzjqlBZe2s^e9q4a3c6mS@*_~w1DF4_N zx>lP^Vz8;%8=2^(I=HD?&hRep-7EDW180mrsH2GZ6t1Wi;7M*-`I3LXI0rNG*t1bA zA}%zKhJnDPG$jH^y1d&QXy|0Cx1M}G$B-X*i|Wxw$(oGc3aJP@Z9O!o2NVrk5C!@p`e)tn^{7K;1!JPWKo~ zi-S#s!Ys4WTUf!wZxHf2uyInoIk6$5VSbd~0}P0Lo3_4>A3kDIuE~Di}cZ zS;+{Lq%z6&;pW*Lo7sVn!yGda`ch$QZ$6S&y7RRB;BX3a)dHxkf)(Y4^r`i8HZhFY z%XiVlL2~d@AH#Zzd8}%$ai~ARt8PktvJW=`Exz|Fbvdw)Xm#puN z>#ceFJ%d=-B)m04^d2gmhQE|yQu>*ztI(iFgjwZm=LkD1BlS(wbWr&k%MW5(+|T9p z`6;nq!K(WxMuBuUkuN#p>r#I4If5{xW35!^tSpU*YoukF>)@xz0D01K$erJ)rYCO0dPeLG4$>o81wgd3j)A&gfs_ra1bIdBTW-RtUN(eZ2^K9Y zta2MeV4LY~G8Y2R?R4~$1`w#U8xfZ`#ZeJofCv7De1o(U-F5f5Zbxludy4B|r(+`r zQM!}7beSo~sr%1YAZSJETP=Fkz@uDiDV61Ag~=hVGR%m2#3PrpS*mW;rorqUew_p2Kd2D-vn}AkcDn6aaB4^)YvMHwXjIwZdG9;MoNj+d2%lmxe@00& zYu0kKLYtRub8C=tL2!yZFz-Kl=m`ntZ?Ep4KY0e!Z_>j}_RW#8*WkNY#mQetc3Bpr zVhQnRDiB_rkF8}yfAOH=zOW9wNj&Sy8I}5a6d({>)(=q!~>ydy3 zakq`h8wuU74R(CJR`p@HZG1CTzpB(-OnMZXcvkw191?+gMtvA`H@(DaX^p3pirr~Y!rqbiPR z>R=brP2>`Jw&pPSlEAkA_PC|X5jo0o!!bJ$7lZW;6Miz`AX+Vxk5LV+UiEKjcU*$6 zy}4V%pZpCm*(YvJ-5Tx89#?a62{Bw5dE+%9_Z4%Fxw{pifL1b&1h@2htKN%f%8y?* zu8fQbZ*Y#-l&bvqZ4T5AB5%K6fNMnQ!A&+54hHDT0A`n19@?u#3=rty68bvSFK zD|u*lx*`-{nbmWYC#k7UeiQSR+OV5jYZKw}>ixuse<1qRq%CM1zPP9tg6@=E<7M2+zzuWU1_FPc>x!t2a zTXUM8xnWm1X>n)uX4FaH*gpR_u|MyqzXafO*;@N)FkrqM9x5Vi#6XE#ZexnKJ-|gQo$HB$`E!LgFo{$Z!D`rp?G0f&%|8+z+-x* zg#q{>)Z|SOAovhDHgWZ7Zi$;Q+guw#Xxh`uaoqvc( zmwtpkJQscg#Dt$Np=e!<=d&Vm*a6S!+{tyZsW6YaURUpe6j$ayMYKffJDBtievHe< zrfO9j=N*+btzOQ->GkeIzGmFQw!SM=NbYKqN3rt#ZFq>(lSL~_imX%~XzZ-EcJp&; zx+EBDVRm!w#`lL`4gX~ia(`ImC%1bYrUD-Lg3IOzS1xdMnLxjzAcCH{RtY?lA^I z4vFEFStIO_JL{9Y+^u$V;0#0GA}7zBqp{Zw>6toDH5<=w^?uaQK)vbt4a^l_mtI+` zog_L@wkG}YvDSjV{acsG-P_nqU)2V` z`Mc@$^d38n>Dwcj$mRZsg49qj=PP0=ty$Ai2CA^}hyTgN=l@>j(EpeUksTB*1) zReM)yJaR3~u7T5iEMsuL0l#8(bGCm~$qcYvpIGX)Hs_-fzZ5X(TiOH)uN|`peQFk7 zw%^O~b~#RcP=?`O%Y{p+Jd$sam2>SX`SP}D!djEYy$ywqOlUrp!3>)%`Y)AY-p6St z6IteGLh@&jjBU8)I8s68_quGEsgyI3wulFzXd6mi!9PP{%ZcrpwQXt(0>Z4txH;jG zcRG1-lPasz0;SGlAO7Q+?>B!qni>j7Ev;z$ENVZflk`vf$(S?i+3!VV`uG!Fb(Q+l zvQvfLL-@*2=asq{qt%BuIrHYX+0Mwl`H(hTBSZ7dVI+RpsNda(QCap1Stdnm&MW| z#`V{ z7|=#~7wkS_Mirm{ETdDJpWnmT2x;T`dF>dT3@hYm2CQS$31_A zGuc$kX7&|2b<17URiXDgAL1yh+XS4ul{Nu_@`s^|x^xf3y1D|H-5tTts}q`C0k5we z-Lf5B9BghJ5XhFaU2WPgUCPqxG1A^ZDx``bfHz*2#Mbx8Wf^%+_3S(|j6gaD@O`WX zyjA!*{Pg%Wd@DB(^yOJgb1AlVcxJEa^-g|ep)#vSsxuMX5?wh_=A)=U5hp}-rK|N} zp=Ajp;GD;bx~uk}KkA4%}E(6momYM@izdwr$yB#`XP zdwue7m|~c0Gw3->4W+7JXtgCVpVCrA&jUDBl0fm@i=g{($~8vjjX>tTah&18oP?v8 zWmxflRCDrrO7X*F_pb(7g_k@e$cWPIi+<|Z=Vv^g>VGJld?QZ~&()rWvAj%K@rBfA zs2vFlIY#)n=Lgzd@boAD9%VWCJ>58k+PhgIFvp0GNZhfJXk^Sl(>2zR9wAU&+sn}p?E}y@efYZeTDMhLq~qf zJ5wPU)M3J2;t}OavD^MG;hyT%T54=Waog;~;2jT>vy!TWR%5sv0{l=tx%lGRbM^7& zCf##iH48Fd8Hs6Z1IUwls=5$Y^XN>( z^$T5R9-aS0t_it-ig<7MzqTvC{y;F`2=B^XBCRU8Cf-6`zsd@9JK5X*zFS``rYj{= zj1MM;Eq%S5Q{UYE0eG!4A1iWpATT*}Ckck^W*>8e!X{kZ-ArlyC8Vg?iDj%9veAhAO7$Q$^ z-qEqlV)1ex^)h@lSg`KKC0Piz&cJ@9OT2zANOT!C$)KU^IXxrCw6;#B*usw>g6uLc zO48}}_)~ISy7{nH#wh-#$knDuT<;7BZ{~M1o{Cj=-BE zx@$6Cu-mt+EvB2qeIr1 z$LbGjq`AXIO2T(Or<2y`igxL zQz1?Z8RY`4>f-Q%z7~T=y}!_;GhupTx|e`pyv-$P3OrfRR4%{1s}n6%?}%3~0P`(j zzuwQdHJ53JAad<`@n$0Ye=S@rCHsXf;p?wo^pTs9rqvs3&K-5#O7#4` zx`vqN$_#@C;+Ko)Z5##>gPKI@M=S5tK!D#+l*mz7qbd^&z*?2Y^Y?~cL5e#9TbsO` zWj;5Pulama-ye!aJK4?|abI$R$`WseK@l34SiHgY_oIFloFyarb(EJ88T|;t$q2DLh8iqq0vsYZ9 zv{!rl&ewe7TKLE($}EW-5e34}RwVHwI$reVS2Scav`_a-}SJpnaV{v4;EHpm}TU<~}^ z`S8o$eoB2tt-!?hhZw4HXu=je{!(CLjqI5w4Y9uAP*uf^tb#wxV&#(=!h^QCxtZm9 zF;EX&(b?7}>^=YDl?O)&ghS<|)%@#aANe0tF0=hqHjyJnvTHZ41D%ggzi<|tV|_m8 zJ~VrFrT1sSggs+0g*}i3dV0@`NwzqgMx_n_T~`d3SRQAx#=(iPTS*D6FV=8oi0A8` zW^yiO0VVk`Q&Am7L*;1fIJ{hO3_iIZKcyR>UrO1s6Kh_uN{J@$WTqnf1(bak3jGlt z;<3M)7ckX(6*5_S)hm>Re%dCWKiI1{3XuT=B>AKv*&Sc z>2zu)f)27PTe;U8Ie2{GY;ATu6A_&Nvz~C##Bl)ykZ{3Vl_gg;x1H_Gu9=f!HQ(qJ zWrQS<4-~}j2$cmtbh@bZ+l4yb0 zoL_xBPPiNgR*>v$&K(X&hJk;o^9{h>04oMO+Bq7ks=*Z%72jT)6Lij2sT2FXR)YE^ z)6kgEf5i}HS9a=il|k=Aa-%DZ0Lw0buqnORkvmGgk$?`YI*I#<_GE*or!oB=5ex@H z@$7M!>$r~7w(8JC9{5o-Hjl*1wSv0*O-N2FQTZFu0S@MsIN4}8ZvmKk$bCPA(PLHctFQmWY4hG_F%QYAfO8_?OQ$g+q5#m1;V{(l!>+B?w1p=~IJ- zqb2fY%Q+2s-iU1h<@YE+EEXrlZYdfDbLmeK4riH%`ai(a{df5aOlSTpoXE;$E?Hsn zyQK-S7=|GON(zyt`g??ONVpVh!HPdoo^GfDZF6h{NFkiRfbZBo#KQ~6LcAyx4$22}ANiU5H1G9%8_SG%w|sz#QuW*e_}Hex zdBw?XpBPYhY+3nPVK6|q56ROuBAVO={fNrnGoUtN&HD!pff<~=T>>MV5GBDhU+N~> z+Wl2E*LLI2dm69$vWCndP!WJta3Q-&&<`bSzcLX7z!oN!Gh_7i27}){F>}H#M6Ivn zd)i8d`db;CUFU)jlt zeg)|t46{&F?!WVUtvY!ZJrI*0^_RqByzm(mP@ugcF8w+2YJqqQe$R+ym~U8zMDdL5 z*A5AW%$W8#2CD_{Bgg8uY5bmIi1c~lUFOSz)BV*223V<|+)fm_Is+<}WudBiE;9={ z<59-56*@cYBM)uH2OSO$gJrHrkxl1WAw0`c6a2!?lfK{b%8Q;@}0tqUW$4o|rHh1&3$FoYFd47SPr{u6x*9BC^ zFYDKb8MX9QS}p92hOv0lgMbVuu*|m@FNgt|f@yf&JUgEAa{umoQNM2u!BZ_@&NRV@ zCpRv%XC~v1xz9VS9BJ-@D<1gm_fVWb{gT9i3_#HNIZ=N6{HD0Rvvm|4Sd5S<#_%KA zm|J=;XH)q?-F;`~={?XZ;*c{tJUc)myF-dMH9ft-@o7^7Np}l+L}WsW)PEZrr+=`| zB&5ffoht#4E0P71h8(Hboso3ZJW_I6vf<+dcTMQz<{dbglC=(<_ zG*g-s8^0CFD5mfvS1AQ?mIe={xQx_>{S8N_63 z;u{?KbyPY5P=z4^_%n*T>~@9hc8SrSHuSOBVXu29yLZh>*Ro00u%<6ofLyoABhXVH zgO`k!Az-XHpH&rbFx9Rw99)yg1k>{LlFeIfsUMluzJ4{~ zm%tvSIq<-}Y210y&zv&6W^Jjwxp_)Ws^9c7{=03F>)*MhD3X4EIuaSy2{oVz;-9G$ zIz8ReyONu7lBRp{*PWyHfuUqsDo@*v>JYN*0XI<8hYKay-%q>uJ{og74*tHJ(KO?H z=WvK(evL-$uSzEvxRq0oPa`#_oT$a;S=tjW5hvmk5#>`7nLzjPo|h<2prfiW3It#~ z5NKSA-R~?1FL74HWN)6fN~95k>|X9#^V1|JHofR%S*Ci+eA}dk zb3WsSc-S$P>FXG}pgSp7(v}_AYhrAKYmJMUc@}|9swDbnJPzdj!TC8BLsF(y^YUvn zlGR-E1z-$;KjyyZm3wAuan3FbInfNc*HrZ5uBEg)A^cO6!_gx`{36zR3pNr1jo1=_ z>6*7MADw9AcZY6>w$svGG1xs!t63Y`t*>)T6VR-&8@BK?wguLJk!?%&x6PH`&4Kh_ z--D%S-@g{!R@cQfTV@Mc_QLjKDzDstwV*1z%t?O{cX@GMDSLYmNc6p?eLhH+cYI)7 z;bu=_NeSj74n4yR9Y7w&R%c$0qnlWPyt_2Te|;J0F#ttDw=^r zCxyb+o6klvB-A?B!|qH|7e$ExdixD7sUomptG@YoGwpt-%Op(~tNkQXU;460%_a{s zqQkV!>6D^F2I-fJYw?g2k;oM2XjkA zp(VLV(Iti+XUWO1(CT}Cih{JJuAmXbe?a~TO~Z~BNY}qplF#?u?UwhF{w@HG4-isG zFn4bv)$={3d8`blCN88Ux!$SgGN26%{tz z>I$6mB3j((cCQqkP$!`4!S;6TZRSeQzb2y#)?LM^;Frwk4OSxSuz&qXHFf+7Qx@jL zApsc7w-m9wYLk4{NdCk|t2mfS{_9R_V21mhyY)Z=jKSi?q7c~Q*-;ZqgfPYE!~{-o zxFV^79a9&$&Z2NhBRux`cEkgX9%6ysJ8y;eA7|Fkt=!F|nBl4QIl;r3&uybM!@%w9 zTw==01tNk%)wQ+FH%6@Mz7eUm17uQU%a^=^XBdbp)`P?45>PXYkDmhwzb9p!)XfAV z9zJBQYS?TVWDm_vQ{=%xcF5729M*^FjBJLEu>n5peGXS;UN4}>DD?ZS0gkrX?g!Hn zI`>;jz>KT}CHRy1x3FVetBzq$>j`8{H+t@NP$x0Ht;Ha5mTsQN3}(IgCh?W0F?(jl zXQ=t&?X$I>O7GczAo~$qTB5YC_=C(E+t2vgy*=(dJbhG_tYzcecIZ&N14xFPWa?#9 zJWKeO$|@x3Q<^Gv6ZN1vIe^ZP#lm=p)VL(Xsewn%bdnzz)~xbP#_ukWnDx+>-?AzA zS(=gbNmS^R?6skEmTfDPqvhu^vR}!=L8QdgrTNnzPk1bH5ngiXc5- zO*}hB%0d&0Fs2tW`eHU;z06(J|Jk={=bU0KuWDW0aU}45^g?^D66i&%?XEeR>J{oN znwNuVWe_Yut}G$BF#%140z|ZUY4-@`B#6FG5(KngU(&8J_2(5=-}wv#jseT5Lh2vj zT??clH5U$`AjVa=|>T$nH z`a~Hibcf&VMN1ZCKukCcK-sLz40oc~lDe#R0W^xSKOOI(@>P0e5259OY4t`PC zu8rq2*LQ^-8XZZh3S0CxRDQVWnu0Pn(_-~=%##fhObIXQer^BeemFAtWD+eQCBmCi)b;+Jm8j&q z@LyHTI_?(JUm88BmxdqoavB&v`G9xl21-+YoloHjVtDd2xte?OR95Dlo}QlWsL%7!^!M+o zG#uH;sY21dX6jPz0{lg{QO`F6b;rW6Hi!3fQ%;ZZ7McT2hlhvTPvxgH{Y3j&rG8fp z?)_QOb~Rs0YK?<4i?8DZyAJVtx%IGLPS*GprC4US;)6n5ag0i(qN;F1nJJU94~5&x z$Fk@ascNlM2T!rUdm>drLlfcz09P2w51dOfkd_1x{ z(IK=be}*?OB6+cL1JEgN-MMLJE&%b zhOVy~-L+?bIN@=y?77Hl@zhX2POD*`(hfl`=wbGXz+EVtTI}%L?JDy};$wAdIHq@K zVJ}(WN*1zH7G4Y4`PJ8gkMj49TpOls+QzES{#aQmR+_xkM;&pRcx%rx?^vHiY;7;B z&Lw7q;Gm@LYa0fLsYjenO?HQXv9FJg5ONy7R4 zC9c(!*rj5n2tfR&jnyfGhi0j+BX>3K{i4?{$f;?J*si1!rP$q-39juONMlVh-AYRL z{mG|6I2pVfeso@e;@I!jys}UEvSxPuko17M?2-C^M@NiF#lJw;mq|{TuW2FcMn+v< zowO#b?(JbW<}37zgtcR~G_P|ol$vd7gQ(c4K)qw}GyHrDMl9)CuO?vf}T^=w*aqN)x~J+iJJY-4cMEh36`;992)!#03_Ey|NIucKW8Q&;!ZWiWO2o0jt@U%EM1#3{mtc^+1jlPp?&`y12MiwQK6b~>$ug< z@tSraoDJ?gAs>(g4jk%pPXc=lz7+1dy&mXJE3?Ib&gYRVzcgcRsTlWOz^aDV^;{ZyYPfTqiP1T$l};n0CE{(Il(kR$>BEmC33|izNO}KV?x9 zGRyp6NT}p!F_udG!YZgR?WlWz8|~DUKmG+S@fg}8h39mqaEQP389$pwR?P~dcWpTV z63K&BByV%pO-IIeUx|HTt{>^{>XLBF>xauTpVp~0#=3g5?KosLo~&p)=N-9)$H)iA zrpY5>HuHmK4~||oOqN>@`n4OEf~pj1N5n)L3tGXYCQbd!ssZ$%T1rqWB}ytXZ92-e z{EnGZtk9Bgp36mPZ)GCL3+v#8BX}tkb^OfaBr7z@oVf#it>{Z;r2m(}o^mmRahOM+ z(!d`9>_km#gS_>yJH{p3y8QUwbFpy0?wSmOjryUrV9nZINimKtHM+{0!s-g#5an$y zW;B0}yG{38>|HsX!60VGr%_|cI!v!>Uke0N!6?jR&advLEdE^*n>yRj)V4jdO&d}8F z58xhN@o4AXMd4fElo@Gx55~T`sI}A&8@)J^pJ}_wt>MdT>W2&3g{+DdC4%n_2wmQa z=w}CfKdn3cl(Uk2eYFsBO|p9MMtsl{x_x+R&cbSZ!uj)&fHZXAV)de7YB{$(M6+Sv z7>=QpnJmx|BZB9mz!E0=)Oa)N^{I-}W*1dORP8O(3Fgfhs|#M?&*Vr1b)$9RPQ<`O zj#8u1)sqdyF_V3O zt@R^|>C3runp@T^iI&OK91d3k`6!V6v1ZX7i+C}iDuyZCyyn=iUeME(SFE>E<-eCJ zgp=uCLpC!o5!DviNjz*U=0Qeh#x+~rh)#>nl z_hWYXa~f6EO&5tuhWa(PylN3?o2wi=9=AsBnZVYM(exwAT9}pDYQ%L-bVi*8=z=rJ z_u=kDtRBOcb7m9-8FC^%|0k{EsU^vU?cR9oZNAYH>^;{jYf$&zJ0fT#Dn#RE`XAPn z5wg|ghSn}FUznx6hbL<}0$W)2pZFjCS&hGEfnKt1SYEe4F`#7T1~!via{CGS z$-~bG3&GB3Hl)?h7*YDLw{3VGxbshyz^iDpxm*>y2X!NU3 zjsR|{KMxdhxxgD5IHr|gsNwu{Aw#Dv3VNPjS8qxYjpb;r>G+l-@{!&6th52>`_AqJ zHLB9x%-nxUx{$#L{D}bvnvN-|y~6zZteEAu10r4R)|q}H^^Ae3vs2~c1n4C_ zzkDLtap|DrTOu0_T12JGx~P$_>qA}%92bEkf{o0JnJO4L9hHHxmyb<@4sYp|of-tEVB?;Iie z(h3(2h8EH)8nj~OdV=Lf780BFPwO7m!N{&4ftn@*nv9ttj8x-`Qcz$@R{^;R(PD-X z6@^aAt5{&!(hT8E5NBRzJN8TWp2(|gz8nzml>qg;@Nm{$NSIs>bsfnS{gofJUqB3O zBixs@$9-nHqGpxz-N%2eQ~>D*83K25&pvfhVm%BKh_6I5FJ|wk+A}hQ46L_LY?uwc z`aAR}pqXzi-E*jg#d$b(Fg4C;I97C0cyI<`k>x7xH7V}!P9pQO_vqO&$*)}!=9&s@ zj=WKboxZuL^WpjN87HgH;Wh<(vdW88p8x~p2oFu6ne{TlGcMFp#YiOm?+%N1e?v6s z&gMi8uizQWlf3vx7dF^uR0Y^l8p?o&Q4Xt&VNFAqr<_?0+)C^k6xe)<77K*HT3QS)5a)j*1FMVHiS@VhJum_SX>e7qzW z-Q6WHI$U)(bZ#y|xNK*4w;H@TK>|eIV;0rkpc2;$o6cGx}#G0eocOvP##B~ZoGW|S0X$9!g8h_C}yP#W%jSf?DeQf~J`yrKlVW^NhSXTf?8RcYdDJTruD#<$N_ zDwP9{DM^C2t^;DVw7=`?Df7lppxM6ii;hc0Te~k!xIdH6ojQ?OBOsdA3t9!TG0-C4 z#q+FouexVcrvu=N+6Wx)B8m~B!}P=um9`0xv|`&>lq+(1l~ozDc7R6sehX5)bn$}QD0R{f~rD*qN=nhfy^U0of3v(vexQqZ+{v==p*wuZP-JtkwZ9!ZlA`3zFA;AbS zeCV>9yblSszf%d@K^jk=-yWJ<9i&ECUN|3Uav}a|KJ+nbtPgNIJnc;Wb`>POTl%oRIhdac|3KegmT$MEI;YTm%EdwWh`Dk9j zdyj}xnDdjk7^MJg$K1z$`ZuhgHUj>SgR?V>@@;#XzkE%LS6lW|m&{`ji}OK}lL;9? zFQKN}+ulSY`CbM6mCa!E6iVk{FGZNqd19Fb@#p+IAdSo!RIR%XRuw zjxDD-VT=e%PC1cxmhJffrKh4$DMY7CLPN@b85okfIOZp0aKDU=?wDFq_HEST4Q@5E z0*;dq@~!cHZboi~+gQE>Ea%qQxSISW!Xn>Q!0*P|zGfJ7o|Cq?0u5<;;@o1b@AXkU zR^Y}4bq2hdX2clDKPbVb%dYGdKe9-~+|6e3(kQT}Ie1WaSpuTed) zSv0yEZy6^@PBHAF4q*<1OD~@-sU`?{zqQ9G)k#`jcvW>C%nMx8KuU4HX6dAVA&Dv? ziAv=hH^uGC89(|~8!yq}D>?ptQc^|8S^Ww#84-g+cB8k zRcbE0ZgZ8Yej}3HaIL9H+B7P~>GgV50J9$)7Mz$FuJjjt`N_LmBSpi^vl5F>(c{3! z^cR4gfn9HbR^N2st?!Su%S~Lp{Fa!gD|5|tISsa7Y4Muz+jR_>mYL}!!nWicPNT6v zO;>HaiSvBZ+%pj#(qQE;cqn9YVm=Zn&t-fj8sUMvm`Rx=OAKS_=nE!5T~N5}n)BfM zBnt#ef8Z%M+_ij16pW8z_|>;-yVWkQR0@DUBov;sY|R4PQt5zt4LbFx^Naj(@$RBE z!u%S#F@M6=HtfLLQcq!@U2ZTz>~_d%v6OV1o_x(|vU)Q_n4yU2cJoMDT4n9544#Fu z7&W*&-CAWKG2gan+BT-2C?&Dw^SsEqzGED1qJ*h{nPD?rqZve+;AMNI`_Y2)hijrdbK8USCd2gyl0#8&ZWZk+TC>?m9nN7_p0R1@0 z%wF4X4Tx`)0-h;5(6VZCs6mXgGst9r*XdOlAAiTp`uReTT&=}ZM%db0)ducFJJSZ3 z*Y+3kPqvWF%wDNeeXF?mqU{-m5VI9(>a$#%D8U z00F=mkqaJYlzt4z1vlaw9rI)Tu9POLvR=CYv7dP%KeJg%2E9X%s~kq!=F3|U&`RM- zyi3qJ^Wr-%n~HP%B%jrI*G|v!;5UVn11BNli%Y^kJdArf(`}NM>37WY8a0?|{*&R? zY2W>GjveyET6&dXU%7A^L5k7jai}OS-P&!){2y7D?=Z+gwRx4CXJ5-$C54Y&XOPJk zua;g?(9|nQ9wuaTRU0pE4cgz)$ALzL4b)(w0>+_FQp+gIaNPtJz3~1k%UoC)m4fEH zb8^yXy+U+|GhRe=B+3LvPfLNy!@!eHPWxWoSX+m(*-y&e#=_Hn(W^8(Dsei}Y)Ka2 z3u`omdR&$M#yPb^JlQ=95u`hZ{l>YKG+yX)Nfd1K8)^9_0lWeK(qQvpoM;ou=gvfq z#l^*zW*Kc5MlKjZ%XBPsRsXb?S>_bsJ#jnyQlNERL{^sByT?0OKm!z6)h_dvj2y|f zGrjoa-S7XO1)%S`Sj98(W)?potM~BLi`Y0XMX0i$kL0=}=Q$0@JD6ngHWlNH)OBV=au74W=ZWJ!l`&ekH$sUcJRRIEfIQH4UDk&xvrvJUO!&uZx zTH@o(H%9Ue?MWZ~< zp8?Re^!5E3sY7RXdn5cP@;a3mpbOiQ@`LNH!5@e@8`pPt%khzlV(zBp6jaY-!J`@+C2PZBP%j6+yR~X6*ZoSP2?XMe&=cBI&KSPSCjbMJ#fop_U31QrUb&qz6glVWZwV_H!!TAY?EM1~dHpFmk8 z2!EzI=V6s_vmY62(=>QpE13xP4)bu=YA(-ymgX*Oa&nFL8PDFOJ!;7w1@TUgZsubQN->%L z^OJL{Rhzfv?M4NDBV7c_hrIOX@`<&*M-tfR9>p4CUZVUT>*bs2w1TV`54qHiXmw5J zX-{^WGpeeDqoOG0_equ@KF*^00sM6-KkA$M9l$%nzI#`}MTzkuA$DIQQxK*mgDC=h z*eFQhkE2=(eFdv3I9(`Vpa-sf?W4?hfRQw7byjG*@R>$Swk-98=LLe_yQZtJ9LcVp zmAO&zh)F>uWooI1dxpevO+y~ql`f}a;QA`N>}dgAnA5sHY$wH;pprCEU%aCZY#3{8 zQ~LfJB-&}fx_TAC8wLvwKLkHTV{Y!IkniO;HfCJz$yaVC+)H?koCtzQ^OeL2OhJ5e zb+yUld9P0&m!uq2x|VlU4m{qWvf{=`1{!luwjO65p>=^emw9UyC?MTvSbt?n?ucIfftqP5(U}R zi&4&p4+~@gnBGfNDZB-y`LO_BxwmD}1RpDgYRT3lfS>(dG103=`_Ym0sQz zmN!Fvz+L@tc2cf=*R@I2bx*nF8pcGa@tcEUW@E#i=Q^7t&Fvz6MtD6Aiy-iKKveBU zr9fWphAe6+L^$n@eO?qJVzv4Z+(#*d$?uZB0QzY#OFvE$T~5zP@s*|M#c`ZiYgRNepk_KpFP zYK{5#Ds?4p9sW9w_xmOzMI*QUXbp+GO9kPl71cch_y4N?m*N7N{$a%g{hVs>_>z%e zom{5^(GeS%t4U4t$%t3kOj_Sd7VpEdLrs&W+)%;Dzt!<~iDxSJBT!l}p+IVFiOe5i zMXX+j+jq0-Rvg>Lj3I6s0=JQvH};31e_Vb0_O-y@S0L8bB5(kFN!FyOyuw?OJdQ{E z;l!sO%c`b7k7@+t`GXxIXHKP~I(^bZXAbjz*OJG%Mjvzv0)n|GGmac^n~=wr?7*Eo zx3ErPaf&7sy98V5ZJ4egpS?oZ*KWPe%K?yr1ZlgiVHNe8tR&V+H3>8Qc3%)E?#FvR z#MnzZm8#AW7gIdT@JVAE<%Al{ZhWIDBE7B8$R?G+vMaL)^@aY6f(rFhsh`irExzd@ zt=I^vaC9Cf`HiYXyy-z-SZx(}Zhv;x^*4yNhdHpvOQ$9(Y=5;LQGiU%MYFRrZike7F^SFN4~|QTy7yl0Qp+6KXJ?M8m%wrncZcthDgWKD8}^&eL?M{sZ&!`? z*)K-{Zl?WcXVl5{4iD+B-yBLtt|5=H^nJ@zImb}V$gSDBe)Evk3}yF#FU)`04RS2< z>`ZthG8f9Y?R?iMd}9!lNq6~F{vdcH5~W$>Mg25jv|J@FYYcrldccvC?`E>vzE5wu z3D{ig5RCM*9=tFeZ+d!SPN`7c1)ucw#s|CKW%}RGJLJ{!#HaBG&i`^8Bzo>Gw*TrQ zHHVe$oe)G!$iS~`@nO9O8?1rM)AsBFoCxjz(dP*r0J6=62nAl3QxT&p?ybzJ2i{ZS z_^nB)aZP<_j}sna_+)8c-fyY-KO3IrozG9bVReBC_9{we7g-F@GfULc-e{y0AbQ5| z$cvOYO4)?e82zzy`QF-yDeo8zhZB>@W}6{sGILmxXWy0dybx9%7%godL6{ z^mf|*E0*O8!Yp2nmfIwcLJ)5S%43+T^Q4ma(7C#I1yde3j5XH3Bbn&<7AafO@v8H1 z(t!vBiZS;B#_*zzyUt@crb4dHPUO0w&lA^wqJtjT$C_bAKx$I(^##4(&Q#j zG<&-tfvm$)l~r?;s#llGgQxCODGo{&enb1l35jo}MB@B2upUZV>z(R-b-jPf``N}g z!4e^EBY`zFSo)OkZ0my*aG64B=n4g7F;^$7&1H_Z*L&E0m8d5f(6g1XaR_y79PwI? z5FK9lAl9L35w3PCOFvP6Z;og{-#$P%6qX9!+84>N7%Ca}2S6)W!%bAV(a}4_;i#`$ z!0e@E0`VLK158?dasM5eJwgN^&tdT9x>j+iVs-h+-l^0odJ@-*33>Ou!rrsY^5D9Z z#?mtVKCKxaC8c7$z^i(xn?txrW~m>E1cQ)Spr)YPhTy~8QF5`l~j52O~CZEV>ZwemB*LB1u2m&)rJVc0)2nqw#$blsc zY^mRV0D4wOXs;dFc0vKD?YYu{1O^R8qPM(@fr(xJK)iHXp8AkdkQmsHgM<(MYW@Yh zCS1k_-^@1(}Cm%B_z(1ObKK*RXSO>j~gA5a;c;%YNMp4AN*FHZ0TI~lZdKl z*W^JR93r$Zbl-3Lb&ZkjfdFlfxwjuI69rEg?u~KzbG(k&XOM{n&pc$fVjhXyiKxebSc*T=Veli4pJKLVA%nZgiO0LgAyx66xgGQ_z=YNL z)pN@D5R(c9u%dffj0JBMJgY{P>wVMbI+PLDK#%au?7if~k#KT<}S}f7tgSx9oNLKs=q& zRQ;xfsgtveTfX`UB;6}r$snKYZ{4@YIV_Tyj9Ca#@(Ne6pw*JRftQA)mh5NT>i-<^ z?9PqJ$VyM<)SE^jKDv1$8Yz3hPWk6pC~S6?77mGncW*}VUN`QeDGFqx(l$Clgd;45 z5gi<^y@9h=E)!RsuZj}uG?&rnWseV=Pi73oD^KQTUO5{Mem``qYz4%csp|wbOtv4c zfjo%|PyBX->0iDewFRIJIbO6r z?QHY5+n-dW3%$@!|hK}S$6H7x#& zGi9Bj&Uau!X$G@sBQSGu81(qYnAE-x7%h-QjrD!G)(TZlK5;w%Eb;lDjV(rf#*D|K zUAObLEM;*D6ApB#VS>p5WSorGwnn80MZ3-iIkE z<<9H#Pe0sEN#Kn6Nvz%;SAo`{$ABEx#}|+R7ABZ0ry*`4tAIf-l?N~@ZCl+AkCT%? z{T{X8z@H=9Nr0?f{sz#(_&!IrIWtN++*X+z%dM>T=n<_SYqm^U$(}|HA!)~y1*YYJ zd$$qwXrRKodNk-t01@AI``B>owBoNVx1l_2<}JC!wHwhGpYq zD@#+K&X&|}N%AmJe1xxQb2zq!ZL~)3cl`Ry{#7_AaI~10Fh5t6Rz=8Fy$QdeT>Z-f zb$@$c^VP*Q4TdkAR%Hw|b#qr=dEp~@RvCYh_6%-wff923$X+z)swc>>Ci7jawYgK; zi04~s*H=pY4!Y3 zC4w@y0IAclLnOK%I9FYcSK_6mLyITLxIefe2&r2|dJ1XJbCboSgV|nN$L_ zh%L3F5>GF~-1s@h^57CwW3ojQ@0+w^=4XZC;vZVCANms5XQM!k`_%#aXmL2E&gsfA|MADa z4Yzx*XWTp{_v&c09z1L!>359QbH5J!2mMteEcB?3c0_r99AtQa1{cVNgWtQm$!>J` z`ewoaVVYchdG$2;=0bAziosj%Mo~f&$2u|}sIH#teBE2Q>{X#<(_-N4pw<=PkFk!y6i%14v0#J=bMt&Zgyk?|Gu>B zwLR&%5nFU`I*a=3nadPh)QmsB9iL5_H^qhWa@nmmmZ1$u$1_>f_$a`nm9vdLn^VBD zNLM&ka3=!=e$3eP@zcf;MoEUOs*Z#EPcKEwwP0VVC~6Ay_pI%4P1rw(vS{OSen3;W z^POpo7(VbXeb4*|9^O*6kEyOCs-yFzt1CU+XP}2^FPZc%4}Lup z=^IVgwaaj9V>6j8nB-7^G+Jk5H9&JMdns73k7JP!w`K;uq>~!Vawm6*+x}3$kd;Pp zF12miQPNTNO(!))$cz;hh_ECz`guEcy4j14Sjjaama6mNwne3z$EOxKr*p4%PWUT*OLLs^ge5l$;IB)d)oel{XO`{b% zeTIN%S5|fPSYk#alT<54i0>i(wEMxcC`6*}gg?Zow{9eJr^4(V;SNU(oP&GRmS?Mq zCl=S6pdbfJ6(4%?$y_(ADWoim&tDceL-gJ$R4-GM5SavVpL5f z1Bh{itMg9sfS4l^W*%iq1soofp~k?Cg%4DJ*0DVS}%V-{N_6 z81k%HOIw?LM`U1EPM}rdflB6SlY6@6eD&}q#rI20v9Fms`A=ug!Jr-Cu?4D#WnsW3 z=z<75+7WTtrGjIk;M#vX4qKDp+KU;oK%&f>gs?>MeS67fyV-8Gw3|z23dZ)S{ z)STJ)7@yi#CggpcP6EoOg?{uw_2tJxk1E4sz)j8sZ0zZ2$b~Y@UF|#Br*8{sP&6&y5T%!)Xp3>C-$=*1vJ^wXdQ8PwOF7>tYWd=aE zF#U1a^j-dlVWg!e(l$xpyg%4%?8(MIU>TcWE$NX*C$GH1_v*ZY^MrYQz z?1q2N?&%cnX%7x!cDZ`tYT)J2$-MG73sME)#RR2rn?2aawC@plht9!2mVTIv0ds^cI}F@zw`pN# zM)f^khOYf&p~!CnkwYgxIotkzg6gkjIFY6uH<=6bl+d@tIP3E!%C@A-Eb?tdB|P6Y zYiO%t&~qrjLJlf^zXVQ&D(g1qXV?$WFJ7Z24=5_sGFqLg$)gI;wzD#*4g)+Jc4j`h zbGlUAsPs@w5TvTA-I zY#O=dDp}ma^tr{-cc}#kBhMn&R4hpT9RMkpt7IMaaqMxp@bu>rJBuO&9rkMoi-&J$ z%D7)m7!o;O)2uo^-!6%AnK-#;H1HHV#+^|T!1@*}oR2?=)Qf%bYwws{Ru=_T;( zzH6`tl_9Oktn<4OyZZC>;-8JRWY_lcYJHY9rEh1ikag6+n)~(})A(2Xbf;`3qh~fM zWM<3Dj|s{VIO5)I_e1p-&+IsU9?d73`*{id3ualDp_co*D@*7n{K&QfD_MRLMl468 zYS!^ZzJ3?7sh47I@XMlCRA7WScU1D!)oU-U&WHcddLzK{0;5D?`!)G`=9`rJd%z1Q zN_+=BWVP7^I&N)#$~CYap1F0&*CY^gf|gh32C4*`fLDYvY-je-$8dQMg1YzS&9ScK zsJ=OshJ9?*&LtJH7A|~_X49IRdk^j6rn`M;;!U^Fk#uj||M~b+lt1B{<_Ku{LWUzi ziJAIAKCVn}8uP9*8*O{x2qEOiEelyGQ{wywKI0dqu-wDic&O*>#zuzY=A&{b=cZ8< zx?mi+A7s?9*bS{eQ~$8JV%^^V$q^WLI?fwfBvP5|x!9pw+$wy~c}T+bvM}U63z!0zm{F{s||Z}p6d!wdGst->uZZx)`?r*aLG-gRY*1Esx0rrjf@P)?&c z1(fvv!9MRF?D-45Ai~F-Z6!dfOa)kjq}ZO|uNsV(*#3lN2ClPJLkKe-3W3?W=@z=+f%om}OdQ}74=mSG1XMYQTiYdm1hrTr%DO==8cmZfpxf>7MT_M^R0|v z34zcrKwCDtzJJBIK{I>$9`r&@l(CDNG+>xpnp$zZp~vEpE}tOYbov1zs5)6)eDh-h z+{o&nfZy`zOyM)xhkKZVU#|O1ncu&+un9~<>=6`#DT(Gzf4+{FNJD>0jn>t-&^Hmu zW}>`s#3jI+Sru^t6VFB_>^QjTeAt{5_%qu97-UX<4-*)1%SsK3Huv+~2^8e2QNPupilU4lI4rDTL zx77DPzRoHV*%v6-S<1M-Nbsf(;f4g9xq)$Fs&TiGNIgZL>hjwR=)PzHso+?DE0^cP zM84MhKmDvW#xy1MUL1>5d-_Lq-!MdoQomn)Qy?3x+r6FO{u_K@d!PxJZtTDU-;IvI zz-HJ{?c3< zB0as4fxnkAwAhkoA}iOEzB~Y>E5sk*L2>^m-U*qDAlwh429){k7jWsGlV8IB+gj^l z{I74#P;m>s)Sjy_V)8|O#Dpp{NTpsiJ8fllE7TA*Vxy1gQ+`yeTE!o~Cu^;5_vYmV zCl?v1-j^S08GFvMzN7zHZYEVa-f>_Vu)s)A%7vp|-r&27>2jK_pp>-^uc>mHR_SLS z{#IvxJgJ6ycZ;>{2-_dxqad_%F8i9hW3epre~8KVNNGi0T39-cqJF2;ycU@z0W9=PDy18bA5S`P_R2 zz&#Lk(>aaYL+`?1g#Hy=-cs+YMqD~Ubo*#RfK~(;sJt^w!!ZE)+<_H+JSl0IvH*eN z;ge?iTNaNPUtvCtU(@`!TXIbU&XD6rK1qG=Vkly2yshF4i{bjNlU^UMQp#_SuqLz8 zVJk>5t}ZMbdS@jA(a4rGeEhjQyz<^rg9|H@MZrg+%>XM$^Rm4U8AR5Oxff_?ulNb7 zp&qSzdDo-} z(-RpJZ$Thw$|y9nsfA>@qIJ0mf?sd20R?~QFyN|&HD@hVJw8G6ZP1b2oZPeS=6uH~ zkCyO&@2s|0`)(1Uzk6=TeW!t3Ouj;zlY@B`5XfK%#q8C!2CGV7gg9qR-Cgg_Nz$@HZ59(1ak?-$XNT8vELaHMEnAkvuxjW1_F%eehnoujL}&uh-yG za9|Aw5mG7qlP6o9aNgCg0HNFiexExLI60mUyLY=D?)Vk;2Ad?A>oUrb z`n3W4 z=sjwb(R+{H6D5+2k`P4iGmPFNq9z!|=-nWC=YPFF-}`qzaxD+6S##OvKKHR-$KK$* zH;1r+=6|j@ZnQdr^RD+#z~)R>t;z#s2CjKqmWOnf#BZrEQq9f&1(P2+#`lxZH$F^1 zvQB}uCrsVVAqHT#o0IR4{&K#OeDouzml)QDb3=@-hAgz{`jvYZ3buT*C}N~5rsg4%YQX5(69RPf4Hi% zG8O_Xt*UJLGyG=@mi!zx=%TeyIGO&oipEBcS>`Qy+@hPgRE{uzf6w%s(~}lWzP)47 zA$2yZwEk$S0cIgW2ZU4K0PoG*u6V zJYUWxZ-bhD#$m1vx^^3Vv}PHzB=6ilLudYnssmxVH=ej4NIO$V9qvu)cv$1{MV*?Q zIId@6eYE=UQZ=^kuKC0o4;Yko`G6O<4s0}R?dJCQFeRcfx#3ry|e+8;XBneNZwDi9Bv$%+4eP(`=VCV4VmmmIym-) z3NwZp!X@GYsn%V`Cc>en44qDptzyBM)EoxD8mfqsOIKZ`O7qTgn&_8gS|Vn{5$iW6?i!Y-3FOzDPvPm-5rIS*j(ZdwiS`Yvt53 ztQ?Qa<8}i8JXtM3z2N)MTT8paz8XvQa=`tmg8cVbILW3h+7QsF#A8qRx4OS^Q2aZ; zJN7ou6sWi>bZ6Urm=W&y2ZI^@`+--eDu1K7TD~8ixE`4Rg|O_eT@9$_2E89UGCPLiKFXWs?*EZ>_(L9L#Dxaw2_GKFXHk8B#CC+!0_tN42+b zz!21`d3BsgM3|Z|EDtg>PCyB%K4F*9HwFDKypB@*~YV@#RO0UJo6Dl;-u{`Tc{AvT8tTn7`{kw5XR1 zOG=pj923}yD<>Rw&d&e+AM+3n56P%X!)w5JNAyFB^a&dK|Hk;6=>ci$_~SUo+ZFn$ z#JReCdU`t=sk~d6Nf(?d=E?xa=I3dKIc}d$<=0rv+W50Lk3by>P*j6qYsF95y% z5J=aP1@8e$l?xW}C#l;8z{?(!u@xX)6?d5{|3lChtQ@Y$gpQCvWWTqWJoyziKYS1f z9`&bs4m8$a#Xobwa&jR(Z2D9J)&B#|7^J-o@m$Z<9YDX3yn zqa@e3Bt^B(2Vq3GQ&V9J*h9mGRpo-JcUMHA-?i zQew}8@k{_YKvOb1Ehjn8Is2l!a<+ z2Xp}KSSs}LF)^1#LptMCHvl^9!|v6bNm;OoVQ>2niZOoy+s%hly4if`NJEBg^CU|L zji%p666kA5Ui|%Jo1Mn*ll@KJ4HI`tM9cl-&Z?WtShA;cDfjEa4+8+Q^Rdd#FVUf9 z0N{N3VxxQK4|TNnT3M%%hr?*E$Ekzz%;qJ1Bx+HP2-(v3rNlhvsfClO6fS_&8R0lH zJgqbY_P%#YCMs~=xAc1<1qCdrpzhDAQW-#hu={iG@GjYgz9JS@{-J2m)Y`b@4G_n< zps6ikybGJ}^2r{YfZt@azbBS&TJC`Sgbj>G{u0@;0~APiJI^_;PB`Yhl4$Yh28Ll}@?I{pzE6xeKOF zndGqad{$iid@=y3mf+k7;ge}l!T<84KLF2~7POJCR^dJNHfFwTtc7}l@561$VheRO zSJd9?ugX<|OZj5s_b_#r&tf(lKJYNi7^?W8Hl<@+1#B9)7Gi*@z<^cEO#i=N7c13$ zt1rPnM~zddxim(lGO8}zGC5SI%qIwGDUCV}U1Kd1?JVcR`dO4Vc%ZiIKeP`9{wKPR zb$3DQa^x*P3NEZBdU&j+Y%PMQ$Q-{9FSyAYPpg^{o53Py&XCgc8|%#jLx*YFQzuWs z15Bo#m%ddS58isK%!asp-o5b?N?L+}+6U8M*sEOAgBXZn-j8L8nf#W9Wt0KZzQf%( zWTECGpxuQ_iT@;6V872;8kql|QGApSe@vKpQSd*vXh3^#<1$~?ZIcVlBK7Cva(0N1 z*yJ=KrY(4%3`rhG*6|iolJL<8P}v*+dx>;g8$5YZB&KIJQwRS%3^@Yw*qIlaG&-X3MPSkLiY+K{4WPsb2+>`SNtXl>Uzn z=Z`Yf7-Q<5Yz8XhcXc@2ZJWuY7Ii5%wZytCuEQbEyUY!QH;96|59(8`8z&lI3K{V4 zFW$;%0sP*}QwO9SP=bx2TMmk!(Sr4Hbnu@5sM=Y&U=DdstqI`NAT5Y57fbT&l@RHL zRuR4h6tkdi(6TiOjQ()SZt37AB?okqQzMN8%qxAlC6Uzl+4lCmEOted-bL# ztYt19M^-Ac_I6t!)5@8e^i$be0u}`?lf_>D@HiN?J-v zHUjgY;+KCG_J!`fkZ72dNG?dJDPJ1C?c3-cUvakDX52XW6^+#y#GB*{#EN-J7^Y;KUWz# zxs6QGBb>d9bvJK*cIN_yYY#q;+`TcvaRZMMTkdVS*``G)U_z{Wx!b>}%)DljunbIK zUZlaz%-xTZU;^QcoArO<4vJnn`u9?=m5Ii(mt< zy@-25wKR2tqygiiNVM#_v@(tXoVL&Np4`!!hIbLem&YZY9!5vZa$zmMaa z|0;cZR}LrY`O_E3%*e<>Rs?J`9aje*Kpz|Ts%)B zc@^SK+=}VgYKs8{DhYSq)qfIeQ)tg#uSThsxD$=8zM(81A%dpS`N!h{Sv{>kTevYjp~M7%tBy5w^)<@%K7>OYvzRtk+411cIkLm z{8kh3;ua8S3timpQzsyni+Zq0+iFcf@Q0vK(!%r0RHc!h`E6}%+zbtAI*tGMktfQF zKPxMr`~r(4W-ot2Up?g@*W(HG9MGB1<@IQ`P|Y;!Dm83rw4cXpD=V3RJ1Fr+Ei+vg z*FvH(3x2n5(VmC$0`DbD1v=q0N@hYv8krlouF!j8fmgi(}Umq`>wkZ`93wO!JPnR}^MgU!j?KDUdgy%pIrgW{RE4$<;l8HA=7A52b4ZraYz9Tw zA}zQrk~!>9k1i%-XR6b5DqpP%$b*4BOMatFcGib!h=5Lb9n>fA z{^ZX*dvIum^zgTdsr);OqTcK|9vs1iZ`JP3IvPg195zQEYj{%fT}=G+y`@U+jI$-< zpXW_FW6!iL$F0`G85FaDQ>;`0ugKSqB{xjYcbm=}(f|85tO+X6-o=2KBfY$wci-c* zan-Zbd5TreH17s8d?SW;xRB1se`HoQiHI5dHk)l6&a*%9K2iCFM*TCaYs&T@o_G-} z8+F@8xofm%-=oakti*3BS+PX}Iwm;UyneK06~;1QL;<+5-`|LD)V?7$bnP;IW5ujy z=lPvG?6Ty6`|GZ`b^4sPjK{W)rRqo%U zhnxUc$8q`jI??12L3<$457quOOxNTQC8#fVHfr4tqkM+iUmwurvFn5?DFf@0~^YeJ#TYj89 zWJV4wPptw&yIqAwI4|jMPF*qer^XN5MtS|>ZH|SK;w-|nL+TT1u5{~^8*8GWq+iY2 zh+4SLSqjJES5o;nIyf$+9=H|`IdF&(wGdWLDdo;sU(Ypq+%iA$fQ@K{E9ChdX>{8L zQ;QDMSi^i!iHD4ky}sdmB}CQA`pd7Y^Pp|GDo}>Q_FOs629DAtTnZJo|0-g{#coty zkYaxbot1W-=X{Z)5wet`RtTBs9Ns4%(6k-$%Xn{yLYU<=?&{1gMt(#moC&i2LiF4O zE5tU)>OOS!_nKqu2K#?A+mEi+<}G4WA5XP%-$*6bqcFuZD0lpq`Iu5)+SHHcCb|qE zBYxo!Msl8OXlG^$6Wzuq*mT4$PPV)&YA4#%7FZUwAwmxf!iIcv z1v02!QIK8cyP4N%$>Ixk+39~J2qy^!Qi0h9s;DNAU~rvj=RZzdneLfCS(GJZ8_iz% zw($u4)tZ~zbLpy08uz&#N0wKITxISI%`O>aXrkWvsT|O6^;DC^s!psQa`yf#UMtJ# zcpq7#Bil^@Y=dv|2)l*np2j_x=k`_Lo(DYRX!4J9$V{uc zM{G7j3#3XM6HUy!TR3`4xSB3D?mBlCf5{`%_ ze?Fm5GE{_C24qV*I+R%VR@hQO>}GAuzNroNcSw5?R>0BS1WO7lA$Mp{orG-d$22-* zA9%%imZaJ~7DDXC(Wz^U>I=wGO$D|E#>`Z z{$s-uT4T>rAcL&Ddg^gRI9_={NN<(nGvKV_er@UA#AQ0BoOA}pj+;h4d8g$Xz9p6TgVZa1RUW5WMfW1)Jx|+1<8C0LE!s?fc8`a$C- zKaaI6i_^EYjiY0b4OzGpferVA-3zz+`pjyFMx;HX{M$|Kmt7Yj242*1#%Of zEss7i@wg+kjf%Pj3<8#qj}BU6NvyTPnG8N*!24b|ShXR^=+`;i1_2w`du9C0KSct!|BA7|R>p^SK+niI z;@;q(ks*(5s#$-X2>ek$FqD!cpjg|*jYz+V_gZP+MWo|5UFdR-gf-cl6p1TSh;QPi z;qpZc^v>ANUF#EFaTbKs_ejR|)VBTZBhK#(@T4g;?iprKPQld8dOpac0x_Ldr z;dmV6qMoNhx_ab_J*tEF0$)!H8NGK0WX8N&JB}s?K)3lF=x=vvxYmyscE?6KNGe1; zPbUe5brciQ(}2fOd|_fxA9!yF&f=pzGbN&@kx3}iu**v2SidAgs@8l*w)>}(`*h$> z4XyFL{%$xj6~;mwxwI^KRnL{IoN7K#%-sxwY~9aOyfHdxh1$xWUsKig{CBqm{&-6* zTGEtDn$+V!B{iYGy74!<9iujM0J=%Jw})iOVpPw}*7X8`JMt6ije0_5`g&*1R_w={ zZM^gI`vVSClYy7leLs2mC4#?KC-p?9nuUNTkivJp(}L*?@+H15DxGut_cxm7Fy2WW z@$c*oMZJ``Mr~ws*q9)ib5^b2glAlH)vGqle{mBI+Gs_7b%nx{@|$r!|I@Q0%DW4f z+)n~>lQF)(+rz?*XUX$#W*7f2Qa+5a+#RqS4ZaLZZ)|M*D+1eI%3kQ>F`j00@J$MO z6KLUWYKd?$DA)ZXFy}V+wHQ3e%<-A_)MBy%qcfz~<(C?pisl$z>T%2YJcvUk8NCkuVr=%sWb^KW-~EqX&=gnP-h{WMys|+cS(v<&QBKUi9>(H7`f?>9jvA9 zeSth8-w_(2W#LsR=zN>$vo3p@BXNpnk6T3_h%2DvHc7Y!Wr)iRRG^giTbOY&c{ zFziM)B9hdx=}deE#tlAGj46F;7U-WGJF@f$w*#fGu61Nv1K+CZ(^WkyQQ!F{htmpH zt+DS&oqtv#v<9k-;&bb}B(KJE9GY^0aneeIVRP3+$i~F>FmCjFzBPHw?P?J(xbDbnM=YmUyzb$ye*mGv^# zzcf!Vp~ig)b|dhi_>uYk-!y0#BZtPL)5>W5f9fDKGCG@~2gaz1P(V%bl&>l~6o-48 z5q(>2XPR8at|OCDeIwW=Nd{7x+&$;)>kFm0f_nCaS;8F}J?Jap$+{s_3ykW6QBC@z za|VxhF%T4)>8>B>;QDEIyQ0#SGO!44$I}fO@%b&S4X|@LwCSR6taP4MgNbjZbGW*< zTFCN~D(c3}ys>*vJ4BtzSap!uXU7jqU?7?V9WJngb3By7gLip0ev#@oTv_PO)9^Md zrO}D4+TzBOHfH|oGfyAs`dBD#d^)%^Qz1&Xl~E@gZu|OhWcJl79;P1dc_(RviX%5n zF5g!nTYP!Jv{K@WytAwjLe_6aT{N-&z=cDjd;d|BM;7B-lQZSFTx96QZ|MgDWazY( zp{XGzQuKLGja7czO5l@3$x|<`?lV9CKgEzq&7j842=_Vy{znlrNCJkqh_Ep+nq>z% z4E*1S*7Cl{=kt1;sj`Y*0Djh{l8o?ug8xPkzI}*$g%8=6ma+`*Jc&pTfd}P9LA+E^0<{C9 z&4FQ+hm<(rZnx_jNCNE~kGai&$JFa|s|uQc3D|0GOLRoi7u6{+oql?S`=R0aZH2p+ zRL+@0wi~lyx>Yre@n2_)rCmRfK3bo0w#@sVrk%0CENv7`R_g%xqCmC}z$N5u+)H(X zwKTtHuY5{xMQFEJ(fE-#p(RQt&r_iXxnx(T(n13pZJK$n)BU4|ftv4Vo}F&dooYw1 zi2Y^kiSJ$82Zd)}fMX0Ov86*VNje7zaEg#%;GTDkpOO#lC=K4xIN}$af3r6eXnB(z zKCsboBAsUzkXHhgdnO56BfP`PVl8Gh78Xv#-VlE&PBSa(rSKa*e)N^yj;1(ZdD-20;U-DRH$C;^mcJtg&^w&VL(HKlBBATbiq$7N!cOE(Wz( zF6dqTE8!V7Npk7ql~!u30slDr^6h@7`ad!0N;}2&nWS~`(oDZNUu#%E^V4Vy(eyZl zAO7&$0<%Y}Z&_XM+M66h>$zfE2A$TlD+|p?Gk-7Y>^@vcbdMHk6I=4X#PN52yxGM) zMFEe48a!HS77jW$G}f1lsDs{$oU%xD#w}F)grPX_O)J|u93QcD+IcBPD(u|yG1Cr)dE}=k5H%v7Z^hD}@8^Jwts%6Pa(P^T(2(xy9^!B?j2qn+4`b=cm0|2b zuYyv)mP4D}9{q%3f21tB75M;1K;n8u!RlVkzTvVH_6OXPvUk4J($fWYZqtTZ{KUv0 zt2IhXQV~Ah%k3A@@>z?qylT~&@iTJ++6jcq^tWE8n1H>jtR@?AzjAP`+cI^>Gu-@` z8wb6LPX}TC9&}rO5XA?*rFw07`Q{&mRsgftQGWc&LX3q=f^w>*yHSRu0WVHlP@eC* zxfB@>Vq?0e@tk3}4GM%3G@(G&PMB{ zokAPRq)9H<0`-vvhaQ%TyH zrg_d8mkDgA%`9hL$f#+vGg zNW@v${oxrr`$$l4*bw)jB_U4r6=#ROJWJHf1(}B zmKFO5dgBy{NI^7Bgk)QIn_RlkzeI9L`(dS)OO?s2alDvvT>qw~sh33R%4t1Xu`Jh;S;h8PrgubJxOquNOm3yrRw> zgu0=NF!@cx*Q%1ZY@*uYj%;%}?sB_pmlUU$@T;};LK#G^MI+=?pC_e%5n+moawk(N zPF;^kr)wP~K~DC9#hgZ5YjV(_zOw_bmREYw65_$aiMafejEYr(vt&jC{bYr!g3z|G z+!VfC_f3}(&dkb8&hbiw=aFdqUlQCm!5A}9pXeHYyj-LK2G1UIeGjrtgl^ebX=7S6 z7d8BGv#or3YYZqmau=A%k6%7|kM6zM`~2wlP|8(URT)iQPwp2YOjfzTQ1q^AWL?$- z?Hm6?zst9Mvz_fDO zVrpQW!luImV2QGr1JuRt+G#X7<6m2AK5XClw|CAqtOW3^i9ZL|>@_JkZmU01SW`p2 zf80mW_wjKzGYI)}ALM2Aev*GD>-!iO5z)kyF)&)HKkBjTK3{Ox7?Ub2Zn7ftC6y8{ zlaYj39XF(&98k4tcFfG-5HfhtLo8W#wV(N|=es)p;8p~_+4=co?PN~TM{!)61){KD z;O<+g=O@=2!im)b)rdSReQua@Fe&fg53nYc6GfB##^tx>w69fIn^yzuzcQUtaDFDb z0Q=GOZmLIDn7*hSLAK&1HL$UO# z_PlrI!Ju;_22!V?X^v4bN*`#|Tvz+dl9InNOSZV8z#(lRAiSsDzq4(&>%~25EWpj5wwInU&5i5lY!?T>LO`3N7=mQwC&xRv#nA^|dtR{Wc zv6#*%oyGrrZ{;bfZSwSXAZt!kNDsXD5Vm+Kl)}32=agg%IlRiE1S&&l+^*If?yL%q zW5yz!AprBF$7n7j2{_BjUc(@GGlXjuS|{UYYXhXK5?U<7{wGP{U5~>j-6|}%nKPV4z@ls=dabTC4(hN~Q-g}!Q{i&VhvK#IzFKg=vV%o6t zT6s=3ZsJO^*I-3PmFam%uXVMH^pt$wpGLc8{N3!m|E_D9eIFNZjr+6~|UCEnftdgX?S@|S{ z1+v%AE%QU{VPR8pO}598Jg9Hib{=!B5Y%p6b2gxD*nR-zd!5p8RwZ!MHYgI}O$t&U zRNb7CwISIN1NH431bwNeW=95gaOC+7{Gw1Fo~QebykJw-)(y5npM-dSLI(#swI5mz zNUb6isg%CFtOT9igJ#ZsHFYX5lQ;XgHFYv((M(r_h4olibep^YQl;;s*tnyK2#md@8ic{;jl_o`OIp>!@8fzTS{&jYFo!3OB86G{dk4eXK z*V91A&9y%I>(Xdoj5zT_?bXA`(5CW!(}s|j1GZ<&F{AySKP`b-EB~N)W`zM9bJbl^ zcqW6G-&)~JSRcrt(#gw3 z9|LvSLw%UFbu?blSUX(u*>qrt7FxE7wI}DNIudIZv>EU=kF=*ksX{VjJnsLCv#}+w zVMs;`u|l(TS13=KdS&Gk{2eGUaL`@$#;X^i@gkOlx;$+3_MBDu&njj%Nr~MGV^Q3N z?#7$OoANZ!{l^NN?;el*|GF7Q|LbOO${@ultl2 zNmf=%V;{PFfD$?wNyJs8lbmz%ed(zT_JCJ8OT>m`@Tq?=7`CxQ{U(Mb>dtvq&e#tx z0k`E?pdDdTUm?x!LY7~V=hzGWOuDiAIyb_tVC|=(dFx5!7Mbb+JSnWL{lHp>aOHYg#H*uo+^?Zq_xIe~i; zb_+rVpxXPv{J9?}!UR_>42x8ZWuo9uj{I-<1qDU@yKR;fD{3ww89{A2cN^2jLxG^l zLPlA?oW`7iyrHxY!>JQ4#M>t_pK~<&kE2ZM9%W`Fe$b1NFdHMTi1D?K^JWffB7c<3 zl%9zFPCNZUTV;l-=pj&ee$b%dN*mTM$xFC8T&ZwY{yO>P+`&BwUjmQr5l+ma?`nua z9j(xGTFtcQ5&hm@9OPu@&`BKGe|>uvd=%(c-2?llJ`+=tc*3$peSZ$ZD4P8UDNgAj zrz*v?!zSdpH8AvqGjWqX-Pi1d`WHmOq{D+>rRl6w66zlUPpbsoBhly)U?xVYTjBS9 z1&Qvl>NGLgtEa<8rtYgP7Z{>oY7T#09(kZTMRb}hn5&|afO%J~gSMbP;6WIW41FH& zZ9Oc^G*9cQfGN_Q4&<^WMSVgsA?`1+Mki6_WcMXC# z*ggmPjz$P6SJ}yWOhSVxzOJQ>D^~aT?B@}SGr%#wm-D$T)f3aKM}og2yxXQcT(Gkl$}IN0*UyE;b7Ex zu~TFNggJy=xe|8Anw4EFoEY9*c#Hcdp}qGXMX7KQEg z;~yF63GTTukG>KfBP`X;1qwTu=c@n3B+RmP;dem0MU_JiOi8;p-nZT|zE?(j0GS#s z7K7q0vHmZ40p;vpNSAAw1|&D9?!(8J;R;3inw>x+%bGtd8vIc|ox)nLth_d49) z^BhFzO7@mXIzgaM=!qt~816m^p>;BHX?DZ;pYGN2K6n;90?;12auEF23N7r1Mj`Z2=S8pzxPhHnaP(ncM>jM zat|t2WCo~cRy_4DedVU6Md^B)467C58$;sFV!rq{a2!@&$)s znu_da*TMeZ=mB2%mE;54X-0wAI?apJemAqPzsLoV0e83fZ)PsFe1@nUqF{M~>hYc3?{=}9FFR_c54@tjF-*JTR>D@Q6KYh? zOgL4G8WcV1atEV5E60OyBVur)cMC`UJ{1GxpKfl+S6&oCT*8S7NA|^Z_+8cu1gf+- z>Z3xt8~S`)#^;x^#~tvorQmzI#kfBwgcDid0*Z<5r#6oryMtn1IE^@i@<}GU#R4+u zk<`+=Q{y>#H5Ng(8lTdy4u(He35#wP+P>c^GL?#g8t8hlSVBo`M%}#4tNnb39tI0m zFtogLCu?l-K<@z3)WQu>@W&LsBc|o|)!xC?X@SxV=7oqzn1%NPkCo~1%G&@~`)7NH zON4MD?bAPT(6)sW*_axWX;~GAF!h*eF&IK zXWpP3e$oe>@iTI}=ZXoT(uG<-cKtky#J~e#*2#U586@P|YY?g6VAK4#588-}l9b@7DfQ zd;lcuKVRzS@a*}D^3yO4&|99&x#^P-y1)DFd`vuZR+<}jU{0VG2 z5ZVl*C9for{zdEn)qH@rXlKoVzhh#}@()Dx%ZX3oI*N0CgY)zGpZfT6*cmUc;vHo& zZgAwzB3S!%NAFI4FGG%+i&WF>QlH z_^UHp$v$cX!5XH=sF55pb9~66RBcc2ri~Ey8k~P?2~IiZESW26F$_r<$n0&_D1mJpg5S6`Il3 zKDe+gbac|fmw@+UiXC=n8Ce<9%JZZ`C zfBXDdhX9C&-jiuYeZFX#M%mnx`|hl&?i`ZQ*Y^yX@6mL761Z&@3XAMgmSjv>8cI7@ zJ#+*ClEx8j72tn^+?8v5>Ucc&kD1TF>94rquY&vi>L2>X8}g1`k^kgjz&#CWyL~0k zKQ12|z@7TkunwFzRr!+xK8|P2hAOio5Sosv0R#8lS~dxw2031ajbD@Oy;ek0_foZ7 zJk7)|+^aR~x1qABe)21YhMNJ~BQtqaz9~e$r2Wpl>IwEMjo@c$r5^B=O7;%LqzaAy zwq*C-gWQIw*AT)-ez_%c_>83lAC?D?T=^Cg&4W_LVh|H`ihF;LoJR1vPyY>P35=PP zTlC~!;@F(&3dkkM8azXVI_bQ`G2~*=K$O**@t>y#y$Bt#o@Z{=q$)IiV6!bc*$oud zBGK~bW%XopB(2bIR#$;4liB7?VGRP74mZeWh9X&8I+UH@7BPii2wIPeZ7W3zXqby&IYw1|foO*)ab{a3$|c+vhv56wn0n z0><4uH*UayYsNvVJ5d-EMu*w%;*Rwd7h8k@hf9oeS9}TPdR{6WymdNNd2!xYlReA& zenVGJSS*yXFrbhFPuiqjGEs@(pVw8-XsMW3Xb{z^ibmY7-Zliz+VmKBHLsTyr zw;lqmRx0F@k?ir3*Na|H;VCmr1G+yS5jCr!^+k+@Im)rycCF3l)t*wEL-AWYzD`Qz z6q9hAss4zYP7pvPv~Fz}iKQoudX$Bx*0sdX8FcH)kNk!dbq&mAo_MNpvpjTzWZ5{`jp+dM)gmq5Ds=k*W zV*L47g5$HDgP%p**m%it*(N>1ixu3kxOBs%+pK(hEMsb}N&}DxpLG7dAJ%Gy`P!*k zx7=bGiQTKccJ%&HVOl5K{jzS2(xL~H78~eHXElyeLd}4=khEpz5~K?c!ZL5HE$XJL zt%AAD>!6lNHhdHVRQ^d%_W&S>x5(1R1)oE#>4F*fx$wJpEQ@5*upuQyO4Jx3S(5ep z$uE~pLowvFQn^Ga%{4p#Z5hoJLgV_rHN@j+r%7KsTK?yGvqE%REEG_UZ=6PCAP>tn zfF3$}(~u&A_$DG&*Sv4|j=*$RvOq3Px3zCPPt~s8#KB>HF36P=CtJ3W9HoRBGW*IO z;U3fpA?lH|{laEIJh}qI8>Z_4lM9E9C}$R)&)fTy(}#7eaMR&5K(@ppVUs2aPhA$f zeP8L7=v|6;=k;*6r_?yE%vQkiFGx(??qf_fGOzaEUb6$qmuo=|6g87X8%F5A&8l8Y zeQ$clSF%bR70}VOU4%aHR6N5nLlY%*u3_W>znH9#n{BZR;SmGuhYXJ$m%?oek*1qcTeK)j$M7>CQ_&Q`o@h3ZaK0_ zMH@s10`(5F*zV2PM9VLDw(LSpeI2Zp&5@JZ!6l&8I1}hCEyd}ihgLg4waGS4yKj^} zwp>0?Y@~aDsnfQ8mgzaI_3?gh-uk6CLMd=#eWm6TT9#x^&C?7^4ZDzie=`I zHV|ltm~R=+bsi7ncAcNDOii6BoM-O_n@lh&Tt7e;G5EB7H#488WKy1ai3|*D4$2$I zTuq0H6ti2wKCfqj2MOJL9iQUBUj|E8E%dYlz1@9cSjXP79%dI7(v|xr&E1P*2`OK| zes}X*Tqqzz;K*#&K=bt6VfwO>+UBV3UPEq+Dmv%YVd~Cz$Vm-vCEJzLspCBq3qd?B zpDKwRgI-@MYKgrte;)WnKR-3&3UN&SB!Gg}UVZ(oIA ziYbNqMOv<8PH@cUJKKaJK8Ax7wCzBu?W%>}g4EyySesxnEP~K0hyALat@jFaW`FNN z7Pd%_UJa$~<063TB4(2#@){!V)Yy4qEO6Za=fK^Os#AUBr_-elrQbg)tDRV1w?JT66qSO>lF`qn{wa{T*&Va4@OH^;h$kj z^-cSac+4P%4kAY z;jq1jNP}nIK^{jhp$RNB@VFXzamV|G0n)L6j{NzfX>Me_FPZLX_p}+t9=R4Rj5uSX zGlky1&6JC%aeVqmEi=1&UpNU`+0d(wxK5)|mm<6gd=I`mv+Cq-SH4>?Xg&;xJL+9sZf10yZte`}pN-iIdIq~Ui^v%QQ&cRJ zeZHeKS74*$xaK!k(P+#66e5c07f66iciOItzX-nlbM%|ms zjl3d*GOXb}de)`F|{c4)2d@3~e>c9Qrt0 zk2{$5zk47S>-vIMnJdoiD63qgrtL5w%GED3-<_G%#b|%!d1HqyyBFmIl$ozmqRg>4 zTmU-&OM8vxy|_1d)RCYYBH5yCEr$J>7JXD1dT6oHNKXMlZ0Pz1`fYZ z#CtBs;zy7=c5Ld&+i+7E1A!V1O@h#jS&hXnbAt32iO_>s-8qp=`LFExRW!yE&H%IW zH9e%=REc99(;_OjrtM|s-Spjz-&qIy(T%Vk5TpTCBTlu%i%TllSTpay%Y5hX2JYRe zK4dA9*qRTD8ow@th*nFRzeS%`HwE6-ZwH>9bNX?Cs@Nxn4)SU~1IT_Q%~)s#Bra60 zirosJl1W&k0=Oy_VcU=N9@??UKl6=b8#wBj${)OpFME}Osf~JC@qaxd$E{2ez&kB5Sr)JOKn@b7xurns-aLKwp zdvAmUcCSd0ZThI^dnXe^=P;3Z{Gkj~fvTVM51vvZef(iDS^_Ee+>(>K`GW_diVe%0 zIcMzXY*UD@adJs(bkCXgAZvAX2cb+yRAJA}T19Rn>y7qDrp%gaZ z@$396YpKx@?$Q<2uo;^LA)Cim8s2#C!D2V|$;&&NQ!TFMp9i?xW74mTFZyAb9pcZA zviOuZZ_(0{lFZEcR29|L^{uTw3u$-5`{n<%J6z;EukX}H3I(aPt&IZX@%!*Ao>TXr zsY{K22a=#!lf}r^t@vIaXtUTP0k~0)j*6-KVGtl_h$McNS~e=LeEO@aA)7(DyfO|D z7hS9V;8{#Bi!kG&?e2LMiPMa_6T-W$ZmJ&r%$g8MUQY42dRV!RkgKV|NS|%*+c(+$ zg{$TICy^W0oybv3+etX$7ot!;zd4x=J&$gdnn*tyK=1{iXHWLzf4F1FeDpDxg|VQv z_LVr!f{v^1yplT!aD_!BDj+;Elvj#o{ciDX*m+0JA~@WqW^F&*hqT7iK8!d5uv9Wj zb2B6##L#e~AN(zzUW4Qy>9(Mzt@kj2l7hfn~m8b^SsL`TC9dcKNJ$+dr#;k-(dQG(Ek4`VjhkzSF2gZ zQfBIlf@D$4URuepIH&n6vLjZ31W|W|aO95Hbbv^c(}Dwo0Bt42Yi!uNhkNf_{;Ysc z{n6aNGqMH^O}}!ngG*$(R#PCa`lEfext9_6+av&ONK8F=#{fU^h5~@cVGi*^&gSh! zYL;8;wYhBD&gc7(>s&8V@Ye@Zrl3vQ#w=Ejt$2}E`+CPi_Nu)11?>~p6`Ez za}5(j$Km|)o3NsLc3U=7=T7%5jN@MEu1p!b{*po)pDX8II-rxSqS-zUZ&Un{DOJV( zVPPdYUCA^`avY%dC#M>WHlgrdVUP7JxeXJA-Th zg9=N-Nz!QV%yjqLT*y|2T=?bP&S4-T;P$v&7Q2s$KU68O*a1awpSk@x)u3?nvwd7W z_bgnVVGr#pl{Zh+A=`ApC6egAuyj-M>JW#@@eXN!+dE@Ku||$=|AT8jrRxPw>Kih< z6!22e5S9$Q=1RK?mM84J@>Gvm2)sHnlJwm3IueBNZZ8GL0lax_Z{U&o{CyHNlYh|C z?%H~)crP5+!cp3_l2=~TpVpTD67(mr*;M}3_5jHnkIkOW1ekc44&tf>a$w_j5)KgW zxT~Ydj(dRaF%5h`Slv@Fhgm6;x}f3{x5n=GPf}M&8#&(5)SJHhA(rvs$wl zs4~-fnLl1M`tJXu=`Ew8Y`^z!8UzGsq*ag(LApdrK)M^GyBRv9Qyf6LTWYAGTe_Q} zyN2%Ox$f`p|GZ(%V)5cy!@ACM@8kIFV=s*F8zyW$Rqw_^rw@AY*C%YG=WSt>>H1~7ST=MNbRhw=mecH(Rk*4SfJF&e{ zTg~YF{CaHPqoNm%hZgPN$;IP7lB@_-Tib#=g>WE4dlt@jqmGOpl=CzmTf1oE{RrAd zxZyFJvhfX@s-*1g;rC{5SK<(qnS*dCkj=YQPu$*IagJ#!7RCIZT;;cuAYiU4jDMgB zHdr-Puh)9PpeUE?YAYq(?4CjTDg!Y2ZBg;+3@{R!HLz}VV#HRrrnsh} znFeCm7PV$5tefgKNjFtzkp4$Mmh2M)@*~y7$G7M5BJ;gYrOX4#N!mca}fyG zEGDLd%17)357Hjf1$&AeoaN_r52j<82a-xrrF`QLgd5b_%?JgX%yzly-51*EZT;R< zT)fU}C?GCBPNUESgCtV?x&30>IaC+`fK#*jcn_GG5hdV_q%x~(&ZPc3zhOW4rjJPa z982s7YM|>H%j#a+ka_4>^0lV0%7A!UTMuDsaMxh6WFts2Zp+X5C^{lB>E1OI@HK<6B{DCDzM-3iGq!YadhNBWxNDG;j?n zA{^{#4yjyA>D|T1dR9CH_M;DZj&|n6HFZj(CP#t<6UFLtb!tKGxs7*p3ASI%-|!mJ zhvUu`6BD0}7_}!}c8$T8omZCIUl2~(bQ|F=6=~E`1J6*e_z!AhqJa=#ouOB5xqS}* zgjbE-mCG+>Pb&(CbNS%%9R5~gmb1rL3J6H0&Jn*HN+xLJCfA&2qET;+;r)&R9mtvv zjIEI3eZfvl@_VI(@gM*UqY1e$Jqk3IbuuvSEeV;R%{QP{yn~3MR4ZMJLhe*EJRNv1#W4$DzR})(0K*;!FqU1394S zASI2kDH#3kFl*#?(S4RYlYVvTJ#DgU3n>=~*0(UfSJKMk3IDR9C;C^kIaE1a++`MN z&K6Lcx8AIn@>Cd>Zk_%~trL4Vd~Gwyb9`EV$w$KW$Pp{BDkOciw)5}<9X|W~&adGE zHs06yPEV@4S^&5x zRS=BEEqi6wu=MPV`Oq`f-z^aa(|+#qiVUf2AMH&HxxEEl^xclWTzY7R9pxpfZEk1w z0hxOdpEFaQ9lD{u;p+2utzfTj8$nzhFi!>Mr9 zv^R>u$)8q|Ipi&ouuF;sVS&I7P%9+BsXxxW@J=j*d6t!BGb1hAeH!?c(g|5nk^H0DE3=d`;8?*FP7Jm0xw2sHT0t_)y94@Q>gXRjhCDOf z{(k<+@YuqG;_Ku^>Fpf@6tgsyDgj|}|B39e$^ANH3)`_vY;xt-us58SvXZ!vb<0l) zGxN&nEDpH9AnVV; zrW5Wvc+g+=<;du|*1hgFo6T@Tz+~863Yko>q1(C3Y~O z=Qe8=hDurn#TzC0f}+f?%htoEk?VkdgHOut)^>$s;~!PlJ+Ilu$$q z5(<7gYZ5zxc{LmfV6FPuW|5BHk0kHj2C*GFQt%^M#{5`Jq>c5&?FB(t z8Z%P%zqh>RZEwu5^jA6BO1mRSBx%WgeBrgYcv*bYs2P2$^+$ z1Yb8_V4?4)zsBsC+w~uFDE1?a}oA2p_vgm!GDm z?QO@&J_tzqkY}o-OPmZxFF@?>FbP2W(HMQEfOnNI@p3#A{gSoIv*^Y7>tUFX!RXCA z?uNCasH7EsflN#1T3hVt6zBKS_a9%67zbgKg94OO!OWw~+I`>AN)K=q`x;|Vgha6t1gk+{lDQf@2fkmqY z3PM?s7<5-qs>x%ee*HHNUS*HP^VM>~=KeBOq>Xj_dzP0rWXJNeHJQy~gVBeg!`1`G z6|+w$7%E=xO$8+8)?Aw zXXkKjAmoYIa$DgwYBo1lu%H{#vdXQwsDV9hmq9K7WCD0~f(W^QS^X^N${E;|ATfWV zRYH%fb97AU+vLU-S}hy9me!iaEy?xvvjtwBR!q)e2JN9i%Mxp_aB!NY*j8=%xHylbRXf(HMP*6|ILl~)NzUiNSV8_+?8n*yI6v)Wt4`|gXO zk^Q$Cfyg~UWjp%)Uw-9%GKy+202$trh3D7;W_^R@2ZrYNL{afnu+zu60rgUTvf~7t z%j_*5Et1Bfqj~FG-75$?GD9i9{9n{ShijTcZl(fTK84grAZ$a|kwVjJ_pVfT!yN-W zpv&~CdgguppW!MBN0vDw_u2H3M=CXmqp+{>JgOEoHZe|$F&6c4fA~P(- z(KdJvw~V3OgnAZ!b$l4SY!=<88FS>Wdt5=tAop|nhs^sZQw=Z;K8>SeN!g;v7OM6a zA`F%3m|=euB+vGAmvc4q=kpie%oH5GzvWu?+X6b}Aq;a)=Xrh&CZ*oV%W9W-D7ykCuHiu4*+=2rO0_bKJJ+OQ~Sv zYdi6`A@+{&ppE4?9%TngL3bZRd+l}~$!Y21=ZxYHWrF%o!C>?Wx%!{?q9I`P4-n?E zZIO0fUEzlS18Td&8C;+A8)OB8-24d0p~$ue6GISOtl5v)VyASkfS3C2x_G&E;$_<3 zfhJuD{U=8+`7K@q@4}i@2f`_-Bk8Tv_^b`7zs46mSmGts%_E^6a%g9<{??@pdv0X{ z#~-ZlrjXg%PqSc4!~a_zvHsuk2w_)i8y;P+h`>QP(`Ckmt_6ZosS zM$Us_B@$xR5pyM(VcFlv$AoEJ3%u#AaO6aYd*|XJ?wfzd(&&jT@MrtIf`0X8yvOCJ zHVwve*ELIn$iy3Ex|HHk&W#k|<@&yBM3+Q!mjMP>G3@~E@?Jr&h#_B^EfZNzZN?u= z5zF1`HcSIpGupGYI-22IKqf`B;6RM9k$oL*Ln{+Y1!h$H0fEkKoW=R(DE2RA7_d5~ z0sI&oZ=olHgI=+HbApuEzP@!A%GG^wO!#&!+~Qn;y2vh9A`6A?%k{b%DgKpl#Z>J6 z@7En)2%+8Hawd}S7*W?2ZDJMHmi zOw7gV?NvXiS_X7+m&19d3WL_KfXmUAy)(5}IAOgQD4XZT^LyYvtSHZo~h?` zaAGIdVuR}IOK>Qp8jp5~pJI?J4NuSQoSct~%4=Zkg-iiAEb&q+*#&PF!8$kA0{Xts z#&ya4qX1j^te8y9L5P5C(;i(QSXa#=Dc6|0Dg=TCx@vzw^f-$v0L5FF|J2K*VPOx@ zpiF-|F2^Y3LSUJjBotimW}ACypu6)NZdvyc(zQ=g>aoLwx&ev90@G71vLgLDcgTni;|&U}VJL70k7M>tEH2i_4{3#9d^V&PesZ!+GtKdF?A` z`i2-M#B|Nr_1S8A->xaSvmc?)i~JVp9@rt(Y;#IOK1NjFQ8=GJ@ryNvWvy|INDAousYKGi6{2?CP?z}{}TMA)NJAq zM?oYE{5E*zm<%U}CBWeChcff=KT~@J0@MSzL#$0-Wg%?m%DBFpDfCMhSllq2~0As!jLWbTZ5`lv;gZH8%W~I2+AoxQJQE4oecc zHQrye$N$)-@0xcY&VJ#h9W~(!=f(oL;wy3~i{qDTi`#rWVZx^aa;PS{OMpd*UY0Y& z#EfGt%*l3E+&ot*hJCiPTp#*ug%PTPWGAO>p;R=S81$L})4Av4@3W%0Xr2dF^XocQ1Y z)=X`+z}R#&kWcU|>bo{99{mB}=N9MPM$a;Ica5^Y0V5iSQscKn>^(-Zzri%77=2*Q z>zJW32KyHZ3|aid#eBXw+ZU#+L6}N>PjF1wClrr!D%~sj9HhMF{L2p5YU;#{f@ES+ zm}^(x1pK^aupr?*JW9Fj>A~8_pgf>cZ;%GWrAVrit79PD08o3;dB1$@((4&i#m$83yKzFB8yXZOIXvFE;DyW zoAIw~HgRf>`SI1qeKBxOuGqOhr8 z|CNdIwS)LK>SwZ$b$wuCj7m!c*A&{M$Ii!8K*#03RKXb;z4x!P{oFz@m?`{l=i3Y; z*%1(9n{H0B5XwK}sg*@N?V~2vNDi9A+NqT8=;R_w%ngE|;cX)Z7rYx>-mTmcW9r#` zGmCk=CA+2}|1h4T(Z>bcH)(qXfs|&~gt<#iyKj0IA1EWf0@jV$bQUSb*U!c^=`|NE2pxZt_*-v5YjJZ*Y&HBt!m8?o+mg2L}? z*%_LBSqn|(EI&dOcv3YpUT5sRO|V6sK!#@2o!Rl-Nll9$r?Z2L^B->YpB~$ms|6qW zkD7FG4mKpl(Y?gMiJa3NEo?0*Vf5cOk#ga5;# z%s#E`IvGUS=TrEjLu3j6=WnO z*Yh`<3YmQwZ#5)RSw4M>NPl~}y$2HIFdZ`x533rNu*UNGuOGhiC zPIQfKS$*bA5hWiPP8gDQGlT#a3M3UsE(jGaq!l$}L^^$mQFLkTd-Px1y7Rwr5_!5D zW0HKHWNMBzR)v5^&k=06#4dmVc6Ci)|~`3ZoX^CHznYn=wiUmHYK1pwD9pV{k1JD0RuH@L=HtO zJ}7*oZy&wAG)}lwBA}8IlNdT~ePLzlVeKtK9Y^`hBq_=ZzrBp;Ke8soS>N(4%2(zi zEL$v8DRVh~RI>FZ4?jQ6^gZ3%+taU9r(b<_op_I6wkVdM%21-rNM-Ef#fYQ{KDb~!L(vRTk` zjp?&Ye45&9QkIXn!{VvGCXkbc$g_=5zgm##Mz7zN`sD^h3*5KeuW1_G8LZmac(;Tw zSlmy~c%24{D`piqh#8NAO6!BPm-94<)!d4m!C4jSav_ zQR~NA2uMTHs-D-dbIY0vuMAGql=`TjPEP#pf8L(9Uda>iae-ZSu>=c;)_jJl+=W6@ zNxK-(5fL zQg+#Cl8;Ijv`loyh}6S=#Jw*gpJl%r@yYCM{BQ5k<=)<$|I^&vc~blL8rb&^+gu6i z5UNtbw`yRs%?&m_!CYE#>z{~pFha8>T)fd(rhxSLW?%jLupzeEa`feR+O z>mA#Op_$J;O0Lki0uO>bM{I7qCIRkrpP;k-z=|XOJ2iwr2@XH#gK9{uJs}OoI@7PxNvC1_s|53zJ2)i(nPQj zSD7*MhtEA(oKymGc5uO>r+%Fz`;jUetX%Lp zJgvNq?&4nXU-y-m>ld*8(d|$w7~7l(YIsjXkBQd(#p0`E98|k3J3|!xOPdP{KIFk<_%H}jeT@b=FS8-elnmpDxSII3Ea^LIe1oH zeE%?Lm+(FBBPVGHnt}+4Z64mps$Aj*!{$_}GT)X#$7~iT&SlpDRQ`}y>EpKAUhWjv z#wWlTGZBOKlJjRXQr$)GPBFY`3Lv&&t+AJlAHAb{SmPrYO6iBA{wKk@9yczl&W z7_Hd;P{NP~OcEu2#xr}Un96w6{0ZMl%r_1_31*Vyl-)qA4_th!HJR=Eh7ZYym?MC_ z^OjoiLxnvkH|g1uYV)N9!%c}b;^5mniVn@6LDCaqr4Ma3y02xX<4hk1KmQQ+^#2Wn zm`X%YDfD#O;t%poh?ggTO-pNBYjqN~%o|ipAzp|;FE_#zv7<0~i08mqM0@mreX}@i z&CnWrfae9xfw_Lm5#+*V^i%{w&=O3`1fq6Q9xy|ED%T_HKc^8HI~7Q41LY{1aQsaS zlJ3LOu`%7-^I=O*eHn$O_y%f@wwWdklYd-|_`$LUzbMDNy-I8-)@)|96&NB;zppHR zpg4U+2P*gGZ7oRhkYle}FlkjU?-d){a){}wxD!>+*iHabTz+3UboySDuvJuAvjn8} z)Gx~orH(lNG6T{L{dF?Tv`eqjvlu3%&%oQmDQ66X2Q#Ib_n{(3L>nxKby=}q%Zhx{ zVX{ylO0sXZUsiGm-_@2CQ@2c}CkJLt`1f|)HZgi%^3D`w&6UiS-&Jbm0e#uMe&z6J zJZIBt@G{=5yvl00EuE6bmbuG4j0#tou^ zP~u(WQ}vlRao8FU_SAub`Pr~7;m6t4S%l;KaA#Nhr2S6)DQLYR?lT}tpySP=rBd#o z>Gxzbjo#LZxm~{k+QPgz@d4v$34wkrZxBZ*O#5;&kZLLo!v^`ADx*lOvX;bv{9h7l zQj)NrK54KuirJr+QH(-0F$QGOg;+KSbVRA;cm8!0nI(BJD%shR(F!9%=uo?gP?SdL zrUF%W%3E=ER_E)(n!SS8$1Tvu-&X{Fd)vP)wMw@iA;Vu5@GZGtD--A2#<-5x7ud!m z&_P|C=RT`IrF5BQ{o(SnFGn1urKNnLHv-qxED!t^svNbSBcI5L6>+k*2XZW|WP9GZ zu^iy)oIH#kmzDQ?rF4KWl2b6fMl*v`gM<{VlhM^>w36i{`BlV?;90u#_v~fv5Cb&h zy75Dt8EsY!o5S6**GUm_>>)?fxM37uwdqA`O$9!DVBNzQqz5muxu5*2n2f!yNCVBN4wxetS)!nAHF}DPMl~LD(1W!>#rWtuW>{oB{sDP-#c$p-p_A-Gw zerod0As~tK3{AczI>OsDa!S+i-%v{UYpn9$EqUMmw-N}q2ux8EL1kUXEGaO9MZ>~r z{WDrnvNt1_sG}!cP;!Cm3H^rj%`nqIpzQB-@aK>jRAXHANDPb6bg=CeqGu|Y;_vA7 zu=$_dtTy~h`1bOWl@jq6EAC*6 z^Hk+MEQ2hUbDwfxq$W-5Z3gJvhpT@IzJ&hWV8)jCIsjUlI^r+%^kdA;ze!+dA7QC& zA}{8tIDWSltQOK^k+5a)w?=4J;Yy*3@@S^-b;Z>^1H%U*O5Hp&w=m|>WGVyg@xNBJ zNElVxlMi2E6{{?AYs=!#bKXrK0YBsNekX~NT(BpFOVO_^`^o-E?Dp%mSl0pvZ58CR zPz@2^56QTTDfUvn0Ci{PfO>7Fo-{mL;3HDa`e)@9YU76#3eWDJTR3jm zvU5z)Ep`N?))_Kk;Rq~@r^7gjNweeaE~I&DS^gL%h(a|~Vw_`TE^3tjoq67)!hc~; zIc1{$Iqh{0|hDdwRCxx(9E#{Fry8`%j+OJCpYqMr=p z*W3fRY>s|MuNMmY`pKpD9}h51iWH8Jpt|NbZlCsN%jk}iZ^SHV)az*FO=F=^J~GNUN8y7XTX>lk$pt3PmMBv-K01!cS8HRIxI9@ z$ciqnrMf;~25~R?%Pvj!X0us4LQ(s}`}>0B6XM!5p2U}u@Os;y=-7eldjGT-Xf#-( zbrAD3zSzv~F&Cf={@;qPFr8OGD7oVhmza!7syux_6>HubVPW1&{7mINU`-mzkNRk& z5lY9}f|-7gk8r7+N}FpXw?Bw<6A6c}EKUl&od!d7NQmKG8@>A^Czxix1U(hh*=Z6? z#kG=00dPv<71qfIM|pcIp0J?tChk_kP7Te3#)+a9zkHP~MvISHqh3aR)fKRoMf8Q< z6-SO^1w@I81wzJ5>_Yuxr(r|q^Y46ILfZ;w3Ry0kiKgZB$#sp;KK_+gOHlu*ZaZ%s znKtd#H-Rw1Q-V?KFrj$nu8ml8mwqnK&XjeC1!tvy7~yG=)H|o)kN4kd4QZNJNjTPr zl1_V~+Mno6jFm)%Nc3};-MpV4QKF)vsGHKxh-^kr^GA6yM z9QPGur4sG?uZdSZ*0^7MfUD^D!(IIKx_Bi?^^-yGielCqq*uzf`f*-2I z&L|s6nFY^>T^kIM$3<1#k%=PKG}20i9fI^$({b>j-L+1x9;_Gu6d=YNQpDX;QYs; z)s=g1p@vp6Kq2r&3+^j>?t35vw9HpgO3DO6^n_|CI~9#zt7ObLnrCiaMp1rV6fd@|O+a=Vt#auJpU*B2vv!dbv(F}l=HhNVM2L%W7ZS${$4yoaFN$|;x**OVi^BKP zc6`eNyYJ($ARN4ejgI2QwMjL;yV3;feROASHr_B>$f|AJ*!{;YvgqDTyE5_?_ZPnq zg%g7zK#sHYF&;f?^n0J1esptB4&Rbg3MML@Zzh(+AM^Ozsv@6*WWQpPG%#4Ts*Mxp!z%h^i?~0Xm zOQ5~N+nt$C*b0cZ7-3lRMRM_qWf&kxd=JkZ_THQl+SyX>`f)_{OPwL&K73SB6HK2W zloW$>EON6i==fyzi)jFlyA$_>%i#nljJLCa#BXcg*ll2}uTLx%CQ6aDQnzGU5MDxC zaAtKVvdEEmDCocr+Ci(PiqMAH|2Q(i!l4 zYVV}Hw{v9AXZ$?OC_$$}gWCdeAcW#RBg~H9KSJt$R#{NN6s?y-*`q{{_6_9o~X+*NsMPQ^i6STY|vI|urV2%Dcn;14Z)|%4GaEVi(%~;5RNqKyuQO!og8+qd5bI%Nb z#tJLgqp%fajqdRC-dHPbCdtlQ*BUI5;70o!L)@V7a}5rmU1uSeZLd>1tqSx?_`4h?))pP1-~GOBT{5ElfYi-UruU+K>t>8htT z^M`&y)$(ulEYehz8CTZFB{Ni$q)Fcbz?=o>>eaO>bGS3vLy6hS-JhY`+N?3y7-G8A z08eiEvGUyF@q#SgXhwUzPo3Yg{cg$83^hATOVuv7x7G8<&8e_vXQEZs)vM#pGhjvi zMb@i|nKaT6;K^xZ?Q=dtIWWWSuYW(EQOnxL9j`xow6}{j!>yagnm)gfZcfR8j=H_J z3*64VR&nJ-j#SQ3tT*_i*01K>&ZD9gU*6{WTx1>-P|a9`i_t4e$*9QY25=kUDIqQN z1rl_8T4TYe8NPK;ym@)L*P+@?dFvQJJdXYBaQ8Cyw0xJZ`hRucui*dHfnEjojR@Ty zYScgFAO$en13DdCqs3G(uBo6C_vbV>V<%<=r<;QWBH8o15dPQ()v}&hz@K-)asimW zBXkO4kZMgMp3B^dyr>G}x#=22K7PX{@x64Ssf?DsajZD-w^PTo^&mcVAPqa*!nw3> zk+80>ieaSiBg^yoWt4D|;9AOW6XtvlDV` z`Lj;+sIpXFwcrfe(g}imck1aW+?OhQY}YPce_xT)@#4)YakSQ*I4c3UB|sh+3p)H5 zZCs%(M9_^4WF2=9lIO95c&UBPVdSMu&G)8Bn_eHy@Ne9!!XR8n-3N?Cg*EVzRvWovQYjAeW$}Jf=gTy@<>sgCRD>ABI})3@fMnJc9%)S(Tr61j`-+#aj(_JHUn-^yKun=Ur3L zF&SS6crsz@HR?f{em5H9P%b>k)gr>g%Q$~C7fLnw+3`_%noCfBJ+8U(t$zxaMX$D= zUW<)Cg}`HTCjCP&u7-1~;_bdIiPntVd*?APbFKs2%?TuEeIpTt^vPX>`w;rE!^&Kf z;6oV);e!HwIamjHa2(@AiY_jf-_5fF@aM3PvpeF-ZKE5~)S+0x2c$CIEcW7u%yGgT9s=~W9%NiOAjtprG!6=k6HdbBi_LBKUBkRNW*#3?P^ie;QwezT@J5+7L z5kuwVafNk3Q()=wnRO*i*JvJp>-bZdyFOEGs?_W(X|WY{4@IPx70sV8XBQIJ%VC^M zST93xBkz=@JNnr7yd*O3W6c3$rXJP&Ve-%Xz2zw%{OKPwf<2`>;&GV>P!HV%}K&RSle>Q z+433_Y80$vB(jNT6aQnR`nR||xI0q~JL$6Gm&*UlPgfSP8lyN_F+pr;3T%sl_q_X3 z@MuD2S8JWmm6Q(g>yUEE^_VHoB2e+B7Js2NSxI#^0Wwr!#cb%1gGabG5FD#ax`6YL zc8<6+W2n>VXB}}pMBei9HcfZ6UR%Gl`!{bW|9L3xwc#z?MacKUNlIGU%7-<~^NvFn zn(}f3;=trjxIFp$^fXsp@1$as|1tT>Wr>+MyLY!|;_qT^DI z{n6giIxqBkY*=DyY2e+ezKy5vL-mnc*v})opan(beD!mN)Yhs>Gw;BKCn3>bYU$gF zkH@!^(%F8Vw%vA1FP^?QBL?^LgWRRG+Mr0NMQ(t)(W{1dRL%~@wKqlqy!M>WVNc7| zSnd2_^?SQXS2`aTnqmZ4oHEnJ+O@kH{z#nuZ{d@~uh{?AC;wJ9F=oTCvHd+Mm!JMt z;2s3c@&T;`XjsTJtL6*EyJKe-B$`?p$Ce37%4vZ@YEm9h8dyhSm#QBSYf{13P4W5P z+*k#(X+Ip(Ud;o+z5|FLa5>ekNd8va`683?`ayxd!s4Qrm14cEeyP(^#(PwjW36Lg zt}I7oD_Bs{O@{k=cjpv<)8Jm=i!N0i0iOT|A8K&W_&lZ_ z>C=<4o)2!RGg$^|ODVTM0JD~ucCFqTeEQvwrC;*l#_K%MIv2MP{kQaWo(k~ZuebpX zl)hUU!?i98k#uAtL)c-_0HdIh7xu7d-+#(SHZEfu7<79rN96Z{81ngvkMR1{ncw;W z`|?^pxxk4JTz`^%%fs)&bLF?D z`B;o^%vRT#26Kn*$f%E-RwFxSt*gFP>>wwG?th{{Sk{xj5Yxeo27MpR$}&1#je(pm zP$I+;)V(jIsPpS23fj0d0@Z{1OR-qak*Ebr(BlcBq zr*(U0PlqX_asnZb0_`cFZw2!t6aXZ)g+KDX>>XMbu~z%Jcy;^Kp;L4t#^62tUddhb zVE{%ZF80tYP~V}1aPBaoVU-|=T)1F0|z|| zcvxh4z4~0A{<|_^7+YvwaXjhr-HkXH52@!iVk;+3KRPFdDN%wJD`y} zhkeA%9QjE|eY5#Tom0Gk?=$~Vex;x%D zqL3nP4od#pxE3VYZ6C}NVaIbonSy>1rh5v&1O05!x&IfgJgebL;_oG3L#B2hj{eAlv_LEz-4~l94jhd zWtdTL;q#PP?zA9Tl{wo3o$?`W@2-r0jzt_xj1_2bAcPn&FuObNSfd`=BidP6{(6-# z51)ma*D$aUdr`pu=frq+GhCup8dehC{ZM+Tcc%dI*X|CeVi)no4pZ9QGH0>?mr{KTBqTt zau_z4&f@YmUipUgJ#X>tZ1+8S zw`Gy-q~urtS^hoLe`J%B*B&>`I{$9Mgj_&RR zuWbKZj$=ZqY)tKSgrS>vi?#0BvM$W_PX&>VWvv|;YBoN)R7%sh$^B)^Zi0)bF&#Fd z;-K|Wcg>5*Nx*x;#I3lgIrj@(w=jZPFI7Mdnq!yC2JgNhXl1%u1>3Jv;cEo3dZvjN zh}G(3{B|ZTpY0l01*o;NVZ;QzjebxCs#)6WYgl-;ZNV*{PI;g?uM%fpS9&Z2IxYt^ zh;O$j~+2N*Z`TQQQ|4y^^@bbszTT5+YsYO{OS%2B@Xj83hV=#g7qW z0dB8Z7FtZmi!`6M6LCpEp+&a;%Is--u4HuO3p*vwprgN%d(kCnKQ-$<9;CIh%~^W> zhA-Go`=_~fTw)}$3zqWALca{T%jgdqppYOu;N#k!WZQ2JIJ!nQPTO=3+L^W^w)oS) z355DbZ)|BkLFQ(^ym=OIEyTUeCO#eJ@v=goBWD?2?qtAr19VXmlE#Y#y9z^K25>St z>FJzG*duP2x9!_KYUk=R9R6Qf5&KuX<(@ohufVp}ZbTsmw%nOM$&NAmA`_b^+E7*L zOf;)>`n%(KZFi)F0LxzlKjvY5_6e$=Q5VF3@PY46GGQrv;Yk5lD1~-BozXA6f;;(f zp{-H}Xb;%y%gli)<*NS^JjF_gD+Z#|oL<|!7=dfmEn;tc>@n96PlESv`R(;>{NIp9 zYVibz4`qoMT}+;YV-!;C`ir{`Pfj!;24146?pDtvc(dicfeU-Q*#;J_mqwQqc>bAy zBE5X|-HF%8hOmu546uqMw+s9uoX&10tm`KZ7k}qL1q6dEsKm7#gvYBXOIjqzse3C> zU+SI5zi)+8)$kl4D1A zLi2ybUtZ3C#Gh%x)pjch?l@tPY{^RR@iY{3C@$O#@D|Di&)Uy{o_ z^Y=5>)_<(6wKge&ojjFfA^o4oL8G&mDs#6Alp0`*(i&_}bHxB)L@&dsvlMP|e$QGPZ-k7-L(llx9ycvcFwMv3W!4m?^69 z%JQxq*Pk<#_ulS!sFym8bKU9Yjc)_R%UF}D9+4SZ0DGe<#rgLgf?eBOUnZ35|3d=@ zi-`M=uYPVTk7_>1V97kmXu=5)XtUxX3kZFL9l4skDW(81Z+A>lqN6p-Ai4ctHQjtQ zH;zn?hWw_})F!li;tS zj)MoGOs;0evLUG&+WQ5;03OfQm@3sfYxzxb@v?uOEb1a@oTaMUv%kXF_y~=&%Nq5K zn3Eke(qOXLc~bz0uo`|>_Hhnb(@_iOf7~mc1_8Z4t>Xrc5+lxL3Lst;Vqx%m@($9$ zQ}{0@F%=B@G6aI3Gl*(+&`6`VjcjvFkwMN_##ankgm`5K>h|3lsp17ZUL_MmIy@u^ ziROTX-KJ}2GFiYzB#kNMdThV4k0rt_7z3#ecMiS8`T(3W8+MzN#5)x~2rt)s93(3a zJ*YNt#owQd$6->9hcUd%w_DWNN*|GxH2*qL{Vy{o7KlGWo)2xbBH3A4S6W9w$3zRm z?8BQ4z{OIPcn2!2VHU$tr=GMI6zNvlNVd)BH%a1S0bqPgx(=02 zKv;pmiMP-CYF0EwjiRZ-#qhW)1FUy|_il;#*V$U$W`R}3OYb>Le#Z*!i+2V5Nr4$aU(Hv z^juo~>0E5}%?~EG9%ru4Ta3eKQITjg{Nh~ha2p(-9TUf--2p!+we&{SRF<_@8xzm37U{wjajP7 z$-BOc>d96V_-W3r%=ql!v15W^^V~M%)-e#T43^K11+E`?aq({SYV?4h&Qn#6=b~lf z=&N=HNu}Al5TQ}U;SM{cFxuKqEr#qFn{YF%k0lU8UX6@xM@O8ewZm}m-a|lrtE;qD^BTMwa*Sz)_#K2lm9YTtN}g-)Ci)$WCtKT2B4;rw zG_bMp9t+Dsgp+Ns^?asRoFkDs_MM zDBcZu&^v;ATsp1m?AD0B_5g{pyH5(2lUJ0RtURkL|2zkG5??mi`FU^5pw9zn;)=Lu z(<2s^zU2{4ceLGRoq?-D6rHo{q+6Js@IPwBGC%|m1Pq$T{ED@jtQ($Qx?WpWes=lj z5*-`s{D7-LiVYVzt@JH`RV;Pt9ZoAvelh$kT*D+y$Wt zw$&W$nIMgC)Cgg(8L5Gh~c)ul~G&ga=fvYWMa{?gKw(cT`zfQvHT zNEz5Wen$G|3|*P)WPBd4TEGBmH-#*hjqX{e3k}6czhc#e54QTUFTAqK5u85zvht33 zrs8zq3kify62XeMc(m*Xp=-jDguLx7o2s{<;$H)@YjH~C<1Hx^OOhQR8%L^{qD~}# z0xHTgV%j+D|G+EX@ZXes*biOqK%SlJpS6Z&#=BH00b9I+ViJsDvOJK_=# zd+T%0Qs;k}bq4#}y|*V8-9;Vuu(FDN1tJHX1GJDInzA3R@kkzQ)HlgSLxxjU${r>F zSwTeM2tP>>#t=fIKs9N5@uqc?%Ef*qZ-hE+9HCWP>{AzRqp&W*6LMw`HUSO>K&BKH zkOhdzFoV~0+Lfa!pd!+F#2Ou0mCDh{v+ta~G-|p7nF@;vS^Ld@7K`NS%V#Y2=*S*i z8DrHVu{GJp@rk4sAVVCREROh6Irubk&^n8kPK?{yA0fJDX(x-L z*WXP6#|7_V1Dw1|nZfU^kINj0Aj*yKd=zPZQT?AaZs>CU#hPSX{?d}!6^0lQ#i@j0vuW6IgQ>Zb zv`R0C;=BhgpM(D*bbL{(7u7Z4zE<(A%2$PN8b!^W_;suFbrVx_3$L(Y`L!E4F3x&r zFg>eRb&(?mv=Rj&tR}nO)qqEX)gCuxk~BpNPe-ZMm>lblhf&ExsaN8doI5p4jz<@4 z6FdERzdk(SNMoS^_Vs5&`zfEsk&X_dEgxZ*9hq8^NugO%6CKfE)U$s{M|!I5pHonJVKf97zj{b={z1@W6^@6hIf0HL-`Cws3qSJvvGH0M9oPc-RB#fQ<0 z40MBFE05S26E0!X4+WkPu|tpo8x`kD2^j~ZpIt?j#rj`(@7-cyU@GlYfH5 zbp)A10+B$orkGYgGZ1ECFmSJUqQ$%cwiQr)mCMP11I}Pbp67F$xC%Yr{X>}eA6Q{= z+Ft@S3^74UEtF_o0i}pD=ztb;QE@*uL@d=v3Sk8eWv|8QFh%lPj z;40mcG~~d<0lQoic8A5?*TQ}n=4d|SH18zlDdAqI$w_NPfLrtqN?&NEjY2DsGGK zrgeH`Y$cjIERd=`eV33V^&PqW>|?n9W1qOzTRQp&y6~Q-Cw*xaz1Ffkm(FGjVe=PD zP?*wvRE>9(O8a>j@$0zozQfXM5uR`2qVH=~>{HsAv3>`kpmE!SPG=9);O(p1W8v0C zr&mVa5!&@k){OfbeG)7i)~G!K$g+CXyyLH`1u*=gDJxC^N8IB&8u>xmueS^7yU#`^ zg0ew09*H zy&`uc)EKAqrJM-P{`~E3`cJI6+}1w?JW}8=EU4y57teIztoFrqu!wha$JK9fzgtN* zFqYOR$KQtJXKYab8w?j%c^(_9%Bnw&8Jx1O;+Xn;7m8>#er4F6g(V0UkRHMI50XyU z`5UWe`c5eNWqQM{lV523g!Jeu%DbaqQSK9@dw0^?v)+62kMSiXlx%;7W` zX1ZR!d-k!07|UH!C}d93%M$WXjXbY!%bMp%2u&evZuRsKVW#Rzlgk_|1&VfE|GMsIKKzI=X^5@$nlfJz+4J zkRGWS1#Qx1?S^@`ArH^`?CkcmhmJBUeoN#PI`;D$j5!bzoEU%W=;?~yxN2H}QR?U8i6E>B)$!qP9=?%4)?--t6;T!f*I zB5_ z0e?0Ok{GE?Ld?l z&!UHW?SC%Vl*lACURixCUIIO#S$%=nsKg=Lh~*$lEuQO_4(?VBRyO#xeZ=P&_4jKN zZ#S%F#?c7H$wYe`sS$gAT!4A!;#cyO+q&$-(fi~mte8U2;}jl+9~9sd%wmY%gDfe$uszZaBv zzT<0i#ZTk!Kit3d?rTw1N?Uc#fHVEN;9g}aJ>t*u3EDt4*1o`VwGPUp%D_Z^c2ZHRIK=c&`tf7h2&xSqOvLn=21*zX#d2 z|2hO+9N6989ZX--)MWAb({?I6vFQ6v!-y^n0uuh9SjD)PUX4w&SF+%3@!d=A&OrBO zsVA0>&OO$G|15GA?_K?$0)N0L6wCWcFzVC?`0o4D{!_k(PG)lbbsyjCA4skuBr$*0 zd|Nb8Us!PkRrIl@?dQx#D;W;aMuRu+Od>okYaNRBkRHB#4u?rjbD2 zq;me}%9-mLi^*tuO1_>mtzyHMrJmWcu}tsR zq~rZ?3>W)k+Ix@(+bWyOswXrNQes9gIgn1U5ZC~l@G@Cw9vRo|9%HMUm>Aa%-uH5I z@H>pI;Vv*Q9jQ{Kai@#4z9}Lo=uaKbHH}?b#oqMt$=%Klx#*B3BJ-V z*5CMJ<{+*)UHex3AM>gzNwCW9F8+qT7&|o(^&FNDQ^fyst~QCrRfF#G6dgL2-82th zT4=v`3wZd<6kzS<)^jrJ{F)S~y|8kF<<7vw+Ot-lbFwwNfFR}8cw+e9O&x66)+DhBW656)$tGLZXUSm1pSBtV*0pI*&}cPSR6XI z08uw|uq~iprh5FYIEf8lPR%JSrLQ&aCJ~zjN&+SO&v9rIHak1S43bh=PiZ zni|JUGD~5Mq^%rNX_0S(R$(YHA$v!KU{rw5bn~Z@?)(R4;#Ux7rfb7dhdh1aC3+rJ z#^K5bl9r6Bc`#}wxQ`Z9dNy2)B=5Tfy5z#dH^z0O-IVcfgV5@%-n*X93Y|@X)m(Yc zl|7eJ*6Va-NnV&od%vz%TV8rvxqd{k&x*GagHq;jX^`{w3%D$1LsW7`Rb@NVBe6La z#^EQ%-UlZ1vcm-BkOVM2;0dvD=l8X8tDP{K;hybx?HK|Echpa(OYs#kpid>)LNIeh zQUmALM}?Mh-C{P)nV0lxkQ5hgCeJE`>hB4xe4B_u)$&Po0>tGf5!n#BBvk-~sg;`} zir&*&m4Lj2EjY14vR6FLmP7codiBmxS#}*-O2Q==`Gd(Z4!f65lbgt=*g&V3y}e5> zwU>6^+y#BoT8eqODQ{u8)lZ%ap~NNHm5<0zbJ7})8Mv-gW+I3ja-34p<((GBYw7q| z_p6uoIW*`5v-kq~xGEla_j$aEbK1IMRIioo;BpBXC%D>>!@%z}QHs<*L^=UI*LHJ# z#ezxIO^hyjL^%vxflWPFF-I|m#r4fI;z9xB4g99o{^1zvyUgD2jvQv z9^8n6Ic^=98uKpnVc@33;nG-D-vimGA{V@hZZJtK1|XKw92F%Xma1#~d5M_G8?N87 zkk@W!h`rWfHh6qH7_oR}A?SK3Py6u6<6wRRKdU?AnNFr)>Nu^NwHdL@Kkm&v@J9Vu zQ!l*7SA^vS4Yu^E^KsN})(5;bVP)sI*U)I*`RpBd!!_FZ=vZD!$Ncu_+dC|ky2o9o zH%Y|*ganYSm8*qu7NfAjb4&aE9WjCw%={4rTXtjTyHl}R`?(6C+4N0b_%ZRS&c{cK z#VR*a4mMr!QI}-4ZZtw5!>z&p;|MgTJ52_t(I+VUm$@i>|9<`TwlQu-Hhy2USosr` zkr!cK(Vl!4MFM$hY&ij*lHkU6ah%y)iqUVcRBS_d^l8&=@=;G7*N}LVD{=Y|SecPZ z*lGD4L*yN~X>Fg5;>Ujt6N{z%7@5q8|2G#_MQDp4FnfUwaDN->q>l z*JAQV!94KpG?Nu?S?#V-k=uM@0=_R@{YO}oVO78W<&y?dhQ*uAG=-AzM;g;a#_@Cw zYr0_VvBnL43pxhU?ET>4Pq`ms+u%tNW=k0#JDn&lYKS||G;zS%J3vq8!5CE-0AaZz z)k}!7&Bqtxs_9Vwl(Lua zes!r)evZGo#L9(J_hty>VQ96h?#P%{`{{Ev;rU&rHaF6O{+BJN6a*P?#aqkaIK!XT zh3~*GO$ZJS=5gAeHpld>TPoy$NO71gt6F7M3kuD0on^>f-L&=nOm&Sgf2B6gjkMGU zi1Jdtp%$=8aRi~M+Pfmt%c&4d!&cv_#_!gi7)4?rm@rl|89RV)_Z=y{-NCuZ5qTwU zHuO4@`VMqDhTo0JFJrG}X_i)1E5M`y1aUbze~MS#4>R|f%i0Z?km+P|8^?~wmx842e$b_9OCK!!OqFO75Yn5( zl?g^3h#1jCQ7bsGflSoRcFp4!8~}g+^7y;?JHiYD&JsMf#c5-J4w=_1dh1AGvRC}k z3`PnAg{WJ&M4XvS-}126#AQCe>)n2zlC74TH)FGoVI9&IzT8;J;RE`E|CJiN`K*t2 z)JkRSK&G?tt5}65SFFCFi|Y>m$M5Y=vfW!Y@uqD~546JxoVj-& zjG$TN+oOQ(UoZf!F`3pGlORL5HR>8Y>+Ciruc;@9fh+g416) zfxC*)4@notXZ>T(lGb3BkDT>WS(#xS!2&jV{}wFJr&8qHUSbT^(XjK zp*fedVT&bWZH7B;vt#9H;;m%@xXUC6rOT!E?!|8DLhD;{X)`Wq>cn&=tfR*12O@#C zi=pEEvT}<#!9K%dPO76H#^gdo*SErBtdwB+Lby>LUyc_-uVxOC6`zvLu9CUCt!irT z%=@20a(=EvLoQfO*3+2PwAIh_q9TR#L&bO7L^TaZWW(AP@amc5^D>#P<} zE0G`32YThMX5%C~i0Q%1P5!R5#LZgGk4BJptbcS*3Vi&%04)(~M zszSwcXK9CZlbA)~;ar9$v-&a70(Vxk?++#9{Jsm@*N)w_KBGnJmvsEDx7i&@Owr8$ z{+OVt1zTuHj4TRCOKDYkM~18ZbsmkHD^03}dvt{Fm>GkRzVHV0PqU3CM%h!A#Qr`0 zhp@d+Wz;-xnXqhyw!6EV?0Za}1cgI3@Jd+pJz=;`3Rx<2b=Ym}>_g~yWd$8%Y_{p; zlMK(Kz{_e(#j(qTKyP-!Wgb!^8x(skDR4|yZ)JF5J&Fx~H2Dvhd={JEnU}>-l7l-6 zxq3&h!hWrbK#+BsT{%lnP>M*D-q_wn?i}|b%O^kNMWR%?sUw@OB3=gHKMXI$T(fz5 z1nuBrjn@H;xx3hfZI!1k4IF);1{R6|EI?4aVr@rjI#HYYAHKFXLdamggk}`gOsyJ? zOcExQad{JnkQGSUrYA3kU9;K?o@7{L!q9BMgx0K{SiFkj0BL?wHk)fR2L6$4w@_AV zBQ>FR@mY6ftS-WI>CtGx!Bf4WzMXcG3!PhMBNrO?ST4F=^N~`Xd?b{M-BW!o{okh^ z9JkwMbM3MR^Jb?)^Cb6)?42@UD)xROh)aDlq?Q6Imvy5S-D+<`kpNFb-SmgFflUuC7kPj ztcNHc>x%0UNk=g>nRu$kM?TI_K_KUi({RLm*ZXK?rtbsO%#}vr#nDU7JycMh00O<9 zrtMv~P40q#Km~Y)_3a~g+Yb@^TPt#A=oEOG=y)_38#*6S7V(?GOK(wRp@Uy{hNfA_ zGUUxU1MSQ1)rC9eztUOS)kma--dRchzVsbvbRo+i$iHGkhzOa^7Uz5@~o3b%3p-+=%a?8<6wg`Syuqn zQ=Ztn27*Bk^QZ#{#10GHZh|3g8&31JdQQ`lczSJ2pEbr@{(+fKEmiBqlB5sf(3k5{ z7)Z@z86J&I=5x*JehMf67(DE1Z_aPBr|U&;nXrt!W1&j1P*$uCN$&_g>V{kzN;{&S zg2g%lMgbC3bL-e^U0mkTBTPHBgP#cs5+myQ0s0~FaQhcbkK(P{E|<o>-(0Am zc7^Q3hh*&>W9X^P6Z$#nGmWFJ_-obKc=U(`{G2XYeQqT zooG^h+jR)Lm!zX2zjJdhQmvkeJllak;K})i*`D7)@ma3|K!aaRe;j(yAYh=YRH#?A zMle+Vl>r+Jg(1KNI|jH@Oc?Y zJQ`&=Ju^*6bR=euDXV{&Tw0+sE9@&z??WcH)~g)GjWDr9r>+s~W?2g-XrG&2dEMwn z;Efg-f?Z9*AoGl;uYX6Fj^^{fMT%NyUY&1B$czz5b#So+altc&50u0N&p}Ws2Y4in z?1agKe^j@mD3MeOa|Kn?TcA=73yq&c$X*P7PKW8qr@doy(F$WgM{+=w&VkIBWrD6> zQl|U=c>yG8IXY1qNlodIxkb+_jkgM~Blz=kXT78W%k>t2D|A^{|+X+kXcd(Gwyj-o(~%Qt>ka(QRKh3rmDm zY{-6b%a6GDlQK0%7fqj)X+t9nU|APug?Uf^M%bMLDfm0yEgW>@3RCub>UQVO=#nth zLAg%Y8)w^ZR#sO2D>VY1WVM~>kGgCwCuQ3@X!&u+=I$#V0Bb5!6tGEt=81{BSCL4( zSGX?0!B_){9p_Lk8Y?>|mO#?p#45Hj2t2U(xUvIYM@M@1IlA^i1<}>nJC$p&n@e#E zAb_OXJ?2Gv&=ziYGSCPrUsmU1p;$pNY84W@xSuo>x}o{2OpqcRWOq`?^DrAfnAtTX zI69RC`fh*OK8MH{zK8hB1P|oDk}(ll^{U{loXN2U^3nfF3LO2T&KQ($L-T8aUZIvrAo6Ai++Cdx zz<3ut0*=Ixld7bkL;3lc>d^~ja!Bc*`sK;2@VnR+NOpoy`+|gB<(MH#DN#Y%!6if; z^Vwm)1f*1t#<>+^7V6pkP>L zF$~Vl!D?nJ#s%ugkvw)()9<$uQs~E^zg=x|x^-#&`Un1MK5D&DdCoa~O z9%Wsx|F-Uvv>tm!E4?;Q+wW+Wd`~~an(473N&eXurp}&g%#i%^BH?GGG<&#z=ua|1 z68S@Sju@#@?4t{}O{p@<>DNmK*S*yLz@;-|uz860qmtz(U)#K(=%7Dt^QBoYgM2!K zcr>20QR5VH326U@$75?9H*1)+g!)Se9!X>sb-I+9`YPW`?7goJ)4t71 zu?CQT)q>vFM*{YzpI!F#tcM9!@!Gh$B53Khr!4<%T|Cg5>6B58AgXJluq5f z6Mxl-B5^Pft=1*GQ%a2AF%e!pB0s!0x$ zI=UifhRuafSX|p)UxbI}yGaDD8`igTFYrAYx4PbVaOW)6Bs0(Gfvx|)Y9Xo}uX)Rq zACsrC8v`s1ijN>w9Um*4t94$_C5&y7RnnI1P)F8EY(paKkbHzkESEs|0IKO$Q5K|p zpAZS|3`|wrdPV2zPb+f<3 z2f4}(UTJ0IQAT(FXGbinsL3JY$4WAjv?&mt7CMWLPuUhH3k8++7r<5n)~nl zgsnbWFP)KGjA4_S0P-9l(!P|g5PUm_fFU%5a`r~V{0b!>1xb7NP^7SHf&{U0E*pfj zBMZOeG}!mxP>N$wZOS}XU4Q52ADuTlyszT?;9LQ%v$FUKJ731Kek@Vrlq`oseqAqj zQzjN9Ee1zvt!zO^<9%nZ=8)M#6j$O&qAKRnr4jQqn2t8znhYk=vPx%kMWG z@|+;UQ*i#GD0I-P@Zoe|xa~p#4aUw~^TfhIdWV?m#^!%kxH&!=s2#{Kt)2}<@}>z! zhRc9&rnW=pk;Ne&3#O4|$Cgb^)z&PW za@QXU4e+>&7w~85KONvhTm41o4uLt-o3&oV7OVN? zud-qoy=(jH+~RGn$Q3lkr4Q%6EYqeZ{m3n=M7^vjOF$Bu;&F|&6cn}ITvMug(?47+^)inz=!J)+ zHv4ST33eSoS-mN3s0~2*hi^tpb5D1z?G^k?qRa5Wyu$ETIpT630agLnRo>*6GOO%< zK~SchMCLjIVPi#4d!U&x!E&+P4}r84;ejDhWcUnLTOf$PTf6vr9rg-;mt0HT8aLER*Sw&^Hc|=sd**3=B zDJ6)|AZFR0tv=1CUW~Pxi=zPnL2_~K+_>JcR4MI!s{&oUG7k$ppx?ZNI7hzWu=k1^ zW$*cEf#q2_{9@WgFqf9GofJ4!^2^LtgoblC`m~snI)UQR-3r%aNHtxqe_| zR0~y&7IdHVB=xHbS^Vei_`N~6$)y-s<6xWKf>Hu%VEU)-!6w=qB*Znm;B72*d~@n|4yE%=^vxtGHeuj>-Oh|MLWdG$1nnJ$7xC z!_NM;%?*I;iYOW>GM_Iu#{K?v+S7l1N_vt!175=>iiv>zXWuRr)_!;2SEMMGuVdW3 zKAMo7-!xaTJMeqHI-oAE0h5wm4{te@;q}-2$|3n%QbDXG={>42Ih7Gyw~hVJ%wW=Y z5O!+u$Z+cs3>X3EfI$L!u`VudxARH{M^kO+sfzmoz(?ftv9btjW`#T5FA66k^Q#I+uxXiz-vaC>p3iH9X|)}d%l}# z)da2b3ysZ`m_Ca8**(9K`xsofv<@yc+6lwj^&Z%))8XnB0qXf{vDr^EOUv>|T%PGD zEyc;Yl|y?z?~JC90W}K6M93YIDbMc6`7CH-@v!zlY_U->I%w0e;$ibPh>nm&5tThp zHU#4$v)1fe#cnmevuBC!8tAGej&+8rhn!OjO~4L?>jh+n*IFzx-z7DhIdCJjr_oFJ zdhk|%U+|`{{;u#I;^$*X_q+mm;66F^LUcVBP5$V*AqpFi^UptO?HsuWyVyW;n%9r? zS^j4P*#FQH3gZxLn}QhYV7*c{Bs1;$aZd`j--5z*m1_V~lT0Hljwy7dMSU(bZf?{# z-!>=VI5tMd)Kiz!A?@cV^*#)e<1r^Jwa~5q(z)QFTklCykS5w8n*f~k2U zN2P2Nv~j!esF(?waktdvL&BtNap;K3&n`tSc-lMq)1A&ChfYn=rk&i~=`d=6%x*q( z6{@uR3wgmtdwNgDs??h7o7rTgd*+v8mZ%z9-L?JdiQdfd*3dzM^NK|1y8e*EP}+vS zle+1mn8A-*50l-}wc-GRqNePtM;lhwo5L+MxtMcawi|p-fcb zEMwv0QaeNwg-6F1>sYx_)$8q%V{=hYp>#GA?o%KB1*@hYwu=c43K2fNX!+wQJ*ta1 z+WBm3iaaULyhDXT)!oCn6S-zvyhLgtt&DVHlQyzgh|F~&6Knf@b?nI62SHnAxhcWg zv89ruVVJxmT~yqHFmck)F{;|x2hZ;HfU0!fGHir(#7iwT5E{TB6YSiJlV1x*i-eV^ zICE>hgNh{=N6a*9Z&I(<8#BiaG!a~}H*soD_H4$|V@VD5ob32C7elajT zOS-Kww)i@)nE4AFgWv3P`vY5RgkS?1m#p>?5W>|axHydwD4&c*v}QJ-IwBak<1;!~ z=QRQvoMIa3z^;T%`S*#FM=(6wRr3*1<6DL(meHF1m;Pa&5o5Y=U7PXCwrT9TFB3(aKh|Ww0P{E71{H;r0T|L>)6PHj;^Icu(Nn(;y*5F{! zTEot0j(AjuDT^@Id_5pu8pb4&99);z3ZO68HE^tzr{1cImvKO+N%QO41}^pURrEA? zkHGN#+jl{otq+a)8C7ab{OmW_(3*gu=Q?7Z+g79YtiH5+o?NHGyaLugb|*dm@sKH+ zI=<0c7g@by&+mIO&>T(8das=S!oIK}12*tUxL-qJCgi6D*so};pRO>X&zTYtWxxy~ zoJc-1{!E`1`r%=iU;6%Tinv$trRNaFwSPnNi3(ab+r-cuS|n+sp`L2R5j5-g@iK>} zuE(-at9T}q^#5o^r{9e^WyvR7HUT~<*{%#U-;U z^-Y6JO9-F0c1=-q0r^#Wt3tmG4b{m!TI5@Sy}?lhcfPcG39!+!KQD;!o#V`A=$K=c znPV1rw`s~=pYv_E2p#`KKj)#NQf1a;tx8n6^0<#Q*{E%W8_>-QAZbH$JRR!D7FB{H zEtqD(-rFijBwtopd&?ztHU3g(w%$airJ=WyXA_$J z%MN184oeFejNgSxWaj37zrGgn-{-Ag{C>TVO!hnbSJL(_(@sU+d+gRt*Ft|--iO;5 z6kYq~3F_oi}s$5;np0XDHocp4prwQz}pA+mwUBQBEGg2qx;iMngi(+E2z}o$bY0^svgb-McNFcn)|Q``q)R$|yxhkd z_l5M}!sw9u$eq$9VqYb-qx$TlE_zgzqQ#?>)AftX^Z272dmhK`y?yovHNu!ACi?02 z?cQrB6;8p&9xibcq;~FSZ*GW}hIOl_v3o<684597G7 zVPT}W5@oh&o#9(6;_|PNz4Pl&t_4|o{vn{dt9rOgV&yNj;Ln+T5ql;zhW+JtZF}uy zr|hRr4Z2r8Pugcm0#C?meK?WCf|x?J8qp6OR%^bxfL4#MC`_ZQX?PsW9Hxo zot?i7>Pzv34L$#IYl98=w=ntfs&96}1l^Wl#g!&~G9O=i!(*j&B7 zJLto%rwE}lq2YD7-X41X5$3_A`HHyKH>fkT9H>rNpDX$;u;N`i8-^I%r}9sUeuRE< zAPkuRf!~(SZ;xa|XT$#tUr@R}B>TQ#&x||n2!BO8tk$r3Ov!&qomN|N`A;N9Ek*~?l6(JIVfQV|jrlO0(x8pzW@`ut<^ z=t*$-<{GJWAA3M)>wWHPyI>K2ZOH3mgJnu1yRKcun6^PvS$r*EjF5LCH3e7F`it6T ztr|mVPXu;DQbDix+9#aNtqMofJ9jQ=6h%iZKBkf76K$ge>EDZB7tto&c=UC1Pgz6J zc(>J|3y%;R1n;m_ZPtCA^n>c>YO|}Hp4sCCdhORuvBbf4qzTy&S9dPY2C+w6I>Ru# z-)c=wi|0f~TMPgF*?H2^?|8ghx?oYbclj#?Co5wp9n&uQELB`fibq7p<2Ef#4Q@Xy zNWV_&^4%e}x}5Af`g;6huS(>vd{W8bn+Pk*#X1imh{F@BH8rds<0@$0k^##5qfm*i zYo=6@@OLFN$coX%Ndg)FM)SF4pOt45r9KT@0q6fHKrLrYfffGhl+G&jJTw z5(k~xr>l4=APOUItW+`%#2yY!<0s2M^A_2K8=jBXfhoyhRh-FbY1{scb^Eu!A0~mY z8TeWkwGFVSvdu#8Jw5_{O4uD9CZ9FZ@$z{5WMCdUiljM0z=YhVgYG3nIo!Ij9Gj%iEL?Q@MzjTb!e@TGZ* zc5(p(>7TV<<|JW0Q&s``5y#Vx_P$bTJX8f^@jxY25d1++TGo@l)D)oLy@ zRlTf0Mi%nCHdc;y8>d@P=*>Wu0p*;pU33}a6!2uwzA*walaoZ)C)swlyT*NM^AW4& zdH5X2ACmH56}~bsImNEhiJ4i(UbCGMfwoB;IajAmqMyLYkdZ{L3`&uP_+AQT<8X?6 zDK_0pWICk#fU?cBxvp*)-8HfF?oE1h$Sz%?iQz8yQW7EdThY~i2C`T5`cU4P(okLZ z1=2}}>0)^02YEaSw$gNHz5PK{3;+ens@zjB zdC#bWPTb1*5s5^mJKu@i--U@XUtElja#8u>QN3PY`j93!|7 zp|s`YWH&e0wbuRtvAw;0Y^-g`!6%A-{4OFf1s&n3hy*M*@&RwT!`G{4JH;5`{xifF zL`jQ9%Q_j9-?y%qwb95%oyl+xlb;xt*8a%Jo@Y*u+uNZb&&I|KllwmT?>x{2tX3hv z&JPMW7;yZ=u#(%8kQj*Us3QJcb1L~6@KM)khs4-U7sb)wNUqM>Gv7fpVtJqLA$|rs`!T2x-_C z(uf*1L9*e5wJt7R915vfDp7LE$!+&DOicZk-<&SyaS%$=IGe=g&vN9|5eg!L^?e<< zkgbkswi5gj9Y;6~HlRfDX|13Oz)g3U0F`zeG|h%WX3;8nV9r;|r65v)joI=WvTb9; z-=QXP;xM~Fv}Egf-TEPw(nt2&CEJK;0)b-!z>crn%r{w7M~P5S9VkDMoy%eOW4v0> z*n#dDEnhtCsN4R@hL?ie)Zjj1Z)28jH=*!5=NGMSlfk_GfTlP}kWEi;Yas^;SWF&h zO*7Llh+{pO%wgW3yng-mmTdD>(RZ^D^u5lC56oy1Aplx#XT=%KX z?Ctvu?>{r&4;AQnYQi&gaFdtK1oa-m+JeDO3bvYwP7{VZg%`(PEtN(p8GTvFjm-*Q zu*Vvi1D>3e=t;^45x;+&+0$mVatjPaTTrq#?gAS8XGexuj~y& zSN#&d&I>=9%@njo(q_)G?qvJGNujWWj)qoax9-Pm1o;nCO!wOaF|$JYA;@A)$6V}- z5+h>SppztYon;WwcL!8_-aaOE_=Wl&mMG;5YRnqG`%FN=xl>p!7fk+x1Ukv!H#f}J zUOdd?ke)UIVLBlY=1Hh>OV78fVa(uEYoM#xXHigI54^nfP(p%;6E(|_5NQnSqwTT$ z!|G{F=42~M;mb^)Sk7zhf_$t zMEuRWp66c<&PxXlou#XJe+aN}2`_dU>il@n;}O_opOS$7=C*-sskMBrxwp7q_j^>uaw6&(E(9#E$Hiajasi(KMo!Q#*#q8`4E5%~SHB zb;m=7?iP|K%k}iO)*`jXDMH<`6tY@EkUF?sb|8xThcwCc|MLPYQktd(+O$(@y1?-l z0W}>cHOl#*(`7P6U;mgEXceoc_!g4taRWPjg2<#DHo&g+y4=eMKlgTb@zqoJ7I@5( zj0dr3tj{!3C1iHjiZ~#Qou;b|m>L(%bO7i2l~Pqe*Utgnf*&g!Js@iu(?#*Pc)fbT zm2F86apkIlAAhl{M)ROnBk_6;Cej5qPM!NQiE{o_-1ijkJ zLw7I!m|6gSGmi7o*j(cIy+(XJO<^N>hH0RVfiX{BuoJz^VAQU~d=%}xEg@^G)(8DE zX*$xkhg}>byRE@L98#yFMmiltc3XSV4|wFi)XRF~rG=Mbe&X1Q6yjyRI=SiV>lS&x zeQWC&3pVwUj#p$@(Ha~3%F1zbg1L;(jZ^1{q=~x`79GDTm7UJnb3kTTo%Hc-(N{{> zf<*pY$Y|T!`ol|h56^>EaNTyY0s27sP8#}FspsgEVp8@0+8JG>(~|+%$U#zk8M{^n zPlTP1Wu41{{4h5XYZXpFqZStsz~GduK_4IUCU@C8TBxix^sL2zX`tf`0`Fy z(81|Oyi@(!-R1oIOd=H|4@b}=FsSid^NhhHCCMGgf9x1#RyUX?GAdBzGSu$<-MUVL zj}aya=v*V70{C#n8PGkripEi)ns44yb?z|QFa80$%4um)eDm@@HDGb*bd`YKcCpvC zqWT(f{Sa^-Ja)CWnDTL@KZ3%oOP65hWcPSw6=pX+Cz)P2Y5qAiUe>+_TC?cr>qgM? zDeDz!Bb?qb{&;%Z6mpeLc_x!tFR1T8$xeoJ4x{T)B6rqJQJ#-3jP(CPQAw3j&*}wz z@|YUW4U<#u^%6Ebci&EahDdWh#93iHLcU(uE6864O&odA>TH+{?0D(d>R7l$nJcVC zHYd;z`Ab^hPe-%LE|Jm#jJ>L>WzYZ|E^0W?=1?SIPFOkll z-{baf%kagnX+F(~i?M}%4*v>f;i7QI3PPUiu>@N8Ahii zyQ~@2OTYOGE=VuY*GR_b_KQuOSOc9J!ACY~&VrOl+$E1|M9u>K-HJyeTpJZ7D^fv! z^r)JYI(j~9*WufxOxBV>?}L}TJeYX^wqHBNNJ9lJz#zniL9UJ`SLf1hQB2$dtA>qG zt}dM^+IEykkrqHA6F5k|u>VmFLIE8*n#gQlJ>}h+wNt}|=7@*n;s1@8qBJt~`PK$x z&X(R~WpB-ejvw5NHv2nyR566%ZuDJC1`mcrKR^Pq=jr{%xVdmL!%(Ibgp?8^bKnDzvuZ+Az) ziOTe-uVQ7=uut4a$9FJ_01qa_Tcl*so5-3=!X+b2yhmy8Qizr!Z3n>RAG`RsfjxT; z#5JP(1$sLlIzgFF(%3=1322w5N!`z3McL?=oCpt6uaQl*pR!hoA^)Su*^&s|lqkX+ z#fm@6=Ko{w*Yu~fl^7M2nWKyX4?DCb2bf3^DwzUsH+0EHz1&gVQR4mOJNkdQhg10z zLx2-DV(~IWydJiFe41ryF2l|h=JyN1F2jor!UxriB=lCA!ZhAtLU#W7c1m#y^7<95 z?2?Mf?5%S--tdA%dFLEgR?!(^Woqif-Zm+9Cr#Enu$;+Ej6DN32UsKKA2F7xn3}N| zE`cd|7cXr#<#MsGT~S?ovUO{5BpyQAZoJ%* zrs4TwPM-^FH~$UqM^&6WHNndkPW8l^BT4?o&qh=DPf8(-gUKR637X@GI; zA829dvM7fG(%~e`NrH*rVStwS@l6FJ(oEU3gRG3Spt>?Jy^WkGmSAjG{!+P2szDCk*@n;^#5z;a2~n_Y$1? zr&om?aU+xh41>yM=1LvLwL{OE?tq3{k0m1d>lf$8Wq*pi*E&_K&vc#!GBaW#Ys`Je zv1wTVs5O=96*p6K+SOJ{!(yyK+8A!Jj*lV9cxZy%3{HL;{mwAC^C->9P-6IkLZ~*D z1VMuabr{K&r3w68YT?>ljbsOPdIDlyON zFpx;oq_Hd?<~XPSBKkIO3{5b$@Ksl7p%Q;mkf14m`T20jg{_)Q5C8M1!;GKYFFh$v z@XZ_^tclz!UrJ0Hw7VJ;7gQ%f;Wowex$y&ymP}kjX+cgNwnQ+mDv%y$!K$4P;Sen5 z@=mF=QIo_fp{owTkCN@oc;~}>x!LGXL62<$kmwt@rTJ}<$)*9}!0Y2?;(3K0;vL%9 z*dFF73^x5Sd*fN_6NXMnzwyq{kzWM?5}#g$>HS zH_evIPPDmx|FR*E@`!k8itsCo|Ib}#_{DP;MaBYOC<^msegJLjz9)`Hm6%TGWu9@2 z!>voFZM^~if1=m%@i9r3_v-(^^pk+fgx`2}I*6OfjHH8iO!-cjJ#biz54ezU-Fxq= zWR@t{bT4!u(RVN|rrk8>2R}u`AWXLsNl>5GFGd#jwNztvQ$=ySt^_A4z%E8RMAyoE zKBZ~i(#CUV7j(o}g_4x&q{(An9t2w;AiKM$Iwoi5ubP|zQCK;pH6gg9E|#MqH@m~G zwMN;Sue=hNaINOC?ZKlOkwRZBsSNu={Z6XPmyjJK6y? zk9F$e?uSttjp)B2TeC$dN~b#+e{Jiv{Rc^2rfQ=v0F^VQba0m8!yFJA%GKX-Rc4Su4yFVh)295eqkKuY9C#G>8}5er?(Dkx_#q@C8ZINP60us zyF+OZ5JkE>Mt662cc;YY(Jfsvn$g|e`F`);^E~h0+p+D~j_cef&xA%~>Vsdd9K2Vn(Z7DwKHf9}la`x#iqA!V1md&RIxKxsPZt&P z0mfx_wI_Y$F^@q4Zu)El8hQ1WlDw&ZbNhYF_M;)RgwuSaWJ4O7Oeuf+c`UMwT2_cG z)l-OiieKO4;5~G~-`3+ya+jE>lhVeKV*lzg_xM}~=vBa_6r1p3XkmqgQ>LEXSxCPZ zD&(wc*V4DPjz-TB>^t0%OME%PodIe>2?9VaQPt-jAM0gPssL`v#&h4BImoSXm0iO` z&0N8zXV{6=v_7`>O?xygKCb0l__OS#Fl^Ik-0XvKf@}f_1Bb}^WI1P8tgls*zk5a1 zRaEkypzCHM4@PxiO%A#tqOfFp_zjo~(q}3e(NUdGsL5iau*$q3`)mFqP~)d4UEDjc zUe$44FFWMZa$JSgO~FTiJ{|c&QASL=Dkb4Q?HV6hqrO>yW1-4{U&0Bpe=+aM8 zbuI51xhAYg;}+_7@BtbRI!ulkB#z66uo(WVX&3!{DE$*0dgS})Aj#Pdy1&|uOm183 z!2T%H(b#`4(ki~Fy)Ph-zO~cPQc|gF1&R5ng+ngqxl(3YkqO8v&`s&!XmYj3=DNy? zmSd%yGmVFZEYFFWSviB_TZ%ckCJ?s`r+cz;dfh<85vmX6`OzMo%;7?vSwl7RSB5O% zz>H$SvdOaAy!P|3eQM}_l(g1*v32U>aaHbPkKCn}o3K*m_`h8zeN#tO2@<2Io& za=$*HysyQbm(|l=lG4*{!<6>Z8gF@I~ClNg3Clt4A#+G~~I z9&Cr|Qxzv8oi$K9A^ZjXOe}pQkO5+Opr8DV9(c5Yt#oXyT7y5aQJ2M^P>1UBfFO$L z+y^W?jkvQ)F4Uz5lFO9BDW%V?wc26faRpHQRrA$+9_7&oePZ*~@b`5yT*Jpx;aPn$ zMs65hQD1)OHd%hrVIkpTCTWfy$@qKxJ8jpZLI;QMq%GCw=K?e9;c-dYDU|Mn=_8YNKa{{-jWOqd^6Z6dJ31l5s(@= zf_N(M$0q6C8Dbldxkz`>!v4%|Pu$5pdDtA$gpr zMKU`W1TI?Jty@T$tMZ#U=4V6aESG&EWQC25F(HX`&Gj(>Zz&7iPjCPtT`TSV)GC+h zO#3!zM^kcSOKfJt1*U`U)>`2xzNXCp+?NR3jHF3(Kx(0l9SZ0Q_p?u;;VK|V+b(jSoCjw1MH4&r?>~;_T_EW zLGe|5kWzX(WS}pzTL;#gj#8Y*q2Ia{F3lw8|Ecb#`w#IBIkE99v(=AIIvjLcK10c= zv8P2V$iNLM%a3*bc;)d>`@D?iRv>yQW*#36xU`rf^f+Z^dB2r3(XH}f_zhe|1xGV< zUtzS?jfYuB&&fiW8kt{t*{emdlIqX*dG*oj8DS`>MVdNTKpC>2A#qPel{JUyAIeNO zY4WKw?#G(_%nbp|jG??G#`W5Twn^SV1`X*2)jA|2P3L+QbkSV!j78qZ7zp_}#$uG- zmbFc*#RNF-H@WnOtl2z-O58gYc#gWI{6uX&Y|O%`T)}iK{94Sw)}?qJkAnHoz}q85 zadof;`L}WxCBYXtfZ2FNE|q7dz8K~b?t2P7b-KnP3}kozFIgzJzW*Ak5<{J}dtRx1 zH>)#TK#4l5Ym+G_6mDxeHhSHvzy{OwmU8b56I@q0;DqmjgPOFy5nQ@#IT_4>mnR$Yry2^L7mTf~ zPavb6C;z8PdGif$*drRb+9J5!zv`b1QoXevli%Q**lFYGM(Ev~OVrlHa!`rlzSjTE z@Wnllll4^oAI&AmC*o3&R72?&6mJqN{>YY?Ohn6i)-`Vdb5${vvbdL=<3Fw=>nG=nR?-fnI zx3&FMCaDth0*cgHQWrZ`v0kYVp#uQaW52JFTkmrJX?`&GqjN`e`PiMwX2&1v(^yyN z&bNLe)6}X3;dTP#UZu~T6um8*tvNmg^gEs59>4Es2C~m2 zOC!Zu6iNKYGUKw!`IA7$gf?UV)E~(hYueK`z4J7duV|j^`vUR{YAakx&LAJCJ&qer zolYuFW}=FwKpkAfk+;b50w<}WpIPmnMu&Ddo593*apO{4r|4PxLkgButvoC>FdGFK zKFjlK>U~b8&!`tVAcx2=P{@ha-uFa7IWOYtq0=X8f(tgY&r*-q1pos)TVtINeoV@+ zXA&{>kd|VfpXH`6*6s1M*llU9%l6`>vpq&hh=t*I_2R{z=23T6cIbmQ8F`6kY^{~)FPF>H#m`3W=*fx@~@myHA`|R9q>pR710ryG>y$aE)F)zE@RdhQ~C-DT) z>e18T|CK0M963x{T{Xq9c;hr~RP=Qib{g`fng-=}W|=MeK8&p$R; z)JQ0pODMV}ZbPo8G%Ek}EMt6uekE;=2Arnk3nC!^IDTBZRj~1=ST&GoV(dTQD8;|U zuLUv0uz8RNnmPq+Hc^w0lk$NF1@YJI)%i0Q^h7*H3XYg!Y8nOmE!SIM4I5$K0JU)# zsy>Cb@XsO%$(~H0VMEmI{VxV#W!Lm&jdKkipPOKc9V`km6EibQ-hVET$KqpHY5S=W zY$GGAm9Odsh~~t>d)Ec9AC&el9&Wn(XM1=-PA>0jP+4lfcz4GEBw5_N?MKk%#5ajq zK2=-A(k^nP^qd-@7s28l2cfSgEUF#l1Dq#rem-5h4jN}YyBO0n=|f@E&7J5oo=>kw z?QX71dtSRhIr{#>T|zeY(^s=FFKMs6J?n<+7OR1MTIVC)uwTXlD@%=dRx?JXE+*Uw zMjRR1@^*Bs3-lSg3*Rq5Kjq~66aES;&}P$0rq)k5KZcUKbmzAeK_`oZ%QQbp(|(9| zm#FQse0_sfK^^garcvYCi$XXE{znrW{OQ}(Q*1QTkFAM2Cy5h#yBOYUQi3-x3^9bD zfGIbQXeRI|KRMS^VTgA-z3y2m^BBes0jJ)i^ z3aYL7tFntcKQSzW2~?<~Eo1X_RZlfv#lEgu%v21 zq&0Z=!M6n`56m55EibF30@yy!>`zQj;$l6X{~ywi0Ac z6$P%wzODA#yjb@g>pz#4jgiiI?V>bPIh)K5X<{u0HlsFTQ?$RnWwjw)L&H_dTAEoN zv#4j5xVB1&HeyRR?ZIdKOn!Q6a3P7y<@jWofP;hM>gJ}y z!ez;+2(`l3YVuw+pnkpJMwHB4(7iU)(Vb+e;T^oHlDUnBrAqldFJxX3_=WVRuwXoG zmHjf*S+qJPaQn18*QAxWi4HR2A06jqO>y=aH;nnuYqN-Mo-AuY4H`X%%jH2zeLloY zQ_pw%x715)$T6?NeQ~ET!9J*!&eTgXPgjoytfc%pLZeS5C>6^nb2Qb?cxuSCwphL1 znf51h=d~ihK4=->(SHXh-Uni4*J~}40~+L_O`B1#QtgcBeiCm+ar_tb&{Gk70#AN_ zh&`r?WCb@HH^S3Zza3S4MY6wgZ0ZbGxFUq44VsdV4)j8hF6G=Je{maJ%zmF+tTSaX zG*s2OZeO(A|7Y{3C|Sc|e^!-YxTz>v=kzVwK2=dKB*RyU>z!q)Tg#!I9#enQ>gbf= z{8jq>9Om%2W#3P|_OjBg>w3@*Phjo()c2sm9IOFdF6*BR;&y?MMce&<#rQ%+`il() zO8jiq%iQkq<7RC^PLSU*DR8)lJuswoYqbF9ugXm(^O#Bl==nYM`W)>R3%fybRVt(C zDML<>uT?5XpLgeXN=WENO3J z&!G&xn13Bm8~M>+@91~R7Zv7KWR?2M^%zjq>?JUGRb1vQ0+@N@UtWYyPK2c!G`2VT zpqdX$Boi5!PTwrc-kLVN2(Yi9RaZ{^lwdU^waXI69dS)V3%1gm*NjtOA$N*BND@Dq z-Dn-q?uIM62PaM}nDGHX$dz*p-D!k-9SwMKiw4>AKW@cU@(yF%tONabT{Tsg#}n%3 zO%0ZVT?sCe&nrj|Iqe8Pg=dcEq(RhJ5a(yUyY-Td(5)d2j4B3$Pw2Ld(8xvPU-;d( z#a=+Zi$kSrBMKtdAJAefqX8E&dEX|mSz}l_I@31fvNMdB!`5U#io&qwxw2JD)2xD% z*@$@}b3gi?))3OorD_`jeOi)^v)Pu%DB{b!a2x0T1W4En{wco{_VSmLE;dhqLf7>& z9;61|hJo67a)n1LKb~hHpA+`W8^h@^rgO1|3$I(lcV#e(e^a_bi_cprmjXI2VE+-= zFe8x1DPGfQMK86fFT)V3Z&l0e%tx%PN@%~`q;vcY{9Us?%aYZJwK>LF>f&OAr6$)= ztLkP^Iu5J>I<`f{c?JvDx_&h`36`suh`p7Z%X80ddGJ`OqE=&;h8VSj{i^A%Wt3?&LUAM`{oieN)PeP51~I_p-4_U? zbGSF`B9SUmC>7rDmI9A4&jdO6TEH=K<4F)c^n4`+q0pKtfD@cE4z-|-uHpyYvgKI9(1Ik}9R5Dp?^0)t*_ zlDGq)RTy}nhFna4Z}iQrN*MAFhL4x-A_MilR&q=Y)6nB0f>f)0NHX}#)581OI=<>D z2eiqPeAD;FEFmIU{d=o-!9R6XEiI-y;?obJk1XBAO7ZKw!)Z~A<$4*B z2(m~;>yau;A3pQzVDmC+B^UMn#A`HdmvbJfRtL5{^b~0`>_kme|G<_m64TVfA#(n8 zwx~-|Jfb*7pr$;hK8IE9sDAhVvH+EPH@^;N8?BJ7cY{Wr_#e%o)pJ3$4Xf6dQ&$#! zPWykS*q+`8=k%XVx$@X{%T~Vg!=EcBKl_DwZ869A3-9iLgd411h3>K|9wd+-!sjyc zAgDa9FD^Qpf;67)ro#$SXf%kk(eSuA+FtAKjf{#?V$3#|AZ;IOXtA~(`S>{OR6bq4 z3`}7J1OXchpAzqX1AN5Xi{3Nbyob`j9vK_Vlpc~=r}1)k)1yBv$hU@ZzeYa;f8XB< z5E?g7(I!1D6x4T#!|)^sO@%2GdMg8J-y8_b9|#HS-q&^~k+fxj0+G^gB|EcPxU@B7 z7;?wZ)NE;o5J#n8RTSZl;;faw%-w$q`{DKP3Rho~pWEH5Ouz6G7F3kuXdEWX8j7!t zj=D-0O-5s6HOS{GRNk0YD&*_i^oB#0EsN@+Bi9dImBs3j%|)`$?_?3XgpzR^c5Ebm)%!ShDdO-U$tO5n}BdPm4}Ld?<`|IdKhtQ~a>hEU7J zmmO)gXgP3|xu(PXO|hr22S_9VtY--xHIVpgdqWs3_gzIC!=)Ebk;iwzo!&(i9@6A* zC&jLg15$i+RD;v*l2WLccJ%(VjrWE{AU?Wa-Mf7UjhPQOiGd^aI+aP90Pie|MxsOD z@O<0wG0mR#bktSQl(fd-=0z(_fkAIL4s-cB7P6wP83vJ93lDy1;F4|y#@I*x*#pbD zSxT2*5FD|E)?m5FZFvY*ikaLaZH2Fd6twsX?MW92l!Bg@kyx+}0ohJVRuh<&s%n;Z zwiI&8ea`6~c^iAGc(J59BI+Q;^lq*+Ys6K#P6xw00i4TWV?E3Ui@PvaP46?KDDM=z zW0yW|QLaSsU;jxqM%LOvbL%m}_c*NFs;KJ~vw{KnuBeE!BReho8>2th_;8>6$o&TE zOosFG@(jwH82MGkTHA{cAY zBnGS>wP4)#-Cq^vShJwfqjR%+Hf3(KE*ShQ5hwtM+9SRBnzCjO;(GW>H9E(Uhc3@b2#B&e;N4#|;4LZxeIa=BF8I;W`Kv;{PmAvjM*AMs zkWUTOBddas;a^+|&sXClSBw6+1RcX)xa}qjbUr>j5E0Ga7cbSdljy?tGN+*(hi}smJ++&lxjVCQnQ271IVB_yIy4p}I!bv4{o`S$~rg|UhQ1!<7|f|``n<#KsnQ^=Ir8d8bF{Rz=)%(2ijY4V zIO5NEq*fuA!Ax@W!L?jtq&MkAn;+M~=*Dnm!SW$0qpA1Bn~r9E5GX6P#>72l_Ew+@ zqvX`ybhwU)#5KO~y*vrG>Zm8e(hT&gT*$@Rc@$++J4V3v2XQ?%mM>(VFsBHad^mVv zCHRlSd}aC2HOTQ?IJirLN4R;X*h(e9Sw(pdi&64zjKj((2aOh3YKr(@c6y>S-T=F#BiM zDx&qGtNrJf)qa&gK@&;Mz%`x83M|ll;}EE)Ug_vUM(CdWr*`;%)X)94VdvqYexUY) z567wpo33~az3k2GDHXn#V#eOqGu2@&6XFKjk5OQna@~jd##5a|7!1IEe}Aj~J!_ct zYJeP}Zk((N@eNBzZKxu;sKcphcZ0*%&XmR?CQqfT3gCvVDVZm2koH=fj)z^(+4zAQ zc6@0*=afWavy&fpUP8J(q{6kFXzTF1kzjf$_-ESYIa8BY6tef8+jmrimvj-RcmHg| zSSVo=5s+@NX7)J-|K@N#)8SpLqWd_!k1r>^Zw>W4F7EU&jDf+V1;Kns+L??qIBFvw zbtUcpFqaEjL!%)3+`oJ~*Dn1|1h0u2ECDk{a+I)!8LR$FVhFJ|kb(+n8RYF~H2A-p zZ=ptBLM>8j}B329OLJ)Ct&VM>L}dT zAn>RY1~IBgNZP1GM1y>*%R8&?I}gTAaKjTfeMSs%WeytwdCG zL^HO#_+`Is;p2a_et39jI;$~ly1jraq}jh4zzSq&B5UWQLT8WW02kp-FV$&i>*6_h zjx;PxOR$8DA%qbPM`ve>@yi5esG0W;(SFKGmEsQzep#=_O$>=oy;t2$7jiv2!(6U? z6a3tFwjlUQ{~;0SXiV$idXMWWT%g9CLxMq zoZ@@0@a?RHe2*HjUOP|^l7W9)!4<`KA+t4C{K?dtzJ(2*?Sy(Fc;c>~2Q)fxIT(Qz z;N$j`99Y}%dYA!sZgayic5pa&Kq#Wo1^FMFsx0{*>iLcNcQ_mVYtJ`GRfp2|cZ_PG z&V+^$QAc*HE?YbmQly9~LKLr_Lo@u zo5c8Q%DESemfS@8{Buk`SMQZNC?ju^$!XM(snzq?MKhcCed8O5&nX_O?j8}{7r#^4 zJ$x6Sx%_5n_BIEm*QQ-SzaPC+a0%`H68#Uq`=5y|M2-QH;=mX#djvV24cFc#Lw9T6)UtKveK_&v^+kNvlxCB^0(PBdGd}8T9zJFZJ@-`df?LLmz*`*2-uW;(0#6DI)x$kyu%m zrjWZo_jJ~P+XU+=nG^haNjKKSo;_LMAfmvFKxcgJCZ<^K%<&T7Pn|=!y1u^LXl`~T zQ9Vp9kH2;u;!b6d78d-uwci$&c5$yZTL2#^6%8u~uQ3<7@orzXF{H{p+8u8?7wuDi znL{X6nHc=D@jP}GLfVo`I_#}sA{EiMtSN7L(Ohl%H-`)#{odUWT$*Ur zK^W|(u_T#aHD1$OAxv;nlP}<{vAd?DdU!fe0F&(HKWQAEaIup}i`j9$_Y93NSc?&s;Lls~fRgL;dq;VkMw#Cd$mtNkM*z9`P_(=K zGjoe9CwW)mcpl$I)Jkc@*BIl2LQzI>+4sAqMnM4CY%k&PY#7oh%M#+UeRVT_p;sY`zZ*kpsQ5JWWPG zYo;cWuy_7}r1pTEq>*~#ge11ITP-xRR#A>!WFzQ@(|1llH}cW$;bSr6Mc0=$+%D^C z|1v1J)5kjdnWx2w<|DJVW1JBr`QD6*cp2{~_d<{PMR*zb|f#L&zz)Ta0gnP~|^ z1TvNMn((y?r7`^?K8(yT>Wl^Sfr`PI?X{FpV zcoiENJ!B1clxmP&;NJV4zFj{-ZOe72#4JrWrLS$su&H0{wL>-(gO${r%9B=&nS4Oq zV0vMKvCW^fqri|WZ|)4QS?NniHslvM&{{`G)D{KrB{hdyuIAME3rQfqdY@#P7c(dLET0AN?%jA|O*}^Y+RK z%ISU;A*1e$?`G4Fhg|i?)Kw0MSy~PH_{tqIKmZzKl&sb?YQyKT@Op1Q2A9F`3;1?w ze*GsL9FjNGXma!0;DJ##0}H&%2ViH-901ciWFuv|wWwY+L6ZM^Xn>fGCyS?y7%|B< zWsNkth^)y@ku^C&!DLl2Cb?*>(i0bI=Hp5)g%eGCevK9XI^P{3V&|7~;+Y-R**<)6 zIRc8Ip6R?9qIYw>KzZAOJvlcwkQ~Nz-aZ687HcNfbZq971wD(%h!*rN9~`~?`(t)w z^anp%RN5)(gdd$1miSWlV;i?eksr5^$PSKCc}iw{vEu5 zy3q;hEU^_{at1$Rqs$fXUZ@WCOr_q7L|IPDnsQbs9qQx>UUiDc5=6ebWO7%gB7pH` zQ?+rcm%3${7KFe3fXNXVE)jU$d^@9v^6dWFlrYG#e%Wz*jzNnX%9gTm8o4HtPB(A8 zPAN|#7o=GpiDt|3$9Q}UeHs`#X>>`s zh5XVvL;9+GKq+EJj^yw+gw*3CEJK}StaWP?6Vv()1G_-t$~|3E!PODged9@;)L3m-{qvyjm-62M^1*3md~(JK^b+FuVs#UG$}QX(yj|m>sHW_e>xP@IBJZQB-ztw zO5;Jjvv8?a8eD(rs?0<2tuc%(SLXt1*U!+7{rVEqVwP*>Ffyzw&ki4E$~75o5`*_A z!`1gWBc}@RTSxdFo;iOx9nO{G1Ns2i+BQ--Xe3p?DvYtiU|!1{>hon$k|o`Z&e#vG zau2hDs5ad@eAzqQO5^-n{e-f4YNbXTVn@d-k!gYJX0poKQnpZlR-2jyFyBhqY*srw zfd5#_W+NN8c7kgQ%ke$cx(Ui3=|$Xk0eN5h8T@O)sjlI2a_)C2avCuCP4s^t^GXZ} zB<}Qn&cT711=hsu@#gbh2Y6!`9ctG$`)C*2s|PA9l+dWX!z`B|6x)k-8ka*;0@>|6 zenSB+m#gg}A<|@V3c)%Y)$#D)ueX@H%?NAu{8;9f5;XXEK|sskhR(o$j?snORftn7 zpQO85qZ612Q)nBXmcXSRrihcp8E>+zi+J!W+qTe3QJ|l5fL4Qd(Y-i$R5gjtoHSA$ zZp1vN(8^ZYyg%PO+m2S1+GQiv>hIZg_ZnWE%LSn`pZl1A+;4bBKhUhKXuk0DV0zZWToF*_Oe5}&tUBs4e2h6rq zXId7iM;kD8>X$&fL2S&F4U{dwvtz5~`X&4eC$oJ=x-42;4Q{38nJx18N4lF76v$so zg^zB@^CuPq$|2xT7{K|r5eryYo)2I~FP7>YXA5~OTx=~zW~HO?xN5gAY8=_IKWJly z|5Wpv-QCl*-4g!%`gPb}=EMAo zNzvrVGK-Y(_%iZRd`sULUO46F$iHE>IhlZmxvKy1L5+Wii*3N$0;e*WyF$@}W;s$! zqbVhBoF_J@4l!BAZEtSg=V*@gsOkf{KBh&lbDRQ-(TEuNr29i`szeiu{?03>;A-V^ zVu&}M`W+gSk8r~9YO5r6Ts=?#5YY|m`9uHP%q~T;1bJifBJv?ismx16{34@slseZ> zy+=8qh^Y&EwAYdJ$N*{B84h;P^7u7eBrN&5&$g9PIq`MjodIJcd-5(>q|N*wI#xgq zzxT*Db*e94?RKo($TcxR88bcL&g}mup<9;!k4&aWw}ci(=qO`GFWl{Plzq}2TbDPD z%Nh^1oy{116E=sq);~h8^_^q&jqxTaEr*X-BPhf+ElewXtm~*kMe8#*8>O1#2t0Yu z^7~YB7EFh+5o?PjQHI69kv0`X?=o|tMXo3$s5xR|hOg_0iMMv+QLUrdWi2Cdj=tN> z6P}+$NJ^1BLvrEN8$DQkek1R?HG(9r=tZo`S*HbN@ik{I-}c!; z-DjIOCdT?v1@hq#n(C2%Erjt%JmW+#KtjYhhZ#WIlFA{ z(s2nN-q-nbxf>)7%2spjUXu)!OcKFpmfjR9j7pOHXq!37ERswHf{A(xkTpVs#oJCH zQg&LIa z)+z^^EeahEI^`YRL=LRiPkfhPC6zx7VW$8h&PY-~PRLVgc-Ir2AViMrlQiJep{lYf z;oRW_$~E~LAs%$lZ~tl=x~_=fd3n8{1H`SNIO>Nxs**#4IGL_g2Hrx>Q^k9>z2(tY zr`&zv*Y(H&IQ$kHU~(^LrEQ1nT`Z9~_}n_}01)9)m!zc46^C5eJY&xgMh@57id|E0 z9OvQVj`OU0Qc_iwBbBt%v$=j<%v9#*5d-yP-CP%k?YbyLUuY>0+=N0gn*9G`fyRRF zbreD>qA6Bul6Er*;84F~W2ydSS`{*g%jdDU#0g*!PbN+PQ*1DUp$kIoI?nx#@YpsC zIQOggspdHr64fHdb#K&U9efr`-ZdM+Dt*hNxALvd2E%Yw$;0%Kj=n#(5j9(QRQNJP z8-?K8@;{Js!owbTx6-Ga`@^U`3cPd?>gB+CD{+j?{@_H#41Cs8X=H`y{%3(ilOfFI zx(FwjVGY&h-DbCx%jDeZKvB-~&!d*8yn{0L2CjFD!at4p?5F8Cbmp}^kjoH?d7$Nf zB|u<+haWjbtJ{7V9fRqUhatJ3D=$1zRb_;=k~u$!Cb(WTWEe$?+A82=kJrtdHZrEt zt26%G^+i1F<+a*stUWAkHQW}K=EH*0*uFnvuYx@=*|)uDr=#MIxg?HG9TQ%Vs>pz^$U z2nben#@*W4H0);1uoOf7uZ3s%pP2RMV=kvaB%x89)i?<+!=m<6GiP^v(4=7%x_0{z z#)?t0UUyGym9U1|M5%lqy^Z8^a64ENLIZCYoMu{{Rx(%3vz@GsQbE*Y{oYGZi9}NB zjm!ARJ8>tqjP3=b%2cM^)Z3}hxxD0~_%vMvW4Pp?k$A^cO2H1~wpkw=WD@}WEH+RR ztBp#HEal>Kvp~3ZM{6@lg}U?s=Xh@%QP!E$=!E)$aCB zwg>tLz4{=Q0J}yskAxm?kmd`*EJ0FS`cIj;GV}ic+yR+D@!DP#9tVtnQ{* zNZ&rs_I89o9mPyIl`WEscr4pIqS->+g^ak9Uiw7<*+HlqP&&h{ z`VWUskuZsFA8njBUQUT=Axi~t5a!>fYGV%r*kYccDnb1b0sx;VFjP-&+M>ODeRNgF`Ln;W4`)9jz4e-inTy z%|Y*0R$P=X?`odEx57`vjVdD=A`K}^u%_O)9o$iQK!ul8e2X}NJUNFOUedYR7is2s zWH61Po8h8jLIWyadG`QKHT;*M>rR5K2Rq&`^9($H~PFS0aPk({P zq1`g~o^m?khrmo1BMi_ku+8>^#N6BMP(o5s>q|YtS%GBZI3;f z+fp%SM06y1gD8NXlBr!R#>h3XO%4Y<+LP+xcdQWdIFBdU8|#}bpAM4(|LHVhFOthN z((HedcI@9=48zTeHhMh&+Cn}wv)8m_L3+iHyN(73QbBRl0*62G!hLMB(M8GU%9uL&MlcJ)1z#ebMqSJ=$Rm+(+Y1hm+q>fJ#`8A`AGBqQ~arT`vz} zoz9NwXY6Nw6Jf_h9R4shB)$h|Kf@RmG1*8nDhxAYKznpkZuX&$ z7UghQhu(37*_yuM159x*e3`^+w#5VW!||+Hroe=#0qQ!pHTr1?#~uP2OH!YYBFQG{ z4U-o*WLM1eP-2m8g1_AF7|@QVpe#&!|D$j99sem+$-a6E8g`?QkMB7BseL}k$JW0) zX09#ZdtW}2&sF#wPG0A(fWxSEm+*O5M_CnOdi-?dBys-}>%*5SDiSwwd_9Z*KMT-O zgom&=R`!ekD(#+hwm`cAp=mjo+#8H1)An9Xxt&qYPomXvHtMU+e~utC#c9L8V75M} zes^_7G>6T6y`{v==)lRmdkW}ZA-7eC%2iUxJDgOjow6hy8eEelHKJE z?P{hnBtnmUoMDADoz;VUYkS2$eo-aSu6;u@-gCUH4aMOj|yoP$~c!*-oei!+TC&& ziG>o3xy;#ysY~_a^s~$(3lx}xB!>`x;5^w5?}Dx}YQjS|BMz_iwA<$&PMl7UsZr2B zWFn#18z)!za?=OaTLBwbhIct*)fz^Rdp{;0YDJOq8OsEM$K`^OTAFsrWG1n#t!+1VlNqU2MCRPF${Us8N6xT8zi!IE_~v> zaUB_&Y`C`2o_u2rODv|@?$r0K=gztLMAwL9!c&qFR_E1FrdL6d$zl%&uSShoWy)JnRfR= z*LLDn7!w`dsnM!34b-Zvl}K}H3RiMR{>-+4*Ci|zYmo6#gKOk4$-bvM{9K>kDJTxa zo1{zNdQO1Yz^-xcX0EmRV>^b)KH|*p22;xeXqowIRA%k@f!tdhwYy+>Dy=dcTcD{~1`JvN=U$=E5u#8a+H9bA{0hHtD z?93hH!1Jrh`Q+h^A$SdXIU-od39LezirzZ+Vcj69^;m?DpX=tMx1&c4)3Ifs4z98O z2%2tiMrLy*zptad7r|T)edeP%slqz61=4-P_+Qt*zjt_2!rs-IKh8{O+O*6|X;Dph z+-JWLnVG3uF0d<^1GH}`>bI2yHm%P(l`74yHCM&VQYBEk;~~f(oCn8Z87JUFxk9?N zBv^@`JCK!kwI=I5*!^qYNs>LfB>+xVJB`GT^m54LTIsU%+r*tkr7?hXsi>}*2qk~< zA8|Uofc1Xtc;{D#T@1*k#g8I8!*;JZ;kg^es%N>-qgr@yQ$AeJ?6fuM`R$@QrZ>+b>a+eV-aN;f!H= zv-oyo7eXq&-ya#(;Oe3arObEoo&HF2ne`@NWYv|EH(Z|&aOnvo@Q8^%zR=EX^WrHo zPHOI!0uToQ(6R~1iKVFK=E|+g9m?n`sVHtFEhgh=aT$KJ6kRtg@WSRadgAJv;j_-0 zgq5)pj4$cP!D~fv)Y{R7G>bkx_<#m|5j(PWE_BoqmcDt|owVpBTj!C)!;aNVF$|x2 z|MFi#z!R0D6RGzkoF;|`!Ggy{akX>*nR#ghz!wgMzy2x;eRtcFV!hN2P2L?iuciD@ z-4Z+Q;F`89Embfh{B&hVbb}x0fyBZQ>XA*V-L%I<_YgMnRj$|;|Mb~DTZfnJdRh|i&TpVs;&NuRcq)nu>z>Y39Y&( zV`N4TGA2>q-f=b<%k8e9Z#_oSiatp3)^DNq&bVN$iYlb9P@^--0yL-G71XJaYZgcGDl|GJ zl=A4qrL+IQ=(RQa&Kg=Q_*_zg+48-F8!gltRj%&;6rT?YX|Sek1=BREm+94&Y%ksk)Fv06;yrnd>4|u+H{((NY(ot4Lxnw`IBCK&7-I0bI z(SF zL-7Bhe&>sSbTBT9+jOc+cR&Uq*V()PEKj`hq{UKZY6PIUxR!)JT$9jVp{$d-Dz@Qf;WC-l9%%P zJuqVcJz9og%`|Bz&1}hi@KLY7z&>A`I$T8oR6WY$UwiGYJG`sB74OxE59rqb^@=I+ z+(E~kh$H*i(v72KN1FiYZu(Eg{u?)l{V9rsS;-#hmUc}IJWBXl<|0qC$J5EHU}{Q; z4$i&X(!Qd-tuvj_nSM-&Y_E>$=O7wtf2dt?NP2OLP ze81@q$$*2omkMz^^7yrryeP%#q7U2(U9_ zp*9pKax|?SXXLK@n>np+{i1!6FC2%`JInus+J2y}yJB{Mou{28&L>TWR|M!1(%qYIbgXutReB~BcL;qK5#8GO==;5lKE9(_`1 z8^xEU*XbHP_56KlMWFkj5+RnXKv?@vMsIB3jVeF6Qu_i#mFrk_BcA(+K5pDWltqJF zf*)9Ds}DaS+LS`YCh4}vJn9*=F=zu9LM-^=llNO>JMZy)>J?K%C{$kr$v34r0UAd6 z7Mb2;OanSBk1lMm(SF#~lJ5e_I zLAK4x6yeJa*Owk0ygd~vr2SMA7JX`bQmv&G0^^w~8D-|J8W{*p`0+hOmS?W>$h2Cx z&^)g*R~pZ#7Q9+f1I!AA*ig|=@}kawtEKWkSF4JIS+=+S-kjk7qv4VU4jL7_dsy>Wm(+a76Jq~^M2=?UsP>T><+WfJ>7R--EA!1 zv%aJZ%EtepKuK0xvljH<@;!`|oXIMh`lID&eq9}S%S+byS=>K3D}x|1qj1PRm2b0Y zrDJvvFgQCGaA%g?>oT^D*d{z{oY8YKv;fr3<~R|-(;9D?qq>U!*)t$f(EI9h_%}%> z5Zy+7+nB!Ztp{qluL9rjpZxkL^iB(r-e*OUsP#!%$(0$#R zDdT^e#DEFhDJSsW+Y)|%u^MyREQt*N%gZLz7O#!kxtE0`*#1O9XOEd-xFur@=H6g0dGY!$yy2z&x=gVJ!A)p?6MOpy+zJ@D=j|~$qd8rZvO|5qxi7t z!(!^fil*H^?p%xGAdab6b|W2iJ>{wZ3r#mWyDJ=gSmB&|7<69p} z{}HafS|jM#7PgYF#jgb9yM1)f3brFb@4xqwiTV*!?XCuwVsL<~s&EALx zAPbKL0GED!{q`;Sz9i)G-7AP9_uEhED?1Dz8JJme$e1~tD(i3E_|~Oj^PXv|l4)nv z%o^c81KIix3^0~JD_*R_)pRQ0mIIZ2IVU()!DLK~jK3$>;_pj4*v@Ygd{Sy;xOe0C z4yB|0k5>aNnL=e!E${wP*3x8+=1j`mUev>tIeb4SN+8osI7Z2?^IT-@35X01BUF+67J>yaKJ%p$Jac>AM^uh~BY2)ui4JzF|| zwr>+>I<&z778>_%1IuYq@p&uvF0jW@E2g&4mV||&E9&jm%*@Q`smCyfiI9YG-YD^I zPbs;!F#B3ZBiqMB0n&0l9%Ti(mgzbQAiF=;N3UKqv3L3C-&@UZW6YA;lceB#w+BE% z$9%nfxn4OgwFVgDHw8F5>|=kjnhgMu+@#E_TX>ub zg6-$t(!)u&{i@Z7qs@$(*Qk$D91BJzYkI*F;)B;0E^(_EV0`vm>J514J!WKR%Q2er zC`EM8x2-7ESNdOUlapwql}g|iDT$b5jUeZ%s+vz0N{fQe63hC`(sDMnbw0IN3KY}z z(Q`I5r-vPnXRTK6?6?aT_u%dnt{d8%WJ!D}t?IUZ3ZHJ}pJ0?-9(?$7q*6n<~Qf(X>C_2^cOwxbGBl-vUD|K2134v%^ z3dj;n`Q$*A32lAb;&Zd9?UE3I+$^rnBx;7-@n?F2R%?$zzJ2|gxdWh|1Hkb|T4?Ps zaiC5q@HG(;ZCM!PLW^7Rj>q?3(T7*4?VaxZMM}7=-f@ICijnFo!ii9D*I#talxoM{ z9`~Vmk9SPANwY1itf*XMO!&V}MCiy0eK6K1Z?DU->x?@G*M7@_ovvs>Z{#K<8Nn}z z4?cs96J&KBK}c9cTbTXZh|APMhO(wK4{{GNrIWdBUR1bBw@WC zLy>*;Z-&?o3Tc0?;}Rb)FUHU?a6z2t;OL$Ae_aj4X@M$)4dTcz2&+kAg|@AA9FRTx zO4NX$i)CDZ8&m0%l7+GdE%UF8kA-EyGD7}&X+;WxvA`rVgl*;aM!O2e8+x|pt|zP0 zPq6I2hiv|%H}W-&Vmdq^CKjCuFeB(?0$K^i=J#k6wLRxRpg$_FC(Px&>ncFo-5^nd zRk4K*=IXMbz2LjTz#l?^C znCSDkZ&#)!WI+?P`on0l;>v_cI?N9Z#f`_yWdI6m?1f&&%2)}7dup1wM*DyMNYKBWik4N1P_tW=dkE(ftLn&So%lizn9ov3UP)ydFIoB%$VHp{vI-z(e5a=}{pYM=89wLW3g@rp6mOZp7QU6j! z)VvnzUQ6|fJn%^d2$CWQ@7?B_FQlrTQL0%d|EVLSM=|G`pI!x~x0s@~ze7OPIiYtS zynq9#Q+}?V6$dM!SlU6YaJS1Jd4s+`9tQb=*EccWpZQPZ-nMn|z}o{YAgfJQ^@#TW z(;n&nr#*eCzm1h?oRh|+XZP4jW*N+7LS6z!jG*0j-M{O~Oc=$lZ%_oj5(?J|pDl5o zgx4CNP&slYf~nR$4C}c)6zGxKrxsa1S&J%VFxwMPPTTxR+d;Y2!?u=sKyq9ZV{+%0 z`ATjo&NM`qTNR^MXCzn$uIQY`fk+vzoBHia%N=4!ak zbGtg4dZ(sXag@XZQ5J^Esl(M&-Fw&`b1h4wC#jPCB2o8avmnznN<5( zScp`N_%FitII@7UT}8ErU&CDnp%bL&W=iUQ0gJ)IM1FPxjkWEeR-|LcDA5337?i|x zTly>Md4!XE*JG~Z=?0e7-;a%6B``-}hK*MYtXNAbNPx+pM5ldFRfn@iEYC?Ig+mda zTLsbT7mQFan9L!RUvNM)@GyUGVFhs}<;`wOyXo*vLBE5-+&66FaN>#A;a$PgNDY(8 z)#26CxH4{Jy)&~Ip&>YT^GPw3cLVY{yX9TA4Rgx<1sg;Iw~vC=!GNdo*qL1kkzdHT z=YRL1*tfo%rv9#pD1kK!^ezb2B*U9+Y}GzhXjTxTve{~w^XKGDVWR5c~W4C z3GCQW8z6r3c+9kgEZUCl`^(fo*m0k#;vn3tfuh!N*PW9aQ+q z3^}^TMz&&}Oun%pWg+EU9gERu8vXS1)y4%W=OnRc`zW=PN>(iMBm~yh-}9Rk9$jB` zI;`0(?)@;732ZOdI!{EPy?vKL>=VF}<`E1(m%+o3y4GRkG|d(;5k*Dm?s-f1TgLF? zd^vU7S^&~j&0c-LM%wMkvJq=NBn#DhAT8E6)cA69rp?X9Xk4L{X^LA|D*HTdc5i{h?-?Am1Uz5iuDKS5A^OMU zUKT?39&`YYpf-UeKXR(MWZKfUi7ye%B=_3@lbAGSAuD*-56xcDz|MU+Vfc}i303n` z!&_a(>ijv_Nrz{cFPb>eU%U^T^jO}ITlbBB6VCo$ZA9WlQ`kK>%H{jdQq~mxmz^Yi zc9`Oa=qQ)`t>=$+VO|(Dp4(mlFxwCS3X(X$q=tO|3-a3Xf`m*aP(sAR4rw5DJ61s< zrYgwu=Q0NhVXcc_-*TdgV{DL? zu^*hCQy|(?{C(dfKD-5VJUnRj+^?j6s;{Z6tTb|}3R=nJw{3_u8IR|S z`cf;!KBgX+ZqpajiC0#zWSd0N#@ua@*NCTSa+VsUkCcf=TgDubg}CLW<-KV0r}`=r zuaxjN4^rM@I8W1WGuwgI)WCG^KjbH0a;}G-oS5(CPrTSW6wO_WT@IAl*qM)04drR( zOEsD3!bW`HEeFFmwdg6UQ5^J|e^NE`JMh;{oDS|UCMk)CX^@kD!bD1wj@pxu;Kq0u z-*`|M_*+?6)ZLCgcuqlG>Z;s5#&Ty3I2HlqnVN2*nik&mU zTW&tZlZ?K$nccmL!!U=pwvyc}g?+z1je7Lwg0%@6f~k&9xqjw^1%{H>aarM9_wVL! zRlDTEdDG>4|Hc)vBHm)!g<(&vao5(!32n&O4!3KSh>ri0NzZpKAAZAefy8${-tN~z z#&LpLLPi~I*1=UoPv}D1#F%-5UPV&-M`-WhqR_||Jp1fw#k#JQ z-(L$-zHP9(!ptuq5bsL0O_O#oYE~QIAOe*f;gOg%{D$`9R@~wKpyV#6AeWK z*gAOr2$|@^)=K2JQ`Yxr+H7Q_66(OMDjS3i-oKraY;guPr*Ch6+jxB~_J3(`QO*|{ z*iy(250{2hZ{tDwRKxNCv!)!7q<f^ty62*1+K+kAIm>*!EB<}dX+eDb zR{K)V5u)&j2qHIH@H3L>*G`dB&UBccCMQeT7bV5_*}Wm&I`f8TlO(N2{D0Ee#f(x= zWwUO7>Dnw4%3Qkk;~$W=f}fBGy=XnqD4liU*p0N(7{E;TA~W3@YFgO`-6dmbx#Lfy zoBD;yHYJaFd}&Z)w}-PI?xibP-Ctv`#WszlXVx!@e$_}ql#3qPl={BUIccuE=p^`~ zP56*bJmRF^ek|%it+^<5crd2vR&PFkC5sle!#0BLJKeSR;QcL#`oX&Ijev?vo=|@rr~R!*V&{4M)b#Tp&E@G2)JC21)NsDatqvs>D${uMm5SsiiOrio z!FEZUL7FknB$AcjT=6?bf|Ukg)w6@@ijGhFc7A3?6;j~r=>}g!2H?NF-0gs=M4+nf z_35aDbgd*z#&Dx_~<@rGj z30RRwYfFA$Vle%o(5ArZdzKfVHNNPrJAry#(38y*ROzQ31U;Y+U6;Tg+_w3ly-!DY z+tFc9e0k6=DR8Qvb zqUaL4kkI6|l`wET#3dwX?w=BQFMgF*K($)!LD9A={+~G|0>xMb@|#4@cFE(?wFPLd zrVWJFZ>8TWl6E!jvM+ebu3?ycex`y~LdIonBS=`Y-`tQsE>(Sf3QCw($~Dbj@GK@9 zu0I3L@)D}fy*+h)`Ug_>g_<@Ao>eND^)Qe-5p<6$zO);U1Jcv|u#!Hu1)PFi}R<9g8fZj9(PMh#FoN2vH+(-lBOg)!a*Rrb03546 z=&^fQP<*ezL$8uw*bS2lS<^SM9=K=rqYiI`%B$N&BnfgLK9j}7Wd$FS#SA2y{Km+- zlLT(WMXN+Fu={jRr+cuw-DNcGUkRx1d%j7;{H^UdE22GbwwYbO*cx(^h_OetR6o!0 zUT>!C-sWEe(V!Q>DnfE{OGwKI=q*qDKRG+fLK#v%g_1t&$*iwde8(??A~}A|P6(R`mZ3TG{# zxMaMEWg=ofG}_W(k4=*=HjL5`@LViw647sUELE*LJUX2D1LMiO{R_Bt!vlQHLPWT%-QC%pXRO`Mj z_l7VafpDv*p12qT##(IZ(l`I5k){x+nY{&C#@W3t&Bo5hLh-FX&kf_sa~5%(Dup$) zSdqXK%ipT0xa8;D1HPspM#sh&ycOy>K}Z*>z~)q|aL^BTm7*oj`3^RzbB5;)iBHW$$kXK}-AO3D zTI&r^NvMTB%m8U-4R3+P>}I)akcbyv-gC`0r?2Lwpq{sb?#WZ*w?S!UJF*o+uK>JN zElo|$y2?ruK=N3>z&YtMJj*LAcj=%{la?sSMnpT0mwA`vm^9-m7!j_Wd{q_N#QmafLsOtEaPA=W)Xc*oK--#mS&PBFrJSM{v=7{Wl>L`hvMwiKDjb0h+ z@0*Bv18QO`Gs&OM5DUXUKz|t7Hb)Pfsa4KJuTc)3g#s-rcneHJw5RTlDi-_0E1j+iQxlCfUPB`8Qu zuw^3W{8<#){5kG)N@b||%bt)&FBbQfU#aBXRS&Ff`LHnMu3qB_57|nBM?t=wwRW3z zXOoo3lJ%!=t{+cAxHTatgL`vsq@ELgj=IX}hi|s>9Y>tq%#wQ`bIclX^|Y z`Z2Ek;wsKJNtqX#wfT65qPr)9g@YA>1P5v}ax$2VWWJrTh@eL6kQ zUmpqeU$uo_LY?;K+09ves68jNI++I5kT&4#FIhRvBNV%mA-V;P z^WJ`F)u%UE+|zn$pBJ&u`#{|#XY%7dW8B=}EbpSp3i!i}*C|$1I_=ebK(q7&&BqsU z4J{&c@?b-v6fTZPwz`=Pr*;#WK&H#bg7JTfBsCoOv#+NS`&-p;y&~rAIaFuU2*f|F z6h-IwQPsbIE~t$?n8~@4MhVdDowTxZ1i54k#^7}e+Jd$i5&}QDo>x7;#f^vtrH_q` z5w6xcbf#rIT^5S8q=PTA%34~|Qf7D>97c#2q8nB$@+06LIO~*nz2|f8>fYXPV6Tgn_SnZ!i!a$}Xxm|%SRsah)=n{#sd$>qVe6t%~CKP2_z`7wW0ki*5mZYO+vP?AThh%-ShQ7=Ehzz4jcZRd%1 z&P?-LG+`!B1AD7tP}l?lo7bcp4g*7{KcqKdZY#lmJ$wBYI_+r^>3;F?H_6cD6Kr9~ z-5`Ak$N9tC`@j`$Ywmb0Cz>OF(a#dreUh^_RNWu+An>WE=jZm|1(Lc$MRs|G1+lM~ z`_Z`f8Aib=b_eSXatvVEy)r|RfHH~z!pF0v-OL`f-H9q+XdRn}hX>G@37p2sp9EiO z7e}E$Y<2>z_>>7`joPxrQi{vt4Q!fJ70)LCd(mg}(^T;Akq;GxDIdNni(TyZ+sA34z&lyt?xKh)s5e9i)MV=IJahlmJ!v*QzFq+5r+YAd#xk*v z6%|pr6~C_ai0j9RzFycCNpuqH`+Hox0bk$@D2Mc)sn#(Jka+~DJ8di3j$bI?9|c+U z7sumuJ;M09ArR1Zhz|XdnBC@%Z&6sAaEjmL4v}X|`E+FThfy=ni|9{|%ReAa zqX@a3lCsWTUf4DfLYF$Z9FD8%wXuh{!>k2K$tEpiHzB>S>jv2xpQ5>IgF&46k%iU# z6rT=<*gOe{xLjr<492Lm8+lG|oBYre+i^C<+RI&!rIM;nl;e5;!dr)dwpF6B>qw_W z?ei(>#fE-A2qOKi9p0P3S;IzTZJ#q;VOP^2CO?woFynh;fAUw)G}tlV{og*l6BbVl zcBOZ#V$OLVjG6T?L-Wx2}N*>b4 zoD0A&FX#s4FSO$D3LT6SHYx)%`f3dep!`4pH}h1jCO}S)>Plcc)LoD3OAXgRi|w_! zsBbcq#E*M&o*pYB89e3w_|XjRe*x69CQOC=|bTz z=mBdjC+Sg$BM57PhCD0H$1aHUu|-c-WwZJK=}@1I2@wN`e#AjsW0 zv%M*IgF$iv4>s@og2=N(!?Xm0?dDFNgPX#55^XKJ4^}EfJJT4qNI!2#e$eiI$Jc7f zI_=Gkoogs%zHVstD!Hg4k|9IxQdfEVrZ)3Z*{hxZe6T)`W{e`&%Oxr##ja}lH_=x?)ivA+HOvoNh((jy7vyre-brY|+ti5Jn_HW4w9$uJ&MSjF7= z=rKx(mv_!?jLtcFbWeP1l;pAm?^9V6GIS?&ms#}j$+`8|&4h7QN^9(kp9)hNukb@a zNTLeGn|R+r=KoxJv_?&Nxr?UUcl?&@q!b!*vLw;LK44G8a{F~}`(ad^eqGx?t)^ZY zD)`oO(Y_{<-Y7L#MN_MYwkv^NPSg6UEmiPa(Ur8FSFlvNY^CpPjX}t_?-GMrNar;T zAD`b`r(ZBFU)mj+C9!MzRt@*mJKWbVwYy^e(uxNe-B`mdnv0(7cH$hO;Ty>ndfIY4 zAhjcZtiZ~pXBILBX0Ur777u%P6o(@nbeO|(IH7($Cw{0mz!@K&nEdPR@x-^;%y*G? zjU>bG>Tjw#B*08Y)xPdAOoG?`9mh%ID>1>|cc%IVKE%@GNb!x4t{5TP6ZzKWX6Hl0 zgqua)(~w{HPV-a#v%#7+5x~LL@_3BRpw`}l^dM#%jG@$nB`f1$=*eQHJV%4gTvG0&JjPToQC^Uf<_qvu2dYRNwTQ0)?i*zG$&&2*9smKA>MIvQ9~tcCg}p-jlyL zVV$>+cu%zDHy(Eo6kyfwGP1+NSr-%1Jc6Ex*v^i-)s-yRB$5+HqqRmgLW*{dDy02W zcp#D(?%T`i!t8 zu$%A1uxa8k2zJ4&1u~qv3E}a3pU>ygtUe(0Msep~A-vRnte21-sI8tkU@aitn(>W3 zLQc(TljY@fnD>NJf& z`qxs}Ddh0~4 z{Z7WQBY##s!)+*1P8PEyUwnI;F;~sC0>w8aICpIr(eC) zp1)$5(u1ig@cjzz_Lnhivl2qy3he3Z32W$dm+ava7H!Ct^w0aBlR4L2ubdoj53*i3 zY9{=~UzpHNlOzC3P3hm6#0S4u;}W*nEn@oF!f4%0$HWUe%1dBG@Q~?JSk9It?C>uCZ&}j0xbgh@y)+T z<1E)C#tiqV{iWSmiy!$~vPtDN77xk6(8dG73WnSh+T7NLY?{LI5xhS| z3>9sD$il2M))2DZan#^J(fTi%wPN4ju@~c+WY}lW`PFo}dCx zKL(;0rDh=LsplP&+eqCk_iU(PG+P6!JSIfHz(1{ramXAo$Mkug?>O0CcoE02R@tG{ zrGhxf-{-lnsAxMH?gl7^JoohlZSLo>MLlI={n^jwczbhk3Skq#H|E07g;^?UI3In~ z4pD{yVLtOE=mKhYqKDp;7{p_1etyAhx`_`M^-el5h0MWzIy>aO&c)S!8aw`O7#M7^ zEJouUeOEsc_iH&fepPS_23qj^%MfD6{3m>()7-X6+*KlneOV3|^*kH(`Kk z=A7a~@I2`?0&w_URGgVJEN5|J{X*-qFS0*0gQzGbpFRXnG5(F(fLp`x8EE)#rf$$C zj6|7u51fwNz^^E3awb&eeVT`pM3)AwPFOnm&|M_Tr4q56?Ooasp7<4c!_}B2OLgsK zFIw7L?X0)RteKju;0%MYocDZ$JTFeF*%V_>{*VT55xhT@`MmM7K>J}^)Fl)>xBAx( z`GY*1S3&FyW}ERapoG7C0r=dEqZ_V3{ghme1u5o8VI*0l-*!wbH`=y7p?VpTUu>~&(tcO*Ygx_(bK5x&X= ziC7sD6`-}b6I_$UoHmKrr5)rl=@xSxPTdoF(z1MSlRSLuL+8lNXl9rio(`rOF|}Jx zFsWd&X&ziPJSCCU1NGvGb)^=!4q)(StUlx@88jHd6++S?JA0S?`{Yz+E4hvp`+c-s zhZ}ahcd_BKBvk4}aEI7O$5wZX!gd=22Rb$IdQvqXYxL#f0EZL^iX5GY11;b%sxU9OjYG}OgL1g_Sqpqn>N$%2K0|we7x3> zjEjpavk#@jo7ad$hG51{Ta_2feS@s!rG4b5o%p?oNvMOLh=jlc**m{Cgwv!t%G)>j zhC`7s0z!gw3F{?UYZaPX8d=_Gc8v3uzlNApw<7bxI7=B*0m+4&KQ^JeVfWCmdy=cJ zK;o>RSO>peNr49oq^H*peW#*u`oT&%kSd$kd5=lB@{lNB2Kv)cEz(Au-%!sF-_|Af z@*PZAH@v|F*3T`Q9k%f)K>BRdtlwFADa_5qH9J4=3z~V=G|>lS%&1@yKdIzwkUgaACGD3EBr6(qZ$woB^+KhY^i$(-w>k2TjpuhAQ(^(`vZ1ydFcXA(-I$wV_7!|Sud$NVL zK{-^^pSIftD+IF29e+ScnC>`=@i;kVDqH{TPFep+EhyDGs6e!QVYQvdRBys+d;VN#OCpIVj|w^eh$*scb)T{6YRvvugKUZumaEkZ>$l7C zCx7r&U0Yj384 z8y`g+XL?4rb!U*kY15{A5Jy9RpQtKjhQjUq2ApVD7fU?5mY4NS8piNGQHw+5cFo8%2qrbKYgu&4)`yzMKa*Ea_J0%+EF zX$AMQ(*Yd#Mhx+FpSCa4X}7a_hF`l8lKWP$3K^DZ5+RdM;RfFp>lUbF9t)%nb3;T6 zRyUmFNSOo$xt^!^f>!mn4!znMMA<+U2Tv<>%g5?b4uP|2!07wABG6pXqdV&qa$_KZ z=WQ~X{K&395Bs?lL4Sq5AQwE~PKoTwBi$r>;z6s9B9BFqGhBGF2ElE8ZwxSRsS3AZ z%ZHI9aS!px%dQ_O^6H>w`luLUe$PIw_7#UF#@Q9yx9fkqo>64o=-A|tR3CEAJ%utX z<3LV;I8S@X#vjgiUz<(E2DZ?;PUPi+jp=p#lhtJpA#X^o5IdJkNK)Aulc(T-n`&QvZ&y6&1MnMlZ5u|XIvP9-<q~K#2eF3j;7U8fjQa1anzba!~a{KURxzRIoH7CAzAsRdF z=kdJ5gYJQh4XGZy^u_WHb-w`r1w~wSk^gjfkYV^$K%M9Ji68GcfIA81l6CUwjt$4F9+La^l5^>E1UEVYImNaqiliMU5u2^QMtKp8NMs}Zclke|4 zr;njc9tU(1Voy$(+L+0emA*gfIL8jB$35sC&r@~lPw?xQ{e{OciY`IPw9EDmAEMgSXza?=M<-J(o?0m#r8+E#h5EuuV0Uy8^5!wAJ; z9IdQkF1pi{w_>)ed#H1T(4;%H41b86O@qPERwBn`;@g+bu;05wt-^Env(YX8!!hKJ zli`;C8ZQ3eDPQ1+o7m2E_ZfiMlCD|(dS>Y{8`TSEJIPv2<6A0d&Zf!K0jcz`J&X@A z>=FP5p*;LXb&BS96<>DIJrg7{0(Nn;%MQEjVU+l)-xnco_!H<8M zcCe<{-?uk!u(01Wj=_H}&%-cfqs?)EDl$*Bm4OgJ8e^xH#Cd0|xcjJF>a#(L%P6?_ zsJ3SxpzQ=}h$Abwmk*48<;V9j515zdJQ{DOzNJ5Mv@0Lj)`lfGo>Ds(FB!0zOt7SlVJMd=WcBJ9EaBn&Q#7=pR6K;2 zVRW6uq+DVhKKU%df04|$7O4rg{qvzTvh!254+J*>8Cej^2^-EMm9cUwEC&9xqV%{FifQOOLr zpR1-&Nm+cA>?;|(kHB%<>(d|pmJ`dR3~ak*n97(6d@|n@Gg#m`t~8wfrVvdy99Z4e zUNYEfcnl1A7)omxypLoull5zwcR>e(H*equX$DC}oXN99CWp@4y4|}KuaBVyD@64U zyHjC5z=h4I&-pe2fi}4*@jupG!fUc9YnKe7xbDef+z$T4=6LpoI6;M{^h!I*oq~5e zxa`u(hGRv~ylxsKYTUz#T zO8%C=DT($|PlZ#k+weDVrMu8;q^|ULvf+jiO%`Ye_{;xi0kr&8jb(4wXDFi-g7_2Lq@0`o#Pn$I{L!b+%u}oi;pZu{FK$@ixx68#`a;?-7e~r z@J)%-xs7s8lPuAk7!rb>ldK3$hoQ>SEkAWT6^1GMbdL6$LprA{*M7eSN{9YJa$b1n zIJ>`fUZQnNoy;c9{kwR>H9ejk$(G5(ZGj)Ccc!`%bXicrHKxO(iC1395@mLwOd=84 zepj|_{>cpSX|W@D*Mrg&V41Os|9eIa=!a%4CE8|p34n&*mOkthH)&t zPa6D4Mm7w_6%=UL?<>SW_RBJiai{XG9q#Xg{=+oT)?YY6zr6k%)^3s5CFgKHPAz;0 zK$IU0o$P`;tD)+8t4DV_8jnUZsvOvMJzeV6QxoLo_5g!=UyuOH|KM?VpnIEEW%9fj zBkmSay-maBwV-;&%GE}>Yc4Qgu7S@QM$3VkZnX(mNrvBM6)^5ODhfQ|o7(!V8n-)DE$c!8)^z*H*y_&}9%HVr%2g0&2fQ$#F=OiDk&8&3cD?`@f4 z@S(iMe^ts6Hya)=r1u#Jm*WU7Q?m~&@DsM`SLjXMW`MNG10q@#(rb`yDY$nZk8_g43CN=|A_IgsWi~+5EjR1pa`O_`@$jV0z{fS$3}qX5#ZHiowT_b3$6h z?Z5%G6LlSH>FMcb3NL(lMz)geg9>f%o))iKtJK?RBmcO3&jBzxVf1{5@^nH208>{? z<~p7B&*ZEKexZ zB&nK-7Rs9khl9$a=wSKcdV;EOLJEeZ#16{8E({cCQQ& zX$Zebkl^M!-eR=CC<1T79GeMwO6tqeM3gXewoxa4cwk7P3hmL{usreHJS=GIEpWR0=1B`uQ^w7|<|`uG4n5HS^3XcW|J4zCLg&9w zSyCsKoPPMD35f*FQzz`PQRy&y6;Hgg9gr9PqPJ(nK4Sl^ognBZn(kq* zsfV3*vH>2yeTtYi3Z`96(?^4}dD^^bme9sIciLq=jHwAeksl1~cx%-SxrB{8av8wZ zE801yqV6wjhwtmF`@wQG4Cr_4#P0J95GiNRp&8e*dV(ZEo>DxTKaO;v%EWA2a5ZU; z?;SI0*qFMdpw_#{ZWFo)79p#&f+^GNT_%EQQc<0SDY{w42$ps&KO0tYzk_aYCTf=6 zVVh%>$P#qfpb8N2oPI6G!%gR8d*?$9Yp|PRSd)ouWRL)Cc+CHW;n0xNB2It$UAek2 zW#F#rQgIV-RL;-a{^Q2_`#H4(Bo+5zDUX5SU@AW&f-m!OUaIiMwYlF2SL?sg0CZIQ zUc^<4{78IN=^h*5Jvn@y8gp;}(x~MI*^pQ(oW&A`(gPd53wayhWF-a^Bt-Q4j7J|> z88p_F+fD5+Rt0e1^<&nRy4&KuygaYEOb~SjmGaG0*gL)3eMv$v8f5${xNy`%bJ~Qb zvq|*XETTm1Dt-g5{JqIbLq7H9Xep?KOCK1JVJ-JLGegMAOE^G?^uxY<0B#r$Lf zg1O#fo%cSWR+IPOwBW!80F$L%|A_|;G81*|Gd~lCee2{^3Jl_^-r#!;ce7b^5b%tr z?+PJY_5DsAUN?w|Kw23=5Ubt_2aIgUIeOiv_6rhx_gJIuYZSLya{D!t0c4{+pNN|2 zN!!>Z8yC_tQPEuJ=!ny6d4cxT%XU3b?%wL(UxCCIBGC)XLeJyBI*M@mD`^S>_7Cm^ zkD;J~uBO25ycAz%*wmNg$ldsq{`;zz=fe<4G%M2TJ@nETXBFdPS-?Cg1=heb;7)p$ zK0-IXkS6^zSxzX|#aI@XtD1NicIJAA$=QXK24?j4Bp9Q;y;}BD40@M{xo$k9XucE+hT{S z`WsJ%1+dYEp|(z^EJF<=SOe>~3X;?D|M7NMOXD@wDS4=TcFV^buP=%`tkCwZS8z@i~fb)sXtzheEqP3n6Sf%&rKj+?3<(js}W zDou?A{(|sL8ygmkMC}cJr??_j*lH8%5cJPQl2OuIdxUd7okibRi!r6rXtPtT|Ll*D zgl33?re;sCCSsGOCX{2pZj74Vz(1>Wb?rO;JG*tN>V|8QE)+ZaYG)BXv=i#XgCG6X zX|9Qk1du|MA4;A7ZYb08Ro^S#6w{<%O2e|_?K zuR(pvs_Aq=0)X?%ETv~M0iBJ3q~GFMB{Gc1RQ zRD-en4LHV9{u7-=2B0fH(rFxF-7z9pejqLnR)#DlHR@9>-!~7r`Wgv!j>083TBAQM zC*vr?a5bKz_4EKKwDwJYD6Oov~_s%OsS-A2>=Yn=cYzY{L!vg`DhCX3k+W!VxUCc6Zb ztPr2);e$`@jOjS@+olM6e_Nlq>N?xlKa=2R_vUzrsBtV!Z__2O^MbqITe;YgyzMzk zqxQ*?@Aps^{Z@{jc8@uohxHHm?PU{Im7HSj$t*~LkThozLch+;LcQ$}^jLGh4z^#h> zhxmr@$eH9I)XAB2ZKk>8t@WLgY}HLR_igHD5=a@U;;fR(FV-l*f!PdTRxx}`10ic+ zDSrGWervev3x?)!M_|ZsV$_FC%ZLw#a(>I@79&LYex~W+B*I2Q&LXzKYz{wbYvT`l z*}vo&&9sm>9SnEzxV(VvGX1}?JOo-s0uP<_YYyNpx6}VbvAu;bef9i}yKeR~3_#X& zNX3OZB!#ZOKysnFPSkU-01C+NcHzXuW+H}Q@8yAH04Az0ohVOKFk_qozzvgun<_oM zG?d*KSPpb~&I27ThN((LEMt{VE8zmA*axL?X&Nc0)L1!$b+uix;~2YvExHs9ZT+$Q z8%!AB#(9&7MLv9sQdCY@PWhSdO)0uTs(qEL{_hP=Zey>IP&qD3>K}sU0^fp=DVrBQ z_|@+Ii6AfW?^YCeNIEC4TsQr{db_Y@-8Qh?K%5i7s?Wpe*uaB7TvB zK)pK)W%&Ql^wvRb{onI2?$8#eI213WxD{wiaV_rd?(W*6rMMJ#2u^T!r$~U{#U)5_ zfA0J9eSS0fX zM7IW=ozVKX__&vAqZJczpPKDp3r$k2<3ClZ&-P5MlC)zS`F?jN8sD}6L#vhTnnEj! z=ZG?tdP;=?j;Q6KL&+NQ11Aa4;I8tS=6_w;kxU2=tGvH@t+-55X;?8t*wcbjcSjdo zt-;o-_k9C?$gly}Z>=F&3J0g*+4|_A?XkFg>8C2vGz^q^vh5T%iz~ zfw$napWbl|>o4V>mrk#Q>Z-#z2m>E|5E_$(^5;!A4(Gp=T<#ott5UlNwp7LBy$9IE z(#sWd#{6AAk+@i+c%rxE>-nF&%EY@y??2rPMFCNpcZheb;k7bF2#z{>b61Q9e*;^9 zEi32q*yMi`-^?Ui9YoD>#9jKe?0C$47}O1juR&C2vqsh`OVcX=c{kX4LQk? zjqq0ww2$d>uBMC|rA)V9I4I{suTWaw2^>n!`UN-!Gf}dI*i>x?9R$u%NYQ71H?|!K zT40w=L{e=1#V$LWjVW*-d&1{XPAt6LvxWrp7FIGats2FFS9N0xuJbCV(2AD!v>yFD z6I2;`Sd`AlJHneEASePA3O(F+ciq?Q+Bxl}oOmCn^|u|0$k3o^%v*iM&+y#z^&F;r zH!;7G-DSg?v}+tf{yl(?7Juvk)B0WSMQw``1!La)+%5~`JG(w;@!#?r0FvuYX1Puj z5kY=`=*Hz7UTv;HU*A~&faQ5_tlD~Cdl3M&F^wC;)z@8G$0P`D15 z$5`gQEDtYQXbmD>JdqQy1I!$X zMR$!SbpHQ6c^JJxLC2q5>iK%?jKBEo2Hguv_b^_Cncd{In*kfpXpSz-hfIL&se30T zdQ;cP+G5!j%x_}bDQcc(I}rnpo;}d?M<}&(KC5oEXr)K8k#Vhh0{-Tn+QqAG9S0w$ zq-wu^f^Quznf=6F|7~N&`CI-RA%RNXtPI)dNIL$F003{xcXVI;$ogdihn+u`+pUHX ztrlTu;I5 zplk@I(zIRV@fZ-2SWD{4AU4n6JsUURCF7*axWVp=?N!xZCtfv%l2snk%5Z|K=^@Lg zj#yj4_4zR{bmro4@)uG9rbY}ON1MyH*d^_ujD>10#Q_Q30v-T7>r5r8mMf>+loDX= zg@eg+?{c=@jfq&_lZDwE@D%k#eS^QsLHU?Rvgh+-}~lMv!cben=X1+x%B$$jBoo z&2{;7PwA&@*^v=`>Fnw@tlph|>9TAOlET1$ZEHdVl{YAQZZ#Z%wCkF|-vXng1}!=b&`NP1#+$layN}gE=oORRWUkV0CSkz% zL0#3-Unl;auS^=MJaKlzro4s-4T{WBpI?oKG~U12F5k(^0y+=|#}e@@X7z1_Z5r{c zQ6P8vuRrLK{j+$l%y&?Y*7xxdJmuMnzxZl5!Bx6F7)tCUt}OHch|}5p#-wjkBsU8Y z8G{!6#uH+R^q6C2)gR4MSQ47E!9tTe%toh>UGJ5o!sLA9u7T+4p>SGF>Ki} zdXLjFa8;Cq68Gm*F7?nVQlZ6O>+*Bx)ag?sA0OMqD}Z6am}c752n2N;*9i0Z!u|62 zW3N%VUe4*HZe&(KT5czEfa%rdZ@64`t_Z=|FE&Apq!{{ZDPQbIEz3`N@4QMKgB(Ew za^5q^S(RVg-zqByH}o;|jQH{REfQP|f)#pxw3|g!{u>clM!1bK9iV}$$(%JH*2ow= z{OCl?=2INPs_9U)2K*oe-Xj4+e{JIiu&cIFH3zGfr~HkB03+KvL1|n|Mmfv(9_^xa zpnLi1F=ooupBQwK`bY3vaPkjV`UeB*o3p--P2fd=3eFY+Y(Zb-w&8u+uD}C+4&?(a>s!oh)NAu|_<05ore_fc8K zrQP0ten$t_9Fbu@VnNx@?n_-5O zLSe>_zlP?k#@uBis$yv2uoJpQ57HMg+m)-r+(EoOi2}p&Uw;P83B(MqQ53Xu-WJJ- zn0)5wcoziNdgWTg+Pwt2_O)s5C=`l{<&*1(%VJYsu%^7k*+p-4w z0z~Q5DA2^oCk9Z!t%W4izS#Z-aHS>kygXfGiJj4b0=&>cqLf$W!2^0jrP!!nWa*8`-l_!gkMzLUX zfB~z<=dxG*QqFMA8}2b-9)bVL1<(wLv#Jk$zpUFDU7KW=5qF~KqCx;#3M>7eXU$wT zi~&mn^b9yK@8_!{%WUV_kgPxt4^SVrFH2Tg_!5_bPdMA5a?!NNnzi z!xRfqc_#d-d6Wx<`mzK%?3j+UA@wprx~_<6y7aPhx_AI)*%Zp@3-P0yb8=`OsMM?Z zYiuUWM7apvywu<9{&Cj3`F&batB26fAWe)~r;YSk=3S#Qoy3oYI*O5hZ~ zmvAYp92-HKrW+ece{qev(T$fcgl;GNcwJDSSzpf6{R)0q{!n&$(Nj-6@^x}4s~-0oZHS8QevQbzNj8(e2uBd$Mrug7Mk^hYi zYBjLKP-kuUEOFi8=H>=9T8ZCy_ab{eBvwgq|1Pb1iFmy|Sxvh0*HDPCD~G3hOBOad z%=g8a2EwRN^xfViv0T1UD$%>XiCGHrk`wpyrGy8{k8>OxX2XqW>ic4b@KE^pBcguc zA+27;z~1+P5vNblywiA}uR1)qP!0I~Q<}gBEYZ`(Qcmo^)MP|Ja06UlHDBm@A_{W}4?-Tl@H6 zZTFdPRqj0Su67yr-{+fjPO9jNE`kR< zPxi!{1?fzTmjBcyUs7lN?Z4saBv_=@HRN5)Kf||-5W^R*Z zC==_Muddw{5$m|xyv`N(X^f^rmn6htPvr05C^E_DK-uKi&17+11MtF zpn``W@AozRs)U;ijY1A3*(+~nko&Sh;aOvgQAb$5N9=(sl*>vp!}AjF!%wApwmmLq zW3-!oLUE>IfvY*?pGwd2l&&N&D^7pDM#o;emel2SEh$x1Zd(;J_Ts5K%fq0v^f4`XeR_+X`J$Df{_Zo9~w4F}U*eCpv^Y*lhKOdZpbsrhr6 zj>>U~I`q>8!;N~hB@5%`w4!%>Zr{tj0C^cKn0kK3y}!RGD>Vd7#of+twIjQQ=p~5> z?|o-uwbW!Sc)^&3R3fzj!{=%lWlz7yi;Su~5&rCOX^tiPYd5~0v~45@UF?>BTp}7` z&We_Pcz5u~DLwz~crB7yUs517;dXs2Q=e@5pUcUhV!l41gNk5_3n+@_g)y z*UrU>;YB+7(No#=2L}d5QRW*>wJ*+3iA`#p*s3YUy~T0RjB*ROE#60`r|)Y#56NtH zApX#naa11O?cwL=m*DyhcM)2y0qU|bf@n0h4&vA2waTDg57Za24jf-GH!;-wCUV7d zFpV=&wW9ynM2d2ll)pF~o5PiG0l2CUy(OF>pe3SP3TtRY` zqqreo0w%|5BNtA^(W>9@ez=6)HeB=AVvye&FRxs4-*{$hrVfb^OfX63C0sC{Z(Wug zRBX&{ZTb;pzgsk+=i~h$dnU@KDLToK3uF&##{nCpFoM&r6n6a+m-?@(SuUryJviCm ztVYYZM7B|@<3I2dBL;x`$u>W%v{2JPq}B*w97l7%aSZLYtCO*V=KN5GS|m3kghYUUkDo2AIOpt1K-&2(xDr-y z@N|UuF9(N49woq~Yh$ox#9**W0Mqm$M`67|*`skNYacD)`dXo($uU1KFBrJ$PM&`( z)7}?07@?2NeUHM|?>{9iUj%H-_;a!R97}im|GWSahXw>eD{V0UwMR|V?8y>qZvT_D z3h&m1Ai|GJwoWrC?PhY>kdSN57cNrym;GfC(ItWgdS3fE0|j^1iIW(qKPm0?ZNpkJ z%EyVo+=6Ldhs9g~V;C2cz09AKEO=r&!`8Vx#;afOSGz0C9a0CRi&RRb)MCF8kcRBZ zD(vY|w>QIB`9kV!su?f%K*O3;Sm2n*^7RTJI@>!m^2zSZ|NAqt`g%OZD3aDXPx)Lu zl>bZfolv}IhdJ_f(Dv09sMfNBdi^rj!+Mt*I?R#UtNc^^2q#*g;#!BzC+D@*n|plX zrIwpkb;$U+uMlem?9UeAGzp|Fu$pxJV-0={Smo$iGn=VSP2-gf*Xdc!D?>x0w%0R~ zaOTWwFc}C9LXDTFQ3%n;Ta={npsk7Jvb)*QlP_Xf`W4M0KzThtQrR8h*ZaoJZZ+!W z@5g1T7rdEEvO4qRd_JUxRLUM{s~^COFt~W?JNsSuGyVCc{VCaYIMd#lK}Ig=E)?q6 z{`L3z=y;Kj!P7De#BqIOuod23T+)46rmLOEMM_O=X**~NAe}L)6@S9*vywo_`SjuA za^B2S9eo;VXMI=VSlmV|I<}u@Ak#&6n-7-VxKGxrrYjO3^xNHM#X-4{tKuneo=zb1 ziWK!BCC2>-u9asy?H--VwB5aYiP7L2+V8-ghP|AT$0dwOM%OYDjnElQwb}bI=JJ9) zc|jz^xhok9TfTWvg$KM9Nd6(wyO0C7SI^q8s^k9K=lzF@RwgDz5 z^g`%x(s*mZHXYP3wY4i6)(}sZ72O>z?MvC~d_KXW)A8N0%5-QeM?#>$is(^sv}CG) z+6(0nFK_Xxj?T2dOR?eP`9IS8Wsty6&p)Eg|jKwVLq3 zT^MxXY`de373wg#avMjPJ(ADb7+lu6g%ib-Ph&8OsauQ6G=*{-OaDaYrsz5ip2%q+ ztoCnYlzMF#(!xU2IZ!szw*USUbslWs2a@Zh48PL_3Sc7vp21qnj62OG7vxD0e3ZLzg;b#M6X@Grbfx&0iZ3Zng6&})L%#B3?JZNweX5<9@2vYtzM2?%HXp9d)uo0s zB&9^+D1}>14B+&yCeNs;bGDC^zy*37vk(2Bh%m;Venmgoq0S*y^7_N%bHpAO@npqA zQt#hc!1js)d7ZvUKNzl^{(8yeNu}t?d3HdUQM^VU9a1Snq6de`s=;U7PC+LAlUi2~ z6mr|vRP`|kgAua@FTj412`d=)kIzqLnS`7%|B38Z)SIR3WG*OOSwT$)VK5J`9}8pt z{b1&iGG-~$qJ962aq-1o}K>Uu?KT}tR0J3|bIq6&^v z2zN^8$p1uMz@MxIlrPI4+}hbkwj!<=wqS&i$enzM&xc{YSQ>lQtQ@<(neG%q^_1b$ zaW8;&h62f8RJip?1s*6SfXl-nUx^*n?uL2d?FOpuKiv*wJ;q_PwNzICyW--&@&X|} zJ+AFWWH{kRa3I-D6#k^o0n$Rd+0$c`MI2XPwUM$LkDI9AlI?iY% zrG1WMTNit_(c>aHmiE@l?X(OCN6F z#Pr;p8o6-uNCj{T{?s<2Sya2^%>Rd7?pNx_^^N88ylT$2{A&^KU3w+ug};-bcQB&Z z&NB3mtCz}KQnvGc#V7wbA5e*HyG3SE(!HDN;jWKlhF5_qPqR0-tI5s z!i7f{!)k^f4WY}!Lca6q4L%y*-cx_?sVsFp+ml}@opmY&2djS(s_9TsN6;9YySZ`a}k7P&%c#thh`0wFcH7@yjoJ0JYeW+^nOk$y+gtRlESXKnl8gPW4ypT;B`%yi zsd}2(;6V4}K7V-J*X>xDi1Wyq2f(y!n@5jF&}Ld*F52^ zO{_}I8vLi9blvtIuBgm_0Zl+56SPDnPEKU#F%qa*t>SUqXZb);o;Y`MI6fmFb)9a* zocS<-;B_g&MuMpQ5Y{hBYYSkR+DxyI;BcLu0X+Piuk(4X^>*>1474%=JcGfY&U+e6 z2v)T3#-CIWq7|tyxhPyu-MzWOOeU34AwuGGlQ`ivKZ%P3B;sAEJxtXLRq-`Z%{6sL z{1(Em;Lr4zkxs|-f~n783g9-Bb`cx7?1PH#8cVwos-ioi$(^y39^m5DszhfNg4iJ< z=}Or9xx6_IJ_i$IPw1o^7wAedwe5S*f1EEyZAy%6Q>ZjdjwwGV0$Qn|vKT@ zS*%|Mrc@2Do7RYC-y1H^9G&60@VhabQ=}F=c^gfc&A*avsZ5>-_3|dXD)|oWXkMCPFMeue!wx< z<(Rn(?1SG|oDms>E?)@)xF(>3xc-q;FBG|;Ta6$%*4eeW8L=TUFctC%nMikQ_a0%G z5C72-zlMV-WC!#!;4ixLLlJo^HNZ`D=3d#jUl@o(yN|CZx5^Ngb>?lH=ez9yEWCd}kH<5P>@TPhIRD+9Dm*XTrYUIjUPVbQ(v(=;`v z;K(HQHuJAh`q~j{S96f`pxMBG4S>~{{^tn$dUaH7^Vxq!P|C5*IL}Q5GnwiN1Z$Bp z<|LnKRjehw-{KV@HZ-7VV5mWQ^!_p||IFl-&lmQJx_O;%9~WZ9?CD58_2x}GXzCTM zI$R+6ZuxAg?M!f}gAYD}5B%D*KD-YzW=~hpWs)7gV^lcsGYY0~@cb#W++=m2!M zM_PZ^NZ9P|I!=Vl23K>Twn80nI8)GK_ynGfvhK@Y<6lzV|NK?fc->6pn$wt~S8k8R z{lt(cNdajIqkmrUuR~ViZFqVD+Y&VsyuubT!0!o%xq}oG6xz?eY_{Un*r{cJ$>K*| ze*(y2vi&*entC(F{LIaY2@}yu#v(;X9O)rlIoYGS_<=uK%aFfZEnRseAy%!fvGv}@ z*4A{P>Oli{Z)}H)`ehx@_1`6-5+!CGJ@t}ssH-RfBfI?#7mtV1?aEP2PI9}KgQ!8* zQHKN0q|2#$#e1g-4>5FFMj&n^_y(j*UzNx-k<6CwvV|4!puxwWHdZ>7&*`G+7 z98s6Q;c>N+C*F<3RKi}zI>JsyA1k8o3hm#);`6PGOh25tny=hg_h0YAt_DT3o`98L z^|By&$l9$A9csa*=)L6aV-w57TIJ9mWulc|AsyQBzvu<*$=XHt>cC?~r$54E`5J_& zyAU@FP|Qmxdw_;ARP{TxqqiyL{eZWmq-2`&SE8iw?p=Yhl;6((CBDJ9sMuw>t;dLH z;gtl7`BOq6&=}2RF>>|9nYqm8Uq&7ubAY#^MX398i8fm@`9>a^dp!2hvfc69V2x8m z!nJdu|HoVXns{2-zFUj8OE>aol&4R&MsGLUzwSMk{INks?ubVnimG~{h>6{PNpLfu zf%`PTLYejZYeZumC&gJ6&V#T(Wt0sW=0jWSc+`$~FYB?X{vrlY6o`>lWFNbqh{HnL z()lel9R&&K0%4*!>{HOU4!`*vtgP@ms^6x8)p5t4&jx*}h!>%`_F#v?|DXHG$s6hxS2}#t zM0IXd_L?BuzMQF%PP`^y{J&rIzKX7sN3RC%HT*CGQu4cdpkK?AcR@$D9AC1mpJD0b5LJAMR zt(J^*R3q6ZcJtjl+XQ8X)mXqR*A4W|gMCFtA?7&d^P&nso)23XzD)F@8Q=aM!NmiC zM}30Mn~j$PmNQ^I>a#qCT_PM~F&!?N-sH77C4FpKhovQ%>^&~NT2Py#i(|TVIx-dZ zFiB8KnK51=avTz~CjoCwf%n{aoaz0Xpg>xg@&3F%(ha?2_q3W@efveOxEE*P z#3kW0Lr>9%OyZEN1(M#=uR>}ZcuT)-F7f)KU=OYw;&~=~WmU0i4dxXat$32Rh+9kk?uOo4Aqg0`p-ACFCki(T&7D|l z$D3VEKWWoM)F9|`Q3d3fEpl1e+V(xp-H-vgRBuWH>qLa|03~~u;NGC@a*@qU3TKjj zX`wyO6RR?L@FH`dhq1)j^$xU>o_YBf?vqqn?G6#Qt*yF$)ocGL4T@@~h&PiTkUIjS zHGDr*f)XbK@xd0sg!w!nnMZ^CO*LERfoO3X=BG&65-k zI%~6a@0F^lgn++>2_75!G;rF6xBYM%x~G0YvvmrCYttT1ruF#cE3_DKB@?Z6bR)MT zOYMs*A3r4KBjkEpOu`yqZ}ibyBvklaF~SU1?hhJY$jaO8F}}$75`JX|Ru|(N;b0t7 zDLK230jz7({Q14$0#jQBPTh)T&|LTNt1b;>yJZ+`e}BIcC}dV&{~sB{Dq3LcpZoV( zzKP{)3)i~B-n0s>J1@_?Euloca1Fm=&`QWssI41q$uYxbrGp9~zsDAT+HhSgaa3;v zRfF=dH92QncWcwPVTmE$Adn>^?|DSZeSiSgc zfVFW*<}NW`WoMxC&9<^JrIC{ls!e*t`XCK~k&;)Mt5^TIyxjfBg@{9cb*!?~0G`=( zDMiu8uo!B`*)m9R292>}|5Fv=A96ZJ;O>;sHR;Iv^2*fVC+$j>assf>pkZ;s93*Gk z?3W}Ze3U7-JC7u9+bEsq%iz@312_5Y2zaq3X7HYcZb0eZ*j72-`X~ATkwz;@zct3O zBL%IwK@`PBxP?~NT=HbZO@uyHu5D*U6Lx>^G8#=xYcsXKnMexMN?0q9X$w0$+SvRT zv1d9I$0aJN*rFGQjvbPC1CzO*aC<`;+-zIRkwVJ=N2*k%Cf1@F>yk5&geb*y1l0nQ2cgG>OY|?`=%uCUcr~fbDr;`9|vBr&;}E`J@R__RF?j)fSJP% zg7XGYCk`RFR~O$*p%1^P3Y}?Z>n*=)|FjD96Y3HFy--wky*09> z#wLVdJL2y*;in9@rJ_OZlnSe{78%(vtqZ0MMM@9uqLJ=Gd#-O@Hl%Sps)-k$b6{@ z%I?XMin&G^3HYCBQ7_ltXMwWP)k?R@(r|>slZh6>%6aV+sXb9$>W`7xE_b_@Qd@{) zmR+53aswN;^$&m=Bot!r+4RA^OjH!_*=^FiZ6*t^=_a3EIWOwMr1>(53zJOZ*2j76yB> zU^{@$;c4W8U$B0%wp8WV%|`C0hoH#f*;?i9v2>TMVNE0F4w<<<*~ zvLp}U*C=tEOXLUI^3k1>+WPYx6etvkH^1mi?df`6Qz3GEv zRi9xXnye9{_g~$CpAOdOHRwcZFxEMWIV>O#cPbY86K^J^%|~g2Aio2Or;g9ZC>SQ>$h6|Ih zl-L4nO9}w1`1NKbph0&iS@B;L1WqaIeG+MIa;F^vP{?j`jcNs~KkQ8Y&0|{S+lmK5 z2OmOxZ*}DscxnSYMORF@y@U1cf_!`w^Lft1YnMN*`3U*7rMwpB_v8TT!8wz&w`FFy z>#g}F8VhV#V3B<^qD6)&rpkaL!ti1$w+^g-c6&Ww?50q41VciJ)^lyL?L+VIcrsn) zBSDEjr*Yi&*sbWE9R72Za81zfW?TbFE!xi_lKo2pbq!DPTn(aIgr$M%BWh!e>^Zx`&TD#8~*c}4nbIB zf71oSn>-bviCgE}HJAFus6(6u*b0YQDe_{sfvz#6wb4$C$7aB6FJL!}z~WB|!e4n9 z#DsssfH;q6wl1C#TzaFh`vn8Lrgl-GUW0Vv#%V7z#4q#txvx=J$MJ6z;p~n}Ixq~| z;^%Gh$LO;gUFWYSXRt$M=b4M+9MDHsjoY}+8cV5+G{lz|`k!aPqs8y^oU&Hm8O1D8 zoF-FET%u9?Kug;_aMHYLw&Vo}u{I_FYz_ok>ANos`l`bQrU3JETp=+~yn6nFa9tKv z&V`AZ2h$KjvI2fJ0AS5LqLY9221zMC4mm!}Sa*89uc3P^8YiamG2(9Z!*24NJ1-Xr zApprE8m;}Ey|JS+ywsAgUVb`_cE&r9EuxwZMg_B_*lYGI$2XUvyV)^OEHR`~ykWB> zffV3OSD-?w=uIlNFq#?Q?ete(W@HrppgH~Ir?sa|x+3h)DV6@^NTwtj_%kq689>D6 zP=H=sa*Ln0tC_Ss1MyQhp7V;7O8mHD4pMiM3p$hEOIyiITW&J!K*zw`t{`<)*XzZT zR<0WNhyfG1ZBzV4-PwyF)PFfxQ25;z5>&H~T&44g=J;w zuU-zKdB)w08dl_h55=LaB>nC{!;NL4V*TdhL#v*i)R~?MIW$vL%HeghrUy!@os8f| zszw$C;AWK)`Qo)ld!bgn$;eY)O#KqdZ$&A*TvP>{E}4Du+g5iPMHSH4q=pfX!tB+h zz{10Gci)^muyYHVc?BD4L?c!0__KqpZ9#`W0W$K`-`zE!4hs0nqCCi^NSl!4#L zjBuJ)FzUgd$Pvx-kx6Ne9?l$jL#bmipb#X`>r$Y&d;3}Rg(xOaIOO<&M~9N(=_|EP z2RZm88vJ{!(-YZT8fv5mw(;L&I_7_74Yp?=f@p|2{9mcXwZo4-?I!r)h#!@y;Z0iX zCp*{#y*qE=uT=Z(uvktAjhM&iV6z!Jra5ANWhgMI9nW;^UjjF`k1@VVZ+P=Px!#|2 z7CLjWd;h@#OcUy{#;6eB{(wi2n*6ycTa$3t=Zuq6rH4zRi(I5++7+vyr#FY&bfD6% zG+@d=FjRB$?^HVJM6{v!LsalZ$G&y=9~BY9RHA`D4v*RdOAU2MT1sVFu}40FmxVeS z;T52Y^7pz3B6%s{kXSY?eDVW7q9jzS*LV{%7Eegw_Gb1gDU-8=NGi1UVGY^~ErBB| zFrRPv6fk^#5W*0*j&s>`UyKHiY^KoWhYBLq0pxLndSR*(3Kmyvk@2vgCI`%J;iKKO zg{Xtqz<5)e;M-_)={rW(&5Q9U{HxB9uR>FW#+!2FWkeCn1BDIgZ}7lP^3xfup@`hO zr~l6ja3?G_kiJO`G)lCDl~)TJr+a-E%(r_9uC_6KaOc(pNG5@LsGTwS7_G<~Ad3>Z zDs?zI3OVSn2wRNg(AYzJoN_PLoIXJ2FA)Vy$;MdCD$v$dbLB!*rBWk>(-(Yd-JQWz z@Wt1wS?4Zn>zP#{buB=|Ysa+g^>2qPB`h}a22enWpeUNiyjZ{LlQ<7Auj_$}h`qhN z9n6Iv@JWocPj1a^fX_FAyyX~d=kBANC77{|ZpO5TGBZLuYpR!|SZ6Czf?2)VKw%9s zMio@kW@{${XM8GjRVa2Zz$u^7Mx&l+IaUS4!8-8uAp%a>)p|;af?fQ=LttF4u%}0Y=w{IIUST2rO^F0Mf?vcBBtC`M{s6eq({>h=vp5&c> z$rp3GUbL2*?oT*Dz;L1tn>V*)-EZ&y=m+)PH?Q0^jmomd!cGrDXi}X+52nT>{MpeU zc{7V-Z=4-~#qD3=Gj1=EZ;r^vbm@fqfU&_(3?&|(r8Q6G!7%Vh`$)8FP{qB`-`f zv=h!v?xYAo85*M$7F>Q{?eAw_>9ow&Ud8JkIptgX(1m@JZ1Fx%xzkJzq9{5(Jd6Pn z5d^*xlPG%t&y+qob~_=f?s8I`F^4j$bW!jPy=#lpYmBh!)L<6O3)`~op(<1uMs6hzwUo^g zpAr2}GzZKSl6!2gr3GMSrCS%!uhus`I$o`>#2EYAt3L#=7y;x)vSBtwwMpXWnR${n zGb5vF#JNO+A9`gD=u_KJmu^09oTva~hp)QVI#1hbxZ{AcYAlJOo-?A-92~RL9Ls5< zu1y9~8`aP!Y#)CQ3-=gUxDuI!$-zjGhXsX|$0V0~4x7X`Xn;~HDk+q4+#46@;<0T` zWfqcOd{;v-H4lxYB@WeGvH}791fORgbP-C?7o-nIQyI-$v;q$LXcS5;XjumBKi=1k z43bZ6_~>({>0=mS4^XXK=nwNId!IPP{gp!xf!pgFIf97>O!zw;2R(+PA)i4Jtz$c5 zlCn!?^VJ9eN8#cH4cdtY?JtL60D56;y;h(V0LyJpO)|~ZUUZIRY0QmuN*H-4vROo< z1K6czmQYFLI)FTf=sHNdOFs{G0v0XltWcQunP>=9Ue)p3Guk?&Z$KYFb-O8;vbcd# z*2h-xcL$7J(yheUM>{Syv^886OVlrB^HuscGjnrp^JMwo?3FX5e9%c3*GD9DxnN8! z+$2Fwdl%Lmm+J4Mffjd%e$NYcO3yG6+MmSGQ-U9Qy=G;;Jgd~~CjMj14(08cjro-a zwvDxD%FApUQ!O-rS=>krRPo7fx1^mksjSUyeoGG;3wEXtBBu;h%(?oD7_tRg!GDF< ze!Xeme)udonZ!2@h2Yh%?mh006E(H$DPaZIc}Pz`@FOoyp%}dv6uIen&H4&+Tp<9* zky5k&Z2ly*wj8?h*VN&h?dLTmV&TM7MzoJI2-8lCq&Lbeg1ro(X0>&sWN!*<@#)tu zHj}edl%&-zVph|sXwp%RNBP#kT4`&ZpjxOgeRj6&=kWtt)z9&i$py4ac-iOs)U^xv^r}<#{e7a^s}WddfEi&<(L%dKrT+|qwfNi~Em9NK%cnLe)E6w_ zj$+pqSfYgpalEdH4}Wk^r1pb|=OYf0R^n`w#x63BA5M6aIP!+E2=kjLoK?m2hpv z>40@}MRInpEKF#|6-5k#`V?or{es2BiG04`)R*dEL=X_p1+M2_|3_`7n6ix@kI^EO zAh`x@vAWPzk3JmbPR5lRl0N_E$*EKpQNf|~y)0HM-;tEsI*5X`#}y$d4x**hWRZgP zV8Qxj{~ka5J1a9_E_+K>ZF3j?`dZ~Sy%9*8>p-sEsZDUT{wAccR%JsYq&6`L{b#=Q zcCw}2tERgcr7~MN!+KUqAVj|nsEcfi{A2zGuj4HbrFM#H5;W^OA_PRaJv+XcWRQ;i z_OXWOmVQQwaPj<>=}$Q>cyzdv3g-ylXWgIhRXeVAPXCzQP))m0JI&4O=_n0qRA4^! z9_irmU?W0wKGN9=$NJ&c!u8fy2#4Zx1>DM=Z2;M^xQt(}@4^%HDT~I?qd1&KRYQ3s z)gD>C8~xyVQ;r)05Z)VU!Ujy&ck2}NM1f<2i7w2m&5Z3D{+D%X<@8g5?*Ky7 z?Ho!_VQyX@Tg&H_-H;#!c@KeKl}u=HvMqdlUueI|&9tK5 z$B}=zva35RR1g>HD%9a)pxAB5UlaK1-=M#FU*FwsOxuoQi-m4I9mNPx&X>`Mfec;7 z#mn-&(l$8xro^%l?yuE;B9=`$49|`e3&rd#P=lC(7uU1wD~!3r!}~tuSI4^e)9VSY zEd^smNu)Jv3#vxt@6xc)+1BR*-=Wo#*pDO;j4zk+*vjW%Lt^sm+GbW#u7K)`jnym< z)+ylgULjD18QVBzyU7L;x?p{^IC}3bqm@c~prM%>o&&tChIA{mBGJ3gwp({x;4UFsy04OLYCu_5{hK z_cwQXNv<2dyUs+o*^3LuchY_fDonInk}og-wv(G`8g%$E?M%br-6r8+SP|RNdvrTv z>u`IdMaBm$6hn9c*W_md%*Bk%C)ss*gk_8wi?uf=k$u0KL`z%tG0^NrY(?8+P1m7W z!tiqdveI9>Ng#NPzai|imihE>3b-&mL={SAvakbRq1glR4?x3kk%ZZXda?ya3+>h3 zik5ZTvi z^;0)^G!#AhfW8L^vImMxXpK7X!J1A;Wpb?(%8Ws%u|Fm#F+vS%iC$Pfcf##u4+S-_OY>lGjBl zrInNtu!7rN3Ih+y!8{q9Bc9&${LMMOx7l4y`6>1hcOFRQm7k5itsrp`!APefP8{n| z_y%=D%%6T+l@KeTMmHiC(ZubXV--rR3|`7C(LjPI zC`>d!AkewXMjwfCGz(kx3Wm|u^iVY{(C@tFBLtt0UMH}6b@c+vqeZ=}Ld7!SfN<-1 zru=ph8?quhQ9$TO_oTtfHOF=sWrag@X6rc&X`=~0%Y9*oxe!^GTsz?Ib<^TZ>;h@$ z+VQ+dyl!fN7InGgUbPXqe3~Hn7d??`=1C9JIrbX5Y}`64iSh=zX8kfc-@nPDKZzq6 z{+g$%j7l;rEEYPBFy+3-*rd_5pUEUf-oStq&w6j;-&M{6JgzhiFy?`Lw2Pm*E!udq zM7J`%97wo3N8VZw5s##{=AJMHzmns5v?#>|h3$E&ORd278qVqAxH)z~m{kZdUFp=H5ACCN#C`%m1^p zAb4i+kGXmRyF(nL_cP<{9qjWFWAg_a$Ms8bi98?l{i3M(LV-^IxJigmM7Ji7@y1p z#LBY9JH`fHUDyl_4c$F1Fp=OYa`1jg|44lGxPSyr+~fm{qm(d|l3iA1c1$~x-sN%K z(8}qRNWHlyAxIwYtmvdNf>~nFdo)PdG?ieO8Gud?HH8miBwGhI@pyA>r_QGH#aCdI z7==YN&%oR|N8rE8b(j?(2{re5xj{Ux$G4Q9zUV=^vTfRm!CZ45n(f(ZK!7nWPnLeq zv-8^j9&CU5!ujc$jW+A$pePtVufbK}l_%ozKV0&?dDTzWjQwDc6`ZNO2+Zt7(R2xf zH2jH00{Vr_H+(is!SGJ~x4xf#J>1DsIia`!*3MlEYS;RBfB9d&UF3bsD-Zf}4#1A^ zlVsq|8qlujv4+BF^xRscxt(LXzV-6~Xx7cmZihe6jo@kYi@(qJ)qshlJEi|ruY{-bW_nVL_=h)1l%6Qm2b6%w)(!&-7hb_s z@TN}%*lu!%qezgf$~AT7(Xa!V0xNF=*e}!b#*5)I?fLSaV2J9QeQfo{61x$L+4xO( z?+R>3Px9AKlmNfqk{-Ky?Zervrfhvo#ecVU(*1-)(Y301CW@)WSC(BIh^AxhVu$Qy z1RKO6y8ktcYz^4J;<9v$Dgm7bf9A_i)lAvooc&ka*f8w*x`fv2olb z-j3NMjh(bfV>h;)#4j+cw|(`TpkpXK{CDc4qhPbI*Bjj^OI9 z8e)_@~pq{#I95&1{*ie~NY7bv(6| zSy+QHYmay4pIioYX-2B-eg->z=C-R@Fjd%S^^V%tyKfQu=JKkie=aALFr0z3Sq zOXy?mNUKo*nB|02_CTHHs9}w*MYJRRoo9{Q7UO)+{$;B>B;l#8M&sOHc1|3eJd)d@h#lYj1D$tj_L^eT*AX$n*OlWzAJ)vRiJ ze8o~f5-UkR6|i6hEpu<|)`JHd)e-)~yd?Wrnik{@AkPC4E05)U2}qEdJU$B^E`6{m zrzYwva-sN*XFjox5Bebq3Fv?bsE6*|)T%cZ9`7x&(iF0Y;w^mJ3;hB}fB{;~gNqfZ zgy{f_VgtktJKt;lUQkE(t|Q;RD)%sEH(y>!{K;^I@z~eppq=<__E%=v{ZAXi4vVoY zW7^+H+U3&wU0wa!Xj-?^BUr8AruOb8o5e1tfY#g;m;gnTJ2ELa$S-tW1u|>ts{E9Y zIv9V;ax%Mr)^n6)%R%}{Q|xuZQr` zlB1_WsCy@T!B`>f`kcnxAHtPI6P@!F)cAs`bz;>}%|;~Ds-oXdHlp!H_XQ4({gx4I z!$lF&VNx@~`A?Z|*jGFtj_)^Fm0GO4{r?EPpFjqV2CxzjEc##gXV(Fhz1?i`5X@xy zmxpvh(UnzTgc5Aa50Uor0P&me zKs+x%2X%?^tKAGOH*BAc!RILYgo^9LG>GQ=z-S}eeK-BeT0OwAQOglrbI+o6Yf+*l0}3y04{r-^;C zB-$QvM7IiLyd9O{x~ z@av#fm69Xxp20_|S%V)}s38G53t=|S#hUX#*PV!7wagBXO8O-f-G|WexLe>X4eq(c z3{8m2tRWdIm|V2{LMNV%5g@D1O;-3O95u+ZZc5N&hidhOxCl5O{3GGt>3m2ZNqhN@ zUVnXFkpKMcsSd|e z!YZo3=6vH+oZd&B%^K;CKjG>ReINL0dix_%adu9zcbxvUbWuh zB5nIZdC;?V7smg%dbR7H9eP{msP&S(FAwCD#Jl1z<(1Loo0$Sx1~3M*OnWSoI&>mh z2)$KIa?!{*L*mFLE)!;`tkf+tnw*s<8W!Uhv#Dg`pzI zq3Le%vlY-rxg*=0>3BriN_K>R99b#TF)6aJ9EH^&AZRXr(*11s2Baj+lIH8h?&*apjHcTmmKKo1oBm_=V~U|GH?BO@ z?Cnh5Rudxhs?wnx>3C=*+4r8`J235}gPUoP_u|gIM1cXmF z)^N~dj>~i`t*s>#nvy;APxgyMzW$ibF0Ma_^tGuJCi z!;GI05^SooRMO`=E>5c+X>&T+ugSY?X9HI z$=7!#6-ak|0M=0uqvE_f?ZgL?-dFvctEIBrNREGFIhYJTzx^YW^vCi_fJllpWd51g z;l2j&N<@=<+{31xE(-(vp%61+&3&w8hB-8ns%2)J)G>qtAQ35KY{jfbA$=KXLP*^W zbhXqW^u{~lI%_H39R%&<>U!Sl`S~0Ti8mmPpx&{REg03v#HhUNox!7TgUePK!a+FFG>>phNq5+?9;@!2&@#8Pu(x;-FmfW6o@1%#yppOqy@J&vuvC? z?!TU?V4=Ad%%52{p)kGZcb<}To~{+;;UTKFwB@wwJ^Y@h`aCIlIpLZv?vvWQ@yL4& zk}^m9ed@|un+q}C3}J)#`vhmo2P-;EapB8I)(>dA!l@~YQggywNfPc5qnv>;YhTt- z$K0s=t2h@uhFX+Zg_H7k>&RAZ@&BMjMjc3W|3@sj4>h%){~y>C{N4Lpo;yMgdgwYm zNHDp_-a3f{Z}H;ghF;d3bKeq#wlIctX4lTekg?4QB+yM+wL7yF;_}Gc7}Oj0Cclg9)2<)WVOJ-2{{%!z8h(^2w2E^aJR_;ce$1D~Oy1vBVW>6%8V_soep4X}?<8$~(OYCo zZ~Ti+$ek|da6CA)4yGu3D$*)|Ww)zxo-CcW44bvP&9YrnB4MRf?3^CPs}bT(JIDzE z<76>(xxuYI4rRX#uNMV1*W`BmB>mxsa({j<77CDz5vQ3fhAo|qgku_rHe#V7%3LFw zu-8DDS{H(*0OUK}@4UBEMqhrL2l&3(ELQti{V%k4$^H-?BXd){4jFrXu^Y^g@dvIELXbzj%PrmBOo82gj8B=zQ54M`H(Of5~E_*dswE|2zBlKCQt=0-M_l$YfF3i-}Rbr z4|<(jwf!B||KJO_12q&a3JlkD-q3IGcH;-;dD)^coSgrus*2euu@_cog1*cEwG2&F zu+bm#l0fx8wAF2MEX#}30|Qtv63y24)dJ6a^iFra!v*+(#_&c(;;%ZGKjz!0Yo9TX zm#YXYbbs@(b@d1cU9@RH8omXG@>4qv!M26#o%UV293!NL3$YV|3FCg@{mne_8^05{ z*OETJV?5@F@!L;%5s|Nb7vA?V{NG=7tsdYR&z>Ng3FA4JZxgO7C+1VQ@^b)i)dJ#|xnRJ}h5NN>K7WyM7 z_Pi^}ce*C)Eb47vyf+HH*UV-&o7v7*d?zWx!Yc+bx#8k7Aby%X80xg1m>dI|OF2DbaQNB{Z;AJwo2Pn1( zAJvk2i1Dw?hG*5;vK=#Qp;`rdw=UUe4 z>s?N!CKEglpx;W!vcX%!u^M;ha z1dUND!TeK3grPxS6_O!~q0_pi<-MY8+hVBO;hNmBb3bmR$VSB{z{A44G;<^7>-hg*1c0_@U9=Gb2lCJ?Cl>MjS zfkp~pHJ2m#)hKy2(rHuH@=ucGy_1N65yizY>jrS-f%&_?zJ^g7_3}@Pbk@BU9!hZ+a(v1_8nmbBQAm9tydkFVmF}_4tOb6SL1;~8W1Wk8Ja;hwqvc?Y z%kKi}9I|<4`GvFQ*v60lPrz&FW?0y>h91e8b|;q-fO?v%@OpZ{ee2$T&q@b_Kc`h9 zOm(Z~tIMvU(EQbOd)!++0(UdQTBpRf+9+eiyp@`38ToYXvS`ReN(inr&5(KOOcb~N zws6w8H!Q{F%qvkzE546Nfc^ho07cT>!JHoU`^Nb%_UwOb8~wXty2&(*%sLfm2&=$` zOo(QEAXz$f&BF?3wKS_3j-i!NmvSo(>wfrVZIiNck>*Dc!SlT@7YD1IV!xl!2JY~M0 zWv~%sAT`t^EykmK)#Pq((c3CK2+%pquQY_N^D;HVN*n)EV zX32P7GRc~Oj^mQ4*YT^%n$-18-bqDemQI<%r$MPfu$$e^_+tGWVP?bjCr&5?ni;ZO zDx1W0FlHY_Idj)Y^<&UG874)H3wMsJ8XPxDnIdE$?9!JMG~=6s{`N=p;f@AaRcX<# zh+$85alW3*sJmd%=NQy_QKK9*2>I|xAri%W(?%v6?AbqK+Av_{8W-|jII}woO%9!| zdN+Hb%E6RmFxH!(`nQK7|2J>=(Z40##Yr#fzh#IQ@bGhfUC+PYhSR@af~eASbN2&2 zMu8do1awIqo`x527${Zm{MPf<`i_*ZAn(>0Z;o-om5&CN&@+s9`dknPOtW)KzwU(* zF%I@7)6Wp+D6%)ya9w?auTT%vfqmntFC z&qv`; z7T1cS>(HZ{?#%HYMkn`~BS(n~PsyyM_u*P3O0i^zYNOPkXdL!b$Xm?t425p9Sn{lY zjH>Gyle*A~dKsA_ul+A1;0AFB8n1(KFEN=`n*_wmYlNuUZ5z}{p`$))FU5;J3f5kI zY=G$vMaHEamNdnc*sqy79rXKbMBMkI3*U%XyrHJxVDj0|O~=G>6HV#bZtlurd^RwF zM)CAw=*R~FRW2seIb{Z4z663oi*XoE+8Vd_CEtO<#D8T`!NJz+)D2F}rWp z&Sk)?OzBv`GA{blK<`(cdq2zxlJ2vWUJ*@Re*T!9Fz*Ei`2xR* zuc674r2yd6m7*@bs%HJQ;iy4&p4a}xp(XxfnU?1KblB=bv?^6CrFk;PDx3G^GE?q$ zYcNn2Q97UXLHXj&Q(;u*z+;^gJtVp%*$%WX=_Tjx?SL#JqAv0 zVl+;@zq~fThEYJa9Ho`c6T*r5#n$+d)?`kuiTS%+qwfN12K;egn_*tV5aef^7?~OE z5oI)8Ot0!AZu5}rc2+V2mGSP#!U~&3GO2(LR0w*DfYSg;YvOmuDS8;k4Tho(uz~5H zBNk&s#@$;aw^L9+dqk%OOa1bW?eEwsbFEHcS^+lZ5e*++I*8MFz>2WUZxudg0!t*T zSPvuL&2dQ3{LAz^;89G#y?aTJ60+*7EI$o!V5#qh9r3ReI)Ccjf1H5aC8Rr`L>b^A zr~Pdw)2>+}uF4qm{8__Z={BH9ijkE1tBH(^k66c7YGgCBg4Jqfa3?};hRxXC=OuXs z1((-bEQ0{+SY+JEn^d3Ny~`sG2>&OGYUWu-ri#0X^bzMQ-qH$g6T&D!WVuUtID?we-@(J(;`<;Jbsxva z_&l4tzTVl$-I zH}he&4fD5TZf7^#T~MP?3EFoO+m^qBiS>^ksA{)KyZ>#JaLn$!Cy$k-L0+q=H0Xi6 zZzb}Qs#gepi1N0b6jHT1n`IB+hsdV(#z&?U59{$WT7=kKhrN>x^f^@9AnGH$_q)Q| z{6H%lHd}lr(sXj}t5?AEt#Gwn}YeN3Ypt@fcBML53?X)*!t{2lc@=luIgrb7Cl${NBc6?Q!*a!BCAFd9z6H=j;PCmmfGN3c;qx8T^V~J>nvS zY!9L|A180zJ((u`a7l(SdOCA++=M?moiH-(jx{$xp-);gG7XzPwRyj&@`~Ahf0-gB zmDtTfU!dW0!J=A=wx|}?)Nq;+6q)TsoAqqY)iUIQys4np!37qJ4{eJs?QgzM1)|yN zgnZD2n9=Q{gWi}{AM)TAwlh5PcX`-eF!~9)&%k29=~7%$(&lmt_P^&dvn zJ+>64S~TOd2>b_MO%b8rznw2&^=oODm2pV%8Esdw(R5Nob(C31r&MXv;lBdA<74h&w90 zFV)jsqt836Y<7+7Nj=QawllG5oYsm-R71qZH7#BC-r8dLEtgz%!Qm_(JEOXs3H?k)v2{KlV`&NV&5u}AWkNW9S?%CY#tokA^?H;jCv%3!7c-%emTJafGr6 zGF4eN(r#8>e;cgx@6^J~A3TjLp%|Pt^jAqCYEZ#&7}8b#Rbl0BYC1nZ=8N5p_^ zXkBQoA+*e_e$)mGl{O5m)%;2?mSXm!-*|zwFuUn%#E(s#FX6LiXM|QnZ&(L;hkKzr zXwG%FjOP4FDSZM|IcyqHFBvy-nNXppzH&~yCChBI|FX?l?M#go7mOt|n+TUGZnrq9 zBYYY7chyy5eul)tH9?}_ff<5abMaNkd>HFu6 zU)&i4J9SY7d5e6Lom&lKh3-o{PbP&t^&y%P&v6$R<#zmB`|YQC8E0#{4SyvjRGZ#( z*AMZ%Il?id;W^R0dN);bWSyxvq=WFK&g?iJ@@PaSDno5s2I+t+--hN3# zOzNf^%!F~=97rsac#UYx6$|cu>A?DhKjL2==%yUcgy0PNYj|qDQJ`V3?CPMd{`H^B64IcWzb34r3aeWn`H(=Xws5WHH%6^zgH3i2c*O+ zj+|C7UWfWbr(c_jhfB{6ietc};ZN290BR`z2WCSTPn?D7dZ_KFV1g65xD8^wT?Z(` zhrY&!qJEA~YqxkPlmF<>@XJ<^?PO_yZRk|H_>GKOQnR^s!q z{z^mxj%+|-pTh}lW;hgIrq@)?yHGKI9|$tLj#FCwXz<*3fI{TEk-uFvOYX$If_JzF zV>>qes+V!cHsjry@2$pkbgR1XsD!^+*aQ>S`~@+9dBPXhBb+v+S93}GSv?@Y=ubvJ z-L9J*F!M3&%lwC9fX!EPO)V;Oy|xVHO^8x+`u(MY3^82kKd_KOpTff6a=rHP1zwgx z3zPB;`YuYI3OH`zf4Mv%b~cTfOF5*FHu7K%K_6>T4XiPMJ3cFJVL4TzDg}?~dql$M zooaA4t~O&jle;k-X@i#`K7#uH?$4< zzFV|hYxu54VTH4?#{LOjd}w(1m9Ku|*#ct-awu60(@WcUxLx@YG+!?N;R2%jmz_lU z^?D8(u_Vqb!J@n2y7OCd(YiFNjcGbC^myVFo8+JAcXM+0?t90MaStj!gZIE4P1kCB zNy3~7xt?;)V07NMcr2>8I z$vW7}3fN08vp%mpeB1F);U{xO;pGs`T_1&*ZKBg%q6tsn6I<|~SB|+qhwFbvUjOvP z-Hz85pSiuh=kdY!x|ea~;@%d$`Mm7lhbUMezj|NH)?Ok4Y0Ahu(%9;vG#%rmu<9*HF~s^ zK}~Csmu}Fw1#^h=1!}YsH{F@{=K|q1XKN}fJ;(f-w25o9%CpTSIig(s+z`m8oGaL^4NJPFimGtXCp-xPx3wXe^SuQ%9kZTm%S`?p(=g@|}IP#l}k zz?hB?n_y=;fxsLX^Fa6@rCw-vXt;?X#7{CC%(ektn$Zl#PnW@zjcgQmiOKM#GLtA zIk$}in`%g<;yj~QZXFrn&fyZGk95U0VI4Eh9Ztcdh{GjzR(q-_n`)1K!L$gQ_8}dP zCgLI(VWPm~u3Mbj1~S^T7-}>)uSNZb^xsH6_!1mn>XYc(d`gM} zZjKLQf&*pJb#_d@AENC9b&^m7n7lwM<% zBvDoqL4oF1-TPgoR$a&r$W^KRwM9-rLB+yU3Lz@R8`Umorb!w!jdgmFnfOhW^TrigwIC?KIPx=&0xiax60C1f={jSZu>9j%?{HF46S3H(VWJIVwr4JG9T$ZySF*7$X6B>X@wJIw==_Ao zOZLkm&8~W=+UKGTVrs^dhf`tOJUrXLjge$i%#JP|1R`WJhQR_wM-lB;t#prn-)SD(1B5LjCr`Fd_R-(z`#rS4$+;hEu5BT(vIB zNl}Dq)4nzu9YpgRDN~}4wxqpU5s7OZ6dtKI0eC>WD4QM3H_q|j>t&p6n!_+h54Cbi9Sx!;mSd{w4AuP>7?Aup~d3QrB_*3SIF|RmbSKbs#;w}@vv*W;NzK9I29`# z2)_0v=&jpjXt2{TNwxCC$%=zN6Z3KwI;6FiLUzj9JNdeM?+R9yIU~?~*2D}-0KHNY zY9W(Ek0uRSSYP{6tuf7H)`18wdOrlsdcZ6{6USEy+}1M^8ZE3`j%2f|O}~LwW^N*9 zjG7?WecBv4Od`B1iLQ>nPLQ!v+1x!Y1tM6@m8E`yxZ`Tvul~K9b~)~_bGsJg^!sN5 zcdR)`WE&>84IAL8Kzb6IxYI6}mK11JuD`b5!!O69B3`k)t0S_!@c=eUx@G&eso(%> zHgx#)onv#M&zG)Sxf#&_y#sX##+WQ_(el|V`1lIDX)%x&g76S7H+`751N;6JKi3OY z?E|xPPEx5J-6%(_;l%#sV4}FVSm(Y{>xZ7tR{ztX7Gik^`TS|TftHfW_=2$!kQSR> zUsoDq)rry}V5i&Bo+HD_tWRrVf%}YG1#sg_N=sRTZ53!v%k317>J${`?O4X0k#5xh zKdyqX$E3oLxSjLn8AG{kopSg8N%F+|A?wh;dMP4udhi0AG8@;P;%LvR_~qDQI2NHb zwAid;OR|fyt3z1EfPePno4p?r(8Z~@ApHve6{eSEXcm;wSH^@_s2q_`e6Hr zT4=rEq?XMg{@>B>b0|0S1a|mhF1G$rq3yIR3ud(RaiJp`yG1cNUx)kXzu~#~Si)&% z3t;#c5LLrGS>gsS1LRG4N}S{C@`mx_sSZBx`I~fnJLj>W&lBxu)M82TiOxDRM%1o$JzNJXEN;VxIiY9rq-{ z@C{zCx=Y%Lw#39>M)N^9O@%v0h5Ie6GU@_hPC+(kS*;j%8H-M5plmOyYb)Xa&%f;g z+eykM4xkiZ1##_4cjeBUSu}hS)a>sE%q)>pemfbhE7BEbr+AcoFY@z&PcXDBkDgX_U;8vMM3T9y+X7w7Vv z?eOGXg|6M~*(ldn^R6HC`rB~nKA*lfqUy?_uj?s>CM_XRBJ1et1UiH-mt~0&o3|Z% zxT^k*Wi#!jd(SDo@IC>evYlnjiwB1V}ceL7$lo!yz#QABo^k;KK6|4{vtWhWX&zF+4{1_%`dTuJy@YY$SJ@ju(aIFqNKC^i)8$BM zqAIk^zE<83#XYXZYiE<7eeVW24zN$mOm+;kdE8(yZ+Usn>YOMR$%|L?_=W~4X?&IE zJ~qHd^JluNQ1%o2nO<;wUXOL!gtEB_5D!@si((H+@)wlf$O?S!#qfloAfz!B3{Ir! z0of4`vSJFOg4r_pg)J@)SiYyBFJQ?(4{-UBqFOr>nGhL82V0IOoSY}xoV6*EW1Gs) zakXTMZH&=0^ApL5o4t{fe6upngIAyzSKBw6@~k0Gy|h}ITwE{n;OB4IYzP(RRzL+zU9YNi1_LKg}iiGrHkm#s$xQKyki zgMo)DAG?kl1dlI*6^$P+)(!_h=C_tlmf%TrYdhi09Gdky`8br8C6P=~33g>64gDI0 zE`$t2e8MC5p#jJm;nVW!0$Ar=P}+Rn8X@-64OE*_!dpI+PryJ+RWfl61xtmtc2^ z?l8pEC^1r-O2U&4^IxSIQpdwL_5i`2OB0PJ4scyK`>}c^Tcyr$Pv<4n*_lgU*LaVD z+wi3L{;z9`G!N?R=bU$!(Q&1suOqy{<1Tw{*P_9%ikDBuH+yj64{&NM7xM&0J}34X zt}S%m74VBlU27Q;u5rc0@xKIAzY5Y1+r@TpmRWi|GoUWC)!(_d3J3`V);!IU(dv}I zu6e-QQA0Fm1bmkY=n28rVQQ?H%)?URws%=2ZtU@eu&pxeYMpm`*L;Ev3gs9+^RWNP zclxr#Ir5q#{GR?>yw3psVPhQkQ|vx0DUxm22am~Re&fJz3a(6CK9UXvjRx*_*XG_0 zvrn-H;-(h9-Q+oJDju(aRMcRM@9Ohu9`)Q#^J5Kw~d+DVE4?b7CN~+-4 zeW35*OJrURduCcKQ_EZz&FSo5UK&oS&DFMUR%T=y06K%R`0RtW4AymD=7w@Dtmh1m`UA=Xz?Ger}TGKz}F0VfeLB=zZXDEu;D*US`N2PlGP^b$nw5S zq-@t)L-J~Kj3JpL_=R^f-@M}bJCO)fXrOJ_asoT1O0ssBX0>ShR}Fbb*)5QYk^y++ z=W7Mlv@8C(XjowIPfcy!x`CtoU$~qCpW=ARi&&CzPj$}{yc-B<8mzCbB{UYR zOZ7T+6L`x^D(Zu)iW)6>nkK~8^J}5Fd@hs1Yi)z7*k;zc2^dwEGW+SkN3k}VkVPnC z2|q6E7c~}QtwvBuH^WXwQL)SLYjB+#f)NkfKr!@I4SDopd$$j~3D@X2)I`WEp*s;c zH246P?dD$FS-u1`N}bafaHsmumDx+b)Of2hqSz$#yW3qOZ9Lu+4NuBBJ!g*rT_E?) z`0QLGluOKTmV1q{8JJOCpM#rk_n?|x!|Rhl2IS@&TBGw|#lfK!;TZb#UA!IA%kj4J zV3)DT0D<>iKu^_@EJS`V7rkWpsXKOA;|>SdsmX3o0Q3tf)NW}(`JpWV#re4^1qs~R z&Y?UuG?P^PJS>cFOZ-mhuQpyqkCKHxf?8s*Wh>S zho5D0{|Hgv(MiF{G$`McaPXZo|3Kns$pan3rL~OnYo!U+OH$C86ICYv>BB<gdmPQ%yp`@u z@DW;rbomm?9f4a3?$!f_N$$@4iK;2}KaN@YkLYH)cldW)>Yx{;{kJFUoqtF9%ye!$ zRcvCk6{ks)Qsgt8jMpt@o7o~Vc7qe0snfKGZX+`)Q$oYNHDXt~=qHWvuoY9pHxX18 z=bKSMKk9HNMirx=Q#!M>k%aQfks&Ug_oh9gOJ$s)tG)J7hK^i;1kt=wfBO_l2Wr8p z^d>Td4$I}$nK9ahEHv9d3s%?h3sHq#TIU68M8YnCmZFrp_4onHar)qT2yH#YE|zf1 zh-G9>xM7_PVKzpH(JS4?6=UWT{U7;!q);al?`=gVP^Ggj z-&RTX?}p#J7q-oaux{+4431ypn@ZQ~47fJ&E~bWg^O)Q%1blz(s5b)W6aPSS`ZZ>b zS5IyrysoY07+X>OTzx5xEv%HeYSyDplsGG@UBi%JZlou7bGY`Cg8lwW%t2ER*@ik*y z0S4FH_OwWyKM^*pr=Zd7ibk#*oJIfEn4F5X-Q_VnqVinFGaHu z{j39N+cM}JVNVCG)Al35dt{IY{Z#UyR+9G2O0+k%9kfT{^3#Eja~K(y>QTNAq~W6g zMj+S62$a;{kO#zJ^_q=wt@+WZLoA?E#9l1v>5!^ETx6NwdOmn8m$;vRmCFfEN-t)vZP%ij^92sN^>M(XS<0D zUnl=dyq5!}8ltV_4q<7uDspw!pZHl&zi8LGG=pQ^_k*%p|Cw`xwrxJDd6Cn{_gn$R zU3QQvpkm~J)xQn36>nD;#icfEbU8r0dt-72r=gi78qDM?moGgJNyo7}wE5fhm(? zasn%Z5`1{?95kkFOqdnP}_y=mjtBl2DgF816hWy z9^pp$AVU;zM4X`-v%vJL%pyFW_g4*e!87M4%ccrbXXfL!$E8CRRc%}U-7qV=K?mYGMeySqx;uykeq?f_h zisNtk{gn{ywCLkI`!zx88W|NF);el)wbS1xL<}-2+I88qA}Enf)Sd_q$-*t`rv{Dj zX#Z!(#D202LXx7(WQcalh}3ONp#xJ>(CD*XW!lQ!n8K{*KDJy8-^c~j3WHcqZ>LL_ z)%s4=D7XzqzL$NQ=r3U5nk-7xrM-6yCn zd^3hrQJm_R0WZ*xdJY)btaExbH0j4x{^RCKckn@NIPSX+Y8I|Wv0FOxjBo;+t!&X< zc)eL4n!8K_7Gkpy&^`Q8`%x0GY~Cyb$&qwTeGe31pl&%&JEMr5`6= z^$-glFcgvlx=NGy?O4oFbVQhn>RjCeeRKSkvrui~3GEw$JbP&w4=oLn#@u3(qn8|` zU%dhE>KYhp0a5t5tB;##nylA62V3cU)$@GK!=A>;%s1PFN$%>bP*nHo7$B4SirZ&P zpE;Usmq($&9EJw-fGn3pcRbzomjDMnVgmcFGUinDr;q5f(hZ%>*W`GI#0;o z;4)9AFV=*z5a2mRPUUsf*Ez$Y-B<%mI&-T|tlF~x0~T6~fJULC`evyk;%3gkaX|vL zptC*$K~?Ofurm~2Lx3dmd2nw~6CB@otN1u0SQ5n3`qtwV($7QFYH34M_xj-=+g8cR zAFCP6L;`TrXpm=)5Vnx*McX>uIXTK#KF}erZbOC^zY|f6>=10@bb@!h`rOONG{KmG zYYBM2-Ed27AdfK}JI(EU$MS@e{_Qe^(&s2U1&r=(a_*C9>Tp?WKqOeW@Yraa7XTM0 z($`zH<1QRZ8GoPEn@NlS+=hQR#ga3(j`V%jWtybBWqz_NTkitl(}`jAO;SI2t!!+Q zktS|i;i5Hz0nYl&PaY1}X5ZE*A%nmXm?@%i9U+@IXJk0z@`Wb;9FL|@?kx#!e$eqhPh5hiU| ziE5r1$o@#Xr0z?%)7+b3n{?ZEO24<-K%DF{Rh+>_=&AtDP z=DO9aF%hC$sgIshx@`FMPfN_j}oWzb5SNWMvV%J!Lv6{I=R1^dn`zLTG{sk ze_KPrD|6TSLs3t&_zD7wkSgfbAN&#cHt5+5Y!*)Hw@+hG2q$bsG}bRy$8xt?AFZ@sY39tX zn5PfY6d%ZFD4(yG(doGY8njlQNN(FHnsbsoZ}!R9t20y7f*2LCmlzwFWA`~%us?H< z6fBD<>=*1kXRZQ^8_p#`)8@Im?=Nu@+}@13t%1cUQ+Gt(5Tc9t85HyNfWb%zHr;N{ zwz`#Hj#ewbD2LkgDqFxj(1}6|lRoQ4uG3hM)gDBaWeSkgh2B~`OlCeSeSPFj^6M4U z_CxQF9Y@)WjXWRvou6}p`rU<>Nv6q~ zY&&gpF4Kf53>%ozwtlac`ueQnjxxUl5fip<&nFR$-AqqVJtmb{v^j3^4QKze{C&j_ z&eF0vC(Dp?Ud-gdnDAz^#LyeStL@SwLp2bkCTs$2ngxX%iK+$J>Dt*aj3nry0OrRh zQS>D}q@^&sPrqHYZf@r6)j#=K$BzrbyLncq)cv^CN`-1(Gc(NkflI4Tf_Lo>3@e*l z%q3xTAQW2m`LnIkqq6IQA3`e4t4nY72{!Ov3Zfiq7Dv&+JYq1?_1ZseBs|3Rc6{$~DIM`uky{*Ztlv!}P*BhWWmQSJRCH{K`(A z!d*7P$pSm-s6{8m;r8CyNYxh|Ciio*v$K^O<}UY3sxYFc{$8->%jyu#Yb|gt1E~9| zSs#i2VpG1U@`t~d4+gx`T6s2ynIKMT1^e9NF0br3|HG(c=U<;TFl{Yz;wza=4xELI z$dOBCh=c5A(%IC8Z~+Rs=(5CS)9RH)Ww7SLIuFb6W-k+2rHbYKVZmSs^aI&7K+XvB z-1DOgYf<^3P<-H!tHhbd73_Mm`Cu5eA)LU-Z=mzJ&}H(6)($z&5C(QIe>V^VwGr_= zG84Zr=BLQ9f$!|1Fikv*!xOH)ut++6bOen>+rLs*d@K%(Lm?@mFmJ#i_w*x34Jhg zI!7}s=z4`NziDR+m3-?=<1A>c;wt_M_#5FicmuVWra`-oyxyP5pH708x4Yg-n}n-X zJg(Y9&xbG7Gb5BL`uCS~jJ9p>1+xTH5$8K8S(V4#v)95E)sv&#%RXb`Og;VBv zmQ(+-kZG;(`K)oH)>p})5&5Myy}sHZi%+LtZ#hIDBdXVy=&w3-gT5X_x{3OT@npZ% zsc4=T5zE0Mo$9~i-Bi_a?{uzT0#c7BYPv~nZvwSHG@~{vSd)smc9<4V#=ykN@J<%q zuRIL3lIpC9+opo&O(d>Woj;7|qj=Xsx(oOeyb`zf0B0oYsANZJ*N?FgIIrn?nqLcs zl2dl#WAcos{CfF6=h!-cVgj@N_|@E~P8$T+Vx!f(8H4K^WRy#m$9*UpWM;lxR~{|l zY7v8cC|Tu6Z*rw`YD+8nmeTI}T*p!;5f&D0_3ZOvec4}js;k#H%>q{En@&4k623cWj5s#Pdtvjsf@&6DIKh|C7$VD8sex!H%E&rm zwmyZ`bkdHrbcD8RO0}#vftmRPM^&hnu}`C1-WF*yeF`7w1(iX$SJYWRNiL=Tot5P zE$-1Sq{HC+xfyaX&QQVKSa=oGA~#Xqk%qraF{$^B&S2ZPY{}GD#0Im|?Vl>|2A61r zBfI(>5=k&W4;R@o4L%zDq%buq7_|C)%Pz{XF>mb6O7HzGED> zL7`tzLK(tpprdL0wYuwvQXV^pRmAKD6o=wJ|Cx|b%U1z!|5^ZEB$DleDy(4qiuKcp zLlfvdx~@nA$vCz2q#m=+>&$>w^VWnqIz;6*^ky4IeLLdu8&x+vhS{j3XS3B@FF>Cr zlG#h%m{jSaWPCyPyRoK^uh^l^?!?buzDxksuWWB!1)woD|J=|0xzvT8P$R3G#&Yu_ zn7b@*b4J5c`WBbTc)zO_$D5)vz}41l6{j-fN8!Ui{V%IZqGGXY!T2_q&ozT-#{$Zx zBG1^&%UBEOn}<1EOr}FGVKy7+l%3&ZFAn|ZTPrOz?H>=}9jW);!1$tcpj7?ul-nC6 zB{o}opx1yB7+{3x4c{dTxHhJyx_Kr=`fS7>mSM|f((J*#kqy7%h_=5YN4b+uJlVzC ze8BL#>!>-zli!+t|1-JNJs%$NqZmhiYfZ0f7QSnoonzPa7`L8P-Y~=1TV*UhPXV;_ z4vfy*e=E90DPmMn-9=o%A-!9^g z#gWt$r%4Kb-=Of596gu2bj+oW|cGb80}7vtJXH1dOpe8 zzGybM`jgK# z3RF8mi11S(NLdqYxU=ljS=W8&#sL-HLM^TM8^@KBpBMEY*uSGpFO(ToOB$A1xXR7# z!|IW#&~8W5hLWYYdOrLzCuYR0FdD%?I)J|dW2uD3bJ&0OrDHjdIbNJ?*uRhViGN7E zYokSC6Dpm6|H#cu8oJ;=9C!f1-0Ezienx8O(x8GH}H_LusPhD3$_Y&dUrS8dYuGMxA z`bM{gis*U$LV*Tr;5&m&4L|tj*>J{cgAW;&lPgC;Ij_}x<`x9KfJnjsdoP%ob6(%e za(m>OU1al(kcdzB=5lOLNq$`RC^iHYwEua~v`Ui~`D87cDRg660A)09n5?D@@}K!N z0)0B?>OZ12kqhn8Jbi6*Cb@&EyfH*@S9);#^mC&*g(u1%ITB9{i#Zk<*r%7O)sp}V zFa#NEgoGOGg^l3DKq{F%Mdnt-mZ(GJ{2d0ejP0mLd93AjHMeY0zsOJ!1d-_+E9m!# zvy&N~U>brmpO`JEr}=|1_UgV$jJwa=$Ad`+>}R5$wv+Bdq1dsrtt%+P&6;TdO{`<6 zHdm)7!oEiU7rNhb7qsU4^Oq``(L{I|f$HGs`F@#q>jJ<1x&ECope7rxhZg|G#-9J5 zu~8En)DgySZ6T5&(QaNyGr1O@Qdi;_Ys2%G$ysEvxWpVwWvEv$TSDCLvh_pSsC0$W zGKs=+wAF0Q`}u;bFI$x-QZzw!m*E^)Nf5IGE5$OqrZA`+3nji8vN?I z8Qs0-H^8n;c-3Oj*`{N1V#4Oth<=v&eZiLDvtF6O`!o9dqHX`<;)l-{EFV| z9Isx|pM@I`y3lFTZq-Q(2x50{#I^*kJCn4Bok9$i{4+Z93=G?g+MCOqu|x zzQw>s{d#+|@VEMnBZI$BU8-;4TB7yrcnlA0s0y$7E+SDE5@4p+6({Sih2787$$9XT zWmJVcg5eP->9V4P2fv*DH%mWc?wQ`)2hPyJ8FLZ~*|Duc6r_)fNXx83qCb2(C?{S1 zGr})j{Y!TDO1V@7s+<5jHb-rBm^D(?gdp!a>OvIgGgG~o-I%U_t^V&s1f_;osrWI_ z|LCTY>K>Ik*fji&|4Alt)hx&aJ!nfcS!M1^s{4$-jm1r4`T<+-ymISVyc#^lDA9rx_Ie9@b3e(LN{E!411{za{Nr#wj#w>j%7&}oiFE34 zNH2fW+5pxjNH?NBafN!3zNyl~ShKP9G!E;iBPzH`3w0(Ub>YT}y&lHD=$-E1uXw6D zP_+m1c89++-neH^QaZV&ed3m@i~0{1_R^T1~yzC3^d^rOJ< zY4JlO(`!)%@9v_iI&IeV)~+ZUhmP$!q(~mLWZs2z>JJ9MGV4~k5|0u&%5R;>F*(|Z z1rE`kz32Q|+1aW|fjQ-lem*vDdqbuG$+yI&dicRmi6pbfl6~bX_lb_OTwdvFh!a5x z!y&yVL|`kU%G;WU>H#lpNI)GknfH8*H2Q(&r^SXlh68mKZ_MHP9|M*&j>7$S=VQtu z8nQboe@YJRo3Q zaOmHde8-8>ze$>_#WHk{4ViSJs8OFQsn(U}b=QNLflS5&B3DsiOBz*=)zm{+ra6Rk zG=TH}ygfgytqf!I4VfBUDP6aUM=R*wU_;|$Xsh%&S;UsW{A!X}x)k(f9zP zi&{+z(MC@(7c<(G4f=m5%B1h?wABApE7A?VUR10~1U!j~d*vPrH>l;yM+W3Nj-{oA zC%w#-lYbyr`6|icp$s#`3uvCRxm`|l83T5B$K^JxN4vbmEd1!Lfi|!GCw%4W%4j&v zWJrgnJ+JMs;=pEO91)RN-?QY{M-;I;XBPS@u{o2$Ikw2r~LnU0WPOyHWFkgryZs3^$?WUrl&h=fYXYEu_u3* znk`js6IZ05!-ZZqZd&pbeCnV#5FyknI%j)Qd}FJpuvqi zO&6;SXm-h}JuDpv&l)3qY@Y<=o|GTPVKhSwjqlM+sIq+9V?1dHFQ-lPb0ClpmUz?Gn5=ar1VkdG5(?vp}9o#feG@UL+%%3#BmG@IO1x9>K@h{6lw`&h`-Ghm`vfK~v|0v} z`q%Q8&fCpm`^x?kZ7HW)A+~OK-872PGPqgA_qLPClu}aPJteYrq^};; z?toT_1ku1fMQ8mTp5tU%2#7wNNq|+oeNDPs+evdL2Js47DSb1z@G`mHE<5D9=9QZ_ zScpK7hM@O$*!+7Db4bzKL?ZdE5$(r#D&gqk{y4!v%RlD~+C(J@%MBSBNn^`vzsEjo zX7K#3oIFgs``Mp|mMa5}p=f+tD(pjQ}7u<7fkbc~KpRZPF=j|wn6|JMw zhKo$1M9FiQ=f`icvfI%Rx@SR$bMHZ$E=`;^dI-NVj7FSd4aaSa#Gg*bRB+^%5{xE@ z0jbD}*{_G^Hj5$jywNJs@E?whXy|JrT-(vRMw-dn<3x&ubxsoT6g)CFR0hUSZWXCN z4}QdxAKx+L_Jpc)ACf=rhZ-D-)9VOv1{5Z<2^X8chw1FtDB4_u}k?F3C_@ebC)HM65|(KOyN3yFzvZ4TVZf8z6s_z~8G%xsRQoNVvjtr2-1yZXRM z^H8hoKCYBsUwhb=k-6=rz}0nyM)%jort_)puKu%?&_ssx2}TIDWB=I$twJCM28M65 zsg=rS1DLe!Moh{RIvUs?XX^*SRUiT526!0X!m3NfmMsFUn&9gBqr&OH8S<>q_hG5{ zK&Anyyq*!U@naVnc1}0~7nb2cu=FcjE1kjy3xVL}D|9mdw5fIZ^fqkk>GI{&zr8*r zwN8i>dt4otVG#O8uTNzp*6sP2Ex%4?n#J4+wr5TPUb%b0e^7?rT$f`yILiv}d`z!e zY^ruR5^A_^Bhf-{xGrB*N`|p=51Qm9X*J2K`xntve{%8S94v}#sg;zmO)L7>`KDZv zUdAxC%%Q8K*Ut^bz>hm-F+yX&=!pb-N0AS~ytJrRAX1-!Fm07}7gX1tmtXOkdy7M3 zhqU?nRVCO>)1iC0c0k5Mp;w#o^3Syd@BBL!Cy_>+zi21WU)p7t_WMw8G9KOeinHjP zg%tr(g)m%x>%Z@H220dYWQuTd3=;cROt&f3WX@6!`Mc`CTqL{89NJxz1rdmvtoM$u zT(sF0uwsOeeCyOnHp@ugO1UGWU_-Ssn(U3$(|;3kz|xg4Z$**{1OqVmI4dq}E5sUv zglTQzR>FMd4b7hiGZySxZ zntU!v+uFT=qD~?>*fLO!DEK{8wQE7TZME+eXXW+9g(uWE=xB-#4ciDw#A*n+Z4mFj~G z$q`h<%NI|4J~h{%SVPGRu{uiBRWrH&S;yYG`si0{6`df!%~5o%LS`C`wKL~I>&a?r z!|zHE6_U{I{<;!vBJGHgNvvS}tkcbL@N2q|!BLP7y@FzfTln1n7~$32Uw9W%zujG<)zj4RQI{(_n6tyz)l2Z^}uA?6v!M8RX7p6qB-Z5H( z)QU^BHa0PFv3kBmwp60tPr7;lMRd#R6=e{NpYDe2kn_sC0J*eLZ2v?CW?grE{Tq$%oNOeXoqo`KB+v zXkMVHq4JVBed^oY(KpXvxP}{QO<+xihv)Db6cKnZQ6&Lm3nD*2uEVuOu4TVmlzHQM zNF#uJQgtk@U7fM3|7~4KS4Cv#26>39L+EkL3PL@1GgS~kd|7sh;YGA%{I;7?zk6^+*n({;DRbaT|c0t{goj23Er&*jVlRmiPt9 zy?cxz|8X$_@_}C>;8ttyhcHGAO=LhCo$d4{1Q$ahd-Bz(A^sPJi!Q~fc0@x=rXb0_ zmBGKh0q?=rKVPg~Rmd;jA1<;m{eJHtrALFjUtdbEfB1SA zgl53d?TyQIbT&rdcqDB&(r|r?<=H~$(llY2W;I9Az&J*T&RzHDL2icWKGyT5;)$X^ zxuW1e8r|ab9>E)U9|;I+-a?CdZ}wM$hVMR?)bwBLG$jvOH_awK@|{G-q2hC&nU8aH z$#Ij4_J51v)2XNmYuz;EcpsE!K0VOgr*CL3k$s^WL&S4UOuwr=4qjB!rKQBBwwFL& zf14go++$b+k*P+sp3g3F5sGZ12gsVVb+iv$0rMW>R_;UikDId+nc+tvC~; z5$?C!0Z|LlRBk<^TPDX+jarpp?147}GX)f$!};$RrE6#$LZ9C!Clbdzk;$;2L3i!> zMUoR6qy1B;&ZF`Qo|M9>3lhJe+UYwn{4;=1vm-y;56DAP@qJG^ORBEbRomyDy;&aR z@M>>fWa`Wf{6)-c9-Xn0WpFywkm1rH0{S#9omx%AJ8NGU-RWvP&NGGb3lt_p30g*4SZN^` z@|u3>t5<%(N%+wUdItC|nS)YLmcd~KMedS=lH!92f4mp-eNeeMP4;=VM``k7U{ zHd-CR@|iA)>BA>fpxmw~>e9b4XOg&)Fc&EKEt@Op^UPk6%9P2WVp7pjbHw2ArRh@M55}~fE@E%Vn81`+PNsRmx_e@tB0&~ zFjR~sT=+Qg6s-y2MFUcv5iXl~vuL1xgn_}rM zY53*0Q=K4hQ$l#<=70vZTTJgMP7^Bpu(tk`oDg}1y6iUE;=&>CpU`bMeQTvOSd&*Z zq$%iiPc1{WDHrDw6Ul>LWAx3r+`wNyG~DSIv&qd#`rYlq0|a%7{O6~H9$mXE&AHSQ zaL@-T!}*I_$wvPw-*pm^yv1@D=ML7R9VEA~bLMPx+TF>O%5Eh8z+WN&Gsd4}Ta zR1#i`VMkURs9kSuY8-Q@$gCcFm)x-}D3+&sQ@s)T_Low*opb5)xjuNhS5%4)9uwxt z)GHdZHI4v?*3whLF=`aW-hYXD*Q9K{2(H${Q-If$j$D&F;jdtngm*f@+R29b-nOjj z<4%Z@mB$3VxFLSrB3ufyWW|aY0;pr#@Fx_iR#{uYN5M;5#A8e3G0-PuosbDIXc|0l zD<6AVfg$V_GLQ6nN)_@dJ+gK_V%)tOh5iLO*$^30K^X(@Az7p869&zR5?#tR*Ys)X zEJkGgFf3bi5U%kRUZQJmY@C{&)&u&%7Nei^4GI$VV9k=(u)`Ksu~ z&YXcD6`G&vU36R(5IL-_c!s657{UE&44d(!9}qsV1A=3DjoaHK-#d~EP>l`?rE}L` z!!&*E*aNtAu2*%Y5!>KeCVA6fWwW_w6`?QL*1SnW`qvuDk-?+)bz<5TZ_VH3sgAre z?t6>_`4#)?O}Rk!{5w)EZO-k1YN~XWQmm1|vznd($FHe+X|xG5CFF8LP@9koc=KY0(xjLYaXRo(MNx_egs zBmwyvbFEVv&~TzQ0Aq%aMNNaqJ3vJ;DA8VOY7;vVp#5B!pdQJe0lnNE^gaWdt0f6BhPU%4%7Cg_>QHKA%w+ zGs0qOM8oILwl5?KecgX^0FRrG2A zYW;rIt!o=wcMie%_S>C`Z;;vfsRbeD!GC;mT8$%z*fxIYIvZzg%?|(c09xDzGc4<-l?ZWtBbUhTJZjp z-D=dyk6FJ^vSg||fzTEkl$*@>=dXnO>EwN_06_9@SR$7qSuXA=Ff5gG#&sD&aiTT< zl~cL%?83zMz@74KCcA*HYL_9rS4#k$qT18qH)W1a*1?bau~=;aCX%(?gCised>##A zjAAu9TQ^@ySSAdBALFpI4F32_YS zFezVpzQuP7UwUrAaTui~ZCpFA>zD`+pdBfW<1v2~%%ActVP=E?qHQGCz0wo*q1jk5 z$l|7hj&zW1K0y84*&X${4NZ{d5(rM`2ye`nU}u3EZjx(l^8Le6mdR*BctVyUCIY8@ zgXtLduvMFSdZx;7D-@FLMoxZlKV8*ZI1>ST=pfr%egm*EuMrGv`}YUp@IaE6%iRS^ znn)qm%sL)`xKp#xoC~VJ2f%2_YsKz5+s8byhEV(CC7AS&RKJru8#wbr5&W?g;u31R z)~PkE-G%@uFbBmu4Ms*ti1z^!)*o_GNhFp9gr$Xne zqgk5yF1BuOtam!d4uxIHy!mSg7#KEif)dZVwWqfdlboM~RZ%98g@fB|3OvwmKPu?k z5*eTvhop&@lQcLq)@x@^FetBea%gx|zyxa6@eX1Cqh;S zI~~x(Jlgny6OOC$Q{PI98Z>`dGqG878gl|h)NCkPnpT;D#RzFYbL|s}b*^9WFO9l6 zXcfM-RpuP6L{-I2%;$!_Z_qBTPE?FBL<@1)9d%mo2nXnpt({#l-J|TW2UD6+GFcoo zFl-DMvi9HAu*N{j!HsRY4)xs0s01L6)Qq_Q^q~V&PmaklRIW_LFn9iyW~!;tOgzaJ zU2S&CV&d1K#$m$@M6{kV@}!bkKLqH+A>4?eIvL9I+szx{Jke_L(PeLea+=T z|51UmJfDo|1j6T=jF@cZFS9c<(H$!1>yc+g1x=LgY&*#K0vAfnNoTnHoGTF>vRiTU z=(Wy}5&O}vUcv0WnF@nPLJ@Q7AAX~!OvH+AGWZdnnn{#dZl>U@_93lco%@G|aN=&^ zVP%(&3-T;n;_euS3pjH9vyo~ULP77UC2*Om%AfB2N9TFMgGSpP;WL;s>RB5OYVrdL0ewHSX@_bO>dnA)1k_OSo``0B3R=JWj5=h%qW32x}ql_+8#F8ttf>z_34b=%L5 zH8tF-wYmy;>y8E>-uYSPX6L^dGzu?yQWuQ48uU+6fRY-z8alyNd&mX-Qg z?Tx1nMErRhju51aiQk2&+hzARb=@w7Z6h-fDD z2!LP4MeE9vFgM1YqglNQtdVD#Y8NfO6SnW2P5Y&aywPfCU3J|+$0q#g7%b@Z{9eO? z>iq1w4YKA4-1@?24&kkyCGQdA3Lj<@33U- zWGW1y^x8L8U-l(C?6>6c)6w2>=WtgZV}=PM#%{vb;to0#Y{g>}Y5Ko*g14w-T9R;Z zZ5IjH40cBT4e4HwvxjvHa;=9=B%Pq>PiqfWbyM}*>+lEH1rl7VAyb^r6*M*kw<3UW z<1=O7P`+(6L5(21bB%R=!ZEX_;YDCK{o?ERG#c9c#BFK0Bl$GA-K@ICTsyyUJ+X+o zw9w-St)ADp_8InmB2%x)D*r!PmLIEVjAP|oQeBc<)%xi3+I3>U|NP!8sooOD)4519 zt?2egVC?Ui52)3EG=F-=WN0;{03&H`P*(5gq6spfu?HoK3Tr%E6W{FpYreLd2Q|hX z#uIz)tLD_R=4n@@5;s#t_Z+JafLs;DL&$d*l-t6_`R!Bs(=Q2TF%>u2s0VN(xvIUj zOtr__ek}|Wc}sJxMA|1rEh`vT)orR721M0P%Z#;ZjlgPq2Axl&_~iRj4k6|a;u7wh z=Id2Jd?lKE&u{_7Tl0dM67@t$DZG?Kj8#^QBTj2(H;nN9FY~qR#>vF5@0XibEIp3M z#BY1xLc*Q`O!LkfnZB|3BbQnkU>o3&uxaP(1|h`iQl49$fOK|DW-5i~S5N66Hp``m zde&0XUn7Na@b6n@)$)#B3iL3CjSkg`pGvHDl=9qES089#jhJaA0*J8?3^)ki%IgHC zBr9w4mF{bG;7`38D`ca!wG|7JovKqBH}KD|Jy9g}uU@_CaNekRKbHGv)TBKMtNpfQ zh1?{0!%v3||5*3)xCb{kx5NwQYnC{24?(|%haUAJFBD6#ehubGYKVdxmz3DAT7mG7 zJPRa($nQ?KhSvo~Vw(iQEvez#V@n@`<-{pAsb2w%ZOo?0sLt<8yf}r#_=5*tU55!g z@9{F_&7U!*fP1lnZU52AKyU@|lP96gs^K~GZ9$$e-JhY|FSGS0uB>$(hK0i??D3+7 z=n$S2{~d~OKY7|k<{52*m2+5?8S17oIWX~=mB_gT+jCjt$Sw1l%r_73f7-XPOc<+6q7jpE(;4FPV@yeiKqub$1Wmjda%*8zA>oYJ-k@V{WM)O!FlEOq#dW|gN_ zX>EA24*e4+BP&;*2^85L((C(_Qgtq>Ubl|7?Gxl}8J}iY_kNO;w>IEo-P$wrBE&JS zBQX+kXG%KVu<%domlriPhd-m|AHz1`7-G;y^sT1<}r;9#U`uP!YOL(UeH#HUr(!UZGq3Z<_6AHs|sf)MQotZriUMS|Apnf2Pgou8 zhK?Tp07NI(0jnd;ILH9e;Lk`OtM90;DCPr_)b5=#sVH@d?soFU7=H(L%B)C-si>%U zt6xZrse;7!Wi!)h9;6UBCM&nccJ^CE8h$9QZ`8MG8E}sCK_j;ry5w7IEowx6A40eX z-<_2TdPKSO$ndt;5j6`=gEM35ZPL2+Ufd%7cv}js{xnGv&n+N(BRMYjrS7wl2m{NH zt5>n`Kj6Qe@3iMTG4r#9fz&yf2HB)7?!vc95we%|UV0oLXmx;jYfzBN8l=UTO?w%3 zf32yOW=8RMY>ar*f2BV_4WBiYb42{+-=+WE(d%W%Ig!^gZt|eO%o;S*nQCJ&{m{G5 zoyNJjUiw#+LW*l&0I-!rE>$K0wDwP8zvO~GSDb%9_pevc*UG4C-Qe65u^7y#o0xq! zF{`$IU@ZO8#R@zxBi;eq2mdkRk_)2!v|i%^#=d_EpP=*1<*Qqa^kzUifTIqtMIWcV z&yg0X|EwouV>`OiilGZ(yKg3T<&e?tq-01r$gZozEib4NaL~*@i6xZMoBB6%e(me& z5Vb}zXzIDSCe@P0$~shpbm5y)e=cS~nRtpPXEY6|&sZa=fR)3mVx#r7$?)TLCCnDsEil@Z@pGN?=cMFIbcy8QNiwes)sPqIBR-)3|X zKSxc2UE`JjL=ATAowt>1O%9W|J^IUKe>c?nTM4eG*#jM$j6B{LVJ^M9UrZQ6`<)vd zY}4FTx#6QBgJUJpxAHjbW}4+!6zu-)exe$|(SoF^*c`R9k@)G1W6&OeY@ol#)&TL^ zH+};&UH#66J>wr{TiWSd)b5H&Pa*809ZnuYkQCJ1eA#^4$l% z4{2(}@V@^1@2ZyVb~>SlY&{jxaR%Uuw&Ho`J{^<$!qHV9kxK1Z*|162BFOZ*%F(x*3+<~tcIM^9L~Ph z<~&HUY1qu?m#<`4K2jg2NXm_oaHV zVs25pAG((_Xzr3fkZ?K~tYSU7+_17p{mX}&^2<@DRkhn6wP4eF9RmhV#D<<--jGAa z4)Z=F-J=FR5O{PKY{{I8H_+Nxp%l5L2)%tx|EvA&z7~so-4fU=xf;_cCj8B~%t6V8 zeQ9z(=M4|x)r?&yAE#4NK#`MyVND8pi|5e7Le2gs+dT`h02;XKvs&MhrDx@887O*J zS^BIUDf=ud`-b#x8rz+Z#NO&}!Nc8(;=#Ff8l0lQQC1dRN{aJesPhZKBFWX2ZOax; zx*#%Pu+M7gnJdjc`71w-C}HNW*2mu_V#oa#WKXsDcr2jUXvivfTVk9polb+M3qA|| zr&x9El5SlZ-2oD+6ny5i4mH?(wNyrUHc7Mc{|=R-Th_98n8Pun*of_Tq8b#zB7(n2 zvJ*b?SUj|(F=#oulTE^{0hI;GQbi{}V~y0jIb3UV49Z;Y7_Yi3N@>k2na?aQ;vi%ojh7&RnoyaAs0*G-CSFmT*yAyHESoW!tI2iRB8~M4boY=3+$`d8J))(zMapf1s z+Og-`S~i!98mUsm9k=Ls&N1wMfcUPyHDOB&y65Ou6hJ3}IZAIFUsf5| zxl_TA<}K(}i6R6-T#UYyMkOY7qx9wseU(8B-&j<#ZEiTS=?YJ*`1kOU@XoICIEGm$ zbc=5rE*gA*W8pmu=;ic5h+St4x+>YGM?E!Myi>7TAZulL?Wb{Z^vw?m`Vdso#ry`V ztf}&4uMR9PlW*sIrsytZxUTQOA+oj}QrKYzjyVzz#t~@--P)$FgOh^4dmjk(PMgdM z%-5j8=m(DRolUqZ=!_Jf+Ti@+lWnB6O1-dRfuZ^Tpp(|Mn0k$Yng^FbjjxdnkUz1N zw~Il2IB7_s4PnV@Ew(A?ryUkM5dj}wv9VYYjR2{~LvES75H|Y~q zD(YCxmV3&(Dh5?HqW)X7VRj54Lg3btDqaQL1jj?brmm%aM@XMh!jFR6KyT6n=o-FJ zO}TdM@K0897)whHS?fJq#oeDtC21;`s6Xp$8hvj!O3SbJvxo7^@@T!Co!qnte674k z%5P0R7OmzG$^Qu^pSky3=_zh|MZnInaEOBA6unoa_bke~Kdo<_TD8zqA-Q~EYtFSE zvwTPV)2POQjPY9xH0tK@1K0oTqi=CeSSfd`Hnt^yurOv|pJXAGk4FrBo*HdTY-Fr= z0oL6HfIH=ob=lX*WAjg(rg}Rk7Vc~+0xytF^iYMQH`GhX+px#r>&~~j_Npc!)INnT$|h%_luAf|3?KqjJO!gQ)7 z;m->(pBAaa>ZJxi^-@|aptNrd{`oXEp0~puSOUMQ>MxOy_k~`;W4qglSx9AxR@!L) z1Y{uL_P^unI9dKh2igmyX{|$YtoR`5fM9S|Ul0N+GHujx5KK)Fo6+{Yr=#(S%zgeV z+$g#iQ{ycTQS~ftOX$#_pF!4XQ4@70iffbDIK52kL_Q_(Pm6O3c58Ke}z*em?{u9U+VJ+_GYuJrR|1}&1JC(S`HP1oOO*6U;2-%;}o zc~Qjm@&NuB6bYS9>`AwA0c-l3nMQGP{;pxy+5C@Rdka$4PT*Ofo-{dvb;=!Tq_fs2_^`RIA=)o;t?*$VZt$q z5176irEuvp1O*7fN&18jjx)8owB!R0JiiRuN#mky`-5q0|g*)<9Ympj1XvyB<$J@P{RASG)RI6Du>&)(B zMqbCU7))s!o1%+1CV>(}UyCq5`f^u$kG@ZgIl9OEToX|XQ~~P12cq=|wK-`Ti!ouo zn3SNgjQ%4~;w>oP*B(V{Bj{rq=`TzhY<404LhxSMncLQ}`}y}G1^H;DClp+0I`;Qf z-4DbXk>wv8urGxk!^Hs5^sQBX6Hs*~vd^g{9r>5ec6R!m8`?mz!u-Z%ZNuCYqH`qV z1~e5y-^Fu!9IFEAm|&}dLE7VT-+uG{^gtEfw#J`69b9hQHPojw9BblpEN2+D&z#UA zX&9IJ-a2IsO@Z2_!yJ?Ua#3l2e>B)@*VFzDX>4@a8Q!{=wu9Ph&!pbOb-d!mv~us# z%jdO@57LYGU=59NYwzWk>Y%Off6BvNvW_y)70Yi){8+WHHgkO@S$t2!@h7_)w|jJ? zJ_$98^D%dGR5_Yc+=Cm9-1s-`rBBt&*pr0BinEx7J;D}c5zYL~;LV__&0yg8+lNw8 zWAb57I}gYEP{f-Ef_=RP*xr4T*l9fNQy@s^*nc(_q&Rzq2?VFCzWR3MhnyqqLyy$| z{n+d*8sKBWSBD7gLj5^}=i3*Jjv7V6NUH~O<82lMUi$r;{23O9;W9YJA%KR1W?jss zF5=1T){bpCDLv&GLxars3(W@D!D(4kjXWlUI}8#se+7SNHJ)#jx}j$_$mIytg-c$& zNkVh8Kyi#j%|NF&rDUNhE@u72USRsZk9+YIi7MI>6&;|Z(}4zB-EFo#4n4L*BlA{y z2Mz~)V36azLU{G=`gK)o@zv(m_k@fQF=b1-G!Pi7SBSM#B7oMi{nP&A@>z#np?w># zQAnewK@=s%hZP3Ko2!dQ7%<^VtkSfn(&#|T_6D9T$2akOE7X>@e+5g2NUz&4!$GWA zZa2w2-AoaGR(C9ezQ7N+qrD^y9QLu1CIwt_x!InkXIP&?IPtdd4sXWx14NBJu(mE{ zNoFIuXFR#;t?8rHsaE}3vy24B6Z!|SNFy~XpN>Dy##AHgQ$F%{e&^cN+ttBgP3P2Q zOSX~R=}M9?!Wty20&{l};-;YUVOpu`U-~7E4kCNxTBfD*SXGLt~ z`Nuz~wXEDb=5B7S!3JzXNFD3i!_8xZWVQ7iMe1bhR$+e9CbAznr`0pNzb^c-fvLLT z?r9(z;6D>=p)m`|#~b%8gofKvihpXUauiLUnc}b6aJDs}`>Pdp!+}#1e5d(oYUO7Q z%}dQjLC3y`X&pJ~A~I4AdplkZdb>9|@6VS#TL10{rTiNOU0g%N67{JM=nlkh970FY zhP%+LuQoJ-qL}yC$QwYW&wp7y_dr2l#%7}R#iN^#8wyAUv%El!qwk81)8f%Jl}=Vp zP8B@d7rOWVuId!B-D5_jSbTv>|U>n5b;#I2<`F1l`+4u!O!W-zo)soaINfCLu~m3}c~uB`V%8!>%CdI2HkWaCF=Y z#6y2c(BXuF&$lELlE7-2{y2Uo@;4{k+plzjO2A2J&rN|{N*n{DYVS_6D=}>XQVLwo z<>xBE-fDTL9kyefVYcfD8&&bIMm`$E*-FUz0ztMl!sfRlI z0esg|iUM@5;hL))Ab#E#YIv7irKQtu(B>3mSf;NE!Ld|i4D~y+v+~_D%Y7_N@QxRG z(k18vuj8XzzVy>S43Xy2ge1u#uUa6r>Znoh57SiaFph{uKL;82-?ho#hx!UnEb_&p z*0xK|oZ-7fq5#!!R75ROk`>mnxNa|PpX}zk?;zx%dhoDM>xJyK=z(4sa7MNHyu{s! zD6;-knzYe&^Z(jBf%>GvA-5Fse7~sUU(|2XPOw%mEW$x0qeD66%#=w}m4J8?TI!E7 zWLavyNhM_&lX6p`N6}tmJ8!f{N8=X|Wk6iij6%`B_DLH=QX3bXF8tn{($bFQgI_?l z#=DFFu^Dw&V-QjNz)HI#*J}PrOrGdR{m6O&A@AG5Eg|LD!{ebR4cWVOT^=(HVF=;H zrRW;3BXOfcy5|n7n_mbx4sGWbJ^WoVLomsYF?)zkrJZj4A<8 zd?&-F%)|2T1u8=BA`jWms{*qtNDEFYlhZugj}Jy0HTAMTNLn%du8;GzLh2HJl5YN< zByFs^Gos5-c@TUtO}uLa`+ov>uz8BuryG?kSNT&7?n?HJFMsZ2DzD%QGX8z?p<1vPz>^c>?Uzp&i^%u70~%5w-!AvT&4OZDUD4yX-_ zeiKbs9Y@;8U;{e~94_yjG_D+^0#Rw(QZ9u{92*$t_c^5eb`0><{* zdJSefIzupR0HL}A!5x<|hg?@oKHMFcShBx8P@pTek0p~-FRh_kLp1XN=;`u3kF0>& zjr=J2oJyo16Elx1LgI^Zq#g$m2mrQIQS! zF0Y@AYZeXvN8zC13Tup*)P}h#l+7C~EYF7GgT?BV9a;u&!%fBrj}N4?t0wZbyyT+6 z)a5&~)%lg|f%$ox>&9U^ei?rlo=}AS2s_(YW3d$+2BitSMcPhg5#=|TjN8t+L>T8pF5gn1tdK`jp2ksKbBmm@Wh*mr$9tN zCTdktyTH8&rPnU|jZXa3rPY6z`F*v*1&og+e4v2W;i*ARS z1%WP5l8rt{G!#;SQm6qd*m)d~&-JrPci*3ITRcSLm=s8~H&OJ0=Bq1rDUx;0p zxB*6?Y#wWpTJ{Qi_cOM+|6JnO`c*mN?6s7VJF&ei>BH#sDgO^sUm4U^1FT(~qJ`pK zw73=b7AO>oySoN2Uc9(Nu>!@4JHg%EB@luXFYX%TJMX=7XTF*I%D*Hh&+b05dvX~} zr;KYSDFRBkukXTw6a_x!N}i~1KdT2F<>*+5pPD;il^?}R>A%^-#oP{w`i;J1<-ZW` z5Sbk4(an9BeM|J8IZz*CWv!wWa4@OdJX2|+IB>EB-O0=8hy6!z8LAD89VJD*y&t_` zGWf4CHQwi(wG7X49^m0SR#SodXjLvn+V4mho!&22*0*ZS_MQ>sv7;YzM}_O5`$&AT zar(GD1->_7@-NER%mdafF)Hr;>2#bRL-&lMd7|;pksgr>UeiYRIh|RAo>2H(A+rLs zR3^YtJEJ+goa+4&e-ilG}oo&$9+=BnH{Hj3I47;nriDPKjXEV z?fXMhMep=#VHd{ZYpc1`G10wOrAwnr>E~QlsggYEgU6bei=&ofS`D9}^<|&b+C@gw zvJDXgt5cB==OV_mrwS|etW)T9l8v}?`2Wdi>(Z2K$-DS5fVD`IHh=jCYj*HyHoh87 zK(4f1t2Gaci&Fv?mG%qOg~n0rf{w4TL^YBPP`_h~Y83SARE$@rd~O3t@Cl}4lZ{5n z3N*4R8GV~7d0WrvAGzRw@XAw1+so!Qy27~JE*QtO8NF`+Ul+gFD8C#jr04GOcWAc+CR-;4a~ml6>78751kWw#Po}}vG0R46!k6JFEMnf zrqr|hgH7~1)~Fin7f+Vf9wwT-e%_XlPPmrE z-d4iCnLEX(Sqv3i=XDS8vAs6|3sCE}$#U_p5=rHHBiX(`8stI+x45Hxxs+W=H6qlI zf>}IQtdeXhrk_9Z{0v2ZRFwUz@SZ0%{;l*YkbZj@(`h2^);thiMY&J)W7}^b$j!-X8iRAc5?%I;|GwR5db#SFo2W#=umt@4m6li zUEqeJ_~Tg9iV}7h^%$Ba$a{qtN=@y7a@~5*g6q1@L9^qQnDlVpUNV~ZwD&Y%nL1Re z(eU755!uS0@fmK68kP#BVmfS#BMn);_89gB80uy}-b20n_>mPoKR+;q$3OpB@3Du- z4dx#r6i@8A+x#Ef5Dp`gE8J=7KLJpqlO6DyRU~SInXz!w%!jIAK4w2_Xmpo58>Qk1 zwc?1NH+ya|Mfvy4;_M`{zp+T(s_fydzue(%(;UTeJtB5D7uPyQeeR|4*LsBTu8E7Qm-s>1#*`ZfeNBIu+9&x@AGrt_J6C$rMe!(MuDC+R>_dTgJ}afoSL#UY_F zYW3^+Pd70%BtK|LxNhC$wgtXxpolKkeKPWSEJK39s{aRD+CBou#m1 znI6!@25JU#tGMN46eosUOS=Pd9jO zAwKpG=Ie-%Z^Bq9|WGKVlU%=NhPTSC;>-&Z}Ni0JQ zDlTxdx6J=ZFt188k3L<=+}(ovm#BliD8x8LS-*T-2@O1_i#LiGp~>-VLoEx|MzQJ> z644rux*^m!PEOiv@dv1GK3+%6P>L{BpT0l`wI?0a+v_szO7qd@C$ZXJ4-+g-<1~jl zUgoG7L*F07w}%dvTvOR3cag+TfE7XtiSPwPXtjPd++N?dhRfUf>I+h+Q@C)#xp|8A z2(MWvnQxdZF#!iJBp|y5Z6r*fgw*h`=**|0L{)`Waz+%}!MCiFR zl`G;e281eNGJs>1tH%8H4D#A?)?CYT{w**fdPFC{y5i<^BI)b>cc1#V$bDmYooiEP z;@`?wR^TAQ+d_hVkL4#V?oLvgrWQ%t$%vri{Sg^PMn*wy;kVRXo#eVSNJlVlfoC#5 z@WAPDd-q6~2modHEqV(_(eiSKSU}Kjxomr$%G=`2ZIY2vm8usn-d}8d=okvCxIa+G1Rb=;?m@>AaTysZ&zfn9Dgw zxx^xeco>bK$`UZ=;Zo7HfdEA z@-P5fXKXpTb8TBeZ_sAxBwIzkZi$&PDiu7y=sZc+%)Rk1_2PE{&o@XO8(UW1opY4l zRU>`+&aAd~l2m2~Rh=rS6MXLNR?##%*3Yv;i2qYQqP7GSrjf@-(N5!5hN)9)4|T5# zB=lR9;154;R>xuL^?Srz*}Nocv|1iG1@n;y&_L(#jA)a}4N`Q^ppPe?fZ?hIP$6sp zi>3F^6=|CQiaA~B?IGKf7m~}Dg8)m%Nvq3V>e@F~X3|5&8?q+s%e~E*I-z03_T8dz zg5Eok;CNsosCbMn?&VIg%4w1b+s83NxrvYEh+90Mo4+FDcp=sJ&)W($c35HlN+D38 zdi*9Nu5Pknvly?YopZpG67qa9@1#|==$})$NM^oN>Cnib&?zw5*gSEFO!RACEeW;=L#Lt*XRV9bd0oG`f>RH*jJ4 zKQ91|r9z_!S}Lj z7YE2b+w-cQX6lgUVJuTc!jv^$nqhzc=#;s)?)OZVfeOAXnfJupExq<6Bl$%a5v2zn z+}T59zO9k z1~A0iC5`P(?WxA%FHDD|8`qtZSv(rEX)J4eQL~A;S>W$$ZMIl{7`5Ik z$6}d>HAoW$h!*hL4gqI2M&WZ^f6`!`=aR?bf^>M5-Z!glkC#pS7I?=enwPdRzEpgr z5^wpK%Tw72T;DUC`z>{fy|hx9kNR1fnFUin{`I{M0Yn#{9w^WeO;4XUjR#uqeiDaT zv#qGJ{AM~;16Jy=0(+Z+9&LM`*Vk@~+6N0gqIM9ZrjdpvzrT~<=6+74P&`SDLL$xS zM1ryAT#C!s<>e<#h}*uqWfm3|zVm!(%#eV;$lhOQb0o!ANa#*$4TvQg+B~P5yqKr> z(cZql7(x;A%|G^=p?!hDw%mDhu10`1%i44PnE}(g`u9o8=NY$nTDU+;&?Zt>8)b`n z)1E(A5>iSftt3AABpZYjP(yjUZI5JEC!g5mdhCA58~iwa`(GPc0w}3os7rVm~ zk3%Q~yTnlKG^;zlT_SBlsdb$4%ttYs2Do`%f@xkDKk7pBho?9Ko-L?_ovSV=C*yRt zi&5&nCc@NAUdCD_cKL}ncRVJ&x2N{aX9FVR)B%SXMf&tHuEZn99~DLK%OiucVbI0> znSkEaxp%TLxY}xpzO(pqQ!+I%un=NATl`+Zr>zAI!(vKjdk7^%#4pa#NBas^u&yBf z<|sg~%gB~xrFIzcdwBc@LNxzoG5;*F(i~1|OUUkLWFYKk5gv#+9YPy#@-kF#e5^Gr z7IkF&ahJFrQTQb|5QSx^3YYUmY~=fLxJ1+N=Y!>=9Q|!HnH>_jhNtuA+tW|LXh$dK zo9hHW^u$`PsuIzEI`;pqrbV;Las9%Eko(y%Zv)in6YxBcv=i4Bymv{+=Wua8OE!w> z&vXud7HL5=_UVn1a;Q_BGbds~nrk2i`R^oRv{JM_wC3iIX!?W?fVwjX2R#}RinSCl%gtn=#zvni6Y zp}!Z^hxU7+PU5``wNaYVDvbz4nSomM`3)#GvaI@x2i~E+IUgyW>3+Uqpg%abHbu2j z+TYUevos<4Reb%D^NetCN{u@7Bj=9VnZbt#f#hLD5o>45eCt^6T6EZ_gD}o`4}Z^O z=WzJKYrRr9Y@yuf+6S&-$PGyO9a5Gt-T(~k;%1SIGLAhaf)&|)#R?ncgP&~s%gJbo z#IySX=z}c=?Dc1Ug6$@@8ggI()?t8Ya@?M<@;&-&fy!*NrlMh>HqUP1q_dEr948i2Ns6RDzI z>;C)lzYv?|7iif%@4{F)zixwp?!6!nPw(_JCYw^W>^OS>j(JaCmV4DNeftTEw1#Mu zCJ&C|{BWIbP@f%>lq911C+j=e$Ns;6xwlOI62i6%jd`->k@<(x^|JEk zySLPNoL%7|F8FFLIOy(|741Zo>HjCHP4WcVle|dyI#E#$xv$^*lPU1Y8GvMhK}0=Y zk(n{*8C07aE%YyFVdf$(eYHn|iD{A9KWw*!G8B16wi$k7A^mpA65!1k$xItp?}Chs zje{wNw(gc#=sYYGeu8xC3ON$-)J-L6$9(SvK z+mFyI2!p6R^vX@lyQv?`RpYkTN7i3LhGxvgtE{E@2eJXleEKTwtze$87T{ofRHB00 zCU5sGQ!V-H=|{C%WAli(>V@7^0Io*o2V^B1O{{6S@q;rCIz~v?)WHQQrR3gnjj(V5@x%E@-ilb z-ohrUJK&m(=MUY7rr{k-P0;&cVh>uGSi??W&HTf#pOu578Nq!RR#DA-45YSPT1((pHCsQWz?0y$gTh*ry$A5Hno+6c9ui$W z@>n!SQ_F0rzj}jG$`lx9DmwwxGE&jfrq2emurgmx{&QMBnKZIuU_0XZx0yE4$cUzx3CtXr7Bx|_^ z?J}|t{qtYV7e>A*5M9`A=|qr>3#U;`&j5qX;f7f!h`k0C-A}OkmhaLo7LZ1gANYm z`Ik3eG!N_?c5=4za-%3ODh*{|hoc=$Upi9DbV#+!)ST2vKXD9BFKoovrQO{!;k9JE z-7;Va;cVl|b`AXXVuSnKIPG!U9KvltV^hav+`t`HEzTJb{e1G#Bvl71z>V09X6&HY zV_YOE1H2~*HH+k()CAm-y2WgnHw{1aXo-#w_u7_4cp7fx0=(+nj` zgd^7zvM}AZ@Vmq#NiqZcL=!(EGmthl2v>WEPh*lzPNpef$`l?|oN5lend4QNjc7sE z)IxSBD2sYmwu|Vf3fLT?nTqM`evBPRep6eXsSPb;k0P89eXt&lC$ zyN=#9y+10Rc+U%gGSOyku5}$m(^Ncx((jj;5;6%Ovw^>ly&Y7)OD2ewASi&o=o^g1 zM*W`Jtu^Ly!P&<$D>hDeNC;1Ud-a{An%C0!gM5JYx=rIRq@>v)Ar`q&E{PkAH+|VW z&L2Z7L@cENMK0q_v%2h+uIXsRGn!l^DOalP$o>@5i}$iQ)^O{FxL0(zL8-IBdC?VX z6YtLyPu7*73qL)Ke`^WP&a>UG7wS&_1o@4`tflR|Tl^=wtq~F)Q(le;o5kAJQG7{> z-a~{LBB{Hv-G!OOzKRiOm|6TTQTsr&c`p3x*Dq(JkjlX~V)mCypBU?;5)C$|5E?Zr z5AV-2^pvuNBYD}bcnlzoLnAxO_(BbXtVoSAa)(Adw7%v;#6BVhJT*m#!oaTi*lZNI zu6CS$E1CotCIuW;4ToHTe8i<&=$xC<4^2d#s z$%&IEn0S`<_1?(s1KGjJ45xQ>)X|!g961)X8q4x6vBQ(o?PW?RK~j@`$7TfUM<|pJ zcHwnXb9%Jar%n8-+S)MWi9xsCc)g?e=taMway-o8QtX2O^*ORVW!y7IP zZduRH@xVvqFO9SmGA8VK5I(`$%aDiGX`$#OZX!#RUId1;q;=-fU1W2J9{#>Hm%;mQ zFI2RwTn_OY)wTkqf0erwqrH;Co}1LkZ$5uU5ms)*$>wY$a4>Htz=zM>9k!wWklDNo z2RT%`)8$)<#p_(M`U%IM3b5HweEhsoH|yvWeYjwdX=qD5%HtphKRao6 znHa@R$Yh4HJ+A+!MG8Vke|cPgKjJbaGb6V39AB*?*?~SwOrQnML+h%t-!NDX!&=L4 zX{mozrk7+qAHuEKo$fJ0O4|PGqGH)V6SdlIaE-)dYTogC>l;Cm+7?(}=9fhB0E$yr zfoEyrhPP90x|A^-6}Pxge3Oyu9~*CFiRU@DpJUpW<;~7lZuUzF)&?B4nvULwRISNj zM3~MuN66qs9f0i8$Apx#w*NyFoG>(kL{oOe$I-ZmmF~9vqFHzxU0c_`Z5=-7j z^Q(}Sd~kY;g>|qp5`N+vHTAUl`sg&1%m9l-u=?Og<~FA1#ObsL%Je>qo0i6&9s64q z$X?RwbKI2xzMx+)s3ayOvp$ObT2;B+I)}G5XKuQW$C}67S3I+r%Oc^Jc!~4hlmf50 z`FQu^(ofXt(p%r*YYZ4S9mydDq0U#SKOcNMG%+k+JH-=7flNnf^pm7AZ6{RIzi&x8 zl&V2oWKc#srBc3kg~1^gfxp+M%mdb?!=ldfTQ6eSbPGn8SHEWrDZTkPDUU>|t+Q~6 z1gpE@6;BRme^c|7|6Z^lc#1#E1n6owoT9+iQ?7r1kYAfSn$-9|p#o{LJ+oCc0G&W~ zhCiA`BMOk26>bkT#~_zyqb&a4Xe7W`Y1RadGH=MEgEWc%{zx5`G132}i^QwpuHBKDH`t zY}Bl8s4RPbR-JbvWEQ9AQB6l1dd#Fw74Ym;g*87JRx`D{%ie(vsa|*f>R>58U7Ntd zo+vK8(1%TO^8R`~J@?&;e^K_3g7^H^w26RubHM}Ilu)#@vPbK2$5+s zoa@+jvWSS6QMv9t>lqrAX`Qign(^{A5*bcc_OA6+%U?+f4oF^*E&Fn7GZnTCdG|}& z>zGg6h^8~oFVDWgsF)3E9|>zjQ5)W>_)(RG^{$ywV4(JF;{4M=wGOncS8O87X4glX ze-$lBF-dFG;YSGm9JkFv`MI#Fv~mShQ(2GOw)}|+*kd!*q_vS7F}X=7AZ&OSLD<5!8_oM__}h^XP|5^PW%&o4G)U>d-773Y);hJK z8NDzFWsvSCLvos%ldp;J=`D2SfZ}xJ@>GTXZi9tNyOiy<>>gv-z`+qt@BpOUgvbmz zxR+Z%bRnJcueHaUWC3%FB zVmJqgL830%WcDKoj;uR+3>xoUf#EW~_jxZaeF=A@#4qXozUxwVJa?SeZX0L>{j_NA z^2Roq*!;2%2m#H}{j*oWM8nnBW_bR#dYZDz{!gRm@W#F3KYxmkY zF0zh%q9fO23i_^6vNY7=(%-yExy#Bi>R+smq`xaZ-|wr)w;rgIg0?bUU;06D?y(C zQWrQLFr4_T7kst&A>Db3gnoU0>*{sV=>=WeX8zY&UkJ@LCe@^r)J4zq=A9649kY_( z(kDlaCC(p`?!yrkQ3yO;*#&>eXU4FNRpEC9;#qXTy+R?qLP)n+QWwA96!D<}F|W@) zi{$1o9SlQjq@~_J+)lFpj=#+vcm&qDM$-bZ60p;=-%dMAzIm>f=uf@1&KXNhl*EM_ zkp1x?O5=zRwY6e`-IdkPCKt`MIEBDUUb5w%oRBh6YmEfGgLlNNza_NC3S=e7nG8Bt z1LA%J1X9Br@G3g$9}t$8wOj4M2)u0$k@d2aM7D`O ztt{+mzZnXxp+5AhP%gKzX10rVkXoy(2{55;V&QoKpj>+`*MILZW;NjaT@kEQSh(>= zS1e)M%%U0)^YEo~kx|jF7kt(j-Eu5lI$Y7~(yi9kHS`g`d14X~d^z^RigMxbf5gGJ zP177ZfY#XX0=3x)$iwB~aIx>Vitd+B-giGpcbGE%95^pxm`sJIj zHuMcF9!6!_I%}P6gUzHQ#Tx}8zdH%A-Jgnb5llrotCBfxtFN)tCxUS`<_}NS%7#|9Pj`E##I(}Qj zyI}q>BiwZM>Nb>b3lDQ-HX0pq#J&s_r zB1AB=!!lqv+OBjq^NpURuUmC;S!%=xD`!E}2#@bpxssbOsJiy>Zn9Z=-l`z^-=>EH z2t@09wnsur`tBVSYn#m!ww2t6KX~W&dj*5^E#QYckke}CU$4R~qzEq}clmq{&m!|i=y@9UjeH|RR?$Zo3PcDE?>R`+0PfYCKOQXK}n8t1&Mb_KmS9e;CFN&H&d{wYz61=xYcvntg11oJI0 zedSt7>uZqU<0*J*jXzU!$gEp19CkBU+8oaNZdfVmOEFKmQ%g31gKIhMrL|Ba!zsgc zNjShN91Le#kt)C}4VMNvndBBi9X^c9bHsuFe%oa6v7uQYQL?6&Dx2veeQPl!4Hd+^ znNtwUQkCLIZXCFEt)(UZxC&I|Z{I*1aBN}s1A6AMEeT44eqc{VhKSprRb=R!C1GM@ zC?+B_ci2eBi_`*4d$~pdd)`?4_j2UTU7Ry=6OF!%`mERTJ)DjJ47Vfa8!Q4KY305tvJ# zf(ihtq2Xp1!)tYJR~RocJJIeK?#6cz ze6koM#H%QmHpDC&Lg-UH;}dMhE*kS+JAXW z85w?F(oduHT;Gat!x`N126-+1IfHyN#~EkqT1=%~JooZ?rzu{&+a^A0dWeY?_j;20 zPV4HYrlTJ!=S<~sY=|z)hL60zC9c04@$UVFN3#9cUjYx(xN!$%BL$4=LJ>7+S#wN9 zyfusp>HVioPNh`KS=pS0FOM=KJaF@Bj?l71x1S9I-*q+F&&!jxV}|4vCvn*{74yr4 zxid1VK5i;A;nhy>`hM9|X2jFvy<}!Fy^gfFp9_wi_*!A(!{hUDnsT{&v>$nQlPUeT zXye&A=`vZg7ZLb*bjTWS^P#|yo^0+a`$)zRhx0e_DhY${Ok;CxZK;{QL8-kXr@6U# zlfjAe!MjQ$7A*25-@WC-5q_Bie_VLr^Y{s`lhD9X!~91N-+`><`=j_BKMZ>r$=$9! z05WvOkd6XA>_4@MADw0hli%cgg#EQdfVe&ZhdwBFBH&6?FBiITRJSf@F~ecJK$&e| z>-Jyn_ZO}w@Gp)(Qdye%rOID0$5fMQ)1bQ>?@E9g`%iN`rXdwsM*)%Ng)#iC)qoWo z0!0srp<>PXXrPSIqH`+sz5Q1ToNM9g~nGEy|u4Ha5|xEIkaW^KZULf>>RI3#nm zC{#t*eNrRkS{`pu;C!*@-zQ{ym&n77O88!1t*PA4g_|5I_V(n`4-p_CFWbD2it91z zYz#BM=S&i?F{Kf{uxUVfzq;nd(1u+5};p-Re(Xbi7Tw+wTmae?+37Xq6T<3U`x|#)z{X zTI3;^6F|2N*(7%qd)482o9NMJu<&Ln^%y*cS}}8&^SxYoQH$C)ClaJ>fg7${$C(ba z04=JjBs|XHSZX6&bY8=fYo*TNF~H;FtzGg)oM!21N6hUgeibbHQ<+tO^~hRr+e*gD zI__%m?eIj@w(p}&)}p?Wk&Va;-;T#~+lv?OHlx~z>ez8@P85l18n zbBJ``sJV~lj$RH!vhJ6nv0g?B(a+qU7r4f9Kv9zugMT*bG(SD5AlX0P(5m;mlT8-q z_7w78L>cto3pm(kpei^XlCauj3XpR*!9)9r5QOk0*VLA`20d6y0oZUKWcp0tvTq-8 z1SHMF{46IBC^BN5hn`>!MKNn4q_-S+Z~2X%=rN#Tv6 zR93GvPy{s(mLJk!c$?bu4Fa72FA^L3H3jaL(t5(8IS$d_|6Is&y{oaA37ke(&-^&; zR%6go%>ShwxA@JIF8;baU{{_B|I$SVlNY@v*|ZU&_#&DaW?ij3!K7p%|9HkNZKTY4 z-b;97plpp-Y@E5Q?gfT8g-R1tIq0>7H>fo|?H@<*f{W%@&QE3!U^mo`L$LIZ?1>TY z(6~Q%K8*g{UMp)VIHUX_!5e3{FP)XMC-N1r&!~RI=dO_8?A2L#AN1{8{vxC?Dx~kP zl9Qw&?wnC8c2(|ALSk@9gHMY_hqOUf!|!MYyF_V&UwrLKxZ3XcE<({HV~ETe2Kk#j zj{!yPVH$!fQpgO4Myw+Z7FNr%10Tv{H`y`VG?*y*`zve*)VHIr++GmntrNVPr zb+3X|uY&M>ADA&Buku9dZ?AHfNDN_zW`%(N^8(0!m~_};NkA|7{v<6*-tlT#8#E-6 z)@m9BHS;Ykv0!x;*pBk%P z32C7Ho17!qAMhAG@csI<%)~D0WXkK$3uDjCxb zT)XX$|A;v}r#|_?68B@?%bi zUjq!4S=)?jj?Hg7xsQ1?hOLw%bNEb)3_`s!;!`jeZ(g_+IQAcynBk z^$_XU7V8&V|J);zi?_Ty+54FTf&D`fp%IMU@6k9t7eG|aYi;Z_X@K-$qQ&zDTvbC!N*dXy0APw< zdH(-U9ldIl_%DX?(m5f^^dnEFq>pHAyE;^83T)Y`ZK|{nl>HlQn-L-RNwLG0ctctC zS_4Lv(rY~=MqYY$4fHm3Rf0+%95d-{>S+fmZ&L|c;>F{fDPu4m6?`<;S1z zbJjFo%dZdls=mf{j*fytS@g~488|)7Vp`LgKrsp^ zTEHxs%ba`Ei>xh>`wj$@0C~_#H)qL8}?>5Cubi=mAok|d*ytF~c{B3kO!?^=?ZkH&^E za1;Y-(OmzZ8n!4i$y7#S`9Cm7{ zJF{e(D39kH`0o2$#r(2dmNRNk>w@Zcwz^g3pNEKmxjJudlqp!jK_-w zdHVd~rckqi`(n>m?n5CrxzWqqAQ+~w!`%MG(B2o?0pHQTiG<|ypwnE+#q~x6`Sx^+ zt5n6Luo6`Lx|d)O`%~z=l7k&_169s3Sp=&;4pvkC?PRa!67|XosL`IeM#y>pQgT(#;oLp2H-@QI#oOS-ZT;^S zZM`F}lWyUHLV##hN?5gr#ZzkVlh{53VNx~7O@n5UC7Tr9La}d+ucu47%c>U}q&4Yy zUHc31sDp8T4_{UPi^mU^UV9Dgv@!x#nGx&^7}Dq{`(o8M_BicvJobq+cFiTC-ge6t z&DH5gUF%ll_exCp9vKxE1yeru4|2+eq}_sVY1KxSgGf70OQ+1y^zc$`hhkDZbHDq9Ib@5luC5{dkBsLwv%OEX^5 zp=zfKEt2!N6O@5J$M3v1;Bx*P!xIX!4e%_#;Ur}3Cf7!)a*=u8HiVa`ccWE#sHyE+ z%KsBIKdR!n;kLc9#YayiB6U2e9npfS87DbnWmh4!shce8OAr`c7s_jx4YWOxSE2vl zOycClFUj^9J`aLvot_c3hU!_#Fs}`TLzNTy+TT-ek-`FAs58DVf)!x_LFuzk`;mqJ zD4+xX#Zi#v|6mj{!ITW5^Z4af1-%cYg7#BGV$kN{=kUDiCl6Fd2n8LVdr zNB>Cqs}+9vleeV7vY24b$LBARdd%Fi20zLdRS775GROwRs1xTlQZ z#o4XB&(qnIB)gPGf8uDt`)*kB<8++VS{!rhADEli9CWg$u*FiBw@@~uJ`;cQ@$C8w zANep5YYCVr>o@ntBtqlhpJ?uu?mO)}#TXI1pRr{uVI;<{T$S4*UWZF345k}-`Ayi8 za~rO8%8d8KK=J-8e1YB{2ThQXg9mZmRfIM0s%Ys`Wx9JH>nkXKh-S*bj`n*6(e*xY zT&K)7h>MANqo|i?=E0w?X`ZxV5(aRt{n^79EmxQA>mdQPhh>oA2dlnaZx{gf4buaX z05DDd7W36#`6jn|x{*ahHfWSiJ$NI&9IpOm=7oD&pqz81lZ*Y@p6Wt86s!;2eeEv_ zd|lIJZ^nT5`_3_@IN-woD?AL~o9SORdk{~(#*jHrjb(h{sAYDGTStTj?ekyM$Mia{ z+R(gDnC{V=TdlFM_4Th=FPVg9Ux282Eb@siHhI$NnF|g^67GYJ0@Bf*;?dqmUkl#< zkmZP2G0AC;=EGCAw1s-s{V@f~dW2Dx(@!YD?XxQNBp$XY_;bTo7ZAqEB`UzeTvNqg z@xIR5LTo}FZtX)IY4fYt4ZL!T9Ig|*4*Yxz6Fm}t+w#SBIDn8#|A*>`T^Cja!mwSa zh+oPnr&eP2;ju}zKcyV%oneT^m>b&|RWS?lvil@~g7@!25k~8YJ=!8ak~yk4)a<82LxVpE z=BtYcHu9pfhXtgvmpKL3`<|*O23*}v(tWe|tmc=!ZzC>o4m!1hBXLTCZeFfWfn$uE z*QAeC#?lsGWY0#)7utxgec9GCCRzyAf1$>qw)KeGKLWNk$`MLX7MSti6fwLf4lpa0 zC@4@vHM@^`HETcp)<5^6Johr(p(p}i1^D$#zpPrMykt{7-g+RIoXq}ZJdgd5UyW{= zEu_+@BSS-OsItPmhs6s29zw5UHi7B1;FGOf4w0J|7OLKaka(P*zE0yq2Ftw3ymKK- z?5e|#ENU{*nw&t-ADMjHjp9Uda&l;6B`+c7HmTqxrK9~0Ok}{JQE4q&2}De z2T#E70xlD0QHhDXzBF&k7cNd=B#?poFNo#XU12=EN}9gQgPzbg5Z-|+t76~ZmPmAt zC5aCOY%(qKiQiR_peM#>HL0k7x>Ba6zYWt|o8q>pns%9(vA@oL)bW&Ko#W|B>3a<} z0}BNmlIu)JA*-mJ-qujQ-5bVA_}T%B<}u$94(%A4=ki>lX&Lxj1<9xdU?vNQ5QJyc z(V>>2eITfXkE0I?7bB;lS1rr>kUuyxqTE<`ce=2gm};U3GBger24Z~pd2H~^^ z*~u8i!arQoZW5}n^A4NC)!Chkv5!jMxSIV{jFvMc#|$4y&tLpUCniL^M8pePWu`-H z9LTct9F>Hy2-_1V*@Uy%Ya)Xb?C)2dwgB5Ag{Y^H+JYV*g4WkuUi-{ZUi->lCa4#w zuVDGT{HO$j*f=V^9V;iJ|J~W5F(2Y@?W`hHiihp~aEQzS$goPt@P_ zb#I2mn&ik>x7}kEAN_1`WDC%gZSY=%XaJU$nadThZy@i*7TfLz;F$XEErWO1Cy``y zYm&YWtZrmJtTBdpi8lPW>H)<+q$evwvl3p2NZ6K`*uuuC!ryl7S*MXR_0X2;yn_L?oH9J(N1V+Ju(W`~U61m z-s@MCGh2>zu3LXr;cqo*b>7M?^E5`k{gPYdsT{R}M)lcC3E6ppN8Y%O*hxWPGe#ZN zL$mzP>8Fl6`_?xhID;k8O|?KKFk9KBTv7hy8Ottm`**78B*ioH=kOxI+6%Bx2j&iJ z+?WdSBnZmI8P-*SX+EA!JpQ22cN%H}3|MbSAb?KmuRt7R`i?``jiAY29lxtIIv3JQ zfwM;#y&>@9vbl!q$IUPGyL`-|hEXl#OG(p9mtZ?g?y4RK70Z3aWs-EM`+Cg=`YxN| zMsb|HN^Mvypg=J*0gI&5>9v!kH0As2LnKyZ0t;cLAS=>~WU&%kc`gT2E$H@;2fm_y z;_7*pCFR6l6f);UCGjah3-P^-KO66%L{=xV*L&s{&I9Bo3poeNrrWRh(Q^^ayr1Ru zD@;avOFV3i8~xU%qWS9qri~D``NdG35H=2+v~xf>_g%}02SqD5v03|be3l};?A2*e z+%U?*6tl>Gl)b4mf<(Q7Q-5uh*xEQE(usVPi#0r28MW4R+~=(+iFHJsu7?0CJC4|~ z8mN9&!$TWz*JQ}}_O|GcVlC^3`Z z#?9)_b6pOv3&8!XaoV*_^(Nry1`0pX*5Mwn&J4v>S8*WK$uQ_oFmdqO-RU_q@;z!T~=>lXzBpE*D6J1d;$5!L-QirR4tibS<8h9Naq`lRu7+ zpcUe8DW25lGC;Ti@?ld&)sNm$i~@=wdP&qy9625k!s3TpLMofgR;x1V#JVzu{2}wW z??fx(39WNz$Uo{>S9j}CP5iF%v2BAx3Jds496_DB?EG%_>%2X3 zL|A^=4KbtmZ(5IL3y=VsVXmZGC#E$`ywF(k#pKXdS~IhK;Os;eBjt_%aUXra#9|_pBazkOWSePoFHPZLMWvS1u<- zQ_-D8Rd-+g%_3^5&}%F(SNL|>sFu>&xL#Pac-1z)*d}8PTYhfOfy;+3`lVx2^vNwA z+6&rK%o)WvhjAaz9)h)`J%XEgV-rOY;<^=>Cr2$mw9&=PML5^ndFVKP9Kr6FNJGr+ zsTX>dV5;@;PqCvBf6b(oFJ+5FmW5%$&|EISLlndP;fZEGnBrikvNDa7K$)8#62E>; z-N!lj_hW7ksPDZFQa3WiGjh*>L!v|Nu=VRyU9w>aUXbog&cGuRyb;6;Jok7X{v(MB z0i+sSmSgbk(HWllP99S;@+ndftbtX}xXL znYlf^qQI(TmUpU=Tp=Ekoc7ES+1OUmEV?v^VC}J@4s&@vVDzSUwVmvGUBL9Y_gR7C7;Zkt?px9 z6T3j)xt!SP@^U{GaV(=Xnj8HJ(2a%+4Ycc-v()oB>vL_ zS9jcYgPj!FDuY|@f>WLT0W2))OQYJN zyLwrA%C|PjM`+_fDO@xwxLX{=fv)RIHLTujGadvM!`-Dz_bpEaPG{hd{CO@66TeAj z1e|ESfk96e=|et)G}j|%m&J-%+I%{$H&Mf~4d_uG)ScmJxK;o8e5w86coyNk&v_%E ziFi0v9pj!k9nt{!d?F^>zi$v-J9A~UKP@UN3eCe5F7}X_dj&}fTzi@R+$s<>$2lA} zx|DC|au7mgcnb%p)ajetJYjz5{uTw{j4|M#%iJ8_a|OJB7V-a&rf-hQtpDE5wr$(C zn>5*;YO?K`Y#S3N+nmfhOtza`ll`9O`>x+wXVtn_|8&l}Kl|(pdtVXJ&9^Y18~py+ z*JqJj%n;(9DrZTuoNfhuYW+CyirHGecL|AOmUz6960HMwJ%lRqevxmfhvl;JsSz%zXi($~S zG9It@hw#nt9&D7ZTZ2&$v%B#}K#i!H2_!es*I1{ilDI!?CetJyn74-1)pR%(CR}N4 zsgYP>P|g#nVE(-yfZv_>_%nhX9eiB}sWIdJHJ{oWAw>qt8fbq|>RViCK=8rU+B$>~ zz}?JU^QY^{2{_2b^iYHj)ey4EzNJQ+~zCe86IkSIKjaJ)M2vd-M{G8kNa9f7dh%VzZ}V zb&wRgcd!9(feR;?d#-aXg#P~Hp?Lj<*NuIl8=EEAsfp`z$MZj2zklTwgsrkAz6*IJ zroJq10*8{-54GWqRFjz(B+(V#(}LElM=*wSYk>=XZxWk3@HTq2(P|I#D+qvJt^oWZ z)Nd;$cA>TczUKP>A9z8PUM4}oBbu88WR|sl`Pa7``W%YU-maUxp7k5xXv_kEtoco9 zReh?XTNM+Lwrk9Uz4}nTZZ;`ykRd74bYL@VV2+ly5o7NCRvN`;QeNb~w$|#ANZRkd zE=1R>sTVItg{03NWsRH#{FVm1kFu|u-m@}TcO01!llFp|FOI!Ilh}5v}7M&i3WVH@EV;uiMJenJL^KKbQjftN0?xUs2 z`^U6anc0h$pUv%{iRAj_N}*4n;v(A0VugSmx4086*r0e~_?L_7*moUW%~2iVZPl_e z#3_27)-u6mRH3xH`f5|c*io|1HZYgG?*dckM=5^ za-h#m*J8{?k3`UZjFkNNJSK=0=1Q<3AS+#>2Ko1WvsVr~2U)y&5zmDCMEmOaRqm56 z*i|ACIjvzFh4eTzz*u8s&7U*NJ!+Pmf@-^o2`K`2Jx3zE^o*qUd2W=!&sz8` zV};uD3msr!fVpO+IlTE&*WTKe8FB3H0O&!IujcI6gl!Z3+C*xj5%j^Vj8`l(U{<>B z>Nf-1XdA%-)t4f^zDF0)rjN>4O{a&f*wS0+N!jQEKSsqG*JQQmbLqt^Y5dyBp;|Q= zm;bD+jEO!J#Di6Hk{3OW3y@j~HJciB!de+jfwxNUAeb0)6@RAOi#$m8#QADJNPD+d zAd|$iHtW4hwRh7>WD3|Nb}!4;Y6@)|PZqDgthRVYL-J<;msfYZWSI0&EDlMs?b8%2 z!8i%F--~d{hPC0|;=ZQE!|2HsHARm3Boc+RJ^BU?xIOw3&aI8HW9j9C6U-5Wwl+R` zWE$fgBwZUpCbLY~#^t+Wse>H=qPz|5M^t$B-B~GE2l{i|lOpzD&I|Oi}g>{b?iu&O9muT+^$G<#*i2)jj$wGnK z6S%4Po))pqcIme#1{lKK0g7h5R@FWXTvAFMho4$<{|U814^V)|EMu)dYNlp)Ah`}r zrw@b0Kkh+FL<1E$V+SO1;2FP5@}c?ej6TA$R4n5$5_7+8@{WL!@G076pHuPcA0V~@ zV*!rJ%useQ^{wrW(UNV;07SU!BKwp*l;zsyGx&%>^;2SUKw_(N@yBhkx= zR(RxGayWj;M78fsf!B8+<9B15iqvFhWwbF#2WYk<-5xI0j_>e#POp$c+9XjG{Qd2C zK0ri|Z$vxZ_OQe2X3CJWp_ZqBIAt4%v=fE3wdc^?>G0;2(JFzmTWwV`#yUSa;uh<7 zq5O8rf{}8_uwmd1Q^$}y)10s3AP_3cS3UH=$D8y!=Tt_6AFshlWS{=uzF^C}vz@~$ zT)o?eeG6uu6pjj6OyR?CP_d2zN>kDE_}`L-V)OsH%-!~K24b_)TD_*U#Wr(l-X}gI zFIV4m3+EX~?{lC|v1zerwimaF2&FvIsTJJR7jVgc&OluT8PVG62DKRU0R+(CDx+K= zH@byxnaD0S<*cQhhUC|UxrQuO{|~a6cPdnNVB~QXl42qv&67cZ7a$jM_#&WILkX73 z0=5SEnV$BI1!8{@A26ycUGFhM#>OJu#-PUiyQ~?^B}&s^HA=|VndnVXa96&#hC22< zs`@`KKu_RGgsa9^J}cl#6s|nB;)VqTAYsyJ^DA~rva@_%IpM!2Q!6zhTIxYP+Kjs! zrjS+Sg~yQI^P=+K;W!vMTYts7v*KY5RGW@stKyi?Na~5_-Ah546RVgoqZ~oMmM*Gi zl(X3zaOS4PV2#uCP0c@Po!bWB6f%ij1zrsD{|aXOlX!ty(wE;aY`b%gn}qCj(|-DV zA*5w1hV=KjM(BalvZT}f#ckw!>(%u7W9g~(yIi(- z$jsd)2^l}DA`|Kx*o>;&0HOl!?dc5zvZ*WQ zpQ&)3(VoCH*_W;;j>-My_ndkI>-9afsj}Aa*TW)J%R^%XYsXTCt)Xh6Or46eXMdj_ zdl^1lbdWTXr{7UFr+fOwzPHxZ_dPRh?nzH1&WqFiNhjN1Do47EfkR#b=*qKV%QR*%j<)FXD6W=#?r#%dS0S@9MGWAI3xgl+Oy;lws61BX`TnVT&GLT$KG zd%kK+ErBcCPYRWia%eNZ7)5rfCy$k($0s=XbzdfczXtgR+qAPmM*v+C(Qa@5jprvG z$RPwBu?)y+#$amUD#YIHMk*xv6`k~yb7#Nq;IM34{-vj(PX&9-!&ReUn-#jX^mJ`6 z)X1@{)5Fd#7U)Z`VH5w?P1yk&J&m?1we3erPobICxjR~&fJL;fNxYiJPc`D?LQQ>= zDy8HNQp>M7R7VNNAtqOY^xdeQm`n|9#&n-TY|P!LVOfQ&AjqUDv!_STq^E$F?8Vl- zACh~kci6xzLB}%9je$T&h{u~tnodM>m6V;V*uWfWgcUpbTfhp;ddGR^>VL3$gr z^hX|f(A}5*gH8Hw-%j`+nq`felT^>Io<-^MOU}u=`@Vcz|5##Gc^ifD4L=x=SK{U* zO5(X$I_T6X-kA0_sxQ!Dtgla3T{W6UGONJPop9LCr3S%<v6z3?m<$=D6K9H*yxsW9TNpwrJBJ6$?68f@#6oN_L2aZ$p|Qz+?%K1V*hWSOg>4 zVFR6U&6osPGd07hwwqH5M?&b)_H~DTs263&?Jj$e(==sb@>G6l^f4PX7-oWgt7I8+ zwwpyUy$M_lDlP>6}0Yn)Vg}0UpeRQODP}U5Zp@t)rd}xFL|0E)v0nCCS7t zQZ&HfwG0>g#zgo}byF{GBilz8AEI(HrCi-Mq{FVLWLb#uG;zxA#s;@A6*?`Ebs0IDW}r^su>0!cLy>j8Va#JtXDBD@l(^dId!wavdRpglGW}>!ki)X)6NGi z$mQ_+xJihfbVC}!Kmpu?XWQ4scBX4l?IHEDV>f9;DXCtv3a_gM=qqRIyN@(Eg zDQ5x|!mioHp(0_{q35Y$TJ#(@L?=;SH}&?Vzw+vh&{GNoY|w`eqyjJyq!-4?BFFrY zxckcgdR5ZTPoL->eYXp>ngY@BC23=CKNqWH>vA_2iSz;9v_{bGE1x4E@(+01w|$I~ z3QhfdvyfUOo4L^ZZ+QLcqLwmqi9hAhp(C{NziKpu~8p=kyty!2z4vBh+}^8Yw1{Kjc?N({BsC-sfIUa=6Nw^Krteg57MVlpTgX62ne z69Niqk{Q`F#%8tix(@7FgEa?)w2}NAug!pLy@#!%_CG4A=lRUCNiu$PADAkuJ($uu z&91_l8gc2^a8pu3X6?DdFn-&^Wz;VRc(gDD`#BX24(N`+0`WTw>+OnLZr8v}aiWRj zr=>R)$;vp4Inls}GMkJ@gNHc7hZc;M)|4SmM5b+mD7`=Odl4_U8>|*ztEesl`-q)g zELRu4$X}Y{gROm<3hue#Sjf8=;{V7geUG|0{G%l2BAP*d^V#%xwCkMvn0H+6j0N_O zS`4So482=iO^7OKfKfl4LOlXjQ05 zg~wFI*NXR5kw;KIpNK(HWJHTeKiORaK2bUtYqdN3oBNGeFql!Y*zTI>)~N(9N^}Ow zmv?^>p-n?W!()Bc%KsKj)IEY}IUaV0`f>=O z?ogARcu@D(<7sy(f$C$(qc+S<%AIV2#h6lMeJ=n%=$kb)f z`S0hmyZeB$1d!Fb6Dz_2LYS{=H|>(>?IbwZYF{G;+gUG9lS39Q!~u)+aW4;t3e>kx zJx9_G$z2kRZz6=VYn}1=8JEZNVcL9tb{e0T$B>Pm-;-YT@u8bqC`Qe@~hn z)yI9oR?EiTwSYfJevZVMh63v=5)c6v=;$U0^tq9atLFXW@bd@27s zi?h5zp8}RjO{k3CE>pAWpp6P7?@&?wC0o|Bzx0^`-d$X>qRad<204b6Zdf z7SLKZ=l3mM8P=698-!Mu_uLIiaqP5tH;m4(9gt!$1w*5RnVo z;Vnqwx#56#esIl`u3Iu>WBJxCpqTl2itFIR9r%xD!+muCLr=RSd1e}YTF~OZ$19yc z;ZnGzE1=8L!bM4{X-ZT_Xe)E+_@=Z`rvlG$?@Y=IkO6)9`_)i(P1;NxF%T=zs~NZ= z>71xA-wN8sgz#o=y%9TYXe#>;_ae4d~^X>s_m+$sjnq-DMi}M>B-B1F zpX-Pt6s+x_s)O!6RmOvEmi2Gz4wGasmc#ft$xikJ=;_ioTN#uFe}Z)l+I#Eu7~pH% zFcPY>sl!?wVjIk)-`I!Tt+hcl3WPfNA>4+UyF#EdP5cEj{<^`X%+yvMKZ$pd>1MFfQGs{B3w^cpK=)P9}O zRA0!Q{-N0}r4qNNfd_+vE8`TX+g3{?{dfh%H@CW^_dXtp&v3L+RekoRwnC^n7f?|XmtEb zxUeOi)W7m55$k-F;_p=lAC21#xg6M+z&`=vlB3xdE8v+tp5^KD}f;!b3(FyWOUH z-Kwo91ylP6N_ObG2TI*!9=s!}1*LFyzRs!bb?WMEbQw-%f?U!wY|`+G%}^q$8prS|A9R`&&$}xs>~;g?dcLpFB$@7)8p69Ikhmn?O5Zk&BPda8M@U&x@y3UL^wcUh`3J?q{uFG zS54!Urd|GNPG*pw=f$?)?F~oAzF*ioTa@g5I=h6;-<&ybyEmbKWcY=kF^#j5#E%pRscea(MGKC8nzGlbU+iX5FOL#Hy!=iVO; z5zc%F>D$yOj;PvFg~@iZ%S785=}m(2y6{Oz%KARt!y_V8(@U{om_4n$w3 z5egAIY3z4Hoelnlab&(Y#hb`>*RX;@>L#h*6CMk-DK+0W(5< zN6fEr8H0aEL!_bMjnBgT3u;-hn6+OpYft;}ZqWzRZdvUvX$> zxC*)JrtGdHTzO4XYK14cpp*=M`S3ITYq#@>afL!Qlu~y#T(PdBcxnH-9`{AQC^e4% zqA(F_rOrG--3WRI8m^4vpuAW9M_g9+A_@)1!DwI9#vK;yj6e3{Q+Y*!Ux4z4vwV~I z#X08CKg7w?s4ZW80#MuB?5tSe=h;=)yD;GxL=@!`VP+I#0BiqB^nHNR&Is9(AYN#M zVRXLe8SN`C4hYrVk0GdsV!){4lcNCHDZnoIT`(qlgqe$%_tt40HFD3xye`ryzW}_^ zrK;#S@MKhw;yNB-qxePBLG>vV<^=V}isg^n#;DuIkGLK#3V-8BPYJNvG|FHJGX7{KeML$x`ussxp3O@GE-fq-my!P+tM7<6vBI2KgI*ZeJS-5UE1vBb_ zb>Hzw>wZ_6O0KSm>pxT;i=lIQ6-#R5z(Irrsm~K+O|&q46Tg1p>sNN@MALc9#86eP z2(pfCVDA`Wl`Kb$VIy1#?=|*n_89-Hwo^ao&82-MRv1P9lp6KHg^i`UT=xbk76Q5U z@A)1pmh-=->g$fi117)h**R+a&w0PXPuSEb>thdYK6P;sY<#30Meu#$o25KxGU->?))Fr}=pZL*7P%SDHUxdh2h2c#G>w)RuJ6aa*H|QW)=TxLs$!}1P*)H$#Mwo-?L5SxOW&x zLt4D1QJp47VN6(2=__50#GqUfuWY;O?gIlE&R^{fNHU@tE1OYc`iXb$9D zxZM^^qx;n}f_LsdaP2;z@UYel_xiah+m8+mZqg}GK%h#dDFwDj)ueZ_T--GJ=YBzV zI2FtFWbChYE|qIu8DZjcHE5znQ;0@j)Azyt8RM-rQw(KRgQ+{T^VZN+>O4e^%Q@SJ zIY?qQmZP45Gt06zHYy<4ln^^6ONYt{4A!`aP@~!A%}}t+v?0+CloDr3s+@K2k#FQeqFu^f5zn71l`{`Bs=GYUb?>;aDER zXNdSE>g@_6C9p!>>zx9;k=oO)f~4%$9P@beW#kPg^-uQ+1$%wMrNOGs{r&!w9tq(v zK;3zbfo@dM^^)Zh`X?DWH452n9s=}EJKc7B#F$>Ad*8Q4Ar36VZlklnbg!h4Ja`yf z`qD=Qse!Yykpl6V9K1D8enVaT>UWr{12*8H;t4$9-Gw5{LVW}U zd-92-i{O~B#w70_+Z$$ZMA*UizTjcA=m}y|_wz^wg+}FS9hBXEQ+K9%Nu>}jJsYv4 z2?Y{yN_`rst=m1WJ3-=asYzn1PpNpK7KvHeS+G-Ld#km2R%)NEo~op)&OOx~?%oGI zUj&b|W#kKXo+-SUI1HCk`^?AMzC!|Ew>?qgPZjl;;ats~)Xag0Z7D7hi z7HTJ3UfEneQGcaG_HE?eFo%x^kuBMW_R`mS3xvRh{ywuEEJY4Mh#uyvLfABijI)Ny z$L(kK{wz)_hsisnK#V^fQ`i+=Jyyg6grnEA>~HV{2W&#CL234;@-+Q_;n+6_AYL_T zN{W8R|GI@rGE7KAw%!WN6zI#h-WDs>GJV>Y@(@;Uomm6bbjsMDU8#AxP>1$C5|1Qu zk-nkb_h*9RYW*axR+#N?Mv*F3(6F-gw8d=Z&pXWc^Mm-2Vk1NKA3DW)2<2p9J6tO% z_ooNT{ei^kZJM z@vqGKty*;zm7S)Vzt3Ow5$~Nl)h&O!@?SL9E;ZMlzGy%L*zF!={M^}LoY@wNo#};j z_26A%;!`#L`UYi+bV{^uCkiQyb(94NkYeLtdHIpxW@7NK;p5|ltm-)=6u8*E%xCXp zMpe>Z8<6&f-hvpts31!sv+ZB{79_n?V2gIBop?6VXf`&3*$*f|so?Xw6ua>#v8JTH z2Xv1t1ZL0u;-?#**+Vm0OkE6SN5oQJ;m_TK^-#~s)7C-l=jJ{6H9?JFBiMmPbUBKS z{ewamQ(|lL*RxfT>@YZP6CjduEc0BZ!IihZD4bPbchuNuq@PAi?ybJ_Dy2<5ef8N0 z9;+6gO`J37nFNlr^o*!YJ$nSM2+q*22<}YjSf9x6`QH!ZNo~}l)?2Yms|l!7^9<2_ zkVdOb$`R?xr@RBcdq9f36O8L`5Q4zi^I**1jQ%SPI1^1WN`eZ2+20mv!=@9yo3 z=uE+{W75EEGdI4SQpsZ-Bi;eli%tnu{I@0ACG>?0vURJUHd+wZtgZQ9SmG4ehY#J& zT~Uwejo6b#Kcj#C4zIYbBe)A_L}kT#(sm^NUXmkG^7DF+AoHY*ElS^?_v{_W3tN^4 z3E}K`(G17HI2d(N!~i!URJ0$Ab}XHe|Nia;U^iHaP7&;#?(fO37u_T?v19KE4QDvS zkRKkQt5Z@zxoTeA5d5X}<;75L=|T4J^XXfHf6f1>;KQdf`?LIB#-eI5`;*d%V{T1i zywMwM1&c)(g6Sp;o!hwrFG#Yp*!%pFk?h-eT;-j#OV?|~UKT@W)lYsXhmRp`^LFm$bl%*Ea4{7|U z7gs40^)B#co4sP4=Ce7J3A?R~+9)K|$ui9Fcu?wHjgM8skNHRFSGw&L3K6&<#-jd> z2bNEo6TI1_bb#Mti+yxMg5?ZAFPz-GZB(PP7YkqY9_{~dkqZ&aZnOnro*hDKVQ@ez zc7l~F{8&MIS#kYSXKg7rimI8Ox zlCzcW2*Yu7cDxlI5v#AitZDwIs}VvxA-yLv-cPYZ}=<$19wsvqfFl0uMG?4>i{hh>mO480h_e z5>hg0E!6dB)#$b8&VRO$ELcYI?M{Pt{iehZDY&56SpWSJxS_2#jKIbS@`~gnIXX)_ zvxFH&N#_q2<>mcA;xwO?z>^4ee<~mX>`h*rJBv z@MR{r!zQd`c1x*wr8ZJjYmz#wXHx*=WfI_2qbR?d?+{xx4E1od?uzAcF)APenG%YO zkKj2x8}R+IIm8_wLI065TsW4Uv_)#ZuROxU9#=Ik4nwWWmUX6&=y{qyWYPJ@tEw`2VnI7%jg*o=^@MowcvFV}_jnU)Tr)cw1b&_5pY?X1xhwl7&fyZ10UCK!)mL); zb{$8QTgSou#-+^~KuC!# ztD>S1a)KmNnTgb;nO1<7F8Z_E_4tzESI<7nTlQ*Ko3Qh^7V&Ib?UbSTUVJVxa8^nE zdBt_Xfad4Hv3iI&=NTHAM$Ve=j2MScl&2v>_6ZWEV|zw@y*X?k@<93#Z4{CGBS`#6 z{l&AR?yuAmrtANC0rWCf%bB|Q^thQN4{)TNzd}-v=0!24=U{b!gtnZ2+Jbt`Y+&sa zN`lYw(R{6c0H^2HhRAt?XzslN0wm7qoaG(1QVPUky_O0Mn-)WitpTvF=#zt^-+Pei zOix~E><$Mx){~Xc#LFv_7PagN)|1VfjQa6={=l83R$X5VWibyV<}_B?Z)xsegP$0l zEj@HV=GK!o()kG7XJs%Kc2*5INH@i9tCRUFj$4Th{80LGzaQ_JR$=urE(ZD}K`1M9TXWjy1j-5_bu+5!W^BeJF~9k!%3&;L~pSlPRny z*I0n;Bl}4YxnffL#5RjJH$`yf$vB#?zR>&&-;lUl2sEXZ2xgn9a=acHHpvW-5S!@ z0_u-R1UgW#KAPjXSch}V+rr^Xrq7YDL!R*BUI_w+mjjV%_K1mG${^U-rG?UKDOqY5P`I$RToNS;3ohQ8GZ4`Icu zSi%~d*!@|K*xm?of}U)|1mn8D<2*z_x!gukYlsBTZt4`p>$O58S}i8siQ>Y9=4B*Vd*j}tO%2tP zSa@sSRrfF;=~c^O;27H^>-kgqSD#JJyU&(3;_+P2DOt>PRAvMU!dzGR zRY$R3PYu%FEWIzRS(mn}q%oW=^67Txyx02W(hECmFWdKTUKWDzJR4-1BBOL2j-Ool zQx^*iHR7Zeo3-1m#k(x^^$Utx+=*q4@aA&@o-(ZWPqLiL)>Z!`zmWgAc@wI zKR{{83tX2u-Ud~}s*~AEch!uJcj8>8aBd%qB$eL^auziCbKa&@VP$ne3Iu|EJ_zo& zA1D0t-{JI4-=%n(4~^l+u-`w~Pq{-v{j-L!I+$pUICjLmrX<}}0sP*;ojmH`Rk3nh ze{J9PzRlVApNgl`?5GL9GxP3|-($QbdD(XB_Hkv;hJ0b~(`PAyzVl&Cn56>Md<<;_ zgmig<{lV$jo@jdXeEd5Tl!1HDn`(8Xeb2^PSH9gVo%Eg`wo&9J7-zhV&@p=N_W1FU zAH55#KfG-Kdz@Jxd$$ChsAI8zjFIf)ufj7c$ZlRsiatSCdoNn3iyQWPkE#Q^>7{8R z-ovZ)at#jUD;?6jd;4~v)vCb&1MEUp4;?=UA+_7IG`g?s7Dm%^b607A+9XoJ5M+Pi zKm3x)tZsEN#lA+uS_eQttponV#9sL)y!txYiEKfFG$s;w z`x!dXW^ZZOe;AIPYl;b0u-bvNSRZH1-xRa7wEINl^f#U_kgj8?^7yCbrrml+UT5l@ zzj)sAm)XTgcN45#<@zz~g-*ad@;m(Gg2wh2KJpJ- z?fGVCGQwFuJ4_eMcYc%MM@ItHnz%^E-)6gNh$X4tkaYZEK=u;(X1bv-DeFGRUA zqXe%kOQN}w>-yvcgb=Oh*Ump)5f~Orv?qFz6#K>D>jL0t?ypw={&wmL@1y5RtPz(b zlqC~FWqb|nt$A(s3rye2s5Q0%sp~PkwB?+fRie^sYiep<{iyU;(d4bv5Gg3At*Y8T z%rHJ8+}L`Sw*Z=-LF2XrDhma9U5FN)y(2m)$JmdbGbZUsjserPFh zW+-nPg3cfJ;AWM+gf1&ZKPW|?|5=)r(^1o#O&rcZPy;-@?$A3nqHvqj~2N60YjLt(ckQbI^FhT zX%5BOug!H|zoF_M1kk7)H`!y4F5-G9HkQ#BS=|Mkmqlj8pZZu+boTGw7JuUznRK3) z0Gyv0L$9Y^9jfJaM}NRq^V=@~6<=2RpU<>Mw=VVUZT9}~EcfkA(77jfEOYScM#ew4 zk1U5iFe4!&YaQ=z*B20NrRJu+7OB*1zKR;v#wY$Krr~Wps6^u__Ki+wP+5%NMm_yC zxMR*?`l6oR-;k^in~VIvB-ONxDUOUv*QEK08n0UeViY2)P@wI)m)h<~t==qJ+rckp zWY0QEln$sg&I&NQvHX_ADy)kttkqDQtWEGO@1Ld@e)hhOiD2sw+?5aqT2r(zE!1LX zdD!s%?lT}8M)qIKzt`7m6m7*GVuy=sxVd=Sc2HuV()-p)2Ydk;-m&9C?1c z|L4b{Vm}s|2ejRapeu-j0lWAjT9pUF36++=paqUY3Cd8(&LyFKAw49cvzyooTN^ zi;c*dJz2dU_jRtH?~k0o-o!YL+R92#J=4+h$aC&YkUC<#`I9u5;;8)A41T%J(77{O zT|3_KQGz0J0JY?9l{3_tZ5pWmdX8(inE0hD^mbvpd#BjLTE|kP*xW2GMr5yk^u_UV zu$|8{e=joP8PiHRmHjKasR8>Njm-=U=`@;OHR7MVs5;FYs&`=8WQ~g5H;@05OV#f?tovw6+M-OM+$C?XXI>KNy`qaYaq7I6-S3coFS-^1 zcciSJ`-l@OYE=JlKKx8v(_}kmG{a}pL1mDUj~Qqe`vPU(X?bG&SDmCmeR)$+|T$4V?bnq3j3#LNx$ zrh>{`ZaIu&6t(1heTo2wgujQ}=gxMqsp0w{Q)qXDx%QiZw+bo}2Nr4mF~V&O zZIt`ueP5(|Kjf0uEvGR<`tEJ!{ac^o+%4?8*C_OfM~}*d1-h{D*{C478)5gi#9ozA zb6?uMR%iJ((a}GzEm%z#{}JFn;z>~4bJF#(;%$?AMY|6>YqLh(eVa364gx4u9;{=g zip3i@vH*3@M`_-7u;j?aMi^iLx)cZu7UGlkQ6Ea7TpBqjo7^PhK!u{l*;>7!AN z+?J#w&Ui&x*>*Gfh`lPDbt8PJ7;V$_l&-IP2B6{8HT*GIfQI9GHQe zBZ*6Qn(t++)&p)MS(gakSB?8!XjdpyIG?R^d@AtTC|SmR2vC`*8*S0I_>k4u+xx_l zfNhpIJnhFi=CTI&P@&I`YLE-~A~tbDBIb}zKA1?%vZ3?C{S@_EPl5~C(^4s<61lGI zBYqV3d}Xf?BasOwa0stmK`l}bq7a_q&fHiTLHk=!h>B=9G0qsc^D&;z`wQ$iej;8o)Eu@eI?kX0zwqtH3OL4Y&!Y(GYXqV_L+3>D~sfT+IJtXn-^Pj*c?t^#D)FuPd%!4 z((}3XawZ;KZUuy#F8FGe1&k=X8#W5k79BO6Hses;L(|yNb=M@SKK2N`YTLDN1pzji zH+~ZyENh85aXNu|77M_C6mrC(5xT%_L+dZB=!U)s>R&5tKs28ijmxRaa3PcGgCNkSr$Bs)o!k>j}7Oxr+WLD4L8zR>?T=dDsdazv;{pc zi+=tL1{^_)h&}66S9`vbH*{_E94BDMv@{?U#W!$&^$$eSyq!VRi``Wb=^Sq~R#qn? zu7(V0KwIzFo>C{`ax&lqZ+w`Kyz?iBwID%sGGb3zYXIwDJ)$?_z#uz&TNsKVZuC%) zQqdND?d>6{E8G`+Hw~SFzw3p|3E!lhtr z9~y$zaj&X9{qnN#TmLZNf&$JbNv?D4AqhykU+1wX+{;7#$0pX?t(>S4of9a#{bzrl zO`;L;a)mvCm=vz}KdxIy8yMxV3D7zdtC9>r@S7w?$!m$PBRc0pm$EZ7%hx2T|FiW!ON1^z` ztJbhp;B3DjIpD?opChXC(g{LfU9uaK;9z1p8f*5pC7@BXe(XKmVg2NRBT-Q4-|X)= zvDGPB%OKkq$e%`S(+u7^;Y*x8vjI~$8D{3oM+_>4#2W}A-Y{1 z-+NiXmB3g%#$H-vAS@IH6 zmY;Hh;rMIhR3hYsSJs)!L5fTC*mcI1LSo7l2y$nJSnZGyzTPFa3aD@gE@=z#EZ}-q zen@$&geAOTW15}*rMzL|e5D^_+A?Y}tx(@NeM3vMY5+KQ-Z(B61aiWmRX( z!ykhhPW{E4O5juFsW1)oRaH>yv*--^+awFJ>*TH-gLLL)Ki{!=fE5cJ2Wb0;{(ThE z-u+p%e5X1_0FWhpaDsOrI)+|T&t8zz#blGCXtNMaX|&fFmwra86jz_w?hyBzqU>xc zN{q*sc*>|8VhpHpRsfeJnfs58rRQ0o3OV_Di)(LT$_ED30*>T#K#0$CH53+bAU!Gt zK^?(7TG0u$lD24>k>nr#HJ}_Xcm1(0$Th|s+7uSi1>fdD7Lv8QdxR1@DKc`n*X^+G zqz*f0){{3BmSus$3rK@E?6p|;wn%2fK{4KzIKNQuucn%mq3fADzD*aoZpN=-Ofd)R zmXS9%3$6?Ca&G_nO|w#HJEUiYY7*YSDG1ZB)WNj(Z%Tw`#DB;F*`@|CcmgsVpNiqG zY7dKjaQsgmn)|yo7=e_>k<^4pp(#~Z_RG^5Op>MVJl3Mf$jAoBy-M$C#|=eU&yn<~ z?1!dG8lWyH^J(j2V%MqOtS`82rG(z4h)JuwHvZ^ zc4f){scXQ1&^d!K9`+*da4ssRHwY8`7b(`QsMnc+-fho9*yyG)*w<)^Z&QoTM`Wo$ z%(L8N&k$=RE(xa2R`R?I?zlP%7h&V839nR14cb+*7>njg9QtZXx=|fF zwP>*XM-=EvwKq#&P=K;D<(!qao!F6P&fP;L#Y5jc=ZP}~3UBP#o=$mBmwu5X-%>?> zdY|n_MegqIN8Nv5`%VSce3$Lb)o(;#y+SG|-xWyi(SI5D`$QhFMBVcF(`3os-6U^e z(ty-DjCS)dRum{Vk64F+%-iF$yVD5R?tL>DuY5H4uS%tEh6m@UOdJW&@N&xA<-4^T z)yd|jAok5Nx^S4w2E3)T-}}%B<4@w@3s~*6_r1+Ilov$X*r%|B*_19S2jd@99&vR` zsFdBrCOo=r>|w(AyUWvtxP41s=Rid7!+f-hTe^2Aj36JFg^4;C+`e7vDL1)ftkyhuBi@Sw-?{(C)LVtc*#+CW zIKkZ=f?I yCaBcZbFyxI=JvcZbH^-8I48L$JnaoZbIgd!OgreHZ<-Ty)J*HQqU@ zB2PloO>Moy6>J~+oUB^d34?FtW<<8OAo=i>x>p^48+R}prY%oeiIOz=Z>=lpBQw#3 zXKL0g55Qoco!+z8Rya&F^okBkm4h0O;PHzsm^*pBEvpbX0`gZl8=uKSQ+vKhc#YOS#Hd=Im|UtXma?n-Ase)(bJIP z>^;B~>Mz!y)#t{QPEUV%`a*Zy>&YqL4w&BKr=ZTKs*Fq`Ipk@Chdg?@*w({coO+RGHIGfsSLkOImj zNpCR2^%o7WufwAGgp_=pP)%zbHI~cqyfAKQ%c+sq2=9(##SA}hXiO*3{oHV`^jIU-J8Za=lk=vk_QwZL;5EEN}o1(53-=3vc1_vKvspql(zTH@t#$)Lm46es+%Y z6SMsVu3vROi?x=~3O#I2x&nZ}esA0>yElYBgPcUcRNv>_O?2(UfwoqvfZBh_5I@mx zU2Z?>2oewG2u^-W4E2y(iDT_BgD5kQ5?*~aP0os9ce{wG_x}I{;mutQaFmC{J+a>J z9bvdSb8^O#-c4Z*7u9AAzSG0}WzbRjrT^ZIp^txMwwv|b!gMhX_L(MhFpJeHBSpBe zBX>u`*Z>Ih!NTy6376gWAj*M-J{fg7Qx2u!s0!?5l5C(II1Ofm1J*-ZnUw2l47J-t zd=&XAWf$}eEu!j?6g>d{fZj7Hnw#Hk&j_F7R`?Q zJnQ=v(tam+3H4tqTy+0P>{l;eQOGHJ`17fJ1^6>QO}~r;??-;7B)ktjyh|}c(}@rF zxMC^f(g@VCMsnT`1RiCSy+k@`ryurO`t0YJ5vX6jvKY5Xp)Q~YX>>;(xr18c(>u%{ zBJZHnASEu{c3|~TJ7%D93p?>;Nob8iXZ$|u0S&pXfT{^{I#BRnGoUz^fI8YdcFOC* zR+F&|L&V}3|7d;dMi95;3-feCa8b|*+;B10bJ<8UX6?5ET9l-*6<6N&&T8=&AUMrfofLN<+vx2P6M9%wi8N3kHrYH3Eu(ycfgY|5?l!BDoQ-G zNI3tjh1MP25aQnxCk{q{%e)wv=1aHAX`yAv?hwr2eP4|QTePmoQO94#K6; zeA@(lI%llZ&S|N*zQ6vn1ItJ>A2@ggCoVm-uH@H*ag-7Bgdi_~%YDN#Q#+th@EgbO zgw0r_vV9uUOts-tMQNys&o6;KA_$AXgj0{rw{m+~DQXks1j*0A{jvr((qhefhW#^k z%@R|o%~=0|BVII;@3JsUR4QdXIdJVg4^rMX0^^~o2R1%cBCWa;juKPVn~1#Qcw|>s`TO;r zs_Z|jtJ*ilx*8g+CI5>psE2|Aq*kxL|5^#(LlpCRTXUqnj4g^^JD85-L_o8$lD|lu zxY~^-LN{N`~B(8L0b-C9)lK|6z$$=M%9a4D6fjJ!vE%@ExYYxRpUKGLn$K z<+n0~tgz@%dzdL{9c>ts={XE`m`bb3v0m#J^}Es{(&;8mjNjX|{4SDAlR}1fJ+`;K zI--MMDNm`H(1ImuJBQG0e%`%z4@HV1 z9rt`DtP1FTV3L&hOE1^jX=0d$BmgTaFHBFD5Ry= zFlh8h=nSw#7)_G_rK!8f_oUw31e;nbH(8?qOyM!=-k|3ws>)v?VOojy+Aa5Qn$o39 zz^C5nr4<^G|Ff~nxR`_T&ktWJ=th5iSgu>+Ko8yd|3MINj*VZlu|hVjZgIoWqK2fg zf1f}=AZ}u5^L5x98cXs@-;<-6**{;5`Z8x4?Km zbH@qCVM;DAZJ4^16AVe{oJT4d(Tsd3PKLTZGsF?&%5c|T%b;=A5GNhF|DDKdaAM1N zG~@Vch)*3ls7CE|PXnuj^hf?1R31f@(bZnclf!OL_Dc_>?hCCO4wbt0l!y{iw~b;A zygXmWAq#*ooDF$!5N({5`<_D(;;iWEpek*eZQYP_AhEvUg4I20&cLe#@n_Jg@H+O% zB{H>5xVvkKS#)@e`Rn4(^VMGS-R`R6WWUit3Qh=*islh+YIOj4{WfNYN}`-Nc#goy zkbB}yH*Y^d{Kb3gVGD;ksFe|t^SGHNa?I&v@S+(OY3ANKN!I3KCbXp%d>()I^Nk9Y zJ&xsv;@A&Yz2CQ?{*4Z(Jz5NZNCw-u0b911o@g9Dfm}&o7ll2R_Bk~TOr%Xe49*=CiPkmpImZ>I z7wb~hQqea;Q*6)@W{{7&zdt19$*iMaBfw|QKpW`6knTvbskL7Zk!%M-xOb*de@N6% zLU%ed?mONVJ3sw?=cvW?nDEKFxwfT80a=?x;+RXU9KgZ@a&}g;y^wNx^>X%S%+|d^b6HhRV1SEy?!c1II1cKB#U0uL5)zF z_^1$>C;l0a031$OE7tyH8H-crE8l?2j|n{B+Z`vd@BnrtA5->($JfLpSp8Hg8dZ)X zrKZP;(q>Psid!^%`4J1HFYi5boOo+rrFdAcKZ^Ff3H4*$>)9edKwhcVuOhncqyz6= zj{jcR+|d9Nob-<8)CTmfobdo~rfzy1k8G(z0no#S|8nQ+N;%Pt> zYBW6+H^e1b+19!^o*`HEqA%X5_6Aq{*TlBwS8W3{2JAF6whB3OFDbi4er;%R=zG>p z>jh}G$Rh`=Dw=P6a`cC)dXT#b$dcHi=g4;n#7(p?^PkH+$l{)TiC7U@{+Q^^G$C;4 z=l2@uE4)s&*rZApXnxw6!xC8xdh(_H#q8UVeI-G*>2@UK!{V1*(gwz3TSf|28r}t! z@)7ew+D33w#DT?+MUirtNxBViiWZhx4sh;j@QicEV<2Sxi2p@!2||hiAa|itvO6ly_EDS<65zV?L0fwevZT1isbH5 zs5!xZZ(S_KGcd~rp)cBZY1#A+s+8JmVO#V~$tDa}-p^h-3!Dugz_v=7S&ZjaRo-LVhRA(Wau>~>wpI?ESC0~Cj zp0qC|`Ct|tPrXHQwZgTZ|BbkFKr0adq2o}ZKvoU7G^j5wg0si_&WM`BZE`;83p ztKzr3HVDmf;OI#r#k3Ge2~dAUXk1%i?M88ivs07w&J9B&JCn!>j#T?{T{j#EhV_cl ziang`BW9N{`?W=wxB)R<|4{q8jYU<4a1eT+;kiU&@NI&y#fRyTP^ZlcisdX>@FgIs7C$N>b{`Z{gO~az9}~C1Ww@g6wpt8t0K)8ooaDfXR6m1}X3!U`g5n0m$m4Da&!UaNu*+ z+l{i|?JSzy_owiC=3Y5q9lwO7hI|7P6(ekQp{&NLz}U$? zgbeF2YcXuL&rOmyV;=*1_~fAMkv7Z9EH~SJY#mjjGt}rO;@G)y z?a`~$(sL2ioC~Vz)Y+;fJeW}EPkn=jI_;i3XsYwTU8o$mQe(L|Ic8F0nPf97syIuH zeh8fJm*$B3F+U*+6QzL*tGY$F(!y3WfNKQ ziz>><5@lH7heHM&-7=MLx^-wQ-vzeLgM#AP=%WVIJ>-JpN6Zy^uT|ZMoZnik{*EE@ z^P4*zvidzp6A!52R(-6Z*J@|s=~?ltETe()ztcK&%?U;yg9CiO!JmjGV{_sF?7jP0 zGJ5yPEG2%zpt`fUSy+qY>$x4n_7eB+&mSxZ@o%nsR#$7Np$g}_!iQKQB?dL4Vhw|e zU8b*`U?ZX7n?YMr!L;M)OfK*4d6`3D;H7$SmrMCM8tbJc|FH+;7W8JabPiDeeRqiH zrtevCm@(c-D{HrqZE%b1_2az9CxvvyZ|BKoS^>?{$qIqN7$J1f_zD3U^RsM`>~{$1 zr6ga}Y5zUZg0YcCG=rQz+bsuYWa7Kau5{9jNFzP{_6)gu)^@Djm`~EZGj7^gqTL!b zZM1hi`!yv$WyEMTv^s%dsF(h9@!yt!&8kySCV3#PI5ymi$7~Mhq^h>6w$rVvN)-I^ zraQOdC|}R3SkEi5YEQpB<{Y}kGXRpEAhB2=o|ITaA7rLxx<6CEZDu^}x3lxHBb%aO zvnjAv@Qj#B3L-#f6Q0G2*t&kBKLf@?Pv3&h!W!LPe6cdP>6qb2xU@@Ov8N85N@I18 zjdQ)Cf^hCP=tn<)vzan0nB9LYJIhZX?taHKRi$%s_qeopu+!1Vhwr2g zO{7@84_I!`G(9SaUDik5ngy>l+*V zzK4r#@I6SOsx&1_#D0JWxO)BVO}G`C+dZk)-l|JHKF7z)Z?H_NI= zLxmbK+N^%nZHcadmudL+5cy%ozHJQ`DedOYVlA%;PW7e~ylXK*_qQrQA0KreIq`ux zuf+s&LmZK{H<6GRzfH9=O#+$Lnl+ymK67idia|X&4|e) z|K=5Iv8)$UBCV|TKaVl}hB$QiBO{+=J7vCpnh`A*_c-bd@|l*D)?5|4$}^xor$mu!B2+;q#HHywG2b2NTRJBEi`fat^b~ z+M8tn>d>9zGrTc}@I#w461^zrmnRcpwDbN1Y`f6}H8kjYcDV2`ZfX_HISC2SlV44o zf5JXG+%RZ~S~-_p>h$cm(Tx#sg9P70Gu0qeUj`)15X{d1HL|k~C$(A|rNkF&MUJZZ z-JkeHOnT0hcQO**Ws7G8O0R=@JuO9?*5WhMI_xcS$G3#sTW5S+FN?ij$mKFY&@Kv2 zkH2ZgRdU4*NF!%G<`e>JnxywM6&g2ubGVVc40eIP-+pjlwja}^o^vNwSci*n zzVm55%cQU179UGwn%uCT-O^|-Zl{?67|zo$9obIDtg7Qvb!dW`C9=aOjM}zucpjv0 z06so1tBn@S>^(o5y$XK=^Phdr-PZ`&`Jx`WrLwE%?oWVo!wa;!)b~J@?!c}m_XM7$tJ{nCvxx>5vfgJC=vwKdo1^!}C*{I=4kpd}!N`uq!29CO1k$lSQ> zABPhz672#)`~j_J{7z)V|H+P>(Vu;} z-Ini_(H|s668soalk26%TBK=ctZ@NV_U$``uNcLo>+)0V3m5`Pffib`fd`PahjhA8)};j;0l!SvopB{fj?yF+Zr9DYkE)5zM8%t++rxVn6<3 zRN=6Y7~q$&D~8})Mt+(mnoi^SC4`TeLmB||<_CQKeOgomJPU;%|%cnWH%o?yy_fkgNVi#9)>iS7*ZR$sz-X(XW z*MI?xQSA3RsucLIm_7dh%tvQvi<1lYmyBCl{Ta0^USwiO;WvLtj}*f{b#hf`pifJz z0?ekpA=PuO*G~p!ai0Pv&Q4HazO=ACBdNkYT-6A=<&U_6R+DwIy|!NeB{?u#Q`ewi z)2(9mp?y)K|B`T#5^R8OMY1)_rkOS(x_)wd59+pw4bnxu&vrZ3e1N7HQx$r;Amh~- z!xz!~)0&c4V_`Sc)t-YEH7zWjo7Akr|0Xc!))AGuY}9!<_qZHSZ<6=9oD1B+3Bpnv zYWkGsMYCSDO2W05$4oKsDrilR~at~^IA*FDmlePl9JS_!Wlw@ko z#<71eOA*E`+aAZUf^eYMUUg82pwsU<0|)#mz)_J4H3?=g{P;S5!w@=xI9svy5$IHr zqU5a4_J4%(nk9gcoCNSd6_GiZ-yO_4ndjx!iLTYaKC$QVjux<|pF#*`|)evUcGM;IjiF(RE>}j=8kT7-Bc4MWP5` zV$;z0ZSY|FT{G+(vX$D`iNh_*>TVyWA#d&GE zf%{&GfqIUMlpnCnPdgx_GrKrfrGFRlI|PjOQ{U?78`a$7v&Nf>vLs%rX>WE~7+!TN z1^V}%&jisqBxeOg;%XA|#GXyRlXEAm9`-J!_F_?LNmIJWsn~E|>7pU0%T3&#R~Yfm zx$L@+q+KW|Dc$0HsKPi}bjkizQc`cSYbs8pb*dKkW`V>L@=R2AFcHSFCJ<=Zg`+AH zvZ~npzFN*hOD5eQToph;&crTZwI9(}5B9}8LXAg`G9#XbfFHuz#WG;BXuOu|+h#Ij zkAKj}4R|g!Z_e+(Qc2s^eb*noa-z{bD{Jo5%wGxamos+J9tIXB6jCz#=KSMdlvvl+ zIQz-)$6#P1&DM`gPg~q%^h=(av zW0so?!@M);#+Y%Z+Pq3-pJ_9iqp7=@3M3Pl%)!kO=Ih76aN|5;@HUS!6g*5SZa)PU z9c12TIAAO|5NM%03|`@XdJ}&xem6npJH|!QTGxQDhDR~eGlth5%Nu;^`v{yUDoE)I z=bCjKd_-8@m}?Xf9?oe?Re2HjzRs-JgsnsC53{Yegzj!3?sPB4Yiy8PF6gXXw)P%F zErD?tdQt+d^DOT4owV-6bDx3%mmVYrU~ZF(uBI&GRvpJ)v>JuR+UzBu^b%at3}D$n zSNz!uiBl9MFkvZik|Tk8OVmegN(+M@&DC}Z7X2t7Y3Pc%9_pPP4Ip^f*RJ!|Dr)zD zXn0Br_>nXA{6Wn8CAQiS#=@2vp>bN? z2`|cHK9OWjiknmG>k%m+JcNN&W0?)1X;c>eHX@o&&(WSlk5X@EAzv{keQKRzXA$3P zQ^MXQZTg^(9i(qCk4dLFDF&~uP{xz6pgKv zZAldzPrP4ibmS28Mk(gg#s;2IHN9*EkOAa%KNmX({YH z;AM3Cd)^++aYkFOp+In^-aPTNQrTo1%a4I|I!6SY#%x{9P}A@^C=ixt9~{j9C$X$| zHQ?`bvxVV33;Bb0>L0+4MQv?$HU_V3mAGGjF+hd)`AS-S+WzuW6Oh9Hj}_JeI#=dp zy(ZPABcIg_{A(Pg$b{q+1p2#JiEVg+r38IG}kDvpK8ta%q7BO$Dz$S4O6$E#!2;e7kDdRfi1}WLS zWLo=M-${iBac_A{8-#vCy!||G=Q(MnO*bZ$9O(9AMKmtWFwf+~8EYBsazN9DgiF^{ zdv9cuE|mSV*4WrrgJGYaUrME0i+^0LmZ+iJD%!Jo7!m=gG|eWh3R?mK^_G>JIRVNn(E@x- zb12;$Z{41T2?5)GK8!HOQI>4BGsNFzmTVf(>bof!4CkSi$d={wy7clXI+W6!!xbAZ z!8i$!WIWnU6P$7*m6+X%Exi3$8%Syx;2>vX`VAT+PbU$ewc%ZUx#B(vQb~UG;8uv% z7+i~g;@eQap`TmSHV7CVTdPX2I-Aowk;n_$|lxja1u}=2>9=rWJ zhOiuyn`73-Y~P$b>n}2JHa(0q4g5bg#EU9s9Kh9LVBPx$O_gj>tV(klDf?Gp=dQ_Y zE^N$f7$#SQ?HqAU$29<}SY zfqkDwUftU`Q;>4zvck_E>a)G`t9in(HW(_sdtnRrsMHV|p?<#f8~j4s#zZ2^T-%>M zP1CsWXPnSy7YVhdQO++2fGZ*9JdR8cT$;OroF542wYz(p{AJ7t{@`MTx+a}~Wjgqr zE<`r_T9t;{mH2({MCH{8c_}({gTpXfR174-9jH`9FTOV={#(aRLXsS-BtM0E1jDAn zMriNa{>qDb80}bpJBhktG&D1_7CXem-0QF3-k}!WKn81JKPeX8Tep%&R(xX{J8kRU zvg#kU)D*vL05=v0xHpuW((3-NGQ_@N_(neR^P?N&Hgrp}PB>PY1DoR77ot-6b+*cH z+~lzj4a=7&B*6tK2TdfG?(t{Xd}Bjzq6}%Wc7UgA^#)(v@~b>Jt)mH$uVz)){hXYC za9H=QR@;gq{r;K_IVg+W1ykO?2kkbXF7uwP*z4aid`waey78oSS?elO>D#hHH%TiG z_zpNeJzM73N|BVIZ!peN*B z)xUD`A*`J0?8ubN+Th{wULb{nAGfC*+2l<)~ z8Nh}Fiv~MjgVMA)LdOfCI>)ghgZmrC)SMXt+h|U!5(os^TR1b4#f>{2USU8Jigl~$ zbd1r#Q0w?*&m*oy%t4E_@LZ>onasBADFT^5|4oVJPOMWK%_@w}NX;mG$ve$=C}oOf zH{M~bit=SlFKZWdAY;`;{gM%8+fZtEokRHooj)Mshwkq~3EjAzp*iY(fY1@2UKv9I ziF=_HYrT?Wgl@pIPzG9K0-~7`gdbm_p3JzBSI6Yl9SDinrNww!ncbHeT`x(v?+taDwQ-A`zE zT$X{57$FS~F_QvGi_rqk;=E^@m}Tn%ukYQ&vi5XndNmcdI* zQ-jMILcCp}af;yHlOQH%lIOP%cQ)vTZMTrY9X6E?hlIC`_#V1n@CjD%AS|wiSGRa+ z&DsXq>u!Yd6Cc|YAP4DNQCM*(drCzNNeS4x+SW_O>G6_G+z|J>p8RE8nOE@nkgkr- zi|%ut*wBm@8n2l)Nj|d}j8{;J!3v|D+5Ls1&HY7?e<{_CS7A-$80yVVTT&2eL6boE z`}UWoOC7#!+#7xKP|_pr4cj8%dVr9^yCD7zP#eY~x%YGMe5$AV*41cmZO8Wtw6s^;*{Xk{eQbe1Q`N=23`O*62 zY@X&fj`jC;CnF@V%h!K&jneTZ_I9qM#|z8r6e~=C0}*z2*zxUy9nDXd%}m`-)_s!7 z_+nwyULuRUIj@(5QFoKO<&aIlv+G?R6k4_V-)j#XWDM<_wtYm+`?l@ovo$8UtS9tJ zN{k1%kuWHzXyF-^@O_(br-gSv(EFryF)kbi@^MG_s3#6Q2Xqpv|ocXF=7b&O!U--x9Ll*-lcc; z4TKEz6$*LE9Zi`0P))n}sNk~nh&Qyn-1gJAC+NQ0o8uA|j(yTk=_0N)uW|gF&R_}6 z!rKQo8QjXx6L8Mfz{ykVgT`gO6lY-<-=!Pk%3VL-6%~nC z-?yGR_+2{nKtUpDzuY=oq#x>I(pJM|X4`LvYBqBKQnfW#qGsc16*YvMqti(n^Ute7 z7i_i~c6n|_1Sz3a295V}wd1uuCaeI5iwf&q?L9E5m)+WW&^R71Z zfRj%*Q58+wJzGbsOhLSEbu#@wFSmVg>M68fC%qFBO=VHd3jIjMn+*=~hjEPB28irqgZV`X98ZY#X_OPOW)7~2XJSE8f*XqSH z`vOTqpK)TJF{C`!7faGE-j48$IAB)(ES}cpr%J#HHZ@l}CnVlouc2C#CCjF0z-CtV zk&^AC5ep06Jmm~Q5qVl`6REpC9X@aLigi@iSl;Q2j2CGRzI?s^jvP=fN&98of3VzT zODqo`R|$nFsBqu_26qm*5u&%U@n!?%SR!5X84r5x=;CMTLbq@rQ*tkH^$l&02p|3G zTC*kV92I>cUIs&4;?Afpt*?ZRI4O^(4u|&3G%Bn6xUNjY-(4tr&a-yYIgY0nilhCe zfaqm4_J)0oFl-XDgKI0ViS;7hTC#sI)BpG}MQ*5H&~4$*+Hq450zwjCKh=$c40epE zcEl5&D8Hbk`g?-jh}(%juQf(~1z>bm0-6e=H|pDFl5F!DsDN_n=Yc>KYZ$7jmDUrm|Y53fyc651$%4A?_Ki zRHKy+kEaf!U8Y#+lj&xHlngyk`qnIDBToLzet>)Z?DOi!&$JsY?$7w8Oev^2Uk8SW zV)`X=(jvH$oML0WRuxm4M=Qc1lfU@R2-lI(7qjMIuW5s#47_97zf)*X=OfwLH1X`o zXkEW;_+~sBKh=>pSD~RFVH|%^;t7n!Fu$fC1U88}sK3AIP=Rjls#~IoP#s+@?Aw2{+LEdx^$u+^Ocb@GVwWPy^6^8s zymy|<5-{=@6f?x)vrTRN>|d{7F-ZB5mD(RkI6f)1xP~VvtQ*R6*K2~FM>yY+Ktt?O zvI6K@fi*zx5+3dW>>Eb5>M^*$T5R^0U=x401a1)nuGTAM!EljM&Zy>1)qaO5{W_KP zdJ_5;`&CtLfB_bjN@!wE-1cNT?8J)2?N%N}T&qz62b+M+3XGV5?w3EXAGvbIl=8v* zjA*9OR&XbXFo$bQp40xTV<05x1dE`Tq{x`_sIBz-_ecu0Tip(T2PD@dmP8}sh>s4ZBPWm`ZYvi+6`j^niKZ2V?7JP1Y6~0FonWo6^^O^JXr< zXJ4>|ATnhdZu}in7EJaChS}l|ojb|~dbU>QEyQjKJYj7T?@k7J_V#P`R3NuxxpMJY zrh~XlzFavyqB(VFdsN$=dCInqn5|kwm)EW#8HVrTyF?Sl82n5L#lNjqHAZ{v*n(O{ z7SM&=;D!=92?;#7_Xc*FwaW1+htSh_`{8zKNlYwr(x!)ZQfq6|N(0s0D zD9P?BJGQmota?VTe!>e~iGBzisD5FCpZva8P7yW<&ExTgW&1=`XRi9|0rnYf$A=<9 z<&)3Xdjlv`%p+-*Y9RMY^n!tY|O*eYwfbin7Y~KhrD5`zPg2xsj_C}e0w2T!BWel~eR)*9A+9XceP%5_2 z|6%|FcdQUqx=4p@u@7{G0;1-d(;4hWY$EwsIieH2J%+188l8!X4JArhtk29e=P}o- zX3z&IFmA{~701 zfI@DVk8ehY4T)0k#AdOC47CrN$dLZ_6pW*~RWWDWnw7IKGu;HXygOBHIwvKST(@G&n zB=vB-_xI%XB|RoxZ6P~4jUSr80dSdcy0b1*zQ8WvgKoB*wD4SgXJE~zg8#^z0Z>9mM&|2o9*p!;%V#1VF<9b ztpP1QvKkyg&WVgJ(#m}xiD@A!Agm!3LPu|n>GjKBXqSA5Ad4DG&o zSSMh&!XO<|shgQ!tHa_m0Q&bdyJF0in7*G^@|HB$gw{Eog#i`nNGWv<)9@Q3=h0$3xUfLemxm>n1gyg_TKgw`>>`FvX~|G;>$hgcVZ zaYVbsn(r7K-L@VUf>C6#+ZW*eskQ#G{01c3oprPM=0f}B3u~GG?4SM}VA%hfBZB&q zYms~Kjwb@a(=yPf{lGngZ{ud#PonzG!WaeULV+j#wrfXEYewaFcORj9PlSd?X~sNZ zzIt43Q{C-=p3^5E(wTTyr0u5i|%9hDuZ}`9Z>4-#TeW}1f)1V zQ*ZiDLyRynaAb@UYWQrp+D<#rV+eG9Iu z!GX>vNIQJ$Rv&kab6?X=$HCqnVaq*c^G56oLgeLkzR((NYcVB?cKK$tZ%k#YaN7&*}8#t5ud&ENXOkPZtz3# zL31nR|7VNT+-bh~F|(r_lBiEuUPi0eCpP}%$Vlxi_!oWXW$$lq&!1*Ga(eO8!^8Dd zJ(B&>7i~;azMnOa7w}n`=Ur5Dt_%!s4ni{iQH_SftfOQN59B0#4mB~C+D%h1Z?-?F z3EF<2T5r@g#2%N|c$q1jL#3&cl-p_>dQ-QE8^U^`eiz7F6r=V&lEk$Qk+_b6T7ML+MZV0L90K*#o7y zK6in|G@=6+aq88_VK^j^vqz(^m)!WQg%~Z!$y=yDQ*|6&+(1NtkhQxg#0yQMO?!`XXHm zo9)%&q2=b`v9Ke01&IRFTP{C1!M;_k-_>{_aJA0xnlqM0{^pZ*Q)sLGw4@zpDkHF~ zr-Yc{K!1VwqO-@KV3pEf%Ix>RfTIL5b`%g>r79;4eNqr48$o{-3aMwvP;5~X`3bv` zXYN1aq4RNhtn;>c0Q7otg!%&AefQmOPKKl&9qoG%r2SicsQxKbxp7XrQlg$gBl|`U zMX`}!`3H~T7^<*`xEIVd?*>b!HE;-6^+dv#TFl#?2~Xr0ZlN2CXxcVEl{U{2cV0d8{_B8e4BNg!2Q;PqFYdBEz=ZcM^1f?@ zb<@&@JDUYES`uGt$G4hiI);`D4G4E3hx?0pqkRBhMma7Nbn?y!+n3zMm=Y^by1drJ z%RB_ej;JPg%6R*u<@Gsdf3Z@PEJ5RiY|>~BtF{em3}0t+`*=6N4O7)v_t`zNE z83Ilc5Sq$A?<-)nEQ#kZQqQt&89CF{-0PclSvmhOC3nTLKqHCefZQc86*dy>;{dS+ zHBN}|?eX~f@pA(Ug;0-9es`m7m-F!bGI(fI=Fz##EL|94BRNYg&DXf+7YKNe6aK|b zC;Zy8Cg64fiG$i)y_Z^N6PbfF_4az*T=J_nD{CaMgbR6^YoOUZM>5Hn@$5mJr3>Zl zyyEVAOmU?!r_flA11g7q7o4eGED<#|G#ePj0@S-AwAr}_O3tpGgp1oCiog5f)XwPE zw|^hDbR2QVA+^olH{KZ7!?ZZnz6e!RwE~ULG9o%_x2tUdFB6yldmfc|os`|{k}i~2 zvxQgWPBOE+*NV1&8UnYlgtC4^&S#`z4i4F&s90y-Ii?qLzdm;I#tX$rPtbxxjE42Z z(WT1X!ec}i9D@4~@0%qafy{*tmGs8NK8x{m=`c^afKw*yKJj^)1}fwuP@J?t|7fEQ z`27cYmG8j0Cu}?Pg7zkzW%G>AkkB5iD~#40Ym-B922}TKLXdbH8fO%@ST5kS-JO9n z!*mi8qkyyc^EPgX+IOn24&h zjUt~91-wLPj)@p1LwCs@W%;nE_D6kDF|q=`w3jP{^%kTawk(8+@G87#NbNy}pNXa$ zhIrKMNR8m9?#&JLG4Yw6Wd-kYKRQ+vox}A)z)TG_T4k7*iYQv z{P1-tft$2bnOtH619-3{QVECB$IEH=9impB1DCTou<`tWRUQI(eLg+YD}6mQDqFCT zM-2qTk({DEJpCuCkwrY9c+)8}ex`aY0A=nofGbyplePWnq_|Dzn@(vu6G@tBL*@FL^R|2 zrfBodPEbR(1Ct(Ku6K71Pluw?+^kMsMt6!N_)7vSjeOIRtI3y079wZUV}W5(FMU>H zg)|v))IdT7Zv>N56LqaH{}ξTQYaGF}{Wp8n`~aU1$`Uo2g%eou@$&o5n?60526 z8@DVtD0*K@E*1m!W|6F8A7sw>iXLIU<+a;xU|r=AN%}A|KmIL9<@M;!>WXo3FV6A7x}inAy!mtSz?8UkJ+GKvF7tC8 zqVCY_$D%O&QncRNK9X&HF3pDD=unPl7ahwj4nAB;VBT(}j4v9??R~!q!<=ejpI&dyuJXsReZ}T@uflb&ZF-gK8o6tI zBGlHOwR7T(w@uopQbHN>-T6rlSkd?Oog<}O+DGYD`xf6MO}`5vH)wGaKQ)XW(r6- zoFv1)A{JQ~RyCMxrlYLyJN9zotW1ze&lNPGMF@8elW zV}Xg?Dxl9HVFRf5!AB5J8RsZOuoKgpNa6eZ!b|I}4RJbriW^_PlDaH2+aLH0Jyxo> zwsbTZ34fV7&w6qQM($&tRkLp=>? zHf|4&eSK{V4Qm*Ye|F{TA^v)t!})Zenfr~WYf8p&fxi*LD}%qmb(Eq0FDu(tlxor- zz+(?D5bxZgnW9m4&oikqP{=CK)}Tpc+ZI}~@=t#)hA5%WJh4wbR6JCXmZ`~G#AA9m z`}e7Q7x%CO8vlH4!oqr4J0IQ0eo)sikp?E@r@D&L*xA779y&dGbE7p zXv&@_2y4rqJXs_)3sFYN)im zoHZJ)s;73&$)Z?|mRY)y-QwO>A(3)d4_8s6GR~W4ye3DhiBxKpJa2nQcnkDR558e` zkT3~dW@F3g%DG1V?3NEd865B151_`%D8wao*KD#=yXsW0!(;^5ws|SKWi!_xjKqz; z6)u$3BPF81@Uwo6$X$Ttj9P#xH%P>X=JYnKt_c0KEFHBDkJ$z zl#p9J4p(Q!_P`1^_Uv(vTq(WGTFaH~<%4cY>=vLtrl;gAQl%KP4c4V+{?8`g{kEoyU|MN z+G_d}BUTFTsCg#R$ZTD7>7@lZBvd1$K0Ua4L0Bupb8!%B?@{#0USQ6^;(_8#YuW!z z=_KZPTx<<6MRvNJ8W!*6wNALQdkOP4_ zgxyy!_jTFYTCsrk523st{#F|`OWNuPYQo z@w>*Yx&4Hn`#{O-@C7%vG<_V_sPe+mVuPUa0LHD=Q`wDOewbj1C;#k~bJ7NX`syRO zO(M=(=e7n!2G(8&sr2H*Qfw>v7(d1!4RfO0c}I;m&VKP}h-{oO)`~uY@oaUEOfM-_ z*dD!FhLPKE?jRz;vjwWFItg__DlWE*_bw|cnwWHb~A2Dpr&z!7?{($4tFu&Qktbly=y#J z6RqLEoY0p^YzZm*me$ZHtL32iZ;>DD0_s129pZ&)TVts=@1s}9qG$7X?^;?R86sQc zORKIIgpIc}DhPAoi#geXzLb{L$_qbtf06kUA4XWMe^K@)VSkCBp5(AuZn+A(X`EXC{h!Ba$<}bvfr!uhXvIZ zxvHo*zL@3)RCq}p_2E#K*tl7=?Vgk9GZ;*zH6Pu(E)$ctz>O00LT(lWwBwZa79lx4 zC71rh|IbAC1Op#gqaHG>l(%D(vMbVLWFMp!)3Wq4%-_bd5q2C-0$Q;;qj~9p3rq{; z0s4kz0y43%XzqNwrRgIrOVpg_<2}n3WHuasf$-x0ors z!z1WE{D(sd!U*uS*@@aw?;Go)HtXl!26zd1lH*2nbA}}9X+$Q1H-1tNbUGUwP?2&0iKY=eQF2;=5zDKG2 z5e0{Dam@e;0mu&^a}#49$KeIH_v^9E-mZxUb#rF(Q2@HVqvSw%Z|LyOBc51Rz|s-c+4!wFAoBYS z98Z@9#sK$34T26fp+rZ^qtV>J@qr{;RJ?u~Ve`0)`#26IQnW7`c9TC|gSABX8yr&K zOM>UBXcZ&@6v~@WeJUg!gzVd-I=R7*3iNst=cmAoJWKQoyFMepEPt=)-eIZNTk>E#6ZVKcD=)p&aQ;4 zb_y7lX{k|s<3Vd0evLc|m{AV2P(9;8IktHI;gjl5I+f7?MG#v@8pFDV8^KPx&Bv>G zZKA70I&`%6HdH!FHN@tpcrW%<5L!h_cJJ#V`X8G@?`i5Ve@D8z?-0T%AAIT{3k1Jw zjz5p|&-GI$sE=WPmL5-!%Kc9^`+HNlzNbcEwKRNzL_?frN7jk*J!|2=Gu?aZpf=Iz zB&`T;lmL-Mz4kt}wgUf?B-$oBz~teCC}=`U`9DjE87Cq{zGLw8rTDNq+CU21#uX!? zX;OWT<0Yx#Z)T=iafRd~)oVDvq-nj-*ibfsPiovr)o1iIoKT<|c{uLDS)Hr`5YQ!V zv4WR!y0z!WDR<(xz|FmzDska-?dO2jI3?Q7$j0miABNp0Iev5+kO`i?ZptKxVi>_W z$O=^ZBa-wB&Nw%#%I?Lke2IQ^(#?xfnTgLiw!@R4P3vBnU4-=ABHInI>0N26vGPkSC+2K-yXvIk&IRNC-e?j- zCZDR+Wpi75rjVp*?~g>E#_0yzPQ4@(X+EFu-XU3+Yao}`qKa135uw*|rw>h6=itF| z%Zvn_2BNbu_Ra)-2R~Uoe=hq!@)B;_Z!fhD+2)>d*kJ=_*R~dD4AlsZaHGwpm>#NR z)u#{GoBF+%(_91KDU9WH%yy2xuQveWWe&%7pg$u#_v(X+UIjME@f?fN+Y)zld=6&)I{3)lMc+tRvC#OcvM~bEQAr;F^uiAWb^(gKT1AGI3VRoF}_g zXUwxWz*{Ij7I-XUCp8_Mw6Hd^+azn7Rb)5bNc(}zZ5Io;i9^()vMv@|=dGWtYZm#7 z0Lzu9cC;aC@Ms2}Ub4}Kmn0xjLqTv^Nm}@vwAo+@bZNBT7*~yzi))a1=O$q<<@t6J z6C7cKVIK6a+K<}{xFXQr80Df1FmZ)_zhNkk7uao%YAc>FVHL0FcU>$u5fQif!d(3| zJOxG}r&q9?!|+0t{5G8I=?DH(Md=!#da{k!(FtT)_zZLo!};eU9a)IxSvx!cZW zduZ|G8x4(`Z<_SP*2V6b#tj)E1s`No=;4UW#MC(zZsNM8OcqV}RAh>*?ZQ<4OFDvi zO#h`#(9|6OK=62-v;?aP6oNQp{4kRe4=)q+usI(e89cRhL5R4Ml>8FJHGl$N-Ar|_ z^4rzOev}n!j??ql1VFa8@mOMg;CrU(#-ImOv3#5!{;^Y+Jk?71NOu%(7U#vpNdWPr zY-Iz>eNyr=DGk?2R=7=d48PU?1lc=2{n~3WC}~=NaRs#In7Mt>XY1X+t7Ok|gVnVM zaZ9k4Fj?A!P}EppP&PR0u7^+rC+L~2HHEM(F4+UW1a4!PXm`rud=csd%L)YdEh31x zS+M~$K&O7CbqH^o{YZ`}=IY>b@lXHcdTk3%fz?%(Yf)bb`~2a-&vzb%Bynkr1W0PX z8_mfEz)WrfR4=iUy$2=*tx>j<5~<(-Xq@WNyy};$eBuS#dOjTU6KJN(XqJPPbQO}t zm+0Nsz2@tVRmt+JxJ&LrEtAF9H3FB!3k$L}ga#IWHpHJ$dw83cf56eVz`|v%4v)@G zkgt79Cz`ur-zwN9ym(Ra_~_c&=JlVqM6L{seG3)*1&Q^@eQluV%B|}vgVre{ceyUw z_w$q+xURqx5EaD#onb`$r!eGmYn~F-_{T~U1g_u>yShC|;QB8RY2N(ne^+tSq%9|L zrv0oZ+JWUCsRGk%vY$Ya>r${+7$;}|s|PIB8cX)GAsY>V?^m}3HB!VGLJlwp_e@AR zYlI)WVkL?66P?=D44=0wGR$wRqG0U!B63J1F2Kb#8mRPrja(peSS5bq3gIy*I!doD9H(({fGdH*op5UKZ>y1pWylr0 za)U^wI$n@>fPo_H-Se%z8o-&>Pau>{uN11Q&^cf`dz`7q7JO<${Nxuh-wMbiN!x2d z{gCdb(uDJrBV|Cd8TM<>12_vQQBe* zz2NEzK{5=@qP0}qQ&S)1`X_kXvHct0tdINr(OjW=Oz zO_8tk*CiwarxLq-`R`O#UK^)P{pUF_cD;ywvShdP4Ck^LwoV~bt^2UT(MXk%hO$uG z96P%|<`NmxOEQexoVCFgkC*b)zak4krU_=4S4nkf(PYp}+b0tnftTg`PaW3SJ4k#} z4nA7PLmSFb zPgc@t6xSwbeQ5OeAkrei-g~hT150Mw&a-9AUa{chrbbXPlJED{jEgllN8x@WFX>v-fLYDrhE}iMAFG}M6B*MrI6o%gJS54g!%Wh-(N~D{(ZO~# z7!x3Dv$=doHlD)oW`%-Ic{}*;4Z09d4Qb1SG|40X)h&0|VntVic{_mLx#Zey*>y3AaOqUj*O`R%=fR~^R6x~72WDo4z+||&aJ23hj^S9y z!2s;8H)MsbSDu1y0w070u)iTRAcyErz!4oO!O*o<>S)GKci0`lqpz88hTfP=11VoS zXCoY4dv>0JPD7$-wjD{s%4=$vm4BK~C9Alt4L`NMBR^Jl-K zy18u46KQyPz4l5mLtOzu*Au|P|H0n#hUMF17C7993oi0|dDZ`{b*-4TnRTSa-p3IT zZu=#Ye%B1NM?!zR@xfGEtTg&9ZPD8iw@*&2H0#D^C-mqhI7GbjBdIWR4E+%R-Tlsi z+-8(i@euWnF;L+!B2JW$>Zb(7!NTH~PRg#Pv{LT|XwN?(pssW1te+v3XU5l%h^ z8$BC~^)>zAw`6q=T^UB<91%?jr~UyVhm2p3#1-JT#?$NV`U7ELS23P+&q%wtsAHq8 z3n4lruJ)FL*}U@KwFSI~{5Si>OC*Oe)!<-m!*67C9!zSZRdcM1C#oh-&&@|aA1^yn zj#wIQK8#H__Qu6M$wc%p_emJfE;OLc=d=SQ;dw_>V_ zoNuuHunVsUT#{7lK?lp$$CQ1;){yvL!)J~rY!?jnyVH*au`!!4RuG?P9ow9xDu}SL zDBE^z3jAGK8)j!Z%qa552hKfndLD#c#&D9RyY;GftXmmG6c8NM@WE6YF$ZT&#=`0H zZv^l~lB;#92-eWAWhQd)(t69yc*|YU-}-%nV7q~y9uf929F3R8-hBKU2XMM*q53jY z6NV2F76kz{2(l2mUyb#eHTG+!M{o-Jk13dCL~_T03m8ZCI+evOiC>Z3%I})S)4$&Y z-56-w3Mz#)XIo0RYd50|P4Xl62JCkUN%;p`{&K#rZ^H0Zc&*e=9A+;h*yu0}Z=T%^ z(Wu3FHG^%0+aihjnUFq0iSmwc_YLq*tor2%cW9~&}hm6FSFy2 zrrNyvwVJ_+3&`bKgq8G})8U4iu-ks+Ei9NqfTssbi${xq7l0>1_ATHj$>l~KsP14> z%&)L(Q>U=#N;LIo!<-?QF?M6-gn}Pmzm#ykvXQCFS1Gt@qY#}i;i5|NLcJDmvywbt zC@L2D%>w%SFJ0E3Y)Dt@R<=hmO|7k7tzRSwu>QP034HuibkW_cD)lVhe4T%K18`Qs zn;m5CZhHqnIg@8#jU+?3>5*lq+6e3M*{$P?IwQC6WLnu990MRGe8k zb1XzD>rHvU<}sv}{2C|7?z!+0IwRqHp=C`&xb}a^G@z=P!6pKVQ@?pD4AWuo_QVuP z;d#yXJN-P2|DsZgu2)lR`Fe^~sVLO%Z87)${)V^aENsL$RMjI?nF!Oa%d3z@AYK`# zVUDu%Sw9x*S55Mn<%;%lr;&zj!`N%DkZU6Ydg4d3WdI7w4CU+pkq9Jn;TL#_vj~mq z{@Z47z{==s^>q!lEFT$zq373h9fnpTqH6O<$fAcu8l;#39>ZOf_HE|Ek&(7|+N0Yv z>1MbB6f)~tN#S`00dIYjmd<}aq&AR}{HOJTPMZCS%T`*U_*>w*u4w!>`g zrGNd772&72Qnn3oVdcv|6&QWvx4q)>i$pEKHTSyQd4Ec{_kE#)M*yE=(O zZxfP!Q~x47#zoy*T5-9k5YG{-1^U3}iT_gb&-mfcj&v(<%bvQ}^a{@4JU^_0By@%i zkxi{~ZQ3u;aoNs|I+Qy|8rA;sc^&gPk^z~S*XQ(&y=;DZJvW_oWi{)3wv{ii>%mzd zn*1>M=~aRvW7wu=w*&MIY@{3Sw!BZ_wx3>DY00iPpX!Ht8NhLifXiwc^}oydJs=ab zUZ@43G^#QY^}9r$C0s*StL$Duf2|bU9kW!5C**+%tEjg+`gpMcekp5>&hbW=2nMO! z8g3_v(Rs|l(_RfMT1sLN=Y`xVym^kGV7~}@vqDXsItAt%My%e>kO=U1 zP&vxpjhR$Pug5(-$a`RxhpyRdIeE!%C(C;P}|k5!(^(d1>u*C zSvKOUF0d7DT!~>aJjBuLV)w3;B(ajQjk2G&Y%SY&S=v^eJIjbm@LV6aL@l{~)a32a z790fpf_gXel=*l26hZXSIs2cX#n_Iu2JTW&k8N96@z~$54L|~d=G^brNUsg#QvX)A+ za)W?t-;=iMTh&iIUAFJHdKJYdjWiN?fxHseL+$lT zlotuI6=PrV@;cDxJStk{B~j-bSi8J^ejNC5$?xPy*W6xH3>*u__g0fe_SnF$6W|Jf zbDAB#g}yMsIm{1u@6uminl@DpI9R5)stm3)-nhES1wPS~GsZ43%j_Jz!EYw?dbhSS zHL55-kBjy;y4v^=t>czDRVVla3iXn5IANu@$d@8FIh3@Zo9xRxzvV;fu-qwHm} zJ1C^@|Fd+=nx$X=I-H!VK9bD4aX~2`>@*p<(Cw=I;zqD6TpGF4SXt!lc4)60v*O=mkY-9gXTu`nb9!m)*d!zd1((IlhS7JkHb zIHAR6My955i{|~p}c4jGTD||^EPM2N_u7ob_o9CFI ziXK;-|1OpB$kRziCG<8v?1`Ljg^)bz+s(ZvH*Rrpak(w4X9#+qu6ZMV-`swQ8aOt7 zK*TrfXEAK_N`glw=L|1z)v0YU2DnNZHIrl(0=Q73yrjp{rl!CEm}&oMKqD3o55-~_ zn;k;}nZ_N5h+wW4KXkM+Ov zb-Wcv?A#Zf4C0`AIlru&dDH>bK+Qf5);DiZ(r+vs(e2cqk1v^V;kDv8Ox*&%V#AdT zI*99@3<7o{FX343J@7&qZJl6_^k3n{sM5TS>57EzhP;nYhBQB;{Ny2-jEJGCDqvj* zHL8gzmS5%mU_L=jKlFZyWFV1MFm`A9X|l+6iNEjnyUpdp<}+x#`6AK_HiSF+GoO?p zXodQFER*R70d`lDL>Kp$F|zYI!xe#saY)Rtb<`U6n2lcJHo^qe^^zt1rJ%+n)SC5k zwc-DbRhKyg20*1GRd_RPg0_66D68Kcb?knkdcJuGqx3B)-j8lymYY5?T~btTZTa~4 zmhXrw-H8c2OHUy+_fd?AU+r$*1{OBnfjdUf|5!nqaC7wAs^YN+HG~uU6@Y&%LCKi3k zvS8QrX+ZGVBh;TpwBe^F7_-Va;-`F7ec5$9K*Eo+^_5W8O!jeC1%MehU6t7Q=SdXz^P3s#qK$ z$85vk*Xi+b#kSxBrzXl`o;9&;w@<5lcRepNM%m zoCY}X{q}YxTcE?1yG1T=^QiT#%xw?oTvoRA^tsY``{??jTBhqi&VVyJKW1_@Huv_E zJI!0OW1(Jlrd~FV*Rn@OP|#^s%vECSd}8iRnY)7}smsYT-`AkbL7|9RKZE%5odU7NY>tT6ozn*mjG{R}}Ue!_{7 zX4srD`2cHAxfX#3aa?xbprMocBwoFlvAV`~34-GzeuZXps*a{pG=Vl|p=ic?-p}s) zp^v)0<_aH_l?!U`82P%|<`&1`9WSE(DOxMv^X7<)MDIxEDFF8Nql3LV@&hDF^?BKw-o z)Sl~VBU10q&VkxiX$&pbcTLci2|S5{p^#psH{-jka8Ia8Sju|(_-f6Z)CL_}j=j-> zjf{--hbnbQU11%_yhxUb@G8H2nY3KD&Z>2loX)$I)VM&yIHIDJDmdqa<~u;56A9rX zbPmgxUK!Ad^W_Q<-%Eq~&o(7&NheZ?h2#U~jiS*ucvKBbXC8pzz!yr(Sm!0Q_pkNa z;#}G*!ny?s7}jYO)c~#6~^3C931dRwOX5m35Qo z=f(vT;3^WRNWc$_l9?xvd7DOe^}X358&^T{I|{vSDyl`me`m4;M|Ym-6wS;q8D6Y7 z(EtDdm*`?{;ccDw-`8LyD*ufU6|k`d@R)<041NX1Us9oKza-06seP-2aBDy^t-l(z z?$&G#(`zGMXpJt;_6kVIM{EudsZv`W>n-!(sMf3%Tg+hp;r3EX-&n+?Udx$$hUMy2 z0!X6_uK3ZIxu}8KIVG`gAywSv#CrdtLOv zzLMpUg>3!DBpgT2!k{T+S?Y&kLA;BUeCEupFVVUKo}2QvLilpkvMtKZArgRX{hxkE z--f#r-&?I+a14j(Aic7iRQYbZM-b=$Ty7CN-VjVEij@&-qT=61c5KJ=ODF8s_^79k ztOJd1g|&>`_~HeP#gOa>`$RM6X9SGXc0>9%8mL!lpG+=HFXnztvt3{~mHJrVWHM8! zA%l~d++4c{l$%;VLf}KS532d?g>^vdG73oR!^jepQF_ivKAHP>y~>ua(PllTk)T!! zCv2hGQF+HXby#NLs-cO!`G_PWB%0mch*qt(h~>2w`{t}sl9|p#PF9;Y?>OxjCvScA z5CVQfN8OT@1>qTOwJWP1kJ=JsbLA>C4=?UEm-LZrZ3Oo+Eu zsvP)OE{3SBeBywLzEHFyop-p|XH*Gh zQS%MA^_vEvi~7zf^Z8PcFdrSZEPcpDERI1BTMI3AF)B{#mr3GdBQ6?^AKiKe9p?5` zO&K2iCRJ1BE94PR#gKYHaWj1)g5fIYvjK6m ze?zV;=B(5LA+QR{Y(i-O&n|VdQb3*gCe~q*k2*Yb5 z?mZQLy;%7AgpFh;fqK2JMXOy0b8)`j&BrMtCx-}*=%MxC9`d`xWeq<%(;{VIrn<_T z{yd{?LA4mX4(HUYm#Pgr@#a;VR!er@93Zl14Ud2@jj2dK^ka@%WkC=AxQk)Zo9#F3Q{O7is5jrpK3Keeff) zwKt{&g8>R}+*3sgiCa`06tP#|@GNaqL#NK*sm4I0Zw^d8l()NyE62J_)l=UB2u;46 z1vTAQedSTWyMMxJZ~>?NMA*>JZV08d7gokml4We<6!Vz&1E!*^7)-(OWVVPhm8ip+ zjrJ@N%^N|2p$@7h)_g|0^p(*MW=QeYkjPdn8qIs?@0wM|Tfe$nj0R6N>=wy3b|}}d zOCSArD@3hSy8|M0!Q_+;Vr+<79QF}XyT^xYlcl8g=Pl%9t(Ns z_YcVQKDQY{$5@}~A)4u{U0c*%QL_0W+kPHRc}^%@S|{`jJ-&IDh=h(uTS##Oh`jHydm-;nlV-W^fxZxVTC6qsAgt z2}cr!gM-I1xQ8RPRKc0)#J81SO}Xth9aRrh@{^17-`5To%A(?XLs5GnH7?03biPk6 zQ|$4iWnhnQ4)0k8|BmFN=FoHTv%G)t-b6_ohnKpD{bMW!3G$`y9)mBUNV?Eq-`2=c zY?{Y!yyNZRN%zw`y(n72Zs4Jo#|5a-j=&mdHbm8y#C%Mm+JVCr%8BQNBzX#nzqLBT z{qv$9W6M$nH_1H5`Wo>46doT+%{vC)TS0f737=typeO1|;rDW>0NI&)R)EJx?71G~ zb!^#R2H8kINO}c*$FfzB&sMbS^(+1~K2+hKJw(YV{cnpC$|jp>4zc?Ef9!Y%vg|&> z*CzW34E>+BN7df=ITKMU>$g3)&R}Gt#o)Z(J1Wm`n+NlE9My4oU?OW zo$S1Q-l~5EWVl#`1A_0CKBTc$aeTLm(OX0xz2A$ib1OiT1LgFlUlP657mh%}vMR^I zCD=gp%!$t)$`UtAR&C`4f+N8!{x>m{n?REO^ceos7=D+9#@)hlRObcVIw=`KKcG5> zH|t-XvXm#`w4&=6%7@cm9$7ta@z7Ut=DH84J;^3+i>>=HLwv;Mi zpF=!j^<9Q zm(8~twoPAZqQTFRU`0C!-r%Ps+Pg`}gYbjt>UnHSra{&fYo=eA;FK>B+o2H(e^_lu z)QvLIJU{=E)8lzslfasBtz*UaW*sCeyZPKYrRuJB%b?u`^uAGyu*!7v(QWfK^R&iG zBQOtmHab?oKxTcwKH~DFPP|W}MOHOndiPHNuAcs1b>)#(O2}e^_y#DHOQu-fyrkO6 zmaic;Uys*L_nxT-=z`Wure!t7kA|q1;Fib4G7T}!c_61M$v>K~?IDqkoYW<-V=uPA zrP#*Xky5$Ni(~*RQyp97Uzwa>*MHVbvzR$6*tZ~WZ%}~PM%RxF^YPE0pQ#M1&XwYu zrG5yu6Np3^Y{n<-ZPQJl0k%Mzt$+}aN_g&FD5dvJjrT7 z(CgB~-M#tpvwc=T&zjeKkt4DUNz*O3WHb(3;xL(`t799Sb+enfqBCEG0l}=vv~&@a zf52YO6rb>g{dY3}(u>RFu`_n#v$1>SZ5tE>)0!O+UB3MNM{jjNO<}0K zZR1%%aRL_M~|FIQF!^NnX04pNmu>;1wi2laW8mD&cy zSOlJQOj-kKdc0}f?$^vuKwnI85gdp&U%JFPCv5x zb)0(ItOrqKmqRg@yXo{V;Pt96S~zeH)exCjOvl-B@(|xJ;8BRw@2Sg37Et)+_h=-< zHX2q>P2hJWUis>Ptc7Xu+zP4Th0wcjU|ES>4NWi_?qQJ;eR)7jCbFO1cG*$bWPM^C z0tEADOd3m0L?tN)9au}z{|8ag;7^_VwM1%QVfcSM_$|hzrNreb?xd{kfTCaQ0TaD^f{hXL%_bjmXC^>-1~ zMU9U2uW?=hmz(H|OwYl&&L5cqxXlRaa?6KC$BI9#_u}pjR!|#dWmUsRF<8w#I z9q;jD5On&m&aAZd4HP=7u~nuzUsfp?rm{5L(ordW)rVSe0=nXTJa4JreZ~|27#Ci+ zb9o>`P}fw1tRN+teLGKE<+d%vc)4i3o$gKq7KsS`MX&e6eh^gay0p;A*;oOBroPi!Y zaW!R>HBKf)=>HgnG%FX>kTKwCSId_>-#L(G?6=gyceR{ep7q^*%g|H*lA4?P`1si1 z;X)gqu(iN0onp8{BW|LVZd6jxeBe|=bH%Zbwh^=&gCgBjoa_o&GQ6a>$uHbaT9eSmiifK1j(x#TUsfPcy;I#g`Dvk zNyRoj#j8@={af0Ug~_=ymjrnFI%{p0=zsjWUrdW&#?Qv*&rbz9@;9cXkT^WkvA&Bd zCQ@c(VD3}jKgG$1+gN9BrrCO$w~jD<)$qR$jLAT|XOtKtTh1vN-pGo&wa>u0xC%#) zZj*|Q_+3({vv!X_I>>1w6Z3Xob<&v^s%A#Nx>O&yo^h7kJC*t z?`paNR}1MfBse%ITtpp{a%_b^`lS3bj}TI@14gbWqgYq<_VUzEiYXjB<LT&+)B zb=(V(0<7B1P|j7G>Ore3C54$Q!-Q&AO#)vQ2~YDun{?p#wCK@@S!H` zcbNg_EkiA@winl&sZhtjJzi1k)#Apf;_0=CzK#u@lNldrPyi#K*l@^LtGN|TS4;s? z(eF^keU}_S*G_Z^coFt^VG)i#g?5-Jq`as{vVWU&ddoxBvGV-tulnH^GF)j8$ZO^Z z*;rca4Ok5fse?DTP?`3GXO`T%^%yN%!L|^w9+#{{2%s~#Z&k3dyJFMt`+J=A`(geu zX(@`BnE0k~Zz559t;Fq-ZEZLWFuzci_dm?3yPdl#w7-^ysCxNr9J{Ul#$xO)+Mc|WAFwL3tx`-8acAfNfL ziMU^mpaH*+WKn-!i!^AmNY!m|mFP`44i=+!zyXA)iI5{4=3cnUyrNh{_YPj`6#l+^ z)a`QUSnv4>C?3QOq zJQoxSZNp0>##7lHoWOxYbU=~~NvUqkOMK8n2hwgN;spG7Ub)?v_drkcE_zih`jOQa za~Z(dR!UW^IEpKk5+T(;jn7i2&#Ldia1;Y~!K)tgo-#W^fY408E6S2aj7F({i?S6t zL})fcdO4M1IklH>WjOs~ZT>&~6I{dK{d40SYHXma zcFEXqsid$Pw1$Ay2afgel8hz9ykUEI-mWbx)~#>5yCOSGeC(|T zR?dQ@GPhnmWz)k0P?2^rIUFX__8~fm*e9J_xC;U>mlx&a@+PhO)f)~*>8P$}M=5D10ax@$Aw9IBRpeRO|2`KNTD zt}^_5Re+9iyE}>5Vm2*mGEoL7sOYfSZ95C>O>!Mz&pWoGi%qMy2P<$M0imL<!cv5Dqx$Kbz{XS122Y7?_OMoh_hw>PhvC3c4uyH1D zn+B_Zvy;v9ib>}Yc@^V#he+(|6>i{jWKQkpQIG>2G2ATbOLH;wW7)5+#n5jMZIs_U z-2AnhTMV=d3mpo@8ZFmcA+q`XNU9gecyY*R8vnUoFZ8K~FFrRDsjHqYx2|!NEi@KB zQDIkt-u z*RSnvZ}m*Yi%ED#C&-nG8cg!bc3*wvxy5?MDuE%pq_fglk7ck7V&{EIDx?`wXWjF9 zNq*`1P<{3o!%bO3PdAfXr`xk_sHM~M$JlWI`%eT`J*H(2Whum4tmHO=mhzXig54cy zdA+!B%PE5%j;{d+%527=sTL0xaObgCk1slpNUOR%*2Z13HBbIc*bu z5K>Kjy-Ahn%fRjzH@~2@Y{BkiJ709;USsK;sUHe8MNJv_>f2l8cm5G0TSnHlFmqk@ z{7!Bad*j4!hI^8Dn|f+nTwl~LzwGp_OCkHoEe>8J-kGlX_e1jCxDv&A*^U@j+ZNGB zB@s+lI&3sAyX4Nsncf{%EoEu1{Tk=8I(aLVnzYFuU8rHV1^WgLWzkFrNqVlChZ2(3 zB`n+w+|?nFjf1@~=6JpP(lJ)8^8v(^4NJNEC`fjHMyiGS!n@odcRGJA1+b`zt|-Gl zSs+=AZ5g5>(oCu8vL-QyJ)W;fZGR7QH}W zht(Z{9?XF+Tkc64rHo_IofJLt=K%%(Z248EW=9B0Z@uXJmwb$lK~wi-ST)=9?c9q#?{%;=i#2sC=k~a!>^V-C(6I(1i zxk?_c;XGO)TWwjff^A5Y#n_j1rx(nyxgX|;wJ;7Nu$~sj7T6V096Ai()$Z)}qf0&b3mQ=pVF0@C3Efou`(inYbNSRX%3l(c<9JNivJf;tB_l%xyUoOP zHGZUfRbaSUHVgeOH<0=JTmfcXXqWxwLEYmDlMcgzOq(6q_klcB)~0gQR~{ncvx12K zVI>F#Btk!!?wiDVL$<3E-8R=X2^3Bk*y*ZF5hx7~CqVj`o7Rlqy%ivWSkLahr`MP-9n)f21S zfqR?7Pfn}SvM+Chs+#}j$Lu$CPdO7?@qQfodV%uuC@I`S+Rj4zk5^=+VrT#5fi({( zL%3&HSJ#>N*-7HE(c*2Xt6TjR1?h^y_cZ|v1tiw6nU@|>SYA4CzE_;~`RK-)WjAlR zwSzaR=kxXkHbvoxo*Ji48b=77k>^b0n#4@zRzkGq5u5%2Eg|WC-gc{E19xGXY+)-` zY08tq_4JHAeRSh?zZuvU^kl%7x$r`ny|2ogw5o2S8f@C51xx|zcctuqu&bLj{1Qq7 z>k8Ssu6~QIJTJpn#Rs&3O;0v{6*UjS=|$J|=+omYflFPn1E1hMdEoD@d2rWOOsg(N zI#*HK@tbV|mXHUUOWS^S(U^|=3I1fZp!O4F;kEHc2_W9SQMa%YS$*vp^&t-^TT#po z?N*2uyw2If`0eXsQG@JrVYrLSatTxXW!LEd-re!58gF?Mv}WZI2bfm>66t`NE&_IP zl2of+gfIZcmxwA-*ux^23C%v^>knDxZqAo1CiP8BbEfRi6zy*^yx5|NN;lPuzF~0{ zxw&xGY-LG7+ve{@+6rB4ZK>q9cVfdPM2KF1^*qAdN7y7A^>6By*mT`nYfV8h4Y)7$ zxDTHMEZ^;u!pO~A=fJWs#D_KlPs%vB9C`R4{QOYhvLH;<++nag!@~z{I^+8fy9Wmr z#PB&jajuS$p$>{4uBUMMnT8xd#bhzI8uKuyVCF2+^85R9zzcgMG44L~cUGXb7#ODR z33A4%5Z%hwCwt^W9mMnQu!|)tq8|>U=*i9|zk>6^OyorLGZd{ny7QG>EBI+*;e$g( z{p7xwZ}#h=H6zA#TnENT?0g%?i)@C^!ak!y+Ha=-D_`F;Sc{#g4jRNJ>DSdnt5o|% z)I#V%ysQERs`cxua%=;c1)XmWqwq#;H`{~d z%hj%*<%S&0C6J6w%fk(A95$N|65Y68&DM62uFe9!db9xxoU^%W)vccCxvl)Kh&XSg zkk6yhj)tS)_8k>e!G-W(3p6JIsWdjkJO@&Ei0Ey&+Q4Mj5fl<~M?b3L)HZ@rzLsu9 zVx^A$d*`HMQj*ZsUU<1lztmXLs(PJ<>l)|%McOn3j}Lj^zX;$S^ODu3ys`roBm-*&cl|I3=o(D-s~#}{RJ1Gg>XB{$`V2PtzE;D> zP51M!6;N|&rkod(WTnn8w&{+f@`7Z5j`6xc(r2x7gZPDj7BQVj<|w&B%hEY1n16ax z>s>7rDmpCqH^O1z0#jMld@2CXZxUl}Kf>0spL)(n@ZAFz`1|`2^c=6~zbW%x6khlW z7_<(d1E5s5(~&qq-qjb~nJ1;D}^ax)V2B6;|yr~gVlYV8w{Mx*Nx3%AO~ zbfI6r#`FKtbXHMqwOzEvT}yE-F2#zww79#wySr?=|K-*R$qQjJsYg@zaMCXA_zpJ=uicB0ZCIc?)4yivN>>kNnx)ZHdu_Q=)#F zyG;Q2V^=_=q6$^dn5Lw7}y$k%J3rxwJGjz`G!NBf{}ogG%!i=J2}Sz!N`c=YR*@jidCv&Wxdy5+V3L&F*?y?q-Q=mXuKp8U z{2C}N_IbEa<{>p`=;igvW`$%BVR(S-?S17a-C~59&IsNRz-$ISuI-dn0^)KtO|jqV zb#VKaH<&x9!d!(8Jgm3%KLVC;MwdUoLvQz6yejcgS!5HECp&&&{{ve zWT_NKbLhce|Bbr$1dw}dbQUzY2=KWCj6aWj-u=aGrNRTps-x zOzXmr2eTf0n{L(Ith7(!J~e(P3t>GFQ4#&Ddh0y;;=YRFXHE9u=M;I%)W5Q@Bra9U z5J}tq^g93bpAW`uDAvz^4VC^G$ip;<_A+&c@9!|%A)Vd_=!&P5%gZ#|zn+bL_iwzz zWZpZepm&peY>On*)x13Om2*1$69pr)EydCg4k{WA4^^&2mVrPnjWIO>R}zQ1weGG= zm$c#MObzCt+==}^jmNvuVik+nn7$FcRW4)EhlH(m5tCE^UN;)pwy_(zpAN&qOe$*h zK${e>p7Kos^OcW(gxzV^8K6AAEANH_fACnraR=cKm~>DTZ8B}?E;kQPo2h`XxokRi z_Qr)3dW?5;BflC=K)>+%+NlshYB@}kb*+zNW8c+)cZ%*(#@c%nZ?VQx7Isd*&BI$qFqOk?W5TsY+ux%B3@82Djc5u#YKByw-65!3>=E zd*l&+yLWb*5nm*bSI@QO8027~vUu28SkSSYv8R#eJTwudQl@JZcC`?Lp3aCyRH+_O_Akw^2Y@Gm|{}t2Q=Y{s|P& z`?OjEu{Q@*N*|4##XmOs|FZy&UBfT*OYJET+>m?f2=x{>Un!PstpqZQcCgm?a~Pf` zdohGGsV!T6#=hy|+Qivxy-;{Ov%mKmetg8&srEv#5OhHZzL$PuHvisf9@4ix&>HUV zNFlI2g08395B!omC4by)#_Fh7Rn~+k#r$;rlk%7+_gAnE+Twq88Z1rN7wfr{o*zq< zQWw9-L2JSn#8=|e=v@-j>yv8Dc;zkDFqttH@1My6Y4|nsI9%*fKKFVtrg-{jig(f( z@Wv1YxmX4f!7~b`POK)Zr%26h!7FI4by(*}Z+WV|MKg!T1${-T2z->2nw`xrgsTBf zDKNY$&88;4UP*&GuNahD+k?=$>q}$L;F@-I;V{c{g``tluuHl*yI3`!kN?@$WJw6?J+EHqJr zp5#Qb3|s^ARd!na0*~$awt}xJ;3$jG*B2(m_q$g*BH8>syY%TOj^}7Fd4Q)cY+3V7 zQZR5cO>|7p>EUdNzHtT8(Ch#>3o_frpqp(iea9dhB(NJeAH zttM(REVaaCf+n8hco$jLjxqnT(&<;yLJRDO>EgY_ZSSO3#IxP}=G(^={-z>g;z zGcdYDD36*P1G-Aofi{ydL-8r=FnwzSGSIyx`S;&*?i6d|r3u9sUqzX{?uxdPHt_{} zFl)?^c5;O|%?;qurKYrQdSHy`Rx#TITEUQzUm6RlfZTTzHNczWR9ixSHPN?xxl<5) z#bzQ6fNavMv_4%U9$CsNd(pK^f)S9aa!7-${8aq=W!*j<3|eOd{~js@rX(&s#IQb&QeLoHw198UZNA7;lqN|v0CTmRSAhk4=;!)7zKT!m_h zshVATpP<8crfJl;r1X&P4nOBKmH zEJQ%MT&(y*KLgCMkx-7mfFWVa(kvNAkiPxapdw0uK@GNZx!;g_h%SuB0+?)|Ptv0i zb!JY_nm{}VA}$ZCxpQ|p3;rPKX0ZHZ9jY_xlW6b)kIHHBMTeQ1xJzC@DqfT1v`DQdo~#M@JcwUa zJH0!yB?kl$1O()|mvBJHFqo;e3=rW4o_9*jbXEU-Ou!- z_6>Y*4PJ)UTgRlcVa7of=MNe16VwRwDc*5~aS!k?jKF>IjfGZ$ZzqGK(e2ZeuU$r4 zOG8@q?2fzG450ltjBSXPz2|Ktq}vTY=osr(*&TZ2QuS67&_905qs<>;fRDEm@OqmR z%_%S{dRf!3A0RX`tvAAricrpdz2tCOXC3AKd!DDxa+aVvh&Z6?)+|4Z0VJ)(+CgL~ zBYdlCYQhi4ZbbY-Q8oGKu;#KWZi)lOqrg)!_$1xES65eRq?YBbmThzBP3$Mjcxkqq z-63^#6EVAm|DzYgH;{^pd^ecF8&1s$kA4=ydss{ZcsgUM?ntG2|Y;#FK+lg+1eye zbmU+MT;rA8qRJlHuqJnX_^(UEzZr#AHh9ZCOsXH$C<22kwEvS}0a5HvS_booCBxlYbTX(iQkPPC!G;BjQ`zrSrlC2WGfV|zFHc`Kfe%;~V3U3Hgc)+^*wLp$g*(|-d ztUX}@Udr;#4P&?d_wx?9%sx}3)7n6*ZuHky#C|lwTT6~!j%v?%h|@NdRG;@u5->~^ ze!~*SgJ8g5HRXHXJf(uBzLKSyN*Fhkv_1_f;$yiQPR>R~j4V`#Sar*ILubictGxlv)`C95%cr2ngXEx;(Qo zbG`M?;dycP)ujsDvBe(-PUTN0#t7?sH^u3eIF`a(Bu5-JWr`-AL)z2E+f^Wa@opFf z@0o|F|C!JQ?i?y|IfubDuAO_WJBb|l@(6KuP${qmk5G}FPT>`4*c|=U-`%CflE~1u z;P=bw;%EA^-s#rx8I-gk_{DRm$L zO&V<7#&srO5Q=*y-ID@t2ou_2FS~g1y?0s#JOz1us1TYZ;1iCkz)@$f#*n#OW9W65 z?HYl0@vpu&X~+(N>Bm*uw;w{a_MRPZztNMlj1oxV46VW#J&rY*=`6wJ%30Z>#lK(o zr-TIjZ-wlt%u)v)tO#bD~gS+vQpRmCY~ zaFu|K-~1qpSHq@Xy|nd=P6!^8Ni>1nBv~4HC(W60SWyRXPga>nc#`1 z54jhd3N261NCK{oXBb$TS6~Ctdj2fkspncUeZ&q&Ep@K=Z%m$C$y!Bl)ljHNwN~fu z2X5+_IU!PGW?@C%_g?Qj#Arlxlf?m7Qn4&ug2ODEeXpLiPGE68tG?tb8Fr+N@S5^e zDbxWPPHS@As?BfT5!UAzTartqq=c+3=Q4rj-NdqPWz9!^K&)TTiC**PMm_7 zMr*mUb0_$|1wFl<^oCnk4s1Nvbc1U|!>zyD<%ITR*&GiGG0uYPeD1Jlvu8wF%WX~8 zgViUS#cx|=3k6`lvc!%Oi?z}?tlgT>sjY%1X3BxU)Vby6s)N>wN8yPbe`m0X4_9Tk zsPVve)Q{*nM0u3s<2_BshzY8)R-alGnxZKV8zNA3v5uhIb^~e+URn4F-5cgAuJ5gHNVcbq{@9 z!T;BSWV1nj|I8x0pR4H9-tLax*84TK0sct+AkKKHO6d-R2lo`6qo}fxrFw0-!!!ol z`9sK@?(IONidj5wss36BAX4*u|H3%}aj+}TKlQR8s|VgnIQmzC7jFRDu@0&;^@oiO z+-FJ^rVcJQKy8m@9SeG-t2+n=D zjR^4?jI>Jt=Ukg~MsTZSQ=RtE#BiUIPcO}+tLd0>jH=}{vvzaI2|i1{@mXf>=I0U! z+a<5RntTRpeBQ?0j{g%PuQMTT@w=i`i2DR@`TV8p=;m%`MVOuV247z$k9e!N8W3N* zA+GDXS*Peelf$Gg6MSFWG+=Jfz)2)+DqVDz^>~X+&6PeBTub)%*1*^aId}~G?P({=K2Z6Ru z1@8nyBFE?4nPeKbhz&Z@`>@6>=&O6S+nIH&NUN2jxS8AXUh%XR3!C?gHq*l`qis)S z)OMm|GE8uc_pVy8Z93B;oAK?AH@C4Fk9}=;2P34MKffRzt>rt$MR9GcbTYoIo+Di* z=Jz$)khjp+=Z@Wy_H>7%+wu=Z(J~S@=F)gkUA>Ye(0YDy`(}B z6qCxAWF!{tm(FB#EhU|3|8|C7DBkB8wMY;e&BqPUKOy*e zRl~P7fsCsONEq&;(tJh7@Vp8wuR5^iLC6q(g2=!6S!WFYp|wHjHvT*)YR+(o&5~R< z7ePmADR(!}jcndj-qt2pGR?d(owbu@esa1vyQkmy3Tgi@=Wt26f`G6I<`K$&2lG4w zxt0KR3+4UF@{#m`2|u|@n^8^QPAcrZ+e-);b0}EG zB&u~oF@a{T-Vo2GD0AoF1o6hnekVgS)q05w5Z=J`|J}79#1EyL_V)FmQ|Qbz9GN() z@S{d72&kPW$j@vI_syR`?Aj;DzE`59#Q?m|z0KuN%r8e;?WCy!8TMnhDe2Ietn99D z(_2kP2e+b*!F|}_z9Mi9`~^AHAUXtDR=7#)3&hadAMIVYYPycms}mP2;XHS?D_YEG zp$#-pjk_t02bk$ebL%b!y^@uYx(6~a2PmNpw^=8kxnhvc+&RDuSG4%bs4qCo_T?m? z_$nt;Ypsp1z3c|-vR|Q_Z#{?65*B^KA1`5p-yC1xCb+jstc4U^f8uei zt#ahf^EUCW0#{Rvy=I&55#4#XnegjYm%S$MgTxhch7WI30NQfn3Ck&jy-t zOGvkqX~s(fr_2kQnDsC;JX*Am{_)J3MOeLYO-K%7i}Z4ATZA84z0?{Ryo&4%snyRj zm*J*gsT$gQLhCq?8`t9<0%8|fr`H;xUe(VSMbizVn`^N>;g&eh2`pd_K#<%RsxtrYlCr0w9u9aSel zgyBdT^^y3Fb4JNg>+R-}@$xdIU)~{**z&ZhaAKy&c`Lz_wXwqiOz*`)J zJM?JS6aXZoU;IRwhew^P2;`)Q+bFC=0VP2lCX;cjsXSMULhcoa;(U!iPhT5q-;JRc z;?#9FSB~wE4{i(l7IP+?uE$qpq&9{y3WUywvePVV@OCj($wK}7I}lV)LGr+gSi8&X z{{2l>mV$!?$`sit#+F}KK1F<|F^=bJtvtIp3#Zfk2oj|{K(V(%dtkn(UbFhKmc5w8 zjxU9V=g36kwDEo~pLAKyK02?2ugK`xTH8mH6xu9kWw4!F?J%WWhZ$xZ%2j?XnvG1- zl7fCMT5;q+*ReUBRkyK$q{063j)exk>a|5&*C4y};4W~IbYIc~&$K(e(D4_AQ&L=$ z=FXY-Ed#8|<+bAj0&n+vSc68qcgJrY4n^y26N2d|dX43O#nW?sBjIfx&rBriUrp|d z4$Ch=Ll;;s!(HVM+RZ6LE;R_2--tXh1Y1t;>nF8Z#7*u`%toflEt9PB_1v&Rxxo|Q+pfRe4l~l$MEUIjZ zxF)k=pa+C|sHCJ)gt|W86Gdd4N9TC5Z)TSd%V5>bwu{wCziXwc9T#kqInLE8Rs=9m z*Tr*Z`E6>k;-jh`&$dgVr?$Li|IGBNPN_fdQax!>=1@OrqT^ZVH%L`gv?m|0=2Vr2 zW0URV(`F@+>bW>|%lB$xGoLI1hZ;t&XyPg_rJ8d4`OCwpN#&+jIu>r-1aZgj!&Sz#p`Q>jTB7`g3=19(u6;jo3gzwApvmCAV_(u| zR5^elVks5fL|KYg8&R7+n`CtKP7Q8S+vdTL$i{8jE`*zf`^Je;y-l}e2Gu~i{dIQz z-^2}HywMfG_#WD%oIe`**Z4e;N%AL zkGm%a@}a5&?*wIc*W(8VjA^uA?tJ4&g6`S#ItZbc14X%dm95-8`WtpjE zOb*uzWc-_4%edsG!}WtOoM(kbOj$O}4jE^I%w*L1fb8+n`^+Ru3BAF8b)d5vsjV8s zO;U?rZCMTppN1VL!j}`VN^|30I59n%8YO>X=y8Cg9w{KwsI+XS^Ei%UW7m=lu4l*- zMk!RsjnWU?uG2>+;1c&Wzz?ivG4>arA_mX~OoebggeSeqcCm&BHkoap6 ziHN%5_`LB!g%&ogB}j;~l3nf4NKNKU7+iFs7POZRbH5S%)MBEcc`ov!81Ha!taB$=fkvl*haQ+pmQ z;pVIA6|({sepa=A-t^;63~)01+m5~rrBQKXQ2XPGF5 z_8#h}H${_yyLpp4?`+}EkBmMuueZ~IWQ0I*+?7&<@fo!e97F3q{JyFN4MpyXZIY$Y zH-9u5n$ZIol;9*RN{1^c4?NANpS2$Nfm)SPJ7<{OKCo*7!ND~~9w+HZ(39a1G|aW; z(%*mX5UGN6j^;+Yzt0c18EW30PS|5V+OJ4Z1tb?$@L5?@8Sgy)6ot7A) zC!Us8x_|`U6Qg^nEJUc&zrCPn4G9`Gcw<-kR-847A5Nc;A8}+q@i9lYqJOH_DMJ2k-n9($YcNq~RhAY>G zoLBc_|GN5~r@07~2xe;KWsoRF@1potAd}C7#N}|hQaDzotX*&;KWDMPP#1GFEO6TM z>BEH=y^F-Hx)V4Qm8PhpLnx^4rEfQxsM>M}SsWptvZR>^3{~iPaId7hV+-^&R6>Y>afTLsmpaiN zpjoF^vuLv^)X9yrc4*Bo;_}Ut;cjG;UTrc1(5RL2fA!`MdaEf>7oUVwDW;@f+SL6{ zBf>iO1J(AzGua@`YVIfzL(V*q-eIvjam}AxHgNUii}M8q^ebp1STO(f`MP~3-jdrV zDRfhjU#0zFROH4H#Dlfr4+XK|kFw!!8!c+vxPP619d(U$`HNd;B*TGA|0Ky1kPA^U zOX`cT?J9nG+8mScVUC|1^Y0X|((=xqE6j16Z??_B^y*T!;M3R_wn*13;q^C4pDotA z5n-|H_1W0_`@$&;RXOi&gZz4;I_+HgvL0MAGzvxeMn7gW6pU7YJ_%8bgVmUMr8v59= zE~jS?o--29G!4wwth;4)djKlq+J`8h&KZ$2ms!4%fS$76B`y$NkGzB;C$JQBCYiyf z?NoW+YFQ7#S}-%_h4b+zw4TUcfp5pm0%dVYyJqKEG4G0!}6GiA}I>`C~oI^-4RxxN%}$ z-SAWKXxXuYqe?7s5LIy6KBz$_9yLgE&j0qlOj%KCnvj41{L1T&(5aff zLVDvHV{p9~hq;m-64JCAyKBM)TY;^5plZ`^>@@D5RMsGCDe=AGu;$$qEx@ADgOfnL zraXcW6!?-Fe2wJ^x_s4QF*4-%vTLjCt^ck)cY=da*WE$0X|(d11cL)O(5A-Y;QJ+_ zHuCdPG?qCvu{I6gj1a(8by@^dL@O{h&TacEjJcn1zQjNZu+?tglWS4D zC2c5^#q8BaxZ-VRwxq*Sk0=CF?a3;VC$Ae>-M|urXu3{B%uqALOJ(Jh({DdJ@xua; z^dq>&#PEolepz`|8_6=Nt+qTwKcn4k{kHlSqRwPSledJk4J2=SyCfmSW+6}N-p>po zkX`o3GKaCk@^PDJx#{5>+}RlKveejSz?8{Gl-#5j)Rz$n)wbWnBK&X+NrGyf$XO zVha3%CgG;wdWTT$2T^-r+?i5*HuIZ7thk<+PHhbn7P~C$ai~RVU+QM>I}6y5ZH*N!fwd(@_^emoBbV$lkmNF`f8 zc;529QAw3SF{jTI4Jtj{Z%zc4Qx9yeO1P;{U4~MuE}YbHF|5wc!wA2H$dt`6?vQ@I z_SBDHb{1{?s@~t^U-ir!)|0LA zUo)0)3S4Yc%U838o*v#KrYQ1UmweRYI&|yY&JOpbk=qLJcYXG=AJ+}c7X4puZ``g0 z6Gim_$t}a^BkoW8_2z>Q-;E`3c1s`GJTCaFJW0W$5^Kop_l;!ksWmbSE80v)o_{v9 z{(j`c*7=-q;`hi>xRWMYyvtuq_;DeR zaZIAD7MyCGiTN0Vu-X7W>t@(9MUbjv-W~>_&b;J+sOL5(>3FID(+Yu-gKdYc{a0<7 zCAo(?1qpj)F6Ly-D9U5B(Tgvd$dq7Vwdlj|IY`!Vc(1mY{4ZTCM4O-=vjcVAaX{|w zj)>Xk6X0xb_9|ASE1UbHcISsTbFmi&o+n%D%V(1Jnt7c>n#B#XQ;Xz1 z8z-%KcOSs@llwi`7D1umcJWrVtJF3XouH`1lN}!FG?0?-`>6HF+>hB`>Ig>`d$;ew zsV3H5$4UEJ9De=16)C3BeJA}D8m{)(=TQIxe8$^O;BRXwmnO;$i(kFnZQ905lG^fR z_f70P)$dJe%u-V~qa;|S3fW#6%PACx^0z7Un*?MXKjSwTE%nP{{cg$cSF|au^l8aT zR2zp@Ao0SN`2@7Pmw%lw#ku~5tg9u~p)3@k#w}*FOVmWBl9#79JA=~t*Z>mRuL$9nVp^ORY30?46-s=5n4J=uv0yha>0z1|6)p$;3pPu7#dMZ<^%X&%cFojWRvs%ANx(}F?c!vVrp!Ef!;V+eqH`RkX zg>t{UJo+K4QmywG{itZZ;CeR&$@DLgP29yg|Hk6T6uP(;okT$FpbQ~ONk09)(ozMm zL-XkfzMdoa&_0x4!epNdhOYv)PCd@sFqmrX!RO0-@DhhLsLDv{ww98Zt2TV;M?;~r zc>{tvdgXDZ$rlT5qAgaU<`!01+Xe(Q^AZ0Ch6SIFW&!`IU_J8h-@d^Blt8s1%qdByzJIs)=lg0Bv@<&7efiIxD8cO%eE zO9oN4Rv&U|5rJkF_M49k79Zo-7nym#9+4J`C&%%^2~1ZrSQSCRG!ycPs!bhaS`0#s zH2J|GzK?>K(r`+ieOiTqDpdXkGvdh*no36Ve^BNRKC*R`a#LS=ir;uG782nhp2mMF z6N3uK-48fdKQU(w0^i^l2gUdTJ;z)*wkgn1?tjyaV;~V4e5fgXQ9p48u%RXr;7`tD z2r%2xNVH_6R5a?PwBJ=0{Lca?N|{&>&dvHg>TXihQqb0Ac@fDfy;jil-LVfRPyd9s zbNO`c{Jdt2H!e+q0Z>`6(zUDuIeWe`Z7-oMGuF~nfQ<(2)Vb^fQT90pPN2P;Z872M zUmJg;$r)O|C!a`VBuyeMX@j3Tmq3sW>1Cf?4=H?DC>;ZQ@pf9m4dPa{|G40eCf; z#t*h?L}Pr~-_(ivd{}?rGC#=mhlhtF3${qB6|3temQN&HXmGuqK?*2OLNyNEuKpaq zXkn>RRllfJ&WJ6IAGhS;*tlAYYXQ}4XMJsyzjl0qSyTL`)3`e&J5^U*n&4W4sda_J zCLM+DAvr+V8x70;+i{I#u?~K~1w)EDX8<3kh_&E;>h6$saM2>Wm5dNenvsvzX_uhf zKZVpr_EwaqgV5g;)!t*E@yQmpc1KXuoSry-$FZxB|IbfM9Q?giR zy$P4%2Z}FcDSPk|pD91Is1tYp-AJp`Y-x0c5`kIVOg$z$m2g3fygwNUxm-JVF*nm4 zZ9?!+a;0fN=k$OiE7036t;}69=dVBlmcx5Zf)8xG(@a6{(Xma6#tw^hIAfAZGAQ%J zaBCYU0X~KDBL)l|qYs}|XVfd7PG~mylwO5#JdC~Clp}&T^i-ALm-kJQVVUhF$>a}R zBy~oTx`!%P99bJiuYyI3btrLfO$RcGmA*(49El8mXNPV`BOL3y1Y^{shi0tes5bbC zlN~Naxm=D&J8Dg77WG0ON7xMsDkUyvZdt2evvYDts{HZy$Fxh$T)VaXC}yJ0?JPu^8N<@!Zvm1ChJkFBfvEc}?fSBt9o=Js!o+wXkx8NO_2$+V-EzK}#Jkp$hA_}pXyrCP73WS%!~o@&+751=H2Z_bIC+JlntnG)1oRj3>0n1E_+Kq zB9%X@vD-{$O|jzEs|*cZJ+9SlsS-VxDc-v_w}(GHO01KAD1%)#waOl251c{@zcGgi zu)|j1?$p^H-wAx#aETWXK*^eE@)Id^&@;Ka#F407!nAedh&6@%JrDO-#NR!eGa~bH zrnf8cH=@|E26D};?)w!h%m%(NJTmA2mwsgF)gpCH8ksxUJ;Wsj$ zat=>`&FuNcF4KTb7s(a}bc4x3t~dPiLmUKImfz7sss^fAaZ|c4$PebgHMAkAH!Eo6 z#R$p;PW(jz;Se_Zt|#SE=8KZq)v~We&j-M%4{;y(?}@doV{WW!rBvHDLZ?H}39X;2i)C=LrHh7T`5i*rz`}ZF z@@-^2oy$Z7Mtr7?#4S;ML&beKAK=_TUH97mwu-^&F8?o@4G$_)SS~YyL2`j8Exj)A zt~WxjF06=Rd5D)l&EK}{fF4TA*ihp*VaNh=v>Dc@+P10sdv+!Jmr}nf$Vk0PENDC! zHUxl{0t1W9%Be*o1K7UkiO92c3czkzAf9)$#*S#R7QgY1YHNv15__u>4V#2WXIq zzhF`AJ{1?Rex0-$w{J%9LhcrKL9kTu@J7Pnl0xbR{~TE3q?PA!do6U9QnV@Mw{@q)`v^@E*HXcEo|$VSbaqp6pV18%-^N$uCMH zp<)`huM4M6mF(5od2{aHXIg9sYF{YvnI*jch@6y-ysB4iY5eZcavc@8yhNpSJYBZr z#u7{3(1rm-V)>hfWbvNSIqEPE_o^AnidR)y6M;FzFnItD|!*+|S%oI+2BBtI^M>^gM;ce~WI`o^lZil}&E zpqTnq@msJ!w|B*;1pT_>eHO6x{BI<~jiao22$ql}x@{TVpXYI!IKO)!kJB;NNN}a= zZJ1MdbEcH(Z0d`h z1=t&ZIQ(;3?gW-^dwBF>`tt5OSZ_{b$MtN{<9-Zw><+D9lYFc%zhCW3XaaF z9oHIE@t>`6mD&ROKcFj!L?)Ngb8pi9B;W@&gi6LS_b%!GCSR#KJ<%sWneKGi z3X%cFln$+BsQ|*@3c)Re@$o0_TGEYwu?IQrwml4B$9?x|`zQ91YI)SGdzV+sTrC`I4Zi1QX^Z1yQs`wj)FyTrvi^f2pwmd>u*hc1LAd`LZg zzUflppik{8s^)vfb|tFeQ=pap;U)IA%e*Fdct2gc(}#HknB2?0mWO;LJoI zb?V%FEoo}%t~Rr2Cn{1HzTX6_i?b|zf7QKUX7hY({L*twd=v*dTT9v<4c;HE1pG*^ zbc7tC@6Ng7WQRKG z3%Q1#K3va_P2UI^8+Vz=FCEG36tP1NWMk9Ns*CyDv1kNhJl6kii|Ledg%1@6@ zu*aug+uoyD$vC#c#>2@MJf(FV{!=S(8J$+G{=G=~Z<~Z_iLH{JdT2dF3CY$OW~&58 z6$8};>$%*u5Bm!o@TiZmn0TG50!#DF?kw{A3UlYW5vq^nUY7JW-6#RnBpwnT?|{+6 zR&BIll~kT;*0zajO8=b8MxzHjJ6@=JLfn~O6d8-s?t=EI(c>w1KH$c(*uhA1fMjtZ zbq!}CX*j|e3kzBh5JKXfqTFM?OCF3aMh0@KKrWSzUq+eigJ_X1+||UDkIBPWVNrl< zB)OGTP{*%V^0x(3NS&orkt+U0&crp!Se=q`K-OYp@Kjx+c?rFmqf1QvyW0yaK!P7h zjljJNEh!?oa!!zW>=RZ}ruc_Dd=tVr)GE#WksA$$*$m{Qr|`Nii?M+&qm-q8vRP&s zv6sJ~SKZJ#`!1y2z1Nv=+)a#(0Rt!?iE^4%8=@FI*D^D3mp_#!!1818WE0=Pys=m96md?PrtG%n>~<9}W5H-{)Y0 zyIFz?J+@qpPnw!X*89MI%$P+VfwLHI7_X^vq)BSVd!e7d0+73L=!`cgw2LCl5Q-nN zbw2`}i{m!RliG(=YS1gs8J`Hu{Q|pO&MrkOh6gH?pJ!?~k{MqwhB>mV`@q_5Z4NYY z`{4wB)FMY-;1H=7chzn9U8dx$6%Ct)p<|*TN4fNeCc3(8J@kNRhjlc^nx&M8$Gfr^ zMX_GH{x!qj15~GN>8fJ#zgEh3kvUDqIh*sf*bieOC6=Iha~o$pR1P*j;d(?$etT_J zk4t(y;>SV5v3$~q$zd>TrlK>2WnSe)P7>^~wCXR%J<}|!BRgK;Bjx?@pvdOqO3JY} z%uc2^aWB}aj%6~}PCU-N<+3F3Eh(r zWb1{MWY&$>0d>>GK=LoIzmOcMl%9&E%yzTx^a|gq#T+?-4_{;+H(>h)Hf^J;_lM5{ zn82Q~G^5YAttw^Qn$A-dYeREZ33fF0P#QB7*n85TQ zD&ERJ{Dod>N9<&lC8EJ+qkkSqf#=Mju9NuNHk%Z3K9Q)!EnGL|6?mh>H+PCq0&QS9 zb9+R}%MM4)y45=BYz+Eco~B-udM;r$rLJJpXOIzUy~KR>_lc^)zaynjr$xjk=dF+Z zqk^)X>iPE3UGY9|I;Ymbxz}Lgmg^1mz4Tz=>P|fx)e5dAB`XVqQ*z@{am4o}iL8c# z(+nDAl6i(82SSzz0>Guq7O6b>BFq(Yn$uR*!;Fmc-B%2nkwLB8<&ki6-TKT0)se0r zIPczIT=V)uoGCqRTTE}*ten#RotcEdbDMDG$MfIkEbrDRF!beUI`kEyQIz>Fi0^={ zpDr5NteE4sFQ{V{Nx-Bk!C+#3y%52|V9mzgnd<7~EIQ_HX7;>PI&}eDno<)TWb(1w z=hp3S>~e<`=vgY;_E{`FbK8TM>vb~jO9KX6z3AH`l`4=3|2^)kPP?6`?14VNZu1+! zS#&M>c>*3Go7kJ)VEerwt+XO+akis3+m`ukLwCtI=_E_N>@#AV)*b+L2zNsm%s5> z%8iS>Pw_75H0?bd5X;AV|9LYQ@Av>jj(*|cEs@Z54oFp69_5qHyD^S>vjAQ>$frVX ztdp8u{afK3{#fmx2=n+2RQD)8GJC$h==LxF9(fy>TusfwmHky!R)tc7Ra`VOb@$UMi9IQnqjl15Z!Ke*7@0+MIs zkN!$gW$zW!Yv<$fb}){XD`ZtI<)#9m18p*+XhT8bb&76Lbu%T{88nxe#Xo5EV@n!f zwEX%Hg2VC9gKO88w2rA6N9spFQL@>CxIq1uY?lt*z#nNX#fO57S7+|m!A!X6)a4_k zj-l!EBebp4rDq#UOT)GL{TjTdG&2-gk~(u z1j(4QM1CPXi=t1uT$hY;iNqL~!m?IK-;1GtuKhz}K**@LaSVrzq%Tfxg1;Y?UlUF2 z9T6W9pDIN#U0GtMH`926kc36TGkP6cOwDv&EoO#-30Mu$@I&B2hp^K1j4l}f6bXkuxdWxicJtIq*j5mW&LDW4~I$jVq<2oM1_ z$1EK*=_nWDiDkDb?VKcACTNb@}Nus>~jb9ePA~?`iq)Y_j zJvjDQ&qD3^ZxZwwfVVtz={~Yc%;KHKrHGWvvRgE9gMpT4iM(=muW1~o^mN-1NZN)-eE2-&}k zb0vk|-Id4ZXS$DUkhVoGnOBU0cSz70hM|MfZGFp$X35}KRK#?Qg_5nBR2Fz=8^g7R z@=y?pSxt&2Zd`W|XZwb3vn>yJNmfZmKp+svo0INBB_JRm4a+BDcrP^>q!^`F!o#8 z*nc>O`w=czG!ujgH8l|;2;NZ0yOZ`ABn@bB{Ex0eQpg_6C1Y zDgJ#rBHM{rkq_ef+oItmNwV<+C3y$z#V%zx*&6)0I08V!`xeDFL!Fq7AVz|fuJ|Dov{qvL9z zwHv2#n#OEw+i2XNv2ELS-ei)-w#}K?jn!yk+qS;B_gi<(@64>6ANxG}(avSb$Qwho z(R1&-qaM6q_h924fBvu<^t2@+ zQpS95<{^=Iw=5Jtj`vG)+pe1xv0Wm#PpQi4f$f6YMz~3IK zXg!M`X*$1!&%KG8N^sgfQ^lB@FjjNescJnv-^jnZm&3 zDvf%ir;3+ScjAO&f3iAI|8-_ zQNn4Og7B5Sa{BB}U`VFWf}8Yzf(J81rYf?B0Q}4P+qOM<1K9+BKF}$k8!J|YbT%&% z0@iw$X+|!v(gq#D%RvK!@W2v!$PawZ2aPEJ<_mu$yGsa+sRY@e%Cf`o&8kNrtj@|9i{)HI(GGU+~Op0QT@^gdxp(k3$!ishQ zqjIT(dn9MIjkd)#A#tRQ_t4pr35lJYmsSC`^KX0GAsGHr&x8vuwbZIy3MSNVSZ|1D zIM^L*-%;YSke7t|_GaumQc7HS^_}(Q)!U|epZm6FR{37IIE0}Wt7iYt3qVikS@<^= zp%|UuFX#OA>Ef76#IU}i!KCZEv`h7=)!%HQEs}-$mLsiOswqfI#<@ZA>IunAvi%iC zF)3HFxO;r>Jy&+Na=n{Q`fX)ZwU%q;i->oQ$_}VoS6`Ys3%lOIzl`U`lh@B5&s;1b!{Y*!}6n=xJi+Q>fw9NJf`E{_NB+~OF~q` zaG)7Jtwau8wQ(F{d(O`d?RL@L=lf9<{qQ+}HM%`NTCM-0+LJ#*QI^-{ag zw0&p-kwcDGp8DH*GRsr1xcm(iFHh=7V_6#!%8C~OIOA}9rzK2S5zN*Fg1NwacFUOa z9b?VizX()Z?|me5Y-Rnkft_4A2DZX2CFbAwrR*n`Vdvpqe`T;EJpB10S{&COmc zjTcg3d07mYMJVMR+@|ggGb#9y?>jHfmbf`;$)k+atoQbP-sVLYR8RR1^t5~)Ue>=q zWG(sZA6lpP1YcyvJI~$Y3+F!ZB6Pp8>rfBZQz^5XF(qNE$!6S;w zm0;z-)82L12u~1q%wpO6p>?X24X5^#Q;xdQ&l9Q9gIxE2JWmep55eL2LU4^Wj;Z)8Bg^8B&~_gf<>XSJ&-xUdb(O?}l|BbC$<$zse3Y7Hq34-u zk6&T6{HRHR;BMvje0b(p$E?AIJRx0p!jn`+SQEyLR{ZsVuoqGxUW))pUfu3k2wx*m zn7uMPX8!TD4oH<<3uQe?limd_lJL`Y9q|MQs^$Z^;}=^MWUznArip1I+Q+rTZdN=B zravql-|a>F)LXi~EeD9D<>6;z_sO@mCApDh1*EObfkE zLMB|$534cpGFy`AD*pP?TmMNiiouG#Fsy=VtxdS-TzLZ^hCeYLY3x-bdv{Gbh zVN$HVc7BND>3ZzpOKCjREy)MD6+2X5_1Qw%#N>?B*5VpCAF{z?mcu%kK)cdLeRl%? zDP|ghL_=EH0B#E-3gSGa349p?wZFZiBnf}<)B=7_0DKk0{{xc?GBJ57Q~cg#@ZAqc z@y?0@>`NXLQFrePk5xO)C23aY69+rxUd?^y8pVM56zM6&8)m7SGUHj$7wR1tRx!?XA)+qw1@Z{$BvkQOw5xY zrpdsZ|8EM!UrPZPu#C6n9MQSk=imk}%){PysyX|D=$p85%Nb(@2*z4g&(VXOd!$xl z1vPU13bUC6`Z433byALyU{Go#FX3%w3~v-NAijnLyNCZ>W|66V7`?#yYk~xp+Hwc9 zgXuq}>q9`J3rMBxc>Qa?18bfW-9_xw#-CHfw#%iqqj2bqk%u`;&d%qH1oa@U!!GTb ztaraB&zLwa>Bb9Oz?jQ3T+aO{(SrxEZR+3eV#Uc!mBV6m8E9O1W z9m|F69(VaDmf2!>anxh^cGo~WW2sx&ymgLW4sAO~8*R_BB+-l43td@D%Mc1iI^J~= zdHUL|Is$^=RiuR!xi)*Z(BD_O)2l5jVz`}M_GgsCtEa<2IRHF1 z>Ooowg+PO=Mv8P3`1GEL6?8gLLWCW*lEQ__ptE;)h19>3NR>}zjy!Zd1&3f4zd>cw*(Y54Vbm;MM3Nb z3G8WQk0IG8gd3r9Y|;Mbcn2l1%?Y#+&7rau)h4-QgK2kwzOdc9?GOx5u2N0Ho-al{ z`0^gNRr=ru8&mRn@H%M#*-{`_uD0BqCHSUR{>Pyfy)FnoJu1Y3E0)%L!0z{Xt32!6 zPv$1(R>%7ngF{0-hJRZ`q2!Px0|4LY==z64m%T{Ys~~sh+IT^;SXXwR;rq1zyi#YT ze(IiO6MAF*EdiQ0{JNpO5|O#)T2r8~`yk;lEv+w#mdm2%GTR}wLFz4^5GU!*zuR$= zk1ZkMdELYv<;Wk>7)t9?aald$>L@39Ye>Bn^<7tr(`D0dth#eeK6kxvL%RR;f8b=h(muungvFDQ7_<68#jc2u&hTzSNh=@^4wMw-TgHxZXpk>$l z1$krp3TziiZC$<|`umegXbTAI!sBf1KpI1GbZ{WO`-`7_B3FnHjfmH2BQFii3GGUr z>5Iey%=UY|4^ml7WjXx$q`AJuHJgRGjI25#H{MyUG4c!&fMjGarsSbc-$yK)!L31Q1WAX6@u-frZB(o?bo8$pFeiX zJpT28|J>KDgb^J78<<7_vE{I@#TUqdy~y-S(-+V>@I+*aL`W1hp_TSss_a&pGz2}Q zQtUCO#?0w=L3RQXuX{6jlke6MZ-Lg*XHHj+zy5r>AsTw}jr>o1288uL@tLL(I2;qD zhiW4Y=K3#q0o#b}rbWcAGd#<`SYdFQeeOQJXcm+lB{u~dN&IW27~x%UFD$etVTeA4 zyR3%wH6Hy_lmb33p=iT+2=}mYhE%O%%jT?vm{-2yZu48wAXy3h2-~!lR@RtmLZr@` z@ja}J59bkJ0RgU&&!J#g8c=0IIP$f>JxhA-?@7_I@$My*@9CI*%Pn#M&=sS{i&RxV^Y?jXT@QCNz`M;Dk#c^;_d-z4lqnj*SR8Mu zv1Xd3hJ}yoQl?MM_o2+tVCX`10(F?e41KzW2p>B3R0jo1*XUQ?5AjE`fv1mRbBQyj`gkgln)1MTIfFLm$;@f)3XAeC) zGF?W?{Iw}wzN1|kF`s|5stX;cmgf5dSxrJrWu|_;|9PPtLQc%eC#9=H zMe~!&ClO@>lY2Oot|pKLtZLC*?Ga$@lWx-0gP~X4g&(YiG7&Je@uiKPh>W=5%_Jb| zarLoq5emq{VjtrFxd@8z7cX;?iz#JU7qO&oksipTuWk{Tnm_PD$+l4QE{Q z{LNKP)WyBLwrdjN?|6*V7-bMou}>#nec?u@VX^Arh)=@Ra-|C2%~V+;QGRZIP|SHa z5IjCaUE9D&Mxz_wDco6?q!9WJT6NY=rSPwnLyg4gvpNyL#-)V!pZKvLtOY~CJyelI zq6p|cN&78e1h)^v`QLPoPG1O|!kN&{twcqTNr4=Nu0Wz?m!ng106!B;xJQw&I)IVv;W6Y+gy;G;aEk5y(r>B!w`UPQLTM&ce66inSxwVAxPj)> zrc2JnQDki@uGrIyb0Iv`ExOpOSk;_*|95#ZEJe$EW2W!Pi@ zd)=hI$j4$1+AX}p-}l0DM6p}bd=b+tI&c_GBK?D+mH5>0eeSG3HAEtGi|Cd?!Nz(Xj4F1Q; z_r@m3TKXdmtj5{mxHc_sOVBo<@HFa;cdU#>D^*1A%aeid$%h-N>e!wXPLQ+4Xt{oIyH3=V> z?Ojmo0gQUxKU+L08pGLc*W4XL>GE5^Le}@9_LL=SuXBNqBB#g+)|p3kakm&0zxZSw-sYacOYcyA^FS zWQ=^n@9m(G{J1@zIh@kikXGFj!Bu?i$5-njl}-2zb;_(wJX-^Eo4X2*LGz_Mkf&)` ztuvcMO0Z7;4Ah~s=Gp`#17A3}hbWGl#I?T&RjF0qmf9IjlG+y^l0N*%VvGQ}Lr8WA zg$dgp?MQ{;OT4k!mT{bFX1S7Y$g|vZ<~px0l*2V1IO?Elsk*Yo!$8_=nDf^#_iqOf zJHhi`T;zWnS*m-NcA7{l_WS>qJJ=*Yy3S!y<@9}p?-_Ih^&8DMGp@9aWdqDl&B2Yk z?j9OCi9O?cUK^Niv*6+IM#Jg7LdNCE?UyVIQTAigReo0sxb!9%J*9zcVm(e)2;`@9 zxNd-WY)(yV6DXaF;@@?NEz@Y5n36QyNR?q4_qtxZX&zEIf5 z|9Np*5w}*FE+|{34Ofwq)ur8v{`QS*PmXLk+AoFJ(tmU%mw5C+E43R`oY4I8ew{;n zJ~jr>JEMH{CJ`#i$$)&`FV+k;A725`Nz_oIHt}y^5kdu6477u`F8u@ICc|!LT8J9* z^IeMWe1G8J%z46%z_kl0TrNPVo7hM$`UURzzH{lu=1JSWnwgQv=Z3?=QhKpTRj6os z5$Ju%rA)g!a^B2rOdY&T;pmE`Y4{K^aZHnIe7WZG_pa# z59if{5m0M+6j1tZWNL|IW_o2xW$@fpY`Nkx$HrK%`mI&Uf>&*C3VETwNbc*4ABXC? z80ukpFY$a-%S$>3Of}Uvq(34h+b{HWDQxwg5kU`7C0@W5y3^e^IzSwuODhf6w^Q+` z7aa7%KaIrPmT>6`#?lCebjJFI!D>jfDd#`nyywsfZ1e@hf#(thV-LnKwhezbYE7q5 zoLrz)VOh}}dLowbjPMiRf~1DCT#7qTvxWOgu~aJjXrS9GePopI+%(Kbi!g_W#dpY( z)%m7Bv$fs;P{p?D2aW1~ewP8B%HvfzzN(gyAgsK)rtd<5%VSH^gq^q_E+J2_KEgbM z$?KZu5c~@o?6}C&;AxfKB{A?F?fkG|!$6p=nqN9DbJEZM;nxE`HLjXEW>!(&J?pA9 zhGpN1RY#tfkgZPQvqkTv#~$7nX4$87iy#a5yKek|&S9fys^<^>9MXWQaQROvY2x~` zCW6;ATfszbtrXNLoq%iLAtH)=4N3Ed*4Fz6_}&)rgD`J|r7%J{V$KeRHzX`GT3 z@s6TKEI-KU#jvR-Ykyo*>hUXt;Fs6OW_|6ySS{=DjFi>VrC0NA+les%Og}I{PPA_R z|FEdK*S`Q}NDA@e4&4%gbl@!F1()CkzXaWcyB-BO4%QH1)G3 z&u>|+Dbu&|7u{>8LqO8yPaOtwD~1~NJ$_+=VC@8N_BCk{DYFNuODshtSgR6Xl-{dv zkmS*Wsb!6X4sO!v6Gc9O|0zrPyL#!FNy(D$S^tR+^NTx=t7oOVB9Whu4&m3pG;}~Nc)L$$#m!j~QjJTlMgSIG#NOh5?05b+%SPPR5R~)PR zO>F7f7L3)g;1W;OL`c1`XuH0`_=h{qjS6xbm_E3P?alUElzzq`Y|~6<2gfv`#SbY~ zL!oq9^+}uIn_-WnHcrPibP6d^$C}0w z|7LwU>qmv>wM)gsR~ZCU3(@gv1YWP>!=;wzx`hD50*4Ej^Cu1HhE3zELzrwQSVybr z2G5<)vz#XkgLid1-g|%y)v2QlS(^6I`WSS__lf@o&|IR!d9%fcm^X2pi_KONG=*JH z24v&W%LD@)@=&uq_(O(CwT5o?8OX6skJ;>UsM@$MnkdwU9Xw$LN|zWM>nU5B56Q=O zE}UNMbF^_XpgdRjJz6gwM5e`1vK@lwm<+gq)qE^um?7GaUQhXNVU4UF4`1&CXWF&U z>q#|N(>kSs$q)0%HtV`d?PClp3A=Z$T~7c8*VJ`hSnDf3qcKwq%r%Ajm-BMD4~4NZ zEjkRL^d+odB+8t3?QEUk_53_@!x!;!@zmvN(Bi?!FT|VOF>#>3`2O$;8!-(|fBWy0 zB-_O!B!V<84%~Ci8fRJdE2}EU-%c$$MgFYP-8vNUFQ@!#130E|)?I&V+YZ)R^yQQO zp87*}4KxniWgJJOnh;el-d`4f4~8Wqk6R;zYSSd<>2QW5y-r}EX)rh=l|hJ{|6O_V zBb!!f*r##OQ!~X9cFO3l3VE)&9!%+QB|hNu-M|496R3pjj22{eGUGX@>p4eDGiBxX z3MK2b5oN&MOGW&nKJjW@k;F%C)4xw+Z38kAaldCPINW{z;=k6*PI)|xvV;4Ip=z`F zS0@iLaZf5`ft5ft`jnHolk`I(mA3i^5JoPEO6vIow|?+^=@%0tAZ>4^)~V^`e2V)u z9h_ZGcCXD>4wJ=~y;rVpX-|7f*7Ttux?Z7@1XAU?oFZeKbK`>2MY<(h(tplMw!BzL z^xBr#xWA@!J}n9QmVLDqm+Hw|3Ohmk{YH#EjLlITqnw(!D^USxSckM3 z(1lw`soFr?Lp(6jSa`3G_0~Uk=D+UD4iltmQJhSB$DJLJFLgRL_ihvzyT1wgq_>qJ zJU8`W3I6Mh-Q>WX=`{Nqs=iR|U}aR_?z7?>V;RyI!xWuzr)4CYyHeRCyze};@HCZ* z?YCXZcb9^R8BWYSv2h;n<4SMTOS~_|-^FVY(3`)+9>^n6+pO@E27lv&6na zs+dT4E9?NCrKrrmp7b(rS~+3s!S!ZFblDzUI8;IwT9xauF!vU{GE(&r@s<R`TC=|6wjL9a4Cq&(t!KKVJ44~qQk+O>Tv z{m>~7=AmjIL35BInoxek!j@J|!n9+Dp;jUJbOe7z%P3-;wtzf2a5|L8T4Tr@NO3n% zIGT5h%!71)q9Y(LVcQ&O3|bA_$Ze(=;LgN~1!o3y%I1!keaQX!V{cBBbf^YR>SfFJ zrDbldvp6wczap)M-soX)vm(hrRY^kW3pquX}hhvPuQ=|Cu zCa7~>;2J9prU>!S$jY-bzBgM`$93jBSB6g4W7keUjI@VfTTs?$>aV;%p0zzn@cA`e z-aFoGJFNfdH0!KqHV}0XIYo8Vlim5s`sC!KC$Gf`=b5|e^;mErGxvma4+pBkzc+o>C9N5{8LicR zZ*=LBycj1QK}DLd$<+m6eh7SvI?q6yI1y<{>3`Uy!3OE%#VqaTZ$7RGbplP93oT!~ zV?0J6{+jn-7ur*QvS<&%_@j)l#*Npcy^ngBncd{ctgaHQ%ZTqTCE=YT;)2K7DH4Pe zT-UYe>Vxr$>#2AjDPJS>0ox+JVcUMh!48EY!e70BN#4y#%>lkP_F36Fi;3@>GY05&g}$?m4MV`<@-; z2gsz)i8Csr(6WM`qj$>6N~`yK9%)!4dNkAz*!OQdQ!9n?2@m8P7av)wh{>L>IrF9mFXZWf_^n7e(=}>6dV^vCYjJc)WPZ5WH)V!HJdaD(em7x z*j8_rEm!rqL0t+K(5~b-P=T{2f0kMXz5K9EWbs37r0{#AegJx`#A-Fp{fi9x!!Kgp zqv=cm?^^n?IAZlHP7Zpj%kdeFRcO)vNA&|sAkH$jM0q~(4SBgiSd~SJj=^tZ!WcTE z*XbH8!QU-mJVNitj0$~uQ_I@CwRSO+FF|TOk=nRM@u%ji*xGo*QH;?!Y`~gn4F|CS zw7Zf1R^Hn3e@yxaqIyqz!<^h)aw$TBr3Xy9hv`v_iDjutxW93#%;ktQonC#LAhNHF z!9~JHN?)l(NpZ=SjO_gLTAZ6Q$e+n)4}>VlFE~$SWB-((7H8P`D$_MX@%~5bgkGt_ zadWF;cPEA9f{v>>wOmh&x;GoM((aXui&>8cj%$*SeyLemsxBkwP7&tzR}dGYGg8Qu zR(V{`728)QlLCJ3((2yx^thOZY-JoWgDZ-AdzZC=T5xpyv(|3nQdlFq(jp;cec$uEJ^w=?Z|evlh^ePic~4xksdGzP`Y{L6ybn1P&Y(Yal&brfN)BGb59GlZ(01 z4kSQ8#`23Nh$9vlis)Kh=C36|(dT6UIdBrwW_&@EnVE@5U}=OZi-tp8I+>+!C%dtl zLDivtD64CkRnxSR2x&zjoRYcWIeqhr?|VreE@~k_lxH76DTh`xgMECPC&M*hC_coW z_^h7p5J@q82&84$eejFxCxlLYPl2n_i*wrBGXif7&FE$Cy(7^RT?~3hZsqwawH(3i*+pPE=``vs%6o9M4 z+w`)FvD@oU|C-pFzAHYVt%cpQ3(3(to=ISYY%dpw(pDvY$qR|SFm2K1@wqW0qeYNT=Mf-ZQ@U**Pji01WzS~om@|6}U$QuuWE zK2cHi1t8aD2l4o@*ef8|$_wc6aBB zfYw7hPGCJrwb&ikYbVP4u@{E-6m1?g!4~F{e zLrQkyya@l+0yrOG15B{L1bd5>=lWNk`L{hN?aLfBjm3k^ zgV#KxdE=61)W1N2&bdrf*SkUT!j<^RQGv`uNnC5$MpC=EBz1V@x>IFMxDk7o#`$OoBtA_{304!|Vlogj(b%evABjzzLYe6$t*SC(g@ z^;<`anSVvF9r1H^vJb!jv`Zbh;6bQJ`@m&DXRkPs3pqyCyA{pGfm3c7vCCo$g)ZZs z3bOwpgRS+$cJVMNB=MJ~(Q8Bx(G%YxZ~UW+fE|36>N>zHBPUD%H(=%A)6K$Lv;T0_ zI<#Zp81kYpm$lQSxwP5SH`mVgYKiyPM3h^UT{B=(`NOwrNDwZ6(?xPjioX|c+d9mZ zxag}@Mfp&~e=M*NAk#fSagV07jAJR8OttFniXI!RP5RHGMNQF-MGO@M<=;GKOhN)C ziT7T?Q99oO_wiskcQ(IRcRNvODui6K{WLg=Xl0&S%;Kes zVg8?X(CTPoi4R_0$TH}(Z`m7Bh0QBaK-o!O*#esWi)k6~omfVDDy((y8c zx%My+*CtbG=`V(Ee)87_ezSh1QBprst^O@p{|knKf=aztEj_9 z8pu?>z-Xa<^Hr`8jd>ViwGI_@*U}j@m$IM4rsVN5bAk5FQ#2`2;y3-%zDD6nsrLYj zRLBjdHL22Nz}VnY$E{m3Yw{OI+F@ULk)x(kd-J&&8n?efbT8^v}Z)`56k} z*VCxQ9j>yhqP%L(4bSTx%tz51AUB*z<183lL8oha*xE~g_QOI-WzQ#;P@TNe)*A`yutEFYd}Staxtb6jcgPmG=#2@nh)2*V+zr(3UE#& zP(;!ZtxOkCr>OdFueEVjccr)N3Kuigc2eiLoBpK->>a6G7S*qUtEMir#0_ zh!ccV3WmvoHm9BLpy>ub^G$a$Zaj;YHz&8Rkxr0 z(n?R9nNX(oOpJ0*W2IVLbfOiOH2t5*wDU7ovS{`TeA(Rfm)6nAjkCXTM!8apg<*kp zIN0{Kr&I+#C55R%i@@{v_5~41cRPyxlac=^SD4TUUP=->bshC@fcf z4TKmOZE>#C_-?k}Wt*rn?BVC%e_DRPF6r}6rWQ9)3^#7B;}fUdl1tcI8T+07jQzCv zL}E*(<^nwjaO+>2TR@{fXC;g?f$P?WXN>S)&Pasa-${)EZL=#q_q;E)I2QF)2OG|* zs}%iWOkG`20zKJGy#c9?7YEH%4YP?8MA}2!+vc3L-a)Em5Va3?&z!Xr4d)&8I}SVB z&B5q{GA;5R9;VhB8zTC8W6H1q;$mRA=%2;{4pFK zTQQkBlgI2*tI#z3U#E~ei6-5M7u`8t8Kilida;{dZG|3aUu#NC?plZf>8r($bwls> z{#Z>s_Y(*(;cNFdS~-?;Z~q!qu=;8+<6ph6RJf}2Mg7k0T{2zvm9>36G_4&?TG$P*H6EGoBLx=F__=N>}jy4n++=j>k3@ME8Bsa=PO%v&Y17 zGLrY)rt{fe-|JFl8=Zw>$vu0)m1OHZNBbdnEq2uj`>&`cb=q$v3!tiZ$TIbd2Vu>o z)rZP74 z#nl0$!Yt|XN@mma&m-4b(n(!;vO5~mLAWV12N_s`;N zDYFDsI0RMP#|+wBEx0pz462gz^c94PBT-ifT@xBXR>MRvkO$HLsc5A1u1HwfYS^b? zXcfw(dQTS%5FNOfVIzc@jmL*@{AWV#jT{#lL^_k-4x@T)(3t+yO<`&TYMJ+Ea$wVP zNd^J6Or}s|^uAZx@pwaW0Wyr5bv5BXU=8wSamZ(7?j|(Jg@PJiIxs@!Sb4zF z(T$q`!Z{gD!fC>>RE+Z=X9n@ zVo!BH`MQ{;XFn6;sX_PUwn-Kcw@fu^qA$M=V!v-BMO;4rHU%!i+G;JoRKS%I4(q1? zsp-+jy zI<$NSMYbjb!V>y;SpDvhlM+9#pOuB6cI9b)`2QBu=Ri~cX5K7FlGMFd#`4r}EWfOCB-CfPH#P+)E@E;e>{mC+1;VhxD?T&Z$+EcX1oH`1Mq zoqq3CVGe5{)LzqDm=I8@$MlM_Pqp}`>zxVlkT=uUBGVihS~Y)PNh!;;s_onM9^0%^ z=gzB+>+9DEJ~M$NQLaqiZ`-uG7EFO5si4bLvE|Xn9A4Y(JT3eH9CYiN{&+*U2Ajs5 z7L0UP%nTvCV^YB?8?ek~u*0TiW3EB5`_}>ArWv^C4jVe9^&5N>+-9d|I_;`4| z@*81k?O&~HBw8*dU4@E)KbpBWG#b|gt9;|HA;;+rEdWeJhm8ODpM?V38Oy+{iIj^t z7Nf#!e8P{1=VLpqt9;!QmiUv`;7GQn}Z znJy}DTzKDxr+?h!Vgtn~qLiQ2>{kbnOf@^6A!WDi8CZzvmWZ!${fl`QsVy-yz0m&m z2SV2>b-Ha~j@$J{s@nL|Z(UfMu1Q(Q*S>JSW)t^-A)@ff#LeXoMtl3NbjbT|dbw@y zG)Eg8ZsakXjF8dNT=lEG!(Ir|L(T{&)4|1cHLGz?d=ME;_^1_oF@)Gm{>|RgtU7so zUF+UN< zJ2ZxCX2*ihmM9@e-u(uPz#}IPTZTJalr~=KCM9Qkhj~UlKyFaWocS=2<>HX1<1x|hZUmQe;v~qd2zP&$T8Y63Cr0em2(3k~ zkG~~9A(u6|k$WPMsnRO1P6urB$Bo-^dA6l+qJIfZe2bU5(D{o-4s_Es{tv|3->VHJ zfs$sCME1k2QK`o`oDczEB7JO#i9SNVV%y8c>T)jHa4Tt)!RQpN-1*#b+IUJ0r=Kl< zw}!8zx~qR68~@MB)^=-1T+80~UtDGxTn)Z*syKh)M&wanWplK|{5_|Bmw?^l5ZQBk ztI=f~A*21e0sW|0!^i9<w83t2o=)EiyfGUT-uN zV+#Z`!d4RV9J!H9OZ|6M=zgsob;kMiTZCyn^Y&aC=9;s9 z)e93pv}MQC?y7sLRw6QE2?@z3aHzk|+U=ap${SCvTbW3}N8uhC=1(H$Vxu^JF^U8f)ePO)=2KgsVW8Fi4js>+l zt;q0JOBDdbpW5lOHF7W~emy~qKz+%P-Nr(|IHUdrysve>)Heix9BmsWS!`AhlKy2^ z)CqcZm(N!EI8LU8BLZdaL1YEE4T6m38m5RJkxtxNc9p)#^sL>U9~I`)k#8o8bLmeu zal4=?bLSLC1r*^IXY@@l-(A>?{nUm(Mfj>i^oA!=Ir2hdQIM|{ekj#&*uG)BD>a4J zY({jTHna(3W|uvcQP`glIa4dDkL@z0?#Xd%5oXlg$UAI@)ePXqyBrSq*1y*KFMpQHmzDsaa?#_&tw%L!3iTo8Ff zRmLj)mQz8Som)$lnz~#(EZa*B-AEJV^Wz%WtiAyYZW<$yDL$*XH29b^%@z0oO{Q^d zcEex&zkJSA5kIadNK5k6l*0cAu18bnHUaDh-2}fb>;iV%zAIcsC=G8+I!&8n^u%m? z;8Cg)_m_2y+9gZ?tHkOCMkIV_k8&%ZmvrrQB!K0LsmO3*K>96t|ACsyPV4@FA^I%^ zeFt|_WGd(mVw<_o&>cUxPVAAc-M!roP(xRSKb+b*j_=6}4pz;6E_0N|C4|T;M#AoY z+S`5HUP-9Y4*JjAJ5a`OR+lHRgjWv{ne%S67TN;@UO(GHvH>=$!h6-pE}3Q69; z2E32^uVG1aFikqb@d0UoBWBI@|IX1~gdUOwbXPa*1EI@KXGw*20i(6vIjoR?`4_&N+L1*}xB(Xp%7ylJ!+=j)1 z{RdFfV%Lzkzy*EPE)8*PjrE=3DlGB@;u*BrXDinE&)k%z3&^>X4`~S2QCjBrmj3s- zFH#h6?)TEulSZ@gNc=XAh4+{&Vm10Gx=+Z zC)dv6vlb!cu_Jz~LAePB^p|X6=+keqZv>>4nuzQdujlL*HC%}k2EmY-{x#U{RoeA; zYPGL;Om)oag;igGpqiLI*>QUt0z}dE&kJ7u{_nYf(O#bkLhpae=Fx><`M%n3gIVnr zJZ`FD=g4gdzT8_nl}5gN^n54A*p!Ou=}FqE(4^AewHQMR-@?Y??MX+B;}G^{>Mf5b zm3-1oq3n?jv%o73zz9B;W-2tw^IMnJA_8#l-hHGsy?~L?Y=5i9tWY2^WNmq~cr;)y zg7*CxpKk$cF0E!!u3uKVU&VPwpVL`du{LY{n|>%gSnjb_s9s zO{U^BmUe`IL6jOpj*Guo`nfG%4S3OtgDP*I8Y6Lt-{@EqKF02)il~`mV9uadYzd9;Z~o?4DapyWf>(AbzTjTtqiYsZpgPeW` zyqvF~R!%MheB9RPDvfu`Qu?{!-H6YB2(9uWgHxHBG=kUfh=5&e$z$M}g(!4-F8dp^ zr)68NkDYO$RxW}_V)H;huS-_-9o}cv$kwBmVZPgW6CIJ$+wtABMz1~_?!aRdSdLb| zQ^vSY3p`gw+R(0c{C_60-M;z^Qy#=+zt6`fMaFOT*u>@nt@Hv6druyp?pk_Zk|E)( z3y3|2!y8Z~;IejKgOe>4Y%SYd_nPg(H6(6+mR`j+m-svG40fxfcLs#h%{SlQn*s&c zzT+3oce9inw8MzYL;Nhp--5ZF3?eXEOH@nw$ub{Sxpp0!Ka?123A>OgSeM*%2*X;X z<`w8J`R$V3U0+Ek!6cQRn&T$~(R12@2sHe>k=sO$MQfW_yL|&fmR;@HR?TFk^Z*H+ zFIndB*_<%BOVmp<)~rf8*)w`z;itMU*%zWPX&Mv5qC0Oo<#TMe7;PfATlO{OE4*VqDYmpAdPg>Y|}d*=9~`BLg)ly)Ng zmXR*9X25Qa->Q9)$8ye-E2*)JK{Ss=U-{Scc~1Wr@p|pxXY%|yvHfuk)Ntua%eL5Z`stSw*L!zKmmAz3zzj4f4LTzr@jx0KO;)-4LWN`-AS|IVdT&KsIMSKQ@o zA^q*>lR|N6oe6rwq!E{!64$a>d9CmX%hX*B+E-h|kJX%MdO6Ufzfh%!(jwu!P(>5#- z(Vj_Tx=aVFI0aQp8PW6qC)-+5cqla3b#F@bY-)H6`x5O9riN4%Fg5n@#XWwgWuUq| zq$+kkmSFhiAWlJh@lcNXH^P{ZJ@9)i(p=ZcZ5gJBu07amQ2E`&89@TF_o?!ucsxy> zMjTR_1fMSE)}_zS?1T3CRh#J-OI9@cv4+K%2s9$0;5^OLp+jXhn~?1PIvaC z1yvwRevj?e8KOOZ-E{+4?(Fpraq5G6;r>zROM-g?A5U1%E9}A97gh9;SAxI2%PjTG zfBy2kEUnY4Htgo`&7u>wmL>Z`kY-i(7sEY?p66TK`oO>k$xSTYUlra@ zi19wUnyq5qy$DGVIBC^~r1rtI`;WT}P8!Q?Ke?ttNVUSua2#8rZ>YAL1f+3VJd9fX zTUG~;Ue!};nCR;WS-qmHilrcbT6aPzq+Hm?V;83x(M|`bB392PTa7tEM#eTC`NGQM zmZ~!AaV$h12;$H8w?Om#Ny9gwsxeT+Vi%YNlv6l~jXrA9;`(O!>kl0x=qSfm})09b0VV6DgIh&cu) zAIavx^D?#Cnq>@HC!b)Y)leo%<~vzO9yO`6utqv=OIXU(S4fd_G_t>5MS|9W>E)uc z9-O@Z^YpeHV4eWIOzBU%45|S5aEp@i;HB6VzG9B#K{m$=SSO4utnq7yOlD`Bto~0c zZEp@;180EnJ}mjmnTFUbzM1SIUIM_`Z+@5{O%9W=axO+fxl*lzS&e7$zouT>%W&H( zX03r68j^m-^2=I(va;j`n*Qu18^B&rq$*9lRH^0=PLrj)`rGx~m{eDj64Njda-p;8 zcumg4A7&EtYU5}j)nS6f`OmVUcuzvN%gxfWKf^F+i#BHQco*@-6(xmK;8kk0 z=d&<;sgBE{Q)!t%6YAAI=OA(``kcRNM>vL2wg{hfI#F;QEH2+)hM8^+|Ggi?*KfwS z`-=nOo5U&YL~Q-OdWDDN8XI{VA3kTpAs3DOUkVrGM#vXpb9)prhiP^wlolXsB6oU} zn1pnkjXb-}>EWPvQ=7M}B$F>mvL)3ucggo_M_7yeFLn}3GN=9U+J5?#=`~QF`d>BH zI^o_8%q{)87a-QPX>S2rRv3cGAVLd-wMW&QYziwR>=&50EeX=r>{NknB^2JS=Kz}r z{XwhiT;y;*Q`!l9iN0mzfM*R7MMBPion0cEPNcT}ogME-*Y!?>5y2l;&x(Y%i6jtM z6>1%N5H?Nz%z(Dp6PkH>xgVLMZIKCul}dSPlkEcQi1&uQ$_{NIEXBHMbks|XG&bdI zbcA$5K$@>8*n4zku>gOPF+o~OPrmoz`(cm|4Oum;EmM3-eP1iu zfP=5kCYEQnR4t&|+PH&*R5=0P{~PFivH{OGDMSJuu@GUkPKOX@JNqXu&CEH59F^v7 z3HS?F)GwC)WB&UvmQkLPx1)nR#k7dOLui7HhU+WFl!M!A+W)#N z^GbS&@$if`5$bk7>fU}pB-WT-y}z|tEo3$BZ;CZW2hpl#?C}s9=-UcWowON9GNbv# zbpz6@c8EA8h0TymXS={{N4fYRGIQh2$wLa5-T+6Z$^BqY0*`Ezsf_$Tnyxaa%|Kh? z4lV9hT#LI?yl8QE3s&5{K#LW3hoZp=?(R@DIK|zA!^?g5y_x*@CYi}3fA*ZSXU}eI zs{Lm=4jl)#-=wTD&ZT+SZT6i$w|))-pb75gG-JY@cDq|Y$6X<4FjD^-UFpOS5nlFP zO)NZT$+8h(_Ga41-cQQU0=iv=d=|c{QDC$><0QOzWwHc35c|&i_lkVmn-a53E4QHj zXN_Z?YfSkF>{!WJOeMzRDtXt@jxxLp=<_In6}b||;Q4$xPq&pz#8fDX=1 zE|0IQq~7Kt?Yf2P#gA?%7`F3rgY4)lWySij_u!!_#^ z-Bjvb2arGlgrKicQcCa(x=S(T3hgjNMr_O%otbO%qI~{^|vQG9>&Gr`u@w|x! zCFNgNRumYs$gZHrweDe(enD7nU&}4lnPW9;9QUu9nJPIS(o_@(| z8BQF39TG7wf*yOB0L`W_ZM#fSRVNJlvU1;k)E5EKnY`CCr(A9shF>U~(1Wq1CF8XF&*O`+5hDB?s1;1Grr^jC_W zh9&jK#R_tDhR)l^f34}6hx^;!hsDwf=OqCq@p72jh5$G!;?iQI@h%C=-p|5>s!LhZ zbEqZ%P}NqtqtQ3pdf*19I}-u zADB{~NYx_J5TVftNbq{WgTjRwT1_J=^7;W**}A7)oVfNm-SnQb7izxVp-{gs{T%gk zXW*7B-a5|B*--F^n52*q1J4!NLTtu_#)4m8pl%ewfCNlRz=#KD(xh0=59lL+Ksqi~zb z+BzEIhc0SxtOmnzHA#GH$rcKB*{E=7`@&i8OJ$9uX^<$S#MP!1e;R$VBi58kOVD+1 z$YK+Xmhej-vX*9ONlmDigbBnOBX}q2lhqz9w%3NQV+jkq&~^=4EI9W7<(NFyA4D_z zDf`7K?IU+Q3*|NC-3aWWR7?aLu9(KA6<#e zy23MiOW1^M#u7;+7aJoTmR~OsRj2=DxBS!pv%We@_@;=2)wW5m5dY2cfZKyn0ro})S*0!2FtD+ zB0x@7mKiFRpZl*^o-B6_Iy%GVw?F?}8o+cd*NO|RH!W_)PUp2^ULgccC`3y_4HZ^4 z!&B4d^eNx@_UJal(|mD51WkaSH{f=t;Ft38+(w-z*$oD!EN}34lfHH2+ zy6zX!6M5aiTAQ1SXEgEL92^qREjPBVE~KXjFYs|I`M#z7<3uaI=`L zp0XQD{JUsomYhJ+ubm#&ic*H&stqfeT$d@RxB8*i>a@KTSvtMz4*i#VH*xPvu~gdo z608?5+T=dZOyk{ajp(&Wa_A2A)2hY0qhd+L`zOuC2xh%H;jlL)UX>t;ayun_s5@NP zRnaXTqf%M!teLZfZ3mVNpyX+ICW zT-$;G>|bglg!2;w*mm|sEs4V3_%6Rns!>hUs_zPa+7QAcj&)0AzetzLN-nw=VZUmh`I0w$thLiLk5v?F zb7k_n|8UhMEv)riwkVI~yBy05-?nUAK+6Ccjnb@pB*AnO2?u(hRe>m{%?RKY%q$d* z@7x!U7i)!}zfI+{k}n8*ZxOEIHFfzTVWjXop69C2#o>q<|Iy2B>9Jc^yXf#BY97qt zI0{l%vD^DP691bQzpH7mU=|j)^_lthewa6|8&O5I^#i|7-P5lhJT=wBPY+a_R1aAz z^>@{Z4^@f}Ymd`x#UAi;iH7NyJ}=r~;}LXh7O*z@rW`ax{P2MwGtp=qF%N4AHjYz! z%?#Kg2}cwqsLGDBhY zSY(JR^t+CTOtBHkLI*93cRCG&^0>G(0@pl8b>W}LUo+PVd9rVDmv zt7yT7%wyAvO~6h!OUQDn;6=~rW1<=BL~x|A{=;_j{P!a@V+&=uxWx^;{T%*ph*6XG z+<_O7M8b_2YB}s!ORWgc)rBs$dd2ziuyUKAlzSeLu_>qCf4(b{u&*#VyZj`%(5@?YOuhRr&gN+QdIiM5{gMSxfQBH8~ zUdHzAQv|t02^SXE&A(O)ozX&YmIPm#Ab%G#0KwdK(a*!4P*@J)D|Ls92j; zxj${2Avi~d@GsN ze@o^^o>*++@}L{8;u0FNcON}EB>-$Igk|Qsbb74#ZinRxmxYGzOiA7NSXmyx1YCNh zbZ;k}Jd@L(e7NF8Ibh7+I=x->rEZ0MfG$^|LY*BzbR<0P zOqA1U)uW|PxIMfX<&vAdHnjUZ;!)i9m@-(GDlTivF424;j=qa#L)Zr%Em>Es^M6!C z>-JCY8s^FtIf7F1gA+e00M+~D24ekR-|?d57+iFWBtSP8$%%{Lxcvyl16>U9EA}sc z+A${34xmZZ2yN@UR-|O^tL)8ODuE=gQw;@GYnHRPUEQ`BhI|1uh?0Uh1m;4Z(690 zxa@52E3)}eKe##?z|JRk-g5;Sh)v=5f5Bnr%Te$dI+w5$gR`7xj}ZNh?I@@_FVxGa zZUm!cbrEc-a9#ZenieYdNJDbv^(?Ud>1o^@UFe-J8d?v))U_82MIzv-8td<#sHe~F zYhsvy*kYO#npbJ~`<4ig1Ya1V@XBfJ^Y55|lmXF#2$^)i6qbvsy<*B90D8fhxa2K> zjGr!VbhIr3G5DYQ3_oYUTN{9=+0+pgs8Z3MVVV{-`dnph^?TyZL35pfoT zmxk@EwuA<$rO?C9S_m0y!BiA-vpsG}5p(=ajH^gTQehR{fBRbU z@>5XkTz%n9<3h&z=oR#I5-+IE1!pS6#5gXvh;?UR~d57duHD;+cXX^KnQUK}rF z7)sj+rqUTXnyMfS4C5nQ2+c|BbIT)9s5FIwWYi4wWwiY2k|Zt=0RjR-y%bBa`9S;; zlzPv*@+tf|t0`H>4%xi{0@x~pA~SSyfF%yd(?_&83nTHhz}!oOQD-n!m#Wl;bWo|= zHuoW4Rcs=sDS}odY^##cTJO>$PYFjXk~>t;x(8}SAFB}0i<+mNZ0<3wozrwfr}M59 z2Y2bb)Pw^cXN54SbH^zF?KU4jzCVo;v99&YT#yyO#O$%}Iui0Xcq@x`*_wZEFa`hV ze=!|LvqWJ+Hj4e;Q%n0u66?6?zHx&-y4^7}k^(#ajY8QvI1k&_S|W_t?jB%zSCZFC>ZO?vwEtgK7biS3OFL4Bvijq&D)!>1eN5XB& zLsO>w0Id-}I)=h4)zfY@3CyuCrxb)0KrazQ)!auWBk}g3#y}@tL@!okRVt!)z{@{5R@xC@r z{%T^jo)Kh|N<8DgOFE(8BLZHOQe7^ee^Adv{}2@BAsgJvxRsa4VhgRWj>#hKS-s?7 zKt|AxlPttRTG$)E_cV6q0cGA6FG7q1Oktm{Ij&8Z{AL%_c%A$xaso@@bS8 zu4m4}s*Rtri)_z#e{?mbCIGrada`3(u(pT!w;8JBwJL+Ze`xE(Oc3-VjV2hf*JBxN zf=&?P>PRkrZCw$K+H%BAgA8Ai2!@CIt;n+o#^Ah1@7?a+EU+1cTil^lV|s_7TC(|q zrF{k}gZJ3oyrQ?xJ+wKm4yei#{Qw;e-Z?)th}suro=|5y9zxdV{HsO&>QjQrlmPIp z5OD?$LK)8y=X)0IxpVHFmu;RJfG? zV!}V?LvEcaJlK>HAY-=e`~X$Wt4nT_Ymc;kZlqa?KwC80n+rvx-?(7;z2OQV?S)H9 zU0wZz=u{Uc5K0qgYPMeRp4Z7AAHP$5@t#*{K?|lFhdhvc0G$pf{u5AfkdtPY!tK+; zVUr8NiF5t6PQbY7EN!P$5QlNrjC}iiatBPs+(q}d`zuv2ng5Z>hB}0nJJo-5X=qr8 zIF`-NL5cE&$j&P$$luzgDK)3q?q9g?X8f?2wWrrP)L-CH_2D1q&8*dO*<5iAKY;bbG`)ii7^~BZEu_9 z`ZC|=iIoQM>^1Zz-nM?y9{1Eubl{8JK|>P7TwUZ$i=cJJ`bVbcrV!<&8(mQ4B>=rk zxU)DhXBbPI4CIV#|5jTk$D~`OL<`=WPN>7oUZ1WBX}DKKcDawzWkR0`08o7U0QGse zij%8Y&+?zpPT>YPFIfC=0E4_;zVrvk&Ywn`Y;}RGCs*F_Uc}RQ$>&ok{b3hA23C{y zjM=x$t5X6r6ZI^&rU(x1-o8cD&#}N(u(>5@sQs~KF>Qh#p9HR^Zy6Y1nNMm#W~{$i zdI=$oMg;FBNbH4A&DNfHaQ*ycR42@2it$%k%m{eaf^u4@aiY&ax8DMnlclmh+DN1Y z8nW)J{{%tP*UDvKeEwJe<9o%R&ToO^RJNFJY=KqDY%E4Vq?Dh4#UEOqYs#Q3<&GC0 zQVU|quRFy|jbVcM4jej{KM0U;p?CUUrja(&V>~h_Vs&@l<-#mozS4j{x=iQC@&DP* z{YYyiF>Mxho33g-(gX20?H4-#t+s9v8mroDhU_ciT!Y7?5sj_Jjw-@a5-4-GdgyIy zsTO;+ckd)MfO!>$YW3Yvdl*81W3QpwKEf>Q@Xtv zT~V#|yXEfFRJJl<0B^SxkpUU}?c*z1*QJK`wA21ZhwsN)hsv`B9V&ozoI0WvQ0=cE z!Iu3Tmqn@Gr_#7*PBo9L@X$8(?xp_Sz>5^i6d&5_ze_AQf&_vyhv`$q>d!-#WJwTpi?m3=LW$=h?m}M z#bdCaVbuN=iz*U%d?)z`aKqcI`|%T##_%$eY3P-X6&!?k61GQ12W%08Xi1Tu22@=VMD~ot@$hsUNZ~W)N1-XEe^Vbt(5Baz3Tg|PiMwqs+}>IM|$q{`24On{&VxzjPC3FLiB z4Rw~j#PChu50SaPG;+r{cunwRzf!MON_qcM-h;b#7}=UP`p=`EP@}#2mjPv2H*Sit z(>()CGbq5x58Mg5dSJq1v{?Xfkl!u%}+(T>93ETuxKvT zfVdtQNXV7xg|hEq}sALV2T%RLG{=UxC@wlYk5=3gT8t2MUf8qFOaxwgP z*o;!GR1ve1SLrjN#ClB${^DYU19rkbrZ=x4Ww9;Qd4pFh2fQ%eByQxh>NlpB=84^g zex~66f|+PVm34|y>qtI~-x5c4r=E8^?9a8yVa^BuCRuhDQuvSfuSONHN<3-bxdgxF z$2H0R!?a6}mO6c(sbf!Y@1pMs{5rhOW-S4pHwdVTraj-tz|1?R2*HH~*Lz$IwXgnT zg+6>=T3S`;rq_>fT-YjfQGa?hn5unR3Ya)b*xr949N7i}0g|hcmBA#VQ_SfIh zp+n2Rl;riB+w&u+6>Wu%9(h(d_azQmgfOb4b5VT+#TUuz2_~9|=W-^*?r}x1D}|$j zg`tU~g+r>;sV{jAd+6D$iyvWTqoF@>&3i`ddf}W`qlqYj8rpPOW9(9aaWrhTr~wqI zi{saEUghFg#uHsWH?8NoK<8mtxJdUDb-)*Bu3vy zvc6SBboQGr&*_pIQBLqmlQgLx52_EWkQJq!TE5ulDQ$2`lB0Ca&tGExe-Di1tVSRMt?e=nNO*t?XCOdf;=G3+T+;1 zB(KeDKRPD;YKSV&`=I-vRV!iKbX@300???uc{XlD zvIg84-oMVd0j6(ZCfss#80hJBn~pz4M5-=Q2nfd83#B`jImYQP91p(3e}4a&=Nz>A z*IuTDq7PdhAoe%&y+f;^Pw<*-&N%#3Hzomm^@;6->t%j{C}S8~1+3qOW!EGL&8Q$Z zeT`ThwOYNJLy{em6L|i;h!*a4*=T1RoaZar2aZqhp?Y$_|7$<2+DS|^S9uzn(^(39 zKDRMiG=%WQ#KgKlsDKL(M^KmM1w)@z@mlLiecAUT28<7R#SdGbD~13UPf`nzn{R2e z8+R@|(~eM}4=)0hy4~D89Nk0T^9gT=wHi;Q0kS}m9HD2;FZf@Wcot~lwG=2#d1jRN zMIb;c52|C$dFA&af0-XH+CEPQrzboi1Pc9_O%gnDw~YMp{*$NA<6}GvsYz=A{4D?6 zU!7ZFA}`3mE6iEmnMN%6o*77x$P1f4aH34;Qaruy!ISqTInChVLX{fiVd^gzkoN3K z(7M>y(vG}yj&aR}{w|szdKWw{S<1EPSTw8bMIL1|muk}-wtQx~Ogt9v9NlRHVsUz3 zW#6SE|2$f^zOq6B|4g`YdF=%z3y6ctZqbSxg=ooB!!cUodRC~uKmP%H8&e8)ZvYfQ=(m@OT>VtZRnoiFzBok z`O-6@52!(I71wu@d}gR_@Ug4s3*8N--d^T$74;z1zLn<77B zn)BixN@-|?w{vvd%LG(gct2S3OpIoduPW)z0lm0gSKx6(t=WmVDKMM&kols45=VUnK4SaG2qQlVHzjY*k%bDT`(k2!OUhZ2cs0YqV6qeJGX zG>6WL^DQ(PPj;~LC@|KTBvpHRekLaxNeZhl9ug(!eq)|%1ay!ykWdEKp|Hvt*;LfW z?Y&K;*Nf%8tsnIZ6dkXD@jY_-8jrrb?p?I0H0cBc`RZXNYBqeZKmvmW`7ml27Iyo? zB`bPMi-;VHaNKz+BHWQ-e=zp*X&ma`xeocSA(f~4bUeYP#n~>$`6|eD4zQtUV5W?q zH&c!9?H*>@$2Zst7qYH+i((6)-UasW`f7ZtFLwIv&NJps3J+av#1$47m8FXF9wpiF z95O0!-655K=e_va5R#S77ayVce)t4%K?2>pKF)gPtYV>#jFFM<0~vVr$-xO3R=-Jp z{t>oWskeobbFRVQ@Ah3yZm^KF8ulbkG0T~AwH_xJ+PfO7nOGa+xCz8cx*(`}gIAbJ zIsK0C4(i`(OP&^QLyFu-*I@9^w(bQabOZpWapUqI_(L!FNvjTj8!i{59wo%2a%Bzv zzZM__$uJ9I_YgB+ha-}NEwY26ttXf&)6)>HQOR4>Xo~xfv0*?xn*#p+8Ef@Aabqv7 z9_8nqa6`t^tY7Q(C3j2fr=6v6p3Q68Z#@-_s^3VsNEa>!Lef+T27zdk1i3o_*;$Y&Ti$!EAD6q{-zSTSV(((v~93XmfXVqQHkCqOmxctoOGP zQoW8FJN5<&+4mm%C(?z+jh2=yO4FpbEwhbUs$q);GdZ2T7N;iKW|7)tBk}ehH5gTL zx``!Blz`5GX(C&l%A0M-4k0r`pux9J;?}v6s0v9CuB@2q|?Wr>keIw9BhzlQSuh;m<7IoZ@16nxpic% zr<)&XgUHvroL7WQ6awc66BbiYyl%c)IlzTlGW30)PM1c1Xl!f$B)FGynj@Z`So zs&8lhn*Vf|5<+2w8rOh$PAsuR)GnFXqG3~&3Ag6P^Z@I{y}YWYl) z$!gC&`enFnHV(6p{B9(uIBSbnVZe#-Ed9PPcXdpaq5HT0DQ4=xJx^*TbwG8`J&zEp zf|pnBDnH0fZZWVt{s~H*jQICQZ95!f&DU)?Xb{ZdE{leCqQvP z5qzsGw*T_ctGh?Iz^q9DN!7m2qmI9jQ=rP&>iOS%ir9I6*{ix(yne$z7d<`w+o~w0 zNnkzbMf2>48PQ`0swQH%S7fUx8*Bv{OBOXKl-mGh6>J)gFO0Y(JO=?S<*jk=tvj13 zg^*-b-&WQAWbAn7BJMJ~bX@B5GAhx+s$bCUBLm*@j<17KHq6B6Z)Jv?wYA2GULj2V zd3PaIMBP{%`rd5H#NM84TrS;G&N90z*FolGFtxQ?6u$wDAcJXb{;aSwjF-l5$H{FK zZOuAsBcl6z5c7h~MKe@CXK5;Dpd-P&!mQvGU+7wbgw z1ZbMqV*ebaG*%o5(}ft|2+&D>D%dcPN1BDg`B$kbp{6bh`}HyH36)#F)Fm(w_xlnM z7dm`E|5vHX0GfU?wSJ9;yd1R#Ssn@1TrrpJFnf2V7sblZY(ar8`N;yn+k+%ypK%AI zK2Y=Jwi93W@lbh=;!QBMKexoyZaP`o0K|ukXxxbut3u2{;vCky*XErtB%AZWE zigF0AdDb5J;7Md?su0*w7fU|(kIV_29KTQ%e@E2eYgm61Wtu=d#2FnH_bXgr&kp0m zhlZ^P_^-!4nNG_S8@L|n=*QmsHkG#CFGAJ}lcja#8M3WWg#u$*sk>#wsh>G5JRBbb zTDwsZ!)=PvN0OoJxHO$TkF<(|gLF5|@Z}I6TCQvo9X56gX4?uh&c|&|47WPJ?wir@ z*VfR&QtXu{!Bz%GM@L}!nDM#ajuk;~NzRBBfo*~Y0iJh`3}T1uM|KbgJLTWWSrwBS z3P#7(#)LI;6KVa$2C)a<^P1JgTYU1(dPe`z47HjiFSPIxR9$XI= z*!3G9tm-DJ7amu;4E%b^wLfc<_P7Hcp$)qUli*pCke5~iSG5+W7*Lm_0k2t!07ULh)SC_K6BOl4eV^Jace;$OSpZ$?X8m z^Y7z}9>ukIzuL0*sCK8!%+H<;m$DsDgtwE@-1I-deP92{6cG_Im3eVgx&bBer3>R; z{_qsEMuB4Af4M}?oQ2K45XjBxm}X9Oh`oFpr%eN3ppfhLlT&pG=LE0#CVh za59xrw5}Vo>FhjyUz}@i-SI55)HIIVS)!(89(FEl@xK3XvW!HOnYn03uCt=wVuROv zEnV2LmlKJ(ury~xXO4svruZqmpRbRMvppSb{JNUXU_Q)TP2MYCxF|f&3!FGiEqb_6 zOn5(I-0|#@F}6>5AD|CiqUQ`$19oCmU(mLQL4Ee5PhC+7GocL4U10q4Cti>tLEftI zq4MRu?}9Y^<_OV40)Dz(gl_5p$U}otiy#3K?~a75#rF+T@~yq53=#5wzEr6&Yuij8cEE(1w0P5yENc8@;QdQ32BGMLL_UhV zDUI{9y|16#M$~X6ziLgr`qF7#z#(#u^L3ZrQyRN6Ri0!%PMW+#QDB@BkhjZ7YS-kO zMHGx7W5Oe4@o4o02-(w|K)Q;lBuWJ)r(i5!Ip?~L-b!nq^`p&@N=+|P zib)p96}|(xmdkqOl6>p~cLcIamJEi&y0zp%In|rU8#%)+Mx{kr@P?yYGUnBN*TzuO z2|R(nR?%hgSbabzg-ZqIbzJD5zjNM0*j0_RK5`t>7L+f;G7oq4Vleq+x{@kC&qI}C+jbKQ&oP3bGmGy^K6US{faWF)Ow5I?!Er-) z$|Ef`0*>6%5G0g?40{`ZM2HUCv9k!U8^iVl7Wn0%q9kgP-I3H;uI1cqs3W_Qxsut$ zDKcp=bvL<`a}@(@agrS9%c4{)11I1yt|Q-;XZFJFZM#Mk(dp)Q?3}5tM zjNN)w^^zfa>5xb93*E4G8J7|Kk;|pp#j4VoYZN&qNh5f?8emxo>6YoM;64@Uq_-`wI(06hZ6q_&hB`^wg+yqVv}Z3>Cz=7D~B0Ai*W&ZO}7A)m+crG(8} zQVIAzAA6*9t=0y?n2GqQ+U(&93YZ7IPRnP<3kgz@h<)-(5^eo7XyeaW+(ZIBjLP(4 zovK*qP%mzxT3HmHIg6a_D6qQ`49)ZPN_pZ-d*upz>YTl3?^L{Ndd~Df80F`xH)VI; ztfvf)zIfsfZ?GDw%U``OSiRR`a#*-F4sm)vWL-Ti+T{1OBR!lj38C*qK}R3y12-66al#BX+Iw$F<+P zPw*x(PJ+KYc{IRpRJix>h7Jn!6l;Ix>*SEN*v~BZ%$uX%(4S*g-J0n1Y$M3-cs6pb zeNdf8pgt{CJ;#2C6 z;>$M|&v4VDr91ldF`!xM;HfOQQ{+3S*XQlq8O(WbR7yQeXHWse=$VuJLbo`$jZuSi z?~4pmyUEt6-#L=TMT_h)J*8K7C_xwlPY15eCKg16{5}JP_H&A*^XN7f8dny8xMBJ( zs13RUy?NUHGe_Dvg=7ziRiCcmDw4%u8;7pl=p1ue(U=IX7en$~R6DWIwb+5eB~T-r zi%XbMI#{gG-E5drJr3Pcs6u6VN9YJuJav9KGmg7FpV5M`OqisP)>09lWoLlVJ*MK( zQqI+#x3O}sk`RLcZ$>FODs9z1c^Q$sfoXt^DgOjN1+Jx|qnrSdX56K|K>=2%fxW6{ zXRgP}N9gJnns3lxz*3#2-@^xd5!@vS5g*xnnx0d`OU3d ze2l7)^cG^%0#!DFv^{72x_HHu6TRcL~Ii^jeqT6%6!D>tXTSV6=h+i*r zOKA=7eN^&3E;r1UGze6l&Tpb$2uk6lg90^%^SUgjH1U7h@;ed;tI-|>Lvm*wzT$+G z{3qB>Ii!&Zb?p(+!&xN9&QO(phiik*arUJ6`GI?n=%(rC8FxVk-;O zd2KZLw_2nBP%Azjj0CMFyyrw;! zBI3V9l3*OPwfPL{hB>iPE~J`ca??I+vd!h8>_$~sfdvb-c#YLK%c*tVo_eeC=`7@I zLz@~flvMU~Ivf+U*#Y}N=n z{g<5GOgx*a%*x*rphA9wuIjbi#Ya2q%?FMoWbNzSnt-T?_t%;j8NmkWz5+>R)4-2b zI>y@LX_%n~n|>@1s8LYWr>t*%q?Mh2pm!-ms#&5)I%yg>ShdYHjV zx(27*aa6e(2tTRdAzEtWWx3}lK>UbX|HClu<->(YAEcaA&rrv-?5>8o1OFFG;U<~! z>I28)0Gcgh{zQtLx|$~*qUEsK;!q^2@=qs9KZTyt2BU`Dla3WAi_FdAUJU6m2Tp-s zj|K+5I0jWNC>if%gIAhXAHVT(7*y)N629jHBp_g=8%;n-0yy$CT{$pm41{xj=@z5o zXvPXe+-+Yfz>Le8-FO(Rpz=X2U<&@!Ci)G?vIZ>~5Te}*D^X&$9oNvQyIp>nnMqOa zAs_h@xZ)<9q665N3Ds$VueMXs3r#6kE2CcB@vSG?+@6~jBCoe|32l(n<&73!Qi^EM zYd1~yI*J!VrWaoDTUQq9B!T<0U9kt#{-c3-{anrR?3N7Ad|y%>h#~78x!#lcY#VzK~wGEGNDg^9}FM zl7hdVm0oS8YMVk1APxFNK~=)j_Da`fzUb=L?us!(MDv3utyXbXVGf zmbi{zZrm)Q+B9q+49};VNGWsK)SrkUYs!zyt7iQ!HoTQjU_fY~BVTVay6uF$EDnU( zfdYF~6V9`wD2N>rXWs%3#{kWnEw=aG@U|g6ce>Mq%n42)QfE*Sx2RV;+_zt+-$G1}2K6kR- zV~CTqcerYVY0yHQMp*7H>yFx_tt_FFjsAxy){%^uQPLS_3^#+6uPWAWJ5Co;1W&19 z_CqMJFGg9`mL;IlWNn126e6AqiGm)_$UZE8p(v%jbXR5qoWNJP zK$^9}aU$)TgD{eS(3+idvWl{&|5PdQb z+RHSnJk=waYD;g4zIsiM=>QG%5Dh^J?3F)4n16iVv<-5wa#&&#a9FC`K1Cw0QHgFx zHLX?YXZ-=KADuVKZ&tKZ~jn1un|+ zSDC+?{e^dD?l{IVu&qZ5D8h`0!#GtftPnhOba9yCaDElV9QhR2B|W+DJX*FErj3?E17D^fCQ}lGzSMQ}OF#sXPU3r75;6Clt>e0z&Rcjbj_Dzv$}}uHJW< z_nfkr1wF@Zz!sO9-EKrsvtig#J6%}M=1`jTjBq5r(pWnNrJ1kui%pb^E~z8SZ*ws4 zl*jYk5TT8!kcb+(Ur;}(`lr_ceW<@WP1_w^ESvk-5(Ty3nVYf?`y2p!@LgI^?Ly}aInfvfPjdSZwSK?rVQ zsCUp%#897={?l#Ql4M|(6fBr2S;I3OEngIkZ1@ly?=+r<&n%LKcpZ%h7@rkts#s_( zlZhta77;N7oB$UDcQBfeVW;vcpq>1}F=8&G4$$5PTn`ce)Or5R_Jq&WmpYHrfl3YpafFkCA|i#a%0gA+KDIjvicYyo*pwB*=$`EcV;`n*z10$uDh}=EFE_H9L8W8$ zTI09OJkGnUC;n`Y%FdDk$RSU}i$iltEyz&vg?cSuZqduCs&>-q+rtt6r?mjiY$IrL z)X71H2;}Dymx##3=|#C)<371`i=VmQPR7kjEc98QaL}hIkojk0wOsdsdN}Dv_pVf` zM?gaCRkf`!Mu88s?$D$-?vM-8B(v$*vVYTxG7)`R(Q^=r~T*hK4bT zlNnIuUGhLw0aboVD+gWoYclWc@7Y@(_*QHZZ%I&IhP9D~!n|iMy|iu^-(lJ$=KY)} zS>hcm8f7%?Wb#r5Y?#5Ih850%D$kP~;$Y=mE{q5p?6v%|FIu0jEjmiLO`};JtcSce z)F2o2g8r&I)1RWdv6K=g_gxIJD=lHa(pb*uEDn}`cv==;fbLX#gsVt?HkeGAv15&{ zIhu->4K=W*SazpZhStLz6;nbB!Wquz87O!3`)rKUTZ-l;IHcXg6!_axJiT9(F&BTT z?HSQ?6S^&g6l*`bd8aZTXkucVmc8bQO(WIJvF)ikA3j~6*|)3ibE2C$-1z>f|J1%( zujs1A{96n32;|nelAlwg*sN0mzsAY7=6)O7UzRKNT)`x8VZQtTLk)MRlNQNs~Qe&azXVa}|L} z{*o1xZRBcL{--Fiexgug!&=VOQXiwfUl7qfn%bIE)07vk5ymsx_|7zxmzc>S#Njs$ z4Ti?wcsIL(6*S^c%PYmFG2>_}=R33C7ib@zoFO|VACxG8Wq|Pt{Tj&~d)DR}sZv>;(@-!Ta790$ry_2cM;KZ-l@Dc{vo8afw;|4 zcQI`EFy3upf5I7eE~0o25uOjYKs;`qz37fKIB;+Hn@9%X34Bt9_loQhF030#JbmnW zH@|;=&n88WuYDUkORi49SgUMUU4(Y{>@7!VU68itnV^o8Sr3AeQBny%l0O^B9vmCB z8cZdmVIx&4;GVI0yN1f+9xs7NWL|(r}3)!K07G< z5-qT8ueVBVhnWo6=Tx%R+>hq~ltjW$YcvQsfDvb3QJ6l_FdWVVDjtK`GiV<_J%wh) za<0Z@zg*qZamQUB8g)l zlsNggeGb(-zPKmOI7kb?_N~Xdcu}tz9YUu6D7%%74SDbL1i{+@C0q6kH^xV-_^~si zXU`)4IpWZosO}VD4MtMLIuEcv?h!zxk4xg@1NNUMZ!%sxgT%){`f@Xm*6z>4(<+O1 zWdE-P*my{I;&@aJB6^j5ooyinb(yyP&$rE`aTmHrww{|`-971dT7EpaPSin}|M;$EOQ6nCd+A-KC2 zcPkDp4#9%EyB3NBr=hr0f&{tw?_KvLPgyx9SvlX{duH}b+z%POOl2rn0pbbgMDp1I zS~>+M*}>R*0hvb={63n0{FM4^mVL|VR!tn2fjDjIUbP&I6GEts%F9L^S4m&th|R_s zz21cP)?3!~KNyqcX&-%_f|I5tCExSi>rDIGoz<`5sRyr&| zV}~*j8l_dEYB`Hjq-|(i^BP!d=wbNuR;t#_z-r|P$Fw41?YiNWYSQ^v5z!Q z!Y61ulAf6+q`H-faevxwd28&5*zXk6t9N2{ifz2Q=CctwUCrO|&*Ywh=x{88;*C># zB2qMKh&L}I59a3N|Kzi>ASswq($5;Q#*XdY7lN7m(qq4wDB4{l9Uy(edV}eZd zQ-s1nYMQKX6Xb2R{*K{h@#lZaI1nwfTADC0q%f7YU>=McajUX)+gO>e?{}itcxaG) zTkw{GiXanFoNB+ba(niZWyxZJ23gC5C4b`2@Q3r#{=(`|H-wr>UhAGn;u>o{95k~} zL+r|#e8xJ}ranf?j@z!1(fTHnIAge%a06OG#{yg@ii})=#h=AL4Y3>ZJVl2Pnn=^A z@5q4q^G)z=Dy+4MIEQXv-R-deFFoiPkI7r*@2kIPrK(cj@jY9Fc0en2gz>9?CQrZ= zavD*Q-tur)l1_~SUT63i?AF(Wd$LX74Ho~MKeF{cd1(}fNE?fI;y&P$*-gdA?H7NF zmDe2q6z4t$gYVeBUc45WOsR#Va5K~zI3G-Y+s~A>m%>1L#lN3N*EEyjUa5rN{vo_* zoe!--Jn^|z6cGXr2$4t5Kn%$9PF?ZR5~v*kYv3+i$Uww5%ATVs(vd~Ic0!c({t zH#URb1~TmhnQf4zJoWRwU%h(Ij0a>yq=SS z47KcS($~W*>&OIminFdyrEGL;@M9My=LDyhW&mR=bMmbQ4eODWZ+FyC!naI!*@re9O% zl;=Q}&?0K5i`>*Ax^gfE@9kG+-42xgSEGL0?INr*OYdrCw=Ge$&^0R;*H!75ja zQ*X}|iSmigF+JDe=~3mXKBtsieGbCE(A42(@c6U%@DN#hE@b9kXFYbLcBGqI_{Q)J zBeEZ0BO5=H_x3HRQ@u3ywQy7(Klet1Rxix(KQ+7Qdmurh>YS%;Yx8?r{(~_rWBXeA z@6U`2M&Fzz{h}UBBb(oUYNJuOLGpz0BuqG5zqC=mbubN&~MHerW($_O{oA)W9v=79Qi!>2nkbi5>i8deF${CHGG3sz>v$ua`gPoW z`}u{62o2AyoW__>zb@(4tO3Y;xus?F$>11`sIx!vO1-5-UP0p$>yaa_D+_8BoOyI| zv}X|G9;*Vs@jLl8^;Nhz5hkB&HNsj9GG(}RJTM3)i!xwg%wb0M(PHD1mfr5&4c_pV zeuw%myM7-)EVEGi@rd9fe}w-0rIEnbsNu-)2E7uUP?dPXnnd!Pv>zEgR^$=siNz~C2TT6Rp)n` zpy>PX&q|0JtM5hdEtssIlnLp?au^mZ=7oNlm!%ar+np}Qv$MW&^&Ke_#zBJYs5z=4 z>I0P13a`mNv)VXcnaME_85)eC|ptRRH zumm! z&fTUo%x>7GWI_BXtppM3SkNo;+&+VJLv{Qm3=%=Uy}mjctbeIEN_&B|pQFqc5XK~O zi1GeO1vRFxYjfuqb3#Irx02&EB%7|Hyq1Rb-rsL+j9mZZ;p<)o&t44a{Cf~1oQYf% z-p3#=K(kdB4bM`P&XXz=%nC)F2u%~5+{ZaF%!T^dPATQOgv2x!W%Fm#eM4m+{P~4q zCS_ED8Rt8Vl^UYh8n zLCF<&bbeDI%VW$0H9JwlG9_#aUChpY%Bg()`qjeopAJsO(s8~H&h+xJi5`6SXez5^ zX-#1^Jr~!O!Xd9juSL{j$nC+tCoJr&C2xbIu~dMGh$rG^f&qxPW&S-qFv z-%)8WiNDhR&X7MuN`^}G4Tk+8&b82w8p6%+JxB=QMCj>)Z2JvMvg+yYoRFQnlvYXhxe|qH9>Q^zJ$=> zIfyK>Dcbv>rUIwU=+?TN`&DhNtC#RjfB%M?Z@*y5SymXCH0MGsZ{Nrr%v~d7YHqO# zrrt~_kQFw*dT%x$0B0k_1JmHEm_{xqwsW;EW8;A*hHYK0kMtQvKuKFft& zg)BuqT>_nhU+~&eJy1pq$j+xo?;&hYuLYy`ws@mLeB&IPPk5yrS^?SX``ZJskQ2xr zvvcI#rolvo#Ntca^5DHQ9$e=R3E+!1wo+R5RNQL%614Qu2SV|Ff8UtqZ+)-u#N}lU z1#W#aqrSJ|c?{@_di_U*%c?r>$NU^f2v^=v(5IA_6!n#g^+rM9Sm&odjzn zv|nwhRV|}OoAe6Fnp>-aNTd1q?kS=5OAGIX&caxyY#L(zCQ^+l+>(Z>L%9#Gg#@!4 zPPRf$FS|ob-z z2UbQGvPFDONA$A5QOQS>9%EB#O(}`@emty*_xAThw)-rt5SoOhq##pP^iG*^5dlmf z(n(w$Xkx^!_fkh#y8qyr*qrV(lS;;?C;kGEUjHZn?Z^H#~Iw& z?pT9uF_We|On`Hc|JGpx6S)F@S6(x_pR1f#e8to>XON3a)cz2nR>{*aI?>%Q6DlU8_O+9|XH9JvmeqRw$!B>CW{ITm4VU&J2jt1qeVT+8eKTX!)QL*@lYqI}>PyhvT4u%0n zCEIqx2Z$&&qKq)gfx)pIsbRz3t+J>dw!a?QYX<{!m}W)Ljwbg~fkd=igvzs>t)(wsA-~28SMWlNU*6yqZT-z%T z{nwfKXNi46XLG)c{;F~$$dF1PxTC-ERdDQA&S~S6!`gLkg<~?u!LoVg z2^?1cPw)=)*j9qeEdU2iH$VrAR`~IK_OpH?)G*-qz6>~V5ZQ1%>VZ2*7W;URI#q`( z)y`71a{mfWTee)%Mr%r%d&KdP-zLKt3(0DX|K(q>sZiN-BDT1{6m@DaJL2OMf7f9u zFOm0J@y(TZ;hZuinrJpSp%A_L+J5QZ%N&>jU5mZG72CONN$owX3&W24Y<632aWlfz zTR)K{-xRogxyz@fEi9J0%%pgdMh1DP^4Y1_j{SAx0$)EW^)e*NCYpttV0OW!jgd`3 zYobrm-M7I?sI=1oFyjsf&QjqsU-29NU%EBtlw>0IH5ta|PHWab(lq=G(() zom6O%3+emHA#k%C**L>A=F|Kw<;EffKL%~OQ-n-=Up{YY~p6Re{^vhu4(^K5s zAQA1Osccciq0g?&VwO|Q&1=)$`L0|3E%?<=Z$T0CpT_`y;i`K+tD2=)ES2h?;XMo5 z(v)JUB|zo>A*HOa(Pe9r;Ra>tS7nV6p>A^J3UOuDf~8SMvkq z*dE@fS}_#p!@D~k8^cqa%2t~{l;90CK6~Yv&URRlXqvboj8mz%D@6*N>(vO`la21` zQT+4qc>{~sr>K&{#(YOjJd?#Z8pQ3jlvLER+Z48DKBg8Fpu?u>!B-4lu3tWK@M~;2 z@J=tSZA=6om`#I6&>zx|Ie8b6P)VbIczjM#>MVKX_`&~m>47Pery zbZXUg@;sHG6ntXuUyls8x3TQUc-TeSToknsoG&ik-=8F2#>=r*K4a`l}JlcNWNWns(~y}PD~!o)8Cer6x>C2k2Uv?{vMvn>H6z;N-x>)q>*wMmuZQSxH_$Gvi4a|Ac|9a6+=&Fhe2*_#+ zE=VDncD3LNsO6#L)T9NL^&dyY&cZh>`r{AWtnPCG{1x45`}K<5XagtZ6$YN8mT27t zj?`@Pn+wth*`G5SMI;LQGZyg}=hqS;zA=)<1aAhw7!zx_9FktMU#ZcG&Zr z5)qvF7&8}FQYl?4U;)h<*x`oxUedN2Z02zDWQ$2vT!Fu5U3KYCU+a`)h}WDZX7buD zAC_v;`~acEv_ezE)R}vDgzXPa%=L3Eb@OqbmL$}b()!Nf7hpt+oTyGaN~Q3nW3OuxTGdotCIN-) zo6zl7oqn}rlW#u@PlW`|WI#^h5#Rndmop?g0*g+~_OV2p2-sKcS?|~SQSxhVdzYv? z$+`7Mz)i6&ZmNAEU#uMWd#AHzd`4DS`fdSNMa~u$V=4=V4~2nYE}lM@ze_2k7Qcy` zq}fqsd#P}bo#)N+^+<>}hDa*793k$wc}Vb;sam~uG%MvnuDX4KUi^(9+d+ZmN#RWk zdU}U0y_tp_I{-ZMxqDoa#@}*g79L*~pPvGoET$sz{MMyNzSnm|)Q^k-*IFi%LY}D# zpL)DvmXN&r|2Rs$9kTJM=-*@$W+7;}lO?KcB=LJF;<0W%Iq>&ZAdD4!b51| z4+>mJJw%zD^u@k}5aS`2czTljDLBhCR&EjIEeolut>tPIt9vdg2n?*Fn|_s9kSxJz!E;!(q+xVx1>{CVjL(weg}2b5YRtT)_?YsdO_er;A_{ z4{|G>aOquSn=^&c^p>9~IKAP+laK!OLWGF?jSG5b z$WG~l-iP_3q3IyLj?3%sT)Vq{52SPa_W2L}bLAUMHRmY>K<3`J_U19?7Ye@Xf95)A zcAezzkg*TW7lX~CZe*|zqSJf(-hEvfMk6aud8PmID2lDXmModeeYw~hQev_FHl(mB zYy68ox&3-}2WB{%UC9HGuwUAp_}WP8Tg5D6nAXy@zQ0oN z0%d7^EVqktB?RFh9=XSu|8o1*{|kE|k?zQfZniy4vf5oPpu7cA;hC?A?DY9>=svx6 z*q|n>y(p6>5Hk6GmHwwoWlYh6TMd!|D{Qy!>TQ5Y8a2+5y_5a}s5Xsyt?`>I1uA(4 zYSSj8t}{T{uw@zawZedKEOc2}?%u7i*8ErIrqj$PKa*nJf!IG*UQNRkiF`pd{V7PT z>LH#$-4>BohL37eP7jVJ+?KjdVc z1L+l7p@qh}i)yX>vlUo-)y#P;{{9DfvPOubN$sCYTmKf%I|rKBvxFYz)K#*IlD8FLi<=)@zN+jrE7h|1IR2Km&yF2U(8}TWDj?qMG&!+{ zHnhuCmYo)Jb}c!tTNe|T>kOeUv8O_ZoGnZWkXM}G5;f=Y32^IPn&yPQGoS({_;=dU z0Kcg=#_E;P_iOyXue4cw^9ol!&R5rQYW)UZ@lWOiS4kgj?mB*FaW*n-pV`~pl)h3A z04(H0^V8lK*I>E6N=I}#16VFm&g?Vsf`SEi8aT4;<(|}i(5a3Zy!()o>xFXcrevws z9pomqi`PW?nTyY2>iHJ4WZhoQJ{$9%Vv*Of8jf-rFIdYFZuMnn26c#>kO|n=vV1#rP@CPm6*9wkQw7iw z`0i}54?^ajpSfWnqM;Q(3}K+}Xk^676e{f55_ef<`*$0IV)`#JVcZ*G z-62%um)kXZ$mD$1EKNe2vJVq{9ml;Z?!MbO`Kvv|IA0BYBo+RctnE#1nj{-MQ1!n4 zLQf%C%YVJEjdW2aD4*TKS#-8rS)7U?HcANE|Csa-k5@+wmwG|u)k7|6lV_YsG9=r0 zB@pjUg@H3DU_8BUN5j$X<4P7K@5=SRW1q_Q-O*Qz47?AcqVw$2m$)D552hlI01&E@ zgz$z`(Fu1#RQqTR2k>U|-MIdU3y}C$r{-1F%&F)2Hn7^+#-#pxr@VrKVe?lviBDI$ z8n+2x|D}`C`1q!|kI@n6cpy9VAHjcuM7SOJZdf8<{xHzOdGRWY z`kz*If;Qy4=J+e-f?3pMVRo8i4JWAU8k^wYoIXBJjxcC8!jsc1szWi7Wj{5Y% zjk&0AC5$(E7DBaPM#gPr*IkJ07I5*!dWAq~fBI-A?6UP&^OYUxY;rkJ;qER%j}Aoq zIc#8|Hzn+)p7BQQG@wtR@nS9o%8sqDnMz$=AHV*i|CEx$k`A_dR3sCizRgyodZ*Gn z=3_6T%639`rsmlfdD@Km@*!gN^vCzWEO45L-tg57!MekNm(caho4)bh4gltMhMHr_ z5TGlCq)H6~;*9E6f=Z0g2g?l(z7z1dOvgd9jGh|k>*AisEU=RUszm=^Jy<*CI^FP3 zpenS8W?4PQ+A6}lk6y>x_)EG$xG6supV_r`->zeM(C@z}oOFcnEoK z!Ij{8&hL7jAQov==7=-7#=-Q0NCgO%g_nj9DHaczV$l_=Odu?~|D%3dUq@)0@s1<^ zCAI#^VUPxtWHI4Pe~) z=1Ys!EpGk}TcMpFEw15V4B{Vl!rvqRd@88KR<`IxALY?m>e8;L?jiQ@FzLRkg4sDq z7nF#l0cKP3R~vtHOaIrLa(;#Th>or^7R-6$wodrDC8oic=?FrnCoq`A_*r{Wze~xo z?Dth8nj)l+6BDR?sgw zU{uTG+Kz=;s6!5gftPSx$I3P^)I59 z`5G4YJH7rubpK>X1|UBK&}WT0ED*Y8ae)so>(&^^9={H^+^IMpa$LWF5j_M4r}K0^ z0?|0TrL|C@o#8Hb%{QHn{Ub*yZNYNa^TZL$@N||l0Wd9M*YY}J+sJz=J8)Y3BHbNO z2>ge1)dn?h#TMzkV)S$~ef8)5g|%Q4xhf0pX*BEyQ85qZA*KSRqZB<3%XR zM;|ojsNGR@EsVOSC#DucgHBZU*N$(R4e@O{#=U&uPzbOhT(gh+njX z^h4?A>2wc5bu^5=$wu#AKSvtf-Rz!aq3%UK#NhFV^o;sNrPFx1Urf1xsse~LZ4KX# zLZ`}4GBc%Oad`jm_aE!&yK4!rLu9gpscg?rxKHey0C_o5jU-*R#`qU=B&!FQ!{;p~ z+NV~j&3^Lj*+r8CYCe9a9-HFNf7RXog&xZo1gUWEFWvE7_ZS<#El;PNR(m7O+47r5pkAK;J3mjdHV}zdz=-u#i=6RFMDH z*w6M7>Fnd~6|AF!xa}xzOfs<224IwBZ^q|v^!*7jXSec(UvJ>!cK6y^V=LOHW8L~i zU8?Ejld`(~ecQD)+vS1Nn&M-NRjMfW}toXCmy64bxryl z2CC@6XtfhRfb}^LT?5#lwQ(MFOV=@vCIVFJReY>%l z8$KUUet9I1Y?BCUN^PO-eUroXLEqOH;^xCtZ8-EGjbwvZc!>hbhsZ7mMz;Mey?DiA zg+8MWt^Gd-o9*}#T zSG(dOUjURMrJ_m{YgjYW$Xt1&ne&6T(Y&C0+tlNnSI_UR@w6eig5!hzT-x3wv*`>S z)J@6WB$_94CWkM>atT1VN1y%@fei1SUnJmCG@i&YzbXqQPvP!+d@)oU?N3yBCiutFQ9crY?VCaK0xm*~~sYuv%5G=fRiWe>3 zzO~1u@2ZB)pb%J~kcTStkLUsFovsxz%am$e&ynqwzK7!>^HNnG!H!kuUA}}9q7YbC z_k4|?9^FdnS%A?YO5p0)*xA>=S}FCRzeglpHEF<1y@BcF;;QbP9-tS^4~+fV_IGdU z8=FO|AQ0ikX`-RNX@!S0hJh-}4!PVIe-Rk7*{J2+%Z1OAq54DWtl8iht3k-lT^`s_ z`x9iF+!1cblPwpKQ;^16Y^eE;t{QQSGGaW$c`Pv<@za^Xn~F}7-$^qSg?4t!OQ1e9 zB9lV8hNifpqkc-}Pyis1!RG0SkOP92VbqHMl~RGrny@T`61_URWb=TC7 zm)|m*9n9!7^X1fSs$(U(9}AQ=qgR1GM1df1IRF=`4{I~ptrj?uYclqra#36*;U8uTzqS}j0NgR4Nc=%2*cF;%-3#WfJcYD z4t8`QTwgjPpoQqaf?{{`vG{9QlA3G>M6hvjuMe9`#ILGqVt`~A7i6Up>6RBAhh_N1 zIkYfxdH{12-|e6=H`S19D_qgf;?%ZiNLe%?^;$H%elTGjxVjYEJol*`b$Vlybhe~o znxmT~254A;+9ka&iq-b)1}w*6g9fL3c!rsA`}%&@^N`s$weXSXPtcxE45!zCw@q12Ypb9wrQS~G5go};huuP}mf)D} zxup6{N83BYH>}X$v~gYn12M0zx}U3eRR)HzAtea6{2ECKj44tG?hf(RkT}W%eUu8< zGCdmZIsbd2>ZuDpFYGE&`920q=BPVfGq*0@ni5Jf%f8*Z6+|J&gUlhG7^5MJw zMA0}Svwgv$44%QupEzDB$X0>Ut7A887HCW$nOLj5(3xA*u)GuQnvZ)|=2)9AmH;OW z5OVO)tV1OGI~En;+pEwZ9>-1Q%excnV6py=x&C#wG*0kK2qo>EDZzm>@3ms=tVZo^n=N3yhx^G*-lRR zFVU^aQkWWTWqpGs6rdx*bMRD4P;gSvHxt^zI++t|4dXm$8M|0oslp&z7VtpT<;&G% z{C!Py@6cS-)a1KXY5fNG-?SmXVxX%PY{kS1Xq~CN>$m;`sg(_!!pqunSZenTULSg_ zhQX&lwNoI>K$^VfT&0}_#goOfuN$V!6(5|+O;NaZj3Ka zmxpCRxZp$w_p40n`Kf4c!m?OhZ1Z}GSQhHUv6H#;)-udPMa z_~!W3Szg*gVT0tlS=}!q0XOiPa;OY6#IbR4v{yC+>e6ZJ9xpiRhUv#+sOL2Z)>T=n z98T~m=c?K1E~}mW(~A>kix4|VydHLp7f6=;%vNTlOP@aqcTJrw<+2xb9xBbh;Xw@+ zD1N<1=pas?jsfwtj#*m*P7kBBR!601GRoX$-ht!!?0cBQOtXZ!Mk700mlPdS#K!&{ z<)J_;OJDmDzG~Md_1K2>%D33d0KKXHdF>nFPdUaOkah<07b|L#F)9)uiOWp z*T>uXmWQDArYZnyP1M=m4w?`M?>|KmoZ5%}vyIyUZp05UpLWPyhfFX2=A1>G1`j0? zN`leJJ?o!ImXn{O9}Bf;o$_klgOvczBwTvKX6o|}D)8c07ne--y3O>=NwGPW%)N<3 z9=mykniG1~@6+jQnL%yj7iw?x&1%ie_Nxl%E|yMt1BLlYp_DW@)i;C`4O)UwD@x+! zDS5-*QRlm>v(|^PyzHD%HMHh0Ak;R$v7z<)a&nt?SMu8h!}qWLf1ST>Kxoau_zRlZ z>Hhb(<#u0$$I27x2MqZ1{RdXqx`#+-wGUrn*&t;S(c|w3uTL-*?JW1v5aw0h!KnjR zXuhSDxL;q5blkWD!+4$a8nNxUU8Lz7jKw$e&-mB}Y>{__w$2c?vxR3X+2sW7jOK4o z0c=n&Rm}zYWzNBW4w0}u!VetXMGW0VR&egr7*eLaTfR!GZaUgQ81RbF;~6uatKP`1Vm+f0T6<0-yTv;hvpZ3NqE{KK&G#m3hV8y;S zA~zR0%jVZSxSnt+sIIwMeK9aR{g;5q$uml+@vffG^H%UG%xtMQ*FkXHnssX--oy*@ z+LEGC2~1tHfKji)AlOAJspCCrSrh+YgX%x?I(>B~6dV!3RDh`8V0R-oohMWz5rEZw z$3RW8$~%$XGoE#N=LLm{8cPf;lm32DG4q-YX{~tv{y6iM+}D^n)bZuwO$PL2?`3f~ z{>B>K()Z@Y?e*F-vm3sqkS~Wima7=D?NbuC_=uZFGlp0p*3*tZ&wmEScfH3|@`)18 z!v?luz>$6dj=^;ncp<1GqMKDizOWC2WzbrUEsrEq`1bbSphA(9UU883T9-1LxOFN_ zo%(9b$9u1jtu+Eb$Hm^=wW=^nT^#YH<2P%XTdwE4XlULIba3Zs-KI~Qf!1$=m05&l zh5=f|9DI}($x5II#B-Cf!higzP~fka(_qwYag+qRd6GoDz1Qd+}DSq!9&jDDBj zY)9qnv-TnJ@yX^u$z*)j94MF6nce& zMWU?1UyKl)XiY){wH)?7FUCRYEXPXHdz%7hRYUggYOGU#$+MvxqH5NR>_%~=Cykql?4~V zPySC{4mD^h45UDf$7YZ9vV5BSoH0pRDBe6qct3?lbeW6N!yuQ>%+Sc!3MUM@FP2YJ zmL!pH0}eBlP4gu18AE+1#Ra^aO0*`HrRvfC(NOjSh-H)E#-1+M1A$>ot)GDrE+^*} zauwF+>x_06@$D}M@0Qu2|0+4Mo#bM*mR;sWpmX5`FjRdzWKqY714)906DwDHLwCnU zOG+-i$l!GASEKuDQ>^2IWTMq89)ru6$Io)=ml-VWtW?+c!Kg_TX(6%|xB$a?NIxnV zVKM7-8$EPXC|5UZ*I-w0E{ngo9h{UO+dwb6@CC`~^$G^3%RZaDaGhbT*hUA$~ z;{gq=VX@ud(KrxKQf>TFLlkU`$HScEbG=ME^4v-1;RrByeO0Bgk1I>iWBGhPJcmTH zH-rjd@uRC4WV482dvjotcIe3fRqP_mY%TaCShQ|yCal72ND-J-u-TTv;!pW++|rY`^x=SXACqiv~p#R$TTXwM@%VDQ3mP%bYVK031&sc*JZbn3BZ)!7w&Y{ykQu^Qm zy^+;R_^C{*Ieq-{c5ppp;UB!Ot^50A|Aq{#t9%__CPA=EExYz621p#KKj>O0?K}1% zANlIq!Ml5zP-TzSLu8~^Xte10$U4w^CT@&~;6n{e0e>rRSMYrU2EKj z;jD~ww!D;u{j+(v>s>yQ?YBEwZ0itF`;Bv7L#o4I#S}ljk=|_;on{vORWH;pk650s zu9iNI!gy+$tK_rKeL4p+Gu6W58=-xt*l5Wr)Gv9-4O5PgX>>s*5?uso=q6?F4rOGU zmGTSlvbBVB$a!o!=&#`lQ#V(nsY`a6CdZjB;q~j=zCHoxsSE8>82^G<;_e1ni2fT) zPzY(rXfU;R0-N6G*S7^?_8N^$k5}`yS zS4S*&O@OZ`ebOv^z+#8jM#OIUutmodfI#Dva@DGsjt;nBMij2WxtwIT`^^zA>vkxB zDQc&rj3b&AGfs`!kjvm`$~BZr^h;tZY?JW|28g$RCG*y~>Sx9e35GMz#3*F}l}O1t zh?@TL_*&)U&lzf*%Wp_^h3^lQTGH)x$5d;`e~}RB9`x1~+xV+t47uj%(NcXgXrdQ< zJG3Ytu|v zgZ-qP1!b$UpF&fl(FiM_2iZj&t;S0JXK5{0g{>DhR`arBB7kx(1)n|brC3kA^av-SdCR2%;CZ-kvfeZ`gTG+fARkeT+L%7M zs(Y6)LJ+OFgV@H!M49abQm0sz$;W~O|1C{ReuTF-O1RDBuG;gwqp+$NDF!eOlNVV> zP(~Q_NvrQT&Wx@uq88mpAW;ZW@Yl!sItf~w54k?U!gB!hwuZ`oJ6Gd;tECSHWY9=f z(->F{MC=%ZpP5%a(qgU*g7BhG<8`a7`omg2fJn1mlGOf|;Bz>C%Rn0=8G<+SZ0Zew zz8!S^H+3f*ywJ+oy65nj=r#?5pG`ZpX(2tqBI`icUX!s3~@Y?>Ot+%Xn>I)2Ap(XeIhCTa~o$Bm^C{|Xu}6ygZ)o=hj5 zB`KH;z^_?Rqu+Blw!XigrM)w7(;`{7@W#x&X+^1GLxkuiM41_Q7+LmosO03t=)nTc+9Qj%|AF8gC$-fp`y&l_z3l7ZVc z-l;g!saFvaRKu8%6AH0Tk*5+LzLSdjfvy&G4bsIF!RRMGL}3RX(TVs|j(5^pNJ9HwI{!7}Q1^F2 zUF^crOm>-k{E#~<;$MBL9)s<=Kz0d|B|L`*UCI!BQ_d zEcFBq%X4q{>Z3Q+pH@eJ{d*i79nSM|VpdJ*HH8!Te=?f82ugja_Qytnk_C(TXxz?er@N zsUdx=K#A@(Ao55zy952toEM=zw_H1Wjb5Ty_$Aar_`E4ls3`^r)&?fMd7!`qxx|^5 zr9eTeYxg?FcDoWum)>85@kZ)t#73aPQ`X= zrD&!;>@MV=YOj4DRwzRe$HH__}S_pG%e+usR$ds<&yB7T75@7j$+%=5>nt z4*rQX3{h<`RJaaO61alb`x<|9c6i7d03|%8fasd^jmI^4H$HswboWe*Y;I|3Jor;{ zzjZDFhu->fj^`G>eU77`|KRsTZ&XJqc zBONI#I{z*W8AaG?FK%OM{j|LFuK>qAPPEk)0JO*2b6~wU(Vki6Og+m0eXB#u~rAN*AznY!!XHkYK#I2c=JcRRD?oVdZK(oD2p28&dJ|gk)z}# zI}QNed1el2ht@7SGQxO1Alh5apHz7AvLLxH{t+DAX(>-S<5U4E12J&X$5o45V-27` zQpkkZZJg~ytzl@$S8#ls(b#i<1g^(4TIjHKR)plnjG0JdT?&$(dZMxr%fR1P&yxKr z7>iQqj*7!7EZR=GZ;UTiH~-+QE(Qnfqw`SCTK9HunOE+Ja$Y|qNLJsNKX`kOc#rZq zXFRPJoB`vVVz^&zWq%Q1b8CUq;m0hCWWAdIN6D892(+2cWPuEN%NPv}Wg(4Qa%?&J z1EbA$QW*^sX|=xaPycpxVpMnry!Rr)5F$-z4~MIWDp}0-Zq6q6&?+a!HsGwGCv@!g zWQU|KT!1G7HG38%p#a;~iy6UbX0#m*0O$bW5Gf`yY^XMBf#Q%nbZI}ei@{YoC}4{D z=Ln38#_wl*E7!#4j*7qDJJoSOc^O)%dw2GOZErU|z0}M#tPnW5V{d6_zzuRDr=Fr` zZDP5=D*M>oqmBZMf=B6sT_Rf`{CKJ|YW zRH%3Ogd_%Og1RHSj%`0K`-*Kl-Xp;IxZicaA(!UY1iR&AP+RFuQZId%=>QZ5O_iyD zxcFk9{>#lr>TQe5ilYmUhSHmD$q%bXC;2z2S3zdo|E~oIjo^6ARuy`}A2ONXe90w9 z;2XX8P=K}eXsQTjpg2a$~|Tsy68=}{<=?o#=U_|=y=rD|Fw74j}!)-l1Z2HAM$@3 z_=M%>$TYgpAqk6JuP3X6a$z$ zCF3rWe!$W`y@-aNj!4;5AL~VY2%;Xm{jaf)$nJWrwMaj)`$!+U( z2OV>)?STE>cvqTu-8SuuV`@suVe{6QGa(bX+lh)CH{TB(Cti15+v5a9FGIcsVk}Pa zs3_pO;q~J};a4xjGl`<2=5yNFx}KoPN9+SNdH~{=6&Jd*c(x7bTm>9U+Dv{8wcIv; zXBdx=*ry&6#<55z>4qJ7KquxDd0@F!ej2~+yE10j^Hrz}Z)=1sfzLH3D^wWW2JIVDVNq50inT%#?)2P zm1|Uhl;F)MLOrc3wZJ9T)&BrULASoR*9T;;32-(UczZs7ClkGZFV z1}Ce#ewF`ePt3JAvFb7g26iO#ca175)gGa&L~Ck7fPOi^`WBO1qp7T3qX_?KJRH~Q zX>L!TY=(fo<3(~UCY{qIZll1SBPk8(^co7PrU?~LZ5Ct~1h~TjJCc+tI(8(ve)@8p zaRaNWz+rkQRJO)|J0?^+A|0!&AYOVj#BCM{nAIZ4A1^>7q=!QM87i|hJx#&ZbVG<$ zjz~9$xMKp>5LkMgQ+qTZJx%4}rkg{oX>lHHb2tGuQxR!hDN-{n0ZwGlJFS?!Ujwn; zxWH~u!z4piQ=h>f*Of{(R?9jg3aENx0(U$H!Q&zUx^{!a88hf=jMp1m9OtJM@WuuC z=Gd0FRe{}1qk6wYY-0?GBH5{^tY5D>DZ4dR)OKnTTa)xP7L~nmLy;0XU7Gs*wai#F z1-L;CJ(Rt%kDh?r{CELR6N$ZXS0$uj(b>$<#<}O2Ls(Un9}EiEx+#?p>@*nkmX&(> zwsHY4rGRScn5@ zM5stSe!eZaAR933>l~N_PHXv(6%AUg2w_DWb_GwyS+diuh;hJ()xSXUnM&(TD)BVU zfRzq8>WUW?%syAf=X2R{o=)LazdrueOD?jJXV`H*EE6<8&LW+XFI#(kTBR(I8Yi+0 zCURxVC_Cda#s(F;BHUf^^~uWzW@|SDyx4U?*u{lmTDd*1yPrqb{5ciixBH4L{G$@4 zv=K41{kgG$u_xAY?16Q(?s$hfmfX_I|M}>B$xRejz3F!T>u++5>|V>La2Yl>Pzlp$ zDCAkYvR}IV&-wVK8!)@tn5R9-?#+Td)>@)7=7Ls6xSN>P^A$Ea2D7b*zgQl!>xfQp zQ0H7L;&XjPzPQT%)eWoLX8bNwK~d*y>!bQydv!2dub1z* zH#$06zoG6GTy-#8uUGT|td_Y`Q;gN?H@9?u{5jt*_FROwKbc4Ok7MS3mOxo)w-I*D zM|gt-85=YZ?jXXe(B4xf$XrIT@7j1BJLBQ@Ntv@vfW}&XGk2lg5hjU z+Oxuz9Q1XHy>BN>D=<4bf3^l<&D@U=?$0NU4>6oalib>{%SPHAr_HD>c#nxG*2OiY?8$kueeWqIDp`A}#6PMaKn=)dt_rZ1NStj3xd%%1g-ctf+z`!4j)w-727L%c@yIHLygSrFueOk4o$j31iT$b>Lu78rSI@kr1lvQO3cVsZ^SF zlcZ}jB&!Gbk&ZhFFVES&*F{&{J(E-56q5Bz{FFJsPq>82GI^ zIo+gGQ5MaNfi)J9Yc&&y+e16{iTHSjfF{)*uTf>kW)CS9sE5EQ$6&J@=eEX5T0gd5 zuD$P9^;5uXZ)*{!Y|z_UR2IW6ab|3bq)!x;VzzA3FJiFTqQGijQxR`mDR67cbH-vd zY9-FLt%wPG;&Jub(juI3gRYda^R4B{K3lG=osu|}I19FFkgJ&Z#9+57ur;N;?TnSS zX+kU_>}qT;Tn&}oa8)LD#<`R^#ol<$q6G{sUdDAh?xv*a_y(U4a zLD?YNWvMK^j|?a!?r4~(NNZqrsV$j#lWLb?Ma*`aj6y2VM}(of~9{O@=Qu+ z_XY#omOS}I!4(&WtoTsK*~N$}J{w?I5re)?8EA{MSu4P_@9IpuG~(Q1M3BImKV#(UJl@kzaMF!$FJ#p^_bZ%(dIgte2-Zwe%U0u^q&c3T1;joV zW8((oa$7;znwqwzn$=NYwxNu|gQHB%m{m5m(mtP#?$06ZWoktlr;UkuvFo{R2zViC ziL{v&Ssc@S-cy)x725pC%hmOiud_(n9K8Jlh{$5Axt=#3zl4pCKhB(Qd;@LwS~TGA zzN7Ku|G$R=htEU<0&_h-*(GR}DmS(qS&RTx-A9Wo#^U3X-qB4kd@>Gp-(@gYpwlW4 zmULF6L!=e4*)e#m?fA_33aoAlyp4oJR<<=V9g^iC_QZr1czt+yQpk?Ofr$8`FD; zAaga+UV^ljAl!YduqD0u0zKUw$lSe1S6LjN+U6gfzM~>@4bnafGj}gR_Koqhcb)W| zJ%PEtUuD(0PsGz~fZXYpSfP;rI33-$KCkaW+UF8v--5Kyqoe!pPI~Wrg!@>$zHcME z0faj>!?tqoMmp}@ND-Lz)@u>&Aj_Ap#J&D90<#T!(IU2F-;Hor(&2vkS=w-+dJ=GZh;p+ zK&fN_az8X#{ZWp#AovM2|AZd-DSE$(_7yZEdu* z&7`fZjms`u%i!R#c$#CUOm{jc`wNdxCxS#_m}@oZp5Bo}xn)KI7=dm&U>d5Uy#YEy zi9Igyn$O%}*6Su-B*+X0*rQVQ zxwpXjCKH;JRqg6StH_rNP({JOCKF}_s!vu!sZN_DZc4y(WmDTZ93KYDsWq~_a;FbmX)&iU`$+QHxvLhLGHcH$vF?AT{!vc7f7;Z}w%csmVu;EoGAV@u@jN(XL50Z}`p9$u_!^-_|2OM&i@4)QGp)|XA}l!Wr6 zbD0KiRnR@wfm;=GeE7X|xl!O|F59$Bm4W=(xs0%ifm!*H}Ln0`5& zl?@1hZ*4Vs`(*)FBN?_OM;?Lp%Op!}$sSkGh{6pTu(eT8T`#!mBLS~N;-6;%>bICV z5s+(DZFQRjH|&tyyWZsOs{-0SB6-InlCA$_vg{w>ul~d2EL$?8Q&P4ice*AcTi`X> zfJ)rv_~%>ObwK?zNyY8Cv?3Y(kR%1nuq6jPK_O>yhFxHuEs21Kx;r>O6VPr;Mu0(A zFw2(c@$ysgI?AY@-7!~i)D18Z zKG`BOfR1l|oq{XyZOImMJ*$E&9k%2it;$^CPN?PI{CT?HUQLcURp7?bACcG8(uRf0 zh_q>tHlxDjgm9_E>l}}N&s#Qc!gO!tO^IR@-= z1%p2kWZoHY^a{yW{vUg99w*0DpL>71d!|Ms9gU=tM=qB~W6Nq=vb;&|V|l^Gw(MX7 zo`w*%5J(`<>5d@~V&~1meea;j@{$F(xi@c^W|RQg2{?e-0s}@i25(R$$&1F8)Y@8d zP05m4(&)@qGt+(lIMvlXl57k%-qgR(r$5zo`qZgYr%s)&I!`^%lebthpvTew82B;= z9l;Zh;Qz}cIXk7;#v9nlqa5Y0n8jby#*bOVTX>dl(g@6IP`(D(g9c(N;d;$q_IUFe zd=15k<96e?tDmRl%@}W+V{bE>(Ht{s_(n5c|Iq|yoAH{CMnG1xFPb+n&lP_5Fv6XU zaN1ut$7JP)A^)?_xsq)N=cRuWv8!uwG)Z#woBI&Yx&H+e2d+RkWvu+plYZ9#;nN6r z@)YN7C4O!t!r4VKvjyP{1ETIb8|6C_*o=|_;i!gvpG|S#9V9dVjc}epr52;)Vtn2} zGV{+7C=0OF5%gw~Y;^>J-KPX)Yf&8d5CF-{mm2nU9!j2v$b1p2|DKaT+4_0=HcBoH z>-`q|+*?Ry{w@M)>&MiCk{4)pt+V}So)6({!|MMQ!rd07B{P3{iu17?Kl?V4Cjhhc z{l0@OxnINTzl;6(|EBoiH=*Q3c-!|Q@BT5ueFAZc$uZ$PPBQaH2Q?jL07+=sANJw`H< zX(%HV*2jH8{dm($IFXqDs)f5%;5;cJKsNIi$r+&Rz@0@hf1AYF)-Z`&6r_?3VCzjj z`5#!U`qP#5w2&#A`IltmCo8)YvP*-$&VGTk6^V3_>+kt?3ukT;IjKlZDO?0O<+EzO9%}~X6v<;T&{l*p^mkY|2%M@Q zYd}`{60G|0oCykU>$${7kRSnz6NsJeNvNxT$@j3B+0;>qF&A|(m!G$D~e2zWOK)s z==c5!OEYZ~ic~^r(6*{QV^dY#rc^APiXbzdoUwG{_5TAIewT4Yw#6qEdd@l_Xq>9l z^X8{5h{38#2;5eay4|Z55`DfUA%I&|3{a%M+Rz4ZA}?B~zcZGtYJm2Sm!HMc`*-r| zN49f*OdpRMuLHWWs>rm4fNfg{hE8ihJv-@ZkTxzD7%kEtf~|6TCSdE#PDbf9KUq1Y z7#JvKLOM^HiM+wuFbF|V)78k7B|oXO33s7S$}UMYDQafz2&~|K}q` z=6_VN%Mt8y1Z#3W8~ZIZ#j=aTuM{#}#0N23lp?-_$7cjovvUv+X%_J%Rg7;jt=Z%-zGN5tXt(ASMvG>G0 zr|t9f65545&o~tB#gcE_XdxgV~toqx!cS^>3pZ5KAS-1}+FQL@;NtC<<;XZ-kJ&WNTpq#ErPM^#?HazV!Y~{a%S@;fS z;X43q4dsUe`%F4I1j`Q`V&CuFz&(%6=aJq$4Q-I3IPgWv=^ljZVt7L@`!(l1Yt)(% z0QV_@yg<=&O_{>OChj(Y6EbBt|1aHt8vSGe)@6#gy9C}*?Ir6SGl-$tvfi;!((zqI z-2H<5BjMz>tr$obaXmp{n~6O;z#Gx>#kL4=4+y*wgY1Pq`KPQI(#6^HedIz#@8jLL zO;GlEW5tS#n3$OOxug`E(To=}aaEJx?Ce~`x#uondU_hu)Dx2LZ=L3biDNuets|9k zQsE^GvSU8!psc~zRxKmkGhRkcs=5qpn;C&za!P6NZd{NaF0)Fk#6{pD7#J@iM-n$&S2Ftx<+l&CMKv@~*|qUBp_-m`)&@)}eO@#8sEe)QsEjkVAvc@&<*`DdT+_2LkB01yQwy|)V zo~g3#v(t)LOs5qL?IT-gGwc4d34_#>io9os;s!kvWp2v(?0*-utq$1#E?ATEIqDhw z^*<&#`)jaLDyoa?P{1xnu)q%3?FjO7EH1je%!1!jJbpl6*a3ST!SYhTXqRS^Z7P^- z*kJKkC_CJ?I^fDl#pq%UOq4=URdvBbn@!4B!?}N1W?op<6<-TDd==c6w^(2YY-$l) z`)5A;;|BBXfV+CTG3|hbkHXXaCO_R|GS3c}ZwDty8N*C~HV!=@a>Nykc?RB# zkU4(2{5?-K_MRxidAj-~`Z9~Zx&f4}$r8^3YhyoZxvYb+F*HaU0=I!}*ZpN%t6@*9 zv12RY_nM5c{v

  • hT%%c7AuOxa!6u-&Brc1Qco1NRw%L=6s*OV>}(zfN(* znB-!ylH$vuIjr&tGsBa9YiM)%Pbe^ZGJPZB-UvsF831~}e8fW{a&v$@D2ewL5_*@g z%xe*4HTN9bq(0@=q8wV*p~JIc0b#wz1HD_wq}D#zFwhv zd5$^~xGG3A2MDw_IX&Z$suDtqsW>5)a^l~%(D#1xNuiYZIqhm0J7j9qkJID8kB(8X zgWaLB!ZM@cZ5a>KsKd6F5H*>f=waU!ArZuUw1V2X>#daL(pkBU2(43C+cpfgv*BSS zVxX@I*_Fr@=q$gfjI>G0Y6qy!9goZZ2TAV#{or<8{jd7mg#r^oy)Tzrp@tj|tF2${1OQT8 z45Nu5MHPJ%J;9ml3`BJY(1JhN>WNuqtOS+b3$NC*2o&9w{SwdbY9e{|48!LUK&Sxf z8!B9GGdvi5@Va*-pnVJxxReM!b{Qg)j^d1ZOyY7{WiQA2aYD2rH)yZ{9$$yBQr|!$94|!hwh61K<`aX({7I z%|jAMSieL$a^3ifH}la@J`LJEjO%`q@H-~9ro8}uGy@EP>_IYdCyF$v?oJQlMvDZ{YR>m>&~D=(Jr|GrCM=-Q)p9$@9d*M)xb^oCv{ z!K&HeNGw4t1eL=q{aBi1%V43vNQ0iPuc!FdK1iJIIY6b2xiXI%tY{yr!TB25&{9!X%aqx&$P%2xz`g*FlrHAsX)c zF<7ZSdmY8eJqJ?B^241i+;G|&1{$nmT6rdtJv?^XJSgg0W9s-(Ra=Ymu7ejH8 z4WCS@E$Wd-(xVN#-LnRKSL}q8uyEqUeA?eukTTDP`iF5Tv(Z5*81hv+zXs8QM?^{g zmV-mKH;DO9w*JE?r`O*h)GIx&Yv{&3-o%BMoFVe$GAAVg@>eeMAUzn7S1}tSx}S=# zwqw%eZ`v%FEwZ&($IFNNWFOie!WOz*#eK_+7C(38cO|TN+C#xR5jSl41O0??yYpzC3s8jNglL+OG?=S> z^BF3-`*k-qsNk{qB}5Zw76=3RZY>Lg0N05gNQ|-C?UuaW zi^m|uJjBDW?vcFczwsxkcY9v+DjpwvPu;`!G8=Veq(Na#WHho>7#tA47k~>=6{(o@ z`P7O0n)2aQ^Gz6lPOsJQjaBUl{{&7#9={kqmC?X_k#`na9R6SQ zcx@7O$2Tsl0KN0UbT8{?sMe{T(zzrU<$cWJLl=Msb1l zys`J~nnK+UsUam1)0(F3N6f|50(@{AF*OGADs4fVnOi6j{bON@p`3Z2iG2r2gsTwB zONX8=#o3YiOe*Li$~#E;l}XEB{w&()QW#~!CmtWd8MOFk1<{p<&6;`P`gbpJOJl5UQ9$GCvM#-^>kMyR=pcu-)D(r+?%e?F$nm1c4B zhF!rS>%4ZdX7K; zWJDx#`=i{;_{Wb^9Jak;Ah_eGZG>m&EhBn?=66-NFZZzZ=0DsO@pQKam$*Tx_z7t< zZQF^@SE&z$be`=RBcKcVBi71SqIPt2h{S@#PNcao$yS~ghD^gLw*daEH*v<~Fc9JF zlA-lF^B8vG>hKQIArH%&9$Fh5{l8v-ULZNO?yz8tW_t%0&~t~yi_(F)6KJ%myH<15 zPjs3dhBs_9SJ2CX(c0b##bV4lvB22-N6QXWoWWtz%Jg)z7Y^7>dU9ja^4Qt*v%f_aS~rqRGGDF^b69eJK7O zf%87wWz&V!u(BGG&|p()(4i60$mx-H*~72le^@EM6~los3ahYoAaUrGn;v&xI#niW zth-f5roC?|ICu!f8imusD^YDmnapI1R`#A=OS#9Y!+-8*)%pgHWT&jIk8Rx!bkJ{p z&cbSbhlYs~ve^ara*zOkawE|`brFMms+eQ;Fi_$dB`Woqp=$YsL!Kj8S692 zpCe+$1XC#;R{kG=YUtp$N| zWb?|L4A?b3b8jZV`AK~_4o`2uu%shahOztR>k+k~sV{nN!Zf<+9N+4Mfs_$%@O8x|@Jj>ZqdWqg6@14RCL?*GM}zeKV1{;49qvC^ZWM0u9? zEO=`+mCKAa;WIfi)V__L=|s!M}ap zcStQ{m=X0{x?l^YTuc5^v*s-B!1D*RN1IJ%DR3Ilwmoe8I){~rP9%vg{eW)5H>{nP z3Cx5h0HM&J!UcYCF*nh!0QlaMK>BL!GJ3YcV{6AohdYmTxan733_K?76M*kb3hW9& z&{C%Cod?>kYy`_DkO_7_bYsc^s-5eh1EDK~yZUiXS*0iY_gw0A@PVITGc*TjDV=*g ztqW*A$+|g4%GcLs!_6e+?ZvX*$Oles7tV&$CVF=A1_nJdG<`}v)zF`+C*0_vGIOd6 zQoexw9xyD;OystvEq}u404ZFq*ayAfv322VYQJD_a*{q>?ZoktG(blkC7H!<$F%Il z#|;ML&rF&cPoh|Yww)9Af!K$|V@3H#<>UeT`*oI8+2I-fb_|kI4re*h;MObeACKC) z2W1!Po?;+g1AivL7qkt_Zo$FK^!bMKi10M(s>$ZSB@yX|!UN?(P&+bk@k|9z{<+6B zJ%H=8)89okM%vIvtgL6}(L3IpFHJTRwDiJAp8ZdT_lBlMJ(+?^ji5G0o{LB}#-#K4 z?3uH%6CS9FSl|%>6AfI)(`|%P>4Viwz0;19EeOUubDtfU_pq+Ssn;|~zm!o85T%{X zUM1j(>U9=jxU}jY{uvcUJ*kpPxk7}v%fsGFqjdRdx4ab<-kmvVd%cvJIZc?Ikrp~R zEw+@}0#`XiWZ^QQzJVrqwRnqL)OZy5`C;>f-~R3nP&TfYkj)TX&(g z6$AE@vw}w#=?61LTlKUJj9xR$id9tmjA*G7`9mD}Gb|)H2`?7HDp z1o-Qw8t>jr3c_5#rupew4S=KZ5}ewT3Nm3Z^-;UTg^bfCWXhX1esY*yKNNq#s8#U6 zU1q&sv039TkVR|KhLs)fTjbWim-*MSQzH-G{ZWr4R@C8LT-5~e!ji~$hAS&Pv20?x zB2g(Xtx6~W&Hl~(`es8B{UV-q;rJ`q4@pG3p2G9$@d5Xl_%?Xey(o7IzPE0zlV?i0 z&G9^c%4B`gqU4#bQAHoOL9TGp*RUEm^I-+meb`&YlEn&yC&0od`;C;EuDVD9S zN7Q0>g9D?=Ckpk;yIA~jAPZS%|BUnB)ZY)RhctCAzn-X1Mlrtdq|xsMQ?>MFEAQZb zq#<@yQ;w`olu0C;JCe*auQym`CF9-!jMqD1;C0qJ3tqflnQG z3e^Gr&1@xirL8KFhE%x4*z?X8Llno6 zdLY7k;J#2^K%}1@ynbiBzixsT`fPQ{T^Ena;~%!*u3P|5eM(BBRmJ81|B}<(%kzeu0i4Z@IAXECcVDhD3L~+_$7Z_?YuUW3% z=XD7BB&p0@-!;ot@xKEQ+W)y+MlZ~YtJBXK7rz|Ke02D0X-OjuY*m{|j2GFJD@kU@ z!aydbOP@I*#|_hlyC$z|I>hY4ruof(zDmrtj#uiHOH>>d6bZk^C4WMCDWF~mmAj;w z|HCZV-b~Ijol!}xaiiJ<9fs5W)EHz3%C$qUw>60A>G~i7w5>bHj2{AWyQd8szoLY3 z0mRa;F>&7M{ruI@l6^mL3nl`z9y6(O%2EB=sE{Fmvnl))-% z_YWD-`bq3+mwf^oHXNY33T1vPX#B{y6u@1_V|BMr)>HFxe^Zfs>ZTLYE?c|oa5bsZ zp+!p;J!}67U=mk;@Ae~#&lYL6Msi=uB9xv?lQm* zK6iA@xHJB1YKnq7GN^1JMaUuP2^MRAeKq9!I@k6rdugj*@Zz}QAOEqVhkZW8hFsXz95vi^uid{ zFbL2>Mha0rRPG+{no0u^Zrr} zF9%Vl>)M}OD&gB~LUgS^Ui-MjJrz++`8v*@c=Z~5&R3S(0%kC!;?(!wpNfJc#tDD8 zMjOz%PaDxGxnoV*-k>5;SDaDacJj-pQMVCg?H)piW}uRm9s=#BLM zhXJBS``c=M!-Tb-~NXa|qdJp*1fgXxagVq^jN zh9Zp_;q*KPL`CL6+!_F7VYG74p^gTP+{?J!UlFPx)GiD=cZ(>^#@GTwWc>~?3OQDb zx#j`}uYb2~QtT4cguN>GA0#)o7%Hn2PsNpU?i@$@k#l5qa z^(w3{Ws_R>@4)rTkK;SqcdM=SPUEACqRLh$guH?9AxZfwMRY>6L+pF4REJflk@|}f zeJ%->a_Lhd-Y9X=GnM<3d2GO4Qqul+G1Fwmx!LLNNazJNLtB7E?!?`(gBkX`Vbr_T zT_^^|H7Z^=xam~~VfpYrg^s99_KFn~cs{2G-)KRb3DRINCwPkAvBjt0$oN|B{yn#G zkmff5QBAW0=LDaFRAjVN)aRNZ*2VktKlBlg-5uIC@k+FlhH*a2g3A`CD(8pt;ZCVZ zh8lINh%8@Nx-^QxLIgVvkn)L3XcN8O@6rbgK0zBQauCVbnW?we9x(NZfv*=7y!D`e7E9VbA*%IStV}$ zyAZZ^!4_(%J8FC~3)xgJR2EEqIGc6}yO29_@08j&rNqe(cJ(e|n|Ow6zdFzIhUFJI zfUHbX&Dp(co)7K(Oxa-&99Z2;6S=Urkj%Si-CJv}9i>y)PNs7+^gb#z!tSS<(T?6H zGaBVPfNiUws3mOWc%cVpsg(@T3LYIl>dJlRSQ=H;9}&U~HMi-emX%OnVeaZj@!rnt zSatoeA&p9QdO!RRmTl__8o}n!y0L&9w~D|Ey<%ocK5FdpIA&-=UNQx zaR14L%Qv_G70xA_ZO_g_hM;_lAB%l?8+y}^03>@BHmy%;O!@aen-}P0^2Tq&Isf02 zidB91ulsxrVs4<_&-H7wR+BAj{y6PN_p)TyKs5fGWYyKu@BEHCg~On=Q~oYYFAko; z$E48Tbn4>63et1QM!+Ll&ZOXt^)zL@cMRD zN7{+?IOn{6;_vuKwtqqP=mzfZF*H7z4aDP%rm(p$@rP-H=}iK*gUhpRmRp4c0@MqYX=AM^eqlvHw4w-ZCnxczqk*LkI#A z(v5^5-6h@K-3`J}Lw8B1v~-B%(A_HCJ#)q=c-i)6czaeD4!#B~x@Yxm1Gx_kmt#DjaPXk3FvJ!I8_)(##U%6f>K zdWkq0^5AJ>n;O74Kzu^`K|H5UcgDy4DO%}Xdy!-YXMopX;W{VoUQ)ls`!-{sF zQJ)y=69DOs0t(&JZ%NDpLn4sEenbsiHXqhH#&pk34$YNs)h-)=f?*=`SbXRu|0HVB z%8kKl@|O*Bk2<2&%mx!M|SAVcZXjrF$5VSZT^zSIHP$xbKjnxBnkv0j;0iwOU z*C$96P_iT1QXruSl$-qdB&xw@E>|B&*3=1CDF!$D@SbhLjroIWC(|X zP>N|Ol>fL>IHp-u&e*2FN7KemV?z~h+jOZvXS7$w%$eiZo0p#P@kOM27!p3^(bHu1 zOQ$(XjyH6R^80qvt4g!ST;Iq6!DQ2fdA3h+5&=E0)H=utQHCRrSyU4Zn2SA`5rTVO z8CIw=4>>gvGf(B@{Z||EA4UH4|LrL`f5B!Kb@5Vebk{kjjmq4OkvTL^c-k#^C&9Yr zk)~aAsG$-*w&s{-0UG7;7> zYPZOgMXVE)V0fcv;g|;qJofKyvV*nYCd%?7Supd$1%f!Cf0RU*i6t__nMUHthjjQ9 z8M66B=Or17e2==-BMB$QUik4vjdIMkun`JeTAeV2m~llE>%Is_nU=lJs;quh9BnZ_ zI+oqHiR~R58 z>-6E6O>X@sN`VrxzPn;E!^g7By4MKvrUxw3`dW@%uUKt|z2CL(Kh3Tu5ujzvBW?Cx|y1>#uw3a7;sn+!BnT zbD|cr=m3Lgurl_%=kFJl(ouWl__(mn2Wb3bz8f+dNJwop`x_xq-hlh| z8orn^RONTs4w?VCJuBa850|qpHJd=qF(jeeT6yM*(7KTG5F>dH3jYB7~KO*NBt@QyfbFxVJR5I%hW#065CS z94d0(r5@<)6B?x4uZZyy`w;K`JM^Cx1!(d7_%3zk3}xr_HXM%oG1*Sqs^K*AP6@@$ zLB4ZucdXZ!CCj#2F?oH!d3XNeYg*1v^lmQrP>A(uMEnun@%Q!sWx~Sp#LVgSBK;WP zHtXXqkob^Es`y7OJfd6rFs1jW%#KIxn>IKnz=wK?T6%XgzW_S2Bmuq`h!i>m5!4-% zbqv!vFM2zJdlUm%UKOmDgTA#Gx`&ZNhEXie1ylM7bl;gc-pQ8v#>(&|Z^Sn2>v{HC zZxM;OEVm-~Ov+dt0!Z|5lbznw#c7XFwUFNKG) zS@4L|mwkIq(?d=V1un>JQvMa{l@|6_k>eq$dg;lT+PiRrJR&Fp0h^8U$+^5;6ETSp zF272?g`cu+Nt;*9$?t`~+=<}M2!qPj$ain0jv}k2M})*D;7ajw{ zl_OpyFaq6y}u;jY=W!rMuvHO*Mxi-V78B8IU#oPPLJ zyJEh7vbL+V<=aUVDU>bX?;BU1EbiDzbwZ2)@|1q;0@HOyTDJ(sa`>TzQ}yaM$wLMA z0+3-y9(@%_w&J!*$$kny=&w4kxvP4p2@X7YO<&q>e{a0|?{bzd`{|>W&@Wn1{L;CL zMCY;cbNwvLC4W{%e+ip%A|C&&`oR6m{%G>=>{*NYM(=wJCTUvWns;hlG}0usJRhus zgrBq-Zv;KUR4Af_Q}8jW!X8?q^_`q-(dqUDI-VeNJDWyxY~`2j1RZq}1yEtxRjD_{ z{d82VD0j9-C(If=)T z;z*Zm`UjHgbAP|2QAP>@PUnFgwDb4xEIQ1)Cg>5Xj1vI7jx|HHUoDGPLeJLb&Fr_u zy}GrLQPLxi@kCx=4i(Ig%?M+NQ5Vv9kUeCY35{;mN=+bGyC7^Ra1dT5_ezHBI4(sx zTV)aa(}pnQUvGh^_~1gkp6dyQ8sFKx{hLhSebMSlGP7Va0e$~_olmjvHtmgk!+@zH z9N;4d)~4Bg*@Sf>*=RG=0$*?L=$XHbWsYyV(-Iy1tH=qHE)r~mZVYDd)8?rG#@VPH zou2SH!%$3t`PeP5;>O=yZWt90hdhYf4W({Pi$$srlZG&Q(Oe=*f)(3Y;q>L&=9IyC z&Wt9^#WLTi`=v6Fr_D?8R^=EGbDh+xbt1aOAmMZPPtnq1R5c&_)*~j3@$W>NUtNRL zq&*x3Edr|9Nr_$Zpf~8|^P~}QRj_eQEK*!ajhx_u!DN1c5?i$daRy`i8olekJUITearbyLgj!1oY4;9{r0CnMt5za}Y+E=xC%hy5%M#Vm*iWa+(`B0tB(4Prm!0Kw0U}TAFr>oX7Y&7&j;3 zyQg5ZABoQ&c@>b7R$R{>?b6?3pV%3Pq%<5j< z3!>N!z6;+I{geFC;gjE_D!X(EzCk1)SPZ%9V17x7*?#VSmD{WEMFi;>e&S-cN1@8I zyc3;rutNLvKPkNO|4HH5RGie_V-lynhpjWww6S4Ue}69U>i(Y=z$Em~U>JA^nGGkk zno66SA$4?Vclewr7klLmYcN#c1UZoCj&f+B%Kx=_2f5DHutW1oNlS*(kJ9qHZVj~? zJ}v*A^AU&VLwHY3pla&6-7eDBOXFd%0vR`WO4#+eJ*%+Jrua!B)s!KyBA#%7>H-a} zsuh1j3W0APB>K($=dz!gWh?jX#}LRFE==BL$ndUMc4^C9!-K@Hc5s3lnhwAeZvf#j zmh>J>FlUxWj+6ESw_AtM4;Cf*QmIU*J)4xp#7M%g*_yr#(Qu?W>08PysH6s=^6Rw- zMMiiV8gqI#<#DpR)^c-RUjWOX@!Ri-v;R3Am9jhJobI_R5CMja-HW3NxMpoee~=eG zpIhDPCKTT=se3jcQ?VtV;FAO-rQ<0~@&NGV3%-){3}_F1pe~j3Y#4WHgnI&lijL;n zJ()+!(lkHgl%7uM$vRPAlfBWcMQ>tK=e0_S){7%rIKF86uf@0kQJL|?%w6p|H&{19 zMZJeALoSeRq*-6fjW-=hU;H>V0TjZ1u^6Y1sbvhs6Cu=^KKyw~!|t9(auY$S?S}+^ zp$fr^;2Zyx{ip^{!w85!kfy;ze$lHx zh;Dv?J!z%V6#2K{{06qI=xZAcz783uIwNm-j2n>C*XLgd%Z#bRC3>XO=u{(vMgC(^ ztRu%;9sGyLW_`e}EMs`C7?RZPGn>Ey`Ov9}d~eo9wbW^Wzq>*vIX(ecEScu17AHka zci!gP>x|F(wxP6@9UXFV*j^z&u(8r^f5G z$+ecu6Ju=YZ~jM`4WTCJh!?C9jwdZMbf(Qs-xJWQA(DqTUbzW`r!(zF;@@L(hY{;@1C=Z2L`PQGw)^}1r4DbuYJnzaFxz# zzM93W$IEeBn!3@uHXLOF>N1y&`;wmmwEtMMgSZfqgs@{%B3^9d6MDW04Vu>E7kd|q z^G&_>NdV-Y^II2x!HO)Mxy>hjnwy!urT5x)pwaXG`irtLkAooXH1%7?EM|#pNUVIP z;i0uW>mF6wWJx~zT%)5c#W)vCKiyAd)z53J>CV&wGI`VeY4fUo9fM|Ula}(22Hv^u{riAjXy>m>Sy5HRNR#q_qM!!lNi-8@3Hcl zv1607j((c9epO5+9z6@A#Z22 z=9xXb9d){dm|~yp0drnWt17$A1tx!Xn(CJa4Tc^Q1dqy!69gaVH3!>H|9f?TN8DPu z4?Cw4WM^z#L=uE)%x@E~-yqOkwr5$M)-l|_OGe&~#LMeP0}iCqpKOeT97RH}0`o;p zzIO)2hK(IO3fsSLl4sE=Fxj_DxDR9sjLfENe4ti*-q3Sm0q~9wFI8Vhm$tV3%KFIi z5F?=FJH6^WTrok7Mb(2RPcVn0OQ*4W&|U~OhgT)iS1!+V^=cgLTl2rd*v}j^7A0)Bunh!p2@7L4xeA$m-p0JXo}b8HC0)--L7bfoan^=Zhm10%x_=F+#A-7EjY zS<^`?qGukg{|YkRu3@^gddX>|4*yqn`Pn!P@DD(&PCqV`_`-IdPhbcVb7C3|2^3N} zyMTDfQ6!9K$EFGcBRZA30szDf?#Kb{OiCZ&tC*StB&yQ)nqOA&l2w~>QU=Q9sz3J) z+K=td;()9wNaEtLcV~IJm7_tQDhYL6>64j|U$ix!WGzF*><9awG`da zj|>Ubjr}Q#{UO|3%eDdvCo&!eS^Lnq)|sF9ufFNqo*5kv8Xli%r!*q^HXl$h1k)NC z|1$5*fJL-Z#NKLKAFFiskmK{6G*%XwQW2im5Ug6m zY_tE0I~#GEw%Miveal}z?X&{Yk-V6t*wxBkL`>*q$kiwP_ zxFox9gkR~4rpvT;*pM5jyx)!h?<^uT_|>`FG`nD%lws%nB*j_APNh9R)M-|AD@kKlp} zeBM5~W({K2*w~rEYNL;O8JNxRy;t9~Jo$x({d~WN83f6#DK~6z8VA@5f^w}1(kdgE z9Jy~oZTPHP0WjbMJE^ZLyGGOG7{G0!|6L2g_NVZ!@MyZNp?1oZ+m?iKwO9obx>V$J zuIK@(=$K{=kbj&;U@4}rXP>$rC?<-%7;Y!7L06R}>swPORbmv5yNUlI=Gkg@bS;2G zhfX0f_Sp;Z^L+1zf=SBwF`ZcQer)1^2+)wpRvkh>#BiZm;MkF373zd;{yzYv0P`dH zVl1Zk@qZ=@e9#1eJ#vo!d&Q;-wcT8BJlK({!fe}-${|afe-}9u{auKer5uxA;O$X< zMI}YwLI@6t_HEscMb#^#dNN#Njjr{rFu4bddZ@C+w6T^EEpJqugf#jzA(2i2Te?k- zErX*I&?09DE4kqp9=(X3%vMv!Eh$wWCH_Kb{K4m)3JsRnWNlxcRw8`n^#5K(Wx~iP z7AJRQdy?lbUZSKskE&x3$X0|dTn1zO14i)lD5t`yLyZn2Ha`M@b|`Zy+pAPWcGRok zT2v#pS(8ioPKy%-fuFtxZFI!Esmcdi+Bdi3KizukXuFjKsGYDtfX;~28^@%Sr4(5oX4mClUPTfa78TFUrYzkp|}RDVvL8qaOX z5|0ZO9aEbnb+(pQt4Nr>_0ZV>5mDTd#{kb>#HmsT@Og5H1_vD~VrUF^*I<#9Do~*3 zstvCFs<6IS(OJ5DYA3P)PpulNk(m?K642bioiCsDkZ}L_>Raf$)XNp&ZEbI)WD^F9 zQR%mBp+7TnnZk>OC+$K6y+NtzB}6>AIR?@F6$lhtA`Fzqnb$lY^DvVL7>>?ze@8y zdjS=KT#_hUNcE2^v{@!~lN|Spj9mLee2c727~xkDF}Lcp!ck-}(d^}QcmS_>;T$pX z1jFD}H7mDst@ia?hpxc%f}R=w$RN<@p#Uvy-eUIHB`oIYs(28nF(DL2!f&w7D9JZ! zq77JEig=6MFnfd?aat4<+I@;}%CX*QmQCuIU1k0G*bb-a$nMjG=#OcGhA+vmd#hu0 zT=vhbM}^x(PLEV93!Z#-Ov8Hf#`=ahH&2s>7s=bz>h>J~oHUO~Z)5xnX6~Q*tsj{vgc=%P3^5Wh!BS1iORfzO{u=we> z!&6I2*NCm@pK0WCN&(qHT(mPoY~V%Q zbm>pZU=xRH?ewQ#P?EqM`s&0V%vk$NGxvfga33wE61gXY{ouGi(}_{@gUH|^`>q_e zsw@7-VTn^30g^G89y21WuylElO4ncp!WvbnM!q zm|IoFNM_vN;VU*2Nlpse>@G62;gT7=>dxN*&91`9VIj2?+Kw_8spv^R^;uD35BS1c znV6I@Uv0x%13&NWTU&i3PK>Rxc6>gHv*#)O>5DgLg5I?da9_k#AXvgvB^yXH0;=eN zVRW`=tAWvdTlTiqEyOPBtqjdiGd4VgU5u5h^IqCyuD%EfUdigbpb+fDrNBjt`602f zMr3d)EDccQ19xxLe#eSx)oZi?0fgCAON0Hyr8?VIvW~WV_f;FVrJ1Lg7Z?C*Lfvwtetu7lW z5vgU*=X+%3xNeApNkf&#KJuOcf9NA)w8Dq0%*i0wuL;W<3`SD3VSHrWA2bvi2A!W;50~f(AMZGXc2D%pu0Cbr_l(UVnsf~xaxwcj`_!H}b;XcYUR?Jq=Um>b zkOzmWZn4<@q-T?rJZ>GM;S>TeNFMEuRkO_aX?k&h-nNT1I^qNp^vzTox6sJ?%ckm( z<%&I$Y5!wfw_?azr3eDm5W;a2-R108(}gP82v#6VyPB^AiuJ*ZI=Uu}s{`gs-E$br zGSAS%IFu1N(&nU@7F06{7J54z7Shf;?L9q8-?CRzJPBf-k|2xre>aN*T(B^F&@+Q8$Qty&$xv#LHDS=)y({wby z?(c>n*crt!{*}uWqh^K7I)b815-NL9Kw?IF2Pn@~Ml!CKztT}N_hg}W+SMkJa8YG9dFg9kC;RdhNoKyl>&4XkNSu&rQ8XlWx0#IJ4B z$Ygk*ylH3%$}$eseCyRwM`&nx@-aTwUg}*UV8r2R`%m-u?5!dkJsw^APUYFP+oR!R z5xI%A_FGy%x$aykRa7%C|JDVNfL`#3^v{B} zc=J_u*c*SJKSaFDoz!<^JLWMvkbp&Xf!${iubY4#oxTkDgUcdswafv6a&md9(}m-Y zF`My$kS0fxx5m)>Yl2l21$G3$V7OiE&qCad{fxxdrnqGSnwIuug%$E*S7;}FDoC$s z?NC7H>s)wy46>c0Z()?*Xh@Q(w0$-WTZe)Pp{Zuu1oeTkH0S>4LwttJNH)y7VY;n zkR%s-I+b>KBa>F8-Rtk@8Dr%Q;u8q6p+?autPbg!rxxu@a(C`OY|-asb1q1~)x6Tv zb3-En#4u8*vXLoZvmBPT?91U_S((=iX}fEX+5jaN*U4L=M=2U#NbY*oHP``waA%@a zc~||DP~`K5lvGy49hQ~$@&FbMc!=a9gbXNRS`0o%>TLXTRgy3mXLeA{)ji{6uDb3B&iANNhn5objnE3F@8jxo)bHt7fPq0s+Ur;cEVyPjrWN{m&vCGEm>Fm zgtu`htH{hRr0pzvCodQ@^roMj`5$9`*UT&pV=0c-Xg@!Tg7z`G(kYhoayuzNk{?~4 z;d6!mN9Et^g=^d`6x{0dqwkzAotuxTh%VoGB9u)23RhC3!VOF9kR~;-WFc)|n_@&K?HuAovD>MfHepb$0W>_Em@y z*qM~tQzlpwqr9?y?-da$cS+&2Zqe@yx%Nb^fwS`Dd z!M=9?sP8g)V&Pjw=w-gbm<_Sc7S>5}yx6f-SLTvf(vV9@_+sB}T{&hwCpTqRNv0=g zthxy!vsSob4SXp5pJ3%>U+MPi_L? zH@+X!BEOD#j@2NI{lqFw1f(z;L0vq%@fulom1IR}7j4YX6$szRP%D={IJEyAZ*si4 zMn3Q`>EEin4+A-hpD~>urRgFQ!4|i5GK@YY0<*NlRia3+%che)DgX08CY64r$$?>P z7o1?tgxHS1*r#ZN`v$dw)o<{7Ow{rhhA(11 z4wu6!f-m+P8&YBL&nLH522L1!^jWvhJi1?ZxSk)-<5S;%{VM)VC3*#Tl9P7LGq^Y zh{td(vv)=v6M$4&+5XHRn)R>`f3i14d=Nz*k9<`McTae-*8rnyv;hjz?HQ~U+@Sk# zB5r#9x$?{%VhWE~0fvOd1A2b#!N=i;E|~4D?*mLRpesckyJz;i=D+6)!H50-TM6nl z@If8@oW5DZU(~P^=;E{}BDEjUB~XV~ElD$q{DlzUD2Bk>sW*+a zhUmR+&r5Qrtj%R?wIdDHuW;xoS@xeqPzp?rl6w-<+@llb5mlTpw=MgV_vmys%!b{L z8#hF-CJp|$#-B$qEbckQW@Asf(o|t$%$BKaW(^K|( zT7rzG!EIn?wo&%frHVJJDfjDRY&=ETQ0PYY*d(IVmYzxg-&Dzx_gm+h@aYNK^Bf4$ zdp$6DoDj{OlbKvwidbqNeY`NkT@pl?6X^#ZJSZv9lJG!tfE9seKn12V^UuQZWLK!j zn&6^LG2)(f;MTwhi2_BT72%7?9IPWo-gvC1SB(HXmLF69Q8;+#TyM?vJ#K#V_$azV z1o-#~>>5~xD}94BC$u}FTVg6<&7?a$+Pvx-@V<~2E!~OmsC;ZB-JXD(CSe@1MPi$c zwg*-(gGR7nm-_6Ed^uFw@^q~ym|r!m-1W}V4Ll`T`g0)NTRdMl&&0Q|pCX>GO3=6d zz01T`Tic~6b7Mf|liOCMMhx_l6jsy@TQ#bRTY4+~8DZ_7u?PpbJ=+@41;iZP8q)@@ z8L-srDsf!}4f;ZcE1W*Qi?qtTBbtHv!6^+l9|}nz=je4kI;zOEI)%Pu30{~c>ktaS z9?&*HT5E&Rin@vc;T&q?kM{Rn%3`weH{^N~9E;;nChB6DG^&KMDOigf%;TnBOqhAK zgfvTYEqBdf30i$0v({~X^13tbaF<`-#h!5}yMyFXv;Ku?ml*i1otRqZ$AjoHyht8u zs^er5Ask9WiQFv6b9&v(hH&Zpt=~X=)V=XgUso=jny;%J!Tvt<>DWHGd-e#u$Rvi* zU3Jgne1U9~z8D-P>p=Nd9=>Y zRbr>;+dY?8bS7QXhYc8Ea_f|YW@wv^FRaX;Za6n_ukIeDfgw@-oS1#2jg2fQ1z0MK zli7hcRTg-4K%9!$+i6o8+`p{(Nld^OAm{KT$poQ(nzucnuBDdj5(?90Rj>d?LpA5O zBOS0hlKPa|cm^q05W~vP^sl*vvhJarLIxrWwU<-NQc*wbf`JhYt$um-db!wd@YCWhZf!iDsH( ze6rgc5(gm)M7vd--9*_>J(D;fIT5_aWB;r`gx>LK)mAFhpun5;f{YvA5D(T2=fu!FhE00kh!WB+{_zi;%#V^Ll~-l^idIu- zYU%xmS=jf@g6Z{q0Q)0zxcLXtSWXE;wmLnKa9_BENV}LeYr`99jgO?)SFFJU@lkNh zQWHn4`NzJddPCo~7!@$1KveiYEdc6xsRseaI!pC7jcu`XL5IO>a-Q9waxIU#C_1+6~0)|Tq{LdZvZPVB5=T#R()KPZ_iqdfY=MDY1zeHIEqvPG;66| zHtkqqIa9WLvI0wv%t&q?(fx9yf5_Os{-7ZH5zvZNwj%lm%qjnpN}@{G_uZ2s+(89JOtHmWF` zgYMuF)bQ^WaH!~igOi7OlU} zbQB>BaSg0HoK)HD!+#aj-h8zHbCs`HkR7!2UYGIKtEIDylJDl3ZMBoY**TE*B_HZn zA8#kgF6sb^%7+@CIalW<5d*#aeUGg^vHkc3q>D&K4*L52whpA}Uqr8^-6K8z-~4!~ z_}~1OxHgkGW+nqN)jR|mCe={I42|%3lxHr+jv&KZe{0CtZIz^6nk~xV+(kg&yhefOgXDPG-@r+L!ubBE>gm&XnNx5Sv#-lqFy{tK6*+pl4LD9a{#@p-~G0&hO#VsyYN3D z@xR7EL`LA|sr4w0Q%E<+~=DI2^|j z9ZI1q-Gp7e%iXRc6Ez*skl+Q%*B+nLU=nGi)dLLJINc_icw+6-wxj`p!W9ZUS%}R= zlf`=4bUQ^^e zo@8UJtPZ?zzu$l-Vpwn5vi*Pd5+2w>#Y^=nR=|3h!zGtazEgT1xCIIVwl`cGeHW-0 zN1p)zJ?Rl4spi8LOB(-Hvdno0|r2HRev`BN=|>I25oVTjm0CdVqR1IenX%2$?6DYc0ArqX-k zI(`vvKAVe8KdmEO8W?`D-&qfy#h!G#B?7Tu;}o-dQ^ zbt|e{#{4XXV$v^hp~;nyhSX&nP_TD`tzjn_nj^2~^>5k?g+KNjvrK zr2Mg2iB!}WS>b)l?&AOTfzlpxvFKuF;-}GjhT0|D zc~ANYd>mL&^>VxgeS@;d%1*z&ijzlko7pu%pqDOsyMZIi#YFgUw-K3~wr`!cR|Y;I ze|RzcPz1yb48_R4dg7qaDOe3WyKG50PXB{N> zbuts>ZzK>bi)pFXM&*oB?N)~re3)*=v$W7OTtd|mu#CIw$fNn=N-e41p>zUK*cAd; zFACU$tI`|y!Y?w=z7yKRjAHk!4y4aE8Q-53*mNX&b6y8rJX8b_{awOybQLo(Vh;L; zAG0$);5!~zF%Q+;*k;VHtG<3!&wb3AAOH+YfvK4u!}2U`BJnf4wH@kuds6k`)P_!C zfc)2*Rt^uSp?hPR)@;>_z#!@;2 zeDl-=-rk2!mBRgYaRXAR@jk9OnlC!$*k_)@_xvl{m(dLQQDqdxdFJ=?b{;;j&&g!R zm%p=WXT7Ep=&-*xNCf{@NHvX)Ni&VECm+A0ibU*h8ODWiF|VA0GCQigBQ)_N!KH&l zJ2y$fo73S>Z9|M)R^jLxCce&vFh~i`pLEc%*R~4L zO6k%&GqH$rA?o+9cROrTvop*Qr)cin-zGBhX|MFvZaNxQ5t6EZu4dTa$UZBZGzE9r z^b9XDWd-==4nE*m+VXtN=rfhtd|04PlFJQ+uAl6LPz5IJ!%3z@Lm|X-bxg6YRdc>8 zuBuv4JLtcb-Ck|x3x(lGOGw$LUL&_%9@&onU#gMtT=zd>_PJmF2DwU%+@%$*?c)J) zI*z3|@{*@1pDhzzO5L&+Q?QPMCAy}}052zriRoXC9+GY0RSdn8P?3oph2F%?4%`>* zP{cbQOI7=YOB80mG(yqAXr~;}6}0wTs|UeK=SmCW4Fj8$c|QHO3wDBUsfrSipcS0F ztg`oMa%;cmgjs#;*J!`MIpE1k%#XvN-l5r#EP(Kj9l0q*j9{`ifQ6+Ov>{nDR8kB!Nd`vzqml9eh{2v)v4Bv=&z@p6CO}ONF1$Ie)TPH6Sfj>jAZo5q^7NZTwW;m zVM{2BEw;^r&b8}@a8BRvUS0rLT4*RYO*NN%I|y|=5g~pEJ{|#OrkOYLH+a6{MqpQ}SX%StJ$-s#%(=sZ8t}y&fOui|Ozh?*b&uK3Aok+*ow>qE+G4f8OgaVK3x}>U z9z|o>EWjT_jL;q2I^QNm=Ud3Jf!x>Qk{7=)(3GZi@7}ciQZm zMMrO0KRRxlezUY{^P0-6Sr49ux)!r9fNzT^Cd{f#`Gc)ovhDso3NmT`YZ@Bq*~g($xKJHI}8Q#KpP? z7ont7^M61qcyNbku>nyR@e3Gk9Eib(!s2=Fe+jBslsf5g{pcq!oBMEGYblFjuq|1_3CVoVJGPIqFTmyz+7g^KXEn!w;izpwaz8S z={GSdxEZg4m-n(b{y?V0aE%%^VrF@2RfC2`6QkU6PQZZHsQL|x08yFc_rtjS9biV; zM7ml(=dYCd^_TbA9y+gET|1lg1geYpJuJH&J44A>6-M{qNY_8(&X0}uTlmXrDSXCP z>DPc1PTN|j#azo0qajOzYr6ozE*smR{&g7`YL;mJ>;;Y6ZW zrmEXxl4u3GWcJq2k}x6EBl7qwPBx0LoF=P7@N$_)V}(%^%DZtad8Iu5sC# zVO18xoxlidN&hEodjdmn>y_T@+{9w^(pNENqpat0Xq#-Qg);r?ssl_O!ZTsZ9Mlmt z^yjmc-Sx9g^n2J;=rO{1z>WARdS*zT+3=&~Wx#@eKJwI^*|+X-x}cd=wTFVz?yZW_ zuXFN-|Bv`lE&m_!Ls!H0-myzVsseqRg(r_q*75h3V}#ixXS9$k4e3;hK7%*}e-b2N&)3$YYNmaHTD3%spx z!12l8+YJv3FK59tazMCsi$2)s(oK2#!w4IVfC*8CpoMqg;a=&NjN*4b?;^z3hW&aM z2a!N>}srBHYf8CI!*i!q`{jDLZerIJ(<^yDmhg1Ns!bi&7n(gggv<_ z5jRu)wkOYT{gxDQfT-K^D~kNCK18`^A)SpAAj)(L*qI0>9%3k9o-U_=%%i%e#^Ic= zXGJsn^OUnSJl!({iD=Zg43|2@{|W0p@|&6+>zs*^ZEYVNju*e?Z+pi*A-%^`b;qpg z6BlO;!H4JuTno9e1Ot#Y8s} zxx$-{ic#5|ZM@4qs`^|Lq0#w36fw32Dm-Et||+VC6aG?i6w=k+{B>OWVtwfB*J?$%q6(gV(sLUB*b#6 zq3SDG*sfo`+EdWIn8VQf3g294Wrs9Hy?Jf4Ey*Zu{6Bh(=6QsvOJ>q5?ONfr?Q>?8 z7ut#Ec4YPtUCscmA*b&dp*iI$RhpOL5mbcRRv3CVBtYm%1&a&M5Hg^2i#sU@rtnz zI@!P7BDMAQS5t-Yr~(IrBOi7#8`o8zo9cRuO%8|ip{_4uH{NaUX!9Mqt^c2bWX>~^ z!iuzu4CAL;!v+DqtQWugv@tLz35XfldEx_QkZy=(@7uSOEg^-Z4LDBJJvca(U5md) zU1vM1(}(*B@)#BXmZw|BRs2N(|c=QWr|Td zegF#)*;z?8VEjhA5@JG_4j5vS!k>Y|KCr66GK)x(BtZefN@0~r4oH3_bv(c*grk#Y z1*X{hBTZp6$u2-vCfnTZTC(EbyjD!=nb*44{K`m4ews z5PS>)s=(OnZ$2UWl!*}Z>w%*0tPj~C$4}D?LEH$z`6$5orBOis=!>S2SN0^V66CN@ zOdMPwTlrNHT4+--&R>7jixQU$EDCzo%5Sq;=0k<)WRYu{Ihxjo=*O!O2}kAM|AGkQ zmHR>8kZU`sM{rmY@))}1vY}#bmN+<_q$fX0JfP(V`L5;pUGuQsXX}`Z(`N%E12pQ- za^JcK;V>^*c7ClM!YiuVSJ#f!BliK+&jjLE@ouH6du4>eZng|UUpO*iik4g z9*8wV!L}!$g0MCOdcye2)jv4vd~=^Kdqip^T$}#q8X^f$@gbditYS zP6E*_!|dPn8M4pU$*>>^ho@A(3fJzAbGMXxDW5U8MD0LP8{3D9!T`pvr$+pq-tnHM zR#2RHzRjVqNDw3Eh7+l(?A{8L!WQC(9W*wLd}&k3#zl;L{!s{D1XrYET_ozN~S*L?Tl?$Jj=8u9BhE57HPpRndi)5(UG(SATAR9Xs>KnWvrm8GJP6o;mQ1 z?vJNtc{Hb3`q5!HIOnojD5D3DDoeEr$G8*gOQq{=@*`sGXoH#~B zciUp16j!}FJT|?9ah6%d7t}W#r5Tm-GjwG-sz~VKaGt@rC;xFyHeOj>#HiYbruO`E zmS8H_;|MMIQRM9J_j~!u$@-l{d%2LuoV&6AkEgc`iYwZhhR-l)aCZw3Ah^2)PjG^} zYtY~}xVyW%1$PPV65Im8J-9=@x%YeS`)6vZrp}+KvwQXK)vH%U<335H25%Js*Pyg3 zFCW2xRn2>ZD?bGA*ev%ha!WGS0&*1N){FK$H!sE7c`(CR@dtbpby0s?FF@PBlZ$bZjOVPG2kv5kzHsKM0uQr{P!3*_18~VvPD4= zHD^C^%#y8gbS;P9@?Hov7VsIO)cE&j)qYeUiAZu1) z^etPaVTO-5(X)H!nWfyNb@|n?7Grp9>W9(H8H`1wb7mHu9m{c8rND+ny_77G*ouhW zjn1Zx6)Y0q6FADW=TlGQ4j7UV3^7r=!C#BxiHoBDK)C^LC~Y3>`p=N8DW!-l(rWHh z|8cQz0{6ZldH=n}5Yau=taZ|3KLzYYSTm&^od|j%PS>)6s@lEM$zIIiEl^ucx|&zL zWP=I&`qO4GC1Hq)h;m@!4Pgh}L%kE-I2yR@qtFfQrK)JG(--K8eHWuPeZulJmvzzl zu6a7sK_2VhqhyU^n^2M4^UG1wzsFJX@QGM$+aO>6^1t7=^>k%J17(CUGVPn84#x*l zG||om9|ov**J3+;zdX4EtiE^-|NpG~DE|X7KTMTEg>%%hCPU@@l3BRV5S6j0FoZ^k zzBlGl+6;mdH3o^QE8GoCB5Nq40=R4Bts2@68=RDn{0n(dMH78(Omqu+nO@7(+_oPt zJJLggph=!dd^D%={x<#BMeThDbHfr0hJ`^gC{wu+p%B<2wh66|(y9G8fZlP<&7>3vll`h2g_Mwo* zWr9FFtHf~UDcgoi*nW-J>$}A%I(6%fg-#c$KJHbx^@R(;&Y6lo-ow-vYE0{gI(-o) zzzBOyG|p$x$e(xN3~s6+)lKqlqceJ|>uNVqk^MjogPT%A9qp%0P z;lC0W-Rnd)$Zk6C#?JM1eCJ%bK=uP8LL5ot0;a`z%eJH4dCQSP?%9=Rgi$eT(gJj7 z3L84l;P7R$!&FRDLGp~~pwPCocKx8@OCfLjRg>vY2L?v_4^3aLiT0-H`N&EI1k3t% z-IHPqGv@scd{iOe+a!r1{yK{XJa-3ED1TZlaHdTT<#ExOTiJ6GxTLhKZTe>d5upxk2+x{zFG# zcb{-14X~EDoKc!i2D*dQLP1Az8YwmD?VOe>@Lnz55IzaNGP9|1tRsY|a){-?HETKt zM^-ORfDApo;(U7LOFw0?0@K7^9a~U)FX^sC+_kbkMol%})XhEx{>XFlz6Y}%y3?-= z*^u$NEoCz3z2%3wMLowe)b1NzR@ZMKY%P(>-c!hCI7!2d2J>UTO8Ty7!;@87SK-b_Q zdDHahPf;q$d0&h3AKO~`-+SjP*cZKml{*B9ca(+6xY8fys&ZUwS>{lx8{*C{9*bpS zf)=RwEGI%u#Re5(;49MQ+$b-3HKeoG31;9f3GMXFL1EJu-(#oIp85hdkoYiea7&)k z*2xBP9d2DDZxwD)nIC1wyN|9JAIAwGN`hTW2Z~aks$Z+*49>0@NEF;ov@ z6$OVYSU3A6lXm9m`tdnSUJx3>+mtI{D%T)P#+!8QrInKHwVS$gITT=Kj}&@E!Cic{ zDV-e#SvFs%)HE(k)by=vYVV(^=Ncu4ca|Xjc4CNz8IKD^rcUi-FhrPlr4E!QYP+EJju(;sHe`%9zuc7rHD*)7L_-e2GKWA}5(&}k~ zO}rAL9Nf8TDe;5Phjmx%sHfjwb3`mp&Q{E{S`lTics_RnIjUb$^kT zeIbt`g?TGkaO|e=&WIZpxgV*U6OyGsJJ`$zYdIW@4yd2~U?zVWgG9QB4^9*WF2 zGH@+JiS%}vO-LQUdea4=ksZqX^BCUjHsyNUm4xrK;XPqR%5}L&GNFxHq}Af}dUFO@ zLAB=xmE%;i!!O1}V@z0YlqQ>qVf99}-Q(c~dwHLg>>Z#JAv?fCX0^M)QKGM4NiBuI z@gUSNK$Pk&m}2tNJ9I%K{gI5pH@7mBfGbObyJ0O3Y(o)so6!6Gj7-9J0 zi6tZ|s4Ue0V$b|Fk_b*Vh?s$UXD}Wg2R;lSL49=h|0U(-e@K}odzmq@ZqeGd7E$UU zxybFdGUP6C#|&Ie(l;^X{Q0I)*Vcbb_#sRV{PBNYfY5*(qa-ri>6F2b_xu%lZ9_k_BYwhR^L^#S2*bSHXi+wiM`=a5J-fbQHaQ=L3= zdgMLB1DS9(0tT&#f?hSt(4d`0hqf#@17w&X=>bbIM&+q29l1WAIrQDnMUi0Mw#qyO zj_+V@ly0+83!c5!s{4tV_8#F9xyj)YHAT>oL7<9VGxB40={wz!^`l)SQMY(Ub%AV> zcPnX24N-Z7I8{^4o`9yyO8}ldOPsZeqU} zg1W~cHOwM*9~s0wqwtQJsiMaf*W`mJskWZzk)^@z1=$!oy2H48j zI!LOF08iIm`TY}ffVSxpoB%p+d6(D&)tJY?RI{>)le00@5eKM~e`kmc9*E*8 z$XCCSRy=XFZ}yxs)d8o~v`vo>eQG$T_7x4OhHf(0!;d<%u6BP3E~y4}mO=fZT|>Cw z!p#um+wRhez(FeM^N9x-on%FP}~RazScb{NMB$ictH2XYhH=)|M}k- zmE-@^`fh5PXK?xwOM6k;Hoywjg&U)sI0WHAm=6b`(+^L&HZ`X5z2DVlYo5NwAjVSZ z-8mV|NJliMXw@CUv{MR?g3@?23$!b1ot$)L4${}L5bdjj5;Mhp*$b!*eLc?{Yi&xZ zBU^?{Tx$Ct+AXNoc5g}MESvc%As#!XNd}P>%4;X(OhI2bZgJ)!Cpw3=`EPJ4QEoVT z3o92{)oqYeHwLZkKP0au4VVOQ>^+$-*Q~%3+R@#&seRj!A5vIcRL!e%&SG^HVb$cW zDCNpj+_spUt3)?V-0~@}eK|y~&g4xS=o)h&uJre^A#S&2R13Cga7{JSj0g4FO)88j zH3dy7YF@GLz8U_us|y$!rfQ=tv;Xd-kyoI&-@$}O`IeT+qYXT%Sk>C1AL;4Ga^yXt zBf~Wwu`sDZg)nu`nM6jmy7t=T(A`nqje~2B;(V=oOemdt@rD)sy|3gU#1O{_z5O}O z;~q&?jL}u`Z;yyct(+9vxd90WCVWKodg_YFv!~DBpsnb$8wzXg!ItraoTQj4bxD=F zM8>a+SmiOlm}A_ii`IOc3f3#Vm_F+&5;JxZ=vgztc~Pi9~Uzv_{cR@ z%>-w)uPCWUL1Fkf4*U+%&3_m%%yZko=ZP|W4*G-3h<39TwSd1Aa?8={x{71=>#hl#zz-XRoYMB1yAh*p^nm&?K zKxA|a&oH?y!+18wOksw$3*8k{w>QU&kS7rTVH8Ar@%1|G6r}C z9OTpm(g>k)+Hw}@n*tae4Mi#TrXy?Z>Vm~jkL~VadKDX!Ha%D_nOxp{^WvJMV=?W+ zyqGVbG6B7-w&l(Vys#qY$qu^W&gAdMdkWr3V41%+j|b|}0UxjDqle#r7duCpU#TK< z0?H^r(IHyZFVOS={N4B~hUbmt&N(#859mSiy_t}n!;fVvu`nHwooGw?TLyMULgc*C z+tTO8x>^Jv3p%@r%-*{URfPz!NP34RrmJslY71M265YM{zLqI+jA>1qy_KL8%67`O z`4SE-X(JKNh5GLVlnJph>^ui-;cJVmLA^&$Wp#ctVQ+@X3*9C9^Ud&a-h%42 zT1yakis67qSse=9r+ks28%g-y&IRLln*N?6;s3OWb1xO3cf*b*f##;qro+wu&5bxd z%#|WNX#Y?1@bHVu_OHm&YPH-ic=ju0hoPqi{ZyJ~2DMuFb;UB!*}*@Bwz0#gTfD5W zP+;bcB-=vw$2~M#{4@=lpg4F$+D-QMS&k69au67#_3(^U6vhOzmcvmv)x0Gqb_6~| z-@S4|&n{~-`Kncp-K~pa=N96o{VmQow>B%rFQYE58PU@P4zb?F;Y{)up0QVv%8Z{9 z!6hG6c#_uQ2Hc3A`2w7ZeCtRW1mgz;###3*%ry0)kIj$dYZ1{5hcri60TL{dChwba z>fZ$<_-=~HHXOasz`i`FmzoiJi)7!`~LRqpNN+MnT3XO$?Hu@Q3r$9ukuqJI2eDWV7Ra?_=qiLH0IVA@kzez zyu!krh#2IU%`%STvUQXE9e6t`-WW8x%y$7YvbZ{7N|eZ2A9WIoDmxln?(e0uou6Gx z1D}|#pC5hh9}Az?ou^ewr(91wa_>FHyFY(c^eJaK&yUWbEMGTn{s7&MMKB)c8w;lU zC_d+uZtv`qgTJ}|uRSz`MsCqX!lA}jrs~v zSu|svztx|wq&3TW+M-c&21{PQQ84Bd$A~#6Bn%p z^HU|E6s?*VX5?&%$DU`!5#JWOeM6-@=;Ti)`%R+|ROc#CpSV$)4a=NRLK<{d**G`i z2CeIs6j4UHZkw3r$skLLtWB+sHpki}o6Cl}zMBK~p|-9g76_M?G`0G>C#6I6@HAX; z(`e-=dG1MTYG@GmsHIn_(~qg2a8^zsc)QL4nj%l%2+uS*wFAGh+*+0Bo!wyNPMH{Y zVQc7rEFs@3E4nW%MvIk&lYu$r{01*m7mDZgS%>)RC*Puuebdn6D~3B!S81<$>=XCj z*jG7mSGY<%OBG7f+CNHL2RzqQNmt`OHhsoQ3?YKF=2ps2w3s>->&|VrXJ8=egJCWVO^SO- zr8b+CJ7hmWatppCQ3$9pbb>4CUyH!$FbQz^2gx^Ox#v5O@Wmy) z@jFRaW~Yf^(r3!e?N-!9;KSo5=RWhl1{(r_Z`)3Lg)o zT>3Q?D?WVNkieGboE`8(&X{od@3&mkH<@^sPm6e_ClXaRRM;rKKpy_KW6mLMLoVl& z74QQ&n@?gsr!FuBzI5a3EL!!51w7lt9}qeKJ-Q*Xvr;FGE?By>&~p(&yds)(6AC!H;W^+1v|@Tz4Ev^4OH4&ABlzT}a%RvX0xk>w2PtQyC!{%OVkidsWpHnU^Pmr@lvn9cl(j$d}rk)kIdxmd#T2wl-mbltG0I>$s93#9`HkQpa>tQp5Lb@w=R9{?^DGPM2(Xg9(bT4ye0D>q|seB}%6J*k#sa=J4zZb#Vb zwhD3I05>|ak@kw;#Rp;m7S{SB{GWbp;E#moYL);{q%lHw$N>JYUZ~`8)5D(eT&itHt zTpB208Wm8nnt9TQ28HwIuCnRS4%9=S1ld>O*++D^42~eAQE`e= zR>jA!f1}0klq?jY7qM`nLV|8n<)!HWh%}%76d8o(x4k5ue5GAZ~5|R0r5oBHSnY1!&a>}wpScO6QBQfx2&U@NAq08L9nkxKY z!70F0sF=1Xi)a?9W6TIJM^bj<@c5F%#72(hF3IOz&*EgxqTFM2XRP5B^r4SmgdU(H z%a;ukYTqP}S+Qq_u3dO6ynKzb9DCaGHXdldw{6P)j(Gj4E-^xWJ?9)ldORswr$bpX zQ=(}fkfqkE3)~l?y!`&pU7Uo|G?ZYoPyMWeSgL1~o7y^eclvcfrLgoiV}2~pJ{a_Uuj&uE0tjk)};^FkCm z<|plt!QQ&?<-lROpQZDb758Z`vYRlLdv$^^G7DnZ)h5lDQ7(^wp=+x6o`mL!vyV@A zd*IQ5=l4E|gyRrgbmiB+`j9lAhJM!5Vg=pdTaGSW3^v$Tl-hISI~WVk@FS`_Z(6&( z46nU3pXRwz4;PV!X_swRyJ<%!SGje^Z^%s+?E`NkR>}%Y2Rtg0eHSW`LL$4!pQuhY zc=Hu+!h@`F%owIQuU8`SxPRDc$-YlDLf7`S-SxherD0(#9W(~RDV-L1HZ4_lX;0U~ z6$Yic$I)(LIR_nLzw*8lSTRcd{#XM~k(ALWSXgOIU#o9DNA6P$F5$EUyTicy_6+SbHjAB;9_6?U5XMf z^u8Ry)5KThJLfvr!n;=|x|KYMHuO;xg0T9UG6iz!PT{_(r_j5)1;V<+8op`U(_ z4>H#BNUUtaolf?N5h9pnscoF%YcAP@m9J*K+l#(it6G-PUsKinh>~_%s;WWzo6o9v z5)flJwWeKk?ixu|IZ4#r@aspx=o-ij9Joo`mCc?+3P-KgaiDH$I*r-JtVvDjJ1&Z0 z$+q4P*;Poq4JsO};o)5w%xk&|(LZ&}(yTh7-FcUiqO&}3!!BZk7c4ZIU;VvJ7THvY zQm>1ig%ZwdAkfU4r|nCsv$|)K|0uK`L_HZ;a2BmK)O3=48wz1B;bLyHnD_mdKwZxK z$%>zoa{jMYGsP~l6n@;Cv8V8|Me8ayrvV8t->l5XuzH=<8V&w|&r2P7yrTR-L7VLTEL%<3PSc1x>SqbTE?#_ z+iSRc9E~vHyz)<7#`zz{D3Zb}1@{=29t>|MJT%C*Tqr^sTKRhOcGP<>Z{Z zfqso^O|M1Rnd z3o6m+PT$UX6HyhXuONv{#T?s}?H38so9 z2g-)Q{gip&!jH2cr>dt~+XG&<4aA6SPBZUPnAov~s1WjQnhcB5w=O zHnm;wjf?{DkkAaZ@ji^UlBUg543n{$nw}DL&)zh2W#rVpq74E!R(@ZH(gSEwSF?&5 z;DJ-v5J)*TQlk#46&I{p@`&Sd=7e|yYhj-B@V*kQ!L0o1{Wx7??a78W8NYu`KuwDs zHwB7vMAt}rEaf(v;YU{VZ6~{0Cvz%UU2cHUUzdap_R^!q;Ll#4We$at*g*CVdlwll za7!ZfWrN=yFn?a?^d^C_pM{u2e+J00fTSH!lQ~S98H*}%%nj5M&gD$M{e%tRF!cSh z+hF3zGigA6>a2IB@im8ZL4@PkHPp+$RNNPhT3BrQa=iy4Ei7KRf)i6#f*gVFT?&geO8>2c-d*Pn&4@PdPuiyKs2r8==%3mGZdZ=ABrsm~q7e2wwO<%68#^uz> ziZel9!J^?RpU8e?Ls)`OuGVy9MNW2&wT_nMeR@n7n_IH3(Xy;-NUKK82`}sHgr9nT zk3V7}Tpr2p(kyPEkGRkYv+k3+{bOS(AI|wzEM%lPBn;qEy`)8bfehI+3L%qvEF++3 z^O%m@)OlZm186fJ^-oq&(-$rE^kx=Izh9?ig^qe00`2vzN;7DLphj&TwWd!5{GD|~xnLWodQmBxN;u{uyO%=<aHGw;A|9Zg=o*Z3hU`^MlD2GI!8dj92(L2(J$yP?9}^Gr!Hd zlpG~>X5qLtkEa_M$MOSB>e`JeFGRomnlO)7U8W{w|=$qRE(3W zL?C|9iYyc+w=`F^b5C;%oOV==1ZFUBS)acweke4WPiUen7i=Sre0F!TmGO%dl_!r+ zEYv$p5bi>}Imhpa_3Je#CnzubL-|vAMUIw)?$AGAh;f2Byjr@I*GiKO5NOJEn|N>y zyko#!D|+=9jt>M8l+F4FxLS#D&a%G-OoO!Rm1u|2k%b$K{JXT$n5b~TQ2d(`UJs7< zU?+=roMQX>sWK|@<5hcqT+I&3?PUKz71c62_4S-hTGy{=o&9gC(uBcVPi8b)kG1_@ zM|eF19N>etfg5BYNZ+qMl~)%1uEam6fYLKj6A!;5W{ZgHcCoJC#2Qb>Y7?gj%NEhd zc;O@4&)^?W92Kfd<#U7^W*kYzjHFDJzO-NOo;X@cer7r^pF+j5s{XbF#aAmKxAn3G0=^p@_xDv3i|-MB`+R({gE= zoA7qrq^}S=h?l{F`uIy}O#)=ff>zIC9vOHV>h$R6DJ3uRzW#dy;>k0Ku0YUX9a;eR@TVt4$Z&(z97tTn z#P&ElRo1r2W*{ezuhVm|-~pV)UFpWyjK|{szAy12yGV0+O+$y^4XjWaYZutkntxQK z0+3lhH zUm>R^f_0pWK+WORE1om$)luKRVK#@MKn`74^Z8tH&H>rBJALFFj z5WEpH<-38eB7o>69dL;6b&H*nO*qif+Pz$PlI~l)RC{wAD(4*yF4NN1%&11ay{~-$ zEgg8RV1JQ5<%#x7D?OkEqIw0zcE^5U?+b}vrdqw3n%2G>ydUml3A*Dj?bN%lI~fy= z+oH$luvkyFB}GZM9r+Oj4nY6fP`(v<5>F2F&IUA(F2kUJ=3@Kt5zc7kIsFFOQ^L>l z42sxsO?poRw4T&c5qi?o~1^ zJE~{0Ml9Q8=c+p1#+Z3%gJ0hzHsG$y20-t(`2-NLlM)zdIJY}r?M!K8{to|(4dV^0 zpKjKEN<-O;^41P{Xj(EJGvhcN^3P@qFOJOQYo=LRhN5hMo@lNMcu^jt4JT6Z8Wxpk z-N=RB@39P2VF+q3nah+K19#>|_GISZ8L~Y*sg$k53%0_`#(U3uXf3NI8l}blRoyFg z=J)a8b=9p)kW4cuchr49GYj4Ubzt~0f>CgqADW%X&}hL9)4JGx7IK=r4f^OXAIkuDDfW2lVhG3lIobX|hwk&cpfoN41hg3S(VTopzHvqny9Ao*kp{j7z!f$<*c^Y3mGo)x^KTf^7fNW{;x2{rjAoI%3YDKK5CJt;;WegGKK&8{~Z>VzL-_{B;)nux5DKv zzRj)vjn@pZ6qZo$;;O)J5UBP7e-d#x=*aTm;kzM{dt+Yo{m=~uqWbaIt(Ej@oo;IT zPGhQj?GGJwK^<&qzB}2Z2>Fe3ryy5GEQW{H!22!rtuxk5nyUp&faC}K6JzWGhW+;4 zW|o%X%)2W1a{xN_>Xpz#nYNketp+IVa{jC5h)t+{N#qcDPY{rWzu;*uaxwvL{I3tx ztGukie@zfSUhsg}qQQR(ch|4KZEaBa2={a1{b+Q{osIS8`2c>aPdSIq==3H53-Hrh z_v!J0Y$rV`7Y0BvHOeGeFXnM2u2*4lc73KVr2fjnc%;A~fz@u`F?jSsJ-JIWr;g&&N z>zUEig!E|wVcOGJ^sy12oBj6YHPU@Tpvm9s=zK!vUn)srUL~d?thBYvb5DSxo^98h zvfV2>^PvG<6RaC8GEol-{I*pSP6N`@NT~dO`-8;|_(7(LvVt|Ml2W5~0wwjj2DHPV zu#SrR9WbK~e_d_Z%9j}!KH7@4bYD9U%kui%75Ri8{30AcT%?p<#n~DOfb!Fp_K|Q3 z`murrtWtIld|8Y8(y2@Mh5p3s%sfi1?9SWkG5wgry&mm2cc zygv>lcPAw>u;Dv5IpVgvs;MoZAjD0+b5clhra}{KbO!KDhEle3W-q6ClNKA6S-+=}& z`0Wt&GQULf0ST-8=J|E&@0lz&BCkye-OMQW^Bpfps`{7T$CXum3TZ-^saaOSlX|zB z96IFhWU(-^0(X{jNx>>vC$5#IJA*wy51?7*aEx#VDtIsWa9kc45zO zFLtIe_P}-GYdIpz-mP%?SF2?TgK|ea1mKk%lI@k(=s<=Osm{M%P+XbJCFnw}rUYtQ zlQ(V&-N-A9b>W!az1w;o0=1SRx9#3>yG`Tl`VHS$3}axAvA%vb&``(QEOwHI{c*PE zNPK}_Yy9*|*4x7S^e^z#OF4_v{=43_SAnp=YGPCFulUqq+_}r{>AHKHS{wvJ?l}I? zE7X&7PaY<_>MJI0?1pe#J|q!s|3@A;%7?+#odam~LzjO)*P|tF-c4@@GvR!Jh=|cs zwTxWvpg{(IRzmq5UC;E+M34z*9h_ zR>VZdiaVbOrsne(ZLNp%ML1qR0pM`_r5CR5gm!Nw^-G~|p~j}^4%rgGip&eTlSI4k z^_>7=EIIn555JR<02e4;rlDRE+ld@a>`3J9?~NgfzJ#1;csxeYy``+N@B-Us>-xv_ z`0ySo1K~eX`5JPzIAtU*iR^0K_A%cpMw^qy+fey}966S9@0y5`Jzyc36txkSp}zk3 ze&e?b`d!JO-pxYZ(Bq8Z=?mO5X-K|U;|2(jW*&UaCHC2uA>tsTj<#e~kH0Pi$-W65 zW14RsTi^dms-n=4@QN2lzM&ywpu`+>S@-Q7oy0`(Y}42@ybDy&9Xu1^Z3qvmb$*t$ z;KpuaUrpr)o^WE-l>GV|Z|;a_nRn>RWeko`!+hI^iE#YHu9reQhiPm7nHaIq7taA$ zRQ7k6vV{-uOZc8`bOpFhigL#q&&(D%6iwNje(FlOhQN)1SGI@R*OuSfVQx;Z%q(x| zYZ+iA?|8hP;wK?}Z_h^1Q!yFLzMI5r&{3*;V|2=qxLR*sR!xN8*q(CF;5aU(YFrn^ zZY|=z@_WTdfR(VHHiisyvM)if5hlD1ZIRTD&IHjg_^wXMjVr~Q;92F+)*bcM92@&S z)NCCcnnkHhSW57V*2JDHZL2J+=?+l=H?zbiHVW`wHOEWXdJ1zP4ftzs**}NcR%xdo zg4fWLOT820IU2#(c2~!m31!0j?$b3-XAEHf?rWH!)Jt3H){01=A_*|TBLkxHXY+b z+YY(x7xd}|Q`q@b{K<8XI*~L%Y&E8pm*dp_l6zvRt$k2i?EoY+*>%k&?6=3XC(rCd=~ z2xjXwuK`6NQ~iJHRvTqQfHWn66da3t9fZ6Nq82x^X8_};o7R%ih}@uOb*65$6EAw` zbzInAs$m{l&<~jlBVZAfrov_Qc_FGg!eavo5-tWz*#&Kk4Za7K4)i(!NFh7S;g55d z0NR9C+q2Zs*6}zUT!E!_g)Kx#?XPW{!qiJ!!s!amk=n-d&;T$UtY7$DuyN|q?A&)% zF^$oOTsR>yDIgUJyp%`e_$0kHum~4_7xr?nN@^L(#y3V6eUMw{+wY^y@R~u_rmz%O zqGp}Sb;P(GGS7tUZ)L=(S}lmnrXx$ZV29)_`<8R#vsw+??kJYUH(Jz#L#Xx5U7PG} zwY?Vc&1z6TBiNIQW%LXG{w=mL@d?UfnQ`vSn|K6BGb@<(-P02z&?tA21lO7+I^E++%SBmm2|%qDjN9B3Yz)O))BpdN!q!q2p^^ALIt(rlXubC+T2UlkBnL zJ7;Z#Bs7yzo4X~2`ajB%RyDh(rQwzE1MVA=HVu|+45kR;z8Gl#lNQSVo z!5c(-4oPfdzoJbOC>wAD3Vd>n_3i(%QO_<~Soy8NbUsUx^iJAGiua;3Om;u;B3wwF z)uuk!>?iU~7q9jx57{prHsDKme3BcdF0&aDG!-rqf~-~-f(>`9o`MM*`pPee4JoyW3?mYQ_npt|);l;dc_WRyK z?35AJ1;IL%I)S;EYiSo+Q`VI?c%04CA9(9;4@EIzR}jZpK(*w?c43;czcQaY+*z`H ze|&Jhb9R-5e;0ozGb!8 zJMUwvbj0Fiz|3fPU8?(P;jJ#3?3Hf+<6XLkX+;3+(!b2(69Ct+$|8oq?ym?XeZmuE z`B!dq(Vp>f>> z*whSF{N!DAnoCUo*qeO%`AnpS0BHNLnwa;S^XE<_dfLYwlZAeVpKQqA#}N&eH1F^1 zPC`)l-ZhRa!;sWWA;-tdQ7+88VTswFGYXW)?a;oK4Unwl*zoeMP z58`*u<_=3?8*r=eORGge?ENFb)7OZ>$7Rm(sm?^ui}^g8;*tXx6!w>&@NGqFkW_HwLs6=ei4tQoPQL zM&ew`KJ%YJ88XSwuHRT}!I2BVQr13)tJyjINwa$X;TuxlJRZHWpg`l`m7D)PR7_jwzl|Xmj?S z+cs!~u4+xKF!E}~YDAaNkAfGH&R#Rpw*#j~%L{SorCHQ7)+=D%WZ;F^R8IOso|Q>H`&G{ew1DCqRq%cbrG%5g0#(0qMjkR(4<9`Pw^$m_gBNM0 zL%!;9#j}7zUbLlve;;;W&RQ6ndC|wOeqf7=f#!o-z`Z1devIy8vYRSfssTN-{2!ss zWy0LbS1dwe+6=P%K}Rc6Mk!56p3MgJ_K z--_}^8J;-;z-bk)8W3dve{q<-)m)x7VudaM;t%a-zp6za>F9z#5nZr{Fw6^Y`iAW; znJ8^_c|0FHT5T8=tTUDZ<-U6g^?m*Fgxq`bMn@aJdZi_)Q=5f;>fnmb zMk*&?I;d-*6Lw^3J#gY$62soqdjgh2(A zck(l#J@>AphatPKavgQMU*O#rGo0E#z|>UV6n(3xmm1d<)1sbzm?sE9CE&<;|K7IN-rjscNR-mS@|6ptUuR|*G+ijcag5;%!XvDB?O_$2)w^cvc zx=Lw8_1<++P}tH{&o46Myf-KV>E`kL`OlWwob;!`Khp8v1VCAj*^{%ra3RXcab=gc zcBl69oS9(dR;`p~<|oStaO+Qg0RO-!o07b}H*S+KJ z^W}IGe#F7*0rU?0yW;gi5ec{)s=GW5{n)UB5GGitvcbK@eF7X338@V+G>K?Q0e-bU zl~D}-_}VQk5e3yUpDo16%6~H=^#_Qc05Y{Q0J;KB%?UKP(^GlzTa{Q|6VvPkSkFiYCPwFxFd_bYaix;p=zz*kqgw`ZgS`pn0^gtYssT?dCDZq^Rn@tF7bfNV+W*f)A^bmO z&S=zD7x zQME%;wpnq9#xAH=$fS5o53YKNwF*54>f3S?J87I#9t0Q{-cs48YGw%+uAZyG4gfFq z@+|9(UWq2J0-F@DV|n7ygxg5xws$JUoFbAA2e_#)(gF+J>Ki^ z1jvdqK){Plz&8^;vE-qHe{<=kKT4}@tnB2aSU34czYcact7Pr zCidU~khkL&uJ{vzuY1rM{)BJ0U=GgCoAA(Ii+%{5B7Gsjl=SnZn z@QJ)bBsz7@OZjWzgW<}A4j0WBqVg=li&qKNp0S*&HBWy~blGEa<@|7ol@A zBUgv!V<$4ByCcSC!)p`H$svalHpJV6o*vsPvuGVn))xOuMFm6zHMRp^r7tDzng!O# z2xI#l1qTOnKz+$-jrGsCaZ>z4sX{l3ES9{ zQb1Mft>H9e1D@K;pi;+mRjex6PWsWz1{?SKEMMPGD9Yc+q|Y8JPsFNm#DbN-^IS$2 zO9wq9=o9`-#F7ZQ!Q`KwXR(;}QJNEB{+NM31PC`A$aF(Ohgx1K zR;Ze6ey`cpC~Ku`SFWKn56t4Uu$L=D&xDkDJ@sNkq=P;i2XZw(2miKY#^W1(Q@y;& zULK*g^qvBIsYgEhnF(Ig;WY`sO3A!}d7x&Za5`02keQSSB?t9IA^3`o!6dUB%l84a zt3no)SB*;}W@f+LWs3taJFrS9kPV&-KB7ft!wC;5qn4gd#Q#FRpPSDeAp27lm38nz zs66H9SYWrhHdwUs?K3EXt)!(`>G4rk4zs^0&}iE6(v zm{o9cS+!_znz(t-Ih*Do{X_O+`TICl5L54}=2V6Skgf>Wh0s%s%zJ^w`t`c*=+FoIr>8YN$bzVT zGUnrE_^%{8tK$fvwp)}xgEfxL!>%ZiU;ol|OxAs*icQh(-v(-p3Z5t6J#H}F4`GYC zWmf(`ODtinW8Khj<%xdIcb~u?K?^kT(VzBW7x)XF#|(qVTy(+kxJIN**8dq5UbFv) z{a=&vHBK7-IxN*gn@T#DK|T$b!SkNH*g2K+eCadxik0p%=M;Z|ZB{ky8>!FkHnBiy zvV+>aOO>b?Pa7ckP5LXUR$H9_pjReIMtmhs<~mDG`2?+}fj&urL+{>Cc%pDE2F(wb zlBut&dIt0cUVo}FC`2~N~$ic0c_s8AmC#m}y?`?Nb@-?cRO9KK= zb}YLkP1Enq`KDMnE8Fe*GoM+^c@En706_Koc=fSjlm};&inNxNlU1lW>=^-?%taEP zyr{oAp+fQfIymvsdh+m9+TEJj<%pji&i(C*@tlhe!1AFxe<8tT)(H{jIBkQ z=i1BlEq($MT`=hHiUcQS_$Ieta+fCtzFFm9S;`1J8;xD@SoQ?_n-FfiV3qTY-WID6 zfRt8NVEyOB-=`U0U-p!)In4UAMUCq2*pLR8YmQ7IdfnKx_bw072)+^aga|Tfvhv( zrmDB4bkhj6wi%YN^igm4o|oVN>ZwtgQ8j)*wgyxs%CJCQ4CG>V`*aS;ZHXPWkKXof# zbQtt7IU_$xhwZ8O9S{^L0Yq?XP)6dpbR&o9s<5fq|#Y^z?T_ng~Np6Hh?dk5B zp)D}Kz&=wFPX8~<%Pcxs^>Y_kcqw|)=_MCz#XL-l7FYcF=&5uR`86*#TtKuW>OU5M z@+O8epMde}b8eHwzc<1fFd|do;q3pmLN?uF#VnvZjl2Q=XSOc%_XP>_528*EO1OhcrkQ<*< zuNUn8caU+~X>C(o@AmuqA8@d8<@-&nb&0+xLS(u23{*&#lQvoZoSq0E{OfNmoVb>{ z6g~kFeVM`g_$uPo)qxHp%)wWAg(m6aI<{T{F$I17=N>OxjP;I#iTl0I#wAXsplPJ( zUa0jT0})xz36&rlqI+}xFQiT5P<}soSju;gF}wi2NPWj?@Mg7c4G1hGvTaw=gr=|5 zYI@nas)ucHp}v()wiEc@2h>uH{JsWbWnO*+ADFHdD!=4>PcB5jesU696OA}iMySdG z2Ywm@EnWJzJ~*IByXXk6R2<3*5t3{-I1lJr$N{7Ro{NhQLxi=NN59&zI~ox!dOptL z#8>xi`EvUvfZzvPo4tOsKfJ}npX@1GjGlRSLyEWp1At@a_cZ%TKuEoU&^lgs&N7M3 zN9hcipm=}H-CaFp+=vwMiTNB~j%MhA_CDnhu}vIjw1d_=QLF|oHv&g{kFBGQaugCp zDr1=+9`zTW=w|J*p?4J&`Y?bylMOn*RNcx)SygATmEWZ14UAP1A?1wjJ5yqi@G;d} zc$Y(wa?)~&qE3Nd4>sV|Fo~6tOFbro$k9a9w@;Hyuq4yD+s|_>wN1=B!|~p=3JTQv zsIHxn@4$+hS{UgidHUv@)xbLXCR|eqBJ_#=F(j4%6a`nXA@GUr+mW9%^0i8N8+rqQ zS<{8?1zSTgOfFBV&ZNJP00S{|ceN6qFZa!K(e|~mN3p{{lXo2m?WN~X#6Rax_v9?T z3n%a4tRl(~5TUDD{NVn5jZX|bwvQcrhbPsQ0k7pwuh{|1J)ZzG8E7vnBzWXue9(`Y zceBo7Lkp3LEO&8gH}VPkV(P$k7y>%4`FJ733yOn8h*BfFEj8)L_(aYu>SJvzw7Lnv;-Jdbl#jkd#OEkJ-s0w5?6mX-cu5cT=z-qse#7{=^Fq0= z1c7Nc#c4ls6$^ggHJg(&v+D1BLNYBk>g=pfikzZt3;)0py(LJ9;qzwP7T=h39dbbV zGuN8cyb-ET2 z)?N>-WJNC+&A4=V1Ar!(hYccFZEjy z`FD{!9uxorVTzAbqxCHH3~$C6*6?uC)hg*P$f|#w-Z}7l@nYsd)6e~b{MEB>qrara z!>+e~Ecs$*0(P?(Pf->>MdSdXM$bCT)6cSNR>=Db3NH-1TQs zqDXdoPGZ&EaH53vunPQ=)Ub+#F#Wg@E<_n(pZ!2ss#leX^K$Jt^xK-927T1AH#cc2 z*^c2Ju>?}#N*=b?QY028>n?fb~4BmZXg^odRPZhaz(}{8( z&1QB?s*S>Sufmag(4fidqc@LwzsXr#@$&utAMgM+R)0SHuf;kN6_!@!UeJe9xZ7N* zbA_?6x z|D;Udr|QhTtu)#1&DLuMuvRqWQ=bd#3-u?V@@U`EKj6Y2DHI%+)tVCSM@?m-$$xLd#1A+9V;?GSm9qo_d3r4j8zo(&|R_pSmH9< zfJoHya$7$tak_12SDye7QqEFXW$!8s*c=q1g0RI*DI0k#70NkT_YngP3YOXht{K&$&^AD_2H4nFF-_ik?J*ah)w-^m#?pGTjh`i~-(uvKy1}VL3 zw)6d!GYrK`7t$j$2?$gX-)rXw%tc`qM-R}2!<~g}m+RMAnT4kMkzQq~W1xGm5T~hO z47U!d);m{*;bGRD37j}E@P@gp*i7c*2fcnDdDIrv;-&R)(dCjG`$WeRk?o|KKFIh~ zz*{NMjHqjY-|}S6Nj4&ls{X_0Y>!*PZ7URr_|Fv@gA~(n*Un5Ox<&h@G5lZwKUFbT z!et|A@r@xiJm3SX)f585DQg)bd!hk*jr+n+T_{hxd6PjrrQi?!!q>RT2j|v5d5XD) zllY>)Y+Jf5lXP=bdp2M!{eqS`YKQc+*Wdxvzh$$8o=^mV^C3m%Jj8?6vot)pYNaS||tH`|<+tZiF&wmm9vl<;W~X1i6{2^);0u z7*V=1DQmq`_=rPS;syr(Vm*fdfVaHlvfL}9BS#pkKGcqpMtzS3j=_~`i2jZG6N`J{RqHJ6VR0Jb~}PYW*?;g9lXn(`ck zcDeSU%;u8E)TL^b&;P`MEB5HIfRI2{yUC#)y2+W6scGnW3OqS&d@g`#QJ}slpM?bN zxQxVr(@$^3bMC0KU^iK`jw|=gXmTcfcc|!H(rL~8-3=ku5oID#{FAw7#nU7AQg{7^ zTZbQzKY*b!u-e!Z2YkerO)F``0_Yz;-^-6O*o~sxm5R$ba`5>{)Vh9&xoZY^JJ~hN z8LwW4yjyyKr<)KmRPVBSdmX-?8r+imXFu)PJAd`D&?tZPo^aZXrN`FL-(l+m9O*a> z33Q9{`L$3yyO48PLZ=>C*AUE8pG?tdoiP4B(|GN{4dvpQoU>q^x6pCC1N^_V7Oqwz zqQpzO*JTBayL+D@enV1p8I}QCtlbP|O?@{3aoTt@V8W_kn#Y`XTa#W31(BLY8Z-S= z8YyKAnnH2`g3f>0q@9;uVw4n7Eo*uNyztWceUgiGrF*@z_y63oLGRWV@S% zs=QRR%T)t$B|RR~TfeRMA?~H|jC#oi_IqOw1KArn@;Z&@v@Q2EeT?rd5+?y%MqFLDz2EsZPWW8z zg~a>~o5uau@KpM*;o0eaAzk0_;9DkWdC==;gh@^=+>lUnZ^+zvWG&b0X718HI8r*v z%IV`;en<1q;7$#(p>`q&3%~rtHHwo0e4gD)z6rcDeqWbQd2W~{Z7P$xBrRhwRrQOo z$W$l(bi$0EDMX#mvvAj9G<9o-kb%MnYj%4)sZjHMjKH_x>=dIKWCGo zvBc&A^vl5=%(Ib0ssQ{ zwroi-{vmHGV!sepYn~UvwDDZez|-3@8oGTCziX<6=@^1R_?M*nS`|CuiA!2Y_94H( zKKSkPP0~BOu<8dyZLC6!aObzg3^L7A#`1W6-^c2Hu4uvvaE8M(zw;;3oN}Q{{>Z(t zK$9!|H9j~CP@oAlw_1A;Bz0>%wl+S#!LmGnUfqYq;e&x{W}x}W>rkMJ8_acXR*O)o z*>AvItX7i&siLr{O)&|gF1;|ID;WD%ly|6}V~&V&xU|>Z(N#TVEa+0opadW`i-9F^ zJCSu8aIg#CZG%X)in(Od#ALqjh^wUp#H`c>#th%(ti#0sbBtoZ;U{h&W+%o6K-3X^ z$+&N6#_T}ZEeZ&y$+j*oEZ_MU&z*bv_ol(JHAg(i@ZYx)6UFQ~0=*|H(vRayIai4= zfMd`yrPe|USp5WtIfcPXGo#{QKvXD$SP7JP;U$t|16}}z0w`32q=pN3=%MrOYyeMl z-Fdq_XJ)eS?6IKC=C|fW(j3db(sMM z03$)rl4CX6$6TdD6ri%8BzUPPX&~!XL1E@JC`;2#-nAe;(pTVbJx)ZJ$$S*tQJ2%J z6<3=Tf8OpHUwfy*6n_sF9PpOSQf}w;E8ld>jJ0s?VX&0FOA**4fEhdhve~$cBTMhY zTM)uk>#p6(_XRiVUJkfMV38p<(Q`Rkwsn=e`l)m`bY3!*JxFdhyH%W1`j;c#!4f|K zJs~1EKCaAVPF|XxKP40Vj3g=B^6WU1qF!RxL(QHQBB$zK3U;L(21Av3<~DtMWdLXt z*)Vw9+KEtGAga&B_X7t>pD;S6bGF1oU*E_n9*+*`}yw%0iya7Gaoi$L$%J; z<03;>OP=i+0;qk7jhKXn{aea$(yc*vi$%M2VVywRid0pl0wv2a3lk*Uc5vdz#SG{% zV;t%!my@HoKp{&B(6ti+c1`|jf`0k=z!l%QlxWdqFp~jIV|ozId9}>63Uiju#15je zetjA5_fK;RsU;`^(=p5IZ4!U$bnD7iK3?9pDZt3qRSQx&;k}BOI~i;@lR^^d-T zvAE%E9x22VG?Y=d{4QzEAMLlKT{Lh$(jFL|sl8Pvr!23Abm<$}-0aBih(?C`_Iw)G z{U-A!TIZ3ky2~a#4lE(l`}d2=mYBqC`{WNx@aKR%1~%X**Ht6r3-s32eyMP_B25_4 zc$(q0N2)lNYW_G5m>`iOBp$qqp#i!&79d^PhN$U_Hl$X!N;mJQ+$3tp9yW>k5nSgK z(N6H6T3|KiKlUm;F;o?qx{iEIVapG2nX?>MHC;U(_zO-ULDelz>WFdf?h1wUWPiNc=h;DLT{kA+Qqp?LH0#~a zBPzt@Tk)(IxjVa~Wf7YUL_nVhEn-15AgSo!!naSpRy>KbDstV9;+O^$47|6-Qyf2b z_1ekzNujZj1{T<8oN_31|Hgq5l0HN6=s{O@lXM#Ndvam}^8P+v<|*NI+ismtvYBm& zRtNVi=d3@kAHVLNit_d7_2d3P-^Gtsur{ZLV&Fz4{%X7WBD5EJ*eyJ@@+^oSiTr{L z@G2sN?Ze&=_%mwo8?Nn5MC(+H6x7u;YJFSEiIgTFYJA>K+(ofZle~2bOpN!@Vz`}} zg4ldkvqMO93+*FOy16$LySUGk!vp-q z57}|STn3tL;c~;Dm0@?CAN*`IJ$!!@QHPD)(fVuYG>3gQyL zQgu!i3Nwq_XEeOlP==BZMTqtTB5lGXNc3<3x$GkJMD$%;F8lGqSc=LRo_7FyHH|5R z>@L0dh~*Dx&qudkwS3WfWGY|2VyVo{6iESP>n66I8$B8LWJ#DF>z{WV*$mpp0;qfw zN(-%D@k_NLG75W7R2PP4Ci&EyC$oN=RWYb6sB0v-N)aJwwjHFIKY`i7y za&uZuivy@iS6#?4hPPQWZQcXMa>x35b{GlTYA2@T-prXO5!l)`+ku&=}1BZsbw#vlEnh&jz6hh&csC)%*Q za7U{`=SL>9htFV0%nsMqr#aHXz1xm6wX(xh`5!GOOAEM$rMt9?d88LXe&8ivp4Qj{ zYf4q=(MQMJF3CRBh#r_cd|9Kr(EZ7xY_+t&15%A+a7=a?;}9uuZB*T`Y5q=5>Jnob zbg^Nz^72Mpj&UmqQ2kAQLQkez%Y>}Uc3HLO*Z>q}l0!)OTV|AyLogpX@U!JG*olSWuCWl)gH!&r+?x7^@1}*gpyswV zgG25?wz02|{S^jEDJA-iD+(%v^H=4u0Qau=@N*)^$>I8$gaJCu@3wOVchDeLwmD+- zNsOtH-Y+^KRl`9HQ4j&T0p9!X!zgGA`4?$r-L0O|7tfu}7WiD=@;4NE#mX%z5t8qR zY#Bk?EbqR5+i|j#r$52(5amm^2tp`91p6#Mj+YE33OC0c29qK$=Iz}xEcgE~ZtD8@ zE11<#VJVzfiG&2XBxmf*t$6F{>MO`br8qsTdca=YU~}8Uzzth&N&|uV*8J0df+dcc z16t+30}iuhKawPDuO6VtnW*WYNVtE8$)WPP^U>a)g5N=3;;|3xer_Gv{7-RmX6W{D z{KQA~-g(Sk?Alx#J(tQw(deP|_FPbqo(gGiXWHm*LAKkY^7`c^f8r3CkG1OC=OLfu zRNXu||C!kOL-jtn7xk%{Ctl7Q{+HWTNdB*IzTmI}$De=NZmDb4Fx`pm8=J(JfRewR zq{UL|5=zgMJP(UANv`YlDXNxTw8^%8sIB;w}ow>ttJJVozVdJ9ycD1miy4EAMXqtHp~l6qzG! z--`A_z-NhdjineFGl$K29Ou5}MbF4r8(n$Pr^V&6Lxo#e`mLXiZt_Z+`_vu}NL zjz*m(X=?Glr{hh2<6E(4QgF&c>;;3m&8W|`K$LO(s`lCGk?6hlr{|T=%={DIsHbs= zz?#_%0ImD>s>?-Tv2d1#JOkGoZs?{bXxo;36@etumsdq4|Y8@6K3SDm?_!hrN z^-Q*VX2C-u$4BOdO#|j1HQy<>z`RKTXjWL* z4E~(>Vrm3UekMi^Fx0WvdlvFY#HVn7-fyT>JCvUH`LGtExgxNk<5S}u=*d23&&Z~S zqpIT@wiRw^%N?76R7r|AWR$WyrT$RP63M*8uTp>OVR=F=en&&9H7jGNSJZ~5x=zbr z)-3%DE-1#ML^1c1C!(|BMrf))qt)WM$-byQ~_XF(RRZnR1 z)|;`J;#!N8+t2SJkh4_?M0_hmCFphO7euv{Z$s2HtmH` z&mXXuZVRoinE=^2Lwy|^^mw=I#hq(bv3^;OkT<36G>&7BVB*pwqc;|2Xrogyb|iEt z;l*OJB)9C9yOb4W4N^zkZio_-1&4id+?w9j1P55GHro5*6qDwDFO27eQcvI1&9@^3aF7p5k#2d*_d%zOk1n*ubH9C*g9J?-+Ah$(M|BJ`xl8UJ!Ad@}x2y>r;cq zE;kIe0QCI#&Cd5>IA~S{mi26U!h;Q=9C0?%+%0d);qIH~Peg9UzfOj2yfN1I85xP> zVAMfz(6l+egbg9pYdb%}LX6ib7Zm9Ue z6S0htEL@o*ZOygt6yx9Ra2bH4gx<`Jy_A~Hqhlz)fRL!sAt%c;|rTm^8wY+Q=aSEe{Tl*j>q|os#G}7k|i1Yrb{(DTJ9+)>VjMHCXWkEizH&9Ob67ai!}dNiBfIL>u^p7dKm zN=D>0;G<@&}c(hC^c|S%Dl|?WOHMJO0@rc^! zNRxLch5!l%dqL>&hJ#jcCiD{b%b`vEP&|d#on6L3i=|y>>}!JR*KKWON7T3eGfnrDLbGQ6o)l1WOz!G-9*RSLe zF+A6XWK14}euDJaH{nWgl{d1%t1K7Lyd4-I!cdn|(@+Nmnw^QLJsvz9-L8x*G7G@b z!jn{XV$De9c7&QusU2G9#0xENfW`7*TKRWMhS8@bjr`QwG(rQ)?IBP zqEnpMWt}8tPE^+kaLbVd!EGw9e8}IGy_;iBUmm|;uYdNNbvE3zKL&-|&$c+zHoe^p z&J1ssaWr`5`_<=F%)dfCna<@?C2b)s_?XYNY2*^?8EZ~kTUwuy^YBY?6}3msu4;U4 zMl!0+NX&F@&RKnIW+^}H?q{V3_g!CT^=m8B3!t(h3t?krg-WTs`VYP6gGprIgEzWZ z`yy~Bzeo3mB4k_H6{B%#yc%iGgYu^r8?+KSUY@xr@U2^RmmSg3YRa9nJ3r>!S! znSSsadkLq)xmmwGR9n#dCw3!K?Bpb3UiIm2iAjp#KUGe$Ig@Yo&C5(fX=)?o&2M%m zn+DDxgW~qx{CL#A9=;R;9@n3~Zl6qvOp_y<^S=@YaboA4Ac^)i(dA9rf!efYgG2P< z05l!~a2+>a6U=&lNZ<~ne7k9#8(rscF{Ag$+vYzOpjjhM@EZSt$LeDBGqf%U|G2E zUQ^EVyXhrHKVI*Wl8cMgB?6+Yu?w@hVl}x=6-te&5+{a!jn8Xojm4jqwY}43lt)vZ zbLL`N2Fg|@%eiCuViw>fuw5L1N4#k${fzwDnGKCnc- znTzvrMOWcmwt&_yIl? zS5#(gl=6{p?Cio8`V7!>J6|zs3yNa5~I?p0CC+&JqN|8Ze0g z$wUXAcZ+rMA4wvRO#s)&;3kcpXEj~e<$tITDg*ISogq)k4IGaLm->qkgy(<$7S#G@ zor5-{5?AMal59Hq=(b7v+nvw+LF0g)U3N1R@g zRJITQeWf+0D6s}E`~7-GzV`P@TIaE5hmR+@N}$Smjk$tNo73i~fTwhkfBa*89 z67*!K`IGB|r)qXgu#cgyJen$7AG#4XOnE56xO=eB{(6dri$@ zFP+LkactJ;Rk|7=R5>bxj9%!vlB+jyCPKpY8V`^d0NvpAPg%?r2bp(RzM+_flc@3D z#d$as@IuuycyCm1w7n70=xD3h-&-&~$=>DJ2h=mv&w()W&J;Ov_BWV$We%;WW5EN%gmA$a`Z7-IrWK+Z3l z%PNBhZkhDDBCy2geom}PM4$DsnxUJV0#2&y>fcMltQ)?XC(*xF&GAod{9oY5dF=(! zldb=ixit~Sg}vCo+$5#i&YQ^+Ef%ai5)5zNOZz{GAO})yK#XWuGzl`t8`4mE4?ilaBztH#%oX>?CMoU4w6Utv`?YcPA$U} zpHZ-XYMf-uK}eZIo5ndMA0b8t3u+6(^$I$LcyX&Hdk&z0<_(Vb-dNc{^-!mK_V-0t zbeunyT%G>Qb@{vr_;S(iR`6OL7xZI%Zp|)lm_GZE2?AEQSeU%pxi%9e0Pa%_Va=>< zeKTzzX@CE4jXGzeoo{L{bujJ=AnF% z8h!Tmk-PAhuVo|RKN}A;BcP@x6VkA$+SW#sZ5)VY+6`7l;Mv4-@cYi|;l6`z#9~t- zo5wZ1i;diZ)=ZF5+KYT#djqIs0!0L|C)f85rTgU5BCq-QK-2euMiYBohDK%Qt*ACs zOXvL!hAtyinBw8j?koBeVSgVD?>D$ba;l(ab#Fjxzx`_qFZsf|H)mX->~&+4SIPc` zmuBdn!dbqh{sRaqpv#iUB-10rXy6{0m<#GizzUqyM92@ce4|6BM(Y;T6*#;4? z#{jwY6tRs^;G*?nQ|)EF?5)#WhEUV<5lk>*m1N8tze^5_X7M@+#S)S&l+6dB*hDuV zOnNPA)ccF}dm?-WMm)iw8jqSa8FLr8>rt7db8xqftcd9e}juBYeeLD;hw047FF_o*;e6l zwcZ_{4aa{bjS;PrSK^RK6KJ$NSB{c1n@HuMuFuu~^&Z?VVY6&$LsH$3MEgFVlainu z?CE}XKp&kF-GSkzv@7q>I}Rh;u9#SfD85T7s1ZR8h})<6v*17VTowh(A+QqJQHWYL zIQuHCK!t)!Ow2#Dd51~2_)&`?`3uF^C3>_0zsINgGDzh8E@njloxyoew*L0*mNFLD z1dm-w0<=pVrk#4k-ks-`Bic){@-DI?0yTq*t6EPX%YMBJ2P4{ z>hI%B<>NCZyeLtsVWJmu#q@rzVz`abezoIDmG>+@Dm9m8&a&FZ`$5j*P=uXBL=bw8 zRn9et2YTYC#S&6gc9F3bM8V)^%brs6T+Ob)K%j68?J{34;VAKeQ6EFpH}SjGI5{YS z60ga8PQS?uvorAJXI;f2*K_kX%LJy~d5+6r{?cATi|+(}?cVU^x4rJptWXIHtS>ty zu)a)yFp4yL{yy80loOlNdFiePqK422+l+x2OGe0`0T((y(j;w&rZAgDjO-&5a5Ul? zJACgm5iXU-_W!Vx*RcQC$)}=m4-5k?T`B_}79A!?*!w~W3mAeMDuS>0FBEq>Kkt1Q zf^z?{#NJo1J{1c7l7o$-GH1nO2M~KpNWAmykv2=#K3-|y{0R{N9TXvvB0LJnRgeVN zNfr4h;UmJgzgXiQ0k@N~1|NJxw-Aay)@4Yc0;6b9MIs<3hgES>a*XxjHMpU{eEb9^ z(rQ-|c2CKHi0zcn?1mp_7ERnDKSF$X;gnDrU?rsXxYXI)z@5iIe%HXO#_ry9Sdt6Yg+eE%3Vn^}u~lv|7KPh)nu!U=`JcGP(+RbQ-Y=9t|barG?%dwWFUF z&PS=<-wmYu+Zti5JJ9#@F3pmO_Il^%OIdb&h*P%XdkJJnUoF2xWd zzb(60kwk!?gXNudQv6Phb8-9fpo0z}%97drPHP^!waDp#K7 zv?T32rMiRJgjM3(w2l=`roPMznf=v*`2rc`jB%H|zrWN_?ah|(KcI(BnCc=Gt>8Y` z7X(zVAi+QH9d8+Lb$aW!(SB#?v&)gm7H7}8JMU95)%PJ=cU>i(_Akj&F$QPOFU;t}nQUfau@e-}xvIa{j`9%S2=PCab{#BpxQOn5qeylm4)WZJKHLzcus}opb{tcU znf-3a;i}^eT%ynDX%(X}R-mb?2IYTFg1!S%y*5rC-}_c^<|J12+OyQowA4$kvFc?IGGUWCMx6=g zb;!0l?P>XEe+BCmoCi}0tcosoU@1N^sI=)^=kklU&)lz`kB;EIdDiGZi45VfZ?CxtVAV}YE)nS)K>nSSVk=knusEx-1j%r+$)&zAVZV=^D zhDe<1=zOZ>S3>Pmk8MR}6V^X8txPv6D@YHKz8e=ZkY-A%RLWjPUv&Si&~<%A-nJI^ z*Jls5H&0A2Ug8Z}(+Lakc0JW6L$uH3Tvmn8POmd7uN2R7ltT}-y06X7XJM5o&)y|4 zpuS~tz&4cQ3hW;$SdHbmW&5v4b%&Q=fN+Zxr9d$MMTluanJH6qT*~(yR8w?CMszkk zBmLDA6>2C3h>Sl>B)@hyb55)aH?S*ssz;`XOFN|M-e(3+>L=6~j|gb>nXIpZ*=0R3 zwz5k1U9>Mg11#L=T->3}_?#Z2#pET#2e=Uv|axG9+P=TyFKLr zLORK7@bKyQp2V)FO{Ojor3@~|%!#s<##Nm0#ekPc;(LmD2BOJOG{V#-v1@n+SGxc~TuGf(z zWC$DtOwwtJ0Y6+6EczGmb+T@Re_%wU+FSCiGYsorS&7ZK{L(=_3yEC$3_2n!i1I5l z@|(*XUZ0q}l?Vc*h~uL6T-C~lCidUyfi6ELN@HgZUDDb>Jy33?>~Ycd@H|rS_^FqX zyWpYYzDb%+cRu{ud6{0h7^>Az$$V_hWV=j+|Kc6)y3+KUe?e|t_$%Ca8r5chD6HeYZD?(o^_lJS4lG57pW=a3XJNVrVf zUnoU(+@=(vxmbjKZHXo~LZydImExPv#CO)wqV*J45({tm~% z=c`@Drt{Xl>TX$!T0+<&(99uaGZ?k5;2_fI8M-v?U}l;Y?Gh!FawHyc?N6VZ7yY;4 zb?4AmoxJ0rC(j5Z=}ld&z9r%-rYB^PWy%X*2BADECMpQ5N-zDGXcDg|u(|g(?)O<& z{!6?bKHTrT``ZEiqOj(~V0Rby2~Jvz@M+%|0$*@AJi7q7nOhaI_JekD?ZYirQ5PCw z00WCpE1Xd>Baq(DNvXAV;^`SaIg`)hny2iYl4+)agy2%0?x%1o8Nj;(7brl8k?$KD z{R&#nn!P@poA$U2Tn~4QXL_h8td0cfg_d26|HxXuqGWQqpR>Iass|vbHhBNZ&T~!A z1(d3eZzAKlD86=}Y^f*kj@UgFu)ust>#&vK#e1w~d#Ew%FOKxRQpZmwLDCQIOCkT? zogS0D*K+^&9C^RDWtaA$$g%6l{1@l@vKziUTMaZ~5Bf!m*w=kEnY2G08)GxAcg64) zo?aU736@x^NdxsaU=A&a2KDJut^>rqZ7qbPw14+78b_A|f<6jhRg~L%uBb_SL_smV9v!5fG7Yy}8 zhuz2PJjwtqI`7UpFG2yVi>%#lM1dB8%8?y+DBZ|{qT!t~Nts)91Vr8qxSyIVA2rvu z;N6f>yoWwt=UwSa z)$a5W{3b%acFKydWIt7Fm%AHh^6VVy#Ll@}sFllJXF?dHI%>_fvCB8k$OhdVc1`{E zN~JvyG68NdSRE$*aK}hs415DIyk6rq?3^yE0@pKGu_HRZmbqoNk7bhgKEIu=>Q7!r z=Y*oEe<&RP@Y%V96N)M*7~h8dj!%$~XW?w>Z9GwyvQ;#PG_X}b=woR$bixoCV1_K? zLYy!lo(mJ*8c*1@(t5D~)%|I+kOc+mqG%^3wWyIvb5SNUrU)tN zOO5@U75m+kuzpNG^1NB@s?A^h(YaAy2gr`p+7SZT-0NS=eqTxr{RphEAd)kdcM}1bpl54X*tTH3ADdcqNeDonOeWV$MB#&x? zQ8pQFmmPciDs{e(&Jy%vLl&(m)E*S1Xg`r_0KvU?aaIt^TfZg1cwhey$kWNIpS0)g z{wSoE;kHGscTe+Hn;#&eul3ZT;nlU)I@g5@_CAwOA$)qcAv@jS`?&*8x&+Tv$UatQ z#k`=2p0=wnD%89t3u_H8k<{;303SP!nywCL(6vz zLDY7{XQAx~Pd?}StXIVI5@U=XR)&G{8Ecca;j+LV77cf5o2P2rBeLopTk8N) zA)#!=jv(jGdNQr1CTS<%c1rDw$_CF@oF#+Am=c1^&;BfAf8yXS3QuaKUsPZ~w_+(C z-~Ks`eBos@_(b(K6S9liyD35BKFo`cXn&eSxrp>d5B~yRNCEWW787OVAxp?_QI;9e zXR}N?Pw7j3}%uI^wA7}cPx%~iK3Omd9nScJyWDgx-NoS?NnZv5L$3+q^F`FSJv>!Wi1ZP2zm1scs-way>G z!Zi*%r>_K0Ia!km8wqV1sr*T&$Mb%_pbU8firjwu)v7{OZ~S~IV~1tVvUD#Dem6ke ze>hUh8&~yfuLvnZ@?6ZD%m~|f{aRXaqfd`L;g4@N1d{&+B+;Q-OAE-@V59@@r5TU^ z{~v>Vfe%J&bgUUdwx6SA{+KbeI@gc_CqvfSiN(o-rAEWEthbAkwFU!|$E)cJK-o7? zTZv4)72v!4eO9md$Mc4)1?}ippR@{be!SrWkogw@fGEqFPo=`%W?YQEG>=Z)!k0n= zt_Ak#r_%f%DAmQRKydKfSpqyD1muZ(s63Ia%-8CZd55JIQCA_o_sd6*R$(0{0k&-^ znyQ|y$&<KNm7t&|gN%qC=;Vsv@UbDiM8v?uG0VFi{EmA4SjJtnrv{w|wgilszKL z<&&<9dQ4R{cO}F$4sIs3_~ngyCZs~+`DucMG}unM?7GayI;;ZsiA(;|wnwA2-sz&jFZ>XA`) z4}?}Sf$e_Z>Aeu6=a|lzzoOH5C&wqhlfZfWn#0n{+W$k;TSr9|cHiT77)n4wq*Lh< zkZx2$x=T7_=oqAHkZu?nhLDghQ9>zE>29Qj0Vx@J=-<5WcfFtAU$bV`tY_W3o_o*P z&p!L?1L(Vbyc~M(AJI>t)1JAV6?HRdHA~j^G;Yolfc|nI+02T#fipkbuwUksN^RYD z5_!hd!SbgJS#zgL3|wp9AShS)x;lzHHSa=jyDbh9I2IybXeQ!VVFt6xm0g}-P6i5rt0<(y17$+oOvD z%FYK)UHd?`h61L~^+5W5ky$GdYJv?jEH#|pGe`EZ8Qg~OXZ8J&tGN9NhFSj&ML8(i ztYcpLw;w1?MS?MDfnC11WH;dY6%nj+aL$knlMLQSH+0dK-8&_;i)VrR^60AS9@od)A#)7LY!y6HsI->{V{Iq^`JU+qM8 zxr5D!+rLV8))q0PA8{l~+t$ViUQ@%@BpXrgkLkPB)IN9?`^weaLLP%Xz9xuKoo->k zPn)icG1msi=g|HX5}xy%Np9@!s*QH_hy+V6wt;FOBbtsNpvzk^Qud&Rb1ZI)@skxb zP#SafroPVVd`?q3YtgcGP|P93q#`KQ;%Lz0*MTO!o4fax^?R})^tEPtLdnvpRoC{< zp|)ERBZfz8ZhY>lzx9q)zn@`-q9uZa_#a6JI{Lj>P+P4Tcb{1v?85NjR zsh_%Yp;^U{q3$C;rm)9WC9in&gl1AN+7v7n&s!I*%`X_Q!;rEB3~rD94?8BueQrX-G>LIP>|iGxNc~8;_JMui z-UZXRvRBpjuub;YHp0QUQ|r16dC6mEmig^r6mQzm$oo+F>uSvAlwr;U+JHR90zt&i zeWw7M`9WP_YUH;e!~2gfLrt~WH#8Ep{!n42ZI)sDqa2n4u|r!hzEDBm*4)9zu`6_| zJao|OBb@#6LG*jxo6;j_U>cZtMZZH@O6+l0`3yCqTqrkRkPkFP$fjAG73b6;YRt=C zPDPgSyp5QJ`iFSQW@~({@clQ~Gpk2GGw5Lw;Q(nN62lT8zGl3Qf7K~o>W7tkt#9~N zh);AX{fFLk!~gRrV!z`Ux2yZF-Ns$Ay!4g+wb+4EH2f_iIYQgj=KNh&P4x(w4RLCa zA;2zLHyt0`@uJ!MK)2u=6WlbBpEy06?~MvQu_aKhV&manfd7U*FSWKG*O$*;O*k= zH<*xCKNgGp!;Znf8^g54E3z-%u2juysrsND-*Z^73?RnHZk!J4XYc60*JJ8*bjKdH zFVbZCn{c}7HMI!VEWgO9^){(lu(WxxT1J{R?x`01q491Xqx#&nnzBboz^p9PnWLoioxO&=gJTA zL*6WfHdezB)f2*(M_#%8W<)<+Sbg}MTc}3( zBeFGEyO?8m+HPyenf{y;j=HcyRj`@sHqX84j=gd%skJ{%RzA6MWvs0Tso9vCF*2Eq z-SbT%xJtMWoew+_kctaPzLqkzhflK#nMm1%mogKw>c0RH%o(U|-vs_J0>B=z>zJYD7sUmP5}!u!23T;f@-V1oxVwqm*|s(yl(S?1T{{JHrs@dAv3;F@TEH zeHRQD>01a)tD$qi4RPF8%jJE1hgbI3GD5jPoc_71*4R`u6#)}GCd=WIdRj8;f~j~O z@VJ^Y)1fD#i%eVt9Xn{w<+zsZPH}f4@#W?n90wX4;_=I5A28!^3{vsQF9r2P&1!C_ zFYAux;-R9Pj_Cl0H*u8Z6E@79ylPb2mi^`W2PR)RR1af+Hp+JV=X2U9iX*!{EEjJu zpGuhtjYId|H~@#N&oAVe5Xn60H>~c}k)IQ?oy_EYXcW%Vt?S8K9cW0VEHwy!h+p=W zd}y@~sMyPIPtCpN4dpjIVNMm(_0A{k;u_h5?H;zQ`}<*mwXw;57)Mg^P{6*3DpZZ-?0Pu0{Y|IV|mVru&pi=OkukD8_$& z7rEI7zyhZ@L)@GHGXJ}rs#n<28e;e+6ck<$-0t(@!xdYCtTbmvSP2VaF77D zi}^dLbO^q-tld>~8$ zb_jN$lWpgsD(&y9ypssavVjq}MXee0PNBiG?3<Khrb~1|v_#kNm>yJEjEA}M^j>u?s2NhjL@^}Rj8Yp~= zmru%#kxzwA9-7{GJqfXm5(9hh(5^U=?mPolQc{^F3@&l0LF z3euS_;&bZZACC85^#o6z&RgS@_Pu=Hm8-n3cy1-al1xI(>EwCgi)niZS9 z2KuSjWamWL@BNjHdr&m0#tSHVT^Rewu3ztM_%#Rys|5uG)0lKc1R1v#wgBC>81>aZ zg?oArO@u4>pBQELHwhjm>AS&sri^0S6S*I%mrxRsox0biQaMd&e~7x3Q~U48P@N#Wtu!d+z}ds3&|=%ny&qR^#(mFlRp`{jdS zY1B4;?RHiPrT5bqkTc+`egbgJ9C%vNI0cDY;ITR8LxQOY8ileeI@3K znE*7!@RHLR?Nj%Xtvo}ir^FXw>|jnA8n$x#8z**qf3|!Jt)DJTg_$^idF=x;#05(v z&Hu44`abfI`pL`GB{Jn4Yo-ojoqM}=LAeK#?|Nw$TlF)RTn6aKEY(sPh#n;8mE{K) zwUBp2#*|3+0zj|4`GLUKpmZ29m|>Qm9I%NB-F5ADCDjWe$mTZ;LNDE~}lgtd)e$uj_J3DOE=S8{#T)n+mArO665bw-8W0c@ZY zS<=WRo_pUgezapu<>RZ}gNa~A{VJ4HCr{%02?hCZ)FlD#pltT^*^UIU9PGKyRnr%J&loA<&2=5B5jxtdbY2$7wuq;*) zASN(S;d$%z=^T2enp$S6J=8!{T)K4BQ`ntDYJr)6&Cl8b|8ijpN*Ep28Qcv zEK~)6#%||4uT4C@P%5b>$4nioyGVuM3mZ7qiA<=R-khZ1*a?YXO?2BL*6S7c5uu4d z;)4(PA&l{3y!F+bzGvn{@?164;&~wLxz=MH#EvVa5lDa}-vhxsymcJtEyUvmIOs^y2RXYsOsXB0y6 zDIYX!JsaX5lnT=AoLwgumgPw^8b=SSTcj$_LGf-*@yLKXLtN(8vGNNg#UAeu0=xk< zsdG9f4T{A7F8z7^Epg>}Q8r<7Q86Vla)oS%13;-<;&h@WKZhf2CBMX_gcIWz0G&hB zO>yZ$WO>|Dt`j4MFq8Q9ofOksBYM_Hp2PW;iM8nlR_*<13;A%p50a0=D zRhMZq{Evv%rw_$F+voTnU3$_EW`<}^qD)cq7sdLDPK{D5asjV}NW8A)?xSK=Kj2Wv zS!hu&f)N8WFn(?-qMDa=Vz4=3|M_`jZUkaaO(M`20Yb->#;1cD-lSP|GKv1HlRa%a zLbqXpauUuMf2IoVWHi#&Gu`+TgCYMeuc%H`#V|jRKPHsP7TJzR{ zQ&ITuY0(85aed`URPV$NvmE9QkIC3_+#yWO*1apb0gG�!KO~&pFgAlZH(U51Ef8 z2)YrjXT(qMUym#p9t74deOKycfgPWc==2Dk z7!HLF{aG-1Db$hp`W1;=>HmxExp#R6EOVIHuBUM?_U`d!JvX$BYF^cL4_5mls)+G+ zO-t}ZG!SUlY*CKn7bQq@=%$B&N==KQUwRKnS)^Bc6-taY@|RRVF-rAH68quQ$6Kn^ z%H*UmII_0`9^p1N1*sjeIf91M$WT$iFRQU1z)k09Y9+lAxJBKP=sM^#O<*V&0hc$G^K)HvC}zFEah^5q zwea2$I>4jFDvLI-vT+s1t?Rvoo6EU5!Y2A2eoX_Jj<5Y@jQG`%Xwe9wRnkAULTY}IrIP~i@mcxLAIaI}vIj;y$>ASQO zm@H=+ZFsA$2(LhH2c80+=kwfgd z@b-=%sT#Ql$8WB@Y&{=-44#H`AFA0I(b>26b+N;o8!l_-+p}Gyi04$U43N)3mox$K zP_6d}g^qT(tnI!~ZhHD2m3UawcH-M|v|FMk2*|JR^Xl~hA5U7_Myy1N`+R_)I6Tf> zk)@?$w2KddOxw!E(s-yQR;j-!q}i_g&2oa4K=+hwOodjm>@LbC6xQ9j6d@c7wz+2I zOMdHPaZOEW`;SINLBN|tnMY`BU~Ov96`PWdkQuFAIJ!WRh~wczoK;R3>V~Mrk{wyF zv1Q^@G~yCdMqf|Z(z68(WBz62{AqsvtlI#-@^)Xs z)5j2gTh4C8bHSxjuj5vS>f-#*H7Fv=dat0_xMEqwT3o&a5MSEsBKA2RD&{RotH&P6 zjfkeb47J0UNvUEc+G`|%-eC{7GC!MX@A?T`_8dZJv^VS>F&vW_k|@N z^zGicRje$wV4p4iKn_iEjt(V|#Vf(1#*{eBU|7$N$&Yj5L@$Q<@DwMnS-i4vy7_H( zn~1&fW0r3E?`-e{FWvw*V0H67G@fyP18#~ebtN6*3PBiJ#sAgj4EMMU;3}e&zz!{_ zA8!b|gW_)kIg3N<?`6fb z&1Ets{0vHVMZSG{lP`hYm4vmny=f_OIFRCXbJ|%Y`&eC$*MQ6tYF#4z+tSA-Y#SnY zLTGxW!kToB^!veL$j{;cGyWTG)WM5d=Z?pb?O@Th^qvO;C}f4x+H|y;4aMV>7XLZ| z5S|#t?NhS8OJn=kVO@&I*8@i!en6imZhE)_xtDXLcW%ULt5DU^)y_=lv!QU|KKy${ zBrWuFa0wI-U4XX=f3o(Tm9UqWgMeghySIR9Fm5Yzk7{e?Et6#bg>42qN!dhuJJM^z zr2sX@C8mWAOvFKfMnh~c=e!`U)&=~3>4`9T~g%)C17bYL64(_SKZKU2{EDxzAL^w={_yfcd8x>_^Z%66G#Gi1=d z9H+a_2$FQzP^P0JxqHaxK=IHZJjE@3(p5*AO|3-%K%Wo+1^iusLBE>b^`Yay9Ye=> zISyw^#?#^VXWiCw;jC*Rw^*rJ6XbvPFNLuh1Vd?8D+cN#?u8)0*K|4nAJw+2eDS)C za^14l&(lZ1#o*bakaG6Wfx?tmf_2-h=C1pk$Pn$LRGQw8-NaVHC?T67e5ya zWZQ)!?4gwI{P+&IUqzL6LxQB7}KHd}s)*=uuo&5U$@j7zeQQy(#Q&DP?OXp%5h$ zHl&X(kZb&bv^eebJRwZb^E?H$gGU1dJ&fkMK%hump8%bg0YGbX6Jg?Q4g0-6-R;^h zQ5-jjUoh7j&Kv6Wvp3KE5pqIDfGkN60r^dXr&`Vj7twPcjaJl?nK_5|DY7(>_%J4X z%ejP{Zh9m-Z{7+qvpx4Vv(Y@S0l7~-=){j_lgUHWYA~-V6&O;1i%k1%~<3eS4Y4(g*G?@N6}c;J*h#oX2c9uDE8N1}MXi7|IG;U`?cu9;X{bZcQ`@molG9@LiwE~2fIRZG8^s+1 zAZL{*hgEwdB@S+QnbsF^h!w(pgQrFYQ=W9FLjfUp?KFS66!||+`~qNFJiZhj+#YXM zezPJUGlv;mGIZ#sMNjs#FFZyXIv+dGj!+<*{BXt9+uFM6*NvQ?)A^;blXh}0`q4nv zIW4mucXMknYL=9z5%sKMVdB0KTgT9R^wi&d`gBW^xZO$oZW$Gy&|i+Y#2M5d4Kq`H4VetU`2g(ltq z5uST?L!co#_QNPW4KC}lAGqN%)7bhLUCMqEkwrBbm>6t?sC|S_%)0$+;il+q=Z{#E@hyc(HrTUa{cQWd`3Z=X0$$9i_uwp430{ z=skL8 zkFEAjw;*nO3FL!+90{2O4R~C&TWF3GTuM}RZl-L%qmtoTrYnSwqc-bM1o5m?K$m1J;) z>Tc+A9m_&4S_sghj=$Ll9;?LzD4siuR++mw_2E-s7*ZRO81q90xO>Z9Sh7W!x!Mh^ zaaNQd#CuN0NW^|IRk``#gG|A%3uEAV&uc)tVJsj1qX03fm?OR9b8>6?&PxXi>Wr#& z#_&A3PFJhNv~B;*0axV)RzvY#-T>PNkcT~DAo7Ie zRJkR_x4f_piTS6Igpj+V09(9jrn$ox9b!Yh&d<$tfxHCQS-bb8^`5i&Q%-;kToOs_ zM;$yeZ?D0=t=#zWyAAOMc$W8V&=VN4SCd<@EA<_xcp4OU?L6qdfItCFt^zuB!m^5M z?8x2UB*LpDXZoO$hB|PJ(AH2(%bLQM{{{to)N-+E;m-sq<;ex)1<2!A9#s^n&0oi=AMUC|cAoB4ThUTJN^S`5j|1=F0iK*>1x z0zD*7=gPY~@$fT&T*XofswtAAhre=*y-;dO8S4S-BAY=}AkxnM7q@Mw+gxep9rtwS zM7=ed^(#m9F zb$j;yo7&uiN73C^BXn$iLH+St`EL7)2odg!5TLgg@sLJ}H7NW1dmr;-T$hn+l#Z2l znuQ8oVsPl$a8Al%9`o4feb8CfKxLUjD4cKXFxAS7UOK4*iW!t+mUcZ^K_U+~e|p1k zIZE!b6(yME&vs~J z)>S^$yj)VRFVAT4q|PmY?ID&Ma{r*W^9LrRchP)v=CJ=_<##Vc1552KAbPh<_W`sc zllqnIF$s#i7u z&r{VYfvRoWaJHr|#T?RN()JNI3OZ(9PwWLQUb7d?e~W?Kkme500P zBseqFA6MNp6t>tbACg;eZ6syhW>pH77a(D76DIHTzkT|knQ_aXC+VUuf0Ii2KPQ~P zavYTXD1h)a$h;H(Ey_5j5|9Yhom@;nB0zr1h=&}@{7;UjggXVmDJv8YwvZY6%Z6ur z_61E2*t>(WYl-G?CBF$&ow2fQUc%ZkqMx~$WVqcB6c z7XxJ`P{*hchgX|OVd}GfXHHIZah2#)dCBPxzWh!OXK?fH$*URZ2(MQDW>9t>UsrA< zH}TCBZwRFKu>Q5IIOZ4@JC2Jm?mR(m2yf+3BO4#si>pJAbVrC``&@^%NzIrdfKla&aui<`&pX#U*wwks!eLvcT>qa+ldoLxY6og{ zuVO{bx{+AQM1gXXJ8ZCkGJ5OPncXM$9BO8HApxbd&Tyap{bLmny&idvIaaNpzX)*e>ya(p<)#4HJYnYP8V#*;~JW2^OkMe3-fC z`K$Hv2di);&b8+al*|;GKNX`vE&|Oo*>B{7MiIYh?;J)hX!>Yij3>Lm+H?rFGHAZn zq^S{Tj#$S6{2@ zeX`>L&vMOi-3TH;G2E@a%!8~8u_hl1^DCIJYD|QP!5smm6v5>gPfN)FXA3q5M@3%_ zh^7QL7t9DY;E8K>;PLMJCxX=(29;S?A5&qWQPCV^-te)&ReXO96B>@G}J74PQ(1&9G(*jJ8VwjHy485{Ah?L~sdJy$>75jB$p`~Cv zg0_l$l9k^(`6fM{xlcqdH}@k`=eWi?-sb z6?|lFBEv&rtVMBWv1SHpoFGfI28Q@`r1j=5k6_AE`t`ZXVp7SLiCb~q`DyyuwfsDj zLrfD1*0>!&{YW-w>>bUud#*a3=1)7^AT3=$p)K#&D@b#aW^kEf=b0@JLI1kV=%`Me zrUW3%wEpr@>kD!~F~}{8Jv8-{AG3dQsi)6vvjEIAgxBHM*7KP*MD5XP}@IE-qPN+U@M-c34GDB=*8((`jLS;pyS@jRXz3@aN&Q|9J%d|Wm3xaJc1)QPbL3B@WGI(x{GJva3F z%Ee#I0Q&sHEysowhZJCDD8fiUOr@$h2A^u0+|Ypr^vd^&MIjWP1h ztM6|_4}I>Z#Di&!=ivh*r~e7=i_AQ1G#(rI>ZiLbsiG?P&6enFvUJ za=3kK#&FO?fWh367v_)X7|sy^|N1^y!#cKJWhYtB)nbWmL-R@CBeh>a#n8YKy#V@-^?AVBWD()HGpfn40hC zCZo{WaV>KQ{uF-X57d}QFb1;-y!MY5`PT85V9CRb)|=HNn%x?9SFzaP5H(<|C`CuC zy08*&?`&az!wG1*o)tsBHIhq!twyQ=YB~CD)z9wZ!v_DmbK-3_kFMZ@H(Q%!b8 z%yS7@^~@PUabS%(kV^VPgc0w7J)H8X^8Ls1sS3(;O4!%`U}cx(T}ASny}DygdJ>RQ+`^SOcnwwq zSQm60KkKyRV-{(?YMr%HNY2J!=yP4+XNkZ&=TDmNqF@@no!hc1`EL%>7<42B%@#^X za0+Tn9tcOPwDuSS%3g-`W^!u@43z`=Dja`19oOG)2@J8{D!A}tX})?vI9>18+wquF7u#pttZhx*bnb?~&ZkJZ7 z>3VAaa6=hup7%z7jVmF)j;;^v40~2YDBkv-C@E9;=h$ydjP?;*o9>kq9@8uVO{l+> zf=MEGBbYW_d}Eck!cebrr^_d-h}DxpxM3l%zhsI-7Lz)?J~UErA%JatFOi`?Tq}|> z^YhAlopl!{knQNw!af8mR0~i?B!d2J5XoDY2r~zjH|B|4#+OcI>|t)k$7=FL89xo` zv49DNTQtflZVo5n{GBd^^Y_&PGi`SU9Fwln4<)jd!W~ajkINdd{SZQc^#}Qu#zuDA zNJ|o7u8Xp+11X(~S8bvyM)!#_W1>FM?2d|Z{MgL|T_g?(O?N1v+NC*|GJO9@krY3| zLjqDO;fRCM=fX$_R!AXZr4xY}-?SzLes6R7qCX4@U@e1Z^6l!QLApdFYtbw$7yPPN=sa>7=Z8k zGQBRbO*F?o1)5-UG}qg4B6vV+V;6X(X6P+v-8CK9nEn*p2GN|y_27p1SWV7Ay_0ED>U_9yHM2u6ZzZs@2vUN-t4=i~1*3E5J z(>>?~0dgHnW0M^^3w^jLg~eN3Jgp=vBEZYid-3&?s)uM2Bqe?*F61yy2<}(f8cOtF zi$hJTms>-rU_*^W8K9J5%9k5D;h_OeSmMd#EgFo1CvkSouM}C6c&X(7kI^=$O5OXf zoF(+lEmtD;S;oBN>k&_=hzOyJPBxjmw8VdEkeg0Jqf{{=ses>$v|kco8M#%F#PTny zk+e?PGX?3@kKI74L2KkCPVb6GPh{Dnq@4XNwR68`gm&9@rbU zKiq^^g9mCF?748<&el_*Np?I|y8piSNCt%BjmE6)aYn4Ht z0?vj?We@Ug##~hLf6F6J<+njZAIUVV6BS>eMpUgfsr}K#zCzUM5P^g!Dfx0O_`m0>$hu)XJ{a!5E;QU=LyLO8(P!u*7yqq; zdI+sfA7^6P1huH_5ThXu6Q5bgS{26-BSpyA&)<}bhUQr$s_PkxcMv8`3_t@@x9)IG ziP#Ht?V!QLTPtn!tggX3ry#CeZL<2`mKv+=^U2amlLjMQ=SAM_jNH#CCs;t*G)soL zam%w+b1?Q|Wm5BkO+8lc-hXjTo{pQ-n#lt~;{$#|Sg&UyRKJ3S@M-%#sM3Yq=_>pj zr)>1D-=!%Z;M7nmo7fevMxFN=kH+oTjnG=*J9s#?Q29&0PJ_)f{e%n@pn@Zp2Jqzh zA({upK*mP?Z?(6rRE?%-f2vD#(gqvGod-wy?}NzB6p}weeY`IkVM4&rlmi^aFnIPr zPDE}A*D9S|jDW=U2X_SDpf@4OXp$&pH+k-jaT+SW&9tqyM{A2$;EF*dDhLkzP5G?R zCIhDgkpLi5$k7TX!&L1O3{@flCRL)tbJR{_UsG70qdzr_ZcNOL$f2R#k$NmH`+PJ> z^-~~B3Y0pAK=wwJF|xoUHLgx#Th!77N)J?;%f9A|B6|k2*GiAnX&=%CGC}a2@mV{- ze{nu;LK;6-RBFc=5|FIN4PB{e?6S#B&Oh|m!3Ox?K0I^wE_CBMo`KJBcdN&oYf(yR zj2PlC6x8hDgMd~?tmcRAYE%t=X00HbXWpp^f1exK`GgCmWD7d=I_K}b6L&{d&sb8K ziufNF#T!r?gXYft%}s zkjiiiS6-MekC-{S-V2wxLyXqig~j8$--VFMrRn_6;O%i86!J3UR)yjq)NoQe2K`-_ zfRfWIQjTLZj$lkV>hfHzon_!>p_MA7hCG^&HsUe~S!ne)I(u(QnR)9{yX*7+)F3UD z|A$b$lN#xcUA=3`Pl7z~F|rJKwr1QEx5UZX)Li7|ShOYYE`J9q-nyrl@~eEsNTXrk zQ_IW1WJ&2U#>`vcx-sCd80jTd+(S-VH&{Ic7>{Y?P|IUkcsT+6J3B4QaV2xr%^}#d zyvzP*|HZH{XQE}1EF}7A9a`U?8!T^~-C6ctsaYB_m_V~YQ#q8V-g=!Mn zIhzD6F-7a}`;1sY*@E0yA4^R4v4fqpdAnP}Bqbmd{qj*o_bl*n&s8Q?x!|2i%wKTm zmq0;W`D7?|h*M{e7;6re&>Zz*_0s1!yseZZb6${++N$c)-f@E-=S4FKr=GVj#Uo+Y}w# zD~eSsf$<)rhp8aEdly7)IXrRq*#b)SWGsjzMMmOv6!^f|#%gcR*Y)?u0;!kODUc;NetAbqi2)Ff^`aTeUSNG_mzQ z6GVRglkeFqG?4U%*H3SFCYTRtz2H7V(3?#BaFz$pN_*0vR};H=hf6;yrl&|xssgd5 z&vxgAo5I!s6u-lsC~0?SWM}!h9B=*VqT@erXn|1qxwgc4b`WW?E{RGqwHrRF7~+fg zQm(@iQ2g%Cq}|l4_=!y@Z0_~?v=4s(bzyJSxOz_HKd}8rokElb{P{a@!^in;0jmb! z)2kk>6k)T@N`!Z%5$N>8YP^N>^WNwj{tOnxZW;80NHvI5W+XnOw=bZP%mMp1jJ{-# z1<;n5&CP;+-NGp6J~eKrO<1gdi{!X^4QO`kPUsW0QgtXK*Ka0-4+?5FwJugZ-4wWI zvkjAAVOyphheV3<%st%K@Oip0fS$+`1~u?3vGKn_=qY#h@;mR?9d<4#PNOr4zu zP0=t7jwOK_296v3rE$9h&YY6}QWq*I&JWW`nWv?~v0_whOWsX_5=n5rc@z;dy!tWA zux{22X8!s;-U5@9DE?&)8*k1^F8*-|gd5;K5#^zZ38i!&f%7S(sk*q1C}rWjd0znk z{BYh4<5#VgAVW!AhAAdY!4k!_d7$7lu*Is&zJtc^$qK$i#Bb*j&E6rP>y@sv*%8m* zj7659tb#2?t@I==^_({w!|`tAvm-y`E${wte-==gql*u>p@_u#bSToS)yA$;4hkQn z;A^+vf2nbf-=&uZgw7f8BTafu!W(g@ENu6cG(M_eKpv z0k4U{{X)2Ee)R8No=fZv`Yi&d zu$Y7A<5CBPxGP#JWW^aLg>;bw_g|QB@AMGBWexp+dIPirLxCND8%CpY&IQ{9EC5Lf(98d0eKKfxRa zt9$WL8xpV7iu&oCt|9}lQ;~bH$)i64wfSt+Cpoco$&`)p4?tdu5XnQ8aG4)t`q;d( z5(r#I_~J{{C26&W2J4u^iD5P6ALowAhEGk2p3n@RdMPAAi@)!QV9QIVv-SHifKyKG zRJ078;^6-hT7;U0c9nEZ;5yB^P1QHjW>$L*x5>&y$yFcM`$kor_p!gv`0eAQ0H}z87d^LbEs~p7Yb0gcCO+2U_p#{{Q<`p_d0ohj z(=zQbI+K>r%8+Z9Jfy<`+>LJV_x7R{+4lI*Z-Fh3{HuiAO*ot_{eWndVUW*ioWkfM z=(rgT#klc`x@XUNi5;J_a>24r-XsZ7X5;Sjo8b^JJlT;%zI@!!P6 z5$TnS226-xMF|tkF3q}NjaPlM-|i?rj)B!)r_(*|%xS_wNQz)H z>pRewsGyPyxXKTVmTTqnQPm0gLndTk>U^b+9x!tNYeqDZ0Sxft=I^?ZF?L(n(h2X7 z-s)YN0U7wmuVub!?t@9u0k2#C#W%5!0*`HXr?*}tU|EfX^eRWTVr?`n4p%`mE(C*A zO=(?g&Y$A%%x_FNgtkTVO*ObP%e~X5&0!zFPg=<8Of3BVpyk!ejX?y z73ce^3hG6hh}T;_fquM~F7+}ASN;?w-LfT8JY-KrHw?EY(iq3?fq436o(in&P3v<9 zf`+&E4UmB3B{Mz!qk)U9#>5-$7M!e%o0um(I){o3;}53E%}K1LUyypqZAG=jxQ*63 zPAnQoc=Vtrhj|wsTGc}Hd$gYAl|tmH0Pa4>k*u?5w4+`GP5a-^18zlTOTzIN5EY{r z_IS{O0=m#98&;6;<~*%@rprlj+91nI79GjK+>jzMZV^RCy=u25o}>nQ*by$~)=yR2i6quNfo8r#*A7%|E)X+0VDjk##=9kX8fifIpN=Ev zNvwC9dY)0GdBeI^4b)+^6fHNBn1`1rsi%F}3}jkKZ#y#jXN+$!QHkm_;-GjBAIXlt zT05X`V&GXMGTO^(;@4b7)me!pbHPdFfuda}l=?vW^)HS!;%%=IV#e{)%Y?VxMeM31C0@N9Fu{}&H5?L-ckwY1k~N4m$kR&{-;xRv?6{eDfG2qjt`%#B zhK;&el{T&q`i~aW`jp|JOh@ev8T_+Nz<&9S{W;!gje#&742{eOPZDiT69O=uMapOl zoo2e?BCfi&9|6?3WBdlcnH78WfLtKhvn!$I~Eu9ghouM3T4s!B?Z7OWF> z3*jLR@9&C?2qJ?HZo92LnTWv(&%Q7q2zC-PdAeWmKA=cY|9KMeERM! zSsNec^A1dQE6X5pLvI>e8;)+3ej?d7Yo9lxq0oH4VNmy}-igWUvts0;$jjq1Zi1rE zf~sPQyJy6(AYP7X_Elqzk=V@pjGQz+;ErBROi?jkX=01QONI%L>Ms4p8u|^z09~1&go^qY-BnhKcjpw+oUxDSK_7+mw0wPR)+kvFDVh!%@?$bsdmdfT3q4398KDVRFhp2hy1-p z24@IYe=VF!$9uTLL1zj4*h(G6X5}aVv0LujdX>1dv*>f#+F|Pq zI-Jj?sans0gTIagQ)7gsdl`GPb^>xNfIhK{0Hqbr@a~I*()L|OA`S|DJJS}BdAA|* z{KJ#%8EjamQJasSvl769HMo@Fg&;*QRGCQyKn5?ZiIsa;65o$RisZ#IzCe}|+i^mi z!~#I&=NIuZKyFxoiWqggodI*~hOmisP?OtPaoSO&qFi1E-8iO~0dZ{cS%8rtvrDAK zW_N4f@1;k|g$>>Ku%ENr`@|pBjxLmQf-7*6-n)$f z?rP1MPNx&+!$t$+U18YeH~c!!G?eVIoAHz|(1puMtwf~vUvEq#ycu+z0Uj?~EFawY z_2ji;MUi5fhdE%pQ9Rj-iT$6SOGw50D(;8_II|d5Cy0eqwt?IMxet5Z2Ar3rk_D@4 zu2w8T*ZOaEho=%p;G$re!H2k2gr7Y{Rnuf_iatfMtHka$u!CQ-X&}DSz=&1CInXh2 zQlAB4bNfu>%vU z4w9a!^_63QR@k4Cx^{pJLtZ#1=JN+x5&((*s6#7_^#tnp@b)v1x^|sJJt0ANC5EnM zaw2-SWq2G~hn`MhFJXN+Ppf!2)t-LT9G7{qWk0)-a4;C_lbLK?R{aR3K@m;;x+F37 zfNwSf0F*drV54zrq)z9}o|KW2#XatGtVQ?R$Fu6hxA#1>Y&Z8qD|x+(I@3EFVE^S=iE5sNW71@E+46M+H- zYFe&xG5Qj8U|Tv$ogPlh23)z6rX{jz%Sc-S=YMaK^NM1Gmh2E8o;2P3vR>?O|37IZ6 z{?#_eMmt+yLsxo=+JH|tDsYlirpfBZ-#B0187usV6YrIbw}g_h_<7tj>T$@^=Q3mw zgtWURf5Ysdxa`;f+z!b*9ra?=i>q5yh)1lDfMDTmG~A^?U$*gyJ``C$I>3v7%S{z&%OrM3E%rta0>7Lk z;~X*#t3jks2&IJM%6Sf^mB?HkZav6>v2H)iQXB}{ejX!+RNn+(+!gS(RsVZ4+*I!$3!rEzl2thy6J@m%}oN%rd??ys`x5MF% zMS`P5fg)f!^P9bGwt}iRLRjB}cim`SO6G_6z7)ua`q0~vc`64?`cs^L_$bE$?AB0& z17vsz=N#%xzPd=f&bT=``?|((2vf0^yhozHdK45@uVWXaRYkWgwq|T!Bm{QD<|DXS z!Wst#Sllh$ICy3{K2=1Ay+U3$8;K$QhtlJ%0WdubdB^HXLCk);8C~!>;S|ExC08rG z#nc?Kb_3O8FGr4uKGjl8=9W`0eO8S@RWcayIVx_#q ze!|+S=+kKzb^F%?Hu06reqcn&&CWwA38iY$a-7=|ADRQr7`c z|Fbq6kILTuUABN~S-fT_EQQ5zJ2RaM#tt+lzIl&BbUfsA>h}JHfWobKL7E1r%7szId_bFhrS+$j`T;^o z@Gvii3c6*dD{oJId$#qD$uPkvuz5onOuJNQ@Uh;zPOg<^L|@k{58cd}bEF}hCu7IA z8CHdw#Kb)#lOajEkat>CiAlVEXE)V+h($tq@d(&y+Gzrp)mL96;Ybx|06_9bZ2-Nt zehJ<{k>S2sd5>a}Ol8pR5){@GK$u>llGgX@tTuB+y=Gbdp>gR4hE7j;jC!5+#=-w!WsuF- z_})r(V9kROZ#_^br+ft+Yml)|(@wL($K1OOsgGU1NWAsvEYcP&f33;=agV~Hwrv}X zhIS{%!&u0F8W^#3&=(BQJqgyBxC1#dthc?-QDiEI*uXi`xTO9!MbYH)s_H3=`R0RN zO_K^t&1w)(2bH2ag6gD~r3)JY4?N6Dh=Vt{F;F%=mry!q65*d)&X_|%eLIZ_2#y!< z!0P)O>)ZkYc|J0%;7FLZ-%X4fj(o&zlPJ}VzRHwe@^w3M;{TD`{bL1(aIH6Kg5w5v zIM9(39Crb$7^t3su?&MES%Cuqq{-$hC!sFUo9a%?Ad##2H0M=0pL36`uJ}zwLQBVo zZKdEEDs0Pg7Gee9%lBF!a3+StXfA)$HPWD*vTc!WM$$pLU^XTg_7M4224beS`x336_C zJmt@3n$lG(H_USOc=7CMYS%R*8btr1B;d)lT7tVDG7w`&Z_kGw)Agbr294aYJ$O~{ zSJn|Mb>VA4jg5`tS&79`Qw)F*o$aR0nyW9*hx^IzCkvyR#k!LNE|5ukz2#_zXIj1z zhh=s7A%*Ww`X|a_Y~Idq9)W8(dH{VXKjI+Ns7~2rP{JlkP*mU|%7?FS!3@{eZX2oc z->~bjrs1*WS8|M_ z5+`Nm^*qg-O!$*eImEdFcPeCi>w6MN1oj&a{)Z$VGF-*wS;0DOR%tJYy@`BkONM1c z-GkVErTG?qhe+)fEuI_lIkI8ysx(fQ3~=+2**G<3cYmIJd}V1Cnrp)ewn)7XSMxO9 zr{y9e6Hq!iKmgxMaK?ZX#@NQC$d)2x{c=*Rzscmv5+H|YMBOIXvfo(hbatgh>VKlT zj6VEW)AWeLgaBxPmpW3R%QLDhtU|07fD8fRg@vn;UAm{9DE_Gy^bB(qRzY94)8Hof zP~`ea@MS*c>zB*vilj2X!m9-4u=%=Pax4)Nn+;gb6688g_(*gh0g^iVO zscXJMzC^lC=0FE}j0Egx19pXYD@P3nW*|dJ3gBAk4-wxWLxE$&TPBEjQ)TNSB;J2G z#IlOIXG2aFH$$ap|H?WYLxYr!Dv_X@{EbUrNZ}LNz z`p1eovb3x5HfMdAT(kP&;Ay!+89V^zh^AfTsLr(KjxZ4h#EAst3t3 z-ZenA{&3zWB+~Yo1LAPtV5S-FYND`!t~VNe{fWq|Bd39#$8+_V`nIyyZh z$#srKxC96B@D3Vv<(syPRd8_hk~em=>9HRUyvwX9HM9Hd(L&5*DLum!E`>Ip6LZEk zJ3=Y{*%Fu}cc?+3yHCxXp+N;x_W;FyoeRtCE3dNCol@};n(on;-NRm?z77XCJ*Gnw z{obGI?}D}62Y9@1>k_1b7Gl29yoLR^7@xVAGI@lT1Dtb{`R;F8F)>0 zAK6nc@tSh6ryjK@>h<`}4I=R`R~P6u$KuYo3no@sFJ-mKMLUJCM7$_Pu}D3v7(q(s z{t0zFt7pDRpt%<(Magbi(-!Pdj_*0aLmLiZyKhS_&Bv7 zPU#-`B2W8s!;2(^A!ffaS=y03g%L@bmtQot(<-^a&&P^loXLmsR!GI<_Ya;wx{iRM ziuaj!5~b1xu_zb8?+0>+liCqCs;{)ThaTJsSt3vEx9|v&db-c7>t2+*rer(EuxM>v z9%W#B30k~Xz-?nI1&;R(h&>vU{@Rc_Rdwyb1P_bi5+2CzXr)~Mru@Kt*x&;Hf7iXwdZ0EA)7H@8fd(-!%#N3Wo&R?R5q`c7kOL5J23&3va}O>HHd^BlAndM_~9y8mZ`3#kwAV8OSr0M zi7Q}Egw&H+m!Xt=^)m6UAj3lc&bKBF(SEhtU~;aS6pi*XgthczVBw1_u%SQ(-7jZm zl%JY)YB6X(%Ni(hSr=VKcty{?Sn(eQYS&>7XbN8E+en5x8D`CG&qSTF4)4e9ZVhx5 z4x4So_@%jaCvuYc71Yu&^el+C;da=G|I}$^Wr|AeHN^feqxvYbLj#rKo-`N7X>wG7 z!uhb-XXDeKp~q3=!7~`RcCt9l8u+8}*eOcGyvUk-|Ib3lL@DM-Hq*WKVGZ+e>_H?~ z-u^hf`xogQ`YQXc-hnQ%P}%_^x>KfWcQt8O4 zu-B!wnr371#`b!$2ew}G-qk6!qA*-e7psPe7Bp^Cz3ZmGIE%eR7UB>#t&{9|MW_g% z_|&P1E;(RIE-VCO0(8DT6oiG!P3>}boViBzyF^x8EPCbw_kuoE5^m|%W-}wRfk1$6 zw=614hTt5fMO>eJMTXqZ9coJ&t-J4m_%auPLw+r<&E7fTl|eT!yr*=eTrd!d4#&?L zk8M$;dkY?JRUld)ug7?p#TGFrU^7K6ooa4@ARGC{k`t2{H^d*z;4T7)%~#N~)ip~& zq)av(X!mwauZ?pcqMhv;xgz@D#mQevB2p<- zVbx(gb`C9FEeErJ%GzZ?q&G%ijo_jK$5YnnFYsqoE85E)XHk1%5(BhF0bkMH&qK5` z-*j#18-=9neeGpGWIZ>;VAy*G&!-NZToL@T|9@BTZtSHokN;-P0cqATGXrTQ*p6S| z4W!SVT#6Dbx^!+!%s)DC80An$%mh2I7x-1Jd3;_~I0heYW?76XhiZ2H0*1OcS9dO? z`l)ORTGu`bLJlX+yWWU%0#a-$7B^5P`6Ks)&}}*5TAqAjn@^{Kb-VQPOTLge+X0xIf8IzTry2QWC{ zuE(Nx@|SuwC9dLck@Pr^7(Z(A0oxAPGBvE{-S2%%Ce~o^*$8+7+NAea8#3ylwWEHh z>=@@#`uA5ogUt7}uGnf%TZ^unosB|)EsnRdRk(2;kmJ+s3o_tY(X~I94(URpA`OuS zz57xAiB;E749>_>g67dk{2TfB=L1cIh*-L`(WPu4Hfe`xT~AhXkDY6nby`Va$qW7F zAahaRFHhDpZ!U0~S__~@ywPuEPJAqvxck9EPT@DCWcP;{p>Fz((@a*p2vmn@;Ph08 zqMiPR$AjTrTn_gxtU+V1MCPQMQFp^`koVOzsb3a0VolgXlayxtzy8tcgUSX>M=pkdrb1>9(BU(rAU(N;&t!qD4D`t&F8R)~|Y+nf?6sgYu>q9=>P35hb%> z1a~+(7FPv19KO>i#Ct3;Aah1UV4>W6LSEO*1-|TW$n`y7d=UgU{}Z|K==(h?YoKJ^wIPX}x1KLLi#-U(3wI=w5rw5u)>n zO7v}OFGGIQMeb+(8IpB9tD1@<>0TqC#_rrzRG#&bJ$pkb3LwS2 z7#Ho4IY#i|#|!Cr$H*7XDvxLx-R-h}li)jo8LxkVG`ct!jSsuIuBL;FqK|MTDu#EM zQQpL}y2W&gUMWSq(f#V?eg3nybbg5nMeV>XlA2Vqxm5NBM$*Hr0XSAQdWmSUA3XFY zj`MnAY5{MyATO?K-fZqrv{M3K#I+PDmOow%+eTNF+O(**W-;BT){X|NFmM_kqYoo; z0!SrVRa;L~(bvNnlr@0p%?ROZxgO_W6kKD%md8=C8pIg}Q!awm5*!9S=4#hClNQ9e z5(l?MxXJ&rJr)-Fr;&2^DKV#J#g4FgbC`MLkpb)34QpL)WL5hhPb1^63CR?vTRozI zh8~bNs>TE(ja-p^&~h5dao_|qZ#C~9Fe#?llUnh~06F^KRB{0d;1cDUa=H0oE_iNB z5F>5%9ke_&`GDh>O|D*W_C-u*6szrPuk;tq4W2{8z;^Lfpn z?MMztE$2^c&!}E=Z*hJpvfj&*ynf5WysxYI1b+GPN=*Zl8Pu?--uV^Q{T<{>poCh) zndZdh`G5BLXM+DrcxKx@ByPL};=4hrB7nbaVeA)>Hl&FHTDC;(bfw9V)~x+Dp$T34 zXa}3vqotxwWZ==EE{aO0cbuGs*O?v=T#7)V51Y95UX|?&rW2D(HoJI=Sp0|tdF)rq zIX3H1-$p50AcxVR%YRGJmI)gl5w#__`Z7iQRW z-C2>04)XuRM-!#{XLvQaErGE`GBDzbSPr?HAIXxt);C~p@|;IA8WZl%KG4`fHF}T% z_rjJ5tZ@7ziV1i`|E^cYzX2J=XOc=W-j1t?Ek{9-z!X$d zoBp057~n1f;t`XkY#{#c2SjFw%qCvu-^CR97E`_pveD;w`6c5{=y3LT{s5uT3lk!@ z3^Xi$_s$GRZSb=QZyti{4I=5JXZdz1kSDF&{|^c5iE3vPyRp-}!V;*CoWEGTLk*rt z%MKA6?2a9=-@?O*q1t8Rz&2Ri5r$o&OeykAx#_x;>TM? ziVw23-*8i#=)$uNT5v^_uNvW{b8tSZKt=De3#JsOh zd6+=1+I7P&kk|B*gD4{G`R*xpvYo86!oGHzG;myjiPzvw??hLg0W=@s`*K&-O6)xN zJLvM$UraECcKMrYUO;3!@U(&$a6Y10yK`an408r(cZma0v%A_Ve|u#=aEiO~yuz?S zrcF9D-m-ywq1OVkjZ|}Kk(w-rocky3PS$5;=msRe%l<^|VLW&yiY4Mtt_NK|@0NyA z;Dmnd-eL9+DVd4DD2M|sh}2Ni^J;!!fAjw9#2JiZWSrn1L66XG+I{WXiqT~2d0d__a1xN7!3=Rp+Z^lfNY`gD!f&B?8Nz2S6{Kdh_f zwTX+Q7EtV#iFGiWDG$Bd+!Cb~FlbElHEareVABFFk&ge^GyG~41RXb_cXE{uoe6IF zBITtWK9&asZENiezt#9Wyw@CtavGWl;>YF$cT329ec_`yPHaHMz=AGe3C~LOalVo$ z-KWx2E$RAqipyGp+L^w)14(}cn|}$ul*s$5!PAZiJOo6B7cB7O9p{SA&DLgOT1<;D z!3$KS-vdFyhL;excR^oYBy{9*hoIk4-3#Sv=XOjij4ep@>`C~nEF}3LTUOU%3$zx? zhHsI`FlT;qC7|~WbwpM4thlD$GDlgUZ3sbP9TWWD9zqTD=t}>n z{B0X!R)tB7)HClxw0NOq^ECL8UMKFMdghtEw2W|r^sd44JYrSsA40vAF9{5J@jqOi z)KtDLCH6XYW9^N?R@a=Qz8nXh&SyuT{$|SdV%fCqOOTbY-T6;z-mwe6;V#gjp|>kx z517M`-4^X z*43(>g_|e+fZMy?Rqtz3o-B$Qi@?kUc&Gb)SOehZ#uiy|Z--TO+1(VaCw*Mnf1+o2K@>LVotb0L* zji{mmd8>#V+hN6?UkO-faa@arNN43|6)%m|;c8*;98873)9?gY>Tp`57l->KgRFsb zQk#+m$H*NuKkw&%k0y-+7-^Rqnyh%J_2c_e@5S9*KuG!I8~Y-#x9ja%KUnhIVzKW7jdlI5BsRqXa?*_!+q z+`yS>7sJI4i03H`nPa=BiWJN8TJSBR?9Q*{M=IXzG(wbk^8(7OcaB*TvZP*9Z`{7k znkaK-Kl2hYz7?C@Q7fZ(IVO&%v1FdgI=bs~{J%xC(yx`@wjiwsDfdAv|1>_V$w%Wj#1e<2KiwlfgHYcU z1V4)rhNF8Z_HOn`sSxKeOEo83~xJ8P2tfWlAP zfZ&_^D{K08&CKNrrd+ZRn|6r{u7Y1t+G|mg53=Mr z1q-S{ay2eogs4z@N_%bT|25>*Vhb*^E)uOr&!F5!T9bc&5*9`KvUT72K%x8Bp4N;L* z$J%&h8NHJaa_yNIn&<*usWPx22I%K=?Y|;u;oVps<-}GY<{Foji8+U@>SMN?7=n3? zF|78UA@iRg6y$v^bcz_AsmjAM;@K2b1mxDyn0E)T0b}QiiyR7?OAh(9{xK!4=l38f z8@N_djpuEi}BEj_|?jXOV zAj7iKW~k0%XJk zJ(L=Lnq7E~BzLM>5ZoHnx|Cn(X1!91dXvt2BJ7#^0xE4Qq%|h7tgXjHpE$qQ-q{j2 z^eO!=@%M>xHiov_5r(C!!^pPuV!qb)W%7)4>NNj5>Gxloivt~ewz&qn@>PP?*$4wu zrZEt4P%OEorPSb2W?g9y@5G@vQbS&^MRsL_Mc&SLQcK-z2u>0P&CY#qWHXrl?~)vvY*A$Wabqru?BrdEDO5&X4ZD7w}r(~1SS|n_Q%H->Pm2b z8npPDQbaJ#Io6wdF0tTF1y#lR>HRhNYv-=p@*IuNZLPIDh<*+(vHiUgu;!`UvsNbE z;;^2QTK|j@hDXMmqDd2HR{iRs!t=OP_iMR+Mb7NM%Tsdq z&jySsKdsRq_5`{eUXQ{gttKLUab!TUMzD2DtgMJSm;KN1fDbPdgkIK}(Uo^}zz+b~ z0d(YbL%*Uv(C6s=q)HI4ZjSn!0w~)i7e7x6Sm;JJI;#Tdx}4WYo00~y+@NjiPnz7$ zbMn@R9B6@vf2h1neQHWH0S`6AL2QJ---@*=)^L7@zsuCL-!l*NLhk8UMPBdbFvQQ^ z22L%SR*+L#R^9~zGA^tqA0yj`j`jyJ0V6yQ{Vwjx)3i$8B zZDqka1@~zqt+@W8axYt}(hRAO6V5XGK$p7^M z)Sm2ME{BE#fNji+`4vleIMJgUvWz2_qTi;UK%Uz8U{yy_1a|g=Q$5!mB35-KWo#pF zx4h_8K0H+5M^$@nkOnfHPT}h{sNhn}-$BI3ms1t?-ZQ#?KySl~cbLUk{0}0YB(1wL)`0F;KWfDHA9>eo_LQ z-?IUg@=r>cDEqD$U<<_G!o>N;X^*s-lqqdxl~6hbVr<}cap{Cm(0)NsS)<)K=~^bh z!+k{S4@l_w3G@D2)&caVBKg_lL%~GS55<~8?M5Vmd8SjbZX+>zzQ8$qN!LLGJ={s4 zyXs2mVtLHedAb?#B!R%zGd|@@{p(97$SRV8^#!zSd`b=C)j{MhBUT;eJ$otf@rxR! z?TgeP#*8zzv7NRhk(JbG3OxuO*L>Pxlex?}m0h5m{j7&Off5G5`v&NFSV8XjEO1-^ zmlU{D?i(WR=7aAEOvv7Ud>R{*9!lChybL!m?iP=I{k;n+ge7xlp4T}&uN(h^N30ha zczQww-!(*il~UEs=b6EpFy^`JU;*~aS!#5-&1WP&ULiBMQPztORlEfAKgq+odEMH# z1R3c7>GHEb((#8YGbkc;SwunQ*7#JPQtp$j*?B&TlQzlaBrMIu;nRKn8_HokGzz-Jz{md2GY%&WBZx~AE8MI*>Q ztp!~teU+29c%a68GzR$HhgBMnC1VX2*ViZr8x{XP6p04nuFlJedu{k zX^JgdHbEgkF?M^K`id@LN4B! zl0g}nn@(0-;{(2(IRXkB{Fyk7relTI9p>JZa#uPC7P)ORF71W^0E?iPB8|N2rO$mob3KgueTfDL`l0`$H6p*kT!-JZBh*)NSP>qXAnaC|VRhxn zkY|OMp<^!mKPTeefNbKUjD*&d?y{sa(se7>jEOGg?Rzp> zXkKjf55wPK(G{8FyZ{*?=62H|y^Sxx0%~$!^O_=R$c82k?n6RxtD7BS)>TfJe^$Ki zXe%-88GHHNz_)2SOQkDX5rYDF2u79BXZFZWx-icAVu+8g`6Ph=fg~dck)}h5jd-$y z-J=BI?@-ZcknnA2gy^UuN}+e)qcQIYXbp755+X&w7`i6k2Z;~O#OCVe=Otep0A-G! z%MeCwG&67WEx*xI#{#KO=0a*^{fL}Q#^$TcW&0ZP(+E3LtSf?bfYaa^i&VI-4`1N` z5>5797sDI#b8!bN0zV?DyZ2W3PTH21Bp?(DXHKvNuBzL4s|3=U4yOCMpevxSjIIRZ z5FOwZEt}EDI&+Mz;q>iGM{wyNd7ww1!A{%Rb0a=~KIzs_s&A~{z?lwY&Gyu#+6T$E zU>1$Xz1m2oQ$+1dkXH#L)Z0Z!vNIjC`x;E1R@VmD;Abs{CJc`b;@=@_>M)5CTE^{h zp=M@eBmU=y7{b#8JvpV6Xmh@WHPcQc^}UhZXY9vxbY%dz~E<2os|#Fz%E?D zk1D7TQGgZ^Dpm>~Ll8VqT28L*uOpNiS;J1o-?HOjyJ$hp!b!Eb0bU7M6!tQ;i(L=W zF0Q=Pud#kax`pQHU#5K$!>ZJEFBT&-kGiBd{(o|&ygfl_))@E7CZ$TZ(LSB&Wt%xq zh`qV{U9_iU-jKx`;K8J^Z0%;$gH&tEpF1Xs3zma`_l+ElxGT87gOstNyF*_^>x$6R z+xkWG?zfYeyzF06`baT>(=RHGDEsOdGEzgQtoeEyhG(00yp?sS3qQ00kQzwI_MiT5JHU88YLSrQ!5()c~PDt-~2XC~%!w0MLBM8Iw) zTL_QhW=X%dKW25#!M+_K{cXNOV_*rVcpqU;dYeXc70j31Pkg0`u`ZHZhD{AfmA0rN zRE7GG2X(gw2xF-E%mcp6R?f$#-wsN!iIKeGQ5wL9Mwiz8d;ql5xSISYEzR!|nL&EV zRiLvkDuX^i>8ze&TKe>cbw5c{9rxk9?_mLXomT753C%Iu+B7kZvtUFkao-`hb8>#xM9ggP7Any_tfj5JT;utT{nhk$lWsFRG>x&i=zj)Ln+#+QA0F#l$IF+ZF`~ zEh!c0K6!&Qn|!GVL*=Xl$60QTT%lygeUspT$z_P?jB2L(B@~H;=CA%Q77dj~M`i%_ zi_eHi<>FDBpC+id<8?hX_!gRNzAJad!hox0^-(BsgP@026U*Tq_>mJsDv$+(|Beuy z-sfU^_Yd(+ej^9vuZT*>OBv(fJ2W9+hp3v5@<&l^^!BJ-uf>g`?qYzWOQ7jdfu=hE zBUaDRD-yS0hF=J{ZjI;U!cw=%5;!=G18Pwwz0*wa2-dqla+dzDZ)amniT63o+5#5%Hl#!LmBGamr(u|@m&Tb~CC$OytgQ8(OmXAkk~o7CoV0qD%} zAD~P*yI1`3&h*C5a%wlZ_Y?qJ37zgZ`G#LUE*}pA{5KU)9=!J#)K?;PO2%(= zSKAcLlvdhgWTds)Ct;=KXut6qw;ABIa4Hk!9zcgpk99QCZI87YI5YS%4wrcI@<9lL z|7P{+j6A2O*H_uy}}tcP}$Da0%9FqXLgfkeB;j8d=!u#;;RsS z_420sNHT$O3eN#>Vsvm29}-xazK!U+?Im45DRC4K=Ue(o(R~2jBltHGgqPkk--r^B zFQP{@AlG{I=WtbdT-LET;nLZN0CX&9SF+(K5Ha_Qe!c;CqibTv0wyJhsmJug83sgB zwsU;g;^zZ7iA*2{TE4}usGQX$&kw1R()&Z4xK)H>b3Rc^1)WZE*bPb@9Ok86Ip9-; zzaE`WPK?MJS3-4>Cn%EhY>LZSOqLFsMqZz1+S`)~N;lUj+Jt8`R``GWesZ-C`d~-` zzI&^N9Gc2fj3?uM!fR3Qi&j2D$RBF{7RHl)_mw#B^_U!cf}fXrt+T`bx&*}kKNw`t zT79(I`ru@<_%;alGz`tjEdBj_9nU#hV_I3;vxibr6ZgoTg_u;F+r~N&?k`FMY ztBil!LB54T+*rZV${ew11I2bIjl!b`&YuKMw2;bZ`ZcBac&WGmDF&Tov%u5mXa{Q{xo-`X#5&je(g99Yb(jU$D|pBq+=P$Mv7qyCol` zwfD}fq&(R%SBpmYVCkH`Z%X*Yf~yg|!4qm@E*cRA0{9UYm26i7nJoC`XRA7wG-0#n zJ}l^H(P!{ch5j+jROuA!%}xp;n43BdWAc`m7ZZ$bnpVqHuz_Nw6Y;{&-YRy0%5p7|5=;4U18tVHjC8r2H1vycx82i z@rsE%*4_e;0(y&>w_%bM%5DytjWH<*XGF}bKq{gGhgU#v$gR+(_;^jc<+!4Dw1~K%d zb_vt?pKD0!)-np%F`k?iUH0uY&#M5eQIZSuQD>Fv!%Nm&D#TPdPtX}_?G+Lv$@{m_ z_a&j*+f6UMY=XX){O&e=9Bk@0-3`0Curh&WBOu0N5|IL4qdwMXP(ufjSKhgGOr5VG zI1HvB9c!;b{9{A%g$WSFATKF-CV$mDpptLFfI2r$Akd<4ZT-?F#7TRQOw}hah~W;E zIeV8X`3nNqWJAin{ZWKJpt0lOL0Qb5U)#KTQUH5{&L9KR$dCkEZ&C>L#PEkS~&mKHV9Y{4q*uZFUStJV}@Ze!V|)TI1T zDFln&w1fV#ZeB7{qrmB3=56`WJoPD;S0;eWpDMzjXWc()YIc{NanV77>Fqct8}u|} z8)Bgw0>2~k^*$2oab+#2_Vv)&eETJ1qyG=DIFA8<1&n3e&EgC?AKy(E*|aDdRS1j0 zmCHi|v&*NmMVJH}L~&*!s)y8pK3dY4bo<_8WH z-^!r>LsDc?gX!_MjW zZmKP~Y^W#(+zuM=oexW5Uhve3yx7&Z?jX=bxhqs<;)s0_<7elYyTccO8E^HX;Pcwl z|L)K){;z1?FeI$))_?}qB-w|C362|+Xz*C^wlX*%J3KjpY)pXtFRW>`k^Kfq*%TDF zZkS-lWO62X#sr9Bd0EOQBe7pQ_pgDqgkqXkIm-99{GM8KX@-c3Op`SAU$zwy0p zEsy&dPC}^B19p#NEd+LDQ*lr7ME}g;<8*BdbU0VY`_kwZMW&f|(Uq^XVY`DTw8nT1 zG+fRVY+`G-DNJ~8Nh3HdtQ|5dlry;54|nsCWw<{&{E*vYAQDfNPMXmlL)--{hW&z-@8CxIINYWV}bAdo5svWqlibqOILbvIcakP^M z>p~k5!QToR?jC!$&8{rGtV;t9lzUfYS=(;diIQ_jI)c)|vdKjF_yDZXK+V142DMG!)nrgu>u;9F!6ntAS#7=`)x*J#6nD?xSY?-z zEO}LRl8kMX!%_LQXSF~$QTddVcAglBv9)``(MK^`U3|~OSl2uACha*El#fBzJvL)V z13XG3Sa6iK+_3CZradPpt`?fhvZIxWFzFp*=>!>*=4xKR)dYef3Sq?Ucm0ExrN2=e z3fF%OzvI7Pi85e2-j~!37pQDgLTFsPcU!Y==D2#y`jA7ZrXAE3p2g%L$+ z&h&ezc^a24mqG?pj-WFx#6y6?E})dc_;xK_m+RS$0UZO;xW?2+3b+uEo&D+DiVVh^ z*&3d;6k;_xtP0D_J#2$I-WFC@z9%%_M@V|JRxzM2y)H_3CeF-@MiY6OKOT?@oy(%* z+KQ1TD%{PTeeC;|e4XxxfVbzl>qbkj_rmbu^tvmU-$r{4Igx zD>PVRdUaJHFEzs8W@hSct<5Ta7)GIk9)V!D%dB#;CoYr53#w`9$M3I_J~Qs)t9O16 zSK=JNxpmI0ibW3cNKC@#uT(tF4EXchc`XNjWRfh%HuMv`I$=SGWLOM#WpBy%Im0C( zUZM!!9}M@S6UV!!cNlbSa{_*rj>>TtaETvl+kLz7(sJYXmDloX6Z<66#%bS9c~X}j z!GE^tpAs?&{@tqwEGeW>%;1;+kaC2^qqsP*+8|c?zsHg0{}*<&^8dV7+Rb6QK|6`B z3C}!4#f0)R(dc)GV-k&VMxiLv0WZ@jT%}wLLEz$^Oa0+7S~U zPZ+K8Uay%?fxz5kTZCu-jNYqhkHFG}MeMSOOb+>S59Z#vW$fuAyVRVRt9@m1!6m?* z4rHf1cTbmqvpti7r2O%*pgF-`qu11sOo zOX${WLI%s(ztqhxE4yRccc|B6=1Ql!r&(1LnOaxE3PV0}a~r?&c!&sD9x;Ua>$?by zG}Nn@GixsW+F-1+Ldeuj)DoQDb7G2uvsxXuNV9IcFB{2X-+Z&9s7v{8Qd41! zFpd9{rIKUu2k}h>#d8*>f=T-qjbtxU1g2sWqPhEKNc%f}rmXpj$nKd>p^?_EnT5~@ zc0`JIhQT<>DGtG)K#00K$?wc*rw+RYYG_5)*JN{rx?!oD!y;$zCmb}auyP{28hQ-t zP^6wvgoO%TrSR4`fFFr&8;zOTmy|s5uQkx8hQt<)J(k58L`PVVk37qZXM%XngX|!e zl7+$dR8?!Lr<6aj(dt*Q5z`=cdSJ>B8mDTURnGWJvU_^LC`yMzv}@UJW8J};;~ z%xcuphlIXt8)(EXCb5r<;IzJ|Vf$F>nWyz;K+bhl^|Gq5D-~Q2`$@n8@pI*M$wpUmIGAv)5$L4ei9{=HELe^JXQ(#hOjb#PAH0FMgQzAs$bjdeOefW&YJa zF%kVx=Q<@Nt#@JULFpsxrFNsI1ZjfS;eLTZ?>@d@Ll&)_e#H|=2LqKLSn~Kjvf0Md zy@c`CwS4+!!%@hea}f{7EYu?#XG=uHGa*gp~}-mBqHj89BewS%8gPc>*c+xcps zWHnxNLdd)jt~S%LxS#d{?9V;EL&l}S>ity2S7Ne1$moQduXesu*y9%U@-?77)#yFHD~ zW}wAaN{2JhI8qYzc7QwdFq8bP=+;lD_QsdSA-6fuq# zf=yWyzQsOxM74dAf{^hgP$!f?^(>Z_l3AJjW{6@Ci zk9KCrh6V{!0uc`wRp;Ho)T-ykS)X8r-m8n`zTjYWiQ1eD@ALSVH>7w9Yn36b<+$P!O{y=)%Y zaa|mpxNS{rG}GFhX25E9C}Qt7jXoEc{W1di>H!QXi*?N=r%9@QztomfK|7TGK83r- zuF+y@zXN^pq>*H#+KN2<8B#N}s}?h*Df8EEMj7MwLl`dMzx~6KoFsXh>#94igY!C8 ziO-+TO2+!CZEj|OLTUW^d{U~wmwMes{J$srtmw&><3XsILzN& z?XkH{Hk05BoxPh^S!HN$C_k)Dh2cJ(U_D}$05X*7t_%>bba#s^8UkT=XE^J@a9x}z z$zbNK!Ea61ii(pN==2BSCYSysOoCCV@OSRD=aHr1!uU+=d&3bj@~1n#>{T3u@6xDA z6vn72CU-tc8&PXtjT>`LUE8s$$zM;c&C$qhq?z%#T42>naw)7GLdASv_mLzAthyPt zvZ%WF2QfZ|B@a|1E?DU4hb^&Cg9$pqStP`q5t~W><&Z&L}Ro z1kZEJWOz5V!0eUJM?hPAH=q9sIzcGp&@di7`%l_bXz>r&QzfTb;F$=MVl?h_-}_~K zt3wVk@L>*bL%u^I1KbdkC! zi)8)YS&fB9Wf7wArYlF+(-2X1f$dqtWfWX_R5+8t5b^S&aywhCL~r<8QK)#2xorzc z+n%Z9PED`sD{cCl>+z_LI$lRUGr~#^Cb=34JaeW)Ii{g_uI;Ngcq`p>88LC++iE5|t%It9tV7 zh?LNUvfIHzvV3=aIEL40*}dVpto%q)J~7a(XIOi)%H;O7?l%S{p*vUo;EHtH0+JZo zWtpDoYkY43Jrj-w3`?8BnE1zAvX_Gpoo?;;=@OOT3$RL`$D*d4SZh z2VucRR_d0AjXDUm0P4$$hezzDJ;UZyd+`<5j<@V;9~k6wFPf6JKQlosCWyJ#-%MLx zsi<+ri-5noGCuP~qnkegkp`3maH`RW_t^h9JJ6yd=g9W*h0~{c?K=B;?yQ+%kx8x_ zoz^^FWFpi8$Ec<8IvNhOU$afF(tDNofe!zWggu0-iTPb>X6ClOZ?()b#kH`Lj+-&O zaO3jfarnSBe!^|zis1Du+fDV7%Ly*|ex$X$VY0D8biej(`r_xeJRY&g#FF zNl#z7@2moGHlXHW0ET{nPp}UsjQv#FG6KD1hcx7)-NL1w%~*sJ;cg=q&PECn9tT&r{9idM3tM0R1LW24AHD5-gkVZVVL5AvOR7M*=f_y>y9@72le2uSm-#)X*r|a< z7f#p)fp}nu%cWbLqZmFwW@7}HeJRc!eVE6DOdXHH-Wih>5<&cLQo8(o#BF6pl#uaP zc`O%7oN7m}`iXg%M=au4T;L#aEL3I8=ZP=d=9%99nEZ@mMS@3|aAc zc9#09BCCh^H};Q->sCN>?|UQq0EyQUd)0D4?;dOG_+eD~TN$pXQXVU6P>w{8busC% zmoEiZ*6s=5!tzg^@geWVwz^h*z+SvuVRGPv=S<}MtqzwUSVB@r?9Z8@hZMM;~1-+{l)w8I>mTQQ5 zAl^muZe;Qq$}(!Q%OrXxoI3+{PF3j@;t`&5JnK^1AO?9fh3+%=Qvn8umS~o(qox1eR_cC5 zR&cAts}`LSPmzD0zSqH?x_V%YlM)_jnBTU1LN9g4VXJV^GT^Y?_QMcP0PDYqpf*JT6P+Z3S=%GZ75xjh4 z=MprvHg&g~43qQrFX5JYVk%px*D+wBc1X=Y1xPCpynC04p@y2*^>EnEiO1*K(g$A#QJaX3zw0#s^g;|Z!(}}xj|i5QLvd-lTc!}sC3>|{?t_iM zhp^cAX&<0t$G%z3xTC0!o5_{Ehyg;HWWU;`d;LLjh2~}IzIc`bH?6R8k9{gI;`4(@ z&d=q0+DcIx*HmCQ?2KGjKPK-i@5BK!rc6!~(KU0QRYp)LTkgVk8DXl8Wha!D$7WIg zL7UxlTv#Op3SHv5$D%+96C4p9c~ga%*jlb>U#?rTR$s$6Tug@+i(jO4^Ah){uRX&< z?f_CJS%^645Ip)6pr>>g=~-Wu`2McpVPx_eILA}O@Z506$EPr{k0QRcYe5-$!+M&Y z(R*C4YcfovW^*2S2?>|NIQmu$*h;?s(xLAY4PBUGGNJw)_pY1Ed4`_wW4dzBe z(OL0`b9$H1b%fBp9^yHKxyvmu54>r6Z=^X5HgeWAk=)0_)MN0AY|MbIU+vb;%mCBY z6nX?_)Af3szwQx*)+FWQHhuo5(OqVt5)BajIdhv!Lu&@K5kvpOv7f2i1zZ7cyAO8~ z&0$-3bo}y7&u+t`WNSAaQ_A(|Ko;Wx%^n7RN20PMS&S{eR|zXs#bpamdI&|WI-*tjKnG6o2+AY5#(jP(h5X)m8cR5e9{}ktcYIVOw;>6Xz9rL{ad^><+!DYL@Ffq zHC_K7g+p1uk{w@|fwuhla39uw)?#&U)!wh^^cn_Du5!Y7w&*`oRd1ZMcci>84doll zJ8C#@>jxxcx;q+*l4z6FU7dDv~`|@{qpp<-NX|)rpJuW*=M1mq$_=p`dEr{yJVidfJr_P={hW$tA)U zh=;rYPubG3!=vQvwuFK7UKhyJgV_u4;ifBRHg__&*p8O>l1e#Dh^6}1vx!)8tl4I7 z>y*%Ws@-EvS3Voq(JfiOUn9@Sm{K`L&UteNvJJjtJ22cmFQ_T$f8`P6xqR@MjY3$a zXV}X=1=oSQw`QtV9^wGM7@$1A3GQmVxCwrzzCavO!%FRFpOilH<4QVo>RU$d1I{)T zQ&sq%!DxA>dcDWBxrL(DTnE74`k?T$I<$))GeT2ra)I@vKo)=p^WQYnqacIEwY~Vr z(>ZsMBjIug!&n?ohyUJ( zUXrf2BOwlcv^14}vm>G+`%yEEe<$2$?|P|kENsbkVo7twj25A31y1xH9*_p(!D0F( zi$rWjc7f}rVY{iUVktPL#CaBWupg@xsfD>I8ltnLZMF(bKlNgP6h9*{vAULoh*<@x zwDFhH@Pll5V*Nx;p1V?AEDx@DPHD~fLGRAOi@pl8Nd*JM-z1nEc#}51D>;Gv2_Rnn z)*`I2UhX^aviz6$%%6UCS<)NcyB)b55j3r-R-2z7t}?b-r5#2Ub*ie{9XtL%hU~p{ zc`jPJo(JCK7)*5qq4vxIts&4m9cvd9ib7`-N_*~@c|USaNFChC<*5mu_9j%E zBwU$aM`j*S;Ai2`>jnqdRI=MoS2zEJOz7M>Q%g?by}L-~;X%fOCEUBb;n`}qClo5F z_Aa?@lB2g9?wL@L?{qX)M;B(2YLgJBy%|0=VZq1JNJ){&wI`; z##E(3L?efBP+nxu1m4xEa-c6IN~xTya{u^4-m!X~@ZKTs)6dVUt?{I|W?me6prgWg zr@cgbJxH5$L!_hMsd~|_+uLlvxe;txfwcFD)${S6IP`iAOeE;L5LXySckF;d;VG&0KBTJx z**M)=BGE6x^-8 zLVh~y)r_z)N>7S*R>YAiUj}5FohJm6|3q1!CL0buHpSX`p|v5ro2pUo-9)EjJ+5Vj zk3xi=4ML|s_c{D35Mbv3E?zf6DSEDQOlH!76iB(P3-L?c~4`)Qrq( za{LTM>p?NXCHC~>^!jgG(vt>8;h%==UElCOrdld6P{I9e!JoO%^S_5Tzy3pgSv~$W z`Cs3xQ$rmymmTrP@4Tqs@2uTx$T7vU6%10Ah zi2tu9H7StyOgAkPAl}ONR@AAQ3uYgP{7jEGmB~>A;vPDPnT44(KL`Uhk|nGAg?co@ z?0G;LYH@xd<{;*b)j7QqEf8WIz+x@+88X7Fr?$8kpV33sLGr`(tDt3!B4`3F(G;5x zp%C5~hDY3NAB|$1O}_-3Jc};a4)@W?$T0XdHW|lWrgExI$d&z2+`u07;tO8xTyxXc zYo_V6A9QOAAk{!mqY~?nv!z>>RaKN#s;#ikEi0tBJ7g9nX-E0|PzxkE+Fp@pildXG z8|UaVQ$m9+IMUg8;PxV-fBqLsS2d$k29nQVF^0gZgaSAhfAXS4)cS2tn!a!SHcyZ! z`mhqL$Y`iPyv(4qer#^B7I>R^89iv5Uf^drl$c$LrCm}w@^+rV;YYd@$N8al;ZHzp z7FyG^E}u`{+_8ecj4aoAOP^5qLbqXt0m`TurBmgkuaPy!di=8$5deF0!V5pDQa!8q z(o`9UlO;xu%!l=u0 zRmwh8q4M=(8$G0{qF4MP2khIdbO!HRky&k>i|Ji>TXbG(5i%#88I0^%;rilzC2ZFU zu7Fw>78ksjz(+Q(#(oLZn8jg6%ZYsnQW%tBWUZ&~{TE5iL>Lp!*6C6zl=5N>pQMei zu<62JXW1+lo}h(Sp7f>}QgtH~C>=CXushPUy zgi+(9z^*J;aTC%fe1J$88&Ju)@^KnHd`d%J75$dcASCuGlg2dP+B<|Iu-Af3LF-|F zxt}qBPdkg^V^x6dZ>!-K8E0>hn=MGUPSZD*5;$ln#65hqOs@{Br^Sdq3p<1_`udEb zG12&-*@2nIVe@{-3Whbl)MN-cQlF6H2={br&swXmcx}J^rLjHjIq_v|Lsu{iUKxXClQlfp+S7CXite3DIjsBf9~ zt!q7DSwr$wD7&G}pp=jQrK80j$-n=Hz3OL|0h4p~&dt9@k#>uBz*rDPEB%|P<>al~ zK%U(d%WO-Mhw|O2&e4e~m|C}BMd7zZUC0n?$D7cMXT)@TMcKO( zjo<{Q<}1vzrg!pgo+u+ng^(P1ZXQr<#1F*Ya|$_YW4is2nP{i%>kGDI%bfQ)Ve{JZ zIv2EXjSYX0uY;lCdW`m(pnbFU5nS#>8E(xfa24_T35f?%IHH3&n@qYb1;RY1N}9-n zodx!Gpu1ko@>=0!8D9eGZ5q0!4`pgZ1UI~dXR~}K zs--j-joPkT!YKBPxH0}d$IDk(kQtftG5{zknPO)nnVm_ydE#Vy^l2R4Lu7YDzUR7I znu=Y)N`l9U;z8gUH&1EIZvO&nj?}z72*lPG$ZM&!we#$@SuIPA8$1(R_?Ex|60;nK zLu+=eqoHyG#EL4^h7C2hF`eGuk`<`iGV*-_om=6*juz;eU>$rJ_9wjQ^TQXlsbEjp z0LhH{OW3k(@9xo4y6z@yy{#HFF{+zl^5%IPYI7(8raxe;IYVq+`up8Yh4lMkJM)Ua zB4Y3bfa<0|#x6qf)NvI4c+sX=*S3y;5^Th)*lYjhtravZrm7oV=Tj&Am0EE2olr74 z)|R77>6M_SG;S7y0z~lgR_*xrrF3X_e(qIEaI?t+;W&PzzDmj?sLS}wv+xcnaS^hi zC|D97*svE@3~%cbiV&6u+C2MAZ}x|oDyuU8+r{-3`v6_!V9*Pae)|BDJpv86EIZpB zLOxq_>Gyh8bH6#j2;CMk8Ho_#**))X?Eb>)4*JbTr_M-Ha_H`z@b}W0mSqb;s)307 zw&OUHBITtLKK?M)V!dJ4F3=#8AhC5%>`w!~A4+sHpoq>75k1C0rPLAogp-6EicI56 zo8%=XMiTVVp4x3bIkjI&(S5H-&~vs62TC^BQ;hPg-6$H8R`fI6Y`T=*D|wH7$C`3= zEOy?)f5s`hm))R_!i8|zK1qsu8bl&5++*iYo=q!#&Qad)x-;>Dv14{y+*)T-0u$&p zdRK9)_6q~gO~t`$CK?VOfBHHx??p_)E5$;wt5|d7kHtr2TWpMOI2Wl_qwY z+KnOro5-2tq@U+uepFcHDuJ)vrvdrD)PL?%a@Qtw_edaq#;y{yy2YgZw2 zxA4yuno*>S$n8qVQ-kbaz<+RSLEZo2wZU)-Hof$VT>Mh^a9gzXGAZGc74dzCze{02 zVG@)Y%7<&mYxZfoI)oA+4{W7f4RBHqf@(W?caA3X)aO|T0-U<{t-z6a$j*04c9p{r z{MfE;_7JKwx0{aEuCbi&REv0 zeA)K^7Bb{s<{z5cQA&^LeJ1I(Loi|QkYyTcZ4!$T(Gd_?=_0dUu=E-9GjRc>yJJm*XyiI&r((-t7Nv0x$$Y>qb7O5CPwBV z#$%Vs^&;ccfb5|$ZcficcJ9r^#S`FCgVKQ;p9-2h^>I;s%cn`6s14cDHY@KZUu24K zjpi3Um{2-u@1$Rv1V+z!h`vfjyW{duyVJkU{9bhR`HPpR;c#}WLhKOH#H(Kh!Q5R{ zYE@j!6{x*f=Jmo0=M%-NPL+@xD||f3=YV#=g$c~c_q!mKSN#cxN&Opi^%mi^Ri0=0 zA(bS!0r4R8Vzad8n)Uv-KZ)o848}7g2h3;hEXa*bw4$bYbN_yCW?-H{t4=EDi0S`kR;+=&HGebaptf1!Q`d(Em!S#tz(oE{tb~C zZdWJ-&L+k#ET($@D7P8T_}g5{R|+Q34M=QxK|3l|yRMf~W{AHDmd|-puK*OnA@%I2 zoZ8x^B>j;w(ToYTrYrHY;!+_6T_6&(*Y$3V$<(`6p67 zvS#Bm?iUVplKda&pS8Y@VU=Bv`>lOwZ17R+pd!#n&s|%j^~0Ju-WeXD2z#6(1CMfg z@Wi)g)|setWX8>Rx*~#b!X9zfGF_zvudNKHnVp*f1 zV;|1ZZ|$dVxft@7(O6Sj2C~Z^UXV>R4)LB0W1&>AvF+~Ru8Tg;eJ==4kXs+KJvS*; z9zhb&vRhloY|&kVgo#z7T5U1#uOW@U&e{6xRQXHp2A8-^P0yMiIrcS7+v%UsItabE z!y-w@%SH)R`fgY1dheRi`ES`dW=jz~WnBd-)-(2ba z8i=eQ)JAKL$KvY5uxah%uAg(P-R9?Hmg4L^YDuAasTYE#?_FyxZ{x-rA|_v@yj|ww zGJTH}Xxe>QLKk%Elwbv~H?s})giPOOI_=1$30IJZOkD}RPALidG+ka4(&ljGb*RQ!Nv`QkPr)CGQ+O)wY)3WtHYtmz426Pi_JG z`QlpruMZsw-QA=mg!KOKg+WyH0P4%Ee0#Z~Bw!Z&tj%N`a6H5Il#TR5w2*P~ujo_S zZ@)-`%=wsP$5Cgs=~>nD*yy1<0X~GEzd^pDxq@gwwOJ*KbSNw8@NWR^<1L8*?H$+f z_6j+l@g&>RoI5cxaJTR414qgJOZOId{*Ug}Yuq5Ka#xRY(({DzUDXB zNJWZOrPOs3?|ACDkX)U|7iLXv{mI2!Dv>J;cZ5RaBi}8F*e2}YcY<1u-!KF4`H~}* z8INN(g24glt--qsXqq1}%RYqXta2EDGdRK?#-{vAy5WaIKc|YWmXCUddDSQkMI+o9zF}Mo*w2&b|o7G34jAj2db`@P z_%g*o)qCMU_~~j;md`6VVLuvomOk(0{TsFU;@GD4A%ftP>Qi^D&?|e6lrKuMWp)Np z#3fY;|0qZ9)&=x_T$#fz z!sgtvj0Z6tmIUx2B9PqV={y3#7xpX|f> zRzIkl_d{m!5{mc`1#p9k#jk!wgCW}Mt zGc!Mvk?#&1g}diN=4^P_FG+Y%dsP`xCA#PdfUMr`@ZzgMX&$BHGYP>kvd7^r#X z7i9?YSQ|=X(s7RW<)iw7Vj7`@M{7|4VtYTP(DAOS0N-NIZ4a;03>cTFsx#b%wc&0) zJ0b*%OdVF~v2Ns)54Ld{7!p~H{Ze^GB=F+yH$i^$)|Y`!3eEa}TYs|#JQEX?cJCQK z$r4$b-q*V0GBs0Nw?}zMpKPj@#I^g>;3UXDrL%KPVw>}BA=8>Y9S6Yw0^YOCBS=V| zwm|iwCf?~MT>zgl6tjBAJL4{}y4xM!1#;aygpHd;*OLrlpkpRX-Ef>Zn{%=tUaH#M zuL~7X;@gjAC8v!Yp8IyRKSsG)UcD|PD@x!)>^Y@L4P@dSO6mN}sor(NX<55TeyyVW zZU>-l?i;ht#NcAurF{&9bkvna*44wn%Ny0yl_-a~?c4QCf`ml(+17%Uh#C~>is9X$ zzwd+Do+nQOZx#CeHmJGzhYS4*Fnt8qfIk+VkCyy*b|#eND;e*|I2LtW zFP=gbhOGcDYnSuhk3<5B0hOFf9+lTQv5MuFr3panq0wNDu1+#dP@G^Wm9 z1e;%?e$VhA!ApscHeNli=>9VkWWiGP+vY&hHQG9HvHOI5HbZx4l4zusT@ z2G9us0gXiqw|oJ{7@^ouxOx%OxtaJVlHQ!h~5<5R5Qe(~!nd_B zg&#z5%kN4PW@|6Q{27?TVZwZnGe`=b-F?E^Q%`Egg<2T9}wCEV`d}G}GaDE#Nq`a=|z1vALG7-_~ zPVsu+mzjw<=O~PLI?Far*>=~e_q+A)zq3uO+A6h~#f~-oW-j}_oR7FYpw*{Ih7)O3 zbt?lXj8m?^SHokIg@ZL2_C;JeVHSArUt0T4u7E##`5M*xorTAVM0oH1tQJ`u&`>IS z45V;u(=G^XhYL=EI}W=eqOuFubGC+N?rhKz){OU_OOsr;yAnrieipE3ZmL{uk4BGi zVTj_XeTzw*IRE~@q`HS1@|&IUca~Rl8=7|VhR^5`ZYC;Py^F&j z9xjP5UoIW;xS!YrOx*-(-k%T5d0fIosmViOat4 zf}UW-_fSoicDVPp3r8YIUoNOHPEYyLBeNa|4xoS#J*(`iZA$WlCafgpJw zx-S;-hQKYDfU=DIE9XGw*kg!R$FnXtP zVUJbF_rsB%t!s2=eMDk;VhSoYHubLvm|x;8bxO&k`7sTD7mkgSYOfxNPkY6SWV7E# zBHB^{Iq1N&51%_FyP`O0FjGZwOdfO}+v$=fWhjSCpB~cV zEm9~OZwN{W1iVpy)`6%Q6eS7+@zA~9>`Ztp?F|UUhNG{n%7O-h_}?b+HP>)x820`u z)w}Sh;1d2wvYG;*OGRzu^wa+&aOwU}D0 z$C+Ar$DD}6;wbdFb{vOnwnn66n8)>FiD`-j$2y{Wkyj*hO4sx%l?R3R;tK&kQ;I$= z6$M1CcK3@2ziKq#{HrZfG6#L%+!M58ifGdz6}hl`G)?8fJA!1dnpDiTG4{}RX#0%m zi7~?89J~1M8Z~o2O=ovtGC zxx*NRuksw7a7-y89&^w(hdXm%o{7g)CBJ!-mI007Fhi4R|Giu*uePL8n4^j7S!#|z zKOfscuXW%+r7U0$PmUgFdWwH!K#@h0o`+Hajcdy7lB&c$Y(Y?Tm zryQ-f?gLdO_{4fHJPq^0)}BBN6rrWNCnnR@)bU}ySw@4-WcA({-^V$T+#gkdV3}^K z2ujCHc{I75{Rq#gPfNcJzc&h~gi!Bg$8ga>w2G|f%uS7#maO=QS@bkfWd34{*4meq zJ71~PoadD2E#^7+q1Uco5_`~ATV)IL97M2k3tZY%1RCz0#J{|{g`OpA!aP&@mR+jj zO|Sg&5DqVzj{yqBr%Ie<7%t=F6CIq%(x1ppc;3!hVZl-9B7Yi~ox}kSGv``4?9`U$ zF6h3i&nG)nCFSF>s?|hRn_4N(sCQlBz3H=JpLs%a03&ZXPbiGwf@2I=E&fVXT(bk@8c*tG&_C^^#)*Sp@WlshjI2D|;_&L>Lae^bs zD#4nL$ml(HoqO(Lu_&CW8}IU$-*Br@;hnAtrPGAkv8;4COnX6 zt1T*v5Nl6ENyOV5i1Su>_NptSROUgXL$Ic<0A=-$izR}C^!;0;_`FhGKN9HB%8wi} z7z@7}?UD2Rw8uotlp|d|v=-DIcPc0Ml$F1l>gu7#M92BKwPwQS(JSpLcyS?#X-rk(Z&n zxA+a(w{(#xry%ELT<9fIX`U~ZfK|`)JL&=zD12vF_7NjVf#l6~R~)0C(I}_}0=TV( zlPkJ)K8U5io_XC%mYRYjmh4Lzj%S#wmrym<|IY*1)E@`TIXr3XYRG^1aWIp*E9vV; zG=7qD8#?OrS^Xn)#7qD%G4`gn>kn7<2kx}~-!1){V>elUOoi1ib5w!~;z9(U zt3L>+oQr+A`;S9OUyShoW(L|c3()}}!{^mjSEW~hBaU|It{#Ph#=gV4l!qUsk6c`O zAlh<{di_318E?g|!s=5dYSL!HpQ$uK8H~aY$B;a;%?^1ziZr&a`$JFNGR&Ti;Y0{b ztzFY5%cq!AZmE z<;6%5xVY0>5fC6~uz}v773)czWefUFLbTy&mQ~SG4QOs3s1hl(UN&G-&<%f+bq+wR zz8jM5q|1|s9O%N~XL!T7FAqBC<*4gw5(uYz5yGzRi zzSJ(zjg(9?AjjH-?bL|;BUwkJ0pb?vS+{)7lBS_JIg^k{>?W{eb+ubuaN<&O8Z}~# zDtT(d@P@AgMV&&|r{cIKm!Lk1BH!%rN-%(~mb!u2E=UI!H=t|eP+j^t5~vxCie4r6&&L5I_slXX;o!-)(ap5F)?_>y%9=_DB)0i>6xmORy*=V zD!uJIjvLH9A#^yGrV8dFx^G`PBhIKjP0YvN$zw8g9I-xmP>2dKi~#YKpL2QDr?TxWr0Do@acvXY>t)7tgdqR{Vw5_YJ?_KEE7 z7OVLICDQwJ*r{%Z+JV#pi#X9>!{MbfGxwvYxHl&Q>{B}uUzR?(r<}1xeTq%UBnoNs z4neb7aBiT)$v&DmqXWz((2*jc%3&FIZ%Z9@)w>t-HM?ZB zo4oymrOasjInm3Hb4V(8Q14{GJh6Ex*isXim3>n~Ssi%Nx%Ykciu8cy&n^1&G!WJ@ zvHb1(#WIcj*kTDY%^%7PMxN4+?xRDR8-7r?goj!SYktkjH>6LPc$qS+pj9;NIH}$E zth%HvVM`v0ZM+Otk9(3px~V#L$Rd8>rlWbf8cGQU;-$6UfUdnxhWXm%1*(VJp5%u! zngLU5&y7&!r+vig&%Zt%L!pK89z7at+GhzW$2o^zr2wD{2^jE9r2GyaejcCkptL?L zCX>R)Ys~ytDfy|F|1Y-K-wRW>v`xJE&`rD-RJBW22tfWHrg_>a9Xh+e@?d@UcTcwF z!>Tf+eAF!esgt(7u1OA#{R^i`ySjBAt|-8~2?u|UcwR1ECD(AubefjLmAQ&uc07i$ z_m%pIA+*cAPS|kz4|R`fQRL#wp9x7N`L0Fb`ZHEOc5oQB2`A$y+?OMw8%Kg?s|vt> zQ_CYKwOR`TaSnQJg_e4jCMWyN5#jS9ciG%anb7)IywOd=*%EyreOU_05!Y9VSbX*T zR&etwt@={-fUjI0iZd_r>VVJPZeglAEAdQKi!$W_m^Ah1r?OXXeAbNYjDe#h{#Mo`xw7A$3u5Ep`EU95t~ow zifKhbylot8B>t1AFyWuUfWubrtSt})ik@_P^tF1>6pp#^`y;4s?Fce+Y)y*v9O*8Q z=NkRtBLj1)N8P4VJ=w&7W^NZ)R7d`^(}Z)`0WNUwUa=t=#4Kz+8tmY+IkbZ?GU zbERyev<}tsevBYk0+#VGe~!pF4*e3BSoR(C4!XggP7-&)eYzFw4`|kX%$o~uEPbhK z%OhiOscr?e{B+%_Z1#LfS<^SyEqC^#YjWFUYQFsL=r37GMXJw%>A0HpvHh!5LGw?) zKjVEF6y(|?4bF1-HCvOFq@;{al)$@kl}?Kn{APb}fz)};;#`%WcU48mV|?Bo^E7%- z^#!l`_&SbgnhgJ}%id#$UCb`sLey#(E%NTVF+?;_fa3ha8jdFOj~;@&lo^ z#102^>2KehOnV^8oVT~=qP+*8sxXO(W3jtuzQA7HHC1Svo{$kL5(cNzxCzjUZ!XZ) z31yGl;yEQDm+VFnb@(q&i9H9_cZ|nrwo;$aAGSJs=m-ln54G*QNb8~L;Q3i?)uw9l zY%8fx&%%V9%OTu?8Ln~-Dr8Bjkv83cn8*8dzhrJJmRF4gASqjT8)(zv{1bcukyDin=sKAq6^LW?Quy zM6d^RFA)$(5y<4vC6C1U!iK$B);pm4&l?UD_~K7h1)(t1%%8WnBn1NQ#EPmS$z z5EIrtItsf_ix0c^P?!E8_B(Asf_TNUFN9Cow`~|S=X|l`s$}D~vDu-vHyVLkMy8`< zEqjZ{)48R!ud4c@`d;0%s5kppI>I#toh#}Hkxn1G{h~NS60J?cppf@xWb0vBvb}Q` zRTUXAJ}+AocKFT-AW2x$?yiODGDMZ*X>{#yn=uXHfP}G^l9@;m1G3;#6uL}fSns#` z4A!H*czPoVSlVgx84liJ8dbO}{!Sj)wX6L^T5`6-heWK{+mSl6F&!-&b?arelYuAf zs4d)-Xt5tfUSgz2(qI{o*`c8K6=Cdyk^6=bjPcd&FWF&W>itR48$0MJMMg!cX^8X5 zx}3Am_9wbMD}Ck$jOGjxSBJ|W`QVT1W*K@6`uK{X;6}mXWfCe83SFdnya(-g;T&(< zx!*)(n6sz0SQO{+{Z5lPYain68QX& zmSoC1s`1W7$!{kP>9|K~v`~k5t3>_kj9}NddU8buE0T#u*Sl%nNV_3vV!#E8d7p1% zr*nD`m@A1ND?fe8;JdY8{8sKeTC@2<7CeV@<_Is}1pj+7u=?ynj~Qip=L;eFQ3E{B z+K`rC0eZ34eNDhZQQ~X6cACKF$1CLO! zZAlwr`Ib>b?P1rP-iSu9R5V}1`i-y@Es$<`(&IR5-tVraO2{x{Y?yM@cFau0@h)VN ztjzrfomgje1Yg*pHb&voWmo(^>Z-=zA48REr7^xDhf+`3G4vJhD{HS(G&W(x0o7wNl**Z#DdI?RP%g-7z!7hEa@Mk$NeDuXZCj7jNDqHN1@NJ6sX2 zg2?ZhLjHkr*E!82Glr%EoRKK=d`x_@5UUV)xg@onv%`KCuHf6|^}Ecs6r*{#T93Xu3s+hi9RD9-Y`I^)D`a+2DE ztQXZ>4SUMZ>o@JL+bj+?`Z})Hpzk-PBkBEahVjYVd6gmXpi zB36N5N%Wi5u%6(UtlTSyai&%4LOi4|@?2LuQD5mLivlA#klUz_naRx6whL%8xwhmg zcS2nD!M}uX`@3T*!sUf?uw?CKsU-e&`|+-*Zuf;5*FEY(K;JPkf}489D4xw$0EqCn z@0uB97DV&j-hUCd1`5U(7C3}Vk5iu8fI)YhioYWyuq9%T-EJ$+1y{>|E zUXOOZ|KtM!{UN_$X87SPci+;8FwU|DWfO8Grj+xKReX^Z1gZMbbuQ|!fCETM4nhXr zzOQF)-)DNo&4ZxFOk8K=SvGO&gxLfdI(8$q+x7}ZRcTs=uZwe&Mfq@s*UL$T%A6Se z#R4LuFbHMZr+e}8_It}K`^2UCf+gKsP37gs<36ABl&=&i5Q_@qo;8yf8;3u(&9x|< zi}fT`ClpSdOEM(0&OU(-vUF|i_k_LKMND~8HLl0%`AxYg+iSPUDNJH^WF|X3FA>{) zvJIjEsTJ(T<$p%_8stWcn4rs}9Ld!$d#N?Q*lK}}#DkYF)rV6~+urv_O{E?4kCeZk zm&Fy|vw9}pN_E4G)o#vh4P6)1_3}x3-Tg<-j$oVFzosJm-aU;v0afKV3)zMTp61$v zpS9>_8KpS2#@s|XsGwINb);_v{_{^JDxOT0cuS7W%jf_mvGWTW@RqvWTRNy~<8b=} zHZsDwqyV?9VvwckH==@ML~49T!yJ9moz9`_53(yEw+P#a!%r-m;2?M8Rmp!{8XmA3I(+bNGbB?LMKFaP6_w()-9gmr==f32SR_eE7hu2xrF_sN=u zoL+sPmf=a=x~4&$_9#^hr;sVtRUfn{bm;(d*Jt9)$LV+=!Qa{>2!x>E%U2yGQl< z4WG8M_Rec*+ot#k-0yD+?Qp)it}2}ERUcr%5ypWZN}hFX0?es$70v1c1l2`!YiM=q z19&ZKtohfQOtpg6DhSjAO74{HSYjXB=se?}3Re>at+j9Z4AeOPgnXUj|DP8C4Aotl z**z%?C}m2>fZ{m4O&QPXIoy%OSZ?_{wB#3 zL+8cxbsJJOYMf4bX_Qxub$9r*+c9cKN8D_J^YD}Dn-i=cI zwXJyHU6TW$cqs65^1qM%u@@9o@a!gfVj=z~N#LpWB_as?)i?9O7)ZPqALGA;COs2L zH5{pY!l+g6kBX_Iv6C5tyb}>uXeXN=56^|VUu*ehu-jcU1@*OGG=qTIL1b8ZFAK3y zz>mBdoKmla%s?lHFK)hk0CO11f%iIFP`i6AidGTq^WU!2d5Tgxs1c^C1lp=*$w|Eg z&(t0NA6Z`&&}O4F9SRhe;_k)W9g4dYcX#*Tv=k^%thl>NfZ*EV?ykilxEKHPp7Xuu z=D*5Ca`$APot>STectVu6tk--|FtLbC3G-4++;=%LwxX zv^;Gw!4c}lCCcf&R?Ks(W=`sH3;h8no9WG`Q1jFIX0J|A(Cj+*sIZyS&E;1+q_fP?Hk_kEzxrYFQO3%~ z4s5>=3yGI;9P{$;<&mv)(RVL8*fV1EwRnF|ndw4Ey}oZSfducYvtPp4Y3Jl;29N2& z*Kbts&y$=Gmk9p!O5H7}o0{u4+)5$1ej7D9w9|b;c0HQ}Q!RT8U7o&%N4oH}g#UHc zc=7SN*$kgQUjP(rB1W6I5KQX6sH24}{}^_Oar{50d{C49zfO7k`SxppslJ?PA#S6R zQH^@QamTHY$86T&-0)L2JK8}CK}e-180euWY$bZWW3kKk*r0!4@C@wTpmXtZZf=SI zRHz=iZ&1S)Jys3G$T_0}a27Lw_EeL8j0Xme6kYwhV&1&o28jU>b}i5gP3n|o|D+Dd z%RRy;uPW9UY26MoZ8zm_woRky0jEP$I2r`S^S8f|^U_A%LG~xS8<%Um-PKQm!1Qrn z*kLIASfKD3_LcUC>arjmQ^LJA68}f$NOAI+z5J@&1`@A&n6|KPr;JHaS)XzVFk25d zr`(n%tv%akJOmb{wW>i(-sB5-rd}oLJo*zj*#t9P#_CvkQ^JJ@z8$^SX*|vFgXH9z z(Wmj1nbY{^ zsKy-&2*~|hK}5zzbg8Y{4>GC&LUFAh>kpqa_kL=gOtcxcDmWY7o)=6J{HSkjFn~*R zj_}#28c*v2;q8yq=vM8+4La=`PP+5Pr>n!npFVg`Io%{%?Lp6YWHPxcZ~m09gT=Me zDa~Rzv$m#VC3O0d$(&i+YpZ(G&zk9$X?yt7<)PZoePPnO845If^nC-NQZqzEGWDjG zk->(_Xywf3beDz1Yf<%;!#EN(dxQ|Sd=lRve0s^shz#?}$Et?{cWLWt=r6j2GC$2~ zG?pLkv9GTq`x8wSX$QjJ;q-yw_SH!0XBe^HIYPwU)VlsYz(1Ie*slE!cOcmv9I;ua zi}LIhj+WW+ZWWwBi8My`ea|Fz0|mlk5xa^u1p5x}N5#p{s?wu4srV82Z4|rs`6KRu zYvMAf_Y6oXyV?h5A0uZePD08WPJV>o-SY;E)D&UV?n}q}hd7n^G+cf)Q*)J-a)T-< z1os8i>=@+n@8v8#ON9)+q%}CaSk=piI*6!%^f1z+&}Tsm zLsIp6vnGOrU!6d9bZ%^eY23GMAoix?`_RFo$y?U(;dA(-?#2DL6$G{ClB(v%Lg-5O zpInPK1Ce)<|5Z9Z>XrR#vtz^$oQ3V6&RP|Fjr=9MCoqt6w7(?C(^5HRAa=WYcw6gN z_FjC!^42taV|rjwsbhW@KVU{8Du%X|gMNV+(4PvGPAvhP*NS@gI`Cc6AklvH{WfjX zl}j^y9<-|q@90x9{>os#&@(sjT%rZuu02bErXDZCW`Grjy|gC3H&QCA#LruqFm31Z zGi8<%@~XQw1xmy&)=MGI+A-~ZwK)NQW&>ha@-~!t-4{2%+#?xq)T3WH%7B5MjH{?)n=kAI=-fEEQ#@|nEg#_%zmSsIxu?I@Bp8C97f$J zH;TbMJe=3ko!?UvE~^**I${^`4R7O^dYe{d0|`#kXoTp*uOj{2C-5Jh#zTs}L(OVB!uVMtAw<|noWDX4 zt)NLS7v}r}_PTN2S2B6Rcsh()-L>t41MCV8#Pm9yFoTjOtCcyG9g}At^;$xK+=kJQ z345x?@kd0^Gb_;i4E-~E+y$es_2Mvg@p`|CGbd89-=gV#Xi+3TnB*LHKHCVZ-Z!?P zMqpl9MJ6bbE{dJRD&I%qOeDN#&67=HP0zjeO3UY8DKi}(#x@t(n1%4eF~iE{k>Ed{ z^?#g2L%ICZ`W`S}*r+7B1h62xzV1TT9_A1`rI%d!euDhe?^(U@XfFHa`W}VHOME|x zIsKog8t1kEi6@?_*u`Dh>oMwIFIuXX3)4*bu@|kSi0Z#s+D-f`H*^8XIy>4>%=m{V ziRmNDZgM=f!yny_9rzv2szi-16LI;$%O8bcM2x*%Dv|D5n+Z|Bb3W-z4tKDcfIKaD z!gO=7-WQCw?X-|c7OUus=%x-}6L)P6{|`LO(@xGlTF%b>N*VH7)3IS;Og0k%brYC9(EzBW>59RJZ-&)oOjpaPDKqEdRgU6w3c_ zZll7)T`{?er-(N8(07;xi;^phr&gI%(t|m_RE@rwRcR=<>onJ*Y|Ow*R4=++F3-n1 zJQ~#`urjL*6XMx9-u#!aEiCaC5F#C(r)xiR>f}DJK-uiYscrZluZEO-%oU__&DzHN!KEr6XY` za9m=M5qbNN*V+b#KOQHDEydeI7*PVE2e>Ke_YUN9cWT$pQ;2yo?o_7k= zAD;Z4cm?La^dQi(0qSgiCX!Nr+;Fx{(fpA0`-iJi>{(5C@{qrS=MW|1_e6yS{n45%`UaaoH zOLcDgUZRdy^#dCcG*g@s2e)N29a87F&5k`6hngJDk_mLLu@I?D$a233Y0KNN)Rk}M zr+om1>WcBlBiEI1-c2dY*V#Z5zkt7SB8cA`jrd%Lv2WM`pdDBrT>KVwl!iPJM%1}d zm+ULi;?V>ut{@9kW#7K6E(r8UoL?tlBW%l*C-C_~kcSYE`)klhUk>4X*eO=ZZqF8=0XZ zOon^|%83(S@~$TC#pI9h4kF|H(f1kKW_Ir)%j*$ERQrFNXr zbcbJ6q>AkfKA|-^HMK!=)<$|DCJWQS))?!}vUC6c>h^a9`r;lmRtH;C7IIZldanq< zAYy0oP23j*H9`SLIK{>fGqM`@asMIXa4eHtjLK>+FB?)L)Wiph^%-rxxxE86<&p*RlHS`pd;~vPu+Z=K1K2B^IfQvx9 z&+xGncI3Aod5uJo-;@;kR5rMB+`Dlviq6;(<$lgQ6VBK`sp1gltj{dD6{ctbYa)%U zf~IyBI>mI=@>EewXdM=vM|N_sf;`DY+N#ZPQ-IU@yY$H z(w1IY)hQ|5^DA!%;^CsstUfeoo!LcRspUmLZo%BRcu(;iq(yk?GpBcnFq^FTu5k+h zT6{-clI%ZH$m$aQiS!jh-BuNq|i8Xk6BUB_2BfGb@?H`XuFu0&iX_cQE#H z>@*RX$G?C&BoQhl`|y4KyE00v#h|uUXU8_fss4RwL4(jyN@QLjNmR6wx)?NUiPy^` z+MAqLe*Gm`2`hD~TE>o#2HRr>TSjz1NU4kY^--@0cqQ{kzhZv#v_}1&fVc<`r0EGc zqDhnkRYmB3qFM{Ee-Y+|x(~*o&VHT}^YZtC?%$DLpc8o+qXR{Rj1dp+8E1u zL0T)qjU7%p|5cT3Sr-@GLt)^QGoLdxr!GGoHrovYi5#Cz@03>c!MEqHpwKYQ_*;&w zB0W|mN??iy8pYeMN#|9|i{u(h<(6c5mg9m4XabmFg7XROj>kKU-=_1zk;6Oiur{^W z09pA5v8?L~Vo_9w!?TWgk2FI9<9aVBZ5s*=Clpz3o<26?BZ3%)7cBN}=Y)@xx8?7d zAH;(mEF@)}%s?GD-j%icpzn-TS|-}k2B5eKZ6E)VU8t`U=uTb|qAN$jhc$(TWI zxLXql)xpdD_*Zv3>Lsnd=J4#Q!8&(yuEMf+@XwhMG`snP`u43Vd6z*4n#hLB5el6{kEQ+YZWC zZt;dk$E0_5w~cMOjz8zO7A}oK@%Owh6>ZpV#~tQ#1O>_Q6wyK~KLW%*wtZ6$)<4xW z!smLYBSoQ4 zvJfcPeK_^oKo@UJ?qScFv@C1-5?8C$I^zceOFh}A5%J!IYm0u zT7tAa$)xt(akM!IkLEs_GS#!L8|tSwxiISXxU!C4SsQilFC-!`xIi?cuHTGBeh~nx zIpSttdx*9dHJGmlH0o=tYbYCrhaHtkrB-hz>}zeni2TItsnbI} zGw8vv{*THI;P^&K0p5yI`(ghzyE4yq-!wRH4{7M8cV9dpVn*?>Cp`If*n2WHkVlWs z1@0=6pC*1cCL~iFNl5HKgM`k*aA|xpe8r|qQ4IYh4H(k;B;d>ShX4sfab)w#x7zQ_ ztk*(jbF|SDn+TncXoDW}Clm(^yN=0xgieW+5icJf9-)D;>6fk@`|73CTG>+_Um(*^ z=~DqOLR8!A(WRgJr#wQEZ^Wo><(2xbB(cb2vp6S1+O7LYMq5DAPAu!eJydE+7`#17 zqGl{}7fXN;{?pXImRj|bM43{-nM0?OGK;QeA?)q)nR zs7=@!YLOk>D{&3A*Vg-1g+%;9{zAnQWkeVXhc>bfV_zH-m$+&IP99s}6GeJ!a~jsA z8kV>+1zYw&D75W`u@JRjQY6v-irq({3jRN+W9<2E$UTx#foLI6QIw$OU~}3twbo~Up$!P9eq$I!)9H# z{l+B#=dDUUi0ONf6?Wabsa$>}Ic%#wFm-+vZ89{Ev0rg@b#H@z3lMV5#wR1^c1&st%su_4!VA zQ{q#*^DwkDpl2bzOf%Y&EzpXAGVBK z)_UA3Qv-l22$6qC@%GhB62ur^R zQ-Ph)n;!4O&6-+oFZ9U_Hy!j4&{P$V9Mw#2C%+iLYQ#?R1;umu8@knJ8^=Z$dWUpx z9R$m;HT|jZ$Y$T>>O7AaDHbRi{-6jHnd*slX~bWM922;}IErZsZFBdt8j5eIeJR6T zI&GETl3qhisY_in_tGP^#R{ut?!VX;4IDl3-s5cG?|jHNrS(E$OWhuJs}v^vq}(ZC zMjAlBMAK;>H1|^~(E};@&YPSHHm-y6ms{owZ83UA7V8P3tTbYZ)Sj8F>2MPAv)(b!iml&>LntJT)D{gK{&0<6Y$ zTQ=|r2<;l2e18l?>n}}*28YiWTEd%G7veA+>EC1bh|z>yjN)wc_MNy{#}ytYMAd6~ ztUr%yf14qO|2R25xiS?^jU(#dnleC#iMrE>~YWktbx zl3cIbJOQ>`xsHg*FR^e5KeA9G?3+Mgu~7P;@@cRzAJDeHGm zS2wT!fzMUOe-c5%it>b4cdR~=To?3-PZH~<2)|mQS-ciCAk;0fWtlKd_4jd{U0_mw zp5Xm>D9U%z>uuI~Hs@OPe;q4n>&i4uNuE$3%hHBeNemX^q2eG8e> zBrrTH1sWgy)X+huQz~@I#?l@vvVVNs9_UD5xuzC}e+M$wu~~?Fi!SnQCT%JE!oK3d zePe$tR+j7v@_Y=9*{4*BhgQc!_!5HS*07gX0c^a9{G2cxV8OJh{iNrjS$5-wxcXHj zcp3;-m1m6HFmKc8HnLgQzgf2@7B~Lj(zz7NF+gDPgJZxX_{Xjv^pjwx9dF#AlQ&9L z>hWZe&$=T?4Xc>L2%;t3Z|1O1O5Tu>$dW_R-T_lL{u-|maMZx;xKgE3>QE=J9Yvb5 zE4aBkJlE9}L}tZg$F-QjW22qDyvrWp$CKe$zh`fFdU!=A-&k6iD{EcJWnkpZ#k2Z4 zuc|g1;r2lPK7M^8jTs|A!czFW0k&D82SxPT0pCxEoDS*H4S2rN=vC`0fc~cMVYbMx zuu#qK4;7K`C4jBUb}cTS5Sh~$0!EKE8B7vA!AW()a zcdH#SZ``o)tVAn&7l;nIoopg+hoBKW@ zs(}LI1fBuJU;R3O5kT`^|Jx6RU@2?#FJ zbn(1Z(9FWgB;vu~XeY%GfK+XH5I<|)1qsgfa=8aK5Ae+07Y@6PW<;i=$A~!}|DvYge71Nuh}Ou zTkB>tKlGzMS)ev#^6E#TcfE`$JNU|KZ1!~48O4G}c76eu%B1qELKcfBL z3Tia)vJ*4sxW!i=Q7E5Gm;Tf>V?P)(CHnSNz#wu}A-di*^UO>sIVCpE?zJ@3d5WUm zQ#m{-oidIUpqNZ=awSS?Ta8lm$CB*l$?T4=vLxQGRQQRQlf~QmMJl1M-ZrswV{FA^ zmX(4rG?M-ADMZWEQR*6jNe@;_MRnu{i%20ST*2$t`;>dtX-h;fi#ZRaVs{xHPA~K$ zAeuz#COPJi6VS}QiNkUGhn${(NiFr%w^=yxTXL`4R8g@XHp!~xRy3~@$Aw{GOBU-*|6^g+vt=kkiRNd>LDhiCxG`_ zSc9aA)_v)R8jc|qYbs1$iWzS9f#^oQnPYr{7u~ zlAaw)4$76$4H2cObnz;)rA__t;(js4Mv~=Jf)`Gse={1C4ynTDL~w7KVG{@B6OXff zjIq-LOlXy-(&u}3VyX9y!}~#(eV=Ps0@UrV1L?S(4siW^=)3aWF~3Mku*?A@ zoDe$5YA^R5tf%G4hwe4Nhd9QnspfZ8#7Y^?a+IkJ?E#qOzcgg2vNyG<;I|paXwW7% zRJB}ccGO*#Z{f1Y$$>cRbA#d~NfCXe5(WK;e`UABSZXMuRm`Z|@|Qw@(>1K!K^{LS z=iAs+NRexMro#hir87Ed-_t_V*ybyfp-+o2X6jV=MZ1rB^*)6g8gsfz%#AG%#{VcQ z+R4bfOx0)XN|QgnXsUq|R;^MrC#KE*G7&_HKmlpSW`xH1lTD+8;8V?yfa|$f_(o z2H~^?|7!OgD(%?wyiWA?`#3;SR#al%X)-Ub$d(!uPX>a%bg(1+GSYOV4s*ZDe~9~h zN$@cLey}O3{1z~qW=yzGrx_MQQAsm`~SYhaltg!A}N%LpQXw z0j9Hh!e+?eXm5Ka<+v<&9eL0^KCbSWd~QWsNtV^UzK! zcF8=O3LgzRMSJ`)7j7MyQ+K8SmRJVGlPhuRF`}O7GXoDF>uxEU-pBhOiHy|7QqLY+ z)C$qMKL?uQk!TI?_5>Shjbm{*7xP;lM89N&7YXN;B;aY6R?c# zt#=Pw%wO^Q)0PsP{f*f``>!<$#S;yh$*`z=<&IGh4QsNh-aH#_~8(1|RMr5}&i^lvU$fceey ztGBbaWQD+gdM&hMU!liA7yl_;g3aG$Dv>q?T@rzAz9I`YDqRz_ipROLBgbxD9hKyh zrpNn^m1t*sJHdzK3NU$}z^&uPex%!A{*w&dQwU%;?j5WlP<0X?5HF$x!@a8iXvj5& zw|L@kJWt=9s^qN;?uW76ZVJNN^Wg>7XNbm*(!D{#CFUKn5BoaPqJK%?jsxo1LS_35 ze%o}$^4}!m4HX1jJEof86k_mfY2mRO<&^)KV2g~l4dSrdaL}4onqn6)pD$?Wz>COm z*4I3)(A=jDgWyY3s(2Q-i#ZK1r8Sjq(9muUEX))4G1Z58<{nEh7H!m@pqBG8chWwl zohX7}Zekl|&^ai2V7bno6E_-DvcB(1m)*PcBNcTJX~4xy;ZXp#XIM^W;Q)LUEwW3q zL{S#rze=<&Stf?W9KoA6!qG0cp07rdo3dxKMGs~|okW?^vOt#Iw`1WJZy=8hAS-? zNQZUXwi)ltw7WvI@~O@RQa1V)5W2U8*0p7|-bS6j6?w8VsR7rC$56Fza8v92DuJ_U zIK$lbj4|xW%YVY-I#}LaqSOT}PCh~_I-E1SHqa<zuwtd9JNKR}7LHliWCDr;}|YtAijH$cVRvPq9mB*v?>jeS{FB zJ~GL>jWO<`fs9soQUjU{qxKkIdhy71!h3AS>~ndF;ONSNrdUA=DOLnb32hlea&thD zG6kf}Wpo11mRr&GrWu<*w(Qbkmr$gfjk@rZerRMDU%}jY-|)!!yWI$Oh>doBd4gFG zPvy4t^nS(fV-JZORKtl@0bbxpyj;z3E@BkE+C*Ca=A#-K zt8zhXJQ}4u<1?X!G{GQenH-n(^IofHEg9z97e8rru3HDo&D)`g-=v4MzB8Yd^bL6Ju$1L=;KqTO5{Ih~9#gW$$ zCm_jWB5M523_0&HP6+TIrcx0+HJ@5=_4XY`Gq}4jSngV^`8JIHO_sXnKmC+oN0sD% ztyS8qg6o>~iM!Z_$^w!L=(U+pLnj$2RNAdr6a+7)pQ;G0z!I1qZwy>^;)&Z?bVMJy z|FF`_3&7)BH2@FqO=1JA!LU<##ko)u;xA7Y)`M+p)luFbfRf2=a~qSg%ys2VNtPTK z@rOQ*BUw`uS$!Qop;bQ~d+(;%17cxe4X1Sy2QBZ;Ey;7gNwnl`-t&gWV=YZHmL|uq zm|FDIuiHj0O{ilEE2DYCXEyvUXx`}UwhH|gGrfvI_(GSeqd7(?6M5Kga;)FbO9lf4v8rD}36zj&cWEw#51u zdbw;b4PT?1`1W6!mX~wNYG8~BSeXLAqhj(m4(4J5k3ruArZ^LNNj=p)yY~iZ4Wp~yNQoHU)6E`~@zdQr)odKK*a3C$zPf-1lT+16nuSe)zm6UG z#GJq;B{A5H=q+zTR-RXBWjTunX8b;NJ$K2hUN_cPz0lWa8Kr!^2MqzD7>E zbJ(ilWSD3A>SUh-)7*ab9UA74Iv~vXix>AIGRaBY+h5weDOc=KCz&4qalqfprJH|< zygnE>;mg;FcWq6Hd|aqKY75l(%L~GgSBHh-Q+{*s zW~n(4mxkww73Gu5d+A;!0v&liighjqj(6sQL2zFWfA@rT%^vIYn{eLjXBek`>zq0j zFC?uApm=F=cnKA#`WF!8g_lJJT~6vao4Eq^Twdn<}QJ1t(-1wV9!)J}Eyk-{#pet{w3V%fc7v*#@77cE1%{ z@J#b^kzDn!N3+u{`MDc**$SZU?=t;)K9+;{i;`c<$mZTW&(e&sqWY(Qo@w8Te!XFi zHQ0yk0UImA0O@3>T)J({ug`OWsoTcI2UQcAOk)?KLxWAQOXMDPQE$2&M+Y zqbE*K2#$%#WXT%)KL~Y_SZJ86V>$c07*TtoPj~yCPoW4MTRiINhZ;Y~7a(lAwNm&G zd$$<9f(>KGzwQKE;ZJy3|HcIevT+v+UZAQwHEKKCz0*qNNGRk$M2V!)=4f+iU3Sx|~j=#%EABY*qIqf`3SQ%|^fR8?)HxfvJLtG%M<-zD7n zp;AhaM7KNh+S!`sya~}yz`m(Hh`>w(G`g>f7}ZtBn$c`fb*D`;Zos1bMJuV>;r4h>f3AamggWH;G-R<~UvF&}`;FNd}7ZUkCm~954D{H6Pvhr;H zxpQHjwZcS77x2vG2;I7p70*vhIC}SMXNo9|E9y*2>%zW>L!8uKsmi^*MgpuH*$SW4 zXHJ}s8xh69OV$|HWVsNV54dYs9)Nf;x%&9Pan= z^K#=EHNfk)cC1n(#k~%xuwO+NjtB5oA?by+_~)Wj4G>gKE>n-iLU|C5NBWTP9W;;G zkuzU}&>*cW!2fpJOWz&;jRfv6^JA3r$~^(6p>DX<#lQzHPD{dAugb4Lvx!jf5+I7$=M1*(JZT zY=!0%(oU&okkiewu?@~SU++Lkw=Y-6Y3OrX{nb!2!y??W`_@crvC%M_#!F^z=3f^D z>!)!Qn)&V%y2R1@SAfprKwKzl#7gLpe1*gbj{y2na}D|Q@f+&=OPwKXsg4C?4Qx_6 z9`|x|9fbU`Tl_A_9`6~ceVJSx9}BS82y|atz@SPn^2e*nxjn9~T#VqhFm%1(p?^%l zDTLFL2XJYVp~O}k40A-c5(+(`eRwuS6{PFuh}JrCq`C#8N@A?j{oCL@RN2pJS9fI4$WO#rB@u2yejp&Z?!y;>5C7uuBF0 zQ;Veks9_wPuAAM*JNC5~``Yg#W3{-4O2S4_->x5;#;Sklt_jVI?R2mnB)Zc~tptrR z!=iF51KHtqj;<&o4y%}EC3but2epLWNz8y7+#gnS^#EIup z({J{xL3ystXuq+n$|ld{Yba$@4KIESNskj&09g9W4x>9PkZ4a!u@H0dKIvCcwr9Sx zEx;4spE0k5S37CAjiwJyN@H;bfGR_?m(S`e!EqT?zp5kr?eVgZMw;J%?jdkPM%}zhxKLCc)p*La4Km?%vTuJLC?a*dW{i56&ZpOWcY-p(@H24g#@7swKAq*B zK@8;+p7|J&P;NG5&h%Hiba%&}5ojKnxZ7L?d_r>aCllZA%n)r@kdI@Jc3ELRvC(UJt;-j^jh(OLn%RX>g^_>Y!-D^?ST*N8s8`m^ zjx>J6{v$7vYBq;Kr6)QS@v~+66EXNup*%%R01p~waD{@Tj8$>{m9a%b>SDIi&24Pv zTZS_kj&rY14HIZ!P1b2+sKk|#8TZ;`lPL~1(>Rvl487ZMg?b1-P|Fx6`*xo2p=0@Y zgo$27AG~UYUQ`FD?^ZhYPhc#!`6C@J#*w3yb*!ofm=mqbJKrPw6~E=8Wr!fx1p1eZQoRkU zAC-E>TgUCNmsRYOFSE_;+f*Z0B2a?sR>QU(YV>#;=z9*-kZOK<+ie^=X_cf}AQu;V zZO|bZ4GH{pUkC|v!7XLhDJX&DF$cySpPDRCtn5)$7lKloRuh<$Xj zW~Y1fY`w`o=VdlP@^S6_f&`U*m;Nlt76r+>IBYNw%|h0Tnk8F#HPEOb`&@yd^|`(9 zd;;4B6l9J6yxc{dx)w9w7jhOvsoe0I@#k{Gcz z?o0MWT^$?EmwB!Rn~dm_G*U2W*%K%3#WA?XHsrnqv(LVtT)Wi zwxTm4rgR_?)8WpP52^CE3O4&jck+S)mdCPRtG67EMhw8l^SLDeD3Scv+)LqEGGlS| z1e}yag7Qn-Z4%VAxkpYj-o0r~UW>4wH2RiW^x$FuSPDDp{(c?&T;1*c-!%|);Klmi zz#E2_s9h>Fb{pqJlh5onZ_|xw5K%x0Db>X7$69$FE%MXK+5C%HcA>v3C!gu{TVszp z&Xc?ZKr3`|qi5*Y$S5(EQw-2lT|aSwv250OH4=-fMIOr!5~!@zp7=Wx8Y#;V@>#it z55}YH&hw#DTv+8G5tcN>PlF9?Zsk+PzZ2TlgVVq8SlgL@6E{0*B^4)pE|I|VrJfZ8 zf=;lNT-oLhXuM>oChA|sxv6{FHjC$%^UEC$Ekp&(qYHVTj7C^0!fPIagp8u}@I;!CAgzicL<@QFD?JIf6H)ga6K zg8jhw+X!b62v^mitXA{Aq|SCF$2(!VsH?^H=h<&b8O$hqCi zTWZx2zm`4~d!RsGgbgN&nuczMd>a=LHM*G%o_!TsggZ&V>iNu=RV*Y$k3rvO#4wW& z$Ro8p?^5kOV|N0_>LdnJ?`B8%u(E1415@4uG zQGDt17KV2XXy#5v5cBx$Mn^AybdNCBE=0#JyVV6@PFrL%pmpAajU)NqXm12%+eHRp zI=loQ&Bo}>WCt@cq+e(V&n+J4v->~m9JH~&gyi{2W^labWrw5R8Y3!=exMy_*=@d+ zMs>RYpe5$pbYJGsfQ>oE{aN<=JeeF*2x`7b)9f{-fl#0C5hQ=Yem1*T&=flq>Dsdw z=Q>t?8PwDN!m}B4_jRav)WOZgW0&nH@fU%Vvo}*OxSih``Y65I5g%XnbLoy_;{Ke+ zF_s&vTJzu=unsCOgcCtr0fDrCdvX414?4lc&eOW@-KI%fEJuiVlWQiUY0d!NeV3a(1dNc~h?Sl8+FreB-rR-%mvpzI$cKBuq~4cV`53Zh4B_bu!v zfkb@h{6mZ2=*yI|5i41sJTTr2und-~oHcrlkOEm-=Vo@$8i2%NuijW-)Pg_2{6bH= zuKC-%S|vyKR>Sg2D%2MCUy}Ip0Q29PRFPiV7#tIV(t*`GlBr+Sky8og#1o9dkMpO> z-%6VswBe^7Bg6qqXj-ql(0dB^=_e}4c}r$>NVl^?C!XVXc&qX2@|m4ZFH|EsSb*E> z*URLk6-T$_&IbKMd!Sq(ofCS~d>3nX;%;2xzUitIi}47pwYOPj=Gf|0KEfa$l*4L= zHN6wSj+`!HPf*jwTax6{t4xwjnz*sfK7PWkXw!2NDZbuHpOC5JK6hr8)(wZ!MRRO{emLk2=2$}>&y`X)cI)MPFezgB zq-SIF(&zdhf`m^Rbg=?cEV~AcF}Lp#{-FtN@N4MkjdgN}D!e3nej|1_6x&kb`B3oiBC3s;d#&3wIj zAroPW!-k=K!JhN<|D9Y#_!eX!_5*^D(1vihaEy>(&G!ANS0LYm?;R5^Zij~r-5?9n zK5A!R=ct&XMA1^B)VtKDX+Kka)M2)VG*%40-9QphrZ~Xc9o^EUP*|Z_sxJ)$* zVh*Jy4>|F{(=*pa{C3MCoKL{iKDfB*oHmh}Z(hWm^a28#jJ~IoWdWB18F;k}~xwxm)9;NXD zjdGVD%4t-?yVWF8(fLcs0E-S#!_Y4_T101({5?dS0{D*wsU}fg9-O$9?mU$fK8c0A zS(E9N4I7ygUR?X=V_#KW!(Fanp29hko5qht9UxmVbLn-U~g#XMhwolen~> z`jgfn8o2KhHkRC-%FtA!;zJARW>9W4UpR&}c2dT6G956IvTz^5i*WKSL|EQxw`c5G zlw^tv$~yirXKAx}TIunqqpeO-ufKUWDAN99mUTAPVe!}jwfM6#qAwrCv~+xM@W(2K z98dG6sylhPO`$g|T|iETgA6wAl&QsTX8#5k14h`khlQG+>2sc!%!RJ(xe^o#gBtc2t6B;!KbgC{4VXUw*LxCEx$d&q($1i>QM!4M3qAF zvaRiftL|oejWZGDkBPGf1ojAfornWl^hO{V^9$C4BuK+QUNa#T(TP-4G~Edda?B-t z&Td$lx8j?z&+k<+5Jk^XhN`B6=i4k8HYSnP>@ z@{1u*7U)0=i>g9#QFp>yyU{o7<8|m~`34l^?l#6KZ>1TeHc%~o!hW|P99op>Upglb zJy#K_AEp$mi(EX;DmzEE?Y_R*MXhH`XA(Ev z85XRa`+Q+nzhDB9sP22!d|S@0{DjJgujdK?9x^6vA32c7lp&@O+&l5i(0rvhZ#jr*8rRX65v$>6iPA z`M51N(gB+uZOfz>r41K&2lc3~qUxqdX1KZzqO19WxEshygVnuv8iXD|K;KEq3W3zn9?HIxO`ukM$#Nm+(jH_ zg={8MbYrvpOPB_36V=?|Q2x`_-NOVk|7re8@bfLYXkx~E;3rrR#^*8hQsHMBV%f>u z%@V{K#)i%E^Kr{_UexWUAb^XPb#t$Wz&g&#XZ0FDYHFA9$@3@VU(DXR*VNPA?{s$D z%XMTh93MYgG}G&G2k|`EAn}f`;Em%&Pl@{XI-|uTpd{#jKfFz!pcD-1(lw4AbqHeG zz-446*e1`nZR6*(;8F2yL~Lf0&)u3r@z3*HI7?7oF?W*TQ-0t=lUInVPIf*%$9z@L z!$?5zgAAJ)kTmVx0tYZ1(I4=Uf;UW?j(5WINWgzHnf*=KXlK5d%J%s9vM*wU3f49o z0CXkYe)Sl99ct=0^@6(9jMrctjj~V1Sou0}@t;^0)S%55;pg_Zer;3i626^nBZKEY zb242($d$=sSJ#_x&1>RB7J1$6e`HVu!K@rVkN;Dc=bA};JNx6>Xp)#oppkdl3ZBD! zd-DPm@tk&=Hf@ieG)bB?b@3yr(tQG4ITJETnnI)gJS%)hxmdA0#8$n#FhSnN@@yjNGjcvku zV&k(;Tp-Pm(22JeDddV6iTt!4rCuL0G!&M65$@5S)|W!U`zAb1cLy=F@oue>&pdCY z+B9%gkbFFby0abcw1KPavrt0oUL4#uA*zJSlsbBq5cGaUk01$1d^p)J z_0=QEpfFnxjDRfi6NtH&eZrIJnXJfV^l`bTj^CUkVmqxk z)4mfc5{)lDn3WViSv&Du4q?b6+tl{z#y3JM2_PL?#JfBF%r8`%4zEK39&wT%lWbqz z@O$E8(35Y;v@Y%S*v0?3|K#M=)k~CA3zbZQN40E(praX+`lsOw1*t&*+$mwH;zrHN z4r2xFaQm^px-O?!e1vM~nMc%1jRU z4Oo~@PokHMlno+g4}-tb-W_|kL-+C>SQcK|2SHt(Zd9i!*XzVNZ_fhu5O&e|AEN$dNoQo6ipA7;1%1=;5q0R4}4u z(by?OPS^s=XQ5>sZ%G%^|7roKymuj)bvYp@o2BnwTpDIUmKBPduXPW^PD={vmS8px z0q4k^QKmW^->P>j@42S>Q+2klkR==vrX;=zeePTiV;v)2aZ^j5Ad5>=E{-q0>)pY> z59+2#;2S@r8~heh*^%LzHQ1fuMN#{AsyF0<+wn`!BfW3jfj%C zQ~h-t{6aU(_8Sg$;V1W><36*Zm=6$*oyGEy2t(*MbL=RI<2NBy-MaAG_kJG>%$g^_ zExthPU={eu!^clF=yW%Bt>ksj=D%8=kn|2dV(}uS9SINXBkW%&8Gxk1*zA$8qmtw- z3Za|dasR-u`0%E?J?^XXDN>Y?0n|5YkR``n?fz(#fYGUY1b+=z5*L96= zWwj1fMYT;=$v=}Yj(AY(TM$y?H3++=wBrMQ1k35lsG^(Og7uqcsFCgKpm!(b(|_Lq z7SBi)|B5m$5gD3fhOUy-6kt!6bQ|^C%R0zX7u7o#E-p1 zT+!Av+DIS}B)A6)?hcIych|;)yIZg%Bm^3FcXxLSZjHOUyF0gY&VRo9!eH>g*gbl$ zS~Y7{%_%+ZA9@U8jgRcw)Tx}r{*BM7;n zqQ^9$*9pYj8|d`R+v++u(sHO*a7Dd~)c;Kweo_#ESO^2QZ*C<#0s%R86)MnQ+>oK# z8-KS!MGsW;ZYO0g5#M$g^JM%Jdk<;1`wI2y86GBdGyO(lg(uvD4%DhHy|nOraceZi zk8QqNJD6$YrCRvm80acBD14gMWA*uqwi0Tci2Pb>R12jc?vemAZ_Uy~yf{d2my{+3 zOS6N0kfSXCmufqMnmoDScLQ+kmm7jEvdA*AxfVK`^hJUL=1K^ExR7*fS>I?IZxYaJYXj#PZ^kXp@wG>Y`BX4V9@ba~{o~N_^Vxw%cvME!E z8wS9Rpll^TVY`?kZD9i-?=Yk2i3GNy-T}O;$KQsN(C`%idBFWn z{7pH8#{Uf*Hu!Y?7CQXKUmmhiX7N9Rl=}Z&$hx+FirM5!b~YRnKn@g04kAU&xR0g- z6q?-6NThF^`NLHUyIqSjmntX~>1ce;2PTIVW)Q^1V@>4Dg+&6Y+2xXqiz|ZACRJsKwZBC@-=)(+|8V!9F%t)gz`d+fk81kz zQe6A2@d}3>X^G{kT@AV_+r|7={@f-icpMQS`T1M*SiFa6S4ockt+6i25rA`V=}{%t zP?0v9rVK3xk#l@o_P&s@!Z3OU?W5S0H%K^SH5G^3hcAXgVdjFqZ#@Ld6!V~IRH+Shc`0k`LeY@A~1hT0cQ zF;`{HScxdWw~l&EW$PsjRDrA0zk(d6`d+uhf;4xlN-J#^=XT8Vct%wdz znz;T3_?-FUdwk$qNj>^BVURm1M@?APa7gK`E01RhaB8N367XChVm-Cli=y*0=yJyE zfZl3XA8DQMyzARnty) zQz!+%DUCg#9n&8-5?M1(QOdvPoEwqb#XIPWMFnH(26N~Xt${j@JI=PaX^TfkveZ&c z=;|k#w0>)NnD<{(ywV({O(8%ls9MDj2bSP35gc{%q}#Kahf(#YJlphC;T$F(w-^_u z8L_!N!5V{hY>N;ZHXYJQywM5w8_mFY(T6?-h=5kBx?o}le`OH8e?j5d&0WR$ZgwEy zs{uhggMx_-#hfV<$L6B>S5IMII+GKatzGX~H6sF=nb|Yxd{LIUDIzfobR4}ShOByB zCaHa5lU;q<9%#vHtm!$vEml>x=|-OeWdSjqwu0Hx$u`<&f|!I6%Ep4MO=t>V5Tc-6 zTNA5s+QN=!M0vP}dBHGq9)ySq7AyL&ZuGearqEDwH+T3|Mfceb^lZof<;Q<( z*H<5tR=WSxu|87S-g!SAR=R0o4oCm0&&Z1U!X&;x$3d-dyY; zy}GtxQYt|5i`|QWb$I>F)E^VO8i>YI%kg5V`k}dqL`2=q6m3VGx>Ldu{OWtvl`pbH zWAdXS>(Awp%A@r4Vi}!Kzl%P5rToNb5YX+Vdyldc%T&l;vmaP9m2|>vs92nnws3Hd zJo`)N(-CqBrT(h~`-07Ii_@#wWU6h67)i?F&ah0?8t#+b3-2W2+ySJq6-TSW-30D& zVkE}Lmxulg0cT1I2mpRnn4FEs@u5pPuIUxBac}-h#xs&&JHJ=F*2AFx>NeTB3R_qq z1zF&3NvwYF9dOVsFLN7I>(xLddWycK#edIYZ@o3y7b93dKLuWlb+5`z_O5+2jx{`x z(!MV~AJ0?&b@d!ykUo+4F2N(Xv9AI!mX%hQtB|B5ors6lSqmOsx-iXPx?MU}T}*YT z`CwHw7B9y(fq-+Zz7Ln^U6@4&1L%$7eqtrrKe};@3wb@OgPTe@XL=Yo^ZxnnA>X`- z{8N^@3eZf8Jg+ev&wJSk#|MBWx+SUM%W^9)iYbDVH#|r_zwJMo) zS2}JeKPra?EZVVPA|?G_r?~%gDKt zBC{_!yA!D4z^hfPlYWuwM`tG?mRXvH1PzW&N#+;?drzTElY+qAMFkw@E6tI%#Z^OmwFXfaIn7feBG`}u`MO(V`9>J}6 zpb1{onZC=@6g#K^cqkxw;$hURyCTkjbKdJxX+eud`yQbn&+yI6mC7Y1K&i1K+z;V* z)#$24h`PU&p;)_-n?#~`;dG^3D zbk5rPNfU5woNY%kq3Nu`b|Dba|3GtKwl(Ly09s;hUwW5nIRGFjb}y`t+%*T^gX)?U z8CGU>N!xg=tkuqj+ujFgh`tVSrwTfhth`;=gVw;-c)!$vZ}c0!3O|_$X3)YLMxpJa ziYuvi4mp79J%x_0lB1qW#9kTO$CAcp3VXkC^EaDwxMN|t6#v@4IL`mOt{?x8I!7tr zd=xNYuIPWvrq3;GMSBue!N`|re0&cKwvaV}F>*6!fPhY}B};u_6}Hb!=2Hs&FlJaN z06Q`GB31gDi52&IOKJ6<_7^BIka`~ixWal5^O)gJ&|5r}=$^^EK@Bi7t0*XWSSS64 zpiFXld4vROw4yYD#FApnI*kHLg?sa( zlc_uKRbf+4IQWuC#s#|0TJDn!@fk0TIhez#AYuWM#I094Z*voIJglzSzCzb(9_wKO zt3y=-D2^d1sO7b+8Jir0Av!!Q!6NZ;y=@ZsIu$-O!q0V4O8V{ZLGJiw{Hw4xtXlvUb?HE5cjWxFm0PQP(dqblBc*dh-7 z%nD#aTRQeew!g9xE~Y;nLE~v7b%7ncyUK$%xYt|_ALe(e^4I=cZb^wfn!uAcL%$G) zvRfBUN!~$}t9>aqXqwRr2Vix~Qxcw5qRf{+|9F!lt?r38xeKZH&g&NAbO>1h`s0|} z$zo2oF5G%=GZ{s&OrZHkYZf%Ozo$G1aNB$BE^H;3`bqo7j&xUUxc)oR#Bu$f9mI%&B|%ZN-U%09XN*rW7XFbDDJ$WF1K*E0zk6yQXVYyb^@V<~OlIR_b-@i} zYg8Q4gP{8pkvZZe5m%Zg40p)TDo1*}v@u?{&f;+`wEEQ**E2ixnXleVIpf|l0ZiY1 zy`5ZS_{+7M{_p5}|Nlq-eMYi+Q;dI8IT5+ z9uHsN{`gf6J5WQT!F)63Yq>qY0Lfa5k231Q;n*7Tq&+*bC}g0^r+YVDlH>R3$Q6T- zX1`SPRj3-Z8bbFcfvrdSIogj&qW{?sQ-y9$O0OvMHq zxI^o6kbYgk@EH|k!~M`C3Z>@#qb_nqz-U6up>zS|K}Q`CG{`mVT5SZQjtHz-F_W|M zgFJj4Z_dsnaRu1Sw(0#}UH#w>!#9dRH;Q1srMo?*_;3R^g+h8isNps5sr8N{3K zsdoSR1bs73XJ$?;+*c$4)`nVZ(bvDX@lT=ou3X^wP6K8d?I)E+I5-}i%HAI{;$K`E z%Q7S$R&xDtVT`JctLJdBTh#_gJpe;3PE|{qP6ZtCzHIze3ErZqs?motXk)$jf%{22 z?{9_&Y~60a&>v8p@=p2W>>Se^lJo+Nel66gvy-Om*lbSAY<}PCqEkxl&I-$l9l>&VJVCmEg|OOo;vJsoUFqTSvYA!pj+FB=Z@!@l>e`yIcr~YiwuoI@ zs0o-iG#y7%L@gIrBkFfQ>dK2N!R|0;8t4f=8=!-IvL+ zE4)D?RJfPRN6S_FZcAh&XekWx3!EtlkxH-34ikV4aZr^e1zEMe$b&>^l4ivcc5S{Ip%h_lEVgYMlovt@5G+7W^}~-^`$gqCzt8 zKlV|!z6|#NIZ0Q7$Kj%oH=nJeq2xYBbi(8OGh=)>KS>6W)sIk-=?vx<3*u$7f8m^*`^H)EYmg<%P@x!0ziMssT`~t#Mp)5MsiOOi z9X8@OiF)KUS9PcZ^-VHd8^>f=^BK;ch2hF=s#>ar_;yH((eP1K_vC1VJ4m6;8wgT_ zxNDIdj%XHGeiC`fUDIpA#QT8T?rT}6CC?hzwt548_eyUbG{u!jQqDIETbLmQ_(z*+ z)5?2#v&}x`$t)hEHS!uANnzA?jqv{pFh1Y%CUZhrsHlO|NNAd;~DXQ#+Nb>nPF6G09*$>l08s)Ntb62<{}{aD;r} z*9SwNPZ%5`0V?k?Pl0w=GCq6e%{0;D+Ey7Mb#Zn~MtDJu4IpZi5$3s6JDHHWUWPjf zWFVVQKEX*F6`ttY+bqw@EL*OxLYEtA-XT0>Cbv&BtVRd$JRqA zG4>^1d60HRuWM)9UO%WDhLx&dR~m;E<2yUTUo%{_`P~mzWW4Bx@6sW9(C>p$^;9yG z;zojLdb=Wai%n@za2@zwRFLYxTUZ;)IU$M(EHscP+$8`mm~q(lN)FpFUt>DrbMUX0 zM4`~(pekakC)=tq^Nc*%m@BZ%mE0gxx)B`lO?{It z<$SPXR}ajU@%~}FfT12vwAg5W_qcAxm*~WN2aJo)nm9VP<~$= znJj_upxWiy(nH7^G$>?K-*^y)FQU_LM#6JeKMw<#4}2U#;1~LTJ~;nq{K5aW1U+a* zTGc!uGz7TKy9rpx`6J~??PAX$TX#~4n;c6c$alBE?0E|anv{E{`FryMHNxTEKnHJg zNG4{C=#owJ5w$f39^>xLeA}0+_C1Au5FpmVM9KjLHi9JhUEbt>nHb3FNabi0iDVnS$Qk# z`{tyxN}Th+ytThNCpelDt&8S{Ud$bzTcfY&+8Lxkwih*RWm;}#`a{gB@CysSrjK3e zz2d!Y39x-95k!B};BnGuJa*M1H5@9-*W5bo{xpmuUswR6j<8Zg+t{a zrh#@vXd?L54X9Ho|7lu@!XT&GVe-(G23FpH#vNebq1S<3I3$C+WWw&@U$njRD_t6@ zRmBgPwma`Ee7{VepR26!kTQj540<7ts0a2QhdhxweCONFc;TVE+ z+r2OrXGq>aXgl`GP`H2Ud=xCA>9;-ez1BcBs$Q8LqYx0Yyzc4g77v^F=@K+3P}#cW zIk#7C-~eMJ7lD`8H!wB-T>QQeqG+M$_Q3N)^xKZDHc&(=ilz7HYi6JZ@4#x4IhX-W z8$y5JrolY$#Bcj^;ox)1r6V_+JHzbT?UVF@hqC-v_a+$bwBwr8_(Nq2_r~Mu+)oSN z$y(D*GjeAp!sjRi`w#{@BAZh5(fDCh-3*zhT31Za62)$fL%1%yXN!nJeY_c%9s0BA zBE2og@r(Z@w=uYHM)6yPH~EUU(!v#voUd`HjfVI)Nin%YjQU|e=|k!L1M?d&3nuya zvR~|u9;PQ_%%=%Ztkqkt@A?w-n|)7taU_Lsju9~{XdqRCPOlL-g&^kZhHxswPHw~g zMqIXVitM1fvgaM)O6|Omr|uB-Fe84}bet1_XEfQy$7D!~9!e1Gd+y;mKg~QOET8OO z(yQ3CA7=eus{q?8@&Bc`(=xmMkp1>-=7px(xSzyyTcmZ%--U-w7M)?K^eW!!2%#$e z`x-}_J%tqL+BDWNg&yP`dgc+TcG?m(gIY{FG{7hT$X{HWPVgtw1SON3*4aplS2(EY z{ctY|>U?J?`oW|x51&{=0!!Df$%@KSLhR%2ORKE>EymigA4k=Scfk(gF2#aY)18!7 zK5tP|p$e4vbN!7^MYB*{0^AM}l8RVAR7Vu)9e}z%+&F1Ky6Wf%`P4Mk(OgotWt&p$ zqBZM7INKgEhmKmp!9!0@7}CQq${Bz79)<>Z*D+MvQ|0%QH*bo~C%C|yc8j)FM+GYG zOm>QO%c3>ITzk5<(fyvr^2MedoE*D@FgEVIwpiN}rc7mU+aDf9hkrb7#?`lzCPB?M z6oL{v^C@D5)M|fnWPzWWC(&#=a8TI`e0c!t&9tMIX;Hp$+!eJmng`$Mw4WXSy-O*v z#q*C|>c{mvFWT?UX1*Yzi**M>>l)}Mu`?aEs_Pg|um~X<5yG%yZ}@&ojeGxfm=!9d0>N){zR~JXt`H>Ma=&An6$PmhTZZc7bJ4Kf(H1M1)SL+ zFFdABkH=)wg|@+t~06lLLZmGnEB|5XUrM(Y;0 z#{|_3Ck-5EWxm7xtkX*lS`BZCHmNY97W1YtkSU%@TiEm@VaBz6Alr3olvyeYgJh?y zhSPv?U0!gM)UaD$u@R{ZdzoWh$%+h)=E>MfrUsqB5L!i0yT)obQqNN@!T7NQhMuGL zstV-~528W`X!RJVD0L19*P2$=&?T-}o`NdBe9N1B=U;%hoc+4Ch}`5ylhC4!q|@9~ zf&RsTWmvRu*?;|K1^xYb`z$F@i{2G<)FvAgAXiDOsy@vBIKEOhre*WE(gbrA8hc24 zmZ<5!&`wS%h*gxdJ}29~=nWdx^Cqu4R^;7oLPb}S6b0svxOKWqei@f+sFXAReSGUf zr|Bw%CC7M0JlRq~j%lP6uyk~pqT8Dh{=EieOJZ@~Bfr?8;w`U7#OYu;>qRiv?v9n2OmEtcZ zkg#cYTRL%dudxFrCVsxt-4PBQ%Q|bUB{~O;Xwc90tsi3-(8ht5s73bj&^*UC=uG=u~>xakM%%Y8>QQYAE9HyHZu`9k51z9Ib*eqCu8l32h^eh z`o~q;SY=cJk20q9E!O_y;ul{3q|Zuo^&oy{9xr8&^&y#9b9alBZufO&>Tf3~iK|n) zb5HEa z9+~3$H%e+oCDWux5ZW83+?h()qs-_0kDrKClopqM_COoP)fH2_arJ)N-`l0CijQ~6 zhMxpSC~St?rD+hMb=G^6Vzsm+4{?Nt=!WW*lUk?E-&tPoCBCCXO&lb2#RsdG`^MrT z+RbCA#LMK#Byih7&7co^GH&Hl>Df11g?_jyeu&7Zk94jSA0 z_L)6-PB)EU_uC;}x}Zu^#Z}W>yrK8FCb~yZY#B5~iM9j5ZvjvVeHyz6(G`w>*8Qg= zBaqmdl1W%F>jQb068i2ovQKjkqTIccn;(mv9;2@67ukEdj<_<^^mhHDJ58;5# z#xhdz!`|iArOoz?HbJOOyf{Njp59XbM=V|IlnK&8UM-Ny?b9_ctnwOOcE4`MAUUXQ z24=u7g@g|nh^5k#!nWBxDzQK~vHbCO=wns(k%7bQwRR}@0w3V@73$0 z=4xmYihulduY9u7rcy$uaSq>HaTfQ!dHZ_xTAqNErw*3z%MlxQRxR5&e>Av%_}Ev0 zW#V{*{HgA@cV2(LFEsg$ar z)$aTHaPa!V#h0OikF`D89j3Q=O8LLp_Bb4C>mDquZnny8H=zzc6P_0!bH~HizMcOC z@ZLOZy|zC+7xlCLw_bTmm`I^P^C1U_OjoR{jnCu)C#$9#@Lbv=X=H>b<2+1Ge!S0{ z3~H{tO@dDavctBU7^Ejj=+&e4W;3z$SC4GiubVSac5wTs!--(f2AEVZ-RidXTpI{D zzP^iO%7avCdY_VDI>xFWBcuDMKdP8NxQuQy2FEWRlaz;M=}XhKRelmGP0D+D-w9$aEPgnOgh{7-;!W!@Xlee}{4~o=^_L|n(SkbJ53Tp~ zuOz_`Sd3|f#LvvJ>)$1bJ>a-k@{A7dTCZn5H=$W%@>)VWncr*b>v^#E^c)h&ZubqO z`3DRf@f8;7)8@=V=11iR@?Sg5S1(FqnIy|w8N%U@6$fwar;lr<+xX^Y?} zww_(6Zl<6>H6btAW)EdauaM9Z5p>J?hsATld}uW9u%q!(({@+?CjXe71n1B$>M;g7 zKMabZ2tzKNKX^Sk*Boe+Y~87T<#Xcdg%v&+d?0)CrRX|QP`qD3OVC$LfldaHH8lW6 zN=AX~`b;NqtGJ@Nu@ck5wE_;d8hPz&pi{7x6cpz-Bg?e1pH05x({Zz>7~>MB|Focp zVA!<1O=cJcRg&!6C%jOURgWIKc>-FociiHj9C)`9Iv4XnVYzie(V@50tmt3VT*X(I z4>}5i`(K)%7UGwr`CkY1BL*{253z+Gwo_o;h1L9ToChnPWff|e)lnSn6K&p>s7rI+ z4-J&5gT9u4K@4c>CiZ%lCz?8j>pDm6hi z?cuRzL$3Xe-f5ct$cV`-zB~oic@P&$cL2;&jdAxa9vqkl7@9zOTKZS6l|%cY zyjdnUS%O&c5UKO_A6iio2s#3X=Rq{=>}w6O9BnP9Uy07HvQmn@*G2{g21bV7uKfKX z@avtE!rhd0*vn!FYleyCM4Bi76G3G>po-324#s+zfMX%4lX@``^2df4x+7k)(^LA~ zH*+mdpfUX)g#@_bOuR;zA)6ucu%zN(6QMC>vDwBO&5&SMyU8^AmJv03ALQ}87W=Au zX|jg6qWlxxYtS0H+UcxGC+26tmJyQ9W>fn=#$b+*Kg;vTofMfi! zGl>$*sVm=O1HYr0&Uvw0PLhjBd`dS+3n%<*YYWThwwR4y{Q$Rn$(er>s$PZdmK&#S zAM^LJIo*Z$d0%{gWn3cjedwv@wTHG1X#I*Du%K^Z@yKYt0tqYk01Ohwl(XgPO~HbZ zgJfywoAoM=M#6eeMo1uODE!I=7SlSU&R@WOAc5lSv9811HM0*V8#4mqyjn@FapZ@t z=EaELQ^%Pi5Rlg%#IAKl8kc@(8-vKyooo6SH>X4e)l!(&6@U^>-!T0|N`1lj| zTfkFil7#zwxO;65$%$n@3)5oy(SLrw4?}Je<#EfXknrJ-OsRE%$II|2Yd-8tZI;&e zt!nyUamYG3*wKd+>vmPwmkZF;f+iuQ|8_aZaQSxubinZLfI zvS#)OgoOtx!V_~PN?q${AFHkcb??%L!*m%NvY}Igf^2iiW}cAmKJXH-9njM>Nd^sS z9*9Q{sq&bE+2Rb%4s>xyQ0R;!!<(BOs=6>oc<8&1k@4E%2?Lv7R?R-20z~knDa*kh zYWw$xC>WAj-JoB+JrT(Vt3io=xzt)SK;fS8mVlC!yep$??+xe1cia(^a`ok8@P$=Z zo7XJg(`_NJRl|O!$|(_#QNl+klPjKN>mX1@lYq_oovr&HFw9cpjzFlruB0tDQj;9k zU?y+oC7q;g%;vjyWF4bDnPIEQ!HgRwMNe;=d^5a|UgeXkf@GrwAwoP)_oyj_->QVX zs6bo~7YsG_ww(6J;Pxvc;^KUrZ1ZSS70v_RU}&t4;J9`=yvAc(R)aL;-3PUakvEM13e| zKWT&w3#^!K2aGyYyOs?yI|Ao73F4Hhp1I|ClJ{xIAEQcnvX}b$;r#7X|H7P5=~yk3 zoM9>_(6vMvTF6vjT*WKOzDD+DBm|vzBF#=9#-VD4+pt-HxrY9>pmVR}w|>$WD7Z|K zcU|gxSD?11#;EU5P1NeCzSEE-*7LFc^}7uVF)6BPE=-Tq57V-Xr3hj4=o@POCD*gC z3iS^a$!${D0sCN9eG5P?k%C{1)h|2{j(6nJJLgKY9q$w7rIgg6IAuA>-8*f;CvDrp zS=E_%$24pCi(}jbhPwTRefU$2LAV4g-+}5BMZ~;dH5S8bH0LgZ=drfqos(qcHjhi zbzgAp@#py2E;{8`v9?iW4kWo%V`ckGtNVKU@gK5Zt|Ut0Jz_DqX@Z`1Hj@OswT6-Y?kwkO^% zmQC@;Y}V_$O~ng5581V~;D7?IA=0+4!WZKzjlAx@4okl5D$-8amDYFAVZvp4)m76VB@RQfn+g3?PJfeYZPh8YZZ#)6_ zCL+lW-RI51!@hS{k-5#L)9P*MvT*vYqZc1T!s75xLY?Ei%2I#NO@6Cf{Dn3Mzn7cw z6h5~R=A1o;8$mmH@Qi%1%43}or@wP;a`wxuICPYhoz2o^c#?}cWjjz}l!+2#_7X=l zt!Mw8sw_LruWI01W5T;Bwix{lKlOvcL5CJNCyi%xWm`4)Jh#{r5Q=!$LMaSqxl3#> zyx$Yfipi%aG;mtTh%ew$W{lb)*tj^GXORcdIE7va<~DXiHhSSLE#Yy z*J8!QW224_wNt-0V?^2Q0ox=fZGR$wy~?4B$0jni^97S(2$Taf1a%_tWWP(7i{F(J z&l&u(o%G_LXzYji3@7Qx@M!BE_4F-axoiTC&9;}G;kWIzH*H@jer0S*uoAyqJAO@= zOY3~aC5TaoI8yZ|&Upgp!j^7)3|0hae3`9rFkQ9ADFiqIVWMCIh+vhVNvYe-u z9}}`;5QYY217l>f+CJYmsc>Fc#Se5w6IiG1g|5Xs%n?8OLl=A&_Iai2uRAw{3w!V+ zAtS3`4HQa#ZZXJFjU6>SyY>KYu#YjjupCBhEHb^);reSX(tq~}F|+U@ED9uI`??bl zUZ58QLZ)B;qx24b%~9Z*2xWyVlqH@|TeNxg4@`;@8>55}q$e{@$(qe1N2`0&>K&P1 z!-%}Cn%lLwUqo*Zh*Z7@8?$XzO^DV! zjZD6j0SnvcAA8Ie0pf_=_nykfn%V{>`-C3ZcGcd0)rzP^@Sbp}hI5pQI0OPp z$QBB(o*0F8*!K+wix10DTgD!zTZsB3q0@bEcbX*@!<7X@@auW> zjB37T3E0=xwpES0=Y?#3I9<_Dv@8{I<^7Dy>bn~AQ8(KuZf?l}hhP2KOhh#ezj9(w z*?u}suca%R6gRJcO9)Syt&V@y4|@I4e{We@xVU^`OxbKVnL9`ywgp8@_D3?6xZ_YVXpZz)bAQZEL1xyIi>xuLLpo&y>_8 zW#+aRN_Tt4RdP{jd_e3Wreq(B1+xLvWa(;y+;d%dptB+9ST z)V~`aY^Qsz!zk4}D^42pAQ)fHmOX|UlJJ3Sz9;>wre;%9y zK%u5%P&@;tZ4@5bWE=VvWvd_^a<3d&$^nR0_?_!Qr;FM;NF8I(y&$vK>JA~2DoaV- zQ{Un&;2UwMI)+u6ZQ+hMK!6h&;Rm#-Rm8)HG*19J^*>gLU+W6hfG3{Zu(1~PI}rF{9<^=`w)v*LzKjKR#UI_BIerHBG)>uU!Y&%FX(Ii&A55# z4;S|<8Ev{|SdBm$YtN)p8}sm!F*kG;pIk)na`iEL#nJ0%gQABzyTkdg z21g(+Fc}5W zBr*?~nqt#Y_ z?<;H>YFc)UF-DT;=o0=@{)RJtj=0>Qa-(*7_vocc-&eSDxYAR814X<;VUBi>hQ6u$;-Pq0(}$ic``yW}MV#h_I!xbn z(x2ILlOKxxALJjy)KqL74$vA^N;LER=cJ%zP8h>Z;xIu@lN-~ebPYB0kXulR{d_gR zD=mEN-NBzM+++ZhTjBg|?@Dk+`iz~OpZKji0jomJu5G?VgzP|Bg8p+_tZWBJ;PS@O z&bChG$-jpN4)Z)r;jPvP> z%wZh`DS3A5OOX7vcGE4GsmvXx?}4UQSgE?#hSCtgtX z)FdKY7`3Ocmo33-=!pTn)JJ{Gey46EpEtOvR&hX`x#8%U5H3J*U_hr{Cha=%^qD!P zMV9Bz8GEc`zf8Hbl7LFr-P$$V>1P2PwfAt69n3b5w)^jbvEpay9DQu1;%8hr4+6kF zw(34Fi|>xF=JB-2$R_zVR&pl8M8p?>Y2)b7L5L8t=nDdBKPHwx#&}^hhro()H9Frc zfv)aE3ps#L6#@DNrR+`&4q4!*eeh2N{AncF$y(04N?~m2jH&DM5Yd-rB$q|O1)I+2 zQc?py;p%DNty9u>boUg#qY`em6Y34w)7auw>PIC>llvl2e!0Zx-+72Cu!9ABr7fhT z2q@rLPkllPPG9gEkbZ(2q0z~2TFyaIj!|OM9b4c_FK20?^HG=xrfh(&rs59~f<7kp zSkb1J$5x(|QUhVtWFNhwQ8pKI)_eb~iA2%~z~xbBVh5nQX89~TdGKY(E8ao{rKs;S zUJfqJ#|-ps?vpX_QrC~#Z2pm@QnY~EO0wb((KQOgs4d-4o$D{1WdwkWBr*c7>@^dD z5Z_{_=z_1*EqzBMYDfHE%3@drF|xa}zQPD*0hA3DVhIKLdJbsZ?5lHd;+C*|<4cd+ zRO8SSv?rKk;)gO$OXPxzhTN)aWjWrx)ehATYUN+`(8AJ?UucEXrAH zzErS3!VQw-J7CHF`oNH!{_~=VOvi4L>v!uFZ4%!rxj|U*!vS4`wW}z~;xleHCwvV) zJfKv(%}eY*MHE!R>DabpnEMaQxga9E5dJM}n5!I#vTlf8MdIzJlPt zyS*;|JM*dU{&<4gAt46+6|R#^sF_VI*b1>m@uqkC+WQQ3GCR2qYL7h0WlHdWuaV!? zvAcBLRYl%oUOb3|YB%X^3H3N1J6kb^#*&APeSD=Q3WDL=?+FKYw%d+o)bKQ6nm6AD~avr&BV^4Uy(5 zck~Dkq!2B5k3(LT^OHQyG6EH2Bsz9|Jo{>({G!y1XE^0GYK*l>ZEsFTkSPjtdpo|y zGvy>nbv8X>;FMeOIY$25_CTK!%vCT^h@UdtKq zMIl?UorL_J#`Vwx)oB~M48QkGTQf5G1tG1JonYYVKmIYL+`6qlN9>CZY`C+)DHQl2 zUpH3rdt=(62D)zkF0-Us1L&}llPtt?cX%J8x+AFl$HyG*7Ul0!;~GrSn<7YgIzR4}1H^VlY}pEfUln70IyVQaLw>Mcub`1L zkxpIwC0j5mE=3{JoHy;+hO)NLwCzQc5bDP$?Z5c{^8z?&x0a4?G{48~C<8=B@IqOD zo_=v;Cn2YzGn;vDB~yFOl$yc0BW>sj?xYs4HkZPmq#oQ7F zzYGlHd{5OVjZ|;vXtAVGt!poBf%0u+5>lki52Eb0?D`7qE969Yd@F*wdMCYKL(=W1 zC#O8HT{ZZZN&*RFxu(|a4!icd99_XWA35`7&)l*`L*tjYW~e+R>r+B5RZ>C;4)H_T z6+UFnXI-|0;s(pnl(H}EMDO@gXZF*sB>1d56B8DA#YUKv!G6?#e^hI!B`BEn z-dx{qgSlj!6kR2>WZx(8I;nOo@>h~ik4aOQVvtn_#tL^kt|^b_OJ2Ci20zh-NKtGZ zv+7SzY^}!SY@!6d0F#VM*R4RUKm~7_3jW>YN+vPHO|0)cNzH=M>@D!UIrJGOrU#b_ z=ldswcVu(>_a^IYla|y*k8A^F$p#P68q_<~EklFZ`w_96X~)33-S%H?#XcB3vTZ4` zTt9veJ2Ay;10EPDBVqae9)SugiN2SUG9no~xJjlJiLm6Q)TtpWzU!r=*EbWd$m3aB zW*_01A?&AtYsz`1c=)9R?;NxAMMGP^c>>&z4NQw0*{YXeW4Wc9u#j1CWCH-gD2ch` z5l;pZRKOVEJOmC}cLo~uv=4_qn6dLVG~%lshZb!gm*j9b2a~=pYqv;tPTut0ff?Kx znq>CSwV@<$hOVV&Fyfdhm_ii_1?||_S-SHErK>O_VNJ1Zg^uZ^Yh*;_W@eHs!>`>B#IFrw z@ob*VR8J>=ZAWD9aA>@{(V^w5}Hcrwu1Wh2hRx9!@TD&7yIK3}?b7FWZ9_@Ud<2n6{%6 zW?O5%D-~7WegR4G4fKp9fwp-ZokO+lq2r!zu@_~_1F)3J?Ka<&t++sqPuo23qw=Un zmYlfLOAc{HF`$7kU%D0yI@HjMvKt`@Q+QahnKQuL@p*_bw3kCMm-&Y)7$(vgN?0bo zUV%bW%b2|!W01_PgjP=Oi~u5~RVLD4QMnpXq=91~!026e2dc{C_LU5E#&n{X(BOM^ zxJ;+uxesXjk-hU2usRp~$bcanDK12^1Fv!4hWq-Ec2e9m&9JTImRyybsmvx5k<+PD zZ8R2&k)0Su=&De%Uwtphy*FlYO6(Q@Vd(a4$QgUp;un4$Rvn8?7Ce=P8aX}IBT}VW zn~xlOmNHEQj+<_7>)+J3RQc9dlHc>u9@%ay>I;kM z`;>qi zRdy-j=?9IOM-x~pqL?0&yq-%3{c{S4@R_Bg8b!Gyy)#$TF?Hm;)z%2sL>7OK4k^-d}@0_B7ahI zt2SSyXz}dat$Q~j2n7K<(}e=QRFH2yG)TvSLZB^xq<(-o3NS&ZI>yEt=CJctl|kvs z9WDx(rV=uq1RTscA-TuZ3kYeZB z%P#44heVoWZ@9w@whG@}=sh%VQ>a)kb6SXFNCGne&*`7k{k|ML7Q zEs8c`n|sF55AFe6R4ILqW+RwlYIon|5&$v$Tl74@=o%BV3CI#%`k7<(C0AAt=PWVBo?4OW2pTExYtZW3ETLx zeTx*X`6UL}CBH<5N_U9hhzPL6=^~=nS90$ZNEpP;qu4XYKn=j6%O;#* z;V<7yH?}ZcmJ!9+6M;X@E4_?3vYu*^dMJuOm2B8rVb|JPL3_vrCgUVAY*0Y(W{dhg zUt{AMj8e@r0yr-P4?#TdGe-ND_moFwLCbMYn+gk4d zz(u0W%sShjvtr1s5+(}<=;r)I~9wAH3%>pF~B>@SR!hXS+@HE&tK zh+Ezmp9>DGyNt>>aL zyeA~CpNZ3U@i*J1966bc_QHy$g61#y7e=~>-d zHO$m6`J*gQzizDvZtVV?%lt`3xA0V?p^xWS@s~o8Y0$A<%S-n&S1J#?2;Q)=K*w$Z zt~q+FDoTm@SN+aADV%(?VU^=14fQH{0jXzAcZngZ(e2Hu>gBSEbzK45*{^fzRmXAQ z&7!`{{T%6sccEV4kROgKA4@;RnlHlWkJG3CP0Vzy?!KG}+1wmr+g#wFyet`+A&EAv zA^K0vRi zcMn_FJ<;l;md@3RX{v3Gd#nC^1YBzDC(Rb(E}C*Ha-9JDL|P4U3~~Eb5`Sl{CRFu%iQ$j@0-2D4#EPH^2T_k!xu?fo3U&NublzU6 z6>*>)YSJ#a5M=4-6*euU9BFk{iZ}d|ueF5dP*q0zu`LRR{7?^x+M69nv`<>x=jLJt zK>Aep0SF4-<0H{jDL_4JjTFH+3?KN0#v>9;(r|H~W%w-Pko)BIw!m{`9jAyY91!JS z1d#IAq&(mG#jKPEo50h-<0|uy& zrCiHim5`9AUk*Rq>L`HWwaL9?pFhu>`rAK7w#AjZ(*RIL?%&q%6GV2cc1FTt-WA8$ z-#9^;Y#bcc$(Z!(ru`9w!MyqAuqlP8F;MEJDfGuD5=1{W#A3<;K0<(kO20A6;SwQ$ zMRtdOs0NSOz$omVpfAO>xCOv$UNTVdv5)8d&1zHwsH6Fi7c2-7rwg}CP^rBy z!B=K~4VY|`v)d?_Rc1@*1N)~wk6#l*#>jfR_~q}xAdG3T6YoGsrnjniz& zVCbALrF9s%;ihR%0;4YepaR;YtW3!M15wPwKIL+^aqrmf<>HG+dm0$6;KVVGuW3_pKTagVF=gB%VJ@wA1k!N1&J{>b zm55!xqZNG|?oO58D(_5cdyo82i-ue7cLUP;ZI1971xuY-h&%(|Pu5!h<>iZiY@ldx zjec#WfM6xA@2)7b4FQ2)q?F559+U;Xe-4K?S;A>KOZR@LNF(QUPn4Iv%mJnb2%6we0iq($>V>d^87e;HZdPXJG7yQh*gsw8`{;MgUy3K~04akQ$SAXmT>Te0!Le}1=1 z4ZWTRuwOj?*s*`mOZzuET=iY}oz>*zG+bIJuziV@8b@k%v98`#%?rK&HlCm@?{wAy zwj0DbZ2?l@l1En1s??D_G79WyS;GA>g9syXsWLJI+-b*W><^e=OF2wVQlwrw zx|0z5rEMI?8dhyk))gX8;1@&^CdTq^y;2cYG$ zA~knNa7Z<4`nF3y6$(EFV1<#*<5;WUiSw=FCAt#EpF0iewn+?CK9ZD(trG%n;u630{5u)M9H@Wo6+s z2&e0LTgG<|qn#?DLo~6XqJ40etxpR>=e~r9HqCe2+R;+yDQ*-V-{>vq43|P(-%ZwG z$F}CMEry^U51M%WZfdEKY>D3dYW}fo7vYp`-QpL4>G-IX+mk!BmhSK8ro7D`<7d!X zN%$TDNhOTg_qo$vSx5=-$KGSgm3j$^O_IJCf6RNQr))G_YKfi~4cX~z(`Wc68+O*X z@O>wubS&x!2D}NMsp&=pADrbzzSb@7FX_U3&;VtLs+{BE7^_fOllsXBH?5du=w`SW zbJ6-KOyVPSiR;5Bw|`pW!U>LCo@zhC;op2bN?dV>`8HK+aY=F<(KQ0{7OhaOZ=yWo zd)j`FC<~y#`VaERA|Ps$X~CACmMOGBW6rZVYy1a?X~SiLs`V8j_H^s84aaWU!o>Lt z+tD2tu)fpg`Ah1iIU#?CFVwuejXmri6CL1l|2bT=!usW>Z;{q z8HK<{0=PCLKqa`wD0uYs6`~e^s8a8>7&-;(pw3S;Jvf$3BPS&>p1x67Vs+aiof&e} z;8wYh7{n{Uzh{*}-E%!6xcHjB@IyCY2SKhW-{VlYR%(f3?rbgh;6H4V2gu);x5vi% zP%{Kc`op;C;Ccd820U@}bE} z%@iRz+34x1s%$QmQhWZyZp#@rJE>W6k}(QcDz8n7I%agZfl(Y>c);^`7H3pKedYih zPUPEm6<@zriaYVmilo$k6NO=b)ug*Kr7p_d65U~bu)DieR8!a(4xbHAJ7+cN4K3t` zLznnB*A&YD{6;CZW3>8&sW{bjjk-f4YhSDdD<^|LJ6oo zWJb^&6XpQdN_NVe^Omr4x|x>*T%vVM_5@BpM#A5lD_LqnDV=Egg$Xd39F6e zKh^hT&fuzy@38pDWp*`qBPl}ZAgCm{GdU7hvC}5yD4VtqQ3vh44Jqr$9^mbO~-3K)zV3}&>@ zQrOTzyYD2TNTZ$y6nRLDevIJJ5-IgV7v!*ywjzXa@8SzUhTyKBp%Yvrnpp33(R6J3v8G9k$?i#vO8~XkKfbjW9wtT z7?DhBKD&RZ#CuZKMBJ^21(BdxMiXmX$;f310vNeZXEp(T)0oMYeTVDt@pZ+yWoX+g z)!54PcN0{pg-qZBKu4=M0a8IKn?1fWlWkJJvCe99bM#os{?LhxnIRKV`r}_X-rtSZ z-Ue5Lus;Z)MoxyyF6l%_y#CXAm8mgg{@R6yc#^!39{6KyUzq=j7Yk>}pQOcz{xTh| zB54!-%Ncdz9OdSo6l63GYxgvgb_$)RX+ATMv7ro~vROxN7gO~GnD!@;=EcCl5f4@( ztO{Uoa3kb+gIroAlQx-A%5&62o>KL5y}ewt-RobkdB#UT4BPsrse^? z8-q{EMVtE`8NM0^EhOHRng{zOi;RKvkZ$CmF@fe*yx96H@i0ar*}_Xl=NOnEFW-f06@ z#`fo`mrFj!pAg*&H0g8)WWVd@3o2=uCHm=QrlsI{SRfyc!MJ3^ERM;#?cSvo{gGFI zfZmLrf{P9}NhbzNDqN!NE1clILSg4Ax>6wSAOM&u$>xWTRKQZOXY8U4D@(U%7`->> z_G--Q+#M}E8QWIXnHl&dNf-OgVz>-wWU^5$E@O5xPU_8bDw%~kSF|K>$c3S49f zy}mqW$-K=O&&41;w~EIK8_<$=y!Fk(1sS4b4gb9xf@`R{XzHjD%_m%J16&Fi`go*I zQ+pwC>~BUAl4l0cRx?~mA54EI5fWU2X-HCWhv8_~ri$I;=aMmHjO7zF=t;6^UNuk2 z>R@<~c`gD@7yR-dOFl>U#4!eLz_|8zRLG=!2$PXoo5{+`tT6-;rkXW?Rr|yy{-i<; zDMKJ&|LL0)31T2ETa6`YYK@0Z^}>xhu`(}Mk!{Xjx(!1AYEo1$_g^dx`~{@ttt1Wn z=!iT7#@c|Q{171M(g$N5$8MBNg#i$u$(!$D+VxlEip59^b7Jlte%IDt)~g|>`k$TH zIMMfr|0!?GDLzfhrU-v4@lgi~lo#K#h=XDYH#P4yWj@7MBCMlOIYzzGfR+z#b9c1w^YgvIr{{u)EaMa5hOTI4WI&5Mh*!aKT8?MM}iZm|{w0D7!mP zztG{SJ0LAB>d_X`gjQOhbifDM8hwpaJPQUg+v@4~4ox5hoTL;>Mwn#V^O~DDk{=wB z2AcpPjL_w?RH=9XpJTW6nc(VQMyXaB(4_%C2jgU>ipGHo@GeoLSnamZY~#!5dadKH zyJYH>6P?)$8&(+yP~IM&PW=pjtCuV47%&-EQmeXNlWJg9DdrEH@kaz}vxOUYmRNtU{So8#X$83zz@rIf$%l8Tp(Wg>QD0Zdw zDRhuCfx_r)#&noB&Y8p9c@x3km%m;Xb(byucYz&O$M3lsl#f5?A8bAi+P6#3I7o?9 z*7XzqxLZv`ZJvKsM#k*UVpuUHSMqOS)vAJCPdnwS=Yi`2r!%U4eHL++KE*G>mN1U~ zb_(+h$bxNd;t1i7gyRpTYl|lOG?FwSYrmYO=l*oTV0~c6l)2KMaWeGi&l*-4$xF*s z*IUB0uTkXG-0@Q1YtaE^m*Ug6z-<>e%Kz0`PmJoGH7(a;!qafP)x2<3gKJ#sY!R?M zg@k=_qpeW?=Q|qa9Pj_3#oJ2(Ek;rYM%m=`~#0(!D~eJIam ze>$W(ea2qMKRC&hlvQE(amVFopn!bg;1iq^B6iF1yr(P22fn2!4@@Sd9zikpjecn z?a{dLRv5xisNw;z>nCTZyjY{5vgDyey!-V>q3m*Xe1Y^<|H3s;j&x(^XYaPnM;|72 zsRg>ls~xxzdcL}{sAb*pqVMCiBwcV+<~_~zR`yH75SpesyW;RNY~_(0i066O71NQo0f3= z-6v(I3(R%sjo(G=jhYE?lRIrwy%7w-1Y!PADtO2Fxhj1v+k8_Avpe73;V(VY?YU8sPo1yja zn8LaiP=D5=2wQUMcN@0N|6>6@!_^?uHdYC^qB4M%jgbi)Hs`ApKsv}VtoHj9c_-4T zN&ZH|&_U=-#(r@HnJrC6;ne)V(_&K}5%{H+IgR>-KOtUQrO!MXcMQ&)$Kng^$+)oo z$Dl{B6%2{vb#67@Ng`8=4)*_YfR_#WolrSWiw;L0(33wt;-~Ja-G)CMg73C-&YTaK zlWL;VH6$Gs40)-xK2y7y`eDTk?FtPo(OCfCp-$s(&9U*>Ek zwn|8FC|V9-SjDAo(E*aRe9)+4Tl_jCf8&_*KM-}eK*~+ToN$gU-$$= zOh5%bfv6#c159Mkt2n?d7KDK9TaBGDt@jZZVj&d7#abeo8!HN5>pgYhCgXECT0l4x zf5X!lnwWbKycmJl6C{f9!TGyJhQ5+KldeEPn~XGz`W~F`AtmmlyeosbBoBQ!JYuq4 z4aT74z2xyNwY+J-wkjg~>&!^1stt$jA@_{X*mG8h+%~xX9C`AOsQo3G($%tggSooh-N-DM2 zf|-j`%3oR9DXcXdx{#1%^)N9icaV&c`y=Atp4fnmb8(dD+udZ+0D`PHw=9c<(;pJkz~Nuy+kR zzWXj_Yj4mx2LEOI0|qz~l)E>ewVvWz2p44It6&=ocvutOBDEG*vj9W!CnHGn+jG?3 z=QZH^;f%_S$$hJldFG<~6ZI8tCEYuuIr1J_&hhs!CeAfBdFXkthOt;?AAONKi{E(L z^?ptMD6x!}@>(QHIlIzi$RNlB>snv8t0+3DfBrtXn_0%8-Z}9MSGiQNX-M`;{1esO zO6a0Vt6};eGNSt@K;0my`JlMQD%r>quP^Eg|dtJRfgWMTEA9gpB-7X0Uq}6ZD%&0Us zVtQK-6~T+*>dcJ%==G`-q|1J#{`v71iQns@Kap0}*lRBp-c!cK!7sVYY<77*rlPwU z!EASq7JM2oOjEwFulJ>>q^aDqW%aK17wM-@SZlIULcsuV*dw!CJ5|e3)5UFCz<`Anz1&rkyc;LJs0 zRT~_S20KYf8frQ4U~-VVa8k31(aQgq#IfD1M!#(%@wO` zO`SF;j%>zhr!NpyT;pPtfhI6DIhLMD;y#0@Z;@CzxNT733Q@^ZEd`C;&>7BF+bO#T z`UIwy$vMszK|X}j1;b@r(>b8aJN7&bLCp`kHcU~9uK5-4$P?u4E}QIO={V|)1Z>*o zp?i~h)Z@goHuzhzdV)P~>U~S-j=U>REO1yVKXkxo4=Yet2pKWEu6I{obZ* z&x|RY&26m9L-0DdeeHT~5!Jzi82a|C-UB}9Mk7S)mXO8vy?M2OE{>D&q`qdO ziPiU+8(%yzjn#58atH8ZOXVx`k^re6{QI_zKiwx0Q4j$vX|(j(;I?qI84j64-B%uw zy+dBfa+w%?AdR;$%Ztw5AWf=ttu%W?C|(y?5&j`j@)=X8#@G+4LxJGZ-*1bSBvDOK z`UT)Er0Mwk<;$_^JA7n-c4EF6U>X}hBKG7Vj$8GFM~kb4!LQGUlBoJckawml`BWxG zOZi}XDR>)u?aUXwX)s+#u(yFWfgNg|9obEV7_os7eV_r#96$};jT<47TgB?Dmq04W zOZ)e0y&k^t*JkfB3om&FTLSREC_w{l4%WA`1$Z85DTAa@O6i7zWiL=&_a!dM2s2t+ zV~0f5gH$~;x}4B^O`U<33veG3xA`uK6^`=HM2IU!wfP!Fb7ZS>*3E1qCD>(1h=5_g z6H{_eTj&wXIxuT+@HP?psZc5V5NB7;i=2bXt1vT_46_Qc?|F#e>xZ*3_s812C881Z zpPCVIo()U?_-L~;{$X8y!&g_Dlx@#>h!X526 zdoFGe=Qk_aHj=s#Esr$upt8*|^GN;o%~D#<;qoWxO+;c>EhaG21&xNdR+_Dh4}xQn zO9p&P(MHj;bLySdP!P^@M}is?x8l8ptkYB+>~0RuyTGLjJ9+w3mId_UyEF-g>Ch;U zB-b~Ee;RdLFjBXow*VjW*sf#%9me(HoCw9&cdDWk)+j`kLhj?5R2Y1mKA!TIdc3f4FSPQ=R z$4_?WLarGE{TGU@hiaY1Cnpdu8ydL6vHkDQe9qVW{{eoFkB?&;J&JpH+z!T)H9Ku? zEHs(BJ2vM&-A#QUH}j@64gL7rk#}TIfK_YxNd|vV01kWU6Drhl1K=l@p7I4yy&-zG zW!IL%*!{>o+0`o@(U$cMQmSghodixk=I#T1a+4475x6sC;m$9;JQp64SJE!+c!Nk( zt+AReIFP*7G}Dt{w7TZrY^^$8A?rSJxF3rSw?y~M1Vl)rsKQDVa5!j1NC_TO*1!Y5 zu92H#xr8YA=8xcjooPQ_E0?a*6WMn-n3<>T(l#iW@R(|Z+b|}__a43-D0WUrurJw7 zrn-K94x`EAD~q%{+{>rFg+h0JdCElM9!njBPgWhzuR1Faqt~rP?WLuxz|)ssFaY-k z-;O?X^r9D%5_<_4T`;5A!;t_mZ_!jUu)UbqyJ#v3lwHjM2Wd_Sup=kSGj;U-kZJ33 z*xLkJe01af51TG?jx4tumxy-u<)l{S@Y*e&l8pa>E35@xgaS#u-IJ~O5CZOYTpH-f z9(ymdF~}Yi>I`|nn#XA%xh}qF2Ziciu(scJ4+OFDdCD$zYlFl{ZF*+9toPzPX!v?p zdYc}JBP=1vQicVCl5EJ>s0P>+g80)XYXW{W@j_SVDx$VFiiiS2OZ5$0eFtk~qC z(6f;Pa>+YZIM`%ZP53Imxh7blw)x5+{a#15>e|;Pq+M*GbQ4}tV3G!<4mcrCYP?v{ z0Mx+BREVe(C0oRFvY34jDYfs7G;W5BZw!56-M%4U;^wPeQs zfW1=ZA&2zI6k8X_tXg_-e548H6ByH&{%@`1t4EKvq{JJ3Hlf_6O}JD5!JsHIk3~$F z;W;>fl?%bbQt|Q9m97ny z+8TEHbyr+)cK}AVdvg5S@-6`9)2HiNpb0bANmq#1+qY_F0G&q4W3yZS;uPQASI@#>3Hk_#l&mPD} z9`O!VSsHEP5ugrZsT)||5QT%Ds2W!ws9oouEVus?IM_+2su|@8fOnAH8)riv>zj=a z@LsQU>a5Fe`y}|#2W}w4J4q{lM~VJU;hVnmF6VxO7Hj}8{&X4Qu@@_uPa*8FBho(P zF7hf^D>T^=c;E4`@cQT^3K0+vkIPG4&40LIR*hk2_;}Kj8tn7}T@NmI5&{VLpxo~> z_}{kNV0j>L@x^yO2j}lH&{KWCUv7S8_j~+_*+t>$xixgLNpO&&;@uRJ#tR;xGI3qEAb&N7tpB_vx<|%S#B~9WQ9_YeBQO>;CuQJ-OTAwJ%o< z=G7b1Z}DVUyaoa?vIXwC{2z;plWz}Z zMix&%XM*g~%;^ZfbA+#7>_i`+!wWVnWTaHtM$2E!UM68we&^SH#I>7VZ-G}aj#&AA zu$A0CMTE8I?boNx*Rq}4mu&yKs^b&vy;n_)uA~=n?&V0Ia!CI3O5KEiLT7!O)kdE8 zYZH|}aCekD4b$n*W2|=Groi-eZEgd@rq^{-{PnIMkcDamHcRzdf06<$^SQyiX-Jdvqim~9Jp2)-32G3-#Wn+29b&3R%Ke7oIPp}{{l0L;dh27 zYK^=}Uz6jqpmNZZ#auMQ-x&XJ;K6_8O6OpoOcBUfKNA@R+8(bmS#{Z&^(Q`CkFzib z(B{bKp>49VOSwO5Fsk1!S4{=rizP_QPN3h~8Q3{V(w5ilvT1E`;B3!deaZKc

    ;lnZx;M#dHA2v%4sdpaL&Og52UdT7x20Q zcbA~kq#_5iYsxaB!9u0ggpNC5=Ce~zr<|XiRiH4AcZ?i>!0I!&qHMBjYF7(cY1@kD zSiA0iwt~33IClMr-f{kMa3|ffxFecLhXG<;v*CQ}5X49j#YNI}yuKWn_A39Y#J;T4 zk3%a{w%S}eC#I5?Ken}4=#UQvxZm&T$s1lN9l=3O57gk9HbvAI2hIa!_nh&{6YHDgy)0zti}PVSDuDyQVtB zFDk1U;hj%hhL;C*M^Ps!AXWr{RDA0OC+L+dP}@C0v9_Tb;2L{ZPuZ(Uzi7&)HG6PY zk3DsapDP%ZoL2H#753C*%dprr7d$<}M(E7ZnaW0s*7=EVy_3*%(P8ndq# zsY5&06(y;6Q>EOfp%}TXS{Exo{&zXMIRBlMSSqu8w^L>RJ0@UPzaKKp3&gqvaE9=g zk@(yW$P#%-edj=vXv@Secu;lZsA|I@RSDfBA2T<(Dv1vxn zpnouk+^EgA^^HLNkGo<{z|`L|_)L59sfGWA^c9Qub(*7BU#5=`a;#U4W(U3=suhs9 z$>V=n@od(|J&TV5gOF=d9pAGau`?1mj%ViG zxv%p6NwA){4Nb$-b(!PVJs+x(z|Y|)b|>#$tEYHf{;-2{PK=vat@&ZyAuKkMTMhLk z?3gfr_C$b{WO01{w?-Un?mGIsEdW$Mqcj1;pu)>CR=3{*2P{_Yjx~{Wnc8x0tIyGz zf*LVh6mO_Z2>MTx>%FBc+T<}E@TYQ}1PdLAc>*zAo!lepX~8B5@`Keg+dlsCva#wI zLWUim=NU#Njb`{5tar-km0T%cVdDX2oYCN33KoSR@u`dDI)5Zy7ni5uQzu;My&@EI zd-TG>1-wC;bt}`~YoED*-%7c^ru2oF@0IklX4EHDec2s+{^S;6#9Gsbh4!%U zk@K1|*>T5G{nqlsA|<5>r@vVqU0<>CIHh)oV_ z3lYxJpiAeY0ObGG`g(2&Hyv|uP8O6<0TIyuOSR#R2Tu;`_z3m~IsCL%gNXR?gD7KJ zP?*+j12AOVHZ%1Ys=+AH8p|i9T4KHz9J=+ao@DV|m42SCLKC5f!-~1$8U)U~N$_bb zb}f$dC&R}cnG$t}R~P#!7Y*`8hQfVjAnyiqPLQ%TC+M-?rWkB7P=#cx6i4{n&8kcS zaix`~q#*Z>FEG8RWgWizsfynD6W`Qr{XR#boOX_NHqfd39Ze|jFiL`v@s=vkg_FxiIaFUoA=i&g{Dy({cvL*goq3s%7E{J}c$MucfasqT+DidX?`$vc=%P2^ve5uE(TAnRr&+LpfwW?u z^zxpsR}(x8TAll=sDt3s-e zgSgbI{G$b@y0EOQ7pL8h1yCi7hBf_rL7YpzU`{bcBUV^UCaM zO=kA-t#b=;Mx=Zz#AcuZ;h*v^Q(8{nfmr=go(7hq)G=RiX`>(GPvr$Gp9B|{*NTg2 zfu0&JTBjW@5}*der5trRB-(dj^};|;wfO?k=<$0Xh`DhNE6~%RiP@W-7qz_)hahHxo&P|L)O{uwklN z+u3S@V>pFq6qsnLvKNVXlih=oH5*i^x5oYp=V(2eStRED&BIEO%YosT=P}Qz%0}Np zQPxE7YxH8Qh|-3fsO{#mt~w3WJ5NoU(3!(>3ZJ|9TEyf}!jW?GMK_tz`Je)sY=Qh% z=_MgVt`g#~r2Dic7SCwwyxbJ~`&+#R)xq~Jo#t~dIV_o5m)tWFFlL-cdav{?db)6M z36A4nh}q5i!519QMWlUHWTnW%o}|h~`m`y_+CWGgu4chb>fIVAY5Y^wOKQIrH)Zoa zGAa4MS=j&TL^?OyC>_wKI9_zRag6Hh;B+!&2lXwoHvnFsMC?;mdmV@^IZD3Am7j_B zCZXp5R~Qp+raRn&Qk{Gx!}QuV->}w7kqs-Vj!4?{-7JW1gq(=2c7}UHOZ}kFa`qB+ zwX~hl{(kws@x=2m%;#X-5aa)k?@(?k?~>EB_Ot?9ULvrwmpNU2UVpqW=_fm)T%gzM zg99exJYykG+A!sZ-`i8eSgGvtw^7`fa237L6wwsAwq5z?G_aXB$#}O;6-d)@m2gw(z!I z6Ro95kKx@Y(WA^iEJ^>HZXmX&h7Nd9ICSUL>LwB|G*s_jV7JA-k|~8SKiEWL)peRX zwW^bSIq+%hQ>N}Ud6lKh_G9+JR8X#cO4_kYD$h;u-NU{S|oQ z7mWr0YOcu}$vEj54}!DG4o8peE>&~4Sc-Ny*BYEMmcFN^3$m%Um=cIoL#S*c7Ch-3 zQL=Ur|IX(3GoWb;-S34|NLt(xs5on?Jkj`hO&NUQm??-1pz167obJ_wj0)VyQ3BE= z&==#r`@oa=wE(5nY>#9+(|&vY)oKzOhTHnV+frbpLld@Eko7CN)pWL!Xh+}Hp2`kVoXhnz62 z8boJ_18IR!x#3GRIDo1ku&Ya@=#1Zz_Rc1{g)?Q~;RnmM^FkCiqt!6qzxbibv3?_} zw$vP6AmvUl7*_GDqvuM1t{J04NwT;=c|MySdePi05#GtakJYrzRuSAwMdfSq@+Lbb z5`k=B_?4R)_PuVsULgdk%kg%D6?p4~r#EElM$AAFWbH zBM7oYz*q|jD9wJc(-iK$#fddt`#x?OKBmkX)CjC2G8~qpkBgX7cV`U?;K2Y%52-~f<#~fUMPbsZ_4;r?eth#nZh)} z#`cp+tFn#}VVe=0FUM{-FI9xwR@jZeCRqMX`yywn3~RT@$?4i8F=vZ7nKd$@H{!&h z7}eQz1`mJyYvz#iLRG#O;j8~7a#B^t*H$$%v7A)fetZ^Wo}|8IYaa8+MTQV+ttmOL zxBYDnl&0oCWnT+CNsr@2HZ*msik5r!{R)ZBh)ZIeNZ+CbGPw-b=Fe*9OMiwYCG02v znhNs}K0+VXW1nQAxAggi4Rd)P8F`M#oQ2XHZZ6^wuzE`J%bv1rO3R3GwSVh7F={H z=>)xBsEs@F2<|JMgGRa`M2!TydXp1bv8I9PgTrA}>zR(OR(UZf(3cA#1O6A6o?RB= zY2E=H2AG3MzY(NxBpNQQ&`l6UPdfzZ#De4gv-T{FVrAX3B|j@UVe;~Kn?V(?VCm{hKGJdq%+mC*Kz zACNBXIhZh_b7Bl@6Is)x!k6*I+Z#k3jI@$mj<uoiI{Zt6RBd9M^)eb+D;DM=yxn z&F$G5*G*q#fzUuIxKi&5QMa@1c581d0P@<&S=8)rmmIKdZ}KZiLdVTw>m^v=^{tbd zj`>`)`!`cLUFRi94KCv(cymXM1aIdCw7aR8GTjHf)shqaygUCIy|1-j?C#VzOS2h> zpVt~=v)5VhZq>KvhtZA?WO1^AQuQx9uFW@qU8`m4t-c0;-q+*TEvjznhVf@Clh@7~2XS=`M>hChYM=KX z#n^iE$3wv~9w*2$fXZ7pWIuBg&%{$RY$7A8&zisb3-m&%9O=t&7b3t2Rw-D0R}(9VMq5)B|vuXN5J4qx!Z16JfGhy%bzh_f!?KvbqLx^DuA zL8v*DPCfgrgIJOd@Nm_C#t!edRi4Nnb9_IVYb|FP08@^%qaporUr25mMiIz7@M8MP zbchUOnCH4s*&Qt_WaPu6E zU3879#8LnSjn4_5rr9A3*Z6{jPqR{NG!C?$uc(iB^at~5R)j$6qSWGvMKP(_ekrfc zqch>4)V445w9Nq$FYc34noKo8jl^Cu9zZRu@ZIbDza=N7|(DzOlJi~vKI zF3ky8=OKkQbWt5EN+lY>xYvc3*;uX zDc7BxXE{Sf+Ikm6OmVzN-41o-aAYs2Gyb}jXM-zU=-mk+JSg}N(>v?iB%<18DPC}X zkmo(fO&Uc|$Foe0KFU)0VRNtKfafl9G!tP9>>&Ap>+?fnXtt@&rwxXnztlVM$MPbE zFAIh^Z604yn_@UT&!7L~8)`fli&qvN(|*_+4wSA^?zIuEGp3N5IHU5v}R5*HDL(6NW#c79fm_p#lhf++{AGLyf*L>?Knbz5( zA!gZrlibuhOsx2yCtUi=12fl~bxd)qeA39FSGEi!aGrdlj3HgjX!L2efhwDgEB2aW zsWs`qe_QwiA%%o+uTxoEQpWWs|C3?^9?Bxy+*DKi{QOCaWx)K3zJgCZ>`tm+ssQLH z@W2H(4ngTw<|YaW3)4V`?j-@}&>C#&63u3Bp^0t@e7~98bcdDwE{*lTVob)*%gO0a z)XHWZTC`6Qtb3}UmY*DSXSy9z-_>0(W!|$hE%oO+W4=ck{Cb)G4UVdo@dHaIoPxTU zF=|U!*o8vlrqi(<1*2KwnO_OcgwkO-u z_-+TTDpX&5Hr*C`jXRWo@mL(52xzi-*{CfC%YO5u=a;&A) zK+zu>REd)#6vWBHXf*iGFOiQx)ii>i-QZ%;jJFDm{43Oi@tzL1djAuO75GqUwpzU- zh567I;6+`$X8kxB@iDxDQ?{b?>jyZ3s6wA{vF+~H@2*O8^k|)!*eF17yfi==iD`E2 zsLZc-XsZC3R;P@H3e~DUOAuvRH&y0^8l5l3^Gq>y?!O8(G46f0$u#^x@^7jvK{Xop ztBO)MUFqi7val!llwtCu>46h`@@@_FI1g@QSH1$&2_04WOB2n#ZRvL9$Ml*0+bZbs z@6xzAe^1)|eAE@TD(2jMKu_O+7A|amjUB>$g%0Dq?Yw2$ObDIrFLx#a0=FY|fd0!` zU8D49I0KI{PeXWF(iqDFHdC7~gI9M{i}us<{YE{qo}$sZzWXFsx+ySZ`}GoSC92<} zWF`)oSuN{Q&|Gcwd)Rm=*v`#*4#4UcEt;$NpL(H;;*jyJJuzvfYHe8fea0pu43F z^5)G~z;_Eq5UFh>=)nKzeu0UI8Z@CBdCkqoA-|LFH-V9ykS+(xshkZ{qOvEhJK6lK z&r8T|_nR#lL5dWgM0z`T9F$)XBRu$Zo60n?iY~Ydsa1~j@mS@>q5o%EFE=V z&*j!-lS{TlR3@|inO3>voZXdMtxA?whNsUN*d&oy{@ILEA#-7v`4?-Ha9q^DJ`MBC zi#UP(rIn^AC7YjP{05g|W%YVi-c@Ol5^EO*$&ARaJ(M@r%dNIQIUj}#>~NdEeUB91 z`GYQs_lsoLVm^yqjl$J);wL8u)*35=^YB@lDSzK+vc|2tTmpXedq<`oC zdX4c;o7gV8ZbU{#&RV+M9m;`#-T}FJzzJf#!!rT*5uogV5AIIpi!&w<#|=JM1Fro3 zwbyv?X^>$@4o2gD2L`W=oslk@YvMZKe`95s8YTz?&<9@c#|o=-V3EF0JE4go&J~PI zOu!trXrO!9iHdcES0Wo~w2Rr&8#4HCtqnc!s}=$H9E87pt;mofe2S&0O*I0shgQ# zO)Y?_-~CUj{$3x@-=4{{qH@L~)7D-PS5cgQJ|m?2gf{5h6r~H?+=b)(K6}$40uhju z2JIfH`W>2CnDLh0$PMI_M`8@NIKD|S{5zq_H*70Ejvj0ufzju_wm_jID289M@`@JM#EZ{^s`FC2aqc;Im?)b znp8u_5{_5-QSUm`CKSOyiDQ(@`SeufOwLhpHj1ET zldp=y`GSfnJ1=O4YjFuP&GmNpkmB==_~C8X+^fSTtfzpoV{v+^*G0G2I2~N-n>$C% zw-xAtYGaPreAFBzV?h|$sy3P~Du|VQCwT*O;o!+SS4caJ%LoD1e_7|;Z&amfda}yW zb5a2t!KR+d!Y>|OqZ~C4gnBR&pMU#q%vuiDI)6;@1#kRKCMfNA*l%X-sMRUvk?i|7 z^ZLh~uEa|qn9&W*tNfy>D_1NsHqzlma|nA*&60f;Ra+|xwX&4v-xA?JKUkMByqnJ%x2$ScDe+a|L!1p8xOPuYp?%Xu`oGjos3**JOSAQ{ zD3V79>JaT%7+88CgPJVUQ#2$pu%Njt0escLxQIm{Sz67@{amSu$VjLA$}Dtci624a zd#G+TZ&vc0oYt1KIsL&y`h(AYCe1UGRvby9`emS`@P%}uE#^EJ1$2Gk+@iP;U91C< z8V%?>64ZzXIS%Hoh4*dls2ndG59kd%PFhi1kbQl(!mUbaw8xXaq~**NrKs`W#_MSO zlY`Y@TA@Wo)vL8z{^g(cCp*KGoo$M%LrVv3`_a(x)N&NM5g+`Q(Cr#En@@Jy|7rnt zt@wy9^*<^2D!pyy7K19anwjxJjFHja8zvK77x2u27?me6!l8}U7sbjgd#83*4o1!whY#I>FAvC7$wivsxfiS#cxf&XN|{&ik*rov?MLghpp?F@?hdZBox^*5ZNORjvA^Lx%h@ol zq+gr%uzCL6j^g=pNADlNIB0cst#}di?h5|eHd40yzrewCQLBJQ!vB`7paA1PMH%I) z@y&f-d)?m28jf#IGba60i;yzxKM#P`)t7-`@F&x1c(Z%IFt&jNZouJ6;L0fInal*l zoa9+2r`1ttZcyO>o(VGOJs(%ARh|_KBb(?_o!l(B9>dC#vWGH-nccXSK+v@~Vk*0Q z>K~XZ)>nHf^C*i*!Rk*^!X2V=b;2}+s)$AD@Yxx3W#AC^J$B{tE=})L1q<_U#kNKI zbsml04gI2QVgC#4cI!UxN64tRy5DK9S`vEYZuBUf(5*B`5PWIy6<+W|M!ycO?z4^l zBOF}ujZN*14J!9ZPwnmUb9l2|LMndaA#2M=UH!1qUBmUhy%;Nf*3!HHmPSyRAh^C(D6*Hs+XrN_*poi2rD0FdU-cVo?a0A{pdS_E2By zF4o+*sMz}jZR4S;?b+|*Yd3y(N77%m_#X5ym4Cnaf#KR{-|g2cs@~Rr`1omU`MoSp z_3PMsj3Xh~x9s*oaRkWXlU|is4v#GoQaUZ2i@GJU$j5XZ4#cUcF%{-spBM|bp#ZbS zNSWwBw?<+=Q9CKa^%Fp0RTQ(0nonw}KLR;&%3WC}j#J}=ReTLh7c^TzW zzYW!bPDT$=_*DL|coRoP1TEhWIh?OPpclV>%}{maOX0Ysp@z>==!+Zwg*#f$QrV)Z zTvwpE+Vcwo4w#nhsWx4x%N|e1czXiLCAXc?h|&P|cQ+C~oSwEF;+`-Am%^2pma@UO zGZwGQK(?eSkEV8n0c9T*3!}Y?EP%LrR8fdoX^I9TJzGVICVWgvRX+BFzGak4%+!JV ziIC~MRcR&BdSE0#ul~J*RFx2uUCo|+2yc>Vpn}F?@{f6INf;FVd4`nmegqeF?UYs7 z%Lo)IgFKH`b&;-39RK!%HZ1^I%sL6%a%)RjazLBuRm=I;{%9ij?7~T8zftjDyKCmF zf}lxB(p6trlO%sj^p^KUj!2ge&D<~=j+V&FPRgxFQPxs>tSJEevLo z;KgoeK;3Vkr^|*uG_6!@T3HhfHu+A_nz1qo#vx(8<-+N9F%~@;-oG|a)%VqVpNK_+ ztK97LH?O|>&TlN=m{fzW8AJdYGi^ZzXXVZQ^(n~7ZUUrTMSG7VfslKUo=1mONimxw z+NBRxVjzXDp$xi}QN7nh*OPr}cI3rAHZBUtSXYadA6w==rBsbx*FuO$f0sgw6pQ9VmqQXe=Edfvw#KQ0SqxUf=M)I zB1+;RIehjZ8fQ~(dy{zay@9F&Nea@lgaz_kqvTozM)OzC=~$QYk$uds7B(7g6yhM+ z2FE;Hp)ts6<=GfiuEDB&$3A&1Ji)$8(7qyWtp|2sipbv)B9%$;ZOu}??(G|u(}1ic zWQ0rEq6{Vq5Kp!(PORx0VX`ixAR!XQW-g1oMc$;Y7)F2rhg$V_1bKE@JoU`2f+i~1 z$ZG2R+~zyQOvn|d+|&F9e(6?4Bj#DEf7nL@QZdsM6enQ)x@C69(`MC)dQA@3FfhUK zRIoBt=d@J-+tJyzix)o}QgV*|&{WIG+>R%$Zf~f)5EtWD*Ru!lo8S4xEl%x~r2>+# z{(Q3I?o>Eq-fdNW&5Fk^r(Kn5jXvdJ5hOXO^q)n*?d~qA zh0^oITZ?+Rl6FE+=04BiawCICi^EPI;GRgM10RsrK9V=@rk@JFde1E;0rOL+Qoa7y zLV~R6#A{AQhE1b(gM|~PVnMo7-3WS@TTMDq?B9RK$6@O4{Tol$c9^*U58yg!t z4jvDuf8~o+D%F9xWoZLIsp;IBiE7OJMKRg!$B!S5jqc#AOu)Q>J8SCY<)wa_AHmSkF>Zm8j*iYM{XZM>^73*_Qv2pLQ&&xW z{mr#C9esVk2pzPzv~;!JT3=HmsBU&EsoUlAe0?1oza1JHTBs}q`=_z!%<28*;qTwS z2M1<&{Ygnlot=D6>Gk=0+uPggt@qKiYkEI;tD0R@_W8N7gYoZgb8~ zwIC68XFCmp5k@_zDaEITrM<3T9#KW#4t~crSZICfQJG%zgHiFCx zvqrbHKRz46x=XXfH(&Hu)jUKV3lO7bz7&;!W8}gk2H0HZ+<}74G#IHr6ZBnJenJtV z@mBBU!TxBy?TC1R8|&%si5qp?gAR&&Wb&SML%(O`br%`LG9qp?Yl)d7KR(5c3+t$M zzz6mDUoLjv^cukC=g0?rH|O#1zTI-=t^OAb`^jm7g!`+yc`ihrCGg6F3J1bee-H!h zH{`~`)s+WmpG&L|um9D)Ar6#loeZK*Kn_6M1~%sV4GPu1^$^FM?Vd5YP>+UH()ylf`8UdVb5>57*`Mrh*KbFrn~ zCyoOzpIvblBuYw%wM^-3(48j?qi&*oL@y5VP63{d zo00Pzb~IZwE?ntvYrn-f9n2{9Bs>X|;vJaV`8=zNr7rv)kpvQAQ;W5F#k+maFKka^ zg`Zau;Kdtj(+10t-WX0xk`>!>n=;ME z!B8*T#UYfZ{Cqd=Kl1YF)*=1 zX(=#8*=bQ^8CJ|3DSt8NCKkCo@}{V5b~95;Z6d-~s5a~b&lnqmMRtG&zm+0akm_OF z+~VWTF%3n#T^6j3&y$FqLPpKe7{y@Twb!=;c%&U*&L}~9*oU6YMBpJ(DEQLNAJ`nX zXB^g%c2;JnFZ+QJk)#!^A7yAFV20*;Ukjp*PN%&QE2-tIs7;ALl4G|2f}z04TMXY> zoGscH^KfD4kY#^l{uw&7np!Sjaj@g&RU)>{x^XO;bDI>&_nwOJp0k!~Jw#oRHObcZ zxUL2_O-46uwo{@_YdSK5%e{b)Zt5Ap)SmF-*{H;7FX~c4=Bsg`X!t&-oS}!Mizjva zQ(%VTmNptDc>Ho!<@Gex;pJL0`z3X6xi6(D-(=O!X3sKqz;l+K^YL%-B0XnxV1#p@ zTdJZKnr5G6y+16E@x<+c$uLFpDES}vtc6r!j1YE&n5>gzJ~0Yh3u#Pf3_Ge^nk+uD z@h0yKN$h6?cTnCJur2 z22RmN*tgm&U<9RNw2-m}8Jz-5z#BB=Q>;|O-SZoe33O7^!fJn!0Y$u3hF`Yt zOI1(*y>h4>F{BB{Lj-Q)2@pGN*f&cx^~Auct1*wSZERe)a2G0(*@0waWOVuB zkyn9{6o0Lo*9u91JFKm(ot>Ql0aLlOqOuaOKTnb_e1G?y3nJ?;&7VC6!s@@Ptt+>7 zAeIZm*7=-YUIO4kV`HOVw*vAm@aDQxy zvu?$)iXYqW}KQ7kDx+RFeKUv5}8-9=MrFmfNCC|A2}?nEkPGd&G_$QM8Tt+nd=^WkZq9!y;djYXBdN~{Q~)+8 z*x^8QkO|f#Lkk3EL)#ptA*ruYZ%5LgrHkz-$9|P@vh?N(6YwdA>-e;KKK}X7jOP-v+FJ#ze;?A+@v#g>$kGQFieST!M-&?@qk3EWpV3sLA;clD0jC>iysQ!(Ild2_ z2jJHN$-Xw7RL2rR`X(fHL|iVv0Xq!p6jfeKqj58)V6JcF!h54}B+nsAR45PwPx zjd)^$SheyQJOw5eT8v3__$6IX_t|eP%{f_VP5HH|97gU)QaGrP&&rDVm_Um^L^lKK z*Hpvf4oG~u$bSin_j~^IBC(4hxD@2Y7ME03&LD$nrB5~Y6zkhrQ0`09^;(h@O+kQQ zO+|)pRTm(jA1-h+>cqP3=z@vE7$`I0&0tI_lZ^v<_ z9~?Sq4T_*y;|QwC$>NTRC@_}3=&q*9OwL1L{f4AuX1wymnxweVWFNC~-X19f-)`oc z3sX?2&)coN_Rg-LM(m;B3x5>4{C z-Qn5E0c3Tjtp!PNPM<1WXeV?e~shc;rnIGQBDX&V)fq+sQ(ld`G8S`BGf^59`lq zVGLb!s&L#vn9wE2r^dc89ozBxJ6keHCs34E!d z^)FvB0+u&mBQGa>$cDHflt(9q6pF=N-F}+B`x{PslCL;8)oJfZfqi#eON*H-==fUl z06SiFUJ8RPi73O!W~Rw~0@IY>@@mSaxl*>sNtj?1fpNfCI!TZ+e^9Nu5C`{BJ}&z| z)qL?qgKvy>+!zUfr>cl1{$WmWC&QkQEmNgcD_4WRJ9KItPhn#7HPNY^{74<{CG7*E zajS0C)|E}A)Q8Ml%Gkk;pKUQStL#wfZ}d`UXJ_(#LPTi#r9+0a7CB0czAo8XAP>B~ z@%GO9@Nb>CQ1i+C6ny96G5eUV%&%A@dJXuqHeSMpoLG6_YR#xH0=j6APVy?igT5SF( zS~jm)Ol1PUVS6s+!Y#vT9awRtx{a&r!(ye*U+V`TumeAM_p&<}3AuH((e4hMAbJg% z36O!q1Maq4yWZ~9vk$*iynJze?SGe$MO$4Rc<$1fYx{gFT>{sanjyP@pr1C2k{Tfnx*lIWU$Y;^(0rl~1l z^TLhVg}IL9e|OK8&mN|71Qd|nx%1Nmn9yWP3cvK{lxjCvB z$`M^L~$P=Lq7ZQ7AGBb#hsp=@( ztqN-|0#Ehd5P_TZLa(qQAe};pLL<_qa)Rw3QsRNTY5|$bpwXm0o-zeyAN&E|X8JJe z<`T^!*Ub8BB=J7r^QSErv<+p*n}yihfn0_sA&ByUq~NBOsPLxXIZG@AH#-Qa77SzW z%P_bsIahj)&t_Aflf9|ym>!9X*;U1nl64pXk=x1}4W1V82-}9=9oy`I}BEB7HVr1BoZi?VDPIrFrHS@rEzzn<8tI0cq$Ipv>b z#GZC3DLy?~Iv+N#G=(Y`3{s>lzS@#MeXuWycqVUH{=jtm4n^uQ6+|1K{wqqimF{-x z6&GJtm9Ev7#UE_oa`AvzCE|kgoGf@KP|t>S?M&s6rcom%*By^Xjpvt0A}0zr-&(LW z{g7d2BZ|l^35S~J4qfq7-%Q9}ET;iG%dH4k!~jJnqwf_@2`@St1bf>z#DD4WRY&WH zNltLsD#SS{{@`QMmJf=5Z07Y8AA~UKxsSmi(rWzLC{u>&zs2kh%FrubapsioT5(SI z4J9X8Plu=n`&$b+LtS{!gtRA%G?9kN=RNlxXrX|mAJ6hNnnknNUX+`+x8&9$Ilk!o ztu#s>*b5$Luo5P#!{$I&?GKd^Tm=oU;vP;yLvq4nhKbxw!Tj@T9EvHX3G` zG;@}2W=Z-DHuyyNv9%E-BO-EZ4wUKS-VrRSX7z5fUqqDG?hqCAlM?2@*c{QsEG znL2s!cL4!~%oOzWdp1^l)TO-^%R*(ElyS($U#I|3qB|GO_NRf)*oPe3u!w``H!weA zI!EAhgzPu(=iA-a*X3bOPdVx|jEbl}=j1BLG&Ey&JTw#vEVzfjFnl|4!T>WIlI#)0 zEbZS}sMMm|e{6|;bVKd?dzM+b-4@dFMH4$Da($IK=I$!~pSMN415 z%lqGD8k>bz=O#dk4(&Nss-FQ<_{PVBAEvYUyw4UZfBk||)E?w>sZ@E~;uWHp=jl+-x0@SQx?0xDoNXm9Ic_2ATZo1he}pGql?;mD_=eA9O}fom%?ur~ z%zI>r6MdkXt(L*mjd%8m(9q3WUxdv=s=3$#2FegC)^a(uv8pLJXzGLBtrGOcTTe(? zIAoyeI9PX(WGr`U$wX~Wl(4JwPtmhaO608lurEi6fruWFQt?G~BL8D=nKkPsIJ zoNn-rV(c0Oo+5UPT$5(ST{#@cD$e;YVkiaJtrUubuYJ?TS^WqV0Li2BY;Xl;2>v8J z2^lvuEQ#&lV@7IIRIz^j#o*dts>^MY0|k$?UCLjs7g=eFiZU`?O?5AkWjJ9nSxiO2 zD!pEC^N9RUJuvJMpge+5V zt$HDffjrVsVQcx$&@4@1QM-Ws5^)#NX*J~cWSoi5qPiOo5dw$zgogm91>su|@@BzJ zvdJ1qWd%yjvcUg61_zUUxcp*rBwk3}#U2hm;mVi52nbv0Phv&YzP)LmwG~wfVS}cEPb@WOmKQZ5L_#dPhM7(TVc5-ZK zM|ZMvVtWv2Ez!F00h#rQCq)cq`p+gRBeU2>FkFOK=(4CWdLOX;@LCy@w|IiioD73B zIGB|>?A|fDil8?#1;#QDY7cU-r)FNzY^&`20=gxMX8OCp_aT;daFG9sa54g8-2<1n zwk)}vFfUoXt`JK)LH}^CC`MCu5nyjBO&`QMEkRC!IM>r5Y-kzgv04sqz=4A0^;_kGbp z)O+~f)*v}!%Y+dknz__vl1p4aJNJIsN|;|Q?{&jIX=+RLYl%e-|G+44+5D{QK0TRb zbKp|fz%83Jm$L*~Z_0zy6+Xg#F6%Dd2D&29oB;sofb*zBpBYhW!g^prsm059nU(|I z`-w3`P8{KwU*R1T@fz(E0&R}Gra3(BrdhKXpA_806*(vvI>=g&1u<r|-R>bN%qgf6fy0GwH{1~kkVFa`dCZ-lJg1R}X3s^{uc}5#n z51i5@Z+3P_w933Y^{bcm<^lXhI1JFi^co7D*kY^9Krg`ffedYI&dyirb#!!6m<$ff z`#tsHpOwq93@HwJ-QC@Pq5ic7Jm_vpi?j1eZh@?^xVUI3JC((A#5vX5+q=4ocTn2g z+zdufPd`IWLfh8XHs+DlK|NB!i1cd7PMYp{x!&4q=m01cqoa|~3mVq!;zJd;;D7Z2 z2MgdpLBrSC+$;gn-qh4oU#~)q$(@B9ty8GX#m!x&UJjg2iq1TE0Y_3GtZSbEMs~o> zE-o$ri41B|c18wS*mTi3U?y$+0$^QqXj?l4ZhnfzG5nBQFJDEas*Z86pi+B8Egg=h8 zw_XBBY*r}w|EmQUdPz$C#tHl8N%Pk-hO>IN_DQx3&7Mf!70K)O zLmQaxfwZ8R=9D4f2+~-Ib+ny}lb*#T<%xVQ$2@)XigY~Dd$Q-Sh_ybTzos&?3yo9w zI&TO+5N>y|_MQF3iWj?=7((1zih1Tn6w;T_jv}~HNa+j?G~gVxu*`AtF-ra1I|C)i zb>?qcdtPjO7kzW)gVNLf1_OAIW`J+|bBa`P!-=^u0*qC6c5mYiOUuw0_~u`B+|_Y? z5?sll?7UwCme?=3!{^qiR+*<}d-W#}2`d;MsOk+QWm1N9bV-6YB8@@xLWvC-tT6p(cmb;}-KV{iQZ8WbfPxbGMctL(33Y2P3vguL^GM> zpWQfEo+@4C1?Sch4sZF``QQ^Xxj{0arr61{M8W@WH)sOH7sSvm2K@ zt$}&N)9#|yM9*3zp%9=KcsoHR3BA7LAxbRRml(6!et*K=qT~8wgiHt7H^!qGvE@Bb z!kLo#SX}B^FF)VY5Dh$J!4^8l_$<8jeyGNOiJ}of8}_gv$F#fJO}Di`GF-k?A#Hs5 zMRK~rUHPF^BgjiuY^4BAa4C)>_J#S&f=j${lP>X%hk05?jRW))hWV@kf8>iE}*T}btfR<-f!9Ngnhoa9OS@h)OKN=wC zZeI`zLk{iS#0)XeGI4-wc7i83-iW3iR|G>-plFBx&v%yocqNaav037@8}E^9QbV~6 zJ9AEc`u4i&C{YSF-+7`E6BP(ocle+SQD;rJv;M@-w<4Uqj#L@}=ku~j@1BN`P)`=R z9nPPX`F_IfjRM7Wg}Xtpbd3M*lG4vhIGN0yb^){~>pxn6zqm3?mQ8LU+_pnFj4In> z7wDn+9FgF^E%tvY9(l6;qez@GXvzLxsoTQnsI1wOUduFFt6n|`8I8LFfEkaE90)M5 zKkG6BM>fdo4cCgmLF8GMjoO%+0D;`8e|3;z0E~dLv9STL8^8j|2NQ_zK%8#hSZn?v z@NeBY@vDS7pruNfi_Cf3r~1ypk(`oZC97F4$e#QSd14Wc6+NyvTSZFT%cN0T&%og7 z!Am&IskH-0Us$m7?0Wxm71jehGXTTyXHddhq2Oe}-bv$`(*9_vsWJQ)oJ!LxaY|l0 zE?>+BoO)!F!509U7C6yNAN_~iqww9MBFQvr|J7C@P9c~FsjI7}TE&Z#rHo%(ULM|g zIz_6W37EDarc(hJzvvtsHb!dE7f!kG9S2Do`vOQb1z;;cy>DPp zoP@#}9ZTJzT&fr?E$zbu=osM?*}hpuBlLdV#mYk|nCh9F?o$$h;SEz=Ib&Hi`DYIux{#J@FA+oL`%w-ZsyPvKorp(bI3 zUs3YtBR(H8!u$F~MLH7)%*8hqS_Y3#kj&D`Q+_Z9y&{4m<~#=WM@DrFoBS8gT+kC; zc1Lwzy}hr1-7%&hMr<<{=u;XSx}#e5Usc-34n8>2w$ABEGy7ciUFVO=;;lu=tvzo6 zY>M9&BsOy)Zyt%fXqI`)m@WJ(L4PPc7=B~YUgPk#MSo|E6lZ*(BBG-_cNdcsZqdbb z3<;HY*I!_3V4=45pN_PaQe5~599I4X04oX5fEGESM!=OF;~RfkYPO@7gGmB(0>H-YD$^lD+K%MuZIOYk!H}*afDLZP9;H1TB&1EUh@!{*t|Hz-GXx_ z4?gm2vTGTroeu~6s^QX;Dd9$!D%mLIC1;bKcVXR)q4(FTE)qA%I;or_HjPJhu8>7% zugzGd^t`F zt6x3qO7etRWlCVgA%t^8om)Cc_9g@SbI9tdhPlx8zYWd9C$PVNX_=44dnA#>6REzd z=ov`7+@G|~M*y`&hGCO?EKfo>`h+y2Yo5)RGs^%((y3&ILlJQuEZnb&SKFouBIeC+ zH0POG9Fa!Y`>A>8BAGEpo5!r+$A&;O9#++zQ0~`FbD&&ZpWs4|P^1?NFU9wp$}cvW zDnuSOK|6vJE3l|obmO5JEV7RFn~IE;EJ^zgcu;e;LhjzA#&VwG@CL{$J@ZE<6_ zKZ%BP(lq0I=biJkkMO9i{joD!tKN6nDoqQM{{SB_}CRdfUP7TIe6E=4~ z%YsceL-O8y(<(}36F=!bGe*QHB3o`$G*T4Cvop3cQY&>s-jHeWdpEATH-aL?in4Tv9vR6c-*| zUQ>7hK}ps?YgPE8q8 z$i`s;o}WF(=pl&Pp|TE>=rkx3;BJhiD-cLvl`+^GXsDPFiOHfkr@qFaT_ivzgfUB; z0I@c%S8;Xv<%Qc~ljhI*)jzGEiO@sS8&10IQHO+7)=?eH<|OG~kAl0lLs`7PB$=J= z4krPeNhXCci_1BLwZrrqm;(SGakEq8bIHq7p6N0+cXY^_h*{ax#VOveITC22=L)9} zETW*GEG;fdCJ0M8D;uh)O#@P%?(XiUCJwylu;L@9RsgI40pQeM>&E#L#Y!b23uLl2 zSdUCKj6!O5gKwHx5{{XQ&iiRg-e0iqlsxKcfB&+&m3_&e3is7LMN~jE#dGA(%i1e? zpJCsd->JIYIWB@sPMBFJ{2Qn6Nq2-$bFn*hwqwW6o$iCe72MP*cv)3#}%I} z^}8d955Y$r)gOnie&Y#0l%ISD#LzlaAg*on_bGdgL-zH5Z>Ja4*wqx=&;*#jQ=#$2 zL8?U;2Oz-GzU=d5`x9!j%PR)v{M#3S5Afee;G>X%uZGgLq%Y$9$%#ejRTY+-kAHwkQJ-k6UmcNK31*v|CC>B^s;?>)H2bq~4srqfn7BB6OzD?M zUoQ(J{Pk;gNA7M_kMDqqP!%+MdHU1!a=10z3oHy{^)J+>LrC_YNyOFpPR2`O){u3%%Z8Jq{|6hmVV_CMtwq}3I zMUX^N+D@J!bQ&U;kkZ%kfmF8Yd|27-D^JYUg9caT>iovwpVK#zsTZT!wFjflW8G(? z&JjclZ0^yx$$vnKI933OZ4Cpp%#%ZDgb?Npo-n~U=YFhtpExzLl&!0D`~~-WfW)Wf zr%z_b_g7nJXKq?@qj9^5;#3%MbI{KqN^?8aZD+W5FO-=FpUF*0;uyox?+(Q!Sd zcQcsJ1yJGHT4Yu+1Z+9D6gct3#Th0NQ>87GeR?TT%ZYy|kzglLwNI?}Rh+hlF#_@W zAnFDCnlT43W;LZ}!Ni}$N`1BxY-rPE`b3)H77%Cxyk^(q49{k*%4W`tmXd^LA(;vM zr*&CrQSdKYXVZUykEbUcR4*#V4TJ)=+RRdFZkkA{d;U5L^aT!Yn#L@-N|@|AbqeH66OxY?JQq|?j)xK>92KL0 znWFr7GNKPs(6k}TMZ%}MVP-U3I#Bv%w1n{5)7B#bYZlQwY@{&BbE7q zVRH7-`U`myMq@Y)K>E5sbe!jDB4RHLUMu=BUw|ki< zO(-l$ehxJ9Yp-v)YnUSoEcKJJ9xFL_c}8;$n-5l>GmR#z99K=V&diIwiU}N|*)!HZ z%po%ei5tG+abt{KQtV{P`0r0wi160@a=t7t=vMeo75X2K%&5(hGmQfMQ@*$#+!8ck z2T-;jAN+R1VYE5Z2?0SKyNK#015%lh@Kmg==B!=q?cTuLEZ|TOmdvrawI#sGIirnX zzqzsDdozdwXAnP%*8_kXoSa_}p&?<0_io0Sx@B*pff-t~DDaL)G2X#a`9eH9$ZIR6 zPTX7V?mztfbAr|?euxk0!$Hn#0)imvLgn(mCEkCnlkRB}70nl>WHGRN8o4M5gMxZQ z%F(Ec8v|!8MZ?n2p7%YZ1c{9L5(!kPlHjT8tYrL{5-jmFwfm3V+5zAR240IktL%Ek z(NNhN!^~U-vT)mqZLWBE2(GP8wHuI_>UH~du3Z3dyHcTC3}}AjE}R&mF4OMlji2>a z25mbli;(moN!kq1>j1;S{r$VOD>vI*0ZKXvd=H?qiEl<`XJ>(23qbY&;%}K8k3FQn z1Mt`*_QU~&21k}`Okb`!=ht~WUC%e_ID%`xRcp?WoMQwJ=5rz04d-24f0Nj@Lh%uR ztb0H-Uv#TjV+rR@z1)9E3D59l0F>z0Krx+a?V5 z5fQ2rn}P)|INY{NJOg|FboE=+kX1qS&}h>L;g}n-qZS9$1274*t0+^4`7rB~JJ{kh>n_qlZONu^XaOiFDVsk4@ z!j9u0n~gLdNoQcJ!(PErgsQ0DNI;Mjgd&gzWj6$UI2)D}Lbx{~q>}8(r~>qOOa%q% zD9J89#CdmcZLn9Zw>FsBBD$!`bihHWco;M)yBb@q)DjJB`wkv-`Ncxsmj)@B-JbO2 zh5UmMjJPEiY#TbLgF~_*xP^+83XT?!2@D4WVgkoObr(xiP!#gmsOLnCYK>&+Kux`00l>c|@qC0(wghr3+gl{bJL=`iU}Gn+}ee0vQ4#*1+<**3nm- zxs8g@Ni*doD@KJ)W;gr1ptP~Bze<&n;;XP~2vi&3V`==vK^0{Cn`D9Ya{Z4tF;Gkt z32tfov68hSB&$t5u(Src-5>kcvC5{~h&B?se~7lU0BE27Xi$VN(WQSM@?lygXr*dV6R%DlT;b0{l^o^%VHW<94E4H)key0-T9!0dxK&Q<2|S?m4x&a9TkGt z?3s%Xuzqpu23}uz0)i`bMCr$Wyb;IXu@H@E?szFGwqSgsHgHX-iH*7{H+r)ZTynYk zGWl-kf+j?hO&Cn!fHs#wqlyl$(Q^w9+x2dw7t%@1XgX6V)%l<-Uh$)fDn%{8YE)6U z?IsUa2M{26$U}+|BA_(^)mGte-nK&(kv;;hY7Q7=Crji^^Qk{jl^$A<-d@hf#G&H+ zb}^Z`dHJr0%n4F;9$f^yNC13hCWjFy%VsXC2^(sNt z@k+A@i}Uv+u1G8AV|Iio*$}Uyn}@uu(T{<0g*j+t0gFp!pq)Ys#2M;AT*Fs>k*(e_ z0Y3F;u;Dht^Tj4;i88>yBRIcw+UlVC*)&5eRF@91>tvu9J5j&S$f5m*qy93Mfw|%X zO+EjA*)ywY+L;dB?98nl@+*zKr-#Q#JQAgWs8}gH>0h>j4u(BLbr@7OiYHE@-zdnk z0TE@CfY=CN3S77eDa|0e0mk9sY^k}aiJA@&i`oTS-wBzD{uOua_)5AeyURJ5HGaUU zIN=kkM$%eAOE#;C9pJE-s$dj?htX$J!1MjPgeyJJ8Hj%&dSS?%o6CKbARa|dg$Y@N z1il9n(Q%XrjoEeZ^owqvAAdhjkx7Iv4zH zC0f3aGHq|3`26Z>tJ^<^d=;R@*>!=AVBkFh0)pyf{Ltc1W5V7C{G}9QO8!kThR?>C z{(o*{q_Y6%*Qy(X39!C!Za}NXZH;0**EiPt2`+c@clM72S+jnVK8;M@15cUPshq@w z^Nit8ew7NyK&Z=$5e^0I)hOkoj_=v~yrP`Q>ldouvJmX12@l!oicy)UmTj{r@s}jt z@#jtDpUo6v zt3UjZ#NUd2@t;okOzErc`&1wb0A#3djr8(jm9V7l^Xe^``f+dLWFXU5eR*4_i%s3t~_RG5_b4` z0)owHVtje4b!1ybrE?YALXXBZWF2p}AoYG&zxU3c{holf`+)b_gX{oz(|b)5oSws3rim^ zmi4PhXj(MnyS}OFOy9xxxi!y1xlp(*{g6gUd~X78TnMHQu(yg2#e&ul2H1p}{x*OJ zz~sS;BYkflc!TZr?mxpz^J}QQN_SUQVc3>K^Q&?$#4Q|?#sphR*8(+5tnBAs-tCcL zynooWNWeC_ewT?ErNJBE45kt(?=#4>>UO3lNm7dZITM^PW^7La8+39D*l#rq$!Xi&H<$MU?Ig&2C?=Y0zl$pA5Q z`=^&ztxlKVt)-^dD#lu-NB;ewKgpPtZ3QUZ2**sX+PVHYeHf4cbtfjkK+b|b*7;lh zk0LKRsI&KVx2`val#Kkm za4p6H#l^0&e_UXJx`#wc`X!r|Tynv)8g?l@zAh(U=wvPBe3V5T&lE@PO&Sspjck4$ zHVI%)b=HN-i#-yAvp=lnLTK=z8LV*hwLcz&u-T4WhGP*FKi~>VZ`mW`Gt#vExI!LK zrokfdf&n5WF|S?wgZ6h>x~P$i5b4Q{Rb7yPnN+%tZ8?41v)=BDQGp+q7EUfE<2T?_ zLdQYdB;-)+F{}@(x8u7F{y*&B4u)PaKNP3uu9ILJwCW>m|K%L1;G}$p=rztq>3*cl z->L7LKm63eJUA{%daaBX9zp7?m`F6gAQ>e<+g9^mMbVypb$>5*%=EJg62KW4i)8BN z8hm6QN&v|wtY(CwbGB!WWM1d}3%yaS1Bv%YU4QM7Nc`Xl!ki%)W~V|E1ycPvP(ve9 zDe@Mr6If_Z&^Pw-041AIGjCF+S$B( z8^Kmyp7aqt)<@RK)Z`kZyb z6d*aT_&*xJJHr*Mil8Zyg~H4Yg(f7t36(6nz?sTJZKxm6M8akB5}r`4CToKOWc^a3 z&0A+PKmEB__w(<(EXj$*YgVINgop5uk#tK5`}}Z*<+sN!4Z#2JLbP3x<@pkq*Bed# zW1O8hq!wO|zTAWnEeMb)RHmsmgXs4WDLiW-F7tg;qjLpvl<*G*B3gr4L1_ce3R|1b z6mutEQY-?jc=(|?KwQBEe!u^wlHqZ(vW%x#Jl%FIbq?tr&9+f^pOC-_W2_kolB1~X zt?ww`{Wc7=M?`kvf5&kD^jD+83chJ1=fh`5j%y zy!}?raDJpCCZ;P^t_TzpsFlSvu6QJmT7p39;DGua8tR+T=z%iN@SQ!xGz9;NA@S=3 zamMh>KRmOR{yP4s1;fLtD&9F0qru?aTadU-x-OhMzI_g$9`F`*YBt8dS766_A zoT$|soO%8NLH^M{_xfNy7CdEmc({GDFhx9Q^K4zEkLA;Z`irZJCTS5X{T0)<`u9H1_dYN^$Ygs2w%WWqc#IbpFe+YUOELmM{AvaX;jZ^Yh>T*j*UUm zcCuvYGiXnFDtYX?+( zFVz@>Dmq?4ewGpoF6$f>1~O?I4K)#eP;dChzOOAPX>iJCzb9A0Gmx10aDPikjKZeH zHBMob2XT10UQ9?G$0ZAOwTP?!9nC+wJYp3v<~Ow@ArRWOXLGQD^lQ0NP}KL|*j$WI zn1nh1c#FiA=}~ppcmBy@Xjzq!NTr(lRESmEbEuQ20rx{STi_ikD4quWbKs5nu6sDS zR?}7fllZ}wEMN6Gq$F2755ez^4 zreErnTw1kje6l;A%eK=LsCVbeb4>0o+_8E0VBvK6cjeUvyfdQzST-(?w8M>qkiY2( zibn)q@u0stj%<>)V%r~0g#eOQhCwe_$u*qb?+C$uJ&DUdU$YrGS@%NHO67}d4FHIb zx+i`VW1q+kI2r@Cf1tM8KtzG9fP+KR&mHGGn1)FS@xwc5Sr`qgu0cPA$bWCe3O^mw zLBt7z{iPrC-ij2=7KK4aeH;;cj*V#O*CB;A=U7u>TbX0oQPhHKgz8~4GxqriuTx?G z6cOBJl9lvP7Va`g;`#idi_QxCwQkcl9t~L2iY~7(m$6uNjBrOCLf`I3SR4MxSB(qP-37 zksL+xA;_kpDd_J)+U&uF(A^h2$%j*?+gN1a^{~;sgWZ<+;|;CaO_ADVEb<0|=(mTc z9{jELyE`bU8OA-v7HwO1NET>p8d{y(io$r!A$`e#2R7aSuUl>nt1>r~!ZR|8F1m0? z6tmt)57W0gJDj-N-LCuUOuz)C8;NP^(9+=R&M(t@3zQ}7eVh+)fkfAgI*>wJIa`P% zNk@6VYAf^{59q>aLx5miI*oW$K1B4$^ia|~P11QQ!1Zj(LJGn1=Z!cLgnbLW2b1=} zGd8OS5y+<~E=IItP}|Kb@kZ86-y*q`+FH-Y;O*jcgeKrF;DRT@l9CzbjC#7myFduU zx-yczOc;s>Her$XU%wItCE7xbz-naV_5HRTZ?wj zaXklg>7L;#@|}xpq{PV>r~XVD-GgB0I0+}LDI73?DID8cGPC>b^+N3N<;2)3wpI=x zhc>M~v@~_4I}v0LtL%>uL6+Ep{kq{q4Cmx?JpoQTR--xSw_8}@-cYT%?Po0<)Zj93oCCoSl*XN-pkQme zsNZCbjHncnw&7sHbK-i84o^Wdy-|AuP;>oqp>v%9<@`Y7hCaI zt+IdkKGh3(ki2b%CsBZt-<@m_S?J;WJOFXE_oB!qp%FuMcqPK z+v|%Vn0{b@gFh3btn=vZ+iMIWl`q|u#J(&h<8{OJ>sqq2UR$p5O66q>P3<(TCT9ziIDE;{QII zU)VqIn5}%=k~O5YBIj;Ts)`v5aRawX63+OBvh&81J@Pj{x|UUt`{)e@ zU@yJfH9rZOkET!r2JYWo8m=2?K$CO*r3cxuyN*JgCfmM;akj_)h^nDWPk(6~f*-ln zUP7yt7f7D;Ds#QqigDVIZ~KcQ9&sm+$Lv62(q2LK(f&_-_|{WRfoG9}VpHY=r|;bz zp5!0TQ-=e|s?CD3iEne+l1}AqoP7cMH5F})(=u<%V8Sd~g*^AH@IT|~{03XL1CI_W zl4f2ehxTZi^Jtf)H(P|FF;vkkhHB-?O>5GV2?yu5Q(uk@L*WJ-&8&AF<`fvW$2rz( ztvwvR32K|Xgh+5=k`N8B`M>(SjLAO%5&o$(}u`T76Tm%_g#i3JrbLIc7X zD(&m%JX4~Lot^7{J-;bp$DQ3j=cq-(5a=V(`5>_=b5?mUqEa$Vs;D#52-lyXz+1Y1 zPy84GaAzG@+H$y?{vkGNz=1ou^95-Jkg``|Xfb5xcB7i(Qg1j(95hc1uEh#%=$Wr~ z`>A5*!E)8w*5(b4dP_>^Nzi|=AP4^-!Fjs4e+KoGfq}VEGPA+ICnmt)2(`GSwxVG} zhXzs5;-zi>`7P1e*%@dB7#x)4PsY-nH%uG1IsvEL1gOI0Q0iF!?#(jtjqaczS6593 z)r}appT9}dl;~%F+&;g6gAQsdoW|+yFTJ49ADgO_jsKgJ0;y^=!M@v1a40+sn#H&~ z#^JMB$iPU74;=E)Q*aP%->jsPEhvtzU%7xI-DJpaIdcIfO1!+h{PMb(#rXCxr^~>q zykT$2P%!+H4K;77iq>bGOS(9#Ot?DplD7zT><;0*c^un?Xk(@Sftpn5B$3Si$Sx&BNiDL zXFPT2KzgF?bopi_QzUNmt+mhWP+CcEF2?Q@hEdj&pK{Rp>uf5e*26`}E5bwku*v4y z=g_=)7>}D)>|;72`&UzM0MdPGw)|-~sPeNXI)Ef0N?u~ijC{a5H1|U=uZ0J?Vrtn2 zg@w9ee8>`mq_Y}_nttJ!M5>1a#(bnv1%4_%S^8NwB`N7lfJqvfYleR_inSihYHGn zNya}V66>sX6`An*UQ-}6Z>ApSAz(y8qaKF|Rvf~4S7@pLA|R3|`j&igq2CD%yz}CW zHI4*x=*29O#%oQJruvJ3pA-TAa4Rj?+HQtIaPcLW`(ArfDZxWLFoi0wyfSn8I)w7? zkYfiJ;cQ}gQ(V)6_0H{>cR>EtuZLirXCM%{n{i>-{OYCPnX_o`)#jpe_mpY!cTq#eA z#?p}LY`I}eSCFWUydNEL(%M?qW+!M*d1&5fwDGd`{705^f0HoMHfM%f9 zMr=b0h$(&qV^3rwrN$ z64GFbwBpf+SQQzit^ZMkF?%&ymNERK zBx6~yBUE58IAdG>g*`Y7k=Hz^bES%N?O)Oibav-$mk4}5Mjh}_vYc&-e%*isba(79 zZ!M*~`q803yzF~+H5mb0M8v9Ep7`5smT++rPjCHF`Hj2#1xUBfKBb&n^`7)qBQVm# zY53B{Y$Cysz5m^%?PLKw7+1NxLy;sqyoB|yp~sfGn&#c$W8(|Ex}gqM49An)MESFY zchAxz1b2DO-}`R6XQneqD4fdlE6~wyQCHyNjaTxPM<8#TSLL|0PLR11O7kV0i6&M6 zTUcbWByrDp!rTYo}^ zNv{)f)-w4gljIIkx_}Vz<;$0hO#5hu;;Y>PgZ^!*lnwMdy8g1aP`^^WRv=2G*qkq| zgAgz1`}Lv0mDbIyt+ucjTTL24m+B*B#>z+%b?V0YrB`~c^}wN87twKN%*tjVq4}F( z%8yU)lKrtq5F35kDCPx?p19``NdgJs@&&j{O5X-D-kyde{e;mlVTTWX?dm89vfZnt zZ4OCwmIEH5(RwnziEYK5!90?F8NLmMP{Cpap&9df<9=ghoPEerF?HUXNz61~P_NF$ z{w9{aGCQV4=jrB62n-Z(JhCOU%KBzvvkG0om6<)Hs!%#!Qa{M6sB@1l!2~58%cz>U zvJ44d!3|%SL3reTs&_`i^q5*d5i(?uj&#e7c1Q-|Gn+sy8Ne)o-|vQOk{5&RQKK33 z4aD)$)p*lsQ-+ST$*8GD(HH&1jrF5D^q?>^ zpRe_CuW`&~pDiDFsvdZXmUtlV3E-lPVnQL>#X;stZ$jo14X4I3uz?ra*B>` zVCSEPvy+l(SmDMuxnW$r^aKLNVhB0{4hb9(HC|lUJ33Xk)21^o@+cd&pTLHslb2d8 z#B;R#e!P250M z)R1rGx|LPjZsA0aR~RbH%9eM69MRo7&!Pt(*F88tMi30)O(Mr;m)fG_X2I&)ypTY4 z{pT%ZK$cojtMv@{r15m^+Kja_Qwotk0B5o-(dEkN3zRoz5~Cy+zS%$ofqD| zqokQ6&<;COn``P=cHcZznY<=#Xx4y4c~=65&k~TvN|vN}BoDgmMf8dM&=;h0;k4Zs z4knC-tG`d`cj?@ihpuV!w z;p|VnssGhr7&5M}pC1_cG0OB4w4IlhT7zy7DJ+00+15Ap2(|UicKpYM~D0m zUW>!`Vjg8mW)J9 z-P{6*h1}?v&%Yhd!2m-s#4?Lq;FT%HWsC$x4(E?IhXMiu+E(M|=T6t>E|Uw3i~PL2 zx3{+%!=SlEWdZw`0DK(uIX>^kOEBnX#KmDW;8y(jVejBTtBf^9nXrraIc%2N!)rt^ z>)>s#)5W5gSzj1<)TN~*+`_*{M@XT;f}G*Qn<<^;V`u9y4?AH#?r1wLKDB6=wTYEG z3U4G{_%)rUmX8Uh;V)ya!1k%)YDz74($Da3y*T&CdH9KssOsMW_@pTuAJ05>@_o?z zo*rc9TC-LA=3FQHv6ybs|22dP|&9iYE$y!x(eikz%4-XZ|N-vUt1T=bWk_5w}&NHu!hj+>3D zmk)50#S5jvRQKF$H7m zedgth*^C#}>m$?FOepp#Uq=LeG@P4;?t-3<(8b7cf04aq=^r?Y&jYPt+btME9+N>I zHXar_w`qlR+e8_jtf=2yTH{i%hsO_X`z$N_7kyIU_W*XX#x63`HT}9=BVIR<_V%*L z$6gY1Gw&SUjI@sBqFqH_w#IB7t2bzOX23f$zyQ}DuS%!OMvuH!{8Qk6At7$7CCwo8 z!3dToIBEFEn=B&q9Qbd!u)~TgghpH58aZ<4{cDoK=L>*<3uXFKJ9Xvw-Pv0e-xggP zYo~U4l#gY{JHTySkXqcI+$OfgR8MJmvTtLM&DR}sul!0dFZY(r>J&;ANaL&@8a>aX zT=h!&sKte!{h~_>WVy7EYz3dD>@RB!1R=q+{hi4GP*w?N%Wm$4oE zVAG-iuipkU7>K@aT$l+iFn|aAMTx~k`LPv7!8I7qB)`9Ojo3B|MizdP=I!U?9}$0b zn>g@qtB_sHfA{QHC9_RBL+s3BPL)>jUMmNW%D;W4>qu6|ZWFyYoEUz4P!&G^gBJC8 zyU)>3=!1Z*JD$zb_>rxZ{!_RSp;N1LyAhXIN+Vx5oQsF2sF?%MNoqC$FYo@Zo!^x? z+us(2s*4^zf0A|lT<(wdXAfnIFNQKeO)53D;P_5e<@&yP+^~!1J2Ts8C z=HTn_zK%S`zys%F7^l^V%eFR1-d)8mhBt&63Cw4Jg&Oa(cSed>b)}Ul4G&l- z3byD|2VDNV{=^nP+Y0XHeC)n%IYT?-0U(9fJ~g?N8-eOI{^k+YrXM7L9%r+l8Ee%x zOZ&@Aep1(=3!7R8+?%?4-jtT+{wJ!i{&(f1?0}HaEN8|$#OrjVNNFzC_~_f4QV$~o zQKmONt!7Wma4D)d50hxmQdPTkjPn_KRr?PxXjxLREe2?vrQ4DF2@WaC*EN}rkZJtD zY%P|;wO`RhK!Ew{q2o_eQ^cmNFWh8Y2nazP{spu0W)MvzNd|0sig|jyJo5((mDkB~ z@~Upr>l_7%k2{?*Q2WR16P?PI`s*ZxGlx6m2zBdla&3Pk;7KX@kK_i{@lDLbyczZY zCb>jB%(P!--$4bEv8zzO&D-Wq{DLA+26tFq$%~H<+A5_p!Jk5iw6B&&^30wX5rTy` z$9QM~EqP!bA)`=ecgeneL7un^bC;8cZ{qto$}Xq$=j_y_cLt%{Qb;+!fvrW zepVCWRTUO-fZ7MDO!5+4AfMRdGiBj&#pf!2MkPa7UQ3x5rGNYBmZotv9VP|5ti?Cl z1C9MK$<=joKF0+s12}7l`K??{DoUDlDR)o4K>nifZNz7{gyD1qz# zue17B0tHAcrD2TElJ9SGHkrJr@8xy48K^u=q?x26-zT`!Hg~za}IQFPrWSrf+oh zu$GFM)9&c$>o09=sD1tZn@KL7VtsX0`G;98IwSqX!`1FLZNJ8^V8EDj_lqY8`2$8U zzd`Wd8%c~Na0)Q`4{H+Ej%VGzF9gNzAA$^jO=?8tXX+};$_K?=i zK;<_)-@LUldO_^fq5*MrE}he$u1ERjH}U6x^B~M7(*050T?11trxe}ngdJsM;1qNJ zXQt$!=%$vC#=@I4C=`o>e5oj|G8g>2>Ra8M;z(s?60XS?^%9XzOhr{y^osS0agX)d zuBWK6Fz`AcN=dpWabpcMWMyULxSPBK4=&r5=j19ckEjZSo`J;`Sc6!OUJnwQ&Mz!X zsJDJzeI zMON42K~}xR@GSekfHL_~2Gqhoboga2BbNf`nvRauh>IqM=L`F~@5yy6`Pgrq@0|-g zpZcFz0{l8O)uA%IHx8MVKCtJM+b6%T>1(f{-P;6(_X5C!*s^mOEnD}#DGsavq^LWt zt6MSWAg|$%o_jUfuYoUj)d+w@HjIWu-Sv_tnk2Q}GIkK0b>W{Jb9K7v<*3P+gYH~- z(q0&*5hgu2T{W;G*!}QR$$)+DIg!Fy=`Xc#K7rB9VVBp>5`!bC$QGX|-}8QpJdl6z z0WC}0XFwdQQUtHydn+)Fz_oU4p?YmaMfnYbqZC*iPgsM7-v*mMB}cC3-6LVJl$JP3 zcc197J9EK}8o}hk0L|I5b3H>Esnqo&^!>0;&Oa}rjqSXN;+gV(Y-zDY9Jv5k(s%F0 zf38L6S=*jHpuOMFMNu>gcuF!W{{wC!SH<6Z%9^)N-i9GamE9D#bdHeVt~`ZOmvCzc z8CF-SRB*;%+Y{ZwH1{xUCI9iTS|Y&c;kAPKKv%Td4C8`i><-mK5AFX_vTI%~-a+bs0&V!Noi#+R)>H+zu$gD2M z?+EfnILJ`Vm^cG15O3G$&~n2V?qRhJzyq2ylt^A-4Xqb(@s zhrC~l9N91i%7Q@rz#r3PKTD60m`M$So{F&=<~6fG8s=Z^E|_~m5QRzL!;iDzM-f6> ztn<<{X=gfo|Lt_CId#U~dhV63gmVp*ytsbceJomutp{dq*vmqGeU@L;Hu9DVFWy$Q zCVjUYBet_RBO6-gyc6EocH z23d+@PKi1H)K}I@CknDVQL7Lxznx(_PHO8}_sgn@bdOJt3RnRT1ZUy;zZJ)xRFX_p z8y3DDKU8O@%*2J?wtmTdCnVNxMwr}9cnyhqzE0f6|`JT|(%I7ZPbohdqMBU@l#CX&E{`51*UR%XZziW)d0n zx>-KrGxea}+)_*o?57&{BhPp~*fFv(MQ8Zxj5_!fH+1tzCnzQNgbcT(Vx@05NY9Bd zuibYG!9tMCSqb{Vx`D!}-C~*>q}0Nd^P-uR9tk1yOl@dG*JpM}3N{@znMTkLHJyU~ zm>^Z0MqO*G%wa1sSPqQ=%CoAn@hVQ)0Ur-|$!>ckfylux+6Ck=_q{J~@+o;nS3~kN zf!lQkAI^kB`Hcr<6Z{I?D&dW&1!Kr6)}D-;4E&FfM57%b*i;W;GdxxsxIQlL;pTqO z()s$7Cl1Z}B;1LEkD;)?o)|cGw2Qt;O`0IV1w08BO}5Sxbuso&PM48%NzC16?5#`Y zrWtkfO+@kKKxnjv-;ae4OogRTW3h^S4l8-XwEz5I#Q+Tu)%s-sTxYDkd(nmumPl%T z>z;BQee%$VCTSL*qQ#A8?yUcz|B@E0P;wN-QTF(-9Y1ot+k0?T>B2pRQ!&fpg~}KN zW_N#^&(&j-csr5(8)YZM46VGH9jK3klMH&B!bvD->4U1Cx8VCz@tKD8Q{IqzBt*6} zuI0(4U;X2cj|=f*l}7UgdXQ;6^=-ZX(*n?6Aeze#b6PzafR*p~o_wPCA3D2W*{_ZE zH7CP*Y`YI|Dvnlz-oupEK$JtNd3G`<`il>%+^@bdJBS_ACJPvnKN@;AHJH|5^P^d- zr=DRxQ%{@%Ta0nAbz^gSbJgB~^_6UtleYQi0xmke9VlNoPlW!IYSEF7@f?^QWRhR; z*V(x)=1aJcAGDg=X{adsR~)oNN|fJyA-;Er4K#=2?~(<@Jf4o#(souW9w1)dDZGws zrMfY{S+`K?@ALj6VdL1!`~81g{%#z;cWNTS!e8}$srI)C-)mu6G4Pe&KT%aUf3~Jm zmHM;tY@S>yauKOqo-)t~{q55ae=+;trV}oUp@dd9u;q7^JpAD7d~vzm|6h}i_lvX9 zn88GaQU0Ky-gbt@jgQ*%j9ngFf~BBttgkO`Xwh(2URini_b>gihqg8@Uv4>5Eb?(& zA{fOH?EE{OYt#P*z5bJP-d|MGfB*g^`6WO`~yI+gn?RjK!ORe^q%_bxgm7BUs=1l`L*92(>Hlh2W?y|4XEGP@ZY8G-|A7?oN_%{+i!aYVArrW~1Ah=sI5h{f4*GBTKE-8v9T7 z5#@db$Lc)(rU+l7NnkAzJKJyPk`Yrx^VE{ek&4Xh6b|)RYS1GiAlM;xB82o1cQ}>qMpZ2z!_S_snimCY2LPz=Yh3LqDd)l%2aga|bQPYd(6gqu|YV zDopzuHJohPqHZhW)rrcaR#Nj%cdZDzlK7U|c=5k0NaW!S&~zPSn|E_mFnQ=|^#TYa zL-YTn;dC&pVgW}oF?G{vg(%3dY%GLU!U9>04p!5bFIA3+E(lxHj_tudk{y<3ftCD# z6Gu2F=8mmA##p`vnU+eTo!<@hqN{y->Yc7R!^PV>K*mquDRa7^kf9ue`|O6TRkIM(Vnr z*jVTbP`C!x8m6^)l;dbu?_Le`E<-sH4B5akYed2nW8Joj?9OcC7k8j1ZQ1cf(`t#y zxE|A{66wB}U&M8YHOs4;|AHYTkCdX%7v-2Wn_N@nr%NqdCF)`P8j}dLg|1C03s;bq z45EZn#X#mp6M)jU7--?o@|Rn&Ic6F3f8`(_x8Xs$Zy7bUjtKF%Hj&!H0&4gV#}x zIiukiXTNdNe4*V;TUFlv>*`&`U&iWZwn+Y3@9F2M`ML$6Tbj&4t#EG1`)p)Q8fZ?p z98|k_KxFm!4gtKO#L+#coz zZc_MNan7jL1h<61bB||iUOIOuy*K2LdEF3K&=%v$`b>&K$oed&W%5YJ@Na5pcEZfx zooUhix((^)9qaXcOeZuHhUqM8=-vuBsgpQ(wtv6Yt`>`vc|5ELTcj{y11IuS;l6=4 z%Y7*Bb1k_8|4x;c@)ic*ZJdQJ1V@G8ezgfmlAW2u0Z+`y9rz>KwACutQdBLjzyn5= zi=?6GTl#wnlot{0_Frd*{azNp{LhSMm+z3vKZdzkVvU4Wq)U55x9Hg1?sNb|S}#3i zNFaQpLeba}X6p({aIKxuJ~CzpGU4gW>!eZ5*#^T`V#L7bIQ&z=E<$Y^!}^wJN{qXl z(pv?h*U}yAt>HRIL}n7)SeXrHPTqP-6<2W!#|1>Dc(UPIKM~>%;&DH4l!Y#lR54Ly zID`Wxo4$XP)_L$Tg!qi9TY^-3T+8*-R}K~$LJ8xUxAjWrnCYuDpUYG4W$iaZOyf!f z`X44VE^Oxc^`O+SRC)0zr^P^$^RvW2`2Z`+xa>na9wh!}q`7vvYIO&5UxWtfid)~V zB&(hqBoxJhvi_5vi<=0m^zg;U@Vh4o)&XyQ1CiKG^!@R~l{K1Vzq!iMjt{F1)(QRU zK8L0aEibV!)59czjy~}mL=-&ivEA4v1xb;2_+Nw;!7~4kVYTBG|8yEY3_{dryN=7C z3H2`}_5T6ng9H{|KtRBMJ*heZOI2N5;PNP;QT`tgL_> zagru(A{c*7zp*qsJ3Bosi7?UCJn&UMmPFUoR04$AgM$MQ2A`gM8^SpYWc~4aDi56oui{8hyfmU&Nb2+4J9Qd_4SE0 zJK41D!k%Xa4a8SYD*(thcTW3(1p0r^GfE^*NlwX%m}xX@57=1CAR&MU0TWfBP%X;v zgfJs7fi1I2lL=Sy0R&$#C=j2xi%cR=blC=zls{&cG=-(SwzkXzwnXeJcQPU>*Og|G z9L&+#8J(e$c6oJm?C&vT$#@V3A1=3xUl>2AF~jfd(qSS_udl1pN)ol#Hhic0w#GcJ z1*Vx~-!x`A3DQ+&x-az^4fVe|nX8#-nSxcxsM+AvE0Q_CI$+K7s`NML}(oeu> z9re(Whm?B)^U~2~SPy}{cdwF{?#m#pjk)rvpV*E2Wap9D1cq%I#p564MF7Qu0&B$2 zO=J9QYFfZe%_mzuG10I$%6HhJCB&u7pQwU^RooRB7Fgr%tYYTK^6ggwTiXQ~VCHbF z@JG!1Q!6wDZvKvrWENi7X;p?}^tUBzKLnD4-#%p#bN(_|z6+y;xe(%pt@B)Lj%@N_ zL@pgyFt!}@jk_4w%25FTMO7+!U6m|pU8U6Mr}$&kas`X!!}gk4({OVxJhmUf;t9m< z0_gdIpgaD8q1VC{X$#M4RPk|_&Oo;}h7mq(_zp9xa)Wp+0{IBc-zY1qM=Y0@Wy@!c2M zl}P#;|Kui}maH=y@?be(1jcOLB6hu4O1ooaE)cm1A1ugV|L}Mn^g2T3!T&n=??g!s(_Y|9C_egSj&gsO_Tly#E80v{pf<$RRKBpw5ejMX;0tQUCZ-NZuqShv8wJrd&idDPf-m^_U>#p z;PAn)&zP>rZfv6$Mi>@qQTX6c#irjQd{9iJGpvhagdJ~eV600`lJ1Nj)vkOL20F@P)k2%Y{I1d>+;F;= z4i2+l-jf1G?h#dPlI(9a+f;>$T4qM0lV=}FHH@7H-wg{`bol^CRd86RUIt7H|DdW4UPO|W{1}pdYkx{-7>v{6Q^ik@oVBs3&(pyU+3F0Ktys@yOan<9Dw}A|| z105e$(rV5fFb+f08YIMd@cl)3Vr;A*QzPA6UiTGL>+#q9t9J;FP|+K7Ld2I+pmMksq2F1o4;@Hqp2>AW`uF;uOn$=gT!w3D}6hNvoYj#fubHg4kfTkUQ894aJcwGajFu z*xTBcS5#2%VvuBP_eX-ns%2wo>CmcYvLIoG9USpDUJ!AQ%1)w-Bk8#w(zz_kv1qvA zV!=}-aH9N__47FDEs>BQ))nC6OB@ws&hG>|ii*BqF~;I(Dqq(got#`R(x(tzMo^?g z=5rm7D>)?Pud=!;_MfBrX>BWUFH;R;VkVA?`+-#T`~)~YcJ?}7pUQFfIdvB{vaw+- zxB)R;DazZYjqp7!Piw)kQY7|AM_XH4M@M=Wb!52feV55MQq$m2*n9vfQ(~lCASWaL zwa%;`e1{4T>aaFiOkN%yAl038O&*-r2_Qw!kx{Apw7br$UGo(Dlqy{{`E8=FFW`0l zq3{t@`4#E(9?cXf8mna>j5P!KyZQ!Z;qemCwu*{xmUnxFYVl}pWbvq(w<6A7>YjUK*}}d zIsu9t3?i-b(P88Cd7A&6aNJPdBhKq*&CV6rplnpaXoq0g3q|vP#CuEVn=OSo0REzP zFjsgfP;INS>iOdz@)i#epJ|Sfa%T~OO(y8pVSt@=Ktsf3f{nQQ>tIdY+t|oRoxg}h zA!{gl3r;X25#`glQEF-Phz+!T^!xhiW9OlVQX5=8wN>)Z-b1{2-P*WS5C+(uVazLg z*LNsD^pj0ox$BWs0fTD9n+B2Deid$RNr8mrh&=(|$Pi9a;-eB~#MPJWoRy9=c+G?I zItMOenKossrU;i`cv_o%qhn6`Dv@+cfN0A`WxA8LN_4hy(S&Puj>)oAZEM;reY4XIPJz{vOePA0G@;;#t)iVI5x?wwGCA+znE9k;0s)2l;$}X50dHH6y?%v zZxnGv4N$x$c7bn(C{_1>STBy@29`4aU_TuFLlF{%$ ziB>84!icujt&5!TJ#+E>@V3ub4ec6*a>RVlj2vSxuHt2*xo~QuNR!leRN`rCU*RL- zd%G<8rVLbt$#Oz<9jzI6OOFhGgN6a3o?nUy7sm|Yx3#Vc9IW!LE$UpxBKIdvV+?&rExu_u64`~RbaSQM!tB>Va?*GQO>ACvCgCbr7j?S-^VZuLIz-_1SHwLRG z2dmj8Zxzu2b>CgO*^0X#Bl8xGqmD`5hq{!VK|~(#@mEyv&cD#L>B#XkJsLCnvxwYa zhKuMduXb_%s#B&m)^EE>`3tv*4YK!3_~7!bczbtK<_=DbW050ivn5<7o5{dh^x!;q zPyO$WSFV1{#qfuGsXys2F13HJ?5g_te;-j^64T0i$Gkc^!#75ur?4w1diHR;pp=!f zqiF|u$D|%>vUE_&<(acagWUb;bTD}wQ=BrTZB{Wq`Qs(je@zd?IliB?fx?j~o2@wN zq3h#_sBS{V%rPe!r^4&0fRy5LVN6GSRJQnKX*p??C<`o=r@OB}zkqda#9?AnU@x6; z!mw<(d3%9NvZYRTN)&p|eWMnkQGFLJvj4Sb4b?!co26*~B4i}$8+kY3(1q2(g@C1) zu-Vtq+B`1c!BgcGyjMur0Jq5z7xSENmX*Hu(M;)( zfZwD4gf3}9j_=79lto90c*R2v1RDNB>{+g=bJk0}_h()F+=dDnqZhAx^3;A(Wzzfn zZfZeMuj<@8B;?(Gr4aB$0vAj<3>+z|Ub{+0mnW$|t!DTW3`|89;-nm!b^6mtmz=HF zR>y3j?%wA|>3ydGPMA*RjZ8l#sl#z|EFFTsM6w9l5YBv)CiCK5N-l1>XjXfG{XfL} zuhqMVvTx9!`YK1&0Ny*fTEP8GH7zUl0q@skwS+;IM3F(aBztjQ_@>*JEiHBlI^+B$)3k4(~!3bMBaQaqV4JNb~RAR|9 z=<*>egK=SCiziEgN=K6`;GD}zt#FRJx3V3w3wB*2dRYV29>>J}Tmp{_wnw1wNM|eY4?UO0VYYkRS^9qmh0m)2*G#R0y=2#F zm{;e%0{A?4cb=SoSx1w%g;g+tekB!wDgGo|W4b!?<(%@j#U#v-$*W1$XN5t=b~5I*9-0 zKZV{q&tc7=6<^0}cxNJnFld3)FmvW{H~eCSG{b1dC?qqRSAlCCw872K!w38Ge4R>~ z%xv28kToq&jw?WnGA%D)cB~JE%-r!(f*yCFRRYoU^MbMxH<*Yryc7?fivOutlN#QF7eEeSAmh{ z4jv_Fu8@L19v$V&Dhm6LxQm&&7q75#Pda}JtS96m&xWAIp`|B3DN?oOi-X7|7G+ZC z17UMU;)`Af|LWUSgxhDmKzz*?GAPGxka_z!(&<|QTY$2+oa9#(G*EG?o7E#;6E%|J z@9dlz#N!X#5kt|*->&dm|C7m+{J4=tr2YcECVvbW^h*}tQ~&Z%kl7lSv*d3HvtpIa zTpk^%z(icc0E)-E;-^RiF)Z2!*#@!2?g9A*Z*L^33JeW6;0U3eTK-)}+&2?OU-Dpc zKNbR^<;0iF_9;NHEn!yc)~5OAhxdTG!;MD-EGIbd+g%aO{aawM*Yp*B2^df)V@Qeo z$|Mvlt^UKfJF3xt&{~^F4=QB%NkO(*dzXDErJ&_UL;Dz@5nXl82h5vS5@uPN^>kZ@ zRl|VDNjP@YN$1Up43JF{kA}tXon4Xfw`iyGdL2Q$k zOLK3@bBRAlsYB%K9W7qtv*Mgb=&@SC66#c!OT!pE5S@V%UzW!#V#Os;0yqh|5+mI^ z$#h?>ZVkwi1eAHk!hem>_(a6S?W0L1@(9i2Uo0GKR4D>A2{VYJSdHmw&rRzYIr z=m5psL4Co$i{9mL*?+YaMi(KUh-YM6cD&;LG`b36cz?*!Px|QT^vY{BDhkdzou?1b z96R1Wj`cYv^GGLV-@zoObhb6V6t`0{f2p`)_vyM}r zr{=5=&7ah8eiJ&WTgC7Fj@}2)QXK=VRZpz1e4s9R-!s-{T!tQ8)V$0j@L_4>2x}6_ zDE^I_w&xFi%t31Up_=5Gt1k>wE#WEOrM&-$_3SWEmbtZLx}+V-C5?IKjxJAy{c!Qlb zu_mW>c3iV>()H3RUdn98>4R@yeV<`gC_8|&MO%iens9UrgMYE|)K8d>b0H$rR{z(Hi@;Nw3K z^n1@vli6J<(MFaCQ?~&?iTs|&dBr2ozkfobY*hnu6bh5?*|6uN`G=>3GXOY&{eMio z1x#FB*EW1`D_-2)-HSUE_u}sEZY@^a-K~XEoZ{~8PLbm7ZvVO8CtvcD6B5W|=Invl z*It*b^^1ffzjK3mY^`MDLn2RjKvSQOqJA>bok#rGhkw%Ilcn1+Bt1ikk_H&V za-f|IelKP3GKoxIMc*o_|6@?gk_pv=<|704y&N1P;q*O$e~x(nDO-4 z9|d=Vb>_f7l6dcuRC?Y-zsdFsx01<0+*Tp2dVFqMS5T2FpVh0NXA7)f}|-`e)E_vp4f3+~nrwg5)2_II6gdVk{-14uDnV zP)RT$D}aVeb+fR#%5O1-3qHdV)qswMh9uXMOrQb`Jp`jc+tRZ_QgX@*185=ozJpP8 zV}J>=rp2jLr#2v30w({!(TgB=sE(NUNm2w;1e74HQxTw(vNLWL!9iGVA5^sPjq$0- zZ;^1A?X0ZwpT%&KV_w^jGT3bpr@$V|N>Hndi##9) zi;sC#M_ntx$Z#ubmy_HNJwD9e+TNb?U`H%;TnH4<_I{uCx-W9GZ>JRd^M>&-<8 zOOETjwxj~&s~My?qQB2~3mtcNF0A3=iZReuBz|Am(BKZrh5yx&#Yi!h_V%ZsP3lmF z9qk;$>jFKWLnrv_*I`qJ2|pn5#^mmrys=Z6N#+e02v*~_S&sH z_8jOzK|Ba$%!;O;Yjb}#kc~sY{a90*dHHsvgM7>)dpZunzzmps!VZKQ04U-aKit^B z0`C!rxdqKZI`boO;Rgx1j)|Ef+;0qxMzSfcbKr?_>)#J?M~vD^Cv&`8gsv)O+^ong z6nznrcm~VBq*{P__`uIx_NQ-its`}JjTT zh7zVR+3kC=_3YPTy)cNW0*J2JD@Dgk69vxy=LPtFVSy3<=jQhZC%t^eTL+6j`!42( zM*cq_x=>Aq@OplF$VCtav7ijMGTa(QiCxP5NaOMP_`*@T$U3aG%raIXRz!$hCW$Sg zij|LAxKMV9eM}yJ=4q+d8|5)Mz4xg4@FGm=-lmxq7mP$d=#gdeIgEMGd9UX7qj@+| zV_NMw4Mc)y6)k0ByqSll@X?Z@VpgGLkBs_9w{n)xHG?FQoI<98=4og2|)_dAOZIVueA=}Jg zu|qnw)dE-Zk208_G@Bgj1otheupu7ICf&@3<+l~>{q#GYx8s-Y`$uN#*O^$8l>#*Xh*s9JY$2NGjh5bI_WY(>Q(HOd zS`Hq8tWJ^S^#`kFl1Oo&(MmjX;}g)Oj(1viBHr9cSTepS3!WH&wlw6PG}+B0Hbbgz zTW7B%ZVeG+CtORlloGldD>^?;lzSr1p`;Xj#U_qA#n+1T2{^^sy?=I-n{bpQG_D?H z+-Wu(^O$3Hq9Q^Q|7W}2Iia-I1Y-B?sJ56jJp8wE6~E4h@VB_I8~zyoU~d%`m<}B< z@Ya?NnXiG~akM8bmyQY&(`rrPE|zZs{8v(V_FC4+@49#pODY6FqwRG7h8`sayKx}M zbY{7F6xVX%KVCvqo0I9wHc{}dwp?XfT8?+Hp#1nwCd8n)xOXml;f;}|Y=LYWnooJ1K@-9nV$%lJ&#K}OS@XlE9 z4NmRR-A3bM;;Y5)Ea8pbR<@gZXD&BH406<4zxd<;JQJl2G=>8I4DT_oegC0#sjal7 zK>rvyfU$SOAf%!2cA-~Ngn9htcmVvgtuSKlIQ8v#-bqSW8HS7?K^)eBZbqye9uvvU z^}o(dq^ot^ur*hz&Uv~Y;vj!5|9*}%y%vb|8YH`pu+y9nFhj`!#m6+$$pt*bM$7oT zeR#|lE8RW4&2H&ZU45urj>yU2y8U~i6nb6MLyYChAHWHXCOj?tk+P#y8As=+C}4^5 z9Qx`+=4GgV5;7>$q5o5?UZ+*-T4DncUIY}HEw6iRN}ARfr_unNL?GKdrYnVq>$~r; z4~%w>Dp0-)4mVyLU%noR4U{(x)j4>tO&d!eVWo2#C+COQ{Gu#YxQ>E~~15_mM@6W>YaKvQ%)~yXBMhmh~4ap{c%W zj=Tve8tKw#(1=s|IkDK&0W84p6F&&RLt;E&I{o;iY`Qm=0c8Y+lJK_QRl7TmR<|Mh-apvPASh`Bs4&*dB;EJ~$wKQ#6&EuFTMdx=JU*GKLIn;`uo>kpBho*t4Q3)9#mCyvp0fZS!|eE4#<4$Wes=X-3wa~_0YyN>VskP#5= znFXoGuOHS$+4+~0o65_8>Pjc*s>A)u9Ow7M{n6yVB2Aai5DbuTkZ@2UGei+SG+~yV z0@CU}TpsvyfFZ;=6a|oPXP?0@#Z+xlux(@$4byec)L2)B1GH7Ul}Dqn6ay1OcMr&c z(dVW@X5xWKh)A>l3OS|V^OaKu{0l0%4!-IPNA44fT}*y4PWiY^I*ySS(L^ud8tE|P zNYNfkcaq~%^~I6$RU5;P=g-|6DhX9E4|$Ue0WeE{Dq3o}8q!jkJZ+5k;H#a*lV}v> zS(n!^dLzt##Ll4fT~WmYZYy4mjvH8X@rdT`4XO%4@ABzk`Zdl_a*@LOLcQHXj9A6E zMxPQ9W7ZsJ%OTpNk96q0oZ%ZB#mBEe@RZz^k8zY!3ym5g*N_3@mkkZTGFp2x6NupF zb$1}{z&k5Yw@_*=o0_@lSm3ekV4;p6!%zt;s&Stev^`-gTm@#Mw;!|X{bI1*TXK-4MGb~(_lnuf0OmwB_7 z@{1&|4>s|LpaKJeXFE6Xwvaj>n*l>;RsWX8$`a+p0(nhz<$}dWASnM1PSzSPL8vDmn0jdr#F<+&<=Nb_ z=}YZv3T4?MN?-VFRA{V!JgyK8&=zl5-N-~f#M<$vr06idiy;YDm$-+qH<+?un5b0u zfZF=Ab)s#55E3{yKpA|$_o+TU@xt$zkd4Go1t4Ec@21jy{$;Cp-044DEn;Z=AS*AF zQFC}*i>1Ya3-~cmE5+R~zycf5k1iB%YP;0tp-z~5Q2B-&!^gplQa~aPB%0MkzSFy; zCG7B65cf-NWa*jSv{$VNo#Q!sUl0^6Va5PY_|=+Br`e51m}7UJCUZd3i%sY7uv)2` z)-tO8`vQoB-a5s3xc`o2E4JsFH5KDPfXvKoPRd)|K<_ZD)L?JSDf`1#@ZssvSw6=S zM7r~C;3o%DMi$PUOq6f2Um&Q2I`r$rlJwo={O20RkqRZ6{TEBO>=%`QVlRH@`#(J~ zbs$hH8G-sx5CWY0;~LcY{(25vp)`jyBlKXP-@$pwGA1a`6fzsMrH4$qv0bGdoSweE zTu&ZGuGe;H1yQ;wvLyUs&&it`0l-QRoCPlfD@To?u8Nv*v-GQHnEBg;5?nN~U}lpa z81n#myzu|j$QID_^5@S2fh%Sqm6@zpn%VCnsTgu2X+d%Y24}%q#DZ?h{N?ravq@R^ zJ9w5v-|tmAvV_g;?fz>`&V6RXYZ-mb5;G8B^fS>PaamhkLnDDU7dHG12J0Wi7E{XK zB2kL)Brv`LLRpePMg+&a9Oa^g+1U)VF_=aHQCvEXSmCorZDr|kA`R@J6S&Y|syR8c zRN89KxI@tTD(VLE#f{~l5!Tk)8q_i&E9&98nw+;~{>tA^5ER7!<;zG(T3MMCtR1F~ zY2*1&&?*bx3YvKAbipUj%FH~FnzBN>ascrhjLwp#<9@n4TVFS*#V)vhZk0dD9YF5- zsZul~(rYPgC7f^xW#eqZs6Da&fmT=KFL+;Y zzW1)RgpZzqBCnR@k2i)8rJ-0e4^b5}6YQE3vFg9E=Fj-mC*SQ})NGFZerhsg(XTV) zy4rAz8XBu(B48ZBY0mKh2fZ)SK&t=lp@?hFo_b!Vt_Ve!jzWaH+#a`p1NAnx#3%Xa3tU%=`fo$AA#hRlzPURaStupI6XpSP>Q@6 zfJN#OHUb{n<*O_tHa`m^Mu|qQoqNAuKYYu9dNeOy`uTov9wsoLJMMZ*4Q zu8x~E;M)7fcBlZC>7N(5(+g;ckXRWnoeFGm z{raD*!jZh&^A|t7rj`JahF6V8hi&>&A-!cS5}EKFZ}tZPXv~AnXJuzv_~GXuDL2#( z9aLUhIMVOG`yS~Nu6S{e7xa+C`d0i;tEG}n)-Z_pq5g9Xg(N0$A;>Thm|6=2P!)9} z?W3xBm~XwQBl2J|pZ}Emaz|^fg>^qO{#asS%(z9F{ zdQ)?9l=V^dee2==gz}m8SrQ}O`@Uerfk6*A8CZ4$A3BN`6ql4Q)wCPJpIJA9@#VT^ z1hR>nfRp@(w3AfVqNU~w>>)&ws+SBKj8h5sW5@Hwat>E0g_nPFEzi)wPdnj9?W9WA zz=?>x^O6(9o_37zCr2nZAZy4bb&Mn;Ff%vPm z8T2N!xfV_=V-K9+R}=Fs8Pu$e!<-RRRj_O{h!C&k?vR&q+mTC&IC_=$KR3Qa&xY_~ zN6Cxs4Xa(bPL&|oOztQoiQc6J&%4#U! z29`vcLc927o$8{`=Juw0KI556oKfqWHx~5ju z%lZXsZ*gN+wqM!lV$J-HJbcVnNJ;RFPoG#02u((#)NafxWBl7UANmV2c0A^KrAMWC z0*RMja+xdSnvW^4&SL1m#r{e%&p&h$&g@3y&vhj)VQoBx%Q3dwNYw`?LP*{m zj@tJQub*mM5JHRYDYX=#1VEL)TrO=WXBso1TW&)Lzuc1H@KBY@7x5oT^zE)-J&v_?WGWQInegE1Cnpie69ka^D za4_&3`ONK4N3Pn$mtB2amumF6JiBU(}v# zX+7Lc1bF~Liry)}U=m+gTdG#I8a3Zd4foer&CXBwln*O742tWBeJ#weJJxv2dDvwH zqu(~aH*Wy>m{37Tr4F@Xyg~_BW;)4q2=nvEn(}U!<6y)bMr~0W_{#Tc+1qFV%ABuh zu^dWR9j4xvk`(tt9(!-uLr}I{y(4sZYwtx{!sfuuHi*=rhj7v7WnVT_W?D?L-${JW zi7cfx-rqYtc$PmcXU0Q(4~ovOAET5Ok%+udQLnyGNg$U@Uqkw86i=>Ej42Wic(S{} z>sJSnB9dQ01j|koG?Jlpvl?-)PAu3xzFxMtdYq-A)%bM;1U$b{#AP+BDP}G6PhNkj zx}TXA*65x*-Q2f!%}E;>F#Pkt*R)ake0NYnVA8owGT$KIul|3R&p`d#+Z&hdg7P={ zF9Kj&g0t3hkN^9^Pc$E5PnnR}{W$;|@`FIOSH`xPV|SABd;L7M8n@K&$Lp(~pwDvt z7sx(pHP+Wt%CfVvPAx6TteOBjVfCE{=jZ8YrQF2;g4qYmao7Z(YVlC z>z@ryTT&<-J)HgF>F$nxJ5&Buq`9hUQpWa>S4C5E0d$?tjdtwGL(QLojAr(S{EjS4 z)SCrX#buD~1*OuPXQ|AmxNF3ng5+ONq@g?(YoLd>_|e?l95j=T@ia|K5kMHVN4sSX z*24W4&{$U}5!eUfpVZN&uh0~;mB|!mK5y}r+-H*(wB?xCv@|$fLI6d%7Pe>$*E+@Z zuu%l_e1iniRny9K#;A`Wl(>HR+Tvis7 zC7kE^_cOy5liw3PwvIeJjglB`7EtjCk{?bx_bOhc}#3<88b{6Vdr7b2eTYW&Z5jh`i;5zgz zd7rt+x^zDhpXg1Cu-yitizYZNAumJXFE*fEb&yF8Tfeajz?a4>v>$l4^Q9-ki)>AL zT&NF^3KLnpNQEPyw!5xf)Z>bvVH-*-v`})SRlodE=V-7yfsST#f=Y;J16PpFPe zxewxx@=w8|O9{2baZu*~klyErFX9`bTLS46v`>80EJK4@i&G9gahWr#+9$4Nm(<`g zcEJ(37+Pk*K_Cw_NtD~Y3GQ8IQY6n`00-db=(+#U+d)x!1wF~|sZX{;hkibIyQ4*|yp?^AOnL^FM}KWw_!NL=W(jyM zo9V4H9}38YY7!&a=a)9mbZY}1TXTIg)i)5fvj+Wd^~`=N3g_uQo#MEBr?}w}NZZUx zDWUhqEKo{2vYQl~_VgH~%0lpOKVQRM(%qNtUgooAmH-B}c4}3B^8`sAzBa^6nMNzG zM^yac(DfLmdft=kT0>Ta*nALBD{myX-Ia*qi{2Xe3n3D%`$@BIo~C(EppOXVS?&>< zjxUC$MV2Mus1fGb^s#U0d5yO+LBU099maoqGI4;Ri%QiQqX#Q<8NQDHg3q;C-D0?( zNR^DD3f73YP8aEQT+c0?hXSc2L#LB_7+0v*Gaym1CuaG2v?Lr_&ThqlG;|Tk ze;>V!8F@Q2qm&iHYa838Q+-kzJNRK8&&pv{|3a;6m-!Lz8n628dSUN{8L@%{ z1#p6B>Vp@L;giU!FOrD_%;A(`0wm4!)|j|hhbly#KhcG{!(JOhUf>kV@rdb;$)%+cX{ai^TfqSt?#^<|87yu>Ndg=M zMb~Fq1Er-~STz^*jdiv{=`qK&mNzDQ_kIJ){lXNlf_|HDFV1Z61b9fIRezBQOm4(9 z8LAxp4KYhi=>NO^k$kt-{v_ zONsJkZjUAC1*uu&AZ*O@_Iu(WaMy2aXyD@HWc^*ZkSSBs+?)~HyYr(s-mFjOI5;>s zEG(?DvJ#nRE&l6rgY6XlB|rvnq&*AieuS)vlrSvYSn7I+*UShyu30buG?zH zABx65MjcX%ZGmfdbqG>}0m{qE51vIY`G03?W5h;+mf6q0Ga3@x#b@kyX6$rhHCA#6 zh!svbthu-jlily{?{!lppIy#|wMkmW!G;1;7MY{yjH87RjiMKvb_LiSpi!ovAeeV) zslinpDqnOYlgl=})&=BFcXxL|U(<=9%`d*5(UB3}MRpK_C}qLqVzX*6H?NeLy#-P& z&q=xl`kD+6L9L6LG=0bW_sP=tri)yez`@SWN*+wMiuc!x6=8+0 zPlg|B4IwVd+5hFtG50=!| z3VNVBLJK-59D>`W^6Jk@^%idH6Q!SB4J33n z+8ekoc~W^wsY(7z|4oY+@g$sDMH7F)+XIo}C$@ym(3}58f^@l63Rb(#_YC|XKV^uE zJ9^@#xG4qz@D08ER`R90qWj&{=$)-P4rzPTZ=XU86-o(~JBa3U^URj99zynBv(%7Z zq&fl6NxRg#kICM^P~sz4%Y2;^#qs+xysHBOxOipF)wU7#SH^WDzsZ|HVuIg}L-2R8 z2=@%W7VtdRs|}q>dr}NEgMi2BU*EX+`+cGMe5MdWISbW@>7wzL)xU$@KGL@svbt&? z#j@hp;2`enrgn#GtNMG6T!$_q$>iM{L-EtN1PrUq0h{J#n#`?~nFbI$HRyBZt@=Bn z;_?oOMN*R>9%lu{<5o|L9%jb_N+w`2~d=@*PJu^9%ucI zPt!UOSj#J2o<$MG%%+v1`F_A^px0t zLs{?&LvQV@9wBeR{~_;>@JoBu)AQyy>=SmQdq0;iLVRY4K7X0#J#RDl!M;0yw)*<9MrYAZk7`~ex7Crkz%IN0 z*^hZy?|?CLqfVW*wRN8v(G*%z7}Jb#uWsi2Rlrl;Me#cQRr6_UKlt?;00Le_mu`+T zIFcSn(&bWNx!F1IdRT>qJ;x{=yv!N*tj}j1yu29&><^B_HoQgXi$9x9BoW0UUPDwz zof9-Bo3-fBO2vddgUHP2S{O_uzI3W%z$+>!5nQm}PwnK7X0=WJcKj<~pnp z{K{XJ8&lyDghD10(*6Fd?6AdW7|r-+zH!F*;za_LQ+&Ylvv4{By`!&| zP*IOqcKhz2yeZTWQEr6y%6l$Fo{G$=G27gbg^~&>&;DYT{&6(2> zy96e8*@?E9CeW@yq;LltY(PmR8u)r_sBk5YNzFtcN)}9wcOXN}MuA$)m<*@78a3yWUL4(HRtM!x&P0JvKmd9a z5p>I(OGQ~BoWZm~|DPTI8~8mwa2B_&j*e!fo-EWsLIOIZvJQE4boA6ZPS?tPES!eBA;6@;3|~lg+8w^_Vx_%|FJQ{KMqHSm7q%TWfy{2E}Af3nRJ%r){Mi8Q@(#pw~UeS`hjV$HX{`F@V*}=J8vSETUCgaO7iCVg=2n@+T~WZ zgY0tsjYpQd=L|Q}i{W0=3w=F{8F&o2@^IO;_#B|(joJkC$eFNdNpI9h z#7IS4EH4=zn5F6ZI5s!$K?CjYJ#l@s-#SMS;7kErfE$`SL>;l~OImcGvsp&N_lt+6 z&OU^+K9i1tK{S2)?~k7v?J?$-fRK`JnnO$)bEc1u{06NA3vnG{(k!}>@z2fz=w#J0Rn{D z0}yz4-g_fMDX39)GGwDb zV1rbkE$}bsF;|X4rA||4J-<+k@%`(+EsK~(Bsz~nNN$Xki+^F9+9jf=YYqc3HM8c? z8L6aB!i%mXDTrMTxpHwUd2n|%bg56O%#R92oy6Lx(03WeYrq;gR?s&AoGv0&71>W= zp9%8*nNrI-43mzvGrc-4pim8EU(~8P-AS1#KnXG5u;o6tvsS{^5)T%c!*4T%8n8M% zr;1q$)^U$JO}0Y%;^v!&I5R+^F-N>oDb86u&LG4^^jq|=0o#l6tR6#DN-*3((ujAJ zk2`i{nZec~%o^MH&J4diviHd;$l#oU)fvb~KTy^!y_1)%%Zw|@zsQ$YEc#J7WvCB& zpP5=O8lLmN6AcLB@eW01wd5u8ZT*uSIz$z?CoDrjHU0XqPhpExaGqdeIQg2QZiuH9 z%I55c>qzD{;Yxyh5>@hvJ(?j@s>P)z#93Bo)f4;k?KtbYxK;5lJo(DS3M>E8sb*Fb zzx`EXyKJ-C{o;A|f*Y}HNe=9>DoN}hU&ySp^#b*deFx^7J+X6w0l>=nI>XPUZJ#;S zrbb=b_pHXaEoTaD7em^r$JXQ~spp|b9&c|SV}dvbeE^)6!%ywIm0|p1VrI|4Nj27) zir6KT>l=XU$Z)fs+e#bVi1~z+`&_L)DYYQB(X3RyPjM{Wab2y>gMC7_+2xm@moz|} zE;~PT(YYU@72A$!?eZ!)DahJ?nRl-TG{XL=3E3O#TeqGyFW~ztR{KY#lQt*BbYTNZ z%@k9p`{$q1h-ZdeIqKZs)PUB3xXW-1b%JS-CB<=g$sH-p1IqbSg*o?Vpld0vZ}CQE zC+`5x5O1D9mgo|-+>c9L4hJ%eytT!omkxvnfZX=TvlW<1;o>AS2PEZ@*fxfb!yS`Y;l>}acihgKx4cB981 zd{^iiP17h2^$z+Yij-e$)Iwrs{L-hdQv=H}&#-q~iN2q|j#}^Kn;3093RQ2c_4PaioWEyKmFseg8Yu z<5lA3QkEFd&$fPw-bZNvwlBnt6_g{ms9-$=r7DP{tr4_*i|2dBvmR{Cw_)$ZBUFgiOU=i}U)K_t! z0&hn<05`m&4*eqB{U|vG)z z*&JV5244)`ncp{hq4Td}Pd+eRMz)TII9-Wd6Yi8lMrmwR-l*wQ3thDM5x+C?8Er{L zLJyfbT&?Lo8j#O}e3nb5^W~?qu;2~oJ5D2G+`L_W%dkt*i_5vyG;Fv5xW{zXN}2Ik zS?lj=!c#IK&UNY=c(ZfHewF8DzJq8-a6e=3b1>C%xdt*`F*ceN%c)dM|D4`h=(mdj3V;0G{Ir@(*wqRI2}>^wh~W&o8-W#w+h$w>m(~G{ zu{`dp6k_JKy4=JU+WFN4_q6khh>Fut2l(ySp^@Drs?ce!x7?|~#G|_H%w+6+AohB# zeZc$hZ7sf4Z-(|JE5W_!T#r13tpgWxlwuSw&HcK5ESKha0^B3hcd%P$JflD4IZR-l z{W&w5nCD9(v?YB5E?msW6rfv@ruaY4Ljt@@t_oSMTm!e@pN!EIVVsp#z&1&&;TBny z3*sJVE&cuE13nz(5oWUeOZhVr_v6F8zflS;Az*dlduoT-pU&%~?_yHo#1zMC?mSqB_vL)K}2F6XrZBM4WKsn!y+W z%do*PkCfova=u10{~P9cp{s-cHe!F=R-m-jl7qo6zWjG!ijarAzM>3=H{_Dw-zLka zV7zFYr-^=JKWE(QPScq!$cOg-w#UnkUb`5IF1-TpM6iVMGh>RYaNNP1h`p#pXo=p-E`_Y33*+W4I$(?N~aiCdRpM?)=K3-IU>?xQHZP~=>Uq$3_*94&PnpFn=3 z=$?2+0DMXjK%Q$**#$Fn^>ovNK%|(_#1>f3?f(kXxYW&bIKa}hRpRVreZt}<#nh?f z?6M(yz$)e3^8OQwG#d|2|4;o#KlK^B;5sZa%e$fK&}(C2G<;6TNwEy&l$C%PN{H!;Y9&}Uy6tVqpn6oHMa z!Jx1Zsz7g7mk8*%a~}aagUrp}-QU-Z&80$qY4xxNP12xEyzYq1UGCuUut27{u<&2| z{ra!6vI4L%IzCr4dMemCGb1{=?UNeg%tf${PRl1{c)Qxil(aMs0S8GS(z=@cJJvut7ZT{!Oy&2mWtvQA3OSK_w*AJnb5od$g zR2-1{ktZ64Okc~D`7K79ZFw{i85y~-umF-xE!kOXVaWp5ouGbVG$0o1vG5b5+`wsR zpmXqaSWJ~f-@qW3QWo@*ha;}$ahaT}2`ftHRJ8MQoyc>7G@F7x$X|g@4=)S)S%|5% z?68wk5~fj;Bbhoya^J?QV56JGHnpFYKYVh0RcRdb7T-}NyhJ{9b*5C<_}92QC?>vJ z{d=9ukjAz=A@X>TnU`L7}&su9B=9AZ_E(|GK%RoXFMu=0p~*0X@oM zSfz*%Zpv2J9{GVNSlgFe&YQ9-fEIT|h~jntAZTI5A`zk;$_)iO>xiarZu zosi<6b-tzrIY>BazcIwVG)1m30zK0|VHGNS6-)w4FekpVB}QsN0NtEfMp_;WRTC+_ zh;=II)^IFJE9}AMS&4p47w03mA79e00<_pAUQ5;em(imd4zsvx%!$nM*h|@t@pi5x zd+#YWbGB6Xvh!#|Kbkhq+^=pAwEJa}{t;q=(#wrwJbL&8jvK=8)wEP$+_O2qcDUgg z4IG0&J0paGpCl0EJ{~uWKWZ3ine*%*9w0&Yso5tc9LPencPTwhkh9{v^fSY&LfCMH zn5rY!Rs0+#Om>5;O7sa`Z3%iR$occ*XXZx@Ww(tz6w~64{qV~;Kg&9G`X+y&47!_@ zp-%#NdN@nXdWoYn*8+=XrHHOIB)nVQY??sOc*-JIjFM_!*^F{GCq!%XrXmAEdFrO$V z1?9?JHgD>&aZ+M?^>C{qDmF@p@fopZ1uQUKOtRw;A6qXw0~l(d=R5eRO-xVU1==A{ zWBaLB_*chgu}Q@vBAm}Ja~Miml<6%*+l1Qt&Y|>3=V7c7y9tVYsA`$hcc^v#@gvho z;fTQn=LmBS6Xj+fGz%k{YPWE3Fo1Bo?~3qv_zhEginSv_$*N79q!8Pvr@M2>^KOJ{ zbw82lY8WfSaWds-&Y3^3-!+5jy5p-ol7euat>1p(oWCzeL0#H|@zWz>SqI6$nBM0Z zg-fB=MvKra6EGXaNfQTHP5^-s<# zXVY1+wgsUr{j|c9)W~WzZ>oq?p4av&4~8- z!*?;24ov;S>oZ$pWW%khuTEi}W9v&B6*&hcu5;98APGnwIR=ogs^o8~Umb+NYOg@Q z!1H=-w08+J^NuJm`RM7Z|2Gw5sI-tvy@JOoh_$|jAv4=HN~W>v1ozL@Yz}lwJI{He zANLO2@+vk~9tvUaL1}{S4|dj(-%o+Sxj4{h0Hm|rB(fT8^2@(`K^eo$oLiE|x)v~9 zlL`6Zx}m@;zDL9pM0*K|YZTl-7idQo9HM@Nj#j9}2bzCtT6+9*b^>CyUo}3gD9r==nb9*# zd+dRv!KG~9sJSTa$iGqRfi5y@N5_5laTEY-mW03-V}22h#{p722oZ3wu<|<1;C_0) z5!l(%;$vo33{D%cvWiGvsAcpK*HTvpIe)9)Acd51Uj<6a)L5Y2J(fGT=I`d7PXHCw zZQ2Z_&tjF_T}tslKuB0D=gzH97DMr&#GE4$7EI;-7kEDSHkYDa)7I7o@-nrxiTeMw zcA`PV&^2A}Iimno`LjJUU_4nNS5QZepeP!Q*rqNQvr%sR;EP_!44d0~anmfTsG#Jc z-Yf0rP%T3E6UIj)-Ltt#x|)s0a`*%pq&Pm{2#qIqvyfF5Vb}tHkOv?yyfF= zFy1`YZ{RBkj_`4G7cEhMzJmJR(rIrne>Ex|j=hf0h`=z!n6M@UYA_QwAWP<=7>X%l z_Z}M?yIf}pHl}u6b6Emi3moDU0J$SaB66J6r;I+GI>AT7Sr$S$KOrZeZmAUR9W~_P zfR-|0Lu;BpHETKoK z;7+a2+%$;tZDoI%v#Ag>D`~!67%-7glB(Plz;f4qJ0@8h3T5Y~eU8V~A}%WI)OizB zJQ)0E`pIiaicca1r4v&eN~>peNRnU*_S^6Fv{|WGvPR`~TV|jw65zIl2C4w_i%}xN zaHs7rlsXQj$}wwWeSxb8`+d}pW;Oow9Pg*n#wj`Pc92Fy7oY56ARd_Bp-+X$o61La36#SgmQU&E2m7nfq3*MiUFUMd} z(Z|yTbOvU_mhgk#o1nTXUWk%%PCCB&8yZ2S!wBf7=d%!_oP18%F z$5H}$p)pCNkxh1knV{9u7y~!_RESb=qv2n8{I(XVVF^e|{$VSqWC8pVev|Dq)yT^q{46Jj`O&-XdmpyN?yrQ)cAv~U#Ou;RjoV_Tv|SX44#ridhjSX5 z_;6#P{<~g6IMII#CsG0t&;ky`+pc>Q3>%`CwjABe`J=ZHEW?r&~ z@wF_-av4tS;{H97h)aCqzrjZnJ&CYA`#H;*!U(S5kgL<5+1n@4`O1E>U7Q{sdDClB zkWbP#Z=9-iFR6BJ06%Hl5$axPNPXX8<53ZJRcsXxhC$_RI4PnuP_@OsPIhjPn)Z@8 znn2)JP)rb1&x7U$gp=DL<~M5$x-ud9=slMhnz-4W?=cSOy4k_o#kPG-gF7s_uspu*<7n?mpN*F;F<-Gt`F7^Gts z5Ln_=j;2hom-Te3tB_AlB=l3G2{QgbjIUc#s z_nF2v+58ju$%mhdb~0-y$1A$>SKVtU>Ci~Fkxf1mGb>saRYeZ&1dK_2iRkwm&m0-V z`YW~rMej3lrR37%YFZO>*Kq_1&k_^*3ps(Md2JsY6Wd=jZWZR~l%!BO9)=O~UT^sP zADnB*(!wn^^Yj#I zRQ+e?=Z;`+rk_7akBdjr%`Ki<@7I0fJm$fne&-#}%(s6-!oce0msVBj4_5a<_03vx z8HiugDO#GE_#C$Melbt!7wsT;NUchh#B%bH+!~ zzEY!jE;<{+ENx~Ss!t41PVC9TtIEm^xANtQ%JPerUus)O;|^C(^VfB8 z!u_BDt9cMe)6J(jaavQPCIt{gS%bhb2W*1~;>p`$z9o=658C0}JUkK~XUhD*^@GI= zh@xg0e+Rb)VW6`WjU?0erX!wYj}E&*r|(PEW?v>ZAemq)9k&^KE!987fMD^AJ|R}Z|iv1Xzs*#+9+Ys+LJp}-_TX^V7inD zDFL(q%DbvbbxYyR<-&YiYUJ&1{J`LMUz)YL2XWy>*~AS>x|fOAQr*XKjBVacB}1)I zuhGS{o_GBvpJ>k2R&w*>l21=oC0GI$rbYh(dznnx#Aore1N0y+3_Pu^nS{&Y|Jen$ zVBQVFTB?~bSy)kuFaglN>;Y{GyRZ{YART`Cmoo(Py*%X2h8obeT#5Ve0~uCWr;5xb zQM{6(u+p8+;-gxML1#ceWRKqo4k56`RudRXQKbqt>sq@ASu)%K;FaQD>xdqaV7jjL z9)l2BqF<8;ALTTf#!(y^cW>!^`mb2r%<|i^kwo4koYzCi?lsr_nSo|?Z@3n%5Vjyw zzwjB!((A(H8T6;aE{`C4p`S}|;P1ncB!40sZLoF>dde(JAZ^=+t`E9)W?n%?8nYxH zC5e%oH`A1GURNb>h0QpS-K;n7JU{L%4}I$PtWb~S-NN?+Mgy$LvTTow6Nzso6b?no zQr=Y#B@KQ2{;lgV&kIb#DF2NjG5gHR@>|700bL7yb>6KofGhsB0qZURh@&+xUM zW#f0=za_bHt4V?`!@a?RAMDr>>;(kU^!Qb7-@jCoAf4oeTyl$@A2;v3!G&B-k{@es zG_(H4cW*xy3%d?YvTLFi$0sc(%=T{O4B>BgiA1G*RcA?d8IIjhm`Z=`B8vMp0mt-C zNFzXZ$KuxW*MwPMa#=P$TJ!Ups$^%4qR>3JtNrqv1|lwilig;peDha5734cx!+rQH z+)aLIj+(PLlV z`Gnip-xtsvV%lZLH}4vUXxftI=bz|t9rD(!?)mYApQGp(&V#<0zq%Dv6;0GHKTAR{i&+~(Ir$Z(u~;A`s?Yfy_Q@Su$g_0Vyy4y1)&)^uF| zRBwAFNkZ&m&b3|3vnFd0sI{UDovVEpE&K270`4YhR^k0^N*A;(v&@rzHYfbEs7u~o z8p8{j;z=%jZx@Ij7rH_9{z5-8lTn-yy*d{8{C*(*Z^>I2YVf5@Hnpff>x|POeHf}PGh$JkEXATs;Z5)-n6uIiGY-J zcZz~Ef(S^LbV`GS(%m3ZQqtYsB`w_{-5qk^e9wFDcm2U&49?!?DDJhMHRoJ&@=V0y z{>Y6o6QB*}w@DTpJLSMo03j%vfUCZ>FkS9xPPpV2qJc{J{37`mcGKNf*0&0(?X0X` zoKI@2r1F;nq)K}a2)BTs>ZyNR1p%L0ZL8;%RSw^;vtCpRoAJfPp@6SEX2XUlfUW&^ ze=pZM_yq`n!HfW8!4?ii9o8x;D$>#@WAlJJ{~ukK*8BG+-wPcJAW4!0aAV-%r=|`e zAt8ZSxP+M*upFzd{_eSgCEJ*RfkC_32zic8X-P@$cQ>Fue$#5x4KB&Zc)pPOPFL}W zr<2{KYRRs`M@0o!mBams-~VX=3isYB3jrrWfW8szshumn9JAl^HTKL*SGF2l`rapI zak z6>e}nGb(CeGp93EyeV{J^T14LY02i-OD$UE%I^$$AJNPm!4x#NEJ~42Jd6x^1!E74 z$s_}iaHQ$|!7{L(5EK-2+E$E;sj8|<;V}o@kjs+p53B%)o73d?_V!Zvtp5|K5k!I( z_ah(%T=-13)^aVmQlA$Sm-^6Vbiy_IoiqBG8qPl`1uq22| zT~wP^p8YWi{*zYV{RDx=ls$^I%~FieY+%j~mO#XVTe@Lhy1m?aH@Y~&37@82o@w~G z{^w7bUF~9Wf6;<&GAQ;1-OJ~Cd&8nFoQd5+JlRz9yM-LHrg5}w@6d^^w9nuF_UdEX z|J@8xFVPX#7HS^;w62MV&Upx+R|mT3qG*_vqxMVtp@Hu|BZaZKxJx}N zt?1F9UmVdkGd^(9^SsyMwLa;rwB5}s*|{5NV(b0Tj(fO@=E@!cpoxDk3f~o>iZMqV z1fm)i%-}Sdnq;AuFtTDfuE=F51fB=(&DRnCE8!I9aq69YVSNJA3OjpS2rWIGJ4Z+9 zSR70gDC%l;eGEtUTNBsO&w||h8_w}jIz(0ylUYu*1VmpDQ%$Zgm5J(bc^7PATwWMM zk4(ysF>i*aAEkCGKUpQ;m3@&xI2GSoL3>8rm*`tnD-5P+Q}tgUSU^pA?m-)1|*a`Ln^9!FZ{h zai5?*M9UIZ(tR;l`_=mmdkW*FYMaRbi4$tZy2$+&KBV)+yIfr*k5OXK4T5PEePWU@ z9x$IGm~_x3rK(E5c6GqUh#ew??AsK4=g<(nR&6&tvm}^mU^(ZmE?YUj7e^A?m3CBp z%A0VN&(Rp67BRibbR3SbdJn3_FY1|S0|v!irPp{FEXhSro~VTNGV(%P3IzH)M{l&q z7p1t^mCgHz{fu?F_war||CD&p35cqF;=je}5`*?AM+NM?>XbL&;;Gf20VdO$} zoza1)ei7Vh$4 z@=(|PS$PE5*f%Yk;+%FZ>l zE!tI4ijP_mRd4pH~r|9xBCiliF2>K=J`ZrQw#VD9k-|MJWQ{UqgSjj-v0YeZN zxpGop0gedhr@T|D`*1!=Da|vejY>b2d;cWNBQl)*Lx=iH5HvalO0%J%;m8lZH#SoN zZScqYzUXW~p#TP|y1KfoOxarLjjWg;Uo~hHgdJ4{G6`bb+)_e3P*O1Y%J1Lu-42D6 z`k+ako;m=MC55`t35d3U3am9kt_(0+K%R>p7|MW-;ej9aYyQb)90PJLG#_(-%|B;& zwLiU?4|uHvn(F`Pp{ZAHuC5@(ezGaRR(3$)!XmfG+$yPdW;6fNt*of%#r)3v?oZ>F z{Hj%Z#zmfB8%J1JcsKeLBL?kWX<^|ya?qB06pUQD<^GPGp+EYS3Kecj0FkI+OHDkGRKmq??WdPcu<`L{}P@u9s2 z>#dYh1&`0k$g&jB-AKXP+uD9&B;OLzL;|_2mp3=|H4`$T@Qw~>LTGx!-`^iB`T!sk zYzOg}kAlr5zEZt8YOow+-+DC@L}538PEOSfih(gjw*Q31ob6Hov z--oA*`vud8PhCFd{CWXFC({#Sjq7wT>mT-AevfJTa4z9WP=u#g%F`Q2pJ+dN!-oj( zkzU)BAlxdXFPRfS#sqBq(@>8Yxu0(<0c;d?%^+4jXoTewZ!dLc%obXi?W>FKoLMp2 zqiMYCCS!--mW)f{sFEOy^+b}SW2l}O4PN+Hmg+gBNV7w;x_$n06oxW#x3%|QAJn(` z9uv;Y*~R!p8By0Vx4+PSdbT;co>F-tg84p=&2QGeKIWqz6VMxC#sB?p0lzuuPZ~aljeRrh zw}*lmQ<*f=x0$s4UdLx@t&|_#ekr{0A?(|^$B~zAIEZ2kXp<@0>!8WNT)VhK?l?j8 zlJg82GmUGDif;Wp=>OF_M;*dB(Pv25Ejva z1glkt8CpGE@&Zt<%hCWm*0q%j5t%+(7QJ?+ki;ay(^j*)WTEvvGI&^g`suehiFvMgMa(`tUnng=5|x)Dn)ROu8>{X98E(MR zPTX3oGx?s?hlVlY%yDDPk@nJckN?{8eFGp(RR*sn)ez=ZN_vIpxb~isp(@h;O;3+3 z5nXb3R;l6N$iS7)cav^bI{b*Rdufn7jWg*tFKB1sjv4mEVmruV{zD^H@LNaQz z&Dml;+81s9`t3D@LVfUo*WykLUJgf1{onacCE7CA$F#hs2f$Hp^xh;bMawpom5mBA z5k!-d*!-2ZS>uDqIXFFj3ZW~NF-dL@%F)Q7f*w;d1C#~M*VOI&&+%k0uJ9^>aS=~_ z#$dQC3)TW!eDuxrby8yDe>s`E|0vKd0 z-O#V|9}zBq=qgAsXHlrWqv<_6M9g``pr1dUT4a=ylD9H55F^LP1jg4ghU+6>64ZDN z_IcQfK4K;1W@j5;AI{U&v7#URnV3-3)a-YZj#7*pqUjMrm7fBEVDpW+P3qWSLXCV} zD9Jf1SRckwSC?emlTZQPg~NqL=}wu=A+Mk zJ9JXGYmB+|bg1@FtpLfmgn*yYvuupyh$;lnrSC}}hZ389 zLMSpqF40&JJc_{XSq^&R`Wq~(7Ia0V6;w0G@1}(1UcHQ-OE!V#Molq%r*%6hwFiQM ztsKH|Jjw)>cg+sktiNmOU0dHO$k^&>nV}8YLg%tXrByHkVd!(F@;62}r8UZoM9UCR z+%i)5`M#Gg7`r`1@_Fd?ZQ5*$K`VY)*^|WdAaI=B{sDSn8G7VgF$Ipt&`MhwtkJWX z#5zf*QOOx$fHGziSFweodHwFcr_if8$7`iHn}qc@ZfkkdHnxFyZnk-;thPv63`F{` zw71^kg#>i|9EdBk5S65SS&~CaFC*bOICl{&_G*D%M{D{zU!->0k~VK-{~OvKCvd#x zCEB%W9fIe4e;ZB1f}gd7@7jXik*_}B8i@pr5mCHq$wpX9x@@P|KMm(H`?*KFL^>xz zMeL+zl>e!KbrS8_^Y9Vp(-1MM<2wyJ_5tbNBAwVbVS%Ns6uQI^_EV=Cw?gX&aodYt zKwpGuXx(|^+kd@Zbs_H%>i7zZb?H~Oy7Bd{?2Q$X--*dg(2C=+xi+64rATed8;}0x zb2XHo4#5w5eE-7Y(+rlfyO2zL3u#p}poochQDx~9t;gjk-JjVX{%cHs^xwg*WmnN} zLJ$I)`;3#Wk6j;V!$)2oPnMdSU^|>6?jRSoxkX}AH;kGwS5Hj;>lYgEETlStI4#@4 zC?a3&+a7rFpsFlFT^zmYd%p?PFYC5ej|1-eA8n&VRi%9^VT+U=MPVA+q(QZ)BzIAw zDo0KME3;1BCwvF!K%(Ex7*PbqZY{``V7pUOnjfo2$J28KdPnEPp4#r zLjv+wwYuk+CMvAcL$NN(Oj9Dv5!D3hX?TrXALKIE8XGxBA6@2WouaY+7JH+0Jg9w| zo~gm+dcH~$z_otf$aI#5R8x_*M-+K~kvw^!OWFtNE2fUlO_7RKRler38_Hy|4J$EB zIy%f;-^7uR`IK&En5mj32@rABA3s!vCp&F(ERnF{`8?pz|EPP}>ZVr2!DMyVAUNpQ zj_CIhTC+X**Vr@07?2UGu7GhJ*O3$(mh{nQ)bV{vHOnP-;RWiLy;&XTj=?+l&}?pu zX9NPT>>pefn!WiLUk#{*QtvL}zYA8-%R>V5ThsMSezwp>1dd;b-V|~2hd$jwS8_ix z`-OosL_dpGmpoeXosS@3N_O4F5$^an8YptKHp*L0y<9fNP6Ui0e)6iW2fS)^xC|p& zGDNx^*45(+vHt2HXA|@lM)e;&xqu!WJ@~8p(sGP4d$wfFN9T(%V)7|9X>IX}_+(Lz z9A$f&N0(v(^~4*ycDe?WLnm%gfnU3+xoui&_v-5!A`R21F>qzXpWnsL)=Y;9+^bH< zoIkHJk8(%7+UyN_=tAB}8P_!ZAMv0u^P??SX?c0HT}#k=9t1<+NZ{sHKam}$J<#7llP;$0FRuMWNUl+rj@$Kf!E6%nI*0@WrDdfG^*SRq5iw z0=Uf+t-@YZ$?`aGHSli$w&wh1VE$C#6BSiV5gN0PGyie;V`>xM8V3g_?vGlZg6r5k zqWtXq1T8IX?x2lUQdm583-TV15K}2zQE~AI4lBRQ%kRe^_G{dn*5OSh-+w}svqlMQqbF5^A(px(qMaUstqY)mGohcHoaBGSGWrji zb#ih7h@(hgPSKY- zIgFax18JNSlm63y`}6enei$Err=vp=j5eZ(ii!#-vyi`qVgeb<;8+1hOtU8+G&Pfx zlgEDWg+ELC^j96blCK*psDv*j#dc#^j3KzF@gVf%FVZ#QZizlh;dm>d&~Mzj*Km%Rz8`PG81?MFk%@&^??(9<1>3MNCd zAI3b2OZoYo^e2-Zuayki;mx;3Bai4%8xPW{?`FVG zKfRYvDItD_;BuvkE;qAug^j8Y9N(#{}kZ? zbT3dg5wYKHr26tRoyQM2f7IiBy*kd5g`wfE9eGI>wpA@6f51()#cD2}M&@6M}#glu2gkfrjaE4Fc?)%eTU9!su ze`NkC^8{L9VsdCilg!0zJkNlOyb0QM* zWd>2Kn!8-jH&QW`{10vJaOL3l292f{5k7ZmoOawPqF;9uk}Y&&&v#$TkD1MUN!u0) zjv6BL>?cJc0D6yKC%Tkn27gtEYax zp8rI3twrzjJ1t{01)E%k=ko(ro6)1W;Vr~-6O$su#u6t1ntjF@*WyRV zf|^th=37U*+c*m6!StP1b$85e?r{RZnBKBs4nWUYDeb)(NI}}k@q1qB* zAlbmNJRAN-`uEmm8*BI-@BEY4vrf*~MUFvVk+ZhrutwpA>IT)7!WR2RXmg~V$KN)Uc~gB-O~t9nZ>HUEkE86IPCIcW1np=V}6qC3_N{7(}Ii{kA?w9l_T zU4VgnJ~Y2IhDCP=^SfH3@$I>d$GslE6g?TM?hWsGY>v>uLWQ;m%R_hvLd>F2=V(rK zu6{nn%;R$Vb^ibNQaFjM%2P;Y*K4XNEgjj^S@gbHc3bh-L3{4LHprOCyRQ(I0O&YN zqowh2hw)cvd;$UlS`>$$+z?WR_mlT0?W8WrWRoqk`~fQW6c7fQ zM+60-V#Mzyivb5A@Mn1$8zeN>foYH1h(8k{gplujx%~VgDV{L&FJL?Z5gL=*wocds zIh8ek7>M#D8(LbHENTk1^2^T#20|*mf%2X$HE_Y`SjAB39w%EXDRMa>QLkF*rR}Iy zya)fre_aree8M8}Bm}zzzVUym++mXGRdQ=`JJ!d#U@Nv7PdQ*bDvd3Asv5B{9TQWg zLI*g-uZai>4%mI_d^w!Yghr7hPN6yP|)cLQZpW!StIsranS!dgefQr)&zPo zRHq5-ifzgcymuGdB46aejJQ zTFXX#8kTIw2yoIGovh@hv(~JRO!hhOvMFbRvudS*oY|6()$?Yl-j_L4wXETFjGt1b za(+E14MjK-G7ZhmP^>ycrBOZe8kV?~U9jBId+g*<>_wBYyFk`?0nh6ZS-|#vb}!-j zSt+z&MiAQ2KPq+D<2$50K#WO#sf!K)5>AvEmHK#wREl>IpOV}h(XYNEF_i^Is3^%H z@vA`sy2A^6^^;&XK;Xe3yDafP--1B**JqxdaRa3vrfl!*g&Os_M`c z9u}igbf)%(z(o5tfm3|U?Ko+_cR<)FosG(eD{7?{k#F=n-|I5C#Pz7CcwE&eJd-ZH z_58uckXSXT4%=4Z_3uZerB5A~&Sh_rf8withIpk)6lk;ZeGkd{W6 zxazu}WBc-aD+y7^-0HjTvYy<|=t;E7Z2WI7oWOsKe}jS-%CY$80~BD7v_=Vy zK33kUpUV_EJ=lMMdLpa+6MWTdko*5>N{CK{O2p`v3COuvmwNzZBnQgmiK5=Ln=FcC z`~e%UrmoiP?Yfb2gelqOR+o4`u1K1@i{YFy%s1eHpb&!PR7h+EpSZC>63P3;t=mp% zw~fj$W+Q`x;5veK#kuxGdDK23rpRVk7RIBoA?fHurF%}Pi$Htwey^N5nIEl9G;MmM|Hoo4=3>t*1al&bAv+gLVF&x6|#+*yz# z?7)BufA6!YNHR#~8pUZnfN zG(l~49a3Q_qyA0t;q>Ra&oCl&dnqYVvcZQ={~)j0t#(G|5-r`BXA5^(_a7B}K7`iK z0ShfD{b3Q)8t@Q<-)KGf#|XlfT*r-?wa>}0&P`QPT+EU@1a^2#lc9m90(MKX z;bl=@@LyE3m@vdM5r?NJ2I<-ZgX~7#DBhScsk$LvF6d7;sOmr^$FG<6{X4ZKAC^Da z^xmE&st@|wZQynmP;MuDwfHBeC^wTbXqw@%O{QiU_vTkcBf+*+e}8|Y*jL*AnWZIB zK|zZj3|?43m@#Rm=%dtyJb40WeEgmWZca@2Fu5I6x-! zxEMYMstvv~I$#4{(Q90&4n~O=)Y~|g7VAP==TN4#jZFlXX;4q-yHMvlR%hp@mj@M` zx7SG10r+ zFO+*Y1;Rd~l42Ks6a5+Z8(ZwxoROba%J8e>4=K{32?^{am6a)yzngc@C+jX;NE zIMc4SO{jiV`>|)Bc?dbiS9G`fk|(-(MdcVBnP-5&8Jj6x6ye;UmYbK#(AqVCkj71jD0aH#M2DkRz{`VKQreR zTQ>p9POLMFceQv|@**`$I;`-^+^cz)B;R9L!Ot6!$@}HFGBtR`Q@{HP`e@BpgAOP4 z-_+u?*~nJjGeBn#rl`lf2%N%U2_hkv^YIMcx~4PJ>ks3IMH?skw4uEUOBVNx!FM}v zSC$7cMLTCcSZ!+y!1N!2)f<`8*5}MIMPl~b}rDnCSSKqW5~!K=ul=(C(0LRXgM{x?*hftvN}y@6+r2hjG`9WXyZ^LUqF>O48gh z$OkMW3+&{)PrLoqq19@*ALV4+WlcnCa5XHDJIC#09WE3uN_;S z#Xa`Hm0u|?wLxFig{NChU2)Gbi*C>u7S^BPdHMND?}{=Km)B!5YJ4q(MIllvS8ury z+N;I3t9|8Nx?sI~O9UHqfKO*zQ25o+RlZ+!Qi+HSNT$TIb}t=*8}B|IlsM(wDE!(< z{do)*BZkgkn_=?9S1Z`R++Ke^JkdWb;$XNi>wV*woo!qVg?&|bDdMOVIA+SCA zH%^;kE1g;uOrT?87nOSFsJDUK{KKQY<6I*CvlhHLaFZcupO#8ax&Ol;36=8k_s0HH z3H-PYE1M(V7tS12&@TIrA9zC|>JHKC`o@l-h)meLkVhWIqgeyo=&l@do_WUCdUvH^ zfWqv=H&s|p%AT1^j z7H#s7wCbCPywK;B+!x>P539%a@-yvzY&-vnPz~m-jY8_ki5CC2#o_yrB{VjmO0MV9 zpNEIXW>K~dq&bN5@VrJssvW>u;r=3j<)ol61SHvVE#!~Eq?L;V|Ve%=%O5m)5@jYMZW6M0U`lV2QA{6taf;u)8H z*#}11&7s_~c^gno6Fi@abG(ws4>SM@2cGycqGz(>b!}L(DWKF9en?44VM-nX#K(f^ z$osMP!<>Rpy4$vmQ?{UTwryE@OwFIIKY#voxh80Pz9!U3<|Umf$#haULXYqIhhb@L z{kL!`%<8klbIj=2A)+ZqPVeFHlo)SA!wycY zMZ2Lpoh0Y%-{a2?URRt-LK@c2A5D)_>diQP>&Ml=V|&&+BNWLmbKBuB;VlKHu#lRjqKs7moEO~>vGl8D->_xI?Fscs zLl124o`ct|Bzd4ny4MXC8@8^uP@___rxK0aCkHs=-D(EaOBj9GJPg4xpp<)TQpZK^ zOGKZ32vCQ9Ao-{L>-lmi%qTuvD_hox+B?jbii|iOYB^&LJN<_8>@M?sLV_gw=5VR^ zc@lhL{2?ZgPO@~u^s!{%J}9)u`|vT9{zSdg0PALz^^S)KHt(=%K4{NOKD?#*;iUAJ zN$)6Lr32uaFy&hoGiX&BKs~A6jFfMw{l^B~a4W=H!xv%_mQ)%?NlGQ;0~1_LbfW%M z8~wyOk$I11vc*AI%6HCA^s>9PBThn7mT>sowYRO1TxaqdVn;hWU7c%GcrS|$L^s4M zeK`K-;~I=2yNlw*nT!aw`PK-ApWtMMm{O>ge=LkS;xQJSrY+p{u4k4=pG#H z#9BMnrBs|{Dep6NbYp-ouBUs*3LQJ z(c*Nfr2#*LYG3%~C(@f@Qqo2g$$epfM=vO($qy@SA$pHEQvp}PozFrWpRZM?)JY@@ z)vds>N;XM+SCL_Ib#)BJx7-F4I^YQTCOe>OGXruqS9p$7T{Ag3N&cN%HFan!B+GK$ z@Jr&g?Whp#AJbJ(CJ(vhmX=DggvRiW`f40b-yTMw{j99yN*z&idKJqxhBMi`K&M>G z%Ql^0wp$i0`YbBbJ%O8ed)&o6#UV34l?|=7=$lAZUVsuNlZ{bYnjXE7%iq6$fm#TR z>e`G_U89FWYFOz58OiiS>z2%=ueX+D%riY?8oIJ}0!;p92%)}k*QaQqv%uZSlkyz> zIzf=_LUuSkn2dyv#yfcs;p3#?0i63hTT`mHS-$m=Dhu|%XC-d5=wu1t5c7T~>-=o^ zeCKl`I8UcXY^%Km}0Ken!wv2SdL>%i#=5)e>){F@C z3D=DTl^nD9q^LMC=pw6oE)G`}Q2g9jhF(wUC6k^wv5|HVVpzX`jQx*P0!A&l+Nv-8 z=V)p_{NOMs_!hU$+xK0Pvt`~=k>|i_8o{q`M%$e&S_1+tD}czr#VHcDHIvZzQ)~HuR*Z+uDUqzBbom6*sA7%<%b=!T+^`99nm| z>g0KSV>TqjiMr-9a=!ZP#iti$Yd@CpBp9dNyp&+r(3~8upOZtH1ef+LmzK{vlxPal zpvU3%7FuB@1}KJZbh$RR5F%4||QKezU9a#rS>#^KTlv_;briq*BgwcS=rYyV8aBtH;4; zB4>?VGR%)KeTkNj%#b;QPMa@#zJ5q4!ct?0VpZUu;p8+fUm0~lTKw|*3;PHRbD0fw zos}#oB;MxE8$~kBDu2-Al!UfnaV<%9V|YQawAeudx#K=a&IX(MHXLus1fs5!!9YaC zC11Hw#2v`gebA9@S?p_Z-v2}lyu2RR)btR{7E|o-bWALVJ&C&*3@VP;L=L$|j=q>F z&+)@&LekNT(el*n59REU9z7Sdq=bcbVvkH_ETe;Ah1o&I*WsB=(3?$dqjm2^=ctTH zTx z4S%jxaQzvvPjDHa8!uv#%yY&!uxNZgCt0kHvEb3H$_5Jsl>}w;aJO947E`m*ax!S4 zC)>c{;yK!yzRlKH7$n$FpF>n#&cOdQCYa?>PqX-c4_QJV+# zb?rWXu4-@399#uqT?_axn;}UWBy99e&mf}&d3sbm5n*9cVlx4$AF<|UW+8-yDcgRQ zeLutfpClsa{IPOH+?*?DVvxvl`TC|xi`7b2-n=Hti+1oyG;rxN>N3f<|M9+Obt^uO zFaGEk(b#_rU|1epOs)*^S-<@Y)Kyq1Xuzhms<~peJckE+GR5=f4C zP?!B+C1`m1Pw%U!5JkI_Ku}Q%~^RITJF^tMaPi7l(L(hls?9Y10Qv^|BkgJ#vm8m0RnaB_F|C(&E9)~hZk zF7Man>_2%h4(qwhTzQx*Gy*VJYLKI$u-9 zX5a1wG>a;t5SfUqyVOeP6nQLPC;M9M`mFxh^rX0?Rw#FRIBlZ8FMp`+T0`&N3zaL| zn#Vw2Tl~Bg9ogcgScc*7d&rhDhys1jBrB;;ZC6C0ZbTeerwz z!BKwnqH6r%6ZQ;84s25DMkIVptBsb~`OQY?R_muh93n;X;|hAEX^K?+miy0l^fRKL zN8|;PUo$^4*{g0iFTx#mpAm#lnoqAh=4Cmlv#yv9!PPpwWgIe91;vWU-D}Nhjm#r> zXld+z=-z7vK}!newzv^kChVz;)y%%GJu9BVM8^jB!f*RF*y>t7>}AxS^MA0-bxg%L z=5k%{tora1KL6Cu>(QoP0TP}$G9VD{?>(d{NY#3QFmv(mC3}MRiN;pDptGm3V=#6H z7)eV)dq=9vQ62@jyhM6a!Rcj|&EqRZ2Dj_yRExWhL;*owttf0bO$&%WlfQ5#zsr|i zA7W$g8*=^cFFJ7S^-rV4Dg{hvRy*o!PGaT9k0UBYdwcSEQryLbpPEc4@Eh5tkvDa7 zGlhSY*1!2pCdDwY#)&_Oq(nlFv)?0t|KMDxo_z_nOCJ-~a66`^)cI5CmrX=Ojw3m_ zqD-#GCyy{Jsk3BzI3qyBJ4C^6!-@4e{uNG%7AyW2`=thOBH8}j2;T0EG6ABStmhMu zxCah9k&$TV>GKUL#XQa;;!z#|hpI@mw6J@fBVf`}gNp>vuD=98HOBQ#$wHY0e}1O%HyJ->U(6H=beApP7*F%L!?LiL-s(U73cncu8_#?Mu37yo@| zYpyv?#Aq#@M@Czz?O8upGYYr=>cWD&v%&$&MXxUD_~0=}4eCn?4h{w?yp-b|3#KjV zr#l{-qEBBSky23P;F1qEVSZY*33&2TixmV*#1&mgSy@`H3xB)UQcXZ2RH-R~~iIL-3G!etv#X z($m*h0wQ;j&r{1&TQ|iIbb4hBE?&VebFf*cDJ(8l82a7Vd3njp@%?g01FfmCstbka z0ddn28w=}n*0N(qr{A@m>4?3yiYhXxx8$RZeFH5s{QTuE=aNndJh4dN31-=qrG#@? zNuS&!Jyp89&S6bo=PCuq?;fqdRZ5E<^NmE3J_vDGo+AApsb7fg0#DkWmZ(*Cps!>I zo?v{X`*@Od;v^w0601biNlmW^qW+Kuks<}A7X@l!z^Fi%_tJUkQ@`7sBbDHu8IW0W zjf*|eZkU;bpLIm_6qPn;)|}fT{UnqV?6shlO`VaF`BjzXIG4LI?B#Z?JCmF)C)$(e?^*mQc^F!f7@7VAd-U1`U=F&k z-+};z-q>n(oD5zJCv=x}dewFM*xTHZk+i5eE|aqlI*;KP{N$ae-5)8N+iNiTr33%I zIOEgF$oZC!Eq_6xJzI*USr!TpyGPat*^*S0Mgu?a?hscH#yh~whjQGenxY;iPQx+Z@VUZQ?;KK>9wv}!E) zwpaGqCU3^k}19l4zZ33=0 zHp4MXJtP*=huZ0o*Ys`gl7qpOg59H;ltlQS_1xd{5gqH>Iu1GG>EyT1r6l_5Z7y4V zql868#^$!%1>$V(Yt?&YZ5g~5Lzb51p|JgInFgB79U6E=8n=rg!^5gEK;pL(;U#J`OB zId?_?`C%hq5<=+sB5?Ln`URL#zZIR!Phqx8wnL(e|MNOvOj>f7kdsLwi|3}JduJcTX&!8Nf{m7z&+b3KR7znVHvou$ zYAS~IE$!Z(9%NfO(Z63@AKCN%n3$OS`v|m4LtEUX)ZmKv`1q~QDQW3wQZ%9ZnuZZS zcEVd>3FGL!Y0*5EVI76Zg(AU^;i+A0|Vu+t45hFJy422FcWPjgVP{L#2G0U zN&)w=dHMTklSY`6ZIG&6hTsvx4oYD%GQjm;?roE!&SuLl-bsyjXUNr><*5f?rE?IA zt2XM+L|xUedT|u2q$-_k_exX_y(dzO%y$irD<*;}EnQ`O6b2kFyCTzH8}F>`=a-P^ zk=>hx4EfD4vq%&_&4OqSMRL0=p*7xqB<1tw$icU@HeY7>P<0_vFZScR>UDKv-oMPC z=!GJz>2=If^Ur-wM}$aTnXdH@3BGh3Q%*N>dwo7pi3D+Cn69e?k17sR-Ju0;j1`it za5!hyZE|5ieK99db3qeG=VGc^jQGB_={ASu*#2RaRfQhFxNp?71^ZN3Z?s98y0!ou zg-GIAJpQHeRl?7=P=b?dboc}BH|#F8^)&`}093?*o^>38UcU1wejeHWx*qH_hGfnM z;C05R3JRY;=j5x-AmY}wrbQrtif+7pS&R@e75VQ=use`onj`qw<}SMFE9LZ$U-PkV zG!!z*Z%g%Q4A-;|-YqT0^-I_zojwXQqC862LXXA8DtI=W4Swqn^T=x@h5CaVi~P_| zug>0hZGJMa2YZ~48#i??6-qK?BLbmREy z+xaS0Q)U$mHxQCdk)zpC0`SaYk^vZOQf=?Bi9`*Namfk!V#*MoJeTbef2*0F_q$et zFwTOOp8aY5qU_c9q!JT?`zjxJ$dA0eqE&JZ;tT+X+kEIurF}<6&kk_FvBEW@?$*)I zQE9$<9s(&nGqOyqFeHGMY2Wsu=n94u2O7NzmndGw(-yG?mxcpb8tZLmfm;1%9D;MqC zy+LtM_6K-trb8Dx*f3~^ZE;Zf!W@5bAdEW$t>mlLzO#NR-!61U3pQ?idiMIMu9$le zS@kQ`?nV1{G_bddmUz4c+vaW$|E?DNUUADN@bmL04Q;)AL9IjAX8MFsPBulb0Vqqv zP+1Z&8aDw)=p_pDk?PDu*)m14A)8Oq<;)rhf~w>sLLW$Z z4cU8si6To#1w$ndSPFlcBt!IzwPG-T`}VDnYJwqW<NO6#eW|9aK}M%;DNkp~^p7NG84=}9-s)R6z5fJcn_0||OmFSHzhb5^ z`MJgmGckPaSMJWw7~KY7+y<0Ok{m7$mHBFgAiDU^Yc=LXLB<571C990cNg5_ERro| z?q!Yc9fPm%pO2YUlN0k8ONfh)Dn~Re(xJB_}geIH7(KP27qd=2XVgRy zZrh*l?0}I!hM?k!(!N}7GvA%@6Qz* z+ogzGy&1@k!zlMZ|F*{=F)OZrcm9q@9gC3!=}D0J))WNu@AAl0%gy^1mX$aC_%$m& zvKNW}15KyHhwvwX;`;d=XBq*fcejc!YWSG% z^7ie){al03S4o;O>!1OS!Zn(14}C1jv`_a`Sm`;&XWPrxHO)?UI{}u|PdX$xoXcw= zSp$TpWu=3)*`j9p|EC3Lk-vHzrfZqmT#yiOE?+#-_x7Q2_F@C+A=zDpvF`ncXl9we=*ELu$!Rc9aiWuFw1M?H}V|Wkw<5C%917BwqOH=+#jRtFuPGu62U_`_?~~2~4Z`F|6igvV$B2YvnS0W*O(f zP|WJP)>W>?jNAuNol;ma?a5m+9~X6t5KbJf(-JSn!g(pH|3F?ooq?7jR|{lGD_y{e zOiVZqbM>2Yr!=3mr55U=a)uuLxAjR+&7|OFPdlen?`#4Wpc{QkH$23N^{B2;b|>hk z%PzpfQ*AlPu+Jp(_N|VN&fc3DgLmIKL3`!qjvF)$5e#)q`IwQB5tVIWWn~4nPLfn1fwv>}0LKq;S>`L!fT8LNnB;AzU#43x~I zNzN%~n63ZE$;{`k;C9;hYPO>jutwcU3kFg%Ny1_;X#k5JxOxDL<&qp18=I?ZxPvce zgD}DYqRR?0a-bVNa&>bfhyu%|oOr_~MkNjZxxPMC#=Mc7Mz<9AO+GVKruL|3SkrbN zN$2^hoFoinVy2bKXFQLJEebz|8+bYR7lu=Kcd9Gs8T$JUQm`e2@Y(U7z9vAv=sA1& zWYt3$STqPio}8pVWvUQ6w}|UJ=olC#whsc!F+Z=^@DHV*)r1+!^%&j~Pi2Zx87#X;7p^EP$m<>depYJa#!dMb@K zC_>ZbQ)pGm7p={q%xSK4gq4gPQzI+=`3C8xyK`KxdRD#ZZY-^THLC}EalcoD&Us;j zNQHpo|IzdnP*HYW+e5b?NGl-S-JQ}P-QC@tN=PW(Dbn5DAzjiS-Ho*Le|+BWpT!cG zHNy;YpL6!UYKz04?wh~BCL1WVuW_}Xr3xh;?tSVuS80@Xi>Ru+>fPf$XPe-FJQiAX z+$O#z`dP{Nai{imMvURn2Ux73lgCuVz(58LzWgcGCMkr{4V)Kj#RV z4|hIYDXx^3Jsz2_&AD!`JxLu3g-lQcB$d5w7{3+Q516{132UBGR4qTdL>vyCCcvE& zPt$F^)qZvny;G#!=UNt`%$4CF$1sqt$lhVLdHEXSV0nzR@x+Vt5TFbfjdzOM=sdGo zrrIB1v#|8yyWcSYz5X%h+EA7FXJLY#7<$g3*Zc@SdIA`Q(_58kkq|@?qkQFG>*>F&Rst$JI{X2!2pjuViEVl~hE-?d z^*a#3IJG76YW&r=1SU2OStm9Gxs~AOa$uAYfJxwt@doq1e!0t&kFl`=PDxpamsciK zsu+%gU{vb}k3$h^Yze#=yAQ_a=~@y0F)x#jCJ-hWz79Huz%pQJ8R$r4^OcKLwLAR<8s8ETMQx>o zJLuo>ny!GjXF^m5-1VJ-s9fM#2RGoPgkAIIki}B@ruY5AMj!%$sz(Llx-> zB&?_VpA}nw>X$^DqqW-!J2FuIld!1VIaet>`WHyX(uZ2Zui zUUi1Do)ph#ieTGldL4l5Aw$t`>oD9VUqbbQu=*WoowFDkZ~V6jBy7WVz~AS(;VJWL zIaJtdA0^w9#!&yGx2b^-b+dei-a(WFpRAe`wY$Th8VJ&v+hTu8W}Rui{qoD@$+mR$ zg@x-&ITW{BbvBX!{R068*CHROV>_(4Qj|m?{I(( zBFW$M*N=8L`=2GhuE*Z7ks&vD46NpEEoA*zSqKQY-c0TwMa^7UZ=2+?eXf5U`~iai z(s$S3)4tSJH-q@_TEa-IujA16m3)VLk0}+rRz(TXpeg(+Z$f^@%%s}Q|X=!BaHsBQw z#UTkJJ7A5aeV|?=aV0x5iA!j)D~P^R!JNv;c~5jL_;AbymMiz5A?v5&D9j_AguIDk zEX`t7P~^LPR%`4bGbp$X`WRQdI+Qo4IRr`wogw7NpQM;)un1-87fx*72=K8Bm(ra) z8II=&a75khg>8^E=n*3iDh)}zeSLxYx>T3Z<;#pKWPg9(@QOQqj5SEHmM!=6fV#z= zghx;?Yh=eV{MQO%s=E1U7I*p^9TzXk&*6o|CF=(!k}^aygM)}nqW!b@!@CkAs;pit z)&5HzKd#?h6;7Lv7p@oKZ`M$ns|DqRHeT-hg#jNSN>sL zH_I&)l}xYCNUN2+S_UY_`YM>9RA!3@Kg2ytE&gZwVyQIVzuq~9UqrWQbNi3kNMl&t zOWHh4GR9SYg+ZQ=WHrqrX|#jQdRo31HDBjr#pJs>_J$5VW=3}gh=Od{1D5`ww#{4! zWVw(bpmVY`B_te{bSBrM?!NV9SKDG|uLrL5UZcZB{OcO@69!DfvC=E!>R>!sK}6z1F`k*{HT4ZZe)p^Qu7gDg{(`*Mn6Ez74reOKH6nvt}yVtI!Utibu< z9V86F)~g9xcp4GuufD-E%ll9ZA0$S4mg+nW`RDz?*0lr+8p!4mUvU3$GSK1fam+lF z(E(`eK=adSE??nxI4vHlZmP`3)kgmPtyPD+flviWdVdqL9SQ@@-+wq04G60pPB@c+ z^5h8}C9q8f3WK=rsWIeKgB}usMfOzLG>VhV&{Vu13M-+8sz9N9BPj!(Tr9^bVe|w3NT(rAP=v=>6fWDDgpTIw zeR(ILElfjFA@~iG#vVB;d>C}=B+G_R(T7SfO~Li3JhQtK9{K0%yS89HDl#U9hl|u#JQ$Kj zvmairuIy1JaUWYqAYhux_$MOrnKyYPS{fv%`NAgN-f32rS(Ub&eEj^QW!|8M2RQz~Q0*v7OpNn{c&X`k z*JP~l!win;9sUgNsB4OD-J8)-R1to*Gx5i-3Rq{DDHk*;>E`g+lc}#SfIiE)xr~Aq z;)!-dSEWf0I%ig~a)&pQ$pYAKGtkWQQw4XsF`F*=r{H^`*zBXp=f*6u)6#x?3{f&u zK;er8$_Nle;ILE|j*Lr0@}4i27XrW9yk6~neRzI;4r&O6H-R9ZdK?oM6DT)y%$#Ay zQTI}r7|E+`^tJou+FZl)VzK?N& zrXACaAs0R+x9J79@|VpDQ`(0PoNl8Q+qrDWzm7uC*2(-AcKR@cxtL)g-FX||#{9YO zLN%VW;rh+&SqY&>Pk%j8-D@bQdsZQT__in*AzN%^=zFT*t;%dvh1;f^&x}Nc)#`L{ z?yR>j$We-V^I>!>zg%nceEWHsiryZFgQA;6j3Dl4Ni$kBlFQhRdtL&Qm1qm|3h8)oFUi;*3yA@yJxz-o*t%NzqRh>KU|)EPJ8+_6zkENDnvt@ z@ix5eTc7ua|I&}j+&{xbv{zC^bx{fvySZ2pUb-vC+pkt~r5PMIiCjgXmwpP~(Korn z4TU_S2iHm;MpM~L=p2nV)@))~rkWJz}+U9>0 z%ATf_LgPoD{>Y;LVdn)U=CVTvDZPGIza(?1H@Bq1uycs4%qipF!^pGQ$d_`Ae~4H< zmjpT@P+uj=gt#g?go+FGWPJiFir2JUf&w-HLhS@PSV~vm_5mSJh4}!_b^`#{$c`?f zGa5)FuVOx8fcX3{Nv~tnKbY^Pn&kCD)s^D^;6zHS{Qf8# z0kuEr1ahCUe<&C48@hqF`*vU%$z?z{=KDl&QChc)!Z8pGfzj$8UNZDUC-F~r=Xrh7 z$IM4|oJ~x&z$qusx`f>0B1zn$&o=p54|A0}isu>hVPK_QspYASn0BPfQAU|CGXJ3g zNmA2O)`C*3;~X#r>7a7OE7+we7|zfEtIX;BCzUY@SY@BF0{jHZA9mK(OLbQ9H~xPJ zP7e=haUwzGAH2&C$1kbc^rsu_PUp;7LSTc~GqX*V1lC@OR|-XA2pRx7$5jGWDjx?0 zdHGmAmwwN6{_r;Ydd-acSN?p!2|PWJx?$+LV9@#K_1Se-`%BIB7}h=7r^_;j=E>C) z3$dM(K^70K!Jdf_1(UY2EM_k<=YA82@g%%3$mQopdtRCx8i%jw+({kaW`THxwV=U6 zRuOrw?Axj_o3pN2gnVbga3}j0SwY@XjHlYF%0Hn0WfAx#)U@Ckg@s}S6T_swfOuZS zfUeOkHC6Ekm7=5mTfiwoZYa?nrtH`8fC|GNN7 z#&VRZ7{9Ok#yb2T8+h-53v$_7IY1&q7{nM6;=0!;S(UCb&1 zw4q&x`~X`Zc)j|UN#@bw@V5;xljJZkrZI^tq{n85sBv>RM}-AFeC?5rrCxyK6@Km{ zC<<~BKVGr-_DD$^#ngfM?m#g8$KRAxK7TE}tkB{t(KTEN(1>}J5qL- z$=n`Ju@bYv_a4Gk1^F95%v-wqQoa3bTpYifjoH#@=e`9>;85qjojw%V>}=(@=9{ojDH#%9R(?0 zSfBEn-L-3Fp{nh%1}q&ZSBFToY&sL8Ax+ zb=TL|pf?2yAWu(jyZrT7*88+E^DXXwk4lu;&I2=g5>VKlgy8=6EDzis<#yYGS`IJRmY*jT~qyDr7JI=-IiHl+zdU! z*ppklkw56ojH6-3sB$p~4EWHEg3FL1xjX&3`0{>xN-AI3s4F997ZmTA!c55{pq>YT zba}IY#sXW)z47$PTcj{TFp(61SyWd(mV9WkvK2$qJk`EaGWj*2M|j7uXVzuO*|{_F z2^ZAy#tOPz8L+|^<6gUFTFJEjBW8G{KKcvS(l2VyIMwy~y+w)~ta^8iMS2>M1?5nl z!&ft>mY&PHUe#KIV`&0m9{P|-I|#7UN{b_g6;|4I~Mym;mh*nSq@=d5_7VqZi0 z6&#YStUHgRTFDAI^t~;W*6ORsu8tHeMCV?G zT{3-ZTeBbGQ}%x;stTyP;wUjRiMwkDE*E#?GrxS5MxBaBnphXpWB;BDrdQy|iy-^U z1ljvT?wpk^q@hhGVp|@$;2ll9I{-CUS+p+F`}8-%K8Ba}bj8{lBO^=so$Q*LsI^xv zG|6hq`b-`?&1!YB?)D|YM~8~3A72fJCk^O9lW$*rai(^*Rd5@O)OC=y(%V*dT{A31 z;d+yKc^jmlqv6rPVaw227E{JGcviZuAGC3FxT>EvJlMIIG*J8~7~5EyJ~sor3njC) z<*cpVkpEFSd`WHc;VL*Umn%Si^K3ic#k4}>q(w1Yi?A8M>-ta3d`zrw+;;T|FB?Aa zOxkVT<|9AKPp%DBqe#ipo|qB6(wIp9fDG$9gD}bm0-;A5)Fzi(K{!;6_O}B(=UnY2 z9BO>I7GJ8%KOJE+HOs(ZeIU?*G30+682`0z#M$)YY>XO%{!=@ zFwlvkqCFMLY%o75c_H;M-!UNe0wf?t!*FE@_}jKGr9EwWQ;b*dxY2qpI0{+tNUHO} zwh%WyM(%OBr%UGF)_@8Nilj|n(`w~Lc@E;Po4>J@ADNDO^YQUXI& zbcTYk4P3+A+oLDuqmtef`tt5szng`7^l*n{PV`}SAQ}QH$pwcPy|bwk*m}3L2jJ4f z!^a2qL02>j)>NQ|qJ6XPZn&GgYbN;avi2=ZZT?%r_;ubw&?@r^2!QcXXxzX7TnIHIpnSF5)>3eN$e2zmF z9Q?Lb*Y{Q}*`mcbB^{e9doSyvV18gt94Czb3*qMBUupAhZE4B!zqitt0{d^9F$hNkcgW;V{r&qF z#8&#~0e2*u(aP%Tcz>2R{DL6+3SS*at&w?KBJo!_Gc|Rw%BUA0EHFTn1#(`%47&53 zTnD&yoA}pmc1U}%7k(rR=sD!#g;n*&60Iw@X~?IGW$8UySR-tSOarhS zKjX(@+|2rWmSMp-X4h;-Cq8~c?huenOcA2JAX->lo^(LV4Atz@5z@LR)9s*wCLyZZ zv8K={9rI&#s$r3C>}1RcS%E;jf_vn8u9CG{K5aA7-ws6jzPe&9NG{ImFzk1FZD+6VB=oKhlwLjZ@I7;~B zR&O(aRsm%N7#9x_g^kppHR&CWyDmnh;%7BHa z3g`7&LgSy~{Y%8Irv-bKrN`pfTR*J8$FDt~U*(UK8=B%{HW>CSIPamWJ1kxqV_p6^ zB{uJzTksy)`TZWEp>^>FPI$SY$ALo|c4Eps*(*_q?ZRF`owXyUPm43K4c|-Y#3B5D zdgsN&9Je&nc+135rCvUqW~%d~el=HvKO&q>VkJPKMS;11Aj~EyUs}KW8Dot3D~K}( zxLym{;26ys$v3!<^fF*x#pqZRFy@MlnAV4y4YXRcjpXlQ{}= zm4cZQL`{hhA=+6qa_bH!jcfk4fNvillbA~R#rzd0sOK`q%%%OCxqf&-t2=9=nTF>{ zw=ZtTd;xcZ*QnNHM>VmwE&+1r*v1uWOHqAS&>|!qEd~alz}B zs%s@MYza6*BB~BB_OQVAWdPOyNOboKWY={eg!YEid0uXASR+`3&uF?#B_-jodZ+bW zbGB`JG5{5%S*=!kS&z$b2&{rR5D#La9I#1ND5CunSa0NyFaX@8*$nI#pZIWL4i689 zcUUDQR@jQ!Cpb>FL5|_keC65U;U+IyCPQ5eV8GA!QG4;;zTK8kHZTA^3u+)51CaUD zjizN`rA_is0e&*n2uKpc-4j6P_nR9%X^%1D2Vm{`ocIL<#>}&HxpU^sot>xH<=ZQm zIXOT4M5g%nq<@pUilwbAEx+GpRI0QW^x#rr8a1Ah4#h= zJ3-<7UdR$u&4VgI!3g1-C!$j-h8LJwH9EApYT4S^XNepaQ~Fi=J;f;GLh*aW`kvy~ zke;KHN{Q(?FEUy@rIvO{x2^o*4BTh4`o7^aT`Ttsgv7#!@3sRK|<#wH;ExrG7Yueo< zH`?UAr0t~9=5uk}gb=Rjl*;^k37zt5P69=j`AcEEI9;k(x|K2B#j$qa@rjC#W;+<| z_tPxNO}LBnGx5Q`wkX3u#BeQQa! z;^cgVhGrEg+a}1#*-y=0|BHandUd${^|A|o(499U+aGAapKZ>H?kb=T$HuG|@_9Me z0Z9;$C^z;2x(iH%ARs2TI21}BYpAPpRKR&xmV*;ZkcJP~ zHGa+kEdlUvd56#6L2s)yg8z8{xeBm}|FHs5Sev$EWwFl1M|`w@H+KZDeFld+1WuOX z*1#!3c#|@bfs)D*SzvxHcU}0rCo0*ud3J1)`IlD6cdT&Bu+Q`Hx8^rI=zs@C2zTK? zX#fVULL|gc!2dD3-zD>J@fMm~j{_nSof$y5&21r-O$_jpza6|`Ch;~V;ZzwXS$M5EvF>B2O!mc66hnK=fjflwU2Fq z_6UiCZrYLDN5${*e)w89d z#U~ z!fCwLZ6^k$O;odyY&LBb-XUFskP4`}C^s@V9dN30Xzp!T=6|rT*aM2W+kV;4E$E;9 z^;^I%C*BW$08`W8@7Xk9qd5RIyFjnh44rsI+i`f0TkRy6X~igO34=8807SJDaBRoo zFURIX{2UY9>BN}JY}^L)I9}^*h9Kes><|k$^?-ZNN&*HY*|ZV(x6)viv7(5qa^8Zj z{02U37iH2vesY4lcV2vf{}-qWz+ns$5k^TDt$BLl>|XOu#h(gsG=K<*Q8T5CxnY z1U*@P!`5h>cU)Ut)9)GF{#a@H;6rSAhcKd-HkEX~Qoc^92ek6>%ukK`90TGgA>#ee zWyyC(eMOSY=AJOS#0qK}_qBD}2+jZ#=#V*WJ=QWNcXUZ5xkaMGW4>5KgqfwsjIC>3 zH71rl50U2rqRo`gl&*2I#I2ys!4saxUYrN@%OQsF#wc}w zIjnGoZDhP1q> zB;FXQHJL8|r+VeO{)3Z$xVhyH^fmr`uq>@GBkA}7t~b2rg~|5@b{{!EPi4?q6Se8r zT}Y0-s7Q8L#lEPmoN4Kp-CyKJKK}6BQ)V)3Y&z25`$uih9%`vwo4U(UaB*F|% zi7&9AfReIxD2<~bmzWF)<~=+val^BUFG$*F5hR4e`{I60O^Mpemgp3#Qd3gC$x2J3 zO&)ps0{A+Bw3Vf!a)Ir|fNI0cKJ87qi1Th4XqOM}*FEbTGrGWAOc*iCteb6K(Pb>$ zAu_E2ESem(OS*C~JCL`Ol~G{wHwSm-{QwK}E0v3C2Jg59cmxq)n~xd&IoHhG zfVgI^)^W;`a)Y9~nY1%YIp2u&A$c(V=R7iguf|69}=P}dx$%Hx_KJh}eXS@1D z52jE)x^lB}W=t~K6fO$fI33+Gsu)KjW6h`5~rTyb=$8}kh-0&GK;y;ZjI?Kq}?hdBU(@a>!VHN$Y-s|BY?0Gvucx*vJs@GB&(g=V zAk`z_Y0?#;S72a;*!PyP7zxPJNQn-Er3-8(h$&(5Jvig=ibeWDhCwo$KG0epT!GAm z?Hagd01FXZJ7YmM+v{R(-p@V;BH$^P@u~Lu2tt);6Ps3rgNJ8P$a}Ef;hU>wNc-Lk z7kL&ex8>(kM45~;<05$;-j!zw8|$_ocB#F6m6D7>!;>8wNukROY_>pF3jq;asQ?Pl z{|52=DCPYL3)v%Z_$n0l6W)Iew@Ja`2q(&WtG(D&C}~XX45r|AeK_C> zd*jA`(s{m+S44nqulCbr+o1(&A;pK+`$dA!jXHn4jYh;&ccj|3-3hyH^Lf=4E-*OU zQPTpDLHKYjM)vXIYJyii@#fZS&Z=AWx!^qXpOMIKmwG6|A31l?Oxz&?bi%Za^6$$> z3aBR(KYg~Y?R9xEg^Hm93YREsygc7} zWO&r`wQ%gK?}%Nmdgi3uyfDx7O#iIf6}Xswg$>3Msw^+`*9 z+PZ#or<3}hcXe;hz~K2;&UDB1t;LI5j?YoW1mV3#$ar-%_hOO|sEUPtLo!TEAg2fn z{!qdhS7ow_6Lc>TlRT6-g`gO3R6S!TxV6I)cC3WzdJ2<3E;HHf_6zkGvE3We)4AZJ zP)HR*-Al=H7)VSCusYT3NqqS-_;4`pgL^IXhBS64PmLDD(LJ!(thNe3hU>L{ zTa~$|nY`J1wL1wCLk8pYv$|6@5*yhei$#6nZgtMe*K_Im?MPjz3O{?(lMVG@X=G-@JxW{P;$q{N!dqO$oRA zDd$HRW8^>ttKGq7OU38UpFN%F!*C@xRDO_1ISs|iuv*+sueeP7OI>6WV9OjLPc@~? z0lAB%tu2SednH*Fx0l5ejl6pUo1tziZ(&Z;ZP@1ocpUwC+E)ZMmk=hN&1;{_-LEZw z+53@rFMk~8o;*Q3R@ZtWF%dXaiuRr{ITL4VCL&$Q$IOot8@p)9*MW|udr_7vxxi5t zmiOicXKYr{Rmznh<;reWLP3qAv%qGXEAPMNnEK5>dzW}*-!vp{h&+E1Qshh_u0kG* zL?pdw*(OZE@l8Yu2I(4tii#RT4>p47??Fv$i84wU@!%$23FvKDEQ&XY2x&L^MCv*5Zk#UzRARW_FmKuwc~$sxNSDM)5{;-%*Ou*-TJB(}vvmGQt4r{o7EOD#o}r}c zm!pMzJy^&4{*1C^$JW-`+PFuK)YDlVkRk3e7AO?8~&OI}{ zULy^w4NF22+G`QG(?A1VtXcx-(2vxAR9fbklgSYD%=}cTNQw8nl>y7ogrV$T;aK%e z&aos7K5*pyo0Vx?9sJOu4&_~;S&Zxu4AaXuXlnL<9}GslIo<7#1smKoVBO`k70=p< zyH{;E_!!x2#P|{BDnY#6r|#WID0E0$&CRHlV|&-4?c>kscb`XHLz?|p?2{pXBUbl9fAAvs@n$Lm@@&voKVFTy|YmYn?OBpInbwgl;}Tb=g#< zDqm)EiBQn@Dnk7AxY6k?Cj_>Ys(J@Auy#9gTeH!RbIEzGm%pPS?v7Qr8GLYS3_E(v zvT^mvt;=RApSEyK=$V69#(bt_Ivf72$lx?@wo0(u!L>Dz=;LH4WT0Ic-9fviYZmA} zB*(THefI54`c?(%M^uUX-A5sU@N%VVyH2W}qwJ^3={fh!rHoRDqsk|h1%=ba-Giul z%-<)bg_aP<-xjoMFHMsoPUtAd2^sY-&nWTQ;K#O{4E zRC_uL;T~^1Eqi$>m;AR-DWc42d4~%72L>8#7cWNHCit%=#lST+%mbyw%XjDq4sXja zIq9>RnS=!8Vih&cPG7+_F!XXn79>bG{BHR6_8W7Q6KCOkX({l zr}Yy6{3@m}o`E(S=hfTr_edN$JSe}|zlD zaf;@|C=~L@oqO`fN>w2NO@iw8X|D`dHT+O!%hYm9CXcO+*&(FFpkcs?JtZe9A}&(b zUy3hOYs$$;=kV%uV~1$c7pUVdLEIR2+cmpD6*g3+-I-1w5EvFv_?&8vfJx@D9RQP3>zyn;18=4frRQ zcvhIgxLFrc5S^JgVkQ_Myw49*=iJ;2z{6Joeim}C^fs6dr#Wj}-DEvm0>%~4u1UWn zZlDvlk;v_ts*GriE=U(QrTNHw9y_Ht)1LwIsc3=Z*zh4pIf8uQyrTwvcW&5?%mJEp zwnxxuq#@Pzw@FBtm>(opNW=yjqHv#TE8XS2;41Wbfn`x;(j~}y*Femv$U(rk!b_lR zK+Z!x=I@4UwZKy%`M1eWlDGb~IB#5L=f3KSOc3EMAr)(yO7QB<(2@`p{r$q;EkN!_ z#KjzfoNix)SnU<2d8QMao-kJC58Jqn? zpG3!P)2{CThQS3CeWFmYk7r=VJIe{HnGvNbdk&hie)8iAT2tolUNAm$Df+s{I=HEG zR5<0i8M0`%p9zvXWhQn6@^ipz_*g2-=x$cY zT|3`G90g6A3{a21vEII0xoZ-Mt#>g>An@RO<0JIyHZIUoe|g_0U@ij%ZEtJZAV*++ zznK_(khrLa(Tbu88y)T7q}KK<&nC8*tr0+zv=yu`H4hGEG+&L|Zfa-q@F(sQDs2je zUN&2@tY7*BJ^%jZ;@TImbZyfu59dB2=k<4iF{vQw#RIQ)N|z6v(8W)}{bSEi$9yG^ zhlW7N%}D0{<8h?e1JBgm>gdn(lE)vlDc8>9;(Fk$%_Vy9V2@XW`Y!6?=*W!PJC@EB zuSG{Ht^c9&>(I~;_!f*DydX=HqRub52;BXUKMgC~ev`zYlhC4)suZINq6A}FS!{^W z^Wam*;UPtmSt%(}l<|Gm%im-)krlMY{}+n|+FvkMqCG3oZRmev5P5*F+oV{Pv|Fxl z`dd#$*opT=GdCs>hR7rgh-cy1O{460fOzPx<3a1OBPnvAAi~ltbn4)_MM234JN=FcP>DeXtookwZ;Jj;u?mes9VtcW?8Kl|J)K0h6C{D#zN^Abj*j_4 z9uG$IJx{SEdLRjG@zh$+vOZ}>c8XZLtjhAy^x%Ti@BAQoa{YndW7m$hx7j1RE!&l` zoMKqLxtXytXURqA?ZOw?qxKQwzlYUpUp%wXyYBDxGaXKGVfOf80_{F@VC<Hc%7T?7J($Jdj?ZAo^qp9y#2>_x+djQBpqy4euH~GB#;dElDL$6`BsL2&5&)E zH-Z~|qV?-jPuFSOEV{-utT&^ku=N0LXmhL0vAJJ|J8?v$A7oBq#Q6Kszv?%a==-iV zO)^x1Og>2O4*)W?1G(mG=t)|i-ymQA!nNQxL`d1aQPq$35*Y&8zxMWanek%ey=U+> zI3PwjBsD*LE$y2@y@!Uu19c}p{sFL9939D0#vix>5$rF5&p7xk6)HMQzkcP=M<28c zU(@~4=O?0ag^!uo1L^i+*qqH&D{P3#@k6FS8_qxg!SJY2zp4QlF$_47s$B6$)zzTy zz9Lf(=1P=#O0mpOF)B{Wo%t44xU!QE3wC!G~iJYFD`jS=yA$QsEawFx9` zP2HraV~>BGUKX|{AnB_WE&a*4OC@j(gsTwqnF|6aG?H#f@r&l*$C1lBHkd8)Ma zb#+z7Wo)fcRVf6HIHF9pkYhRZ#5iBbayA>RFyO%-8i1)~*d8)mr!6BrTnW1s+;EJc zT~A%>5RuS43JIJAZ+iz14IN!kUfv0QO8J8uE}%y*rmIeX)hY`n}*JA&cll=64!qnUxFmC;@(r(r@zeEXvwn!_mg6x+~ zEiC*6!`1)ci=yU7-1;(H@}(F(u0%zB7j08_$tscKR1Xx*;~B5bClJd$7@wKuLr|36 z*#^t-o8P|^W-Q$Mcz5?qP_AV~)*WT!&q#`qtKYq3ZOwN3Xs-W3L&%V<+) zaDja2vkGnMOGtM%iatZ86ec;`eUfy{aCM{)nneoibS3#UvX~9;f1zJ#tVXyArqQY{ z>ERmwAkA#}ou@ICu!6vGFh^Fv>|0s3C@J#*Ias!bR1q=%geNW5yE~m5TZ0uib7i74tiWoG9zN(zt37;c&kymgbWB{&}Qv)hxo{ZdFWM{x+^T)=Mwt zq52icWxr#E6x-$Q$DC@o54&HPJ=z8BpdUIrZZ*aPMb%gJcYM&TZ(dLNeC#DZCd*@0 zD3%;^9P2vA-J@N|k?pu0&GJjg;az5e%c@)?%!i(vlg&P1>u#s7icZ?x6NGHeEYIGv zZ~L7HP70+qhTMFR{>$ipaOfyHnS^L}Kq|-K>lZpx&)}Fr0tg2TE6&e?;BZxhFl&(dnr|;dFvjEy1JI!6|^(!J2v~ zEH1Wkbd0etWFOV?KLuC{m*u)LUbdYT$^UQfCA& z52ohMJSF4u)dr?|^=z?(FZ$%_+o^GJxeH8-M%D*~RBV)!x94taPm@F* zRj&*0Q+vg3gN562;Dgo1+vX<5LRzm*o2%w!ZZjwxuNU<{Ix;YxTeXyvx=bnXe?0SN zhs5ys^}pW?@PjPQhosJjoKgiHr;FDAdU7SHxP~%ad)t!zs&BTVX$c|5OAL|Z@?M4q zJPN{Up}HF3APJYn(rQ2Vd(2C@E1byS>hGpZHmJWhUJbXDRaq)<9cL>` zJ|TQj#^vfe>1bL(Ao1UbG*D%<+cOEhrk!q8ygdEwBa0YGc=N%ESg-s0s$Uv(pX`xD zmX}Y8K;ea7k3vP;b5l3=XFo;&PB{JbjZA|ab80;eYV35med4wr|0GrgZ*djGhqIu9 z8OR4J9zyd36E3M|ZdVJ+S&zzKrVKZB|Z;Al)G!oBi34{ej${j(%qY? zdLQp^XY5C$E<^Jr|99HY{wf>Az*vOZyY!0qj!*6+^IrBICwgG002^s%{E(rYAfYHp zN|wT0)xW!LU`Nt*?%x6it*^8MY3z48M6E-xGeCjf7n9dIb!b_75sdlSr-3r`_09Mj zU4TaZRfa&9`i-i;)Mue384Qf+U!R-WK*<1zD`lD=E}ME;q8kb|+Pn-^U7*yZ9=(^M z!3q}#tejrBRcd)0owCup=mFq`8|qFKaRT-kUVB=X1Mjjo%Z~{oFnz*Xx_06Cd1W2wRxzmhs3Y%;*hi&bUt9plO9T9KwKAYg~1 z)tg#9eEgDkS4NfJ{T93*@2L2BtbMZKDQSHg zWY9EH2}gEnlm)<+>+%dTSwJ41vWXx&dx9KgamSw5Vmv68?tJ}0;Kj~x;xKE-DmM^! z&g9UE5!K5{bWD_{m`Iu`s`q#aU=7nt!mJkgNE;&IZ~tixxaldmq^jW_ZB07n=itYpWt0amJ`pK*O$JONy|*A z%@BhaIt%)#*j*k;pzWnfF+B4VL&{~{@#Y?G`eVHOv`-zpPaPZ;H9v@Z+J{~Got>p! zr|x(n90{m5=i}l&2s9pm16fdY*M5%Y^PJBQTk|tkr9^gR-`>XOAy*-S1xcw}1DFRd zR*xXYjxC>n*#x(6wqVlZ*1OV5B(UzH`h7sBF30E-l-4OSpovEF_G%e zDIw1HCyQ({MXA11!)Xxn;*r|I;6)YDBN+2tY@<`06+e%4Uz-D5&Kuo7LXn=$XK1R+ zH|4+OO3G>AVb{^DA;+(z-#2g-@!Z<&@$GRF2f7s=NRN4$;y#QC3b#pr(u<9BS|JcK%;$6RhN zy6&X5y;aTJHXo0snuGO-76|jNBZl9OJVh&XU;AT?tAzSYzIx84m92Xh`o+rhn0*Y7 zX%CpYQpKNE40!$Lm6$i6R3~v3K43WwGI-H)(*IHoY8B> z*&_${E)QI_DT4F%ke=iK%S_{`abX%lwg@wdpE3a~ov{h{YIpb4@q5NFZhZhQu!W1x zuMT&Xh8O;SG<^k7m0j2NO^b*iAqonDbSfPJf=G9FcXy|Nf(l4Wi*$E)cOJU?(B1iO zpa1=4m|;c{&W&fUz1F&lR-Ez4A7J5tT?5!DiBaN)%%;XoiV}FQXg0D9&!YO(l#n13 z3>6{H_Vyjxd1`d}u165;LvDGDC*mJjYHT`%IVoY85cc(LKv6-4A=hb=zQNn5&%ovj z7qz`htEh0&)%_TkURHE`^+Cmg(|~JujO}gf_1Fj~$Xb&(*Vj?ljo?@0eh$brQZUu1 z2yd#$9-vHh4lE^+Gw3pRIF|JvaQLsG%g^uCzKW#qoq zYeBGN-df*6?-I&y?&th^bKEP&Ka3l0pDHns7D!@DP?)urznp-I8 z#1#arjhoS4uhLmVOTUTw=W-CB9laCcWfBbZ<^j}dFA*j6`mT2!0*xGh_v|-b<&EH> zT@Cx@ycA}f(AiK5+N6n6&`dVIMEKHGK4;~=Uzx;p&Tl@{peE^- z90E&e>_GliXWdy9`DLVTt1^AJz5wg@whcI{=jrcUepvIX;AopjKXP!{rNaJxCHi{E zcJI&1A>SV^A688Za3P)zYz4&yo$!6CA4AifCoWJDS}fOYWR7%ssex2nI6eQP98Tmu znDkz?ePZY@dS$ zz4|zMM$CWK@_L8jH_*Xt5h&`BQQf2y!z4c z8v#eox<`mCTs$Lao0>zITw9q?ua)hXjhlTKB~W>?y!*|ZVlp|Ma{eE~1P>f*`4*{E zMy&`C%K_9HqKQ4Q;3Y6-o8q+A2aX8=+L>*jZ$368z%Z`@#AVpix!BbXoT~BmX3$3? zjw{M42RXm~csgvb8`yG;kHc3&{M0H%=tGzH_>1Car)Uh8j*k2%!MEMr-QV%)9yy?E z#EJg05eujp6c~E^ymca4oFZ8i#(M2)`*usR6|88q zsqr}XBr+nRB82I{3?82uZh^Gqm)i<)8btTU1&e{_HJewU#(Oj{t@7=ay(qxaaM|q{ z0fn!0DCaIq@YTrQ@LERKts@jtHmY|7g48&0i?d?H0oeEnuDSZY%(7=+_uXQvVJ^o3 zZIj2a>aV41*(PJMI;}?+>wXR9wb>H$zK#`_Ip3o$4MM{KE|pnNS*o@C32p)9iwy8c z!=fI}(B2;2wK9piNI`$DBw16?M>ctQzn=Z6aY3Hk7w`i-`nNnG1oLbNetf>$Z5=0G z7d05QP52_0;4e=CQjsUM<;uK`&fA^1L;BNfW@s!Kq|fGkRKI9g-@G#;s-Q}qEONWU z*gom+drK0mGT?#x+t!xlYVcEuvUx8d#9R+w5+w+7-vUIEJ9g^q!`AA*=1q z{$mR6*OO-}X>{dAIajfo z3U#HQ5T0a#5M_qdp-$pkM}}?T36Zhs1b!YR5F_zTcoeXK)Xf?QP^hmwtHMJEisc@sT;q7?q&sUn)da@nu1X)!r)QTz`Mrmr$hFIVpQYo;irD31QF3YQEwMQ%de zJBuE1Y!MKuX^d(#y|;6+Hl=0vz-d>fjh63^p9=3975OVmEt_5Ev@-!L3fi*(`XXR! zL?R$4j#3yEftFhyK(8#O28a`zHIgRi8?@vh6ta|e^t z>=TK|@A@U8q0>`S-Cn)| zw528fgh}kEy5d0rm z(~)^O3arMYvS2|Gs`i+^r-|YYh3)0#<#>-#3eoL+t6K%a2xbaw^$+#e{yvIL;`|6Y zPO!oQv~fEhXL^;V)U_r<4wMe^N7pO)8ypZ-YHj=!Rqx@q$j4Bf;>*Y51{ZBwTsMrZ z?(K?$Sar`&(@~e^%;%i+*S$9i;toL&(LCj19J*AUy}wH!(JPm<^3_qdnQDbg9Tz0J zcZ<#zmqg1*oK!@Oyts(fpDta5$XBZ17K1S1Oy2f)*yBm4!zW5xlN)~@748L`QkH9a zS6RPHw1Q=Ok=~E3*z&_(BYtfAxi`3q>YF&+vD~P7@Z(G(Ovi;Pu?UbyEW+gWpUu~p z)W)`NHF|iyS=g(~>L)(k?fZ1ZwdkeutKf4XOP+V#H z>vV6(=`&N-ypJD;-E3riNca9OQe zN=FMrVK|)9gfABN_Y`y8;6AC+r9tu^uz8oSSIzh%WXPZO*bm zH(HYNc@=PxdtUo?c6Ndj)^HqMM6R!}P-pm~-3NMvj6nU8QsS4qykz_k9K;I5@k!e; znzN+b%)yCmn-O|{rO&VgbeDpz6qphLWn3KkKY_xKEdJkaV?g(&VfQKoYoZj-V=;SM zL5&Sqnj_xF55zXs*3y)bj$-?pn{VviQc|9!nREbzm4=FI1F$N5d>;N`pL5TQM!%B9 zNoLB^5UR;Ki_eK2F{9M4ZME;Tw~XzD3bkkhD3|;P6W(LP_<-cykMZAuifWxnGLY$P ztG$|b{jE%|F*`6De4o}EltC_tVdDYuzER`P;_k8fdi zwyzS9GoCd9|Kdm#1=ayr$zFZ|vrTFrTA0#|Ibp4tbhtumf{jFu#BcrUL0=&sSTVQMJzlKFXQER;8*+p-!rG zP%!AHnw!0qI?VQ*xq#wZa>e%Ut|Vn-xqjAR3XUb)wWj`Z#XCTc(cpnSDY(~`+Ux9-D~rQyTUAh35y(ibbNN_tN7sL0;tL`23T#Q?%i?hK()+jv-W zgs4X>BUn@&&guAe*KY@m z6%w0khszmRlZuEY+%i2J-`tO&Ej6-0OUbVdRle;LAsz{kXe`|_x{ppjQu4Sk4!XG6 zf9ZD-wZWUgHThz~hn^R-a)@oUW95u&2&%DhP4P!bLcUHZ~rsWvD!hi z#+$#*ynMwfLXvJ9poeQ z!GQqH;RcOMm0Exqd&Jyu_euv=cM)7j4k62!4mJsCzamjD{l>m)VAL6G&)_{=EUn62 zbAiv6+2B;a<@rV&=TIDW_1ll(kJTMy^Swb?>pIqScM!1u5;3-*D3s?WL2~JEss#Z3Q|%D;vwL zT2QuP{F74To`rI5zSYQzZ4=K(UiJB6jhXFn-hTt8i3zI;(L68<0p{UWbJcQ>1a9WP z<|>9repjV`E~fR&NK?qrO5gz*<+A%McRU9o|M69f`SA+iy$PLdSNj@WSP(Lj(5kRG6!C*ACpoJ1iEOP8nl9!j&Rtkv~YFAazT zQCh*V3djoRTN?wNB>3K~vz^o}Z%SycymJ)g7oM)$*8tROHQ{w({cBN!9sJ=>CDdrPqvr8^3K;x=Z+*p(YF?w6xyzj-T~<`>uiyLq3e3SHBVQb&x6Rfy z{zl#R6N?$WkHxLF|A?I;p0Rn*qPLPx5ggjJnjtT?wLgtj-m!$ihz|B~6aga0n+U&_ zs(|}%wLdKEcfzU${c|>{RYxmR)9jeUvWtIv>gN(pKA^YF5~6=DL5_2(m`Z?|%1-J8 zXfNK0m^9Ji;E4dGru>VXHw|qtwaMGrK~e)ugA&ye)!qGl;qvFvL-1*$pywf+6x9o| z1DWVWHO%RZuR`Om)t5?My*=9$=4JjCP}Ajd-*wmGcak37w^O#(CV52l^t^zI;8W@c zTB^w<>17gN&cNt`bi;zvd=U6R)(1FO&Vu*no&)xhkmqLSI8xX9!k?n;JS@vq4(?|d zMft%g7731KccXY=S1XT5qz;ou?PYe6;+Zf0=vp^=jKa-}uvD-Ti)jbO`aeabRLoNr zG{x)thvnwA@V+gcq@S_MJ;{5d*F;l{6)_QezMxfmG3;!!mQN%JU23gc4UwGAC2>O@ z1&%}Li3dWCt9+ks(+(P0im}4=Bg5d$K+p*l@3Y1U3?_{3GR9#TOA=p@AVGsRPh1q1 z=Gf-1_K*Bl=IdVV=OMufgg2&!J=9NJ3T)-o9m`gzWa4pn{+Rl`9g)aj>j$N7Nc&}r4$^6@Xo9(N6Od6u++1tEoWplhmh(5KeDmG^ksHsZ?O%^ zQ_VG!l@Jwat9g>?3;yc)oOR;oQ#59GcD1CuVO!(;HA%Bo9+t*hzj;{`*AL*g@EIlc8F+G74s zBV?oT!p|`vQztapxOR%%%<$Gns9Y8H9NiFFv zea861%FIkJS@Kvprn8kzNx9DI7VyB2IM8>OmUMv)GmvG6 z{r$)jCux5frSZtaH&JEU&4FZ)y3|tH|E}2}4z2)W<*t$?AAFhj+?%rtutQU2|G+PM zqv@udAmG>i&xE*YJPk60^}c)UJ9_D$2U2W9koR{ft^=s4hwjBP7*HWN;J;bV#nn>&qt$dm`c9|IDd1zO}ZJk zs1j?nu&X|ZF0bKqy7*K-*~M^3SP|?`r@=mB-!IsA7hP53eFyA8pQm$xnv)H-^Bg;3p(#?@%xX$D7X4He4Z0EYSJjplb% zZs^tr^Ztk%8H%J6H@_pzSz*s+j*^6iFk!-EgJ&LV_gz=1%Z)S<%t`oDXcDST!`D@x8&g~ui{^jz&)81Te%_bXy8U5umu2SFiTp+z?$JOf4(Z-?w%askMbJc` zya_#HGI$$L|<1YBjWEcz;=<5^ayke!+M8ar=iZzwpHsZ3>ABSn7{4+ zTFlL)u#x@l!i2Z%egB;p!NK<@n4y>+`{NE5`?J4uh@WU7i7Pa4~OWBr`ZH`g@K|B&$ygnt~ot>NKNe)<%T%672s(KlR)VAxVXI-{W%y}ac zuHWt~e{MN~V5l50jZZp1Zts>9hCahEy7%baQ;|W>C_~4M*&g-jH|y43CzdiaWYUKX z0s}QRwTE+QCuco#Ya#!2^KxP9xC3imv=XxbOFF25Cxi7SO4Q4MN<}-IhY{LX=h|K( zKPYr6o{wCp_OUj>kI&}1&uVt;dBVn73xK`Ro1%&eVB;5i{yMz`uMnr+dbZMPZ>9ol zamV^`Qh-A}fLs*Z3S^DBldOR?DR8sj5ln@AX*ZCba_Ry{V#OZ{)KW)G({o^?_}nPo zk^eC@LIU8c;QNF`lV4_vbHqtT;L+vjtLqi_2<4R<_P|fdyZ=ateIO=z^$JMw$!o}4 zKjh%RX{#`ud3;Ak9${LaHkzyxkYVJ=bV3R5ih{GE*=xX3 zS&KYFvCAHLOG=I*HZ$a(yTZ-4HcVf6J9b$k`n9!XKR{Dcd|3wPB2%o6Oa%3VF!)fF zkWL|6I?ry9yVPK?(2;w94QbtQfTl%TUV5PXjml~LOmBToj+nTZf4C=Kkr`pf$k>~* zG(ti`R8&;eH}DVR6Tqd;Qr*IWE+OBHkl-EgU`IbPV}k)f8V8PgJm_!Ep;$CmsejIh z^R>|p>B{p63{*93`eEQfyhT&AC!0D!NE<_b;z-0`~%m_>P-2h+{hh?bbYvQTC_( z?q20o?=gNmX*0zuWS=XeU7OUVLvRh-Q&Wod(AFhkEXYTHa}zUsU(;SvOcKsXID!8x zjBl{Z-8J>A+#jrSbG7M5x{v!wD6}_`nvo$@mx)bmrZI@K>GykiZ5#5D+7{$LqjO4? zA`74KZV9z z@|*wJo+;riCovn*|8W7T;@-FA;cMW%LU#GtHx-C^)24OYV&f!&o z-8Ak6yf8Zy3xLPcA$(jt%nt@6c0z6yM7MvHaqoLD8|5r+qOA`X)MsPa=Za9y-;Z8@ zTW33}=ii@uP`mjh>UF#L^(OSAXMYtV3#c~muN}LG{e5k71!X=Zs#(?d zwk{i7)Ezh9QCr4mbI)0KcREXa37I4yG|w0#V!!sLB;NQ+XENj%Fy55ZF1|Qp%sic@ z6y!~1$_GirThkXOq{j~LDw|n_^6_?x;PayW8C!hf@@eUVZng80YncTfhK7ndH&cD# zfAfGl{j4eHe)Vb;5gQ~08{Iku)uAU>bPjsA_-E9f*ljIbk4;m(2!ErzY2k!rQrqGt7yRNQp z3`SJwsDYuYtE!zOqNB1r}wXro>8eBR34HkhB)6)^H2YL#cb3^AMnQ( zfV7}9j+!_>JCoayN-zBIMU3=WPeTokZ_sEdR$lasVN`p2d#U63l2{E93pFBePy=7T zi;1Y&Yoq3-tRz0YupnJINUTh&{$(aOI2iZ~ffZlb(^@V7{KSVj;Bof0_kyOO52+VR z-7D9g3s7C3U}6H(Z$J$JESua`{ML;Za*cH#(4|}0+;|hfM5UasIs&Yh<^hHVfPhW>LA>x@+JLWI zP4GZ zeht#<@Prln#p|FgW2A#;3^x(jA1fqhy(E_IwEFI>pO*TVHD}q)pCHaXty5SrR3%~Q z$ntsuiMh&{o~MlxjqXOZtE*1_UisX3=Ham1$G?y6*C0QLQ@Af4DRUvW-ub8d%=)=T z*gAGB`olAsooSXJ27|9$K3Cqe2Y0e-gv~q5%kCQ9)>kb9f$c;A4<8LP8bE*)nG&ElP%v`GYhi97(lDHhv?|UG6B$YGfzyGq& zj|L?cDNkE9yvZIc&lmjNNCnW2_8*?)zLf8*@^5+}Ux!H2Qa&iJ3(w~8DkWYTHer={ zQ{OBtwnL2T>sq+T@~+`fCsK2$(9lIzs*sMT%H(q?X)$cH7KTT4wcyK6pgqagkqM}& z6HJndIfL_3ev?J(#DzY42XDL|W_g^;0?^u%x*9LjKj%n-wI4~>Y8bzFH|aNeCx#fg zxtrO9gy`OgKOt&o)p7zd_e$*5y($4gzh>m)pUCz|U||Nr@z8*+nCnKI2{n(BW)bP* z?@7^#&!4%Zxgb;YL;pOqxG})aIynPG-aje=Yc~D&+lE`o`9a#?;-!uL%kz%R#SC)% zrpwq4SlEIlf*R+~ZUTs(_0s>%%fo;aXygTX0Jrcn&LpY6~e&6E6*~BOLN9SG4$B8>=kWMTuy`;G_I-;F16h|i15)-`i|bCT9(@O z(%r)&I308iHJZvM@OWgZu;Vi0Dj0H_B5jBMd!U9wn$E*hfPMAoi(y#H0@JyrG$?Pp z!kcq{J=Gyu87V8aJNc-_MgUbaQj_3F8tIHB0n6fHkcz=*Spd53@l( zkt@E%!Gz1GGAtNinUvI4K{6-|37vp>3M}=_ztVLPYrFJv1sJr%fGwu&N-Ay9+p02r z^XGeAatfHWigK`cH&Q)*5#vy-1ioOYiy>FSs44d}hB}4j7sFrbbatxd!V(yVLn|qK zt4!L`ti*^E&Spy2U$=I}*(Ni$D|ruLy6?Nc&eKa_YB&`KNi9mm)R$zQkyvLe1+7T&<@0pQ8J*mr<^9c=c){ zc?@Am8g%tGh`&iRU~&OHJN0~+A2)u#^RP6nsq@|%u*WWB*}0?PtE5_1f2}d}nAxJ! zU8At-!qU5jmtgjT)$_{xVxm{peHZGKzUG#gA9D&Gyhy@TCZ7Zr=p>`tgv@wLNc*_3 z&*@4)1e~22a!9ekGwQd4U9V0;8o~-}aPNaXjy*bSX0UAzOYq0zchsihU$zqLtHC`T z>KYUW@?Sc~lGi`)y5aSiqFV-Suz>eK0RDi4pD3$?tD(VHy;>)XF`H@*~CDQ|(K|r%2?X#!y z*@b56K0ZFQ(ZFRG?<68PatqwAjmD(AbYv1ZR)lQ7YIEzO9I;g5EttKypQ(gJF{`Iq z$8rO_+%)Jt$RJQ3xGt7EB}e#}g=b#ULsp~g7j!;)8h0ng@h`B|J%YN0$?M%z2%Zio zBj3|%3jbLC;gYHTnQBHD2nUP7Amn?+BnJxr2$S4y^sZ?tO=DSqRo;;46vJzA^+ER1 zaX@7Uv@|aNvd^!cxtG}nsl6Yxf_eAFJBC!^-1-U_)Pl z7exHu3D-@$p}3*Xc;*e`w2w?4WvqO_uu!7LTRFM}VEXrtzxJr`;a^R38&7>PZ~)a@ zGjS6v<#%^~cCA|S`6u<1*~Wd(V*}zBnGZ+EP;Jq$V7j~4k0P6zt=PJ&=yFT8$vW(E zf#QAb+gW0}-;1!UgM1cYr)sd%dWocjxGmm;b{&Ku^`^FhSj%*M{sak*feIZFl7vAJ zpW91CHNn8ozrO6sowWpg32Zey>P9 zX>HRYqAy0aD*+vC_V?EhSwJ@to6E3xSOA1ZgLY+pu(EeUM`^9QG^tfe4u#+41wf$b zlBPv9722r`^k(o7!S!y2-md)SdvguN43#`fFvryb`@n3bQ3{Fr~IT+7T6Q_fvDvMb_9V4{# zf$&aLb^St=S0!-)CWYqwqx{;~f_BPZQQ>Ee9Z++D*!~C^YG4Xliid zj}@Evj~?C~KEVat1rP-dqUYvp-l7R&saL)@~7>iVO zO-Xm18jw>ku>UP3EUjq)sR zv#fCEw=PZlR^!Y=SbIq1(1j6#jw|@nr)}3ITeqFX-j>QH%9_ek*R7w&wY-HcA>~>7 zvoGs;@Li{6c#8WekQ_kVmS%gxxZc|@5*m1S7VdY^j}{v*52hFUfso*0xUBG-PYmqh zvnA$|dmnkFckJOJ8~ouo|1#5np2YG_YuShFnzmZ{(q^##D2abz&SL6XpW`z85W#Z+ z)0@4F=zEvtGQb1$nRWZC;Di!enzA zD>neOfQ<#DxCKNi*WZSd+)Pb_gkMGNlz#551rykaG&yk?OusHI%>a~R5G|`e>dBWP zokf!qBYzIK4UUc=NkWuni>H5kyc*O?|J!>2?={RG>`8NgHe8dHOHTv= zSi`2qv03Hkv{_kLD5yIb4K{b$KZ^2kDN#kn4(sAF2Xw^F;qr74S{t93m|m=2!$8;L z@XwHK_Z3rbRZbDm*vKQLBX8_#^j2-{N>-WHiYgR;01{P6%Dnk^=}~wEu!1iqe#DE4 z&lPM2#YYc?u2f`Wq`BTnWp8Z>6tH4su{};0;u4OlId+wEH@RLIp7YN&+#UvK2(X%i zg;3%I-`{(m^M^>eYM+TB45V?X(xTDKvj7efr-T{L(?1y*8Fh6Djbz}SD=TvV1nJdT zpiX3r1wv)z0`-ng@C_Cgw7J)ck#dl;)KlgquDD2Obm6k=16)0de}VRJ(gtjL0mxh= zRNI)Z-QW(SiS}pa5*BCu$OF?`69weA;!e^W_!)i1CdY?&v+vU30=ySXg97EB-vGZ=jU3{8qW@l;_vw7RRM?C8_CPI&uRO0f zkM`C`e$3T&p!$%STO4UF5>4bfygajnIW%0CSDo=UU&qjRuOSs{+k7Vix-$!xxz1#b zv+X%?Uj7jWj%|p#`kZ()(T9VUiID@E66prg*L|v5FQI^+MW^pkeu^kHIL=(B!IgoR z17fj?gmIv~3??*Ho1Q$QP0_#*f7V0^*;uUakId#Ok&jZLzA?RbQo8PK+8*aQQ57nW zFUr!HGlshFKBF}=mpoZB#`t+w>8V9|dnB3XM_}AqSG5|)!=e2P{UF%cdlUwF8klr< zt7{~$qJ|;TS-RaNB0apvy*F-QQ`5aQd;j=D2e=^CtLRTE)kC}@53Af}_Aowu<9GV0 zCfzRaBFm^Xh2HtwL5=MLgDsy$P#$<*wal}pum;_8jxr#G9QGPVH8fdeU@=*R&n;1F zG&(Qr$QcV-sfAu@676_V7jBLC{DL8P>e^_H5mdLhYb4`3&3q2EDN`Q9TvYP1Zn~HABbvgOjplT|Vh3A;zcPbgAKFM1Ui*EH^3%%mrn#Hs2Xg3J?6{n1{5t$l+@nql!o3n$s|LRJ1S80fGE1$gCUyjec*jFCVA1Bm- z=YYlpq@r#{6{`g+F6|S5&0zd!JZ3`3U@i6g&q(&s42~ylz}{FewRuvg`BaD!O_Cg^ z++%_@gi2mA?xz!Yi?hCqlN{AnTmMCFD6}>%k@pQ?5b^rBk46(y|HFVl3kh}~pq6Bl z{{kGy)1S&2@7G@g>F32}t7KTXD*XiTa{P~GKaKBL^2WDtA6F=u_B8y>rXq1y`s`Zp zt2d)lpp}Cxfmc69x>SI8E*H?Ye+X#*(QE79mQGFkEpuk|cbOp|F9*b9pp$pAx@^4q zBlZYVl3CGR$4Q%O-r^Rtu`8ViP5|uuKvLKa8}KIyFF6)Ea`glSF+T>^H%&OjBJ)%+ z62#j@_pO6o7;K22v20O55ssnH1bk{VH?}c+J^6-=aG(zTlA4;huPm?d2Az#M|MpJ< zUPfdOIo+qrK|xN~)OSbj0(+I1J|m+-5c$*m6j*tJrf!WC@XJD;7AdH=znj+wtKE6U zP0pd+So&XIxd5sKrbUfPOS#B`va(2gN@SB-IX0!-*rLlM@Y2Dvz8nly%A9&UL6>E@ zU)7 ziO=VAy~t`aZUYQF5xX6g$2eNS**V1d^a{}J9KS6@#(PDza}NLPf3J6bK?=2#e)WQs zJ#FT0N|-0w%7%<&y4{wXoT@F5qV?=+r^;>C;U8LR7rMw3yDZk9suL|ud`CMyy`Q{V zxQllPCoMepC>(c~+}@`GpeqP>j`X|mjk!tP*T&PuIY%{X7%%4#_b^!UocL2YbLG-@ zC%U9*%^9nrt$I+X*khl$W86^W%n$c20v~|so4?!4Be^pxN4l8AXB$udu=r$O^MpN& zWMInv24@koQRVXDbaP=PJhN(&j3A+OIn(k|sSkLX|gRLO7*+WNCqDz06l&9<<{ zK6-dBb7Nc}!;g!9zoPEC9$;BL5woa;D(aH6BEO7Ot&8Bh#nS5254*QmXuK{wTvX1> zCSHCRfHiJ{YVip&F==Cg^R7;ULw)A~c?2hbiXm1Z@qF?cdWUd;FmUt3*ya~hkCurZ z?y$AH;o&n&g)+(H;;-Stx+i1jpE6W86c~CG!_~W}Mq0L<%}|%z5j(}$m7n+Ly7#(8 zTjxpj*n7s`SNQI7teGT5Y}FEd0RAzZVdu!#j6Rtn@`T2Tb#8OsYQJMp9mGF1v(&0! zP6B&lB78wBBNOILi;Y{<>Slw}ZA{pFk^tjZRfGp@#+E za&v1t4|;~O#X>Ug8gofq;tGj5^+KeJXARlv2YGX6lOn|U{Fk}G#dN7gt=;EEy3A?{t!o)DncK0Lm4FqVa!_8UFChA1qf9si#}j)@5{i63Jv z04b*+uHNn0$<+rK7EZ~?#~P4C2S6P|XMq2J{Vu2=!*R0A(c%cQVkfF%LXWNE^-t=N zPr-dkxU5L~`D2egfJX2nL2ey@jWmGoPAQJDY~MesH0`ey>v$d{UDDG6)Q_ngcYlJt zria$b(rX=qlp_q871&fQpD8s5q(&)b!OZNnBSd0kFl^W(BY?ZR8t#e~Tc$aM|5C&k zJE6+SwL!2?0%1O{@Syg)M5-|_x_z;E4z1r^U0uMs{c#{7T2day<6?WCKrb#*HNS}o zWiqXdrOcX|UT-leRwy@%=H-T8Z%Z8Pr^M6pL`uhvEU-)-w>OJ!3YYqrP6yX%UBRbQ zez!`IF_GU7Oz}ZS@>eoBF+0%=h>|?TKZ+fLL7ED^D1Q4hfpzM$4}N^JqFv^rhoC$I zXG0^Efh%B*(xs2@NDQ2;t8rCXK2efcco0i`m!fm1jL+9xf2w5hIT3w3VzH@&4Z1jO z)@Hyzn6)S=%k&|BC2;e`bx$S`!67WF>iUlhO`cen<$va4w(}6Qh12wTk z?hX{;A&2EQaL0=Rgk&U7Vt^T5FU=QCD~y`IN0#0vSI zeOxQ9Co{y##{0D38f{HIBbvje^8?d+h@H1eieTq1ndo%4ceqaA(_7h$%KaMQp}UW0 z|H6Fun0vh(4JibEH3+z4net9$`=EC%C*f*QRpIv_Pv< zi2iz_CiBvGJ#(z#UGby@IBnj^vfTfKgnKp-Jqkt#q)`b@<*I9mr&yirKJdzv9%Cu+dciT znU~hKUP^H$H7(;TGVg!9XdK1NeJ$!;9jUmvI=kpY+8=-P;9L%;dcI_SOx$;CSU%e| zw^XXNH$^uODa9Sl(ILSbgg53>y?#0_*aY!kE|9R@yx6*vYa{=Vs`q%>;nPk)x6UT` zFOV^XfaAx}+r^t78=9(rEmAxmYC$iI}wBm}{M(&DeiCyuRVNt{oc+9JY?{;cRs6v0hBWiFD_dNja6t`1`4T zCqdyiWrgwt+&T#tA{%agCmma_cb!HDkfjH~BuK=m@^VGzHo5L}PKz7Ltk69jV;(8& zoao;ViZi!xF_OJYn;b{tVMGW*^0GMjxuJ-3B>riit@!mb_y29BUJ8F^&hNGdu~y93 zZ$kd26F$@5(6L_t{+%ESB562`NwJi#S3<5MKYB)8%_>^~7VF=G1WYUy|27Gxz5}$% z$;m1!P!47*X%3#@^y`-Z1{zQy24AWE5jTG1i;fRiB%2}vD1)(lFZE+}rtKP@Rg_W~o)a8YcufBY<$ zFJD~F$tz}|YA>L1WPjbEZwH8}vebZ}wK4{}qmq&mz)AxLm4?D-PrjIen|w5<+;rG4 zkKFXAF=dAp8uX@>4gkxL-_M!Qip%D_`uqa8jwG4|ONRrWkoZgr9Q5Q^E_^_17mY-) zMet7w>u&Tv0ftL3nXfRmBxxASHw&CyN$00Uh}NW`a6I{;kEZdR1fHC}uQQY*IL%oF zmkE(H1nwHugUGs6o|1m|Jt(os&A@`Aws{zHZI8@V2&{_@p#*qsp0+J9U`ZO-73C)x z$7LzaPX>STikORi5RI_bp}VyR#9GRibX8sp^|EHaWedO9!~S+X@riN)#Ulw>*3OfU z=sXIqt&x`|X(BL#j@5I!#f2*|>j|6&$(QE?iMRbMV)(*-a4A}VX|kH7neZKp78|mA zja99ODDR1nVc5iR6rjoacdVJLDeeA`}hb@71g`HA!RG# z9Go+l(%AQtb5JwB^`Y0Y&3E6WNn^zJzPTl4j_Nr~>l~wP_n!VFg3nfWKD^u|P8Grj zDf3JGaK$B&(Dzs!+6H|D`=TRm#S93Zt;{sld{|I5x>%bd=g(zq;-CZonhW*>^% zDx=m1+A?V!-)fN$wogpnzq`xN zxx8**!{%)ogSSio5`u^GUc91*OkOcy`lC#ik>O(G`4CLUJ7QtZr6C=KHQpqDq*%tT zx?Ewc=vMeYEiIH+XT8Vf%Rgc#i@lZH+b?EGW6Wf0KgUNx^Dmm9S%R^RP*!Fg4 zqldfwes~lPw;bi;U(GKZR4Ypir7^CWHVjtzrE{Njenm0xEM#i#`w}wQr5t`fqx%$t zwE4|XfsJ>ff*-}7i4rEIj?6`}z+6NYCmUV44N9*^ANgTc`!H=NBt^e;nNajv?SW6) z4zNvf8l!keBndPsr^f*<8{pn~ub+ofi|BA>gR zwcleQG2#@Y$aiUKymS=nnyRXQ0$Kf%V4d>!U}~$knq`MhPEH)T{$$5QEPz@Lit@G! zZM0|{2ngA7dJ_QFNM>ecc8u7-r5`B5EpbwbxL)&q0Zka#suMW~yl2L59BlWG&^DJl z5nKi880ScHYi_<1TJZv)2@AxILM=o7BDWoc{>5yv*}pwp`nosQ4Av3@Lf8P2A1(!w zSX&oLl)!5MCaPc@1rd?R)%3sayVu4NHOagmn*o~%IUX?zrc})9+uIL!@ig~F=&aYa zos{W4QKNvw58!+JAD_3UgM+uK1r3gXUu%S2R+ov6E2UVK2feSkDJk;e%1>5yc4=wp zQpTtBcOSDg;BlG~nr#8~c$z#8Soac4PiOjUd1VKrQtZATfj$|Ca9p_tN@-l-`xx+0 ze9~F{Woyg>0(h(-=O9g5rZ+Hf*FXVYaKOH&o{cjad{Pv1(1pX{;I{(w5H;3;*rzX+ zmw;v+(4#?$>|v0{j4uxd@-Tsx<1?NWO|Pl93+|ez`x`6TD87+YGWHb3E^{ZgSmvHv zi;ahP{1M3~b8y}coO=x68h&1jqI!XLB;m>#?t)(Hw|Z>`0yP{3rx}A9pRTxBTXeK7 zl5eU}WO*A>EzY-To#Qu!q;E@yx+#C$sFe3}n&ka*jcth}NGKvQm!}HRf9vtf-Xng< z)aN``g4Ne>8-1>DJdiu?d1+fKucb$@bY=h^dmNtXSI;bz!=}dVJ5P!R#wXBR{wb!O zZR98x`3lyKPbWVQyUtK3C(jp$gRPUktrNN}5>KXA=zM7h`$A`Lovw}KcelUQ_cEm~ zhoM1ZDo%d`JY%HxpP7D*V)qpOvp)atL~G6aV$a2(GHMbaz`(8|R`=)w zs-oWm`dnm?tU6>P-F}mPH=BFW7k!#6R8M-`^ygG2pamX{dKjs9xG+^uag2W77#&2H z(ZK$Mui(@x7_tp4ccEHgHq(hF`ehNtr+gMV{sCfQ$|}lE->LPn#3PaAMre!*LJG%P z3Mskj>uw@rzwi>_+?W?fa@Cmd^_xo6Rv28Qy|X3DUNf@p#Nvyq)lPGa5Aq4|gaW7N z*9#fwyvUwWK+RobDL&jNcSW>!Dnvi~e;7nk3WA^1lz-YI!XR5{z%vB6lz z6n{92S6?V(_0`B*SdYdFo_f3Y@Yr94)=T0Av?=TU{+WV>xu=!oU?dm|Mzx6&>V@w+ zO0MQmL;9-RC2JuUJH*+RkS7U0#*g5wGwQ5J3-) zPxC~*l!n+>B(Q=O7nTfhNlwz{(ZHA8bIplZm8kL9F(&sAxvkm{(q+MwMwtRzETT{k zvGfk*GalR;PS9~v4zIpGMQfDMI+i<#>++f&uMMrA>%?e ztNoDY+=~R>(MGt~J;883tM8RV-L^;+u|)eF(a$|5+B?64jG!CMCr1xLTTDs~5*cS1 zUa*Tl?}vgheR zkb+XI*Fv6uyyQXfy=1QNH=``c7Qo%!D_!?1dTa3GE@FV@~)wa z{!El~j?jLG`jPcANimCY9BM^FJd+P`cWlImzi?T&AJ0;4McOXROZM1v$#}0(g3sS> zw>g}8cXRPzQnhkJz2A6ONttDnL0*}aW%6);=Q3yajpc4BM^ST>xf+g;CpHz(Jci4%wD%g+L z)YO1Lc?v}?^z4=Nj{*Y&c|Fc$Yb0^?zFQ#xc=%T`&pfxs z*y18kN7Q)ToP%&&fE(x=Ra${<+}}yC0904xSR2)qZC7vF$0(26%mf9Y-qqX47xCHgvqXXP?(Xi1(;QAK zucknH#)K$_y}p{cM^9!>@Wuqn_|XRtEipbeHa0$vvNTmIM+Tg~cY7lXdD9!#W&P4L2w>#D1#Kr~zE zBU0%UK9FJ|W#W*#;l}jFzhmy((ywFbR3!|PU#(VzUa}Ot@87p*hFkU=AKUBv!^2&3 z6jwSw0(TT5VFw)RXL7PbY(pM?-YbC5*&S5Lf(v(d7XG-8jvk8qEJ5K=f z5kn@M%RM#GUPHJ{o7#5?DaXpG<~gTVtv+Dp-h1MPzf<^|0j? zrjxLyjU&YbW_KAIW7cpePC2pc~FRrIP!~`{r zCNu5XfG=9}tvT`GV&5U8X1TRDpZM5$X!6A*8m4r;en_RZsgL1$ zd6v=`ff)4))p9Vu=ts!g z?$E5;Py5FNh_li6wl6dbPF>HZ8d+uvjZFCTm>Ls<;^JNWN6~T@7L$=muT1Z_RA{_h z_C*(r*Mu_;iVE{HZY*}%_B({=4MS{H2%FD>t7(o^+-eSoT3Ac9SnDd43T?i*b071t1llN>LDBD)Xzw&DZ)Y-44mn2myNlU;IY7VL-I8rq)&&g5zBm)Cf^|Fky61CVuibTqDtT*S4 z=Zx^Y+xL<`r(84EyVO~)M-ivAq-u-sE-Hd-W^-2SYGdbwPpC+1P8_#2$rFANU zmF42IJcBZs8KrZf&r8=+bJz1zEY;-fNu%CxpD?Oi-{;4$1asaA6|A3+$C@XkI7uJL zXQ1KQiFmmjKfLrR+eq@TUdX~ZntcLew!zzB-ifZ-E~&V-;lAyje#^+DufKy!Uf41L z{q^vgOSm~l*)$rmu{Os%^vF0|*-NOvhiH$$g%$IwW3cb8|s-#LdhYr!8_n|hx6zS8;S%=W)< zB|@A4p{s2pwO2&jk4jq@R;h|5h_hz+!xIxi=-5t@W{Ub@lNg7x5NMI5Ajz%ZoU9Hi z1jCEJ;e*Eoh!BXl?F%|@{)p`agNQQ3eN(K!_ux#aqN-|Oxi;9X8p~s9wFW?wI;U4=%Uk?;ltB5F#3CFh|^49*A9CHMVenL_LGKQx) zX3dS?54(g@7{q8N2=VY#rEOp{Y*>guEx37j#^>ji{)l*Q!uE(Tm(Er@X>80RDe|M*PpW1TQ_r;tqjRo?x zK7d0d)y;_=DvfB(tyLiVoQ2bdfYN6az`9ZUFP}b_t59S!;f2JYP}2Ibfu>^q3<0oPez7bj4p+Tx|8ZvuKc<1r~H=ZB(ajK?PYYR3JJnPKLHO) zWx4dh;gw#u~!req@Ua4r*0Ejf87i3iNH94N*;x{%(#T}O4W-ctn+ubYkY zcWt)ynVp&j5=FoA0N`k7v4QU{-N#6%xiqFl9NPy9N#i_tf{augID2F|HPKY@f4}3F zg7(faRk=fT35zzwC3J!o|sWqPE74wz3?6qRB4`2`rMK>*ydCkTEeoSumHw zFJ@LVwq_H%H#0La4GcBpAx#{okfzp6+7ME07LH6xbl|os`!0-+!s-=)J!;DbleNd0 zxSR*&Wo9#H8@FR~t)tBpcW1FrSs=NK3WT@igF+=_8jw2C<;p8H`bk0)49|*J$pp(o)S~fijgCsw(?P1&<2; zV@3zM0f!?#?AvM`)f9^G^SbaQM2X!Gd=@5*!Tj93Kv&y zPs`L&UQ>)%*H`bJ;J%I@S7&_S`G^KM&|m}mp+kKUN0G7ul)`q%`vJo2L0ov*;FvK` zgjRU8SckS_kmwO{!b6_9KY7~(MrfqhpNhm~O>32<`Pzf& zF%um8QM%hUB)NBOdaRp}kpp<^g?{odz(@ELGPq$kcxHCyv5q>!dEf_~_B(|U-Q?l4 z?44-CMFM_b6u2xAlLJS_WytHOLDsz+=O5R$GR94_0;)`$VTD_o9!`ZBYEh+zFJ77) zAXiS9TijPOd688s7+%YTHM>4WSrMV}P=*l?M|5ApoEKY-8C%UN z21g2jKM_*^+LJPcUB5rqd85$IQs@o=PZw8rcM%a-Vt2$fa>JTlo*~+$-P-Ieog4<+ zQ?!EQCz9z-@7{HQ>PW~eDALhdgmI_iL{f>(O-{a-T?Q2->M;J_pwJ|e!UybuAtNUT zv1)L*-R{I`;})L->*$ouFE5|dfahQ?D7Tc~Ev{bg1?7`D9lc|2W@gr~Z}>z^^gG~g%By~H7eh#+NUaor-cTwGl6=+*1@@A_T!v<-YmnTe8*=h+9u1q&pF%U{g+rq*EO!-gb!eIf#xwr)d<=VlSe`E98 z?*qfn+c>M@XfyOzXy{vGH>r(7%){4sj?$Uehxb@syE9~xwn!0o*umG~-i<}ggyBbG zCxywq4$1T~NYIBv5nl|+k)I=;*AzgLD0W=g8hYR~?U%OSp;+RJPk?Guyd#v9?5t0z zUGV_^(q}{D%|AI94vp|mkI3*-6d73`;KYyqudN3Sunh2~OB$*r4q2(ZtXx3JPlo_K z4?2;Yv|bbbuh03H$AJKy?#+Z=s}^ymTK~xVXRIu~%$M3o9g82N;6JOM-x6p;Hdc`^ zIOB+OQx$4{38;nNXGRRY3v+nc-J*Ne4M5VEUkAJkBmH&EgAL#toL#q0H&G&Sqxpb!=sltUP}b;Isuyses-{1 z_=BeQ{sVGz=Z4va3S7X)Sq^;Yx&xwrWEmN&)GFR}70*ysKpftj{_{|d`i=yjrsASH z{(P;CV|k5&x74Uc?0-q?sRA!$+^u{#ZjqBXPg{FDK{c8 z+CRqMd%i#lLx8%nO^65ADFo4l-o|dY)A!aUy`x6bq||#j#oF7K#$AuW!Kr4c`2(?zuls}6B|~C zlO!Qy5N=#D_8_FM(m3+P z{B|s(%D!|V`W{NQqZNO+}!`o$=s?aJeu^K#|%Kqhcv~E~vL0O=ca{_BUcUE5qEhhtDU8zuBnnL9B6&86m z0LxY02@J!@H`#17e2umTN){$2#@{8w=Cq`_-|VpN2=$3Drz=J;uDJohr7F={$h7~`y=bHSw%0mV*<;*cn`RYBv7%a>@9$WEdm0v9boSwFE{sx zS41F3DYz3J9)3RN7Mkpy-{^VsRgvxpI1G+nae_Kc_j6xSd(FDuo6)<^9RKs9_MLU* z|HkHToFBX6%FcdGe2H52_WJBgGX(ks6SAxgcYk09f})<(vPS68B@+X7A8zAKk3Ya2 zQMtnVVGTSriSpiG3|Z9LQ36nmBRu-0Lmp0_sY78d6DAej9COFfl6=q`+ah!q*QsYG znOrVoea;Uhq(^+7S*=c7=CiwRa01l4wbt>p(bWMWn^?1@f^)I3>pW@D>6$l9efpfx~d3onp5}0aYeSB>E|mRhi*^|C+0+c?K>(w z)P~>l+6K`Ne$GQel<_W-b3JtbR$%$y{A{|snl|UfPJnA5!O0(`)x37`AWU>~C!lRL z?*54bTO0y>)&SAts%X5d5Bk6pxIo{ZD~S#uz#)>2+##fN1|e5Ow`98a3n7QLWS!s! z%Ff~>#5K=?t*HV!Oo8Q(V3tq?H1_fj7wHf#)k1z-%Cwfe!NAUr!dz0QHng#SM|TMI zSQ{F}uu8vYRLyGtm%6k<;HDWo-~Ax~Nwaeoxl7xl%NC=o1)w`=|HpgDX{w+JVYF}nlI4aChv3+QofyG`X?2ja};4EhbXb-y% zrRL{wYI-q%8^N+~LzUk*pMqWA9STWXREJi?@V|l1vxw6+Px7iJtwx%Nu;br5T^>C4 z7$wDWWDof{lO1$W@28d`@JVZ0%vAmch7xxD`gPf%d*|X9u%AU7#NKJM#0Y#`vIJ}n z=oJ#5SA@JS{zudRj`tMdLkL7{e7y}f_VS?Df@rdc?)Up0zN-aw-@YooBU!U?&I5g5 zS5~Bo;F>>xrpf8|qa77bg~bj%|oU%lRGm z(2h2&>wmB3%AU;(Hw$2z*G>|Tm1M39696`%W+W#&_HBa`H1yLbn2rB}`AJTv!J!kd z?xHfZi#7)Xl!bb!3#j0QDalu_*wEXQekj$}*-V#?=c)4GP-<+A88)`I`a_`wWo0A! ziaH_9-dA7&^v?j)EPAfD2Ox~`sUBn@2h-&k*|~YcSmilvUu_RywS1U`N-up;On*4H!~{drRPaAAM6hs?feM@7%99tfHf%W4zjL1OY(W z(dEkWHE0bC8esn(gaFlWpr*tn=GD}T_GeG)3doqI@&<&A-flC!wGfq%0C9CN_kZ(P zU{*MOf@6)5IU2>&iiHP^ygtC#!bq>37Ia$26xs(L_GRsvUhW-+JjWG!?FG)AC1y5Z~aEiQaS5-cc$O|wmlRUq!oo<4Sx;9Lo1h0 zQ%12#T#t2rt2SJa^ZQvM9kUVU*yt#TmUN!vT{nYlFo>wo9d2xVsx^2gLCsM$JF7Pr z2wQ4NXL_wfF&Fo(s&YlSKb=vD~7Z?#bSA^M2F^!m{T^;D?%RuAW6%VVVh<*9YY z-ai+m-1jc2QGbEu4!$EW61Ol)vpGr>1g%>#9#AP-pM2OZY9`}+vU?Wqdx9$#W4iZS zpzKxk3tsV{ZB~g#M*5K|LCA$yMAX;KF<=ziB};g3(ozgK`SBvA25tbhbbW1x%l_q=XZ`MwX18*^~SI@BHrx7?S-(CT2>MvUL&&r~PwB+pj{02^< zFQcU?iamQzt2RCb<1w#BOWzkG0r8Af5K$FNnZ!lyko2Zo%s+3y>ouWF6^Bl{k_wik zi5s8YOnI{Xe=R@@+0Dp+TGt96oou4_&qabevok5^KfgeeQ}<6j1znHHGj%ThB--pr= zXOc;w5U4#?;8%o6ufCrnOxQ__3pW_zn%gNLRsrFv46YZI-Kk(NFc((|`r{mz!Imex zmzt8Oxs=-MSAn!`)2Wh3H5-o!tx*srMaP4bNSea{_Kd2ApHn#B_`IL%yz(vFO-CcM zS&UcsE1lNAXdO0W=zAk#{!Z+OG+>ZEm0`~^OJ}E|_h_V0_xsRGpzZQjY8XVR!TTw4 z=<{Jo!3^TPUnBBn{i)&xqI_r2uW>hQ?)%|2Ilx+=a|Tezqmht`cnIrYUR-oZW6Rw+ zeq^aN{3lF6xp$xn>%>YV9BbNKj-2_yXvSLP$V=dDUWG{!b#Kq~i{>C+0rmP4{ga=t zdsF_oK)@d47T#9RFfHK3K=3=vqiGXT$IlO_0N$1HGO&lpnfc7nL>;6~iO!Lt`5EM+ z5J8xzNvC4luXswM*+%^X4E&&wLyZP8f-PBbfDrF`Oi#$wX5AcT*fQz*2es`0_0#q| zv8?l+FNz(2^&iS9mhrNwZ~{Tn18JEFP%rE*(4dTp4_fz+p&hgl<) zMz)=7oJ}|)_vh?>Xqc)Yn`)GW!p+JIEXZu>`zL@}U7ta!Sg6NHu-HX|t{Z5-vVq7+JsG^UZy?LnUGXRXJQX`N;!`+thb4a0%4H6dL z@?A%*#2i;*I)G`)hiRW9ug7|^1!ROShYeqd^zZcXF}t%h|HL#{8m8P(=D*lob>=&A zp3T_%*Nb&C$=95qBL*$2KXrv}-16SXGe2xF`z-A$eojr0h+!{L^|KkzupS56y-|S; zw(+^z=DD%>w;J{!V|j(P%a23T#1GKGBbMxcP2beA;Vjpi9-rT;=4^#P0#5gaaiQmK znevo6WcSW{=iIj+Bdh+Es^EriQ~O@%gV1_o0A627(;arY5~f1=q&Ov2Dcfs%ELm9d z>Ft+)qg(&}Lt*{{VhVb>wFPCaaD>;pv=c3vlQKmyl53k8jclumCV<0aS1_{oIB2 z)Kf&Gae-cMq4Ew>>5s+vB_#)g$vogWn*#@>Z@eYO#>R&`J1@z}%|$>}uh@u)<7(&0 zT2I($}+ z#2FM4?(gpxXyhfy;lGs5?My;3(3k%ytAV|D%@Pv*ImQTGQqeJHbc3CR(N-zc*C<1b z7A>0h_1paA;k;2WoDD2Oqha`Tmn;|i@<|x|j{C~z0zw<-+|S{ESbn2tvfy~eD+ce( z%hg@A;Q&tepjhzs7k-=u$$lGmwgh7Xdyo;+h^v$n6JmdRJF7F5)uWV-Y?vzw&Xb>A z!ax1I;!Wd7OF3GKQMu1^Yi-#Bo?48}tt~LE91N2&FfiCLXs=&8U508Fh~VL zX*=&i`&KFb>V2)Q0dsGj{kU~Z@h&eQnghj*f`!9fZR8FX7HDnf=e)6@$Zx@GM-zui zoPA$j6JddJ6eal-fo#hvXwI4pj74$0Kig)|DYnv@d1VWy*LdqKzx}J)9RE7{+xe^M zM5DYKOBjmP^b0f8Yq`UadEc;5DQZa%hENQprVcsNSST1CApAw-gleBY@Jk%4sctvIXr<#!;0H*pJheYXoKIp}U9sR|jfz z!FzfKfyhV2^?$mT&yLaI5Ycz~a(9d11R7nO77-)uOMhCnDEZUdkMSV-GNV@_0~2tc ze0Mg`zq1j4E?8chCOlL&_&{v5(a<;*bj6dZ9>3MSdD&}{;AXMreAuUO{ZVX=RIzg} zPCPo)U@xjw8VY3M28LKK>cf2Fk%VEo7sq$}@K)@!uzLYkoaGKJd&DNC#x3cniHiKB z327<>8ikUU8Xlja&>7u}F0F%*uJ*FNGJ zvnB;})xBOOJpl|!Q*oh3eJUbJ&7Y%dMEI4FxWRukVZ`u*aOG#m9&YXGLPmwfs-@oj zJ90y)AK7-&5JZ0uwQkicD^@SxhnDo1SN%+Pqd84AdxtAn=0YV#jgHlphJ0;`&sx&H zJa$2R85s6CfmrgxTzVTc%K&OI%*qIVhOCiO|O-1BXS)}tf%HI^XRmE|jn1|H~ z?A2AdCF2Bc&dfi*X^h|W>pO_Xqd5|*_#R-NNDT0VZ(hljE~8>yWD1>(kk^j{A7MWV zkrNVd-h6<(`aCHVtONZ<<0H+$BkG^EYg^_CD2aaDxWy&ar+hA7L|vk3yUL^OL`#D? zGPRgc&A?el{PaFQYcfqcoNkA(FB3 zA$N7vZvl{p&E1%=ekqA>cfF*mPgUV$nX~H)ck<%(5e^W7+X}tdEBWjHEO2E80X#!e zsW zxT401YE|0#BRy{{vH9=a&bzQ{$%j8pvE4#42UQtOpEW}EOx^(3lQw6%ck6n*ne?q< z!W2S(n;clxbarP_wz*rKKC#yR-F}v;MIdgzF}KxFhPL-Gt?k{K=x*Q7?3$xdbK8K9 zFD{}+jqD4g^XdtXFZ@ruu$3|YGgvmW5ct3Mh8f$V^Y6YL#`GIb)0aEei;%XbuffpZ zl4=AW@ZYxJSZZG8?CcCi0N{xp1Ig*Xize)a15wQ0BvOKMZbujl2C{^_Nt-8T6*Hg+ z#Hif4J1H|WGbzb|7^BmFut%rd5xejZ&noGaHWNBOmwSnA2db1L|ft= zaC`N0Yh-9h=nMY_5-lBsY6i#U0`{7e<AoI zIQdU?s00vUeFH;>Km_VT;9yHRjzwoqH^r;f_fi&ll<1O-B4uXOEM-jp(lawT;}u{+ zHhHA=weB0!kj8i9FL60TzKsvTyJ{R!1GGl@zM&BZjFXJ(rjhwH*l&r6}{a68AJrHUqYNcjptDq=s5gLzri#~?w!AK4V@*sI4u$^6%4?4M;_UG9n-;BV#jEh|Pg1dA*9LX`H;$qC|8R$pd!Lf;6|& zcc^~M6}sLd=g;hu5c-K8zJOyZRKP^@_PuEq$3#`)iog9;yZ-T0xP5W1z+_VtYx9-z zXOZuHildhy#1c4&Ea7!u!<|g{#N0ISYwb}?fjRNntmWE*Obc?=Sxq9_5$(h{R_WR7 z$AND|0`I7*a@tJ)#@?MQ$8QVX{#MOxIMfIHJKhSxjms^FQeHo2Eb z-1Z*WaZZc(Ne6cpa*(z}Z~N1GWj4-g`;HD!LIL3wmvxh>jAAD)8|35#)%?K*qO3B~ z%Pv#D&+qB72c3Qn<*?)TKPdvbX8HT-Y6(8szpIR#*M?>f=n0XyQCtcQTuoE zBdIBmLpqLd}PM$6{YJh0h)z zVr22Urm}EBfTVC`#dUwv-{QcadZhq1pkz^Jtq%oMTs(ydLht?HB=NcVp8T<5kv+LQ zr_cDx)Xq-lE@LZ_qc5AdwhM9q8SBN%!rI1|VaxWBhc@W)01|xzp*5!wovC9W0MZLm z>zvY$Qm|sg2yh!`d=V$f2Ec9kQE(LK38dz_q!Ez7Xpm{CeF)ngSy*d~&rt3JH=a-& zr`+`-^eyhII!VTZL^oXUj$e@EDKGhtZK#q&{TR?P1CXMS1-L;&0*XL=7LHY&p-L+2 zj#BCOG6+vt9lj)824!lV{6N$baqcreI3&My3TPKV8w(j(6nqwKzZysf?fKsG2cB#q zeE<2AG1GcfT5%}NeT{}e>I>x1^thiU%18J_KT7Od!6VtfN``}O+{4|EFnq-BX(5ks z1oI#YoMygYlK^lj^O*5-J!V(B-| zMD>0>)q@NWL7~AUN2DkX3>lX^Y5NGXgr}ggDZxcOE^H=2$*)B*(e%P3Md!dp z1>Sndw*>kW|9S8%-i(hk?#KStJ)fWs>lSd6Nr_T+F8#S?S}wa2%x=3wN$y_>d6f|e z^QlkcpAcQYe1kE-GG!=evLq#r>cWl+XM`#uGl0!?p#_w!c7EQpPv(pOtJ6hB(Y)Pq|8&~!fXj46TX#J3cAE0GPwlVDd!LkCi(3%Z z134Zr9us6L1}Xbzvt0%CM5|(iXI&Q`g3BAhurUP(to(&aQ~nP%v!7~QhL`QA!^4LP z%7swagN`=i=U^FUo&U1&E|z!$j_H?~s2fSVDtlR!$MWDXNnYs5 zD+h6?2Vr|W5Vp5+#%rzZ%Kb1G#+4-BnOuB#;}aYe3<)>{83b=(Y!#-}qI!2~tiUfb zL~tXN+~<&wKduEy0^6c{TP1h;qz9S4Zomd~ch%SNPy%QB&gyrzwY=(DY;a7EZ!V(1I$(@s%0MUs1*bM~aRq=Bth47g)73trEQd6P^s25{Z z6|`HwYJ3e~-;sw;WWG2qiv#h9=FQhzZY*`wTxe++h;F8`%!403Ki{GP9NM=G=6)R-F>F(4>VSgvS1`rh+ z>@YzS18!!(m5?7=mOvcPw{sh%-CTNcX-;fyY|q%Nze6ucaQvJb%uaI0fQQKuLY7I) zP?uMv0XZt8lKhR9>CArU$1Y!S%+|^pVF@qx*JU18)|2Ex9oif=)ucfYOc^y!1d{lN z0w?UF>@n{FCJz1CxUj>Jt-LG=R+>*EF}%`lUQEG|Ecy`5dowm` zeEp$Sn};dm>^Cu+jsslBrrK$&AC72RmVM1+EM&L(TU+JH%D8rQf4?VTl>ThcBzLSf z)s=N3>UPxqpP97ism^W_M`h2!{yrKXFMM&|$xn39v){h@VwS6fo*qLpN7w@G;GOhS zyQqL>zYF~(B}w6;*^u*E?qpahH}JH#0%1lD5-F910%~WLyYL}Gg)?m<&09pn5t@GB z&rxz*gDrE8Qv-f{*^x$X2@-RysF@UjoeHkcnq+Ns8-G<}7CCf~I|^P{Sv|KOg(!=2 z?pRp>s}D}X*tY_&*QM7{U&W1g@0YIp!$jS1$%<)MDE8(@FSz&5eyW>5+-5jr18RZe zRR~XRdhH8yfJo+5jp(RBHh*_mZdFtr2KcLZuMovx7OQ`nEuIw{B7I(}+%?>4B9K%) zZv5#^C^@YYmFXyT1#P;5tFkZn_uK0OAYgZ5#Usl&2NGn0J#q9ISP?-1PM!98t9^o> zIMgD6QmjDoft`)n!a81WM~$II_F7GC)4k(lNWk&z%M3qPqt^a1Ih#z~2MMG5H-x^s zu%{gUzr7lAN1g`E445JEcYA1#N!^!;%cHDB(6kD8M6~6W#Zdx?v*bU2oGra60 zo=?3#D^$-UH#5Er?td+T(}HrSO0D(Y^Y1Hfkv^aiz-s78o9&Caf@id#NllO7Zi9Do zm?!8xVB_xj211bZhFMD0K z50kOC^oPGah+Y4Z>u4;D5F!3YG~-mX78On0%NZ5`CY?Ik3- zNJmj8f4?K_Y#d|;>Djp?jODN70fQdWH~KeZv2AOT!@in+6HI5nDqojS$dBP(hx*dD znhH3+5z3>Q{5N%r`)u~pt5xk-GRYagON^MRJGCun98F%yycJ{u*CXB*`i9Zk?L9P- zu~(Zs{d~&06d zwK=9$H9C&C1VInPW_EBosMr)~+FUtTe5I?>sY!>P)7d!dt`(m=~<2;VWjE%GeW??r3J(Wk^|7t^lE;(yjwRIN6>-`@Xiznu{H%7y2js3dwQn{H!3 z9%LnQD0@(kRLR>=DXSS~oc-pSFslCoy!m3}x=Td8nnzD^tE_jvzTqg`7mAVqyZ|lZ81GR^rn3ic@exLVkxGILYFW|cdy~QZkq;itI z_US9kvh6i=BjF8#Xfrkst||#F&>wg_{L!e;!`U%vHA8KKDL6ed9ZguE0d8%K{fFLx zHl#w3B$8eqhg+DyaAo~+&KI8W{ zy#Ttsp4EMw9*ehtoQ$@(TTF*l>#a;{>e}!$8gMu)o^Ds@De!4wkXhm8VP0AUMj1aY zC?fPoPM>M2mvSor(mE%AY#x;OCv_@FF+^s z;g|Z7neYF-uD^scZPhCou|B0q$M5}?jvXui_cI%IR$g96!yKsDXX0|nz+3lasOkOe z+M=B(6U8UovHCwL)!5RKDu%U_jHL;fvBaeJdyU_h6+C~_Wx3={z=WmOZ)WJ#U0DmB zeQWRS4JC{Lw;a%3aLSs9>fq(o0Nzia;~0#*3ySn{0ClBI44SqgwfIimQVCiyTb!Jn zcsMwo83J$KNENC)Ic#s20(-|E1U?&J2Ye&}ipsYq^>HW80x|3KX6-_(jP94<*Kc%t+D}CYP@wc zevD&wwzi*krD_vS#c79wzuj?Acs>q%+tq&aWMY^rs3>xD7LMwQlLgo*nuHU7>QGzJ$=H9uCLZ#ZL0N++u`l)tMyuHQ zonrry(~R`F?@8lvS0d9Gxt{50>S{q;YjhFcl%VXt$?9AW0O+TCPfvA2YKM)Ay%OG9 zVo$0Nr8v)ifdg(Hu?lO!@dFY?=Uap)m%Tb9&?X!Y>WQ-5U4iB~0kJ2qm!KV)c&lHd z8()K=m4di&844jZ1_v5J(^50JfQ~oUR6y`gkOrn?ZudTH88xWZ_V&d8H^Km$; zdC;hpA!WsBf0-Dx4w;NR@ z^M9pz-^;Xx{d23XJ!FK2{^hi?U;`e>WN}lOE|`uA4k3Xe@MZ>n)+<7neB|Ns|JMR= z5d4n*_gle4U8RwA$AgY4^uD05R#rc8;gC@Qgwjmrcq9ovk3h>fbi4?%_=lLj60QA2 zhyeittiGZI=14P~n#0H;{821~f;R&;fauyh?DbDZW?}{2bu1&Du(C{cjN8Pjn^osT z(T&Ilr}$DsPkNVvxAHntr$0!9mq%B_g~cTc++E6d*Kh!~4^dzoX$L zOn^wR{D6ZzRO!^ETmI|;Vmx9c=j>`|xrK`kjJ7BZ9a%gQ$^PZ@z1l@fEow6A#WB?DrO09V;SHlFGKbq?Kg-Qjr>_ z<%*!!KnL0Zf87~8^@^~~j6=u5eR8jl^#C_8*=f%3OrH(PNyx8YfEC!sr(kjUi|=%+ zAF4RC)_Oz8MDL%IRx{CLuHX(ixH#}s+EJ&gK^;Ky16$0$es4lv$r%Q8$^4y4ENp-(PitK=R+WbbOxTV zJ*LM~#eYr=B79Oxe7osu#K}^j%fBv!e@*&Dv+K>~PHMgNs11Y1i)njld$k3H^*n@9 zr;N85>T{@zm4JfsprWpNA(-zAAev&L(Db#)q%{+!L14LRkttzfF^ot)JbtPZ8tme( z@5%1|7)CQ+Ur&e$L=%OTJbaGQ#@piHgkZMs-0~|y7^Bn1toboV#``xHe<6I{%N@#+ zOqh5`GrX6W!)+_#)2pxSGGFb`R)M;<%FR7&i%x{-oE7u>*&QN;Uj+S)?zjS&%&T76 zTJf*dizawaA5_LaW1_n10NUb^Ak!|>qO<4B%r5V(zw?C))GXN0)lB~l=9PYQs$mZ+ z$$Mi?4TPADzqU128A(q)Xban?4gQK82-6+D?P72It>9j!*PYs9ad@B0UjNC8ap8k} zeQhnV0Z$U1o5hfUMDF=#Iu(m3CSFC6Xui`Y=O+4P->7F0vv7qJPK>sCa~og@QnM(^ zN?E`@_jwyu@uA@~WyWhGYbc#-12y!pFX`#?_!Go|UVwj@dkSSHO z;eXoViWf^EW704A-taFhEt#;!M^a0uJY}utUxLTDTU!@`js#FE0D6rl{GO+Mpirpn zMk%O~>Bfirq#u`@<+f>|F{J;+=)w`NU||iOu0F~5^}6hlKYk#<)BD>5naJMLeko9g z0PaMfWERvALz_O9Ft#x=<<9aJyqcx(6mu5Mg(|4aZ{b@vW1ypNA4__h0lZzt`ucP$ zpZwEbC4H*&sdQ~nSF4$yo9q8#CQ$#b98A}^{m#z80XhZM^$%ew>EdAd3OhS{IpccG z;J)l0HZGW=W}~4&_{HAboSu*?21*yWsbVC~%Palw6Gs@BYPOp)Yx8Ca{Gi6x(lS`e zyk#RTof40c6Z|$1MNHus%dj43@gM#=v{bZP5Ib{0EJJ}Hd{BZBhjbRIXOABKo>Id) zT=SLH75ABJQbdjrcCsMGmr6Ub8ix_oWO>{$p{gh(b4V)VAX9$<3voEO2P#GF>?_Z( zY#FqV*LiI3AwgeAI-jh!msd)^9e;p3ac!tz`8jrWps0WosMxl$v<$6Zz{NRI2F~~0 zq?}3#?VdouRW&sw#VJ**Y3;N?&&Wei2*A|uB_iwJ6V_ZWx#SD%vOo6Oxu2F2)FWqlqcH*%k05AJ)d(OPRl6Fpr z^ucs^qE-F_$jCERuYGHCZMy?Q%xG?eXiXu~B`vJm7KYM+eui8p#bMvY0lwd{UqkgX z=JBeW-7V)|WsJT_4W|7p`2>0Zv1hzkeMuXhQ17cfL^e5z&`JG9)XP zH{dk4)k&3cH4{uAI5V$Op0fjE?AtunuWXe%Il_ii6}-P8^7f+K6UIvw6gnaVUJd0X zQ5SgTuQbf;|Gdmdspa8+KoWxx+&&6#0GY5kPs|5|h_+P?a2 zDR$8qi+3VI6+@f~9Vk`1b<9H5MGt=NxaGAWK@1AL%;`WBBl7(tylvV!ZvkgeQ)lUO zGg5z9&Q9}a*vJVg)QpH3)=~dzWVZKZ2GH%luh!}R;FVD`CW$B6by)Z|$<2T2Uz;6P z;G>gpl8E|XuSywm_^HK*xhIJx+ysEIjj=2&C5N)W)3%K&APvUCKOVhQyJ>ar!jyu} z_3FTJ`D-ud1m_Q2ICJ|)I&9z^0K*{$(;Of_dMu6Src$;l2}*Y{O}OYOOsJJQoz|bh zA!%w}2Z*tX2Kv(-)aAMHpP?I04TkdIB(1ST^6M;avwZf?CEo*hp@t4oWicGM3>kbY z=`mZAH$VXu#7|5|L1_d$@A+Gy^(P7@fDaB>g(?sK+mVI(S=;NmBx#yv%CE7$nL$RB z3u6q1QxSkX755`I{{S-P8~ne|{fbZwdnG3_k_Q3S(e}HzK7$d&umpIzd}jfSAu8mp zJ4~+BQ^cJ`ECv%m^XE};e%Iy6r=;)~ey(e042UKf)N1hAPcF<+rS|p8GI>iRr~6bR z#avapiaYt2g*MKIQ%IVb={5MM0|=2Rb$_A~AfKzL1LQ7IO2B)CHlTmWLb(9EPGsk8 z2#=o3NxvzXq>2``-e50hh>4+oeJ^pjC?*%PUV3&v#YP>U5wA5lxiEHg_%d^>smHgQ zF&l&PX@!*jC?#ihN2JlHklqXyHtL#SmARe)%$7u@yjIjsi$x;AU|;tOBH*X)m!Fa} zUpnQo9jS*J|2F1%H{^*l>=|w7#cS!sd-~tM`9)t;XeC1*79V-5XJDY68xqnOB5Tpz z(|Ypo$!(D6tuo4ADUN+TW`LHtIXh;^h?Gi+bDvV#r)ma=4z7`n5SC(J)B&7Cne8pwUH{~Z4h2+t}m|#4JR?+^c!L1m6Z!1A!9q?|SlQ&vxPqMF=T1AZ;&(s`&C|4g6&@xgJkn zdqI|eoQxdY#%aet;_VIh6rWV$q_?_Nyu*&BHLCowNa@zTLX^{ZQ*c97Cea?Pm}s_m zbP?4WQ~D6=l5dhue%7SNUr=&Kc7Il%pyVw!&IW6lE?Rs07|gY_e_`du-#x#n#kl|T z*AZB5F%t#8>_okQFHK6`eN5*xTnC_9-;S?ZJ-Gj7ZDg8NhHEKKGD zXyM@I;wo=w5Ec}y1Emdy?1XlBczD#pE}uVr`iA(c$@A3wse0^+OyfeSc99-OYiv*Cu?3^Ywud1rjbjJLWM);;9RweIU|F{x^%6+7$ zOz0RP{}48Z9atmFPW%)HR7pTcsi{qjjl~_7C1rT}o(JJGXN&!64w`$K^jv2siw6pY zSWrkPipuSam_L9eu0H&7W=c)*Sv&`c6V*Ss=bnT`L$T#MGH%>8)r8Le-H~0fBZ4f& zpgN;ZjT|uj)J;0n2S!ZwV}c>Pq9P)SedN&hw6VLj`mYs&X5@K1W7Jd8mR|-8%cRc9 zqtnl7=6%DM3*w!Y{&iMLmNSt1HtW-iQ}65#{pSk|p-kg$WLR%t*>8WJeNEAPMI!V0z?`%K7NcC+2uWxaMiSLVcg5uPUP{_;I0$ zsA3aXwD!qCc^P#N-?Zm{Y+XNWlhxd=sQQuh5-))KpUjKyakD5z$NUV@jCW7*3~I@E zp1Vs#+l+iz8(^gncnrWQ<9T#W`R6(KUy1XHE%aW{0m{@*?;V5culxP=UJIHiW0&LF z7O#ZmLg17b(|h@EPZaDwi_*4#*i+zs#{CyP2`hP_-?w{OGwa+8kIbKM;fd)yzvLwb za|E^47bl@eNKxBQtehIAcwR;>hF&SB*5X2~p`vb`AJp2}^zR9_Nn25KVh|3!4P>K{ zdOVgdhHToj_5c@k0j-z|+b!7dzTw7nv%SV*gYa2GZd9%;DJo-5eF2Ip>)S2M76>ag zsRUJ3B~}%8W0urJR7lOOfwz#Q?3?H}mzdUDYg+XD~IQWbjq%D}J z%Lu)3pu1K}H<1o?!=N*x*MCZw%-^g(nb?~&OEeR4b>SryLA_X%t~VW=Gs92Cvb^~A z9$G+iSM};iz?_n1vdX5@3|WD#aC7b!^C6-%r`>gVc;dverSrF8VL4)VeQPp9-t4Z7{!j-)3A}ONir$DubjTj5cKbY_hjJ~pUYaQ>|9l6S* z=2G_4LX5KC$?*J&b#|8Dgjt;zdG5U3vmts-{TH+6BlPTx>t3L{GWJ$;BI#^XQw>$} zDJh=y|KaJZqoQh{c7FyWMMAnH1?lcaq`SMNyPE+)kWT54M!LJCrKCHg1cvVBp7*== zyR2a?{s7LbGc#wOXYb#Bp5aAQWlR?=Xq+q1Uh33AEJIb5z3W2?>H8UKX^&~JEt&BYcpx$?nE&kzIW%`J;a-1ckCf6e z8^h*}7ggl4K8vp_{DS-e3g%A$Qya|^8;auXy2SfH08o%o^CVmCn%nXhIFY1vF6;3i zm*=7)Oxntv>__@e-TBEzv^lF(rHUXDp=s#bPvCM8+~<3FuTxlgsp^B)H=R`{*A-|d)b{?2&mD_;(mEcPWO ziCSF0%<;eUL+N-*5DY~+8Kz%$t%4-Urc$&e-Sq^ zGrg-=HF0gY{E+3RzrcYG^*go@I>S>-Ha@<%M?uf6Oc>2I+x?=l^(EfBORL3X@+xEX zao5f1`KJElBw;hf75@T5??z%YK^K9wy%*A+P7c^>3KGG2pSP3*jy;oEX_ z_busqZ|z43m-`Z)adHLBs4qaOzKv%rJD6lOkv-J>_gJ@Llh#hFwl1F5(bsSHIMUtq z%MyB4nlgY}0qNtUwkp+9OwsnO7y(d9Wx8(TDR@7!%g{KR{G=Zl3gfIYZe%e{dbK*F z$$N3|KDWK5M(pcI-!1YZ6C)$$M_M7?J5x1?4PvR$@SP_(MFPbWxZHTJTA>NbGdf~w zHf8bNw7(xME)1AcP-4^?Kz9~u=l4V-1S3$Y(w{Qb^0|KCO3bSfbNU3&9P+BKpcyS# zY#WGrOluu!Fhw{y>uYPpO|^+W{@T>B)vLfu)B3a4w#rPXiY++CIAZMtZi^1ve7S5d zXe^?j9F=AN3)7x?k&m!gAt!J^3`A(4dj+9(CD@zj?A~tt*O}yN4%Zq?O*HSbtDD{F4|6m|Bg~%l;)=xk6cI3uvo#@Mks%QW43cISS zi^qJC5gK8)y6zn9n-)*rk=2EquXSW_&{*x8_)D7W*z$+>TYV#K=2D84jGkb#}ypo(?0Mo6-E4HhnSlPtIo;nZ|!k)X)I zxu={@;pK}MqWyG@VLnQERyOz4XGmB{qp_d~>CUlw7N!IIn$Ca#xdd1S=D6O)b&E&XgA|l7 z@Y4nSRY7v+MLP~L8@w_EU602^5L%Y*$eq_9>Bg2{c|{%j>D_XLatvWj{XedWC>p~! z(@zmmo_58#NTPb7iatZSs`XRs8KPw_+jg`qB-WnIO7GKZ-0`_;J zdA}@#Aa|8;Nae&F0otKQsRr;sRDo3H)Z50wg^Cu3VqX%utP}{zt5)#Nmrj7t-J6<+ zmR8j^X|UXPw3X^<)-YAEQuQXC)pol( zU{R6LP?<0OnMOQ)$7Q(nJuE_%WX(W@`Io%JW%=5XfYh+&Z8}~f>&9K(7GUQ8~>v?$_$a~UShU;lUvGnrHg&CjoW*eOcMoElSRSxd=AtoM9-+%aY(-|%aei8qGY!AphOooEIjU6t2q0bU%N zb}V-hbq1D$?R3}keiv50(~0dEo9BrwolYHaP8$xE0*s2mKHT*1Z|<);n6Ef-KvwfJ(jnVgzI6w9X`k9PcmXA{GW}Ohtjr{JvQ* zl?{ZAi#0bO+r-wg3&+7QP!OoZK=G!ukr0nyqH8SJXg!ge$*>(4ZZZ?hADDYf(`(3V z@I@5IbJ%$~Bhp%8|F3B8mQ zEh7~Zi3{<{1UfpKba(=5380cQPlFDVqhP_OyEW+9v4d~RsJe3XWw&uxPXH~loOppN zv8wRIe8Fe7wdl-T%SAJyE=dNrgKJ(4hIrFT>AkUtUwEJ-UGvd3t5k3f`f`VN$K)Au zr{hTMd$`)!Pv|~EM07DZ@@P;%6YM<%&+6%;F=maEjwZTd>Rh%?;gdYlg&k4>;oOuS zzeN0T)`JXvb{4+K@E3_b%pVu_se64#7SUz*_|)R4@oNsepv0j97Eyt`PwJ(o0b7s~ zq%Yo%<8A_$k4%Azn2pC=SFyan-5_Ob#Zg(7e*^q!gKvnl$hFyjkLMt>R8{u3+3=uL zl06>PQT&vrk|Y#6L~aIRfe6 zG-S@+NT8M^*8EsZ8(Z{;GI`<~fG~;%u?f6>Ha1G4yruJ{ur~e{u{%lcEt;6*4uW~* z#G0C#1ZL(8VACL~4x8_N%@KIPO~aY)l%6xF(4;#vZqY9)YFs`7F}s!)zVn7$N$v~< z)pLvAR&eP$_riIZ)H;P7=200=v}uBv=G0-I*=Z@r%nLk5>jy`f(m7kwc3wLhn)Vb- z6rRzNppj#rGPAH)4#r6H?8nFJeoqwRXc2U@vx@_>n|hMO<67}9tpfE;t$8i*%bfu%Kt}C8f_r*hk zY;qqFnrZlZ=ls_%xRxH}t`9vHyE9^z*gx(-Ur62PJ&(4nEg=MRl03) zl330*D<_bn*b5d-2|l#`HY$=ehjRYf;Nk3dUI1&Fa1y6QSDyUWwqBB(0%XM8z|NbI zXHr#Y$mmI^pyx&9VVFh2`b%Poa2n@SpXPdEo8`loG{fU8vI<&YTSw*PIHX;Sh*{ND zEE-Yp%dJCEU>baNaaMGuybo7uqt+_<>nhCqu5j<06x^RAjGhAO+vhSWB3`bizQY7z zCW`l?t^7v3FP7hbIRA^Gr+8)*c&Q-J_=^<%Vtl-N?OEv6aAq{raj`l;reRW$U9U#2 zr}kHl?SW=_qA8N>rtJI5t)S?Q^$MQ_M5! z&GWZ(xZh2$wSU4HPCq7gdu}_dcIDocMT=xOeA1oy$7Mu0un zX?3nQ-_b1`YsP(;p!q8Qss89!=*RBYr8oU_uu7eIgk6igJ2&YR&K%Cp++UKT9<+|_ z)2(%?Zp4#`^lqF;%C(ir882cH@N;9fhTbX!Dy#v@p*>O1K|AG(*P^qxC@{Qf+PN@j z-q|NybizO?dwE(~KW3R4>qq43nyql`9Tk(I+aIYrW1M(UjSc0|InMR!7#9)Y;$L5P zb&L=zUgQP*g)|s`ao!HCEn(8uZ{P-Pp zOEoDdzuRC=2r;VPj;R4_VajjZ3+Pp~BM$7^rJ8F9k`bRBz~}OugER|S=+Vo|POAPe zd!()=s-wtV36J|e(diO?f#(28{Ys>wg#hHUjl7*xS(BE<8a9SoMPtB$;;KLU8#9Fl-dbv;AWJJv`Yj4R~sN=tHAVg8mEoz8kvYEJYt3 zD10+syK4Z$GviK%%k3RVnHpxzgEPg0mUY`!*bW@>(a{fJ=t)UCEZj!6EWK+yc0r#@ z44kYYGSd889G%k2<2DF&gbSEmAy$7=f^uiMNF)ASQ&*Kgud-DX%xlvgCod)TW=GZ# zeq&5R8G)k8mxEBfXE6~7@f+0v81A^_E$0CQ!Pn#^z1GxGWV70nJZxivRe$Lz~p zQRPpL{Q4*QKmPH%G~(cd2=3ZBc?9|K1s|y1G*H3ka9(+OzwSUrX?SG;wQQ*eLRnrk6 z)E0Q4Hlz;`{D}AA@?YvM!;`HDe#OOr>zLGiRsGI$BB$#Roz6TWGdyfA>l>ju_=3n@ zc*8W+dE=J16WjsC9Wo9$;8Le)n>}5%oLB^K!sU+6nQ!-$m5mqLpNb}gzJV>VjjYTq zUlmLT-W3{k(^ic5YE1I%yY34ZkoTck)6b+}-_JMSEedsNZhk7-!hhJwx9LIieOi%w z9(CVoo-R8v)}Q&);N!d?kZNI28gsMA95q%r~kb? z2s9lI2K>*1A<{&3!{RrrqJnA4!a|ZvqAHyJZQ6kwe}iuHt87s3Y@4!ia=M*w4}+|o z>%Z|&DiS#sSLVO}jEyOX+reAU@dodvwI-$~|CnN|BY8hK()CetIEsy4zB+cnHeh+w zE(jI#pwP}MtxIYbL7v^@?NkCO*w7n3PUC+kK2*&zY5223pP46PY?S}Yp92u?GdV`1 z#C}uEP5yqKQxgn{(ar(*Czruo_1RgCT5Sp&`BOJv-wZ!F5GNms3U1E^9n_>>GNNgB zEDC~bxHEQKyxrZC&xI_;$I}$J-M_D`tgKKEezPNl{>DH<p`CK1zLK{9OXJQ?a!Sk)JM;wt+!mVG4+hD7?p$pH7$)tj+((Qj!%_19Ixg$;sd% zm^?n2IM`&Zhe~u9>gyMLlbG@agUI4jA7*B7gmOiLZ)_T5!>BkoC|HP8^}sV}cWK2x zNvN*`cOb$aPV^7e>MP#$0EOqzfn@;l97efth zR~nUQQlib->(Y9x#!33j=KF6sTBP8YnssOrDNOf8(P(cSf7ZMB{6)Cp@lH~`3BB93 z8-I9U>GsV=`ECxV;dduLnY$xe@9fdl;B*u z_3srIZ#n2k$0a5dXg{(sz<+5Gs)VmbS9J?gFqQ*d>!k)Omcw-b?jY|i3@h~9T)wHS zPScAQg5Bh!!f=Oeihh!`fv1usvuVh#Ku6Y;0 zi_Vdb+^HbMi*_ul#;W7OJq}+aagx4J6xx@k?NwEWQot0~;Orf5PCU!9?TRr_M|Dz^ zhI>Blm;~XAPF-z73A@|Y zA1hZz1{|>nXEF(udOPE;3xl)5zHJgH*BqDDFH{}R-tf%BjsGP%vg+=|Wgs{kjD zzD2Ba6N|IE+^<$Mp@PVO_Kn59G8Np0U1>b@fIsE#d;=F%Zn!8>XR6>XPg%&O-ak zuOxE(VmktQrxuy8!ow4$%(J3l_fXh!Ru)qCl^8H?XzYxVI(qoC!`gKdWG8ZsBYH zC^nXc`qA2F_Aqke)8@}JDJ~-!fpf>s%1v(&@V~hPjk2Guev)2`&n3@2HT&N*}>F;Xux=V2N=S*w8iR-dwV)j$nwrNH2vHE zojpC>@_#caK cn3_@*)-bTJ66O5f*DvuDK8Mw-Yh+ZVS;oM?U^$WfIf_)sCy9HM zF~d5r5BuAn&-)u6hMYDue=AVhN()I!?|#F{qxke!C*z{B?T){$!pdm-4ipNDV>&L0 z;at7zV4b3_tVeMdgvrsoqs@;ReSBrz`U_2B>S4zv?JMl`Z!ZAe{iDAVY_6?Mz&f=< z38J0_Gn`CJg4h`nFxyrgKsz50w_e)>hEju@nV_Jj4f_lYrP53?GA}UoH=%=lr(+bl z1uBlhcoHHaP%89AqWl6g9&G^Uf8d&xZpcuk5@3Fsh5o^LmNCtwY<6j7r9eccPF~!) zHmt}5Nz@k2JWH%QtKFH@`XaFzSx)uo>)0`u7x>l?ZOm>=neu`U6xHrb! zJ0;m3Z3;Tr^K)}0wn^XOC3&aorrGjzBv8byUxhz9*x4!Dn>PjPd#L@|0b7>fSp;Ls zLmsS8W)#yG7Ez^I^qFx`K}H{-PeuiF-N~zx6z1fA6sGKkZ8#yYX)~CBDBNl`oT$l-xs!k|&CFt9UQaR@$?8-mB%rbUzT8W|=oo zXM|MtBK0!JlDHe=*v(*ES@4`u(f(H)O#c zh1)koo`~~j@)ECCEb@|u&_7c>=&*i&SJkR1(>7!T&CpGBZ_(8m@Tk8eH0lvTS z{+Vhn%Do;?kDJq>6UO6sD@;~OJNulVW%gB{zb_pX)}1wwqiVut5ts=3R1w%KA33Jp zyn1_)p2HrX9$H-3Tyz&-Z*M*vJ)@e&P8gsW;X4giwJ(JcYw@TU`tfR8lHY2=2Hkk& z_T${qwTu13p z7zM6ww;dIc>W`IJK20^AQ^;1=E7lD~*ixyW2X^YL-|yCnw7qjT@l&5atz$D&KBA%S zFzK4+&jxFvf4{nWLIAu10`BK>chBPk7k2E1qD06R2Bhcq@5E|B^jYS?7?i^=ekC&CA9R9NJ-|R+IK(ZV*U`KwXl~(5< z8*u{1ZFc?1_zgLEN<-MGo2JaC2&OH8IY?@p>E!Ll^qi*SR#ZLF;adt^O(<=7S)U!8 zc2gx0hl?36f}OP3mQEvjcPq|EHY)CUji5)R@6oi8@U>eXh}In>h^HM|vg?Zz+w*_v zjy9?{Q}-9Rzgqe|kfUjWlR9DhIE^ANBlb_#PGOuQ*+*3wl*VW~t$ZbL<;!rXXT9`p zL62;~?%;>g+C?>#F@Ed)m{LcQn%E;X{OMW9YW^>>XKS~~)|U?mK#cILy=o5XPfN?5 z%`0==S}&}H(_O%czXXLsWdCrL(E&;0)y7zS?r(9!A+2AVa$-G;AH~PvmhWOiNZdVU zGMFk;LfaEM$Y!KfS!k!XKdkQDr}H2+zjOaiy_`SpP~!!K{m5M!A4m0$>tEj9h?mFz zvP4#Q~Hf&7KwE&Jaan_`1d|O4-%891IMl&ibHE$A+UrxrbT({ei6dBgDO((OF%>Qt^KtY;kSoZV?L@@5<0t6 z@+i-_I5&Do8_sli(d)0Qyd6J=egdCc4c8P)a7zb&as{MGUAvrik>^}V=Z2WY4ATL3 z7gA*-7O>lI6Q^`3+%V0|ak+qXFgh0bjUVfvN{%Qel89SX1;`zMhf3;-8YwC8ZDuqK zzt8{+4+blTPv>l1+gB{tvgzxm_r+85FDdgcc{jR3Btx$s94mbDadH~ayJ6E1?+>2e ze5DbB=MR2BX^jJyhdm?xwo1MKYc0NuW?#3zgP5%Ojl4FnIL-3*IQf4XipL5KTZ%^i zlW=1a*eU;(%W*Gx`F&vyOi>3>@d{0<4%*34ke1M`@VLL+ud|#;ARwfZ7+=^sKX=aDn`M8;55}%H*!cTrv3_`C z2L>h1+Gthk)8U|UYDTevi-Dh#I7p^T=$A2C{~l>c%FVzJ%EZF1+O)%2&Jf6Bp$834i{ zV(_1~vvB&PUEhJdOI_O^CYhdG1P2PR3@m*;$wU7vn%pxS{fK)L5)nJei!^$-;H^YBTbYORdk|QJJ_>B z7H%M1QbqmYY-?UTEv9|<>8%syb$vdXi0@Z=B-bTN9g-t|W(Rh5G>QvM|M-mQcij!C z{<$w-GmT-y<$6HpNGr3`+tfw}8lIWJEQj;Bv)H04j>U7Q2u+bPK9@ND*M>@dRB%pt z*_o+|(iM+%V_oaFTl9}%dMk2zbij(kBOC6XzytWYeDaixWGyd0vl2S+Yg;zx{ZZ~ z@jJ_Z{V?c#ZQPC(&6CFrz}_0aCP31?DwqkkD%Te3aeG@pPVLiwyOlmc*!AOA&GW~( z8NcqFX>bhhBN90= z_#`@;yF zFVn-}sJ5jAq}?=31_kWiMAs%;0`%nrIme6+B%RYNriFG63)c&5R1J*_5PE=O$5vZ6B(aL zg49M3OvAV#5T|GJ^JRG+p;K60zBu!%hELZ+jKX*`V{)YPB+$Cv?t(hDNCp7I1}NE< z@uz3Xarao$slH_e@T&ObTs?yNaVs6+Hx31r3rLd38&Ok<`&P_H^CZ_1jE1&=??n(} zZuhBEi>=Me*0>!v^{T19zv;g48|6HoD`U}3AkE$lbUb;*8hZi?<-PJDl5X%H2JO%U z^3{|OiB)EA9pS8G94BwtS&{AL648|@wQRTWH5Md;`t$X3#<{zMglxez#P&0>P$XB{ zant*B`M;hl!z8~eN9hFt!PytOWtbdo9pci{q_z+rGkDK3KmBH3;P@gsd^YjG&E*Jh z{YR4w#Mop$y+=f}Ps_1XJEbem?9Yqg!n*79i3|wDJXw-JAKi?M4#E=ld%uC~g`+31 zUF?$6`Q|{nTL~W8%42@2J1ly-6j14Cz^A6SoC@)(H&T1KUm>s|mH!Yy@KM#fr*mmx*dd|V zW_{oAgA@4+ItGSXa2ts1*{CIizHQH+2W1B63k~voX&FH$>R9*1-yiPaz{`-2x z^_BbttQxz#D++4L31^&anzaW->G4Ys7TYmU(qYA6g<#HcFsbp#BV)7~%;Ei>l0uhk zTDMpr2DZW^bgda|9xaHddx|>ZbU5y~-KNMH6<3Qz=)wg(Txpm9@VAFC+h=W58atv| zW1^$6+DO2}vrxwdUC^{HsVq)n1;ha9D@furIAx&Uba%1nzcml@b*Ppm$rdu|k?%L` zhg%Y@f$GjBo8mn$>82ewcuuCv8E{ae*laXvw97Ti8g#+FC3Xb}$8(YmeJfnF2S>YIvb`}KJm`|p0^4Msl706Rl1HcM3e{~r0qlFD53PnVeE@;2Z)L(;9 z4KhgnU`vxta{L|jO;Lw>nZ~&dZLhOxX<`l9*sJ?X@UEajvrL_yiG^j_XX5_;{@{Rq z%s#y-N#D)I#l_!W$n{4Wn4`1o$?yF2>(>}k0m+XBV1f3s{%NkCtvGeqR~*KQTs5uw z3Xn~g{eHY>)IQAe;&;TX@zRBM$0IJ%cu_f=d4BEC)aLZH;)u<%sPoWn|BOF!o)EZ@ z>#%P+`PB$C8e_EFSlk4`r|Luj8$xlG2*AZj`<%YupQn!Q~ zeoJg6#`EoLapCdk_$BO%(+{+`=lw__j9!!$zDgE8r^~@@Lzo8+kg!d`Fzc9|xGc0B&vGwAP%#Rn{xNT` zjh&Ry-YC!tM67;ZHJF3khU3hec}VGQxKQbi&-y8b7UJ*Y0?^WGM8A@kaliLk{~jxg zD*FzxRqNH8A&h{h-c2}8thCshHpF_U{F^69SZ9B0lirQ!PYfaR$E>z@oA1>A9vgU> z3R%FjwWVvmj~1C0!NDMYvB)j+9_B9?KGRKi97OAGK1<#=U-1G!0EBStALj`Wx*sB0 zrK?2adQAia|FDxL)XRJ|7zcz5e#QaYYJPpKRC90OGuW16bfhjE_$4ytR&7_&LmxCp z4TnhP$jVrS2J-vR)PR5G^mgVruicg$h3kkk0N{@bxCQDaDm#HB~FvjbLLK zU~Hkg^Yejrn-I+gL@s0HR{SbLb#B#n&cU(d6v@5AqD$RP?4~|Nwh?Q{6;}!Un`V`@ z=QN7Q)wSMg0$XY+)hMU+PQF(e8(|YbAwiOyG9+Vvex)-eU4y0`Z8Yyk3ohQS=_hRR zS0lKYa%0y0NL87VW)DXKa1kroObpCPzm2_~n@o`DX%)l83u3|@FSz4?mbUm^viWXS@bA@+VPieCV|dvSR$ z+}U4YsB3cxF6;~c@aB68k>O49Z4mww1aN}W;hD`BmNL}F*WkN#Bn>IYV-Ph^f6lDq z@h-oy>0SI#l2M8fYFFn4|3N^HeBup7T3kL5LV`~3#gW3`7uQcU{tm~56j{c9WYOI? zzJFQYv9>vJrs>N8+(zr@CPgI`UQtRxAB2$Er+(?ug&;eMD6lmA`@pUg5TBdnovUwlL~0d zWGYihw2*&^9xnov`8CkYTzgxTN?xL=Y-^r5<{s7$7C>RkM}V6}52;)4Uj@9A>P1^Y zvk@v@9c{V5Ye6A@Qc;l5#5?Dl#{&B7aQ5VB0Zp#|-ri<&?$A%UjGumBfdkhHAGnR? zT~c6gyT)C(F?vF^ajlXsaxvI_RnL#fFlO8S7q-#H`wJU1#b! zy)5wG_&RV;1rEI2EdyM@^mYv1hoEO!Zj-=4216jKcAteuA zTDxvapBOA(ey8PJ9cWnJmFA)&0^v}#4*x}_V#$vy=Fu(ExUR9KiUIDNELWu|oo3z$ zKj?#2#2H-)LKF?{;w~1JGS7eF01LjE9mS69B)1d1=l(pgyI;UT^cX*qp9{^sFf5{b zu<$l~*GSg!Yx0@nu*phS(&l7<$^v$D_+?8~)3M=Jz7M7A4*223rhn8q{(2`f2I6D_ z6~4vp0OP66mXfwq(ov<)In$iKTIJWlg4>6*z3df%!RYl-lQu?%t*klH5?Ua8lB643 zRnR$-_{!F|^EKdA0nX-!@b0t~g&)IllulH84W=J;#ssWuc2eI!)-6_>j&?3GVl{O& z@U;)BuD{~Ivr&CeQ!tR#7W!5`QhjwaU^JCky>T>GlUfmn%#S}IcjnicujqjP51Je> zRa11Qt7}ZoQ=K1eg{fUdJIW8X&z)hZXN7JT;M8@1r@~g3rxKicyvIeBa3}^^NjScH z`p1(3jPmb z`dkIP6esPM)eFvTK8QGYxKvZtCG9o3#Bt4!xG?fbY(r0V>P7QSjzNM*q3%yKp0WbCz((bi~a> zj?aPf6h&XGT7ntXCDsG!w_IOC7z-S~LoRvks_c2NJZ4f&&+LJALXSoO3Y#rh!>YyO z@)}Tg_zmf?Z&zRggx~VvyIu{j%sA7&fk&A76@ob19uiVV@2PjASdP=rbMmNoA zdB^6VVulN9`ga-sxy5X`LC6@ssU)Fu*3*=w`nozH_=dJoO`1xCiP6*>0?rmEm;-~(4)Iu0P|X+UAg z)s@iJ{%R|w+*k6#a*Af`#^~+(?D|*V3ITgTXw&LaS@D@Ci&hfpM4eZ_Ka5|ug0_$S zYh0s`It76j?*qtwlLerBCB|R{&ebScnz=o_p7aC*%I66#SUT=fI?&UNE_T6{^oOSL z=L&dZi~IZM5_b@-erkbuzsM01LaMuV4jr$eD;^Cf0<{3E%*gFQ7x8lutRxp2mS#lb zcc;5SRqCw&16PB5wGl0wd?P{HVY=PNT65d9uPK*9>d?N7f<9`qFwL@AhbF@RMhqZo z4c`8Pwm+cVC-wGdUl;Y>xN1lIHODlICw~^moV~qB*h{X@F<*^qp$Ad1sMy&5fU(Pl zS)0!-n8Vfu+Kh0yW5X*gi*|UZq2L%~bUKZZsAL}ecS-#*D+C`*R>9f-&KZ?JC@3go z3&r`ZYSkqVcIDri9U$oF#i`%@`SEd^RP5?cILMBvWo%DKNB;ohc7|-dK*Its-58wb z41^@$CB$T~lYk?VKQy7@CZGe6VPf>hU4C&I;ayct%&)U|gZEVzJP8r^5QKtu!*;bmJzu^2%ied{9 zeM6V`7*Y89{Bq&wS+ZkY<^kmYOPh@T9AgV{UBE+o;snb)d<#(wtvY0-L_~YY0xEeYka46I3aW=H9kyIBh)n={#J3zleQ({YC9Yi-xM(ykwl%M zgcYS67_6Y$oI*He&psYqw|jieX1jaPl6R+9E+A6pIy!I4-36=JliN3V65)DQ;tHg( z=lF42T%i3bovp3p&VMe84dkOum-5Y~hr!$Hi?-7nz4C_;oOK6MsM0`r*)LFeUBhag+eTXqKzj$9BbWyHRUN=2<}nz+;GI!XWz`T8lPHN(MY8FLDd z-sle(=?f7$e+12zZM#EuVRMk&&@e`^ck19e(i=C8g>*$jAflVZ>BIYeq#L3*=dIWD zcDrk7^N-N8i#99wDu^nuU?=gB-Yx2+CA1IZ@p=b5)wQ`hOT`gixS?06_NCRSy{e?R zOIIOi{M;}ZDTLn~GUL={(R(58t26J+d%S9~2#|8&)G^z3|I&@I5Q_Y`qkQio@9Trl zT7Czr7qo%$f;&kYU4rcI{Y|TV9#-3(#_+E7`7Jh4%ohl%xQVC zfK*~YPA%w4OaO6a2>G-Pg%(il6$D$z5cu*F?sWG#*Tc|5TM%=`8&3%?+(LYY+}P_) ziAzU31NV^oa7J|Q@oCZf?Kdta9*t-rB|*83Qwb`{iQPuq9<_*3aK>jIGYhXo-yi~` z2{supI?E~~4M@Zq!*LI7wBPH<-5Gy#5kptdY*G(p0p7N>V}5KBsOkqeieEh9rw zH@7eL2%Je7Vx8ZT?lZozL59X*1H0uJbt%OTHNnV&RNJcpYy9!|5AeJ}EoFO59GR2t zdP;~>43Akno}P)yRb{8aXM>!U&MYXl7H4e6r0TiTewUi_*jr5+AGq@>B*AqtNys^B z@nH-@cQ~pU5ILff|L@6P`vNuqZzbo9!t2KX*a)hNQo)HT`TnV0EW+t&Ey$Lz?)s`h zPL-<{MUc8%p(pATLHxAda(Q&ky%l?S)vSScu4OnkLGg6c_HN{1-f)%pl`| zW+`v}f-`@Qwx`F7iKb=yT9o3J4a>pu%U(o|+EP=~ zLjZH*fAwMch@0(rRP@W&NSAvoI|CylS|uA)_Lv25Afl&7m5=u8_co)L3>Lf z2Y-7((?VhWQuPlA@3R!lXT>+N2cqX#t@0XmnbH@)TLTvt_K@nv|Gp%z7tQ|(@$!0s z#C}jv(0}yb8pwd?PJ$<4yX<30I-Yb1#LX~87Q8Qc4}c5>=%SJ2z{YXCU$m$ezvMct zl27rz36scGcWP*k`x(NlVbt_PWWuvVu(Lc|OQ-$5HXuumrPIakjc7C?dvy$%`B^NR zx59#wz=JhX_hXz^eo(!}wPofVM1+H^pEm7|0;Bs8s-+eD3>M1gkg~G1j?9*_f8q9_ z`S{9zayEYwsI#TUG?5~8H)bwA(uW%nxyJk5m$9PnrfThE@qE8Fv^;VD@PoGVoyWDJ zWlWcL-I36E=Jn-cf@zRfamW0AWagpvi{9vWQx7R2h?8)K-b2Ffusmn{+M=PIL{37U z!)ou|JE&a+nvyx6F`d|Etwf}9nJiv|#kn1au(6Y=jNV^N!9N=HrqAy8 ztyw{#h6$DvxOVbwk&o_Nc&SMzWj1kmlq^2D|1b{q(-sG!f8VVor_t!5GUjxZwkMYM zXw5g$1^&pk@-`+UjV|hbm(hWT5j%)E|77hkC6HTo7jXvAaA~o%ApzBucdfhm12;H} z`{aq(P9`)&iJP@JDTU2MbzF3)16okAF>KuLE()ZO@9Lt=y?-B56&%|O1)V9Jld0^Anz%wqreQ@P$@ zrZw;EBbz|2*6Wlg$GJpXRdwL^3-?U;I56lE`f=$AnRoRh@8W3gbMe7LftMft6Vhp* z>Coa}ok)uzwoCtF;u?v|^_%fdh^VRvDip@sMKK>M#i0ZzePEgCuXb;tHN-rhgCx4J zv=|Ar^X(pT@0UX2@;@1pj=DCd8xqmM5w_fh%l1KrkHSsD&n>qZ`U6*FSq?ZYFm$+qe9XR%`D`@LpQ z`!HIMvoNV&W$|(1rZQCo5$UhRw%*0Huby(wvKOV2oFqA~@PO)OX|3FXwG72IeO#9} z%?Anq>-+wS8ZM21@kQ6g9Q!S6u^nMLNiz>DujF<*|ITK7-<|uJv3b?Fe4+U!Ej2HN z$@sjoyGGPy`uZrNy5nD!--Ld8Yef8X5A~^K>_?z$-VLcpb1yFZaCx1oWp*>p2p~mu z1w=9|yLMwgod{Z!LP3)m%NPXri$7prj93pthsS)CxT0;Mm1#?^>AIqGu=Q|>$69d8 zu_@O2dAUg#b2sOu7bWPZIP31JbG6^d{0yHEdaHsb@_Ur!Zr^jQU7s^Mb~E4Z{z|~4 z!%rQE>-unc;sl%Uk(cDGoJsj;SG$3KxHKb!f+;3}V^W^{Id$A_KD>j*YRHz~LcQ9~|=3buN zkUmZ3$2Wtw9ZL%fR@@mW%m$R*JglsuH0{)4h3R#iU!~K`Xf6sud_#VL*5X>4ngfG_ zGHtSMEIB7J$nM3{U;tA-V@$yTDOh5fmcgkKs4YUoP}~w`xjwH^t$v`et5u=#83`iELQXufShZ(>BaWM)@`w z_Z)YnJ^qG#lUY$|!14>EH_W2%wdqbib2j(=MoCCeO}(6%v3dJBaVd)*T=!CqRl!C+n|492SppHpfA5Dn z+uG!YQi~X@duyACf770fL4|O*pXrN%zao zQpFs){qAcp=v3z6cMAetX5W694vw?kI6h{6!$9br=+kOgrDyv(G}zUJcFSEBM+URq zunG)^s$V|Rt&n{C(9pm&aWOYP5Blta0UjSpsTAnx&24NVwzr=G0v#M;m_Hmi`H0z5 zK-|k_T>}227PrL}T?cls+~w39DquVJ#`nwEvu%b~t|wP6l9z~hn*LWwk{DiS0A=#6 zy5BFjjd{=sxe+CB6^VR;xW*W=(Tfx-A?2yVwbaFgrLpKyJyBj!le&rIL1dyn&6eDKvP{8y)x_ig2p(u3f>pm6t4G08W7J!=3w7JI^J= zuYt2T)E^%sAO)!^eiyr2?H8Pv>^_R|+h!zr)Cc)JFy?Bn>zFs5=xlRDc0Oo*r^m}C zM~kily9WOwS$A);m*zrj$a6F2YWPv%dCV-;^*+w-ZPp(or%DoduY$J|TAOb+1pmlW zgWk^{o-j|B2UpibGN(Y(@IykAv?+7KLwXK|v2_g}J{9kOLHLLeiAs_tIu^3iIL<97 zcI&gs9=w<8{)B`b&*cO|7J{OjS;FtQ8<@DuZN(p{JYEls1SN)!9(c;F=&UYN5o^zQu6&5Ce^S z9E|fR@|uv&=uF%;NZhvtr#ZVKbG2< zC-$N^Mw9SpKZU!0%n3gg-&2C)nA#3iuxwk#zUGjHPnF+2_1n8i>ZG%yFja2N_8Nz~ zr2>8lOW=MOG^aC!i@;iD9*mY1?1cvywzU`zpO7i<2rv`IrQuC3u;gfi8C3X0wf61$ zfT*)vIt97(>}qpq@#BuyKSateE2ny~G7#C5c?aPc6totOdW82;+nC;bwzc~j!2Jm( z>BUN`pq1WU4V=qpU1k!??=?ZOO!S76O5{GSiYJ=4<~_(H11o=fo~z+FKi*@(!k!&! zzhK828C^1?K19pD@MAoea{dc_lAe8-7rafsIo5I{Y7Y57Je_q^lz+7KpJ52;QktQp zq$H(5ks7+Y5hSFgV^E|!rMp`sq(LM^YUplB>CX50-Mj8P4EzBM%wiVL`JQt=d+&!a zW&z!av!Blxw(gGfDvfbF%a;lp?~bG!4GdEw*%BZf4!?4LrMao0t(dXN=p`PP=>akV z6*H%0UI3&6t+QW@?FK?)H6~jr2()MeR|+`fK7K zC1(5t-OoIC!<{;o^$7@F!}}C`Yzu0n3)%byIhY``cEC7oe|4 zg8PG*T%OVG`y3tQeEhd@(%--?Y{PN`0L346%S5LjgLk{i$}q0-T9vpcYC+Qc4N=Mm z!%`ouqGw{Nfvi0^KlR6?Pu=DcrOMMG9kH4|f5QL%ocZv=Xa#~W-1dl9xgE?6_;56z z%eh|%m+1ZMEwohGbMPbTqs?4*)?WzXosE8X)>fAbV?(!i?1smOC%3fty}K)OXcD5h zE9%=ODswKvZBI#S&D7Yi40OC%%-6e>A=j2-E{sCd*LKqg6>0mX-D~(OdiSj-E1Ymw zk!t~rSkmMqi(9V(>!+j~!1ajI)uZp~u%pBZlqJM@vywaDeDwkIQOD%rY^!rkd7a9? z1%G8*MRlxhY(+Nk20rxYq}p_!o)+-)f#iHX?GemJzCrvoc?PJ`j00C1frfksZrNgT zKs3o)(`!oTISd!^m;gv#pF3}!b3d+1wt;dx8u5d%MmzcZED=HK$B2~In@&W`&i~y5 zq|Cn(J!`g%4AN#zqGFXadeZ>ro~!eLhD7S98d*R6J38v>#vK|#1Ek7&JP-N-VmZ*- zXDiCM+Pac)W~=o{XmElkIdH6GUV81@K5KulzaRVI)6br3Uw?1{sLGLsa{~vysILa(g3Qg$^T09i-pAjsn*KANtpnp{g~8PC*?;gtqONVQQ_3rRiwPp* zPp;$e+B9G2*@Y<(^16AqWA$nK&63po9rT$$SnD zelI>|e1b_Q7?H?}>AYc8Cod+|CM!-E$^B`1IQP>=X8~@pMr=vyfx zPTv4+;rI@y0#kobA$mKGP`@7Dwf6V-_wk|Z1XT#5qoaTRL@J<#1-)(A%bWj4R8&1_ z`*x-jR4~YzpGc94$7@D?zj|GKYXCbjBliFM?r+_$njZ_z%GSpTa=)hyzh6;~cGHW94-Rfk=>!<1F5@PGFf!>;f5lpSC5zY~Gf^~@&44K^VM7&7sYY*Hd zG+-Ib8T5GG*mFrQz_?%iJixz=@A10-{s<$Uqoot;$W#bMsx2Lvm2#1^q0 z3ZlWk=Ss0c_vFHd#aTV=$GRni0iK_c1^^-k=NsZt*#-!Bqhc*<&tVR@M{Dl9w(0$H z&oxjhWCl4494Mfee)G6b$keWR9-HF@s1z^V@Yoc^C|qoRI$C&Em_jdrv%w%^O>ciM zTxdsltEzs|okQkZMOCfYraWm-=DqbBjK>Oy#3&wgt|f|LlDm<1v3TMKG^+c#7^fMO z{>>&P>AaUiNZsXk8?Sf0E2PfK((uNgY0On^rm2nSoE&9F+&a1R4iqrQ^s*c)nY|Wa z!==TJL}AdX)(V4UtU=;7-M67%vHgJZPy6yOscxJ;?e#pf6lJvrBMrI+UQ*O5ugSc* z8Mw%6WZr)wNg-YC#%bg)XFwpS`EXpS6*|T zu`-wkV)T3sPC_5ugdozN3r5W-Z%-$|)*-3k_Rx8_2SadyBpk(4%B>1g9iz*9jOFnf zTMcA!wG&|mXGLFzP<~3X4qRN=^T+`3T!|{a#HCdTg1k_+U>5KGd^B6x^D?Ujm0X3< zHHW;msOBfqO-iENjkF)SLynS@JY%5YTZaT3n5XBeshBnHr$^Rbb?k&`c}bOT^~>m$ z6Gb$$(_{a&hImGl8=nV@ye+Rr3r2Y`&~FQrHt;Vg35h0AUJZdcF>_`|v!Pr)2PCNY zT}00z$xB`!#m=x~K3#r*CTd|h5^l8eP5X!>WgXu2PloX5K4Pq2jV-wKm%AZ3=2f&d zEMm@IZsQepXLvJBH00l{NRG(;4Ix43P+ye&>@&{v7u-fTlS z_ILip0Yi4UkWGs7M9u@dgjt=CO#A9h!)3$GhSQzYzq z*f;`|$|&jx@C|%fSWmUk5jW1bh=7qUhZBq_1td$rOwi+t^SYx_0Aa`%@?vLr?W@n# zhg(^WhYX$j7#QN@@hOAZ)NRzgQ+&d;pp~B@vmy5?cEGy7SyqpH#((#KcR0jBE>+Y3 z%=f5kzR{65?fC*GVw7&+MJ7ec0)F%20SL5BO_5ks=(5MVd3$<(b*sm_fRK@s3w_*u zYLgL0q|TV}4#SHgwuv%Kw|?xsYT(=Fm`);e9L`JXrJB{#n0WEka&5*Q;;;e;4F$#A z>@2w10#w08Ug{q(u{QOE>Yt&ZIK{6sERz|0H6T|%h=&qAK~)C3R*ubvmi_>Zo=X1> z_kku%K0ZDP2?;cWohg_`70xmfkhjeUm>e=DM zqos%xiq|WZe)7+M(n<-0`NO{LU;;=UVwU1UY?qdzX-#sVV8PcZ1;-ew^${yzVqZAq7?g=6{H+Q^P#nHjRy~Swv-|FgW zR1~g@8W`S~``X0B#AEmb+-P#O9-&;P3d$*|JQH+v^~fFD$hA>n1c%a~a1OMqa#@s5 ze^lLSVuWB+sPyv#+-4^3p8sm#iBybu0zc>3$p zvsWB4fjCE*o%0Y$P+x*omOT;CvGt{6t3053kS4U8=4c|u7P#|)UTZUO8oc>_Vi5I` zWU$i}=yXIS`;@^=?|9wzS(vNW_~Z3Er&52tH(~{((`~!W7__acgV?u6X-iSf7-@U= z_guEB;|s~Me87XRs`xV<9sD`Q2e-#gaVKW;$2KJJfWUb1aryQfnemLIvk{C4k-%Bn zbFpziX(99}-Ob%K;_Ry+3P|D`k+sj?rCWVc|Mbq!kRl{L8~=U_^85GIJ9tZReuuUV zAl2!p*4=1%ON?9ypW#5ZC#`dvK^AcDRgQqp9T&y(R?^yK?0Z*2AK^1>c<~258FU(s zfGEBZpd~jzCQZ%EBvLmG#SMXXWG%~rFp0j0-`$D=PV#9uP9kU3EN$semGPd}hl;JM zZ^-`)y00s^v??Gcxu}Ix$>MaXZ>v1PHkF-G?4e~xEQSuT`6c#bq!h8RBdSr|8Qdw~ zFJxB|M~LP)z)cjQOhvf4hFKReF5YCb-WMPn>D|RAcOO=A8k5jVoxijRTxrK(05TAy z+!W%+=%M_$%10mBwDy|eIakG|Ai_1z#8&oUaJ{D<8K!=Y@>i~hrTqXG(Wi9 zxR~hjH@8?rcG%3@?ZX#~kX>YftS_Cshrn}ogqBMwlNH>Lk{c)-r6F-Ay*-#wvbhM# zByyLVp@y}t)vdvRP+jpeoy1`XwrG?1lU)7oslr*}2AbMyO=jza*Uv5XoMD!O&az-X z_azh;TY-)Hhcv#V!cMMqOqv8mZ8FlxG!nxy`(Kg{&C~h?Leei;eEFiZwE_skp58KJ zJJq2kdL_G~&bIH^N<9ryk7#dByjO>Z+L!Y&1F+4YC zv>cVw2+dL$&{w2BPtRQv{au0Ssmh#%;INKxU3ARV;^+Uz0%%7*)mHS0 zplP6&l_wm?|A~LuHeN4`kC47>-F?XXL}L}Tpd;xsX=Rv-GAGke*@U`}CaR1V+4k!c z=)a~w{G8&f*zVo5G9dDuvcH*|PDC!$=20HS$E9x=S5A6&TBG>KCULLy z`NP>0^HLBR`u`wLu41)YAY3S+Y?V#ll&0RYr+wT#d0zJp8$shO(+fl{Y%?4RvXcjN z}jixU;C%{!yQ{~H7C*?O}q#))`se}8pfeN2HbjNFLNFB)&QH+vNr z&F8O@xY%FpBvSFc6=pVj%8S(dEtCw+=nTzE_2 z;$8mQX*!tLw08p8RHAqhJ;j{oY#7e1}|?#gxGJkr3EZ@iW0`m|CT`BwZx=~+8WD#AaP*A zxeupPI7ko-`|o~56k%38&&WP`csanEQd6p+CHuz0rJHdXJtfZ3+PZk`ee6XtUkxg8 zX7acfb}Y1adwUy{ZH>tnFBD{g?&lOy!S%^3LSx@S-@fW;@Do&|4BR|=0tv-|r;mlc z9{=2Zz<$luwQhPZE)Hd~VeCD@4^EPZo>!$TTc6edvCU*u$x_0)+5M}lt5jZVxv0H( zDxwF5V=l~)%vawP-tQO_Si1SI4d(?4N4e8db%0L66|P`eG&iS@UcbJ+K0iNCO-&W? zIB2pJfwzFWvlmxj4;p{t;NZa1Yh`66M{2@OG9dq%T|6`^q1(gUy!(d^u{9S-#Pe|G zln*X+%nb^1i9L%O53d&w{$dL0t0u7e(VJ<1(`=XmA^o@??gHuWBKawzz=RaAvg}H} z2x8}Z7%v$3`gS(tJCu`pX_ zT{;@|5_j8>i+6n6m99KT^QDQk!M}FdnZ862C|JIsy7LPU*&=I0`FC(|h$^Ef_ycFH@ zOHoysTYOI-&+e8Vb9ra5G3`j22GL~cj9G#rwo>ZnPhEBE(p&O3(4c=Xv~uzpE~4Ye z>-S!$c%HF4uB;9l-KC3@OOrI)+Ek7 zI@@Gn-VY)dh~0(E*9oCVZ(N$sh}TkGGAet#a*l-{cJa7Gn8v6_tT4VraYlB8&%n)V zPV>U&>&wdKGO?r$*k=HoT1ME}18JBx0OOI%m6)spgprAe=o;z5SDpyzn4Dd~(QvZW z^pAzE^5<0b!l1CoI-T||A-c=Gd0 zz@?K9Up${LF)P15BNSJs?YeAQlOm}JR@+cB+%;XEHCKATJZhlkjlT`$oiSk}b1pfM za}7tT@+-6Ag8f+Ls3R7(sqv0`k3dWtRgf5EEv`-MpOVEz5tIEXFTTI&C+rpb^^aH6^g4luqQx?d8eAG)tug_X zF!=`3itUz)Fy|kCwV3Z~NK<%?`B8EvgBqJCb^4tcu>aJ&UkV>U1SH~_jUmudX{-X% z2TY`ZAFh_@&h)Le>EhsvQOAOQVmZ{6XT#RqS*4R1$%YX^_G2$Z8h|V#!^wqy=jAr> zz>a+S+*7o_AYR2dFgxN_I$-$bhLqw7*8I$C9uKCRJ^P7LNk*lVET?ZHVW={)vT)QyscJhKIgK#yA&IvkNtreu^VHliUt{|IVyF}x!po)w z*E~4WEl`iJ?Shxn3bg=E^}f4NFERe5f0F&#*!Qx5$%bM(qXzuNECVEG;d4eOssZ2(g|+J~AbMEgJ3AtZjY9QL25ld<9%I`i{7N9VP50 zeOT^gblGYr8@xHRl-RN`UldrJ)>YAnf$a$vItmeKu;9L z*u}l`hQ`K$kPsq)DcgFmaYH_gClCj97*tN3ow*65FV4>9PKGKnt!K$O;cHpe>A8^R zPNGoYH9l;_S0H=eNd}!n?9t!XxR*PwG$)_r9WhiFg`030W~l%1a5s!JP3EUbkoHH&EHsQQTkl5q zHm*>2gi4ULhTZ3n22@Z%uP~6b&R>-K_6n~1{Y=M&Y{I)A*zwy9cl3K$GS?LdZ#B1x z>x#}I3l5%>?sN#cVBe=Q5ZwK=)T15p-ky$bRj^MpmJrjel`Tjma4#d0!18@Ddv!b- zAelB6`T^>paoeE{t^;UFdH`c#yq@{cd;e_-)}h3jfOySYTsUu`{QbRo&lCpRk^1gP z9v>dclKk7vdlwwj2n>VHecI=YNjL9odV~H++bhlxQW0AxqC2Hv_?cx69!VEE#_HI2 ziy%Y(!0SkEfPO^=S#sE_>3{E(iO5j>-GaTb?Gi~w>I_K_wfNNmga}+|T z) J0)~%GWp`STe+nem6Zs5sJ1B1$;9CWHF*9!`UB&6Z7?-A^vvdHU31zA*Nf|ZL z@n)LsB9}=x5XsDqj_g>>_A_NM*FbIr8Epn~^o@T`h?Vn@-%;!-87Yow!J&l5Kz@Y2 z3v8%i5Uts~+TKk_3jQLV5Uj0nkxpD|W|rRlHxUNeMHrp!%JWw}=M66+Cf7eyaPO+zE}AQ$??KJ%sz+Yd)93@Z@JHmHp_xlS#xn zGI|qe2YO?;p7^@_C*0sRtWZn5Y6FyBtD@fF0kn=AlWw2-5I#WUejImb9nwmzd88Kt zXlT0yQUGih-}ChDX>0aCmfcJrLA!?!bfUb(v9I0Edq!Q^8%Q59r>)wkSog$&@TWga z8t4tr&<1&;B-ClSul#EEl@yW^W9E*%NlIG~l+J!U$(P=y{$rwgI;Lt2bXRf}(hlqj z#7+{Nj!KOP$Ssb$Rd+#DB&unEB4#V>fSnOYjJFBdYx_Vp8?1NsJMVSbA-@M@g6iFv+lw7pd*vBQ_z1+{%#400wB}6f8}W?; z-MbQ^y3mga8miipj%dIg0eI`Oc1Ko|+faN3z zt#P6Ny9vVKx>wpJesZ#DUmh299H+;qNgk%0CHMp2vRt)C%=h1+ABB;>kB@w!AJ2*W z4?Eq>r$X?m+xyDfx8!`5C1Qzsx$OX7ugCMSiJRxjYv5f$BzRz>dHJwK)8~1Y`wLSP zuOQY;)kM)R9v&X@J#Yu2w~f@UsFJM2;~R;dt9&tIs`$>gtk zEsd*443UAq96sF#d2PMEvP}o{RWI5V=-N`WHV07aDq7DdkiPkBS7~HyT%?v?4|$P{ zBlVt!=wJM1sKPpC4v3}@@_Hd+QPa=PgVMpGV*!S6MR+ICg5DG}cXxN2gDGK85|T5X z@Ds^%#q%NLDv1jW;C8@{Uo7q6*)U%m)%zk_V*ihd$?hU&#BJHl2 zyxjXGao!^qArYLxz1mE}dA*CP@0a@b5KsKrYViirnv6lCbyLi6dIA3Pa~DdG*EW86 z=mP_KDPVvq{%*Ecej~;mSJKs>7a*C%yG=j$Zjw&rBR>oS@ji86c&nfEY?|PkDPCzM z>x7q|CXAIU?OycU66vA`1-XxN#9tkZX5rQynm6-mnWcUFi1#61Bn}1#(K|;@EtK!= zCqX-avJtk$$Qif`uLRrv&&?|q6LE@iLJ`J&G&8y()R%1RX1Tq!7q#+#Qr0)uv6vq* zJa*YOJ#}XWf?9+;@1v0HPg+p#DDbgnJTwPTtQjuISJ(=K7}=w4em;xpk)`Zps=@Hh zh$KyPkhQmnH8I5X1G2I1u{X)Wa9^pJbC z0=MA1EGHIJ?DU00BTkjc%MvhG>Sm3Xus!4d|9s;#DAHomR*I|3GSioRG>^{dn9&eG!G`2_R00 zNy>~3zzH1Hzd6o6VlA%xv$?!i8s~Vy2#j(`$osbyZ2R^+X{gnZo^FAl%o1wI)AooK)9O}treqMH&hs-B5cyezj zG_12GFq+VdOI%tko8$oaz_X#@a4rsSsiZ6R8tllo6%6b<6()szfd1dqSSyjUh|ZE4 z2ISq2Gj-uoHEF=W;1lc|QtryL9cjn*UBU)*(~Tw?BrVn6)m?m?A-IMD7HZZs4gEXI zjqCGF(fk@3AXlqY0D}#|1;fgG)#G-6^N+V#a}!$ZzfsUCm1|4ZLk#rmbrTs~cbhUU z%RW@j?V!{P|I8yHFo=s96st}{+m)m=^%u~M+MVB;mi0L%e@#YfV3c=9+PVyki+!*`+|9nq8#!PXcz3Nj&wwpuZRe%0PiZQ{LLC@)*SqckdvYMydC=hBXC zyF*Zp9LgI~@I=M?j_)xD31qdapk+yXGxF1v4X55aIi6iFQKbL^*15Nocn@m!Q0ZZi%tr&<$x9}$&cHmic2mr?<-Pvc5w@nI$(uDKMiEX3OY zf`_jGHJd()SLwk@s>)TLRVDjlThom{zU1|B)6E~hfTzdX5qi-7 z9nuMgJ$Cf8hbJSK$Cz9~Xg|rwkOv_{E8=qBR%#pQ>CJ+EvRL54XWm{wo;XvxLzvt~ zKXJ~XF)Sn=S(n}PW#iP##kB}U9t$4as`;k$Kkp+>6RKQE7j7mROBAP|3lPC$HL@%o z2MNfQmKJ4#e=i**-i@WpQ@ts=yS2J2md$Y&}idj3KkojBFZS4 z{4rXE1aPGG=@4wkz}rTHB5W#pB?bf)Tz=WFwf`d$1%2E#ij~!xJ5tHvH(x+YUT*H! z`I4>3O6#**zm((zoZpzkdr$Tn}SKpC5>BNpxYw2>KnRQSTF=h{z==70`O;O zvy;dp3|XGa$jE@kzTn6AmOG2!H?lk}xdYM0$N1HcoGJO#B`PQKs%k$BqYX7cVkDFz zAq4Xs0i!G_1?k8s2?@z?rid(Yn3ey{Z+fM+&)sravg`q#KFa!DcQgVM@9qae z$7C))z0q#-&=O0s4{HyGlvH_tvp7PHg*>{^9_XJ1!hSDWoQSZh4DNK`RdEDYuv3Z0 zQ3-^ux+uW*MXlm^Y-X3Q{~VuFsoF{u#TgQ;;+ou-k*sS+&O2({>=C2f-n;E^4GpP$EJZrPsq3HKBpMy%i+T#2Jw87R_>6J5-lb<&`~}U4Qa5IX z+4G1V-&ifW!%VdmeFb9E3ddQQl&?)mY)|YDhqUGqX^7EO^=L?PnCEvgBwZ=NB{+xn z;!$+^f9TG5t?0q-Uf@5loT;R&OW@vbk+!KEuk7B(tr5fLrAN%{lrQg)zF&|!p=br2 zHyB<==HIr&V2UUztoMnZ=d`$>iizuHrXd(65K+QfZ61yvHOgHxk-EJ6fd-|E$Xdps zG9)ijaNgX-*57akc2tWhwy@GwQ{xf%FSP#mv2t0q2ZI1rZKfu%zUcd7Q$-5UiVG-V zhVj@TftM%Eanl}B9hBTDg2z}dd!Q+uHKesINllph()Rj0&Nj6BN`)zzenBNemH@|mZ}H`c)zKRab?%M!je?kwndU{IftU8y+n#Qtof+Ho^YTex}XHW7Dq~BBCX%MiOhT-Fe*8 z5(SdWBE#5dovxyu(HPcWz+C3{J^fK_8s~En#y(@8Ys%r%8n`w`fG8Q{M3UFsN6XQ1 z45}J4Q$K35+Vz`|C7IZLwSO~!g(P60ynTM}G1dcHkjoxjx3mXXJAs1lCC`Ka{We0+ zFWM@Q&_R`=pqV47O%8G5qe}=7T)_frcf3J2P(8P~oiF!JVk>((-LBKdw;J4CaZEWTMMNWdPsUccCv`y2A-27V6h1US^D{So~TI zoGOFq2)|-0w$rW2`>+w{FIu(l6(J^(!6f^XK}5g4USCN+4bu|_-0y|t%aHVIqan1@ zWgIAHxxYap`;zDYeI;9d%+7vBhLpP_&CZcu&+InP0g}zYNNtS2%qjVk2o>d1Q@NQU zJ~u)T#$~~eY$Z;?&*-{8f>iGgh4|B%PZxS=@648MaVUFDvI3U{vqTpV7#~T2BCmQq1SWspGcqvIdg01@xctzvpIv+lH=y^vgHs5-^#NlsW}lzvksaMevhw? zZ^1A=zM_NOT@W@r2(3qSPVIiy_dB}U)4#7xmT+!by(>kiGpTE~3v+fbqN`SV?~=M* z4>_N2NnBD0nb|F5gSO?BB$sxKRl4R=YvIpy?5}Bh*TT_gJNiZ=?(>#bWx2S4la?sY zew3Vm$&vTxytmS&j|Msq{x~^zo`zm)rZrE$w>lnd{Qq56q}iwLpb;d&Z!cDYMn(v0 z>DT`-K!mUd8vPjFits8krVe$?{QSIuiOJ#Rt>yNrJ#PHF;>D*j8l-b!HhWSb-+OA8>8PNI= ze8l^Q(b|pW_#rFGDD)3>lR`vMUbVXW=iZ=QaWbQDCLZ@5s3!wKjO&wkzcWDP-fKVU zt?+eEGc!nMZ!h}h8}=kP=+O&0`)dBo%%mPUt*8%Ll>a3vEDX0J0@Zqp4vpI7ao86i zIm6*7Xmkx?AdHh#FqpBCQD$~F=yL^nHvagyrwtlrDTW=$qr9384hg9?>A*vfx!rKQ za?Mx}Pq^wF{rEb93e?Yo=a6&nMGk4py4g3mk~<^=7#UdrAW0m|2}x_5&~0|v$;*M- za0FHvZXNx%5xe_N{6rm-j5mxms)Zo-YN?ey8*aj*#`!Br{ZIA%vwq13HebDNkK2>H zE*O2y(ZvIGzw86!Z8WOfy#X1Z#;`hud(p5_>8KDW_ki?oS%Tf{n&BdJpw7c6Ph8t8 z@E6qHO7)4j{kK4E#o?qs$sm;WNqkK+(cu5b!0Z*_13TIDvy)G+9SIC#=*#Mk4kX2l z%w>3R^bF5m6t9&G=Lut1A0Ga=qRgrx>EyX+BQ@q4DrImwI(E5JoHQU0YK>uQYu&EY z6azZCq4aY!ivLdek-$}eh5^X&16k~SB|X{74c3VK2nEzc6As+CgK2o3Xwy$e#>;<) zO2&U!7v)dr#W}%wA{Pn`)_om30R26ecMOY??Kj>ePeWauK#A2Z$|V1MWWXONkgcpW zgBRZ3=At;uG`+wugIqwVIyKeYG49C_oqfAsTR>U-l$XBc|5$(mau7tZdvQD|?Wnm^ z`1&zcBw}f?>=MDJBh`^`azhqxr7**Z4}cZ%J0I9fg2NxS<30v-)3>_#x+qo%BiJ9f zEAznbZ30C$c@!b$q2Ft-T^*R7k*PJ4a>Ka>NW|X!^fRL#%Fw*wtkHtSPJ;YGAS;dEIMzhit0f(+gQi7Wg?P%t5V~v?gmjw)@^5~W)kb|G0&`==< z%`u7Ad2zfhN}IcxhO~j&@k||MNQEMWV6hq)LR<;0X-glQPdLGC9sWeY@qZ&&jBSXK zna{Jf#_cFAF~9TQ5227eUo_s#{gvae?xHp?}|YHmr?PtT{ir%M(GN z&A0B-RSs(i$Ge)eeASz$Mp9qV54ieYQ2}ff+QbkV6apt~U@}8H6>$l9k7oL_9EqPq zSjp4L5^-@?ldBadEhb?P4IP{}KCcPst?kO2DIbQ`tbL+!fR5Tu^~&E)gapuYHdX>J_d@(C@#Y5e{P_854i2)!_k>R~1GrHvqF1;c$J79+mGCT2M zN;4FlJEP0&eE`g@eRpg>P1p4=yS2LO10GOF^Y^uJ+72}EqB~2}bK#v%+LsAB@*M53 zJ_y@xzSg1oZk`=8`fK0-?y9DHIoMxc^<2q#<{j)iD+3#TzwBVSxAA1Urm#s^iuy=9 zAQ!MWN=(O#1a$H5&o{<@`k7o}kWRi&-Sq#oXOSOJ@p{raN^bep=D-@4XNY3eW(V&W zZ^aE8Yu%2u-nqoTM{>Vl%w_F@zh*fPT+~MIbYEX(CuB=K_J`IbKf0~NyOd{x7XuH} zx5?M@(T=S6pQX6UI{rbNZ0$%lR7oG+eha>DSW&ILYa!x|WsLaA#P`2jGUnq(mf%dU zPrO}D!tfJ!S_%R(~Rb%f3fA2dnQ!6|YT`_#u`JZg# zevO$QQnagXJJE2*+`odTVW?~xtC|xa*a5@>0x5$^N=k9fsp{~HgneJlRj|Lw$UITx z={2l%rWzR@R_B$s+1u9+|FyQ*;xYdZG%FS;RQzLA2iAh;O~wWW`TB7?A$$K87Z*Wj z!fv`M3IsHs@x0dh9Vq`gp6YBhk7BHE0?P_ORGry1!tP_B$3#+WtE@823_iD=+ib8-lnYXFc{8 z&t_It#uGZTl;TWD&&;fxv~>%spZ~yv4sIuNo-yciIDwTAFTKbxR~4Mr(zZ2}8#I@t zD)#E{X->{Q|4?c$>#}_}YW>BaRuGePawvu48QquWl6)p?i|hbl+U!^^`i&ThiA@z_JsY#nAD_GK5-B+vpS+?Eoe$z^^z@$~;EiZ>E0`F{c5i znKZBvMA(5bWl7oyw#VV-f2Pki76pS6eh}Zt|6>8T$mkIK-sS)=mU&`Q%M6D#87m5~) zlpB94KvQeacmQbR#=Mn(#fZzAV#EuMmusZ7pLe#6N^mI2&ct<{Dzhv`=`x#BoADAt zYt+MT0V2Z|$Cn&KpC#LN(VlN6STUZ7AkV%GopuVot#b1iqkJZi?a~CR^8Tq6(QJOL3AFxF@zE-tX|wv( zW#E5B$YA2}-G+Ux-kg2q7EjFCYor{{D8~iaq%i19g1S^rrXoZJ_We;aw9R_sZ4b+bA*dO) zJR2b#l~Wpe^s5}oy-6Pd{kR;Fokm+@9h_MNs_!F4S=_6N88q0~Z{cwli9Zkx=h<)X z`DQt+e{nGQ_jYqQ(Doo3uOr+IW?^%~bB+lkhkb)WLlvId7nNm5ttbM@-zl^<;hN z>>ca*J2xy8lJftXi*_)^4HbNw7vf2hM^+QQ+hevle!@URZ6}Zp3bX84Vz0DC3I)`a zrw%ONN*M7ppUKR5Sy=@~#t%^D&e{(T4H0HBVc;MiL3=I&RuIW!e~Oi=7|bmLM6(z) z&ND(ozy|B>q}kc$RB21VBausPqMW+Ed&%^l$hHKN#rXy?Z1r*!|zM}y@bYs6~$P_F(Xh_7G&uwag zjoSu|I?GdU@ab6aw1Bq!f*uD8KU}wN?)~d#EhFQ+yxWYI=jSP@sozCH$Y^LB`6w)z zG+3U(3*+}D!Jevk``mlF+N3xhq)I?;GdVdK7^VH|BINQ2NM4Kvb=bJ8Ef0_UcLVLz zHa9n0JPtu3atKt5MMp2ScsSbGfs@jx|MBpOtw^u=SU21Hac>GNuj=NO-ed3iK%xD> zG~>TGzxPDQ3WXL&>pDFOapbf{gSz+cT;u9#TYidBP^(wQL1&*v1WsTzUwmv?1f!!V zGIw^sj8DRoK`=DNl4%{r<8%%hpX@MWZZEGsFLB`1dne&sdzf8dEy`(Z?5Q-9W=sR8 zyz&ZeF8ReZyKO)gK)1q$s^+qODGc-N!>~AyeFz*4Sm7x7(+gzDFEQFz!bX=bAFgIC z^M6h`jHEwO=96xwl67E-Vmr@;w`*CX#h{uUIDOd^VvsS(iWFXrf7C;r=KQ^=Th9l~ z3M3`^UnCnJu&6B9wQte3{JyU^jp;0&*aO(>ZdyvK77XQHAYZ zq?3j!UH8fGmq=KX~1!FHfCJuwS4IA{^98dKJVy9T)d#yf3r-wrYBFZb90 zV7AAc=>KNNc(R4ozO*%9f)igZR}nc%n#7dE-S%=yHp!pWPJH>k~^ApP9BSg)4R!u^# zO86ifC`H3D4A;%XpoV3D0s~EnL{HVVE`ge;pJQ6hk16pO9kJL-8#(`SX+=|A`^|74 z4#QtioQaq*?h){;>H5rxpX^oB1I71b`DluMB~wUK*+a(19)I}qgc==l3I4__0xT+G zIg{_^EPs8~#;3Tps{DiqAbU@KExAjOS7KCIg?e|tlV*F4<^4?O;`?r25+}gMRPnWj z9{L?1^P1})*Ed4R(PHH!ePRGL9TT{IcWag`od9tx0uMXZ3-;2?oQJmjL@6QPKRs(h z7`*5U7jvOLE+b|amd%=Ys{iggg(p(7Jh#cW=2y8u|LXIPy(kF8NDa#&2T8qc?s zU?VuATPM8cI-H%H@uMU5m4$|s_ zva{d$-@ds#UTJwsPn8!tXNFQ{mPdp%q)>O(-di8JKSZoIBg8a}M`9!o4wIiwYi0%XD0-E$m*$PbV zW6ZaRpUY$_wyqAIgB^CLhYz+mb5C!kV;(8X{HL@#4q1|wd?WihQUY7GD$DeNNk?%O zz5C>|pR&Zjnu+V-5A;z_VL;XIgluj;E_RC=xL3iuEqY8HI7lMRxM@nV&V2CC?~wQs zc!!AF%D5?*d{ihp5-NTS8_-6RT(;ZTU*(|F_7qTA|6eJc{9RHEwECU+J9UQq*9pz= zP2VcffP(2Ct>2>(nI+@PWeGfo>n{a;YUhis7Zw*8-44OfvcM$Fh%tKs(0sB8L=0O& z8~LCCCT7q&S>T=00@%Gxb1+7sz63eT!%O*1_LRXMx?}yy;uK4z{0T-RmKeh)LCOM8 zqSTgQzb~Og12!^+|4LM zu*vm__vQg1qLbsH^jDYQ$QOLLEU3Y`VA#1;Z1p@TOEBIirP@&M^uB2J9H5j0C&Ipc zS680kE|Ts)0AB?10_YNqh>wM}r8&Y^Vs%<(kne z{D)f;C6keJKXfqZTq4*0(yWJr$#~ruwhfi2V8<$X^_eF6&9N|P^{L}6dGQDta6@_?z(M5%&y|4SlonG#2_>l~~r~^b7;n3NMb~P_CrTWFVx{HK^)q303&m zdU~{n?gzTA6@ZMWQFp-{V`-OUJSJ^B>gAGIR1)oy*%}(B@rqlb=fld+t}S{e%yW}# zxCUtl;}zdg!MBmZ>ZuNvtF62v)-IF&)`Z4D?BD+70-B^dD>RdT)%hVuk~diQOD(Mm z0jjg@ZsxjNS!gcYr`U@fM(Ox=yo^RPSGZjeU$rCW9hl;tuMYpfFLqK;#L`8I#yrLQ z@dWe3uoiL3|KsVcYgy;C(y)$Y%F zsi9sOgK_EDf-Uk!pySDc6|I&1RX%?GO5bwm!n5m!gW?GMFDr+r;6F5jJ0gxr7(3cx z7V;Yz?llUXeihJQFLOpX98O%XFbXKy_l2W3F$<8^ILmBW_C8xSp#SNvcNF4LDAA1P zAY;mD75Pnll%de&_lvNCN{26*(LZH|owe|_g(sgWs0onOPi>d|B;f5SLjUp|YzX*C zB16?vwm}<`)aKj0AY zWRFD3I`$ev0DpWgL*;SIK$SCpQ6{WFA*^*&V6dMpFEesPEnSuTxLCQ?uD(K<+v=X1 zl|_+ft_cBLqjF+)ao+ltRIUt#2Bo)WkS$JJlBBzCFMui8{!`TGLm{=ocCw@i)z(9`Bl{!U85} zoKgHjZVKx#l2cG8HN4(tjfB)%%;N$~164R4MI(x7X|b_VnWA-ctGljNqm?1fKODr| zyK+oNSY&vul4mbxLW1LpK&Q5W())-65Dn z*HeiV`e5?L>fC5@pClkYgg)BIPu7d%S2Y>0?@RcUAMBLW@J(B~MwC`cYdQ{@Iolcz z*+T=4VPX4!1pv_MWi(t^1k|wyg3lJN88NR+gcE|cDO;nHqSNT)k*FaIbB1u;rA{?R zukrcvM>Blksj9X`nCL+%Rn^TS?io5l1^LA)B%KCIePVS-ES_<<3G#5 zp$bT(tc&cb%Ht2_e584s61}I<2L#1ze5-vmoO6mBz79M6 zIKs7B#X!(Kbi(2b4X4N62?cN3^gHZv824K@oHrf19xR^Gb`aJdI@2CrSAhaxzstu89HSxb?*MQ|GTRD`HU5VoAZ!OC0$Xi9PKA{RDq* z;_aR0@C5`Ab5!GrM&~qWklc=+F&-1s_oVwkUl;|N3ygga zic52S?ZDRQ-IsD{H)+xNRIRhh;v~;)go49!;^#HsEObHM^-JI}z%u#+nZOqjxzC_B zCtxQ*R$wpJ{TO?B&}K%r+&5mb@s_-5HbnXZ-{^yX(y4&ToNEGVm=ui^X z)z@EHU(ZWV*U{B|y}5$F^Qlg9OHA;)Ji+zhOOX83+~UOVb;0<-BP^_#?)-9VXiton z_pNHY?C1OPOfYvEjQx}vnn~^hi-HbjN=eN@#nNAb`^QnU#-H-NFo3*O@=*mYr9@~|?#!sK1z#8MND$6~8 z;Ey@&k3YaB&PJb@r%dRc*r%4UoigOJrJ&LAM-q$v&WpUsjgkWrJlSGIh3Cfja$D*KSD2jCvLMvl%!0&ZsoSV%8Xw*;BfgmZUoj2-!eFHf9T&#_{hE`6Ps)u^Ao}=Ep8|GB~ah+?xg5EYM{Hs z_vFvl^SFk;+rDT0mxMR39f7)ZWqI#L%8q#qphIzqQ+D&f&aExg07;Dfc74){&+6Rp zXy}GnkuyOE3(}#zRLV=gUVB7*DsU!gX&fsB7%bTyfc|y5)mLYiE)#i^RRr{A zTultxQhae|6RlC6(xDU^-l*tjE_@kf^k86e^7!n>YS>vMRG7P6N<9-gmfl#*ij;Or zQV>yYF^bk$gwsKFo48RwXCX>aS%5H~CWOaa>S!s$iuBvJk3#HT&c1xhI?#A9Q1w8V zvkGW6Lf%E{s@y<)N?ej*bow^+gjGU;V! za%=5*g?|=I)dD`iF_A<)5@0l6!u9-eUn40;56MKurD*%fN^dP-I z8E>|@{leNLQVH2oG``JwE6gRx0lF7JHVnLp-pu>iDi+HbRYd)t7T_hRw)}k|vOE%P zw>w8tGy8~yK!I@5Uh;Kf%YkDl-CV+$m%sl%a5~XN;8_J%9AEi<4?1H$!U&f*vO+S$ zJ=xgmj{;RB7V8Xs&Yna|UcO9#WcS%U_kmZteBz{a;%_;s(Y-&Q5VF;vX3oyA z)h%qt0qMj02*u)QP%cxf4&mbA*~%`YiF5}9!SOQkW9TlJ zx_saP>M?7KI@`eOKgh#@3)k1Lu7~s04-XGsV8?cIjyo6@YS*Y&SXc=9;Xo@Km~8^f znx+JMw8=8S`#V5ESeAK#Y7EO~K_o`xQ)}y+Fa~ZKH)gUhAtfnx3UDTm{NiCQExPri z@hVog{VxT2V(tB`D%T-)#-=&t}YdV15og)tfG<_l=tTD@81tXhw9}G2m~lgT0Xx1`Sa(= z$qA@YZ8cyh!T!_=#(!Pf#Ahp$^0<>?p?fY0@{5WdQ{jqJNi?JX>MXJjJ*kmwLknS9 zn%H?)TpGU1SjHvF@a)+$I;EK_8f}5s-VFb9izHk-yoz*@`YV1wLzDATLdZ6GBHy75 z&VNgFt~IkAWY+Td2j`sU$4@#LPG6S zPZjlT9~KGe(m%7|iH>r(PQyK|`|T7WE}3l(1hQcnN9%fWNWxosa^pzp9irC^Qm}$Q&ygQZ6ppKm3&G;JoQmre??CTI6eDOyRfSWPpcNM7_;4= z?|pg$PNY<)C!VkA#%LhB(NLuq0JBPm}?`iKZezb`wMBG2()(~ z!nVi5EDmE4vw7_~4#rts&{EXWSvxxYQZqj?>=knDX~TtJ!CuC~x=M$e*qJ4@CVk-}MYW|hR|FqiYLrDyfH+KA zvo7PyNWX*LSwea>>!IC{Zm%=u8YC0A`owYmXSpNcK!R!?py<6Z*Q%h`n9v%PYZ5CS zD<8c;%G}$(?MIpZyW`dh`s4jY-n;9Q3(Yu@p=^vT=3G4AWG{>AdsY;@zkhU%2q+w=79tpk5p%x$LXvac+9Lx_D|Sv?^cZH7Z~HNqJ(wJnyJpe- zg)l0C$vj+M)kspnfGyF%ajr}AKJA3ZRvO`Hyd>(_vLQ*kKj2W98V~-+(-?st_K;4< zy(n__e!ZUSxqr=@5VO%?Z)2XVzLEKbMqMpvw3OICRDGg<*avH~RyzVqLgXNl64;y7 zw;l>kt*>|zE*7z?6VW{*YPVLRfJ9O)N;=sW=a-K8W0BCPVXb7#Wl$2kEvvQjCd7St z)FS__@#{w~g1|-uA239L7Z@vj)vYp%)8Se8ySwr3l=N!qInRE8R!~;Ck-)#E*>7d{ z;T07e#nK7&2N5&Qn*sB2PR*E8E_au<(>KhXl*KI$je6jfddw>6 z-Aie=e5X7?_a8UG+)drxd32bhi{S4B^RtQ_=@Jrj@E-#6W~V_4?4^!8DPsewdDZ$U zK32!7le44ae{DFwInzeK*$GZ7u>at{MThso9j7Q|Mj#$<@jgi21)YnVdo$<4V`Fe| z5ZnQEPr>>0x@c(p2=yJAlDakow;o*X-hF#p5K9o%uiyM)p2c^9FQyL^Y~s~)Iw?w6 zXO@9&4@+CvVw6TbZB{QC2YRhFWPyvT(h%(v_Imz@z$ zH&IVLhsG}gRdj*wf|ysX(u+K{DN#G*e6%kITZNrF4Fc2miG1^ z>%J-(I}X}4KX2^-zxv-(*8_&&p!6=opiaaG6J9H-h24PV4(HqId+(X%pQ_m1gzx7Y zM`AX-r;#E)^-cQ#`_CEmL{MKjQ=@QbCdJv*)2*5x*d6Me*{k^&o-LgE%sl!!Qc|4k z5t)QvjmaPQL%)hgep7w+VxwZCxiDUyn8mLhj}9D!8hjZw^tI0d-CM$^qQ&m>5!QB? zJWJFWh@@q}rxvQnjSMM)0QPEfL>qGrN!xRw4M+B%8amIRpBuR@|44VZw+y@C!#i@o zT%wZlC+lkGG(>=y7Z4+)dmRo@vPCvAK9eNaC4(U6PFgi(hAtBnA=i=Ck1T7L!T!E< zR}-M(9Ue)mM3X?P z9|d+ANdfQQ2Qrq{_L%T44+_ga)7YODmH~l~)qLu+-Y$>(X=NK;ZAG98uUvOYda1rA zK!P)OSpqM{B;NK8O7EpuSgx$DoQwN!jcL?wY-Cs+CYxCKd3blaa6W~8qbC#U%+hYC z+&1lc-ecg;WTU=LN$^js*LZR_?2@1ah3b)gwty!F#a&tVUN0o--kfFkK ze?BV|C7K`$C}VSXC4*0yYblpp?X?WLPVE)oz@rQ~ymUpjcAAmv>}X~teJ2IrW{i#J zMM5VQLqmy4XQX7+nJRYHtxSMlk7Ob26p*Wk$i^p%L-AA?Z9(g)C`o#I=EW%a&Vlh+ zxlaHzf^t<6cGIc!oH{x+)Wc9CAoqOCHf+y^qNy6ez?7RWxmxx#K-U5V#b9(I>`O4JoHXDFP1KUm0?; zCO1WG3hM1~Dg$jZ=BoA?>x6=J~*8~+lP=j@2c=YXG zYL(4m{@5YJANN1MjTCJ~ zfZ1_|-=_MaIkVv@_UD$AokU2u6D~Xk1Fb2^K+GNu_kg0eb%+CfNQ-K$8B`r~m4BxVgVJH9<+9gO_J8;j&u4d5}w0%q9_O zNL>Mm9#D^$?=X*E?F#S%5jSv*IXXJ}`}_O(-Ghn}N}ny^RKnBv3xD}O%Vf}mdTs$Zh}i4O31-1oJwp6u+=CMXh}cE_Ej-V1TiqfdO5u zPzU>{RfuhTO1cN*eAD_(cKi|GdHLrlq3;D!Qr%(FLPE%pDJA>on<3E4CYHfYc zWFUspv;PG3qE&IkoJIzQhQ$W4DC=kO*`TBS=)H?{-W74$iI+1uRnd_%3+$~z=@IwO zj|9ZqIkQHtCF~9Fde*bwHoe?N+1$&a5Rg86Y zGxGA*fBwt{zpt$^914lP@EG=pQWu?dzf%DlEJBq_8OJBKZfl>3-+R6cDyMP6Y0aJ; zI1Ui^Is0+pKRUmh?+|(%F%?L1%LX)1{ut=y{;NdmqthmS=RAu3NY!;G|4%tX!#dIV z!9e}*`Ny|`21~L<_o^`)Y6oIBs$;T&iO4<|pONz?$o{QMU?k(NTd9F;SDSqteZ)V( zP?A>rLbuU=C!1ulN{H?hyrrLv6#{rp4ZAXCByFpR3_$h= zM#*uurbi;5h@v`#;itx ze^PBXW_%g(P6}mv5rn{?)C= zW26`_CFNvA7tU`#oh@N04=>rsyKD6?#wSp$+eEK#J z9$|)C&pIuc_3Yrf^9|-})URU8-j_rY5R#~+7LR-GKSE0qZMle#=~t&rL6U7BXEeOT zYCMV#wUdH9`Y(&d2OOMrdNYz=U;~S3HPy<$TC)5(Mg8@cs+Q+cPm~B48h6?dh8ict z=A-mz5No3&#ZNo;MV= zlYkT(VYp1Q6v6dD!Lt`8l4r`6k~3)BSrenlqezF17PJ&kW}_EsEwyY#e#ra9qEy5p zlRq@^7ciPo(BEl!887)0IAMyFD@(R%5$wVZ4`6UX%LCgh+%@iAh(|*PnotO*Z4z>( zgt(P-uTzm@KqX=?c&6vR@vj9rAlDIC7C{UtY~D@qi)$b<@42rQB8TOn_n^LJ2;7cM z-~hQUWP^VR>t>hR1|rXT_UnO`{Lw(wd-Lp9sIb1W!)BMS&K|u(1yj~KKd}onyGIJ8 zzS;EJkgOuz^&qo3={Ig$e2OA0L?$|Q`|2>qL3}ypdn+A2Wu;DU^CLjA6I0+cSH(_P zWep#e1__;#^8MbXDg36<`jVbwO-}frbk8{g&-N$D#>=Q$z{Hg!`a)v8;>E8R4+MtC zx4{WZCCj9@lpgs)X|uZ@?`BkDfl8H-{v<8zY!qUB*u>WsV%Q3smjquX$)}wQmv2N))-{0rK1J)1f%GU_3Qr5}@Hd!pv&wAp-nG8JLVfum z#t6Nnsqq8XpJddSzxmwK-jK6sD4W%D>TUjGhR7iP`>@*DI-fVuFS<@_=8!~X|9X%e zAfSK^GfZ(wY81v3^kQ6ofpiz?uRxe#n-u#&Hq;s=5BF7%qh(8(3mIFL- zf}(sWcGKgZS7U&f{QR*{k1?iy|8g3E5oh|z_y6=Q*B_v>$IVnzs#K2JPw{w9|I&G5 z9{)@wZh1$1PCyH|wGZET-R1KR;p%SlLL!fUi%i>HD>bL3A0nOhw$lQLTrrr)Xc;It zj#rvN>~A@St1($wPWAh-xxEHDFn}qqGF4J8>0{i9&ea+5|4FPA_|$!&b{VcvBxZl{ zc^Y=HLqj+&XL6Nqjm5c|xTeiS06OE&6Wp1Y zmiWzm6CaVq@BGprX&I)WnE5$B&x6fSm`ojki9fSsZaNsOxV?1j zHMFP#iu^w-(u2<>bBsZ7-!}hqKMl7K04{A_?aD?bi4_NEOhi#@SxSCG8$S=Pyu7`^ ztS;7+Vf)%nFVJakF&#Yp>0Ms?D#z=0gVxF{|3J|6s}3Di8_YR?&DYV$xbpKjnE5*2>@tag5_D1=Fv7t_4ZMLyjc3FhRaI3e zk{hZs&HL}G?*>vC96$*yMyS+k364?ujq08D1GdM@Q|Wzl5W^mJt!3hmSd-Y%C4NGQ z62nKj-DE04iHq?R`Kzk}qDwgb*ZH{-VwgK$sJIGxgIe+S{gfYQB^|jx=|6Waz(Z}b z)L46*m;JbW6zpwvk@jU=KN@-U?66>x4b|Dy^R#x;Dl*||tu{mMJJXiE0M>+ERV+x=zwPIynt6G`ODyTA?@-_~fWaUax{5&ap!6~z% z4}p%rPX)!?X)As!x}Jb`=tvI-bHBGV^=c7+9bhoKRwuAxkM!dv2i{Lt zBQ={tB}ay4X4n+aO(2WNO#sl`AV_~(1-(xeQf~{e1h+6tT`L!~X}-p#s3j$WM8`j_ zy^w4)Xfb&ugW&-XZ_$w+J36uq3}VS!sGne}EKP_QTD;G)?TrdCp0+|>M7eGlf}r+7 ze!jbQSk7SJf>Z&8J^ksPyohy$(Q#?hH2?j;3fdXp0teYPYOMBY>>_eG^bKrBnE5=! z3x3c*S1w1stn{Nw2gkQDlw>_h4Z|`2NDwHmJ2Y!zTqU&BpB81i&E80^kLziK=~u3K zxP{>)wNT-8)MCTsd-JBO$}>@7@@FtoD~CQqXL>3Sr6?1&?(ef8@6@5HPWGRpo95KL zWZOO-RvtBZh?H>d;Yhar) zaNkDqdc~e>k8byf*lT^YTWP+fq!WkTa$>4qr74}-Sw)W~lj&_?^h`in-+so?S8tl? zRvVIsoF0Pkt+pv%10SFMg|9xs(MEuY2M!QborIj9EgIe*kiWmvGsImufs7A`kge>? z6P>!AH)#IlVj)q!@Xqa52H4h6ovhg>WNB;~z}i?|n}+IPVN8>d!PhEXu0?g$M&tpQ zOs|&gHSrgbe?V|skTDuJt+^4K`6Cokqb~5{K4)f>h^-ox)AuKnZWR*qF7uQ)u-4nFFC8SSe9`Re9xzqL{R~}6N|ns@p0j8F|8LO|ER-9! z#ltHS^D!%TFE66|i}Kv@^~ccb((JId+vBbkI;A8Qg=^Dc68VQO$yr^B4X!~!>w@U{ z>gDm@K;li9kFODdkfJ752;6_TuxKoi%y-u{HWm+h+{n9scy2+;Y$uquX-pMthNBM0 z9An)Hm;bet6?0-8!gF7F6fqk|h%Khx{)XrJ_Yp~=a@O@U`;OXck4%re9XG*{hFjaX zBT?0aoYDM49=VV6_-vq(5}3A$i;DwY3*Za_o$8qx={Y%uy1GNZ+}`v_avc1Z4?XhG zr^o^3i&YzNG=ui}hK8Lb&ZUT{JccQi$QYIPvX>b5em(0AAMrH?jSb>4?~YL{J)g3n zRCw7h=+v8ptbe7`9^d27SzOQ9RH3_O^$SO@>4@nnOMgUOyrUDlt5-Q`{Ud&QHWTkM z#k!dhbbu?F)3{~%*g1#NjqQ(g!K-4h3taX@zKU~aV+m)%zLFI+Ewp|N=?&AZ-~%2a z%Q?|`_I3)QymdPI%MQJ;VM0f3YlQ_s|E44vDw7)hEa8Ph)X*jV6%YCGpr0M`oPiU z+eI3dmVC??(yxaw#L1k7v`~gA>B>scaaA8R(rQbeA)q@&tb8GumWqw9Y1f)IZkP{s zv56a(>HBC*@NfTRz(#X$hA*z1b{T!t_tvg^3OD^Mw^6GCt~^6L zs`?zgExG<02G03JTN8FGkaERa_nqop z+7#;&{*9i$Y?fMY9w?MVEZFUKY(&MF6sHoH!!ijf(W~%)eMqq#52y^7R%p92X~F|q zNW!GgNM@1WgnY6?yjL7`yqik4Mm~G@7DJY&vMb{;i-u2VX3wdgy2DH!)pj1UUmuhk0Sly zQPK|8CBXxmxqik*-Pk2g=}qzBc+=U5<&n4+s{SHXDH2$9(H#R&35rx=ql{G{^WH{L z#uSfNx|Iys**te@9AY><70ij%I1?IO#PF$FBti}?2+1l+X3tcCKJ@>z03SG<$O0$_ zA&&WGb0qI}%vLJQNE*QlJ`=!EHI)WeV{|6zB%XDqYov)sXQ*CgJWh}Ln1T$$549lE zLEo_8C_8Tii%AWp@e9` zg^3#T*hDilTB#epAd3RBe_Fc^4WXnfRQ$^Snx)l}9w=}tX6`yMZP zIFK%suoR;TlfU9pEY)0L|3G^1h8*DFK=LtM@+-vc5$vtjbH89(`(6>_t;k<#? z5&r7>2S|aQaz-xuX$iX2As%h^Oem@q`nm(ovRP)LEzE|BLYdR7rNdW=(01;X$Zy4) z+^>n7o;;%&Cg4%SHCCVT(CqY<#zr^Cn2zjtp(3T+fhdoBbeL zATr25`WvgU%bg+2|E~-2Sl9boHs-6V{I6mb`Pcft?IG7{S@Ioj%AcVpIundFuE5mt zB(>kFZq=$Lyyg@wW?n5c%EnF9DwaLy|7zSE3+1}h0J=&`?1fyE5RDp|L+%fOaV|I= zZok!V=mryoEFS2Z}HbRh^ZP$#|z98L9P5sF|R>Ps_#P9Td$%MyW;C42)XpQHG4Tq_NLv%i9d1lx`Nsy3}b%JJr z#1&`)00yg+3-@I9*iyoL4>4CgWIAe;)AIkPCGDjIZDrrIYLK-r;mUe;;04@QiVAG( z#-@(JDQ}i*G!*yz+TFc=;DO<{b-WVT(m{FbIKJj`?5t?vrZzna0SXEo937{S!v3?T zM@NH|G-)Hhz@1S=S(y)fkJj#6%fP6wz;1C~-ulKynU5e&Ys+E@J|*y(p5Ra5%L=7! z=$B6ApBL$W1Mx&Q*^;*^-w$iKE5eGj>W=x;KDE-{S5y2$VNyr_M$8WIxdo?H;KvtRj@NhxMvxk$ZBo{slw9nqR3){)*1wF|jply- zrfP${F>`S3zU*P1Y6ur89wXY2%7(TWP)+ZW zO@7jChX8wU3d^kNgrY$CC0FpE9$c)qzYFFW0e2aV%^05`SWrES<-2As%LdGn&IFNMe?hXcq?{Nn{eTOZ-KCOcXT$(~l}` zWpI=XL`ziO$H12D4SN zDJRhzwN#}P#PGjN9mQindaSN-TUF1jI#ExV$Fq=A7JVm_?-gC;M+Z#Vc-f<$no|tz z^64mEa}pKSRV!1r#3K428v9#kJ$FWi+C)8m7*Qap6md|m} zW{50!Y67yc#oZ=&(>U~OZLS2P3R!rXy=Z&AmcEQ0wReEL_r*K)CR&QW^M>rCpyDvs zqmX+gtp+K(lD;#&n#m6g+H_*Iwl}>R-$IprEkD`qqL!xM1o7qc{AVODM4k zkfw#;ey<&anSw{9(j5P#SuE!6;)$*7q(e52u&LxJ{T?LZ*XYq*i5mQ;B84lS>-W2#rc(O}m%C_lh-;r++y(T6cZnux+02C}buO4gslsqd zlu=^(wIh1(3`8Q^LuDTTIlC1Vug)!;{6&m$ei!AXMmvO-;)&`C{SukP`z$;YI>T&N z=|K+Lw~Cl0g>_X&ZP5CRFHG{F5=k#3!dv=G%te05dWL<)HjH!OqrLZ2Zs~0S)HrtO z>Czfu7{u;s5kL}_R^2HQ&|=9x=!7nT;N$srlTa4R(5N6)^Se3vw~l(2JYu-9CGqnr zqtoI4=5~?97A%a56v8F2=u|9Im?xA-iX1}OWP0&=J1%!2NS#I#hpk1mcv1_^`_9 zFA%mHgsPN+sU`XxY4sZRzcp(Y$U*xxG>ek&t&?vMmPcpg_SAt#w)?TyN}LFGm3Asf zl~Mmvd(I<=UCTEUsU{EPD!vuHY}h~giqe%ovS*DUav84jI?ZkE;1kJnv`63L(gvb7 zwFk@LV!(!_39P#2=7zut{Da~w(}bxF4>yQup7T(@0FJ$~ti(XR50t1dGBU~!=4NG? zM~{Ji?sh{Y1ireJgM$OuQDYTw@z);|Re~SZxlx(lUnO5y;;C>>EEUc4m@Pz_C{>wa z{PWdg!qakB>|>j3A=Thd;qo0VMts4of|Neu=O4x)xaFH<5_IZrayA||(%&H(d-$H? zVz;Z*GjHH=rOvM1>0OEJLBdIdvI9u(_NskSXhYgex{vM3Ot-9cHL&K&2y?dAB_6-6 z&WmkPl*lS~OcboXT)( zdhCr5s5WnZlbII<(?a5DHNE_(7;(KQwXvcRY0YPpU*;)?Y6mRStDmJV1l9@syEBvR zkk_LZfQ**5xml-U@9u#k-dS4Ienzo2Yo@WLFpGtmv&IM{T6#ikz75 z^F5M!(oXkZ29xbp4yAh}Pn^k{sAqx3GX+|VWcpx7`6bqALsS-E=`$pnWo4+0Fs%V{ zrX-r~fD-zuwS=Q~WZX7?0b>#nwnxQ~9PPd)eo^XE7gT#jBYWUSmq#43qopyUwjaUTdquB` zAr*q_6v9Red>_rT8mO!bq4f5#g~Q`^&&iplQ~y!t@c48^i0>KYfmp#9Ip#CqS^?x=RNyWCg)dNcZMw1b5bPL zz{b`e*aU>WFb%%fvTq^~0!y4dQME&Vg~P!B=**dMlU6!|`ibvDQuC({9-MPsrgI7; z>^|2GNrEOl{jpPpJsnAfJt>z4KXP8t7q7^hrH>ZLdd_6Jvx&V6ZPnrNCDLhT!MS8o zEYj@cVj-nKv{1mD(PGpm^K+9SB%NsRsMZE&P^zfnWI4lygaP7fzp@QX&n3xLX)_z+ ziuBNid$3Ke7m;R}qKK`7i@XR0$YFblzgh6g-tS-g3nA%J{ZUfS`enAff6Qi%0-xd! z)+CCHnCb+Ex!W16;S8-6;IjA2Z0CIYGMG zC~p)J{>K)H&bDal8oVG&>e@YAj)tr%=^I#db8)fw$S#Q`R0SKc>#E}Y<%f4clf0{( z$~BU{>LnV|y#YN5qlM>f(3JETxwL_E0|!tpBU*D*-xs&Gs6R9hJO+r~-Z&TPKxf4p zrY0!4EVLu}0{tNND|-(7W&J4_7q73kc*nm6_reSH4Pzs#;jdvYRTV?+s~eU>%fs&4v6yte;=_{DAso%5wCPUY+g~4y zgust#L~XDVvzFc%jVKuFOjbIi2E7)F1kjn|sqIi&a+Y3+6dY+(M0p0YUiEc#{^#5I zd~GypRh*UL#EMnVl$f8%bs+TpO!Hb?b~6-8Ta=w>K@}E^U>no;KsQ+JU+V#IAV)37 zmtbBJfz-nac{7q42fP4Hlz3<3uco@u@r!!$U5L{>|}W7{&u z=iyj6ek4HWwXByAQsJ~R(t|ITy7Jw0jNJ@g2eqMA$I169R>SVpH^qv8nS7cWP*Y}sB|C+yLqQM`x&9j{P~-(Vjdca z3%5D;+Jcq1RX>vmtpK3T`e!;NrT7J}r8jT$x&dvv;wcIaj5@LBGt~TQBez9rGV$YG zum~5;ZP|Y=58{rrgmCv|+{2GV7TOgW2(UK=HC#aS|P!a z{!?8~P)1yf%#|tJny%58Z~F1>z5Fp=r5F*cTk+rxsA`xjzzH?|a)I<$A#U))|D#oCC$GL1#5P0vnuo17nbUF5W_g4uM_Qr%a3&% zgEg9qF$#Mni6Y-bb0BS);lMR%lUsOfju;x#c>5a1x7;R4gt*GI2dO8v5J`fS7p8CW zniA1X=1P)8iQ)uX_coW=a=)NQ_J>tDtVU1p^sM}#BJ^+1L~*6J86^#fiTWd}vc7K( z5%^F$h0GBi{VWY7NGt2TgtLJCVaBHOb6?8ZqAGGM#&*;X$T5A1dnoI(RnFeU z+E^;q9@oawMn=*EgZ>%)Bz9)@wC^3=>{zGrys%tracv$PzWwR!A0!56RY0bmpttDa zk2fmf@Z!PFlFKs(CXs){iR5o=C84*wD;yksl-67}7uMM|mP6h+^}n*Scg^c0?+}B| zlJhDjNi(!Yg(AMKcEYSDz8}r z8ivRcFU~nYVETedJnQIgqty#ds#>diKBPd4W&0xTt$Pk}xWj_evbNHK0nG zCIXk|nO7=7;Vf&$XG_hmCw#j5>JWQ&L7Dio)PGFblwdd@VN}0cs|Y{8Y=O2As;*9a zXzKV$bmGGNJZMyvR{&422Zbu7Z@26buf7n^FT1sNG=UuoPEN5eCVc6w{Wdkq!1Jz< zN)woFU#wm(ki$0AW@w$$&y|`q7jvQ^S0_+uooQ!Cth2({R5=*h+(WNP&A?xIn#j+y1pHWILHdXE74izMEAP=}zU zt?gcJ+?r*{KQ&$)I)2Dz6OXks)R`IH48E@BtNtir@C~vt0-Zd|$6nQ1g(#(2Sy`Z1 zdwF^JBM5gVRILm#w1aO)Gwwnf=-^G9PST<%N6FotGAwn9{kgGi;x>{b0NtVg_(rWg z8(LuTB$XFAT2T!tGX@hU#n*%jFFa2_w$M^fke#bK%m-gBpMrsVKB_q}ZLlal2wfoZ z*4E`toEhB5c4jinoVD+K(Tv1%ltnzbWap#nP--i`J&JJ=->vju13ky1YVteu3FszT znT(M|rKNuFbbyKCI#0krMLaWk_vKmfB&Rjg&aB~RZ2h~9kZIbD;!)w?Y2Xdck5G2S zKXf>h8e|!C@iN7KBuMwq;X7x0$tTFdJpwp25I$QuEYX_Fc~^q;ut(D3+5rc_%e^Az zXNQlfEXalFId%*{su@gb)l2V_X4~wA)09hbbRrLHuD9GBHFrj2htUqC<*h(CdRj^i zKxh(-E@SIdtV~w6%`72*uqkP1s=7!VCYn`4gLvlhm(rb^Tv42cHld=GXGwDosWySM(i6Wo#sI?)Sy||J)3(pI;-qA#Vkqj5tP4n&* zSB4h|1JWAcoB9(|Jb2 z6}D}AkI_Q3BuI48dxQ{Oh~9}&qW4ik^if9;iQapU8Z~-11R-h$LG<2x@85pj_kF%! zEX!KfV%gWd@9R8|!>k7xQ#lc|iF?gT1U!+Js5p^N$KIS zLwsCb_0@Ur=_8`OI4kN4!r0oLofOdNGtc2GX2tW%UUSk>E4A>~=lfa-76K{blBCiN z3L(pGy=*g?XHQ4BxKIvdZCF5<2gV&pUH26PIO;ICBYc!g_AL*oC2kA~9uwKTdVD|x zeR1ShMq_?hKr1etmG4JhKPnLs(?*JA(jR72XZE|7jYE;MEoc12g7@CEs#AnA=;cx{ z7lad5XI+`bB7BufaL^MW25+oJ|H-2C$}-i$8fQxkd7gLdu}K&}9s*^FQ1QZX!Y~&< z&lc?7P-+t!tj*e_Tc;rndxpY*NK$i%qcst4mA#C(@2u5fJnc|k?P=NM#})mOoQdC{ zDrOi1T%qZ^dhRh;r-H(b%lgX4pLB_o(HPWqsq<1wGkSnTy^ZxV1JDo?>- zQx54>;KTEE#-vc!t5C z_3e#PtI+jGje*Z8vGeSM>6Q0)3GO&VSQ4?;OXD;b$2h8t#*SSztF+e?{*uB{1lfm@ zk9?;X%!#k$Ta}=aXC37VRbS@Su0UF^B-wk0xOhrrX=>$iNho%7@I+Yv`L5TX)N|G8 zhT+Q3k30Ua=A+PJwll>rLQ81$xQY>wlcgPckECM%kJu!RYFML_)0wGf>nW|K__j^9 zOL^~e(NAS7UL8;S(Zi;x)G-E?$Co~h24KS2qGJa19*>yV+m~tk6L&Q@pUl`4`}MJDN|j5 zWU%6sF+V#CqFybeA=%TrOK}#Mqj5Ak_QDJKXSi>GdD@#-DYVD+c4|s&xzzi4gx^n zt%wzD@>l$wy?);?$dzpsmHb@_nHiPmmYZAc^=1q_Cd)&#t%~_aXEuvQWT{29w#OJm zw%o@z>X36eDpF){Crq&2Uc7M^{W7JMb6<%T1P#^oW-O!!o~m=$0WLvJ&ZpSJ=xu zByYPnC5z!q1*4Elrvk#kz9?cFy@RWCv?7!55kQb#=9+Wn<))4{D{x8@B|&}@ zr(c)KGAOi;5@ix6b_ao@D0aipmW*CX3s?pW47JMMvk{urQC3?5oqx~7$AKXTHYsyO zM(9*|rEk8HC?MI8;`&Q4e-qdHD^5J7W(g0D50Tbfd;!N!cVM-w1cD`!o82@6WLFae zQ6HHU$Jh(Tkq`;w(JzStiju)N6Y<=?2A-|CBPkVmFhn|E<~NJdQ3hQmCm`Pp0QMlR z@1R=loOzc+N1f;9$xC%-yT%Kj%B?hJ3?(ySrYs= zem3FhHJ|wZr~xmWe-kOm#?rbz(>>PrrlHm+0NHs_6fA=@Vlv;ygC@3^2CHIfzx|!$ zu6eE$hv2y4EVt3dy@-U>2Ygjd(LlLaD97-BMrD*5w!n1sd_Gs!!s-Fcn|G)QNHkUm zt?JX1`scrvrdJfqx(NY>!ZOw$4Nz1sdzc7{8<83PFSRq2W<;=RCBzqioQJ3X{r==& z8fbxW!?~GMFlQ`1sBGOPe+>3gJFls2*C;R?J|~hy>z?Pb0prPKVP|zde~5^#6Vq1% zVtNEB3e)8T|CTUmybhnb(E+bQ-;bcMYfUNkb#@Lqt6#H+ha1{&xHm{`F?J{Y*P{ zuUV$$4DW-LsuKa7&mWxZyU*Cf71am$IBi#{M9hOBkARz7?~pDf9jgp`#+8+TfSTIh#2$244*~V`|p3Ip3!f_hoDc4g>mG@*(e;uQr)%Cxv z(~=0OTK)Vnm#(r6O^+91BQ4 z*rPqyuE?I}v(8TFS zYwxOaS98Yq)UJOZ*#L|yqpdUvz|VYrGqynKS2!;KN<*^ClvFkgdioY;!$IFYg*u{vmXd{SsR#Q)FK);i3{}#V6!cVYRzI$63N5K zX|cNi4?($gHOfT2oMM9?z?HX7g?CNC)wxc|I7kQrVR@Rx{Nm!O-*0wz9fps=_;9b- z&DMAcxHT7aoGXQu)MSi&sMmqP!2DY#80iAB@E|&2OQY^E9)dPZI3alPKQgbc24JsA zM4^H5*oS$1UBM@KA&T|}%lNaXIbps{p$*w%s&~acw|{QR^DYe^+$Ssqf&xGsqB{__ z$}!(hLq-PmnZ^n1u|E={Rr$~!`1QMQ7J9gAM@O0#b^q-o>KH&dvfbJb_;HYwN1X>d1!gvU)6X*^#vs-{+wBwrpPc z#;S^>dN}CrG?@$cT9=Q0=uOSlx19UQH$Qg0quw1c=f6p$DE@xs2M1h(W>Ib5DNyIE ztpqdE@?=`u;nq_3K72y+%HpxGYdsoFv@$g#Zc-j%5%)1C#E9WpK_8KK=U)iD3e{C8 z&OG-Z5&P{myq0zuf~;12jGu|wX1Murp)Ywn$Srhpg3ZBPcAY}&DmYOvw52+QqyhUK z@;VP8eqx6X&;Nzqelze-?jIrp$2#6fb)L4XR64U0FoThvg`;_>mKM-Yf(=(YU@H#! z(1u3{j+i7z#`=Jck43o@S3sy-rt~~YZ?)l7l*u0P<@GHboqx>*upXj!J{1O}NJD#}(K#WN)`&`a zf_zg8931PA@UnmywA?unV3WTdz$a?*kpS5r?x95i^ed8^3m|65dLIF%`>StMH%qH= zx_wp#C9Qs%9_T+#J@UHft09TUR}!TsVv6@h1&8NQf8whpK8i^`!aT933>A}W zS`hy+A~^-~q27sV&(W}lmqCEZA$hA!cbL)0mLG>L;$!fFcPP-=Nvv&hVc7H>2Xv-lls#aRs%jA*W49hxDTi6bB zL^`PhhkGk5s+&(X^5%tgH$_<3vvd5Xh*`T?s6B>v;*f&*08z0iMUiJ2-{}Pj2NGA7 z8Rq)cAdB!;WGlbzwe#I=@{6Ma+A9TyXLw4JS4{aFywX07XsYn#MkVhs>z|>;VZ5J4 zaH3fa6|(|7kvKYh%`jinZ4?)LD34O(SLQ_%y3o9?ay{Oc5XHLd5`a^mClu7FlfQ|t zB%%x3*?q4pmw8Ptsh1j@SnuhS=B`3iN=i!T4mjDG3 zbBYTBxcGIhc%+sW?#;1#LD&4$n9YW~#wGUi;s3Tn8QVfxqu*ooyH{TDZ3%OjMIiN#?`&eRB zr1CRVt@$ZPM5!NQg9UsrETvOn1TNKoE;_lm#8onAZ&MLbZ7{wm*D?|j!KEP3tOId& z3H_EH?wYa;ubg`E>N9$idKm~XNc+(!&eLz?Q!9Q`6dP*ayWp)v5tQR`YORVz0=DgZ zznvaDs77B%e?2XN1bxjQeu^@Ak(`z`4W`2K1#lMGl zbpZptpkn#Qk43!Ee;~}x5JcJ;8?$&n-olRn1}Q!ot*d>C-$l!P82C66-@~=3k;?Og zO^Z3#_Y3)BJ6YTMB~f9p=n2U?YmmdS(Gc1dB6UK;g+WXYPl96ohgp4H-E5;~jB-dM ztXaHiI~cppfEy&Gf;vdhigkE+2->?wdLD|!fQ$tV)+ZoQ_5p8PZ$`^UZo{S;@P%<2 z+G@1l8H``U^7hp_-&c-Vmq!VT-TF%4q3%B%b4I_y6lcFzm;683UlKvmyMEBqzBKDR z8pe`$kglrx6Y|NUZI1S2%a7WzTE`V3eoA9dq%TUa14z0EY_{UepH~qr_>Qz+jn5d! zAoh3V*@vaZ$}XbFWEN_aVz3(Rx;8G>EhyJxH?9O@|M=IE)Th`L;xFpG$~P>yZkBNo zhY)ii2>k`gV=pFjJ-hD>7bIA3&CBxUm4VkUufL&7p_!HUI;nlO(TBOWxI}ZM{3*uJ z3!eN-e{j03Ch7otpaANZ)IANnJipqdE(W+D%vXc9yF{0^s!}+QGF#jfGt4*`=voX2 zv(m(2qkbWPg`9#+0M|%_zb~PV*IWD~?Cx8fBHqLPX_6X3dL6TAwA8KsjDY86%BNO3C}|g)5r@sM|t{ zj{bBAW@Y1ug!F?)Ao5y-mjllm`n15nR)6!&K;6r6LIy|A=&1PoKK$!PfJqFFuc-&x zZ}-8^ggu~Ikw}x*Q~YEdX$c3$%&@ZyT~lxb?Vg>&EcsyC(E| z#bLl9n`5x9l1~&&auHWEI;^X1fP(@$K0-@X6UxlKtDFl_cken(J_WEJf+~(Y)2zie zx%@T-p6cOxVndaj3FtEaGLNU>J zP8$E5(p~7NM%N_x#p4XK`wE;KqgUeRRw0XhrIViL@&x?tK>DU=@sUS<3h`M-a>@V& zC2K2nHQy#_XgJI8%twB8c_EnjDwQtHJ6Y&!dkqgH0>R(yr!_?Trs&#BOQeO`y| zT+(X43!$<$p@ppK+|uz)<)3RQAQISZ0=Cb2{g=J2lVwJx;4KmMv zgsfNA_mnPq876q+Bm__YvlRikZ-Mb~&Y6DHE>R$J)YHJbpax_KOLci)?uU@>Flo#P zI1hXUug1oEpOsnZwrr22(vsDt0*c`M7n}nRVmx7sqg%i918F>NJ4GZ|o63i7dJ+Sf zZ>B_l?_Uyq;b1|DByEOBV4->q$%r7Y<=|zZ5SEP7kx-Jb5Lh_yRIe(xgcKta$E17l zBmvMJxN*t`f0WvLUZ9lpKgwe9FeTVYtv>!mO-w%wXt0u@hpWa}x}&L}3o^|{{Yt6w zsqZC)s3ANV&2BuYco(faphDEk4=IJ>p-PXu?Ov0~B$=pfdibs-8IePT3N?MDt$V$g z7el!R|ExKn_$;rPdCP8#EP_-RV0Jr~t^Zf*iCCPop z*47pe1=<_n&eYc~6uMH0L9hF^a^A5E^;Pm^(|vo0;}UcDmu_q$*-*UpVZlUKD){6C zEkt0EJvo_f)PiM(IZqsPCGMYZpI!|Ose(_#Q!k61_Z1WSGmX+~-75-U7at5FZE|)s z8&*&o3}JZLhMUKCZG4q~l;?tB%TmD{EhlV15eJqAO9yMrXFg;f75}K>%XZSY7i3UX z*};ysDX6}2r$FdPyb|yCDYkp7LoMl{j@A=xZi|v-h((LE^66E9;aj0v=lW@`1jS3A zHvKY9K?M?H_5={{selAgJ0MOwUo$7RrdiV3wdcvHm#>{&|0SCU_U>zO-tE#v(Pok* z8}SGycN{E$>zz(o9IDwL{uNy*@?^XBX9dCzP}XEWLytBS32s4a6=`{nJ@ngh)qWo zR@_^yshnTk$>n4tcpHvycOnCx>f@T=#>{UQP;9*Z<+*qvF0ikVdd_$=e2+0MxE1@M z%`ZH_O=l`}#s@7ukM>efi89D&OHDARm+*rIzqRJE?$f$9bUWvl|?+2Ygq2!pQ=Xs7XFBX0N0uilh;i zWtx1vUHbUD>n;56ks>eU@QE3>RmtRXr%pnqJwgkv&13zpCph_sn3$C?EFy1O*}#f&V>D+DDG# zt8>o-X~lcDqkq`IjW7{#GyL(&So8CY9`A?l*MP(gI!AypA`IexIFbfCDP^^BtML9M zFYLo{drSg~D{S6t9Oc%M6*B`wtlcp~e7G4*Fcw}iF(Vw@~5oGd^z%%f})P<^j~m04>>$%^rc!Q-ZKBSfq$)CjZeA1BSX z$Cf{d!t~2*f|0|vGN4&9WEtgyo>WK`10dF$MQh=l#DUmniK5h4rBDY69|EB4Z>;RE zQ1KVo%GfRC+A1YUx-FCk2*DhP#OH^Ui0ROBQZTBpxB3QM8S+vRL!LrO!R2eWr9=xR zif9;qYMH$re4d}d4rwdlT3C63w=3UU> zm4Oz!A)tj*QNRRuM(s*B;!yNitzdCgj47v^Uc%uY{JQUPjY!^?&EBjD!2pjRc>diU@hM8{;moub+UWGv3E@@fr=l_2u8EZfJ z@Ko7b?VY;U?Z0i5A}Ep#K9N%|R)>d-Lv`>txK^ zc@7Q^K0ZDWBz7`3M#GNekD>b`jW%9)7P51w)dyc1m?T0$>3p7OBxZX!DCq<1jtYWX zqR)!ze72A~u2qDtkGdKB*7Mp_adv}Hk&eO&uM!wX)Vu-4`Jvx#kZ45kXqwilMGXP+ zNILfYk7@R7K4GiSKw%FYi(xy#g)emPKNH0rrjc`z>B|dad{pvEF9MT{PdIhD=wPf=?YosAh5J@4M8&e3$dx4UUzb&Aq^Li zu=`bO2+{B1U-&SLnkpMfQ;o=+wS0p&n!$_Dwx=MY>cG&ZmdMt-a+VjYn7P335veEg z_^F`rkmxUjyGZS|4Zm|BXnnG20Ee&KHxf(VJkvr4sD26fTLPu^ys}!-+8VJvpt11l z*RLHWm0&4lm%ew;UCZWoZ*-8shZ$`NiinNNaNAl%t^E;E&7;g&456>)ftVAoZ77#o z5{!Ar5Y!%ep4Zy98xlcfY%9ZQ2ZA>e?6cJsOXNZLgRl89aGoF+c2 zCru&|p!2)!M~iaqL>(_A|zBAn~;OXK(VJIJ`tz;RUfGSH1Rsn17npTsEed1j~a zLSJxkc5I7QKI6+1|C1E&SB(Z5(ClLA58g}26YM=cLzqZy;yJB1REti^?_u4&I3eew z+I4~Vc_*}yRr7%h1=W0sof@CN!2ZAl=e4WayuzEGOn@SJ00%GB>D3A3p*ie{yJD(!kQmX5d0olLB*$em zp;VSKCM>{5*ws9yo||)(he0rwi)JjL97BY68uxY^ZI6Eq5IxHG2=?W*vNS170a%Yr z)=ls_-fR%X4=M1GU0F20Y5o+Pto=O7URN#Tu8Ci0A=v7Z)e!{^U9H<3oN*iVZbK(e z5BD}h_N5K;_{i|58Y6~HL2&ki? z`JOG9%3sP<3#?`hPG1O&AF)4c6$;ztw7T3VV!}}5HIGSh`wmejyxo*Vlafgi=n}(T zy+Q^*w4946VC1YCVwYq(5=eajtlufCH-EAa^p*Ej*)&8Izag^J8r#Ai3GwnF`Su=3 zq--h9{@k??6bF0UWGiYfEeK3{upBst2iO7gbYya`Y;#d=@qmUj(*JISJtJj zPOp^q5)Z_g3PvXu&|Cpql0=gjYizXURs_bv8;-{$G%ehQ_U+MDHa->nQLE~(RBi={ zmUM^YnDeTJT^S{mC)%Litb=IZ=2Qj1xWfYcJb!@-!DQSE>rG+~JjwAza|xe+y@Jt7 z*nq^0vR&r!Pdiy|#z95Yd6`gYvLeNLAL&1$tWn#!&{%S}a8W4mhZ!g%lXq8{{3kDq z-bC^+MNnw&!z*exWDsPIkOTdL+}kh|k&FK9cJ1F=r`cY2bdi_Fuh66#DO3p@f1-5q z@Fy0>5$a2KGmLJbM0V(MF$ku#`3=LnV~GSHi_+7Wu>IPN^>XO!XA8_2o5tkOC{|kY zy@)jtM`9J(G$3E7Cpg?*Q;D|>1)PIOTKn^r9*K!patE|IiDa!Vm$Kuwcv zHy|HtH58g5{fx8KhDH+IviYzoY?3WM@=Rfwkjc^z&L|zD4wL0ct<8mIKdQ#7OE_~dmtY(d%}(CDTVa0j zTyW>TE5qf4+|dhK${UY%^!=Nau^d0iU;W|sVuZmr`{ACbqpaDAw=?bYjCUSTV2gJ5 zzJlVe0GwJuBYb+0~%iSnG-n>_F)&dD_MIwaPX``=o!}ip><>R(}&e z+PbWsu^hevkxB)TX4}fx=}+DHDfH~NPn$-KwU{zg3#WHM2HA6&*0&PW*lvk~D;!nL z%}Oa7^7l&C!^}F2uai|~Lc+bF9WzE1I>ql;i|J}zUOcrB>wu5ozFpIDu}HFw`W%LA zsIJTAro|Z1QzLzj1TXh08K|9my@T{KgY)(n1S?csRBU3uOQn8}`M0?iM))yM+RTWh zp?i9i~`Fe!WpXIYO5|HD$3E`enj4? zOhbNa`w`sAm@ZH;L-)1a`+#uFNf6+~IY|&h>7Li*hI2mqAk6}(NdZoUhW-; zS#SXaE~q%Uxw(0Gnsc0{HTW68!~~dsnBR}P6V7V-McmE2=p+8B*n?r8J1*|RHZXR* zCH0Gla(sJF*9k!3s1oGAa6r2Pz7!dk>iI}qjNej5&HeOzX+?j}{(-Ojj(IFK&!Sv}B311$@S$;ApUt!zNz+l-US@1iujuvA1#Z354juoTKV8mpS)RT}<-sT6& zA$RID)%1T7taK)?V$Qrf%K?MUvSdR--=twDkrNI@@&uX!(5Jl}&dsIo{1M$uxg-6oZpJceKSe$>e*uS@WV8gH}F{%n0UHw>k*z?rna)^F)%fHkrFR zDFO69Jhv}i)lOAd{ld$3%U#@MuQT}yeuOgHkSKE%v#L#wcp1Ss|0vefNSgxnmZ48D z&X6YD^ffW1#Z0>VDCyZ;q8t<3Z$%>WzfjrE$is#3N@=*4oNV?Z1m^dlu2R~oD8PfF z&u4{8A#g0vJ9jnUrL7fV;cn>a-{L&PbvW9hmNy|_IU%v0X=kQ`?@@vALtnC_+XGVu zV^&j46MWVO;P=!f&!*8hv!B#@#rBbZtx7P53FRit4RR*qsY8s^uV`rO!6b;#!W)|C z;;xrOWbrh3BJwV(dy0II$bM~BurW{}LjaDQ0`$A^2mSHP61Y|Md&di|J#Sa%4}p~R z7p!CJuaKsP8;G-?p~AphCCGgd>|A$oVLu$^NN^DX?!o!=FZC}Wf&fNa0V$s|IDPUG zsA}&%lP=4OFN7G2pZK999-x%g!@8jyia=>m0oLAAA$^3Ev_!JM5Rj9VdDs4b55suX5Zq)v5wV_7R8vU^)1Hy^(G5eJ~ST~aAdJ#a=rg-8<>pGcjSrd})4MR8?WN|B)mOoY!}3{TtG!_*s(J38@o40g^B_@SL`$aI z*n3f{h&+y2$M2USHNi?1#o}ceCHIJq}Os{D?@a%PB`)Ne(p{rqMrFrh?wU4X59P1xvWLn zJRb24=zpfjjh3-*ePq4f_GPo^Z!6zEWeYLh4?oKuTlxN9^WNC;NiTBptGi31LH#sH zp{B5$5sH4(%2?0HtYl_d_1Wp^A9@)UnA^jc_+C{D#Z&8Qk~QZ>@SqOv#KFxts5%F0 z<}pf+wfY&EnMQhg5cP@)(3=kG>mVYrw_p(xo$?54X#E(B1cM-!aa*@|tJjQTY@4zf zt%1-Ed1{s-C(tEuuwE)E`;CNNpGBe&dquO}I5()gFp|((B_alL#SbA=7Qq!!Y)#8x z!i{+JwXL{g1+tVb>0I3UwInot=-b%SAg{$q)40p`__rn?j12UXgIscu>3)- zlWE-5?fLS?(&zZU4+z)>@!fv!nvTeQsK$K8fvC5~-9Gnf1v6~mI_Jj^Ud5cLP1mi{ zE0B#={O?U?7w;i<{VY`f~wO>pLD5{z|%6xB`FjXtRLunN~lZ_=7u>4|vn=uX3z zCzZk571OeCj(HCcXo?2zaQum;`n6yBAlP zGatHnT8XbA0?^)@Zj|IEVm&Spv|1`~AZTS>hg_)lU+?y65p5Kjk-=`vkGtbcd;dI) zxW=Lx1um@bou7J`(}NRf-0u86jf2v&6Gre5-rR_~wGemev*m?e=QGH10sd-%@d_2Se zL(+s-(VCNV|7i8J?8QN3b9FydO+MdW~Kb|KEIzOq_*hos4i+Gkl z=d8{}dv(rc2#rl#KOmIxWzT#fC)u15PSMARecWlJL4m@eVMNm%T}9+QL7c2%yuf~k_Wfi!;FUv^Pg4DM zlJm!N&3U!^JgWgveJhY(W5@iZg|ITehCyA6*ZU0x2WQx?ezX1uafa_0Dkv78<-4S~ zCMCS%-winiuFUKv|Md^PjxWG=4Ql0%;IlIQ*qTbwK8%NNN`m-LPEKiR%S$n;wnb{i z5PJwZo*eV*Kv%f($*X+G%;FoJRK<;nggVB192-Zt)~0G|yQAlU^Bfj2U(lV~g4y>v z@d|zgjXCBBmK}PQ++TdshufkTo5Oa1;{wF6S_wV#WFCWVAztps(9#=JR>6^eE8ha` z$d((b7U}<{q<*PEp27t-re^>s7LyWS+-U%^+(3!n>k(V=1tmxnk>5dHB2)=PxCAjN}@Z3k035*THlGH4?s zeo@tl?SV+NWIFjp>D`=QU1dbuIrr}BWBzGPvR; z?J|ev=E1PfWq-kC<(h=wMc$%>m=E_UgaFyj7kwZ1HOunPb!*Q#^WeUUeA4XA-rEa- z8v^6o$Fo=FJXgJQ^{qZhB-Whwr>$4xYFmGojZQq*$p5?sUy0H;M68#*b*nP~b*2a! z3eK-P##Z1F`G2M97aYXi2Sb)c40p9{ZF`J;swLYS3D9q#RiLXXB!x2!Q=z&XU+>xq zXNQV|rD;8=i1C6tLKgH6fa(}*YwJy_}@ zU9jjJl-f{stnDQC=ZU&`G+t9otgqbo=G!sne^S|ILw3(SMqW?Hj2LXKiYW%JarY}z z>oYY9BfO%wvGfeVTo+%@@70%wW)$wu%I@1in9D0MRbVY1G`P*OP^f0t&F_O*GQW1U zl3xAh%E|=+KGu%xO1{ z_myO<%?gQ&q==$fuxF&9WB9*6ZA5#CyTyLgjv)NLS)9?FG8Q>iMh$>a0t@HewRm^@ zf`S4N0$ns^@fDQV78VrP92Xc>JT7!!+H-Ckc*=19Y&~f2;gsPA<<7rjpLZVpE?2g7 zN%Zyq*_L?sT}~iM&&+p;B2?N5&H|MMP+R_or`4;Fvt zRvF0z0U1^=N0ng+b?qh~{MUd$Y*nQTmm>k|0}=Vg#-$D{cu)Ksra*v}sC>|=SsnAv zQ>XG`53{;w)vA1NRtz=38!$yS0sm<6QO8f0z0F*uKmRt$#@aC((zvE77;hdX>ew>J z!$&&oVkyB24EdFQD<<8-In6U6^?l$SQYzJuOQQ(@8uIz=5JOyEkvR4F^wD+E@b%r1 z3ij5gh_J|B!C2d?Cfe$+z0E8~KzRPBB1Ui|@QFx0D> z$^r2=Ib66Z?jBH47eCp@N~G*FSRsx70IfG)3%OfXjyE$Ir!DFZn4xvD&IHgq-koo7N%kx|bsD`~~SY%{OK40MEZ&nrg7 zx5g2nG2DwV+lKgKOQMSy2k~B<{QLwnSEwdFFe<2xGpY&jB{^r0hAxEs%;UwTTS!y* zmdL+tR5Q3#McSA*g|o0wi!VV1K(kAi-*K{-J$xYtTGlTa!Bd#gtS4* z{z1y9BT0@yv$c>m(rKM|=JgGMvvcTYZ}v4dj;nY=UU;eQAA0TDut6&flb1(emr(e-u_wLKlk!IVR}Zp%f8xSHWqO!?H~Wid)Rt=!#R9As&y?bb}jAE z-8s~vR0`-7q&#r~-a}cl4{fB{W5$R!J--I~Z}q2>2yqNeUwp)-+pD&^!+ihWth68< zo@(CC>oJoTbZ*sJde6UkGwCbpTLF0*Zgj7+^jVs_JTP0R8kxytJGDc4(rNiSDnQsW zs%CT(C>poLEC#)F5Mpf>J_0+gaai#?@KFmkAH}nb4GchgHmEwyOil*hJtqJC`wlAs zgVQmJ69~B<8CEGpRN8a<=U+Eg(Kl{D5jKu?#s|S9-fQ={C+|#Q+$#L(K+)qBE366r zWPTFD@4}v2p4<^HNQ@@1yyBSSkb5)`4Tql&iy8t(MVz8w#6m7VB_cUqr2%3rKU zHMVNZ=Ph%cv41=(d5HK65Vs{rIL;wv#Ky1n=k70*9~m8w2d1V0!1J37mh(#cOQnU@ zRzbGA5}pf*DaAVqPGtQdfb`N`p1p9)JRG;gE#A~Ql{5i^N`G+;^Lj#e&*a@a&1?8Tv60(R(Fz;|J{gamhv6Z znLokpehfBBjqR3&x0&opf>T9R*BR&T=1uO2Is@du9WL$~#NVp4X_{&swN!@o?7T~B zo?(=rxtfoeOVK*&DGX?;T+eUxB7ZQM7B6cHjg2@zTA0qKx4*^ChxqW`vZ_;{gz{Y^ z$tNTA>g1x>e7~*Eerc%(Z+w1=zR1~s6+5apzYADr?wuzm0{1JE$-m~EwndC~8cDq7G}z>j zB+m}%!0$YR9PR1$K52e*g@E@2Q)~8gC!U+FL?~$C-|oty`&>=Guc}zzQ7Og|-I_Ac zU$uO9{YDk=OJ~<*ogFkjduYX5bezqyQ^n6oEp4Ve0baY= zvvLAaI2J%F7MOP)lzmBppdk{Dz?6io-UgxNgA;+8tE!3A4AO1zRx+``%js!J%AT@? z?7qQ3^i;Shc%R9Rfz11{CBvt{@M93uI|$z+C>TwN3PqnEniQRU<~Q$*?6wEM?$N|^ zJ7yOYfho^taU?HIcz)sBb7z9|^*3^ zV-DquuXPXL@pOf|R)^SYHsxeNllies9WemzuASUUWA&!rfe%ct!PG|NC4fX<4*c8e zve%l7Mf=j+Xl%5D(C9n$z=- zPLVxj5$25^px^qp7k+d#veki(y@^ikj#4t+F&bLD4K`w2!AqdL{g%W<|Rjt&pQ zy-)(e?HRtm*Z8}|8D`o&js$lzn9h)SOyYw!7-<>G?1DbrpfXo#CG|NR8>E3kO4@`rIg>X`}Z7Y_A^Jj>DA~otQ`Y?Q>8hp3>!Uk|yhsU}NdjF2~Mf$P?IeeEVC z1LN499`*zasj!JpVmT*DFngREQ-%cI(mUzX4Ux8V4@SafZ0>Qy$z;L)UF@lpo!4MBSGu|6q7f^et)! zzx-Tvu~bTYuVjDp=)KCtW~;|oGm-snedbxNwJ4Ab{k@PiBcT!W*#5t_cJoM9Vlu|c zWVKOt;U{kLa?1O!3uN(N>p{`O7M6@HZt~#|OzdJfueZsSvmL-&DxWxTY=PF% z|B1z^vTwi57<;$mYSADnAW&CT^-@f1cGLC4Y?I8YLNNH5JSZwR-ojl4Yhc3m5&T&> z%O5d6WyriDw6e@QTOSPyXymsuh81Owm#mGRAg3T7*Yo*eUra?f!7_GhS{uU!d+8yi z--&+^G`{}$?N=%s|AbGN_&4`n1dRIVu!&4YOEhs3+k$`6&enwRE zjIcH?7QC9%@EY)IH!c~cY6atXU^Nv?f`9w-<&2c|kS=C>=ScFmbl*&Ry26*tq<+ia z+8a(j?q$OMF1aX1xCg_I6)~G9Q#Co2Yil;#%?>sAayQ8$;UA&<`pZVaS-q+`hR6@= zXywey@a8MlbKo`v5FpRwTd&tvaCqfm09zv6cOHsm-ioo1bu)D znHxU%-P_Ij*Zs@=-aK>Uh4v*uh%d{(09+1=sgth6KM^&sgF5#j1nPF5&5O_ zG{$cI@pF&xr+P+LS2gk#&zEKlvuYv)TFnV0S6XGqxcr4}xETR`57CgksE8f|bh=uu zC69MQ(ewdRdt)-LmCS5zn7>nxccDB0;tBeack$joJ|j?!>)VhJ+cP?!>h%_ohF*8x zsTNG${{k^0djEqFIX~LnZ<}G~;IQ5NC+xMK_*`EHga6Z;2wl-Yl&s0X%Y~Q+b3cCq z419dQehG+Mff4lef!^efO!B6mrX%umlHrwDFQw!$Ea-DK+H_iZ>YLBL_m<8axA~?? z_&uv%vV^(Sk3I6tySddkeK{A=+#UNY>pEheC+=drj=?=VEedJ7^6vBhnfu7BeudGua*oK^hX>0Lb|k` z1cL?AY1BCCmaG^^#{>+ZU&IS(;c$SYcB)j4+F2A4wTcWUR70dGc z%p2>VAt#sW&6$ZWY6>!qi=mR_biP+sqbaLvSo0zYEfF6WSX>j+^ge{n7+|7QuwMLC z&7-lF!a<(2YKrYKK?O+|yz#C+s&0r1+N~5&G+^aCxYMjF$9wbGn^hV|lH$GE7VnQ) zTZZyiOA=wa_@0%U(Thh91)(3-FzUy@;6!*nXn6XAP|!L}m2(_9qZBQ&D=|~?3mB3s zC2vqdVdX$v8yo3Q>~l4#{+g?!WpXx?R#h4HKDzKbeLeWANnJf~B~;8#lJ*nzAjvDD z1e%kyCu!uq{gKPH=X8?2LK9TOJE}8G!eA-v6}4! zY{7=U{$MZ&Rqeu#@ErS6pT@G(^ZhY5gBc_FAod6CjpG0jj6@_N=XeHXlpK(T<1EDk z z$ZOC;xpXOO;L!E+%Puze>>3(3jyu}GS?wZO#fANZ_rsm`mg*7cUwguP&o#HKdFv{6 zS1ik!8ac^uq$fBT*VokXiffN$up%}J^20JS)1Qs)m>=NUd)b14I<8x0Q)ETGe_q0*vwn2 z<*R~4L#AJVs6>fO{{e|QCZ2xyES(Y!g{tmXN{)}qW-~=XgXN22Kf^w++t~2ue>T>L z2pui0+9-|H9&Z1CG<^k7R1LWHAq44?knR+a?hqxGmTr&+VM*y&6c9wZJ0zsLYn2A+ z?(Xh}|9toUcV>qf7Ix1$3$yP&&-+AQPNEj6wl=9YQ^WK*8=%7rioy${`crMcNizsI z!U9%j8K0sL=S`tYvIX zSJb2!7R+ePGsv(%0Zd#VH=aYLq-XF;p`Cn(f|~tbu9jmIWzNQrCFrdf7rmCkjy7E! zhPU}6zR-v~D>~Dc>2CxAOL?Ter9yTDm3lli>2{f7=KnTn+=k?7&sih%#rH?F>qY9L z+LFnAQPo(+N;fzY$)TTQ9T9Uppp4XU6`8*i33?8Aq~XM#CdTabcUn1CZ9kr@PAtr%(IB7Kb~m6^m0 z_$fnI^?`c!;OK~B(}6yn&+Gv7g@QaKvSQ(=ZLO^hC!QPrPyI$-1SN$8c7q|tTf)*F zt}ipBY_YsE+)laVQPGZLPW{%Ye)PPVkVbR!7)*~ko(Y%z)OQ0Ya*_pv)cURbl{P6S zH4ZXf;Rr0<^0J5B;bhZghGdv1ysdG|k%~-bw-4aa*-6Z+XF-_S2lV+O!oiO2;>jw@ zS71RMS3-hitfYsh=WM=DZnd?O(`j!sU0h%+@;woeKDom-ZYawS%?1_xVXV1nEvXkJ z!ZSnucOx@J%m<&5-RkZi+r)(344G1If(gEX>4Y;{V~FO>!Jh_Za1wMQW0B+C*sVk< zL1Ppc$pC=Y-A#hH2}VWu`DJ)bLhDP*G81sE2ZI$2-Q3*3-CF6RSNn3gRJz4%)Ftm zQ8VzB`1z|S?+3&4=D`Buq@Hkw>CC9T9UMB_Y5^y852B~Aj22m%>co=LbA6BIV}zR= zjY!!NyoNPn+o#{B?X$6&TEK(5*BL?(ZnXIW63R6of%+gig2F9{@q|?_9??-kha%kD zd~sZSt=^`2Yy3buX76NxDv*CiO{F!c$z<>am`H@4?&vqa**Ce2Sgf14U(r4*XMO%v zKkLV2!vh%aynu?w`&^c)8KMf~{hCmbppAbq>pr>8mVM4&SjLzBIs3gXRV2g4oqk?_ z6dBvek7M6*jeR_%6RX0WFSOIdv~>iPY}p+_5s23{BZ)}h7k~rx=)IIXOdIh!ccioH zD87iIk{jMYGjM>qe_B0`a~nCe&Lo8juZPqURw4*sNQ#(t#x2uLYW2UEk1mSxYHeb4 zjYu7&=d>VhD91y(S)W(ZE~MOU6nb5`{T>z0m8~6vkdaVSHGJ~H8X2lt^s%#P+?tP$ zFor(RtdLuY2?vw?J0U4t*n~X^vMEc&@?`_qxuc9vLq5tM!HA>&xbtpBPdogx8dkvf zln97htjN+?TT1{q2P^CYz?|Mj$H_Vi7s4abl`Sq+SCygEA<@hx#Bk$~2-+*BXn z1wN3d;=tP+Q!Q28C@=#@nG=Rp=!}<&Wx(#XU{c5FO0$cmYQzNmhZ8%pP65uiCx~LHWWG|t+3+GJqBeXIgq3VZ_EL79bFxBs+>@n+1b(yV0xP$V zxen4DR7K+ zSIc`j;WCx9k^bRr9bR4op+RXT(VPvXVTmI1XlXM6k`-*cX;~+;gWK|ypmTVjwbSGk z4F#t{ZP*)NZK5wiA?H5+8}^2zI~oQ z(lwzsl%gTWZt-zrpNsvqn$)6D|AP1T_&SPgtK*aSaErnrL=il1aYqD=eWzNyWouy` z_XeSnX4zpGOqS12~8?nS77q*y5-cUxgPpVW(1<|3SAhX%iS`>adSNztt> zAbve7;rWeEluhC}!QE$DJCEnP6Nzz;)9G4Qwbk&G#r2xRFOP?6|0FuW)Vi9wi@~pk z^svYqL(uDE`U397s6%2Oz!|NML4^?2G~TZfUByx{X7Y9V)+Zykc0*Chq-ha~^jqt{ zI0Eqf{vtO>iY9U3@Zf;@<2TTLD^Cj+0NB>*f!MEpz9*7Opj#DPmfm?Znf}e!8fU|^ zlnVHSZRL2;Sk3s?pf0(z!e~jA&pa`G=68>63>gUqu|i16dblI>yTzLW^sq%@pro(X zegGZL6lznOcN-grQ+xQHv|L|Dh&0@`Hiav=g|W9c=;Rv2QR10QwS2b$QB2%Q&FMtl zBs4ZvIgH*|Yq{oAEtQp@b{*^I#hf=@+O+mf{3Q)h4+^v>lnOIo3iVf*lTJ_2EQy)h z(xc~9jD0Wc6*hX9oe7Dtk1-KSrKhPG$wV=Y@7={GoM7CMJfcr1zPFWpTtrMAm{E zKL1UA?f{x$s-kgAj#>;Rn_Q^xA%afiv0}eGb1R7>Nx8(>jNU@25YJO$TW}};OT&-T z#~6m5M!H`2&%Ei^G$<$j2a(=fLDF< z7yN~z&?P6#Dh5aEcp+kD68v6;_VAzM`Bm_pf!gG+%Nq|mnVkx+2gS}Qr0bs}D_e~d z=MU7cw>s2n175FC7FxpGI)Cp<7otnP5JUxTY6jbxCf}OoMv60CkVdU<-R5q^YY^C* zh?oLPZ{kB|1_Cgks*(3fR=C3MklIC8Hz_9ebQINBqiyzU8DmC zgW|J+mttrO1Cm^y{=9|)B^Y8G!6()UsW}>Ca9HXryp%89na(o&hNuyWsmSY3wT3Cs z0Z&({bGR`oro;iKiUCl7=pI=aBsrZ!!`$V89i{mR@L=dIq z0_2Z`Oqe}0#|?NExO|4rCALw9txu!KM3E%>3U5DF{mqFcyGV1SSZyMD0R&TtzArra zwc(T_J$aJ0ybie;^i<2TJSh0_NDJ@Z4B> z6PGiIwnC;Guo~9MRG;G*4T6=DV|#^K_DO1|_lOmkn6&({&NIu=MbgK-zzgs{XEi^m z$iMHpu3-4qM{G!7%`>ZiunT^Op6)p*5JqUKw)d%(XI+g8veEg;xj{;%km9o^o) zx<-m=co0fAJz zB=^5lz+X<`Rbq-$LvN%|EfQnyHLk&765z?f1GSP5mbHzDYk@^g$_@NU!N@ZD(Q%Xw z>HYtJ$cN8t_+64<%9jV~$qFU3kj}TnkZw`#Ulk%T_W^ufbw)&h9I;}{40mVEGc2ej z;UuP+_fWr7>wCv4D2RsmBH*rqoE#|X0~LMl?uphEvvjIVXja$vzWuVYUWbZ|@6k=^ zBZd2e!`B1@LEEJBIVU+hU_&q!sfawOV_hnnF- z8R?wIFbF2<5bdjMEA@`Sgw}Hi%HRZBKd%n+E9OtXK>WfDfvJe-Ioc%(mk^1hZoEjR z4gIg8ZP_4o=a!{BJ2jO9I0>cm1WR8{?l}i(((yGk zQ!FB7et|{iUd1p*ACQpz^eKCKUpJoDkOH(*Ie#A`L;EicNP`vpQEo-PYZ&0wx@68R zyIQVueG?RTbT!UaRMYb5**_s^Sra%=9V+=IZgXHy5aO!x-Njt*)^ci?^QCAxH{_1Ub7VIuMNgER|TJ%nOwar_e;y7vZMy1tuF!@i={B;0E zYv-VhDVi^xsTh=U<8Bt-iYuIS6-B|DzK^CP!s7Zp^<8Hf@=^Rq;l%po2HxW){E;#H znXRxNF6(ow;(Kf^CO#WNh2PXOI4GhLq8&+0daBjgzW`JKckc=T^3a)&P&e8u2-}mA zcuSnmOtK%&9g2k{(vO8#Aqn|{e;d78&>lh=5b>H#G{>Z_X|EUyGcH=+b=pc|%*ao+ z7)0{m&7&{OdieyVvI=O~d+D(vVbV^~Dxfb{zrC|CVKCK%9Z*EbO>XBCSEi33RHVC6 zN88F3Zo(ptHv^A?u_x=2;=nU^TS4r7nZ9a?c+rReZ^(}U?$i*d-^$;%v7(ig0z%6Q znat*|qVO0+l=SB=J>Y{Mp=FRSVqN*yUAAIS7Z?85T{*|4=)U1(jxIR6Q+*%wt?xR* z{?&?T=p!1uwEA2)x9}>6(y@BOJ2>*C5z=qdOSxD=DPl>3NGt&cljTt1eeY_xn^*=$ zdYBXv31TqW@O5u%p!DkweLC^F6E9;89|u`$HG2>#j)oAw-_|VzM0dOc@5V6qb2QGC zdisZLTC{Uh?1jys{CUD#-t-MiuSnsL<@v%MD|IDfyrzypU%UZFp2{)1!ZW;7jD^q< zF=#)mu;+~{K%Q7cRe1?te3cR-T(=Jbn@CtSM4(Dag?1`4c!i#OaV>usD@-T#=R1JS z!~qqmQe^k_0We2$*Dlgq86r0sPnB9mjcc%xJy2MXWKBs6oh(3wD(|?hh#N*OkA+~J z`T}r;>~pmp;07n)Ub@f^QdBRH?mrpgkA9<@hBPJG{;SInEz~dMiq z3SX1)7be{3fL0*>LoykyTb;6|#ys!RhMYf$=Ir{5+F4g*xx*DzCDJMp_!jCbi(u`lQC3d_4 z#&Ox5g!AD50y4OrGbgL;0eyx0EfSCsvxm3*-kEQfByfn@H6bW}`lWn;LVL};nr5tk z%^2P-C2V$M%HCtY?&R)vm!ck#SPct0(AgM`M;DgM6KBG2dcFX7d_Qijr+jvhdR`;L zH9fAbRPJepUVE<|qd%&|Z0$)93HXU(OC0pJ7vw1XoKutkBwGV@cdws6 zo~rWdNJTu4$1MU zZ?aL)1`Vt4T+rG0W#x^O;&qm-=otwEOADpPjK@bSm+)fgxu`v>LACZ+WwBOqsa6<$ zQ|B)TsUnkPp4#rES7+`0qxhybz55wR1?swZ8Q5ewO!i-OR*%OkQ(E78>-j-{R;GES z=~U7={i!2bBI2;Zm-cDm7g2DlV`8~Zg3y{tG+@6&WsdE`&0VU$r$61OB;$efs}~Jo zM~%JB5dQMxjV^Sl1;U10Gcf_JcWET|JcycT0&{~L9Lmef#~(7qeZAh2fCbniXcEba zJIuMCnragv7-P}S`^p$);|ecr`k(L2EG#x>D$R_KjEq%2O5h17clvE0yfpITlRyWE zu-Zp&-U2JvQ2P}^o-__xE6qSL^4CwF3r>HjEAsDEti+c29B0r9>dmpSP-zGvJjWWX zXX{91zbNTgzI^z~bfJp&3cOz7GI_UW;03h1aN#Ev&VoZm zg0=+nB=^bdWf8+j&hJAiFR@m>1$eVNewI2$IeL_mplUcAVacTgJ1(=A*&@-z)=(s= zk~X)TJAs<~%ruC-uUb(m9FZC+@j%utz{>ZSD?70<8KK`js$!9j5SHk3Y>&mqHVO3d zrQ6am{;STYNm7pTpmA+lNK4!!T=sV1-m6CoH5|8EL&7{oJ}dQ9D=Zr zIpJ@(Lx;x}tlW&JoifC1I!(p}s~cel;G?_iGh6xb!oqafiAag~az@cV)S~Rs77>Lv za0dr-vHV#GGodDV({h3VcG9{9r|pm7AmBY{Vd+Sgo6j_v^;#ZUyqpq8;Q(?M-)j^$`dM;x!S zQ5Wo_YYCJJ@P*?TPtlyutvh|8L`c`CA?Ys-03>K{eJ*K3E@ht3hn(i+Rm+KxQCBxo zCk|7l0H2lo@W0K41i=Rw(088Mcnzsi*8!w&g-z_ZS1c#56M{IL&rLd~5Q(KC8z2fH zeXQBU!rB0m=v+v-^nuH`X6xj&IQ0d!s|VdvyHpRxb=7R+A3{KH!Rn?|G*I481Q>qC z4C~eRegPx9sF^|dxvB|3M@DlF0<|$Sy8=!gdg4X#rawD%c=%z!2%uy}8fVO^2*DZ8 z&T3bmIuJzjayxR`$m{@BXI{g376AHIgL^oqYV|ccBODu`ozCz-_bjYwpn|QM0rE?( zDTEy=z_Z6Ek4lm)2-lq*6+-Jmm!IvTt!`?uwQ zYSlnaNvd#(ja{kqz?Etko0IP(T4Jo}UOX-#ejubE>_OEy-+Z z*A3fC(4eadtrw_-FP8O)6s9iWWpyg;yQPb=XmXl@f7^`bsKtz{RQaA?YGSM2vo`K_ zWXTgIoVQD8*#iqTG0{(Q>yrx|##W*nnlrBAC&E8}0t=Zbl_wq8Xl0N72MD+lS-*-g zB~P5RpDJP`N*?_8`#{RRApIn{u>W!SYQz0Ev*km&Oq+W4i)SkbtXN{qDcnU9z+=>; zB~h`f-AS&v9dG@_=IAZ<`r9W&QOA_=l_j$@S{iijIr{jqRw=K z7q@1<&^fnCoHkD+|CNsudF(psJC(nMxdlg;UO&0;&m(%w#&n6%gFvCc-{?SDw7uxL zda(QrJ?M|gTd-zg&b%A6D9JQ0=4*rp?s>HuRqE7uL4V>gL}7HLM)O*Hjo;k7W6sp;CgzV!iP56opyU=To~i0ZRebNp*WZr}h?7uEnU8@C zm~-3I>TR68%+tr?q}*J&k9tYE>QQn4-QJWECtE6SmXbgj2vHs6dOpig>{)$>f~-j0eYoc z;0`SrBqF;%%Ev?OM^kZ;OF(EjHZ}&bhV}D#K?r*F)VFR0PA43VHg;g)(EF zji^>9&PpzZ_pI*ET}EJhWIOtMk8d=`nsN+zH8exkMtnp@0tseDd@ZIWR4?&)KI5jN z=3xJ#+8;P=!)dYY6rwP29Q~sOQX6%QW3FA-Pbct>=k0>}H%QWV@WDr{FN~LjpZ4|6 ztefJ!qKqPExS;%Wb^iw2Pg}kBPQ}7+u6=RfI0}~zv8LNWWzMl-Gok{SSFPW3?`n=I zihIJsS)8#})C2C5MlzcgtA!igazz#pXtVx?w;|2_ewn^**>kPz?80uEmG&Kgbxp)x zv1y4LL|Qd^O73hUUZ;%!8Ff*vO_^brH_k<)ztqA5_?#WAJL6>*5HZoBg4#$LcrHoc zv<$x$4|NEdTw$XH(rsjF(T?}OHJDN(q`UdD-POAoS+X-Z<1bppzH4P;DD@N>YX`bD z=*o9y=6*PGd@n=;NhZNKyfxC_!4uehlSr4Hxn@=%)EuXF9}$?Lc>Qcshz>_owGrNK z=$kfE)2}D6ldqfB7yY#{knwD}w}Fj&{&dl74rqHzzd*FHesQ7 z!;M|@V^PNOWo|#ZA*R9pt-`*(>&NF&iX`Ige4|Kz{F_U!hh>4Cvhzjd^ArLjmv6*1 z4LC3&E6j3_Co5}WqS|yvq=ur6$j_(gZ@m7Xan7SJW_^p3A%kr%-=+SLZf)Sg!HjCi zX!v7mP~I7y5KqYFNw3-F;4!Ti1ju2O#it>xfIvci3&G>b&vYmUgg{K0=gK2xPOSMJ;Iw zFGHogVKc2lP^^i=QDv`(zXIl%>2yURm}8!5G!0~JRKF=|_@m2She_q}^l=V)^LBSW zW!1N%p1m=@cx#~)GhCY8%SkMPjLnrw5Ra?slJky|fE^IS2J}Py@n9}}-(B6Nni1XY zg~!)hz67YWuiy)tnJk28=gpy@z+$x1wn_+w5SSU7bBVnvPg}nfz7e5hycTBXh~mOy zPijAES(f>5x}C_199tE9V!V$D_NadUE$6^k;oj@CxceafOGEGD0Aj8m5_5_OXGE)_V~YvA3Eb%<9;%%4(592-uj1i zk9Lzs$(<43EX5ZWJVZGX2R3NLlNEa%(-L^AX6?$SLFB}XqwzD};?pMt_|Q;<#bd1= zd+MMTm|H#%YW}GC(3-|&10ocJBXbVfUII8-$u`?CDdCnbmCa{Ow}8*69G|AgXrCFHx`3b+&9f3b3cD_ zKM;%E!u|@~v>zix;S}wl>Yfa6fZ-v=sVD2oj-&BbghPNfjW;^MP2RLf;4}}7@!|?0 z!D~yJ%RjRTk<7q`(V;~1HM>o5Mibe5p&)sb| zZrPED?VH{JKOO(@V0+|DBI31=m>+{HaNuZ0fa8}qf-OLGAqHe(EVMJmzZm2U8d^Kd z=rBfG*z{^46^;a{>etIi6)~cl342_+<}JEAxAfW@Uq|jKN4Hak@jd?{(#$ zo9?^{z&lYctfOVb`FTVlun)kbO`=narP|3GfUUec(F(rD17EcrZUN&HF#rcLDgW`z z9dZd-HoMf<8Vw8gsKnDZRX(s?yiUmF##0b!)M^yci*%r@Fwg$D-Kc9L403uWc53<% zYx(V@SoBcQD@Gjk+o=E30-Wy4Eac~U_K9xi(iXhTF?CTx5agUxhv)9%#>j+#nxmy_ zt-Pj}X{W6WS*bd5%jqfKHM4CJ(O&hRvB==L6a_M|= zDmWESfIT}>B{Idlg8}N6=Nv->ArZ$Vl@xdEOWM@w)Y;jP1GUYTuivVD3FJWKfT``+ zIaN=FFiG;6T3vIi7zuzM_>EMGoSb*4Z|C3Wfl7?TwL5%W!=B5o2B%Im0pLFp`UJwzJ_&}bpk8oJlAX6aiAjD*#+IsxNv!A4} zt7NsKA;bM|0GXgX$7^hMTWCdUQ8{Lsvg`BP7Ri&jlWZdP4l7+=E}vt41_3eu0O=ka z%2z~UDvb=azZ>3(JjTa}6$q^dPN7rkwU~OmAVJh+7tSzNb`!;bpFo|3q{7&TGgUO} zBu5fxeJ8D*7O|8Y-bF9{caJX z?&?xOE#i8XJx=I_rt{K(T?fz%4Fzj`C7$dlf_*!1RWO_iS(bpY5?LMS@TrUd&wb>V`OhJ8)N70 z94L24y1YrbfUnbkp4a*%C#k|an8}-pv}Upr^>RQcy%h;fIN7Kj?7%Fe{fn2d(#R zrMwKxqKp=y_r!pNqz_uw*VS2CS(TOxV5O;2WZNT_n`e&gy8h+?(Tyl2PxnE6Y#%+S z_soF5}Rq z^Arv!0uhP$FE8Q)XqE=$iOa{+wzV~nFNMbb{rfjktI8TbH9gIfjCmRBOb-GxFulW$ zAG9J%PWOW8PhjjW3|g=Mh6vQ*vqz2W4NXlES=7;UdABcv;pDtCAjv9~Ejg3IWl8aG zcSjLF3`Z{;oT=Hb62Wj;PtW8j8*8Ny^XYhb3trOEK7Po*lK+nMq-FWDT9VaA9< zhps0!Bu?N?*xF3!(2cwb2TJF^gcBy#xIkNIwV0a!e8=FGkE z1>Y77^Q}yr#k*5ZQW^D$dncWS%NBQ4`__8jxurR;>Je1)tE5^&i?DOjSQZ-5(2_z? zD@NPOm9J#J5vNN=$#nHR7sw~e;7}9r!GSmDnZnzzS|?xSi7kaR145Qdiy;UtF`|F& zq^JEVqU*{5~zKe>1yhd1|1CHr_wb~|(ykgy3ZcI)&m-IhjwqK{XnBh`1I`DYPrQbeS zJmnC(hpxI|Ddwmv=Er3^3-?XcAcI}C`bH|HYixFeP<-yxhhqwWDgaP!{*HC*-SW>F z#T|0OJ4-#XUM0wmVrQ?wr=&aEVR;c`ySeTVELwh>PWo>YGKwfikiw%Eln$Ldp~{X4 zsrNyQl8~eBJh&L+g}mDNxSCkp22HM_@9eAWBm~Um3;dLpxsYQl3idM6HYdvUS&hEU zk=N7f5W0-h*6`dqGy$Hrde#f%9cT4aOWI;J1V^7^y$0kg+W5=q!Ve`_f&s-FL}AXs z^#LW@?JTV#tGlIMKDNh7;Om^s+>U#&$f&h{>THXx&?X@F+jn8cz^0^iww)N>qS0lY zQ1K;`Z2H=DkG9DoGU{ZOO%0)8z;uEB-Dc59ozNUNeoEl>dnhKCV76>1rx1{k0x$Ji zP!h_~vEYUA6~3HO=a-xBl-%h;3b9pSEf%#$ElWUGYitvENr9hQ-`J=dd9C~BCmnys z;Fsmpcw5{``7`@6%K89A)s5hv?z<#dKIMsVx99UTrN-A{fWNf$-zh4&7AN4rl)KXN z)}bw=TDdy6ODtGBEs8`l6q6&(@mmESz~qAu+kR#N*sGv#uO5o!#Zl};RzX(X@GbdE zyy-~cRV9Yu>YaSDl6=j{!krkIne*vdLF|JVpH%5z4IiEU*2Tk1R^r+ru;vmgFheXRf#8dOsIT`m6d+lns{O zKE$mG9YlUyXjl!jQV-IXq!L62A45KEmG0Q%#T(n9qUM~np)_XP{3j;Hp1ldGsx}57 z4I8VT34t6QY?b2cG?2CdJ&Dn{UI_TXfqe7@TzJw8*lZlB#yB_WA$;L%!s_`aZC8)S z2|z0_4|F$2wB^NzbAFJewb^e191y-~S5Vh^(G6KKdeszzZ=qhZ=Y;o5YMjP~e{onJ zLgg%}vSYep>Eoalx!VKhNyfazW2pAM*iC>pT#nBpz-@Sfs< zju_^n0VeNl$3ORfj^vnm7`UB3e*3hx{?O>6U1snY@BdURaZ4cKw?ppy-{dn6>!pD- z$~aEV$&=S0W#o#+*$2zym;_p*#VD&m+XLlG!>caovkhNH(Nwm`eXFPeW^K(%%}{JS zLeIw{J{Uq?8nDLO*3Mn-PZt9JjUcx8AD0oJ<#?(z71JM-tbq+f35khl*!Xcw0`~Hb zvcZ3mxk}Yh^L*&%w} zF4{f^wQ!wl5C`QqOHIO2EV2dTG)@ASwqQgan6?Kdg;($id5i?m6>_5G6~=&LZzV>R z?^K=p`|RQ(D5UGOjjj>}QD+=9+JG^t1R;tsQH!N}{j}1oN6tZ6h@Yj9k)qbGy}h