From c3459040315a70c49af8b150b300f50536cd425c Mon Sep 17 00:00:00 2001 From: Niko Date: Wed, 30 Aug 2023 15:46:39 +0200 Subject: [PATCH] initial commit --- .idea/.gitignore | 8 + .idea/Fanuc_ROS1_ROS2.iml | 10 + .../inspectionProfiles/profiles_settings.xml | 6 + .idea/misc.xml | 4 + .idea/modules.xml | 8 + README.md | 443 ++++++++++++++++++ fanuc_licenses/license_nuc1.data | 1 + fanuc_licenses/license_nuc2.data | 1 + imgs/landscape_full_interface_ros1.png | Bin 0 -> 84422 bytes imgs/landscape_full_interface_ros2.png | Bin 0 -> 70539 bytes imgs/operation_mode_one_nuc.png | Bin 0 -> 35937 bytes imgs/operation_mode_split.png | Bin 0 -> 75550 bytes imgs/operation_mode_two_nuc.png | Bin 0 -> 39502 bytes imgs/rviz.png | Bin 0 -> 159568 bytes .../fanuc_msg_translator/CMakeLists.txt | 205 ++++++++ .../config/params_bridge.yaml | 59 +++ .../config/params_fanuc_1.yaml | 3 + .../config/params_fanuc_2.yaml | 3 + .../launch/fanuc_1.launch | 5 + .../launch/fanuc_2.launch | 5 + .../fanuc_msg_translator_fanuc_1.launch | 64 +++ .../fanuc_msg_translator_fanuc_2.launch | 64 +++ .../launch/fanuc_pair.launch | 6 + .../fanuc_msg_translator/package.xml | 68 +++ .../fanuc_joint_states_converter_node.py | 38 ++ .../scripts/fanuc_payload_converter_node.py | 101 ++++ .../fanuc_read_single_io_converter_node.py | 51 ++ .../fanuc_robot_status_converter_node.py | 57 +++ .../fanuc_trajectory_converter_node.py | 230 +++++++++ .../fanuc_write_single_io_converter_node.py | 0 .../fanuc_msg_translator_msgs/CMakeLists.txt | 213 +++++++++ .../msg/FanucIOState.msg | 15 + .../msg/FanucPayloadNum.msg | 3 + .../msg/FanucReadSingleIO.msg | 12 + .../msg/FanucRobotStatus.msg | 32 ++ .../msg/FanucRobotStatusTriState.msg | 23 + .../msg/FanucTrajectoryConverterCancel.msg | 3 + .../msg/FanucTrajectoryConverterQueue.msg | 3 + .../msg/FanucTrajectoryConverterQueueItem.msg | 7 + .../fanuc_msg_translator_msgs/package.xml | 63 +++ .../fanuc_control_panel/__init__.py | 0 .../fanuc_control_panel_connector.py | 92 ++++ .../fanuc_control_panel_gui.py | 112 +++++ .../fanuc_control_panel_status_viewer.py | 97 ++++ .../fanuc_control_panel_trajectory_queue.py | 64 +++ .../goal_point_generator.py | 45 ++ .../fanuc_control_panel/my_first_node.py | 27 ++ .../launch/control_panel.launch.py | 26 + .../fanuc_control_panel/package.xml | 20 + .../resource/fanuc_control_panel | 0 .../fanuc_control_panel/setup.cfg | 4 + .../fanuc_control_panel/setup.py | 32 ++ .../test/test_copyright.py | 25 + .../fanuc_control_panel/test/test_flake8.py | 25 + .../fanuc_control_panel/test/test_pep257.py | 23 + .../fanuc_web_connector/__init__.py | 0 .../fanuc_web_connector/replay_manager.py | 307 ++++++++++++ .../trajectory_composer.py | 53 +++ .../launch/web_connector.launch.py | 28 ++ .../fanuc_web_connector/package.xml | 20 + .../resource/fanuc_web_connector | 0 .../fanuc_web_connector/setup.cfg | 4 + .../fanuc_web_connector/setup.py | 31 ++ .../test/test_copyright.py | 25 + .../fanuc_web_connector/test/test_flake8.py | 25 + .../fanuc_web_connector/test/test_pep257.py | 23 + .../fanuc_crx_description/CMakeLists.txt | 7 + .../launch/fanuc_1.launch.py | 95 ++++ .../launch/fanuc_2.launch.py | 95 ++++ .../meshes/collision/base.stl | Bin 0 -> 8784 bytes .../meshes/collision/j1.stl | Bin 0 -> 47884 bytes .../meshes/collision/j2.stl | Bin 0 -> 48084 bytes .../meshes/collision/j3.stl | Bin 0 -> 50484 bytes .../meshes/collision/j4.stl | Bin 0 -> 24184 bytes .../meshes/collision/j5.stl | Bin 0 -> 31384 bytes .../meshes/collision/j6.stl | Bin 0 -> 11984 bytes .../meshes/visual/base.stl | Bin 0 -> 302584 bytes .../meshes/visual/j1.stl | Bin 0 -> 203684 bytes .../meshes/visual/j2.stl | Bin 0 -> 318784 bytes .../meshes/visual/j3.stl | Bin 0 -> 208384 bytes .../meshes/visual/j4.stl | Bin 0 -> 131284 bytes .../meshes/visual/j5.stl | Bin 0 -> 161184 bytes .../meshes/visual/j6.stl | Bin 0 -> 160384 bytes .../fanuc_crx_description/package.xml | 18 + .../robots/crx10ia.xacro | 183 ++++++++ .../fanuc_msg_translator_msgs/CMakeLists.txt | 34 ++ .../msg/FanucPayloadNum.msg | 3 + .../msg/FanucRobotStatus.msg | 32 ++ .../msg/FanucRobotStatusTriState.msg | 23 + .../msg/FanucTrajectoryConverterCancel.msg | 3 + .../msg/FanucTrajectoryConverterQueue.msg | 3 + .../msg/FanucTrajectoryConverterQueueItem.msg | 7 + .../fanuc_msg_translator_msgs/package.xml | 27 ++ .../fanuc_crx_description/CMakeLists.txt | 7 + .../fanuc_crx_description/README.md | 5 + .../launch/fanuc_1.launch.py | 93 ++++ .../launch/fanuc_2.launch.py | 93 ++++ .../meshes/collision/base.stl | Bin 0 -> 8784 bytes .../meshes/collision/j1.stl | Bin 0 -> 47884 bytes .../meshes/collision/j2.stl | Bin 0 -> 48084 bytes .../meshes/collision/j3.stl | Bin 0 -> 50484 bytes .../meshes/collision/j4.stl | Bin 0 -> 24184 bytes .../meshes/collision/j5.stl | Bin 0 -> 31384 bytes .../meshes/collision/j6.stl | Bin 0 -> 11984 bytes .../meshes/visual/base.stl | Bin 0 -> 302584 bytes .../meshes/visual/j1.stl | Bin 0 -> 203684 bytes .../meshes/visual/j2.stl | Bin 0 -> 318784 bytes .../meshes/visual/j3.stl | Bin 0 -> 208384 bytes .../meshes/visual/j4.stl | Bin 0 -> 131284 bytes .../meshes/visual/j5.stl | Bin 0 -> 161184 bytes .../meshes/visual/j6.stl | Bin 0 -> 160384 bytes .../fanuc_crx_description/package.xml | 17 + .../robots/crx10ia.xacro | 5 + .../urdf/crx10ia.urdf.xacro | 233 +++++++++ 114 files changed, 3905 insertions(+) create mode 100644 .idea/.gitignore create mode 100644 .idea/Fanuc_ROS1_ROS2.iml create mode 100644 .idea/inspectionProfiles/profiles_settings.xml create mode 100644 .idea/misc.xml create mode 100644 .idea/modules.xml create mode 100644 README.md create mode 100644 fanuc_licenses/license_nuc1.data create mode 100644 fanuc_licenses/license_nuc2.data create mode 100644 imgs/landscape_full_interface_ros1.png create mode 100644 imgs/landscape_full_interface_ros2.png create mode 100644 imgs/operation_mode_one_nuc.png create mode 100644 imgs/operation_mode_split.png create mode 100644 imgs/operation_mode_two_nuc.png create mode 100644 imgs/rviz.png create mode 100644 ros1_noetic_core/fanuc_msg_translator/CMakeLists.txt create mode 100644 ros1_noetic_core/fanuc_msg_translator/config/params_bridge.yaml create mode 100644 ros1_noetic_core/fanuc_msg_translator/config/params_fanuc_1.yaml create mode 100644 ros1_noetic_core/fanuc_msg_translator/config/params_fanuc_2.yaml create mode 100644 ros1_noetic_core/fanuc_msg_translator/launch/fanuc_1.launch create mode 100644 ros1_noetic_core/fanuc_msg_translator/launch/fanuc_2.launch create mode 100644 ros1_noetic_core/fanuc_msg_translator/launch/fanuc_msg_translator_fanuc_1.launch create mode 100644 ros1_noetic_core/fanuc_msg_translator/launch/fanuc_msg_translator_fanuc_2.launch create mode 100644 ros1_noetic_core/fanuc_msg_translator/launch/fanuc_pair.launch create mode 100644 ros1_noetic_core/fanuc_msg_translator/package.xml create mode 100644 ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_joint_states_converter_node.py create mode 100644 ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_payload_converter_node.py create mode 100644 ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_read_single_io_converter_node.py create mode 100644 ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_robot_status_converter_node.py create mode 100644 ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_trajectory_converter_node.py create mode 100644 ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_write_single_io_converter_node.py create mode 100644 ros1_noetic_core/fanuc_msg_translator_msgs/CMakeLists.txt create mode 100644 ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucIOState.msg create mode 100644 ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucPayloadNum.msg create mode 100644 ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucReadSingleIO.msg create mode 100644 ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucRobotStatus.msg create mode 100644 ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucRobotStatusTriState.msg create mode 100644 ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterCancel.msg create mode 100644 ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterQueue.msg create mode 100644 ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterQueueItem.msg create mode 100644 ros1_noetic_core/fanuc_msg_translator_msgs/package.xml create mode 100644 ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/__init__.py create mode 100644 ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/fanuc_control_panel_connector.py create mode 100644 ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/fanuc_control_panel_gui.py create mode 100644 ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/fanuc_control_panel_status_viewer.py create mode 100644 ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/fanuc_control_panel_trajectory_queue.py create mode 100644 ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/goal_point_generator.py create mode 100644 ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/my_first_node.py create mode 100644 ros2_basic_demo_gui/fanuc_control_panel/launch/control_panel.launch.py create mode 100644 ros2_basic_demo_gui/fanuc_control_panel/package.xml create mode 100644 ros2_basic_demo_gui/fanuc_control_panel/resource/fanuc_control_panel create mode 100644 ros2_basic_demo_gui/fanuc_control_panel/setup.cfg create mode 100644 ros2_basic_demo_gui/fanuc_control_panel/setup.py create mode 100644 ros2_basic_demo_gui/fanuc_control_panel/test/test_copyright.py create mode 100644 ros2_basic_demo_gui/fanuc_control_panel/test/test_flake8.py create mode 100644 ros2_basic_demo_gui/fanuc_control_panel/test/test_pep257.py create mode 100644 ros2_fanuc_web_connector/fanuc_web_connector/fanuc_web_connector/__init__.py create mode 100644 ros2_fanuc_web_connector/fanuc_web_connector/fanuc_web_connector/replay_manager.py create mode 100644 ros2_fanuc_web_connector/fanuc_web_connector/fanuc_web_connector/trajectory_composer.py create mode 100644 ros2_fanuc_web_connector/fanuc_web_connector/launch/web_connector.launch.py create mode 100644 ros2_fanuc_web_connector/fanuc_web_connector/package.xml create mode 100644 ros2_fanuc_web_connector/fanuc_web_connector/resource/fanuc_web_connector create mode 100644 ros2_fanuc_web_connector/fanuc_web_connector/setup.cfg create mode 100644 ros2_fanuc_web_connector/fanuc_web_connector/setup.py create mode 100644 ros2_fanuc_web_connector/fanuc_web_connector/test/test_copyright.py create mode 100644 ros2_fanuc_web_connector/fanuc_web_connector/test/test_flake8.py create mode 100644 ros2_fanuc_web_connector/fanuc_web_connector/test/test_pep257.py create mode 100644 ros2_foxy_core/fanuc_crx_description/CMakeLists.txt create mode 100644 ros2_foxy_core/fanuc_crx_description/launch/fanuc_1.launch.py create mode 100644 ros2_foxy_core/fanuc_crx_description/launch/fanuc_2.launch.py create mode 100644 ros2_foxy_core/fanuc_crx_description/meshes/collision/base.stl create mode 100644 ros2_foxy_core/fanuc_crx_description/meshes/collision/j1.stl create mode 100644 ros2_foxy_core/fanuc_crx_description/meshes/collision/j2.stl create mode 100644 ros2_foxy_core/fanuc_crx_description/meshes/collision/j3.stl create mode 100644 ros2_foxy_core/fanuc_crx_description/meshes/collision/j4.stl create mode 100644 ros2_foxy_core/fanuc_crx_description/meshes/collision/j5.stl create mode 100644 ros2_foxy_core/fanuc_crx_description/meshes/collision/j6.stl create mode 100644 ros2_foxy_core/fanuc_crx_description/meshes/visual/base.stl create mode 100644 ros2_foxy_core/fanuc_crx_description/meshes/visual/j1.stl create mode 100644 ros2_foxy_core/fanuc_crx_description/meshes/visual/j2.stl create mode 100644 ros2_foxy_core/fanuc_crx_description/meshes/visual/j3.stl create mode 100644 ros2_foxy_core/fanuc_crx_description/meshes/visual/j4.stl create mode 100644 ros2_foxy_core/fanuc_crx_description/meshes/visual/j5.stl create mode 100644 ros2_foxy_core/fanuc_crx_description/meshes/visual/j6.stl create mode 100644 ros2_foxy_core/fanuc_crx_description/package.xml create mode 100644 ros2_foxy_core/fanuc_crx_description/robots/crx10ia.xacro create mode 100644 ros2_foxy_core/fanuc_msg_translator_msgs/CMakeLists.txt create mode 100644 ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucPayloadNum.msg create mode 100644 ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucRobotStatus.msg create mode 100644 ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucRobotStatusTriState.msg create mode 100644 ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterCancel.msg create mode 100644 ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterQueue.msg create mode 100644 ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterQueueItem.msg create mode 100644 ros2_foxy_core/fanuc_msg_translator_msgs/package.xml create mode 100644 ros2_humble_crx_description/fanuc_crx_description/CMakeLists.txt create mode 100644 ros2_humble_crx_description/fanuc_crx_description/README.md create mode 100644 ros2_humble_crx_description/fanuc_crx_description/launch/fanuc_1.launch.py create mode 100644 ros2_humble_crx_description/fanuc_crx_description/launch/fanuc_2.launch.py create mode 100644 ros2_humble_crx_description/fanuc_crx_description/meshes/collision/base.stl create mode 100644 ros2_humble_crx_description/fanuc_crx_description/meshes/collision/j1.stl create mode 100644 ros2_humble_crx_description/fanuc_crx_description/meshes/collision/j2.stl create mode 100644 ros2_humble_crx_description/fanuc_crx_description/meshes/collision/j3.stl create mode 100644 ros2_humble_crx_description/fanuc_crx_description/meshes/collision/j4.stl create mode 100644 ros2_humble_crx_description/fanuc_crx_description/meshes/collision/j5.stl create mode 100644 ros2_humble_crx_description/fanuc_crx_description/meshes/collision/j6.stl create mode 100644 ros2_humble_crx_description/fanuc_crx_description/meshes/visual/base.stl create mode 100644 ros2_humble_crx_description/fanuc_crx_description/meshes/visual/j1.stl create mode 100644 ros2_humble_crx_description/fanuc_crx_description/meshes/visual/j2.stl create mode 100644 ros2_humble_crx_description/fanuc_crx_description/meshes/visual/j3.stl create mode 100644 ros2_humble_crx_description/fanuc_crx_description/meshes/visual/j4.stl create mode 100644 ros2_humble_crx_description/fanuc_crx_description/meshes/visual/j5.stl create mode 100644 ros2_humble_crx_description/fanuc_crx_description/meshes/visual/j6.stl create mode 100644 ros2_humble_crx_description/fanuc_crx_description/package.xml create mode 100644 ros2_humble_crx_description/fanuc_crx_description/robots/crx10ia.xacro create mode 100644 ros2_humble_crx_description/fanuc_crx_description/urdf/crx10ia.urdf.xacro diff --git a/.idea/.gitignore b/.idea/.gitignore new file mode 100644 index 0000000..13566b8 --- /dev/null +++ b/.idea/.gitignore @@ -0,0 +1,8 @@ +# Default ignored files +/shelf/ +/workspace.xml +# Editor-based HTTP Client requests +/httpRequests/ +# Datasource local storage ignored files +/dataSources/ +/dataSources.local.xml diff --git a/.idea/Fanuc_ROS1_ROS2.iml b/.idea/Fanuc_ROS1_ROS2.iml new file mode 100644 index 0000000..74d515a --- /dev/null +++ b/.idea/Fanuc_ROS1_ROS2.iml @@ -0,0 +1,10 @@ + + + + + + + + + + \ No newline at end of file diff --git a/.idea/inspectionProfiles/profiles_settings.xml b/.idea/inspectionProfiles/profiles_settings.xml new file mode 100644 index 0000000..105ce2d --- /dev/null +++ b/.idea/inspectionProfiles/profiles_settings.xml @@ -0,0 +1,6 @@ + + + + \ No newline at end of file diff --git a/.idea/misc.xml b/.idea/misc.xml new file mode 100644 index 0000000..f9fa219 --- /dev/null +++ b/.idea/misc.xml @@ -0,0 +1,4 @@ + + + + \ No newline at end of file diff --git a/.idea/modules.xml b/.idea/modules.xml new file mode 100644 index 0000000..255daa3 --- /dev/null +++ b/.idea/modules.xml @@ -0,0 +1,8 @@ + + + + + + + + \ No newline at end of file diff --git a/README.md b/README.md new file mode 100644 index 0000000..95b08d8 --- /dev/null +++ b/README.md @@ -0,0 +1,443 @@ +# CPS Hub: Fanuc CRX-10iA Framework + +## Installation of the core packages + +The following software needed to be installed on the Intel NUC: + ++ Ubuntu 20.04 ++ ROS-1 Noetic (from binaries) ++ ROS-2 Foxy (from source) including a separate initialization of the ROS-1 Bridge ++ Fanuc ROS-1 Interface (Fanuc Driver) + +### ROS-1 Noetic +The installation of ROS-1 Noetic is the most convenient option as it can be done using binaries. The following steps need to be executed in a bash terminal: + +``` +sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list' + +sudo apt install curl + +curl -s https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | sudo apt-key add - + +sudo apt update + +sudo apt install ros-noetic-desktop-full +``` + +To use ROS-1 in a bash terminal, the setup file must be sourced. This must be done in each new bash terminal window. + +``` +source /opt/ros/noetic/setup.bash +``` + +### ROS-2 Foxy + +Installing ROS-2 Foxy requires more steps because it needs to be installed from source. This installation method is necessary to set up the ROS-1 Bridge for custom message types. The following steps must be followed in a bash terminal: + +``` +sudo apt update && sudo apt install locales +sudo locale-gen en_US en_US.UTF-8 +sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8 +export LANG=en_US.UTF-8 + +sudo apt install software-properties-common +sudo add-apt-repository universe + +sudo apt update && sudo apt install curl -y +sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg + +echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null + +sudo apt update && sudo apt install -y libbullet-dev python3-pip python3-pytest-cov ros-dev-tools +python3 -m pip install -U argcomplete flake8-blind-except flake8-builtins flake8-class-newline flake8-comprehensions flake8-deprecated flake8-docstrings flake8-import-order flake8-quotes pytest-repeat pytest-rerunfailures pytest +sudo apt install --no-install-recommends -y libasio-dev libtinyxml2-dev +sudo apt install --no-install-recommends -y libcunit1-dev + +mkdir -p ~/ros2_foxy/src +cd ~/ros2_foxy +vcs import --input https://raw.githubusercontent.com/ros2/ros2/foxy/ros2.repos src + +sudo apt upgrade + +sudo rosdep init +rosdep update +rosdep install --from-paths src --ignore-src -y --skip-keys "fastcdr rti-connext-dds-5.3.1 urdfdom_headers" + +cd ~/ros2_foxy/ +colcon build --symlink-install +``` + +In any bash terminal, the ROS-2 setup file must be sourced if you intend to use ROS-2. + +``` +$ source ~/ros2_foxy/install/local_setup.bash +``` + +### Overlay Workspaces +To install the additional packages, overlay workspaces are needed. + +``` +source /path/to/noetic/setup.bash +cd ~ + +mkdir +cd +mkdir src + +catkin_make +``` + +In another bash terminal: + +``` +source /path/to/foxy/setup.bash +cd ~ + +mkdir +cd +mkdir src + +colcon build +``` + +Now you can place the ROS-1 and ROS-2 core packages from this repository into the "src" directories of the overlay workspaces: + ++ ros1_noetic_core (into the ROS-1 overlay workspace folder on the NUC): + + fanuc_msg_translator + + fanuc_msg_translator_msgs ++ ros2_foxy_core (into the ROS-2 overlay workspace folder on the NUC): + + fanuc_crx_description + + fanuc_msg_translator_msgs + +CAVE: all python files have to be made executable: + + +``` +cd path/to/python/file/in/the/package +chmod +x +``` + + +### Fanuc ROS-1 Interface +The Fanuc ROS-1 Interface package can be acquired by requesting it from Fanuc's Technical Support. Fanuc's Technical Support will provide a folder containing the pre-built ROS-1 package along with a short documentation. + +The zip package containing the Fanuc ROS-1 Interface must be extracted and placed in the file system. It is common to place it in the user's folder. + +Before installing the Fanuc ROS-1 Interface, it is advisable to create a ROS-1 workspace if one does not already exist. The following bash code demonstrates how to create this workspace in the user's home directory: + + +``` +source /opt/ros/noetic/setup.bash + +cd ~ +mkdir + +cd +mkdir src + +catkin_make +``` + +For the installation process, the following steps need to be executed in a bash terminal: + +``` +sudo apt install ros-noetic-industrial-msgs +sudo apt install ros-noetic-rviz + +sudo apt install libmodbus-dev libjsoncpp-dev lshw + +chmod u+x path/to/fanuc/ros/driver/lib/fanuc_ros_driver/*_node +chmod u+x path/to/fanuc/ros/driver/_setup_util.py + +source path/to/fanuc/ros/driver/setup.bash + +cd path/to/your/ROS1/workspace +rm -rf devel build +catkin_make +source devel/setup.bash +``` + +Running these commands will install the Fanuc ROS-1 interface. However, the license is still missing. Therefore, a file containing the hardware information of the computer must be sent to Fanuc's technical support. + +To create a hardware information file, the following commands need to be executed in a bash terminal: +``` +roslaunch fanuc_ros_driver fanuc_interface.launch create_license:=true +``` + +Once the license file from technical support is received, the Fanuc ROS-1 Interface can be launched using the following steps: + +``` +roslaunch fanuc_ros_driver fanuc_interface.launch ip:="robot ip address" robot_type:="CRX-10iA" license:="path to license.data" +``` + +### ROS-1 Bridge + +CAVE: Before installing the ROS-1 Bridge, the core packages from this repository must be placed into the correct workspaces (and the workspaces have to be built with catkin for ROS-1 and colcon for ROS-2). + + +The installation files for the ROS-1 Bridge are already included in the ROS-2 distribution repository. To initialize the ROS-1 Bridge, the following steps need to be executed in a bash terminal: + + +``` +cd ~/ros2_foxy + +colcon build --symlink-install --packages-skip ros1_bridge + +source path/to/ros1/workspace/install/setup.bash +source path/to/ros2/workspace/install/setup.bash + +source path/to/ros1/overlay/workspace/install/setup.bash +source path/to/ros2/overlay/workspace/install/local_setup.bash + +colcon build --symlink-install --packages-select ros1_bridge --cmake-force-configure +``` + +### License Path + +At this step, the core packages from this repository should already be installed. Now, the static path of the license should be written into the FANUC_LICENSE environment variable. This can be permanently done by adding the export statement to the .bashrc file. + +``` +echo 'export FANUC_LICENSE="/absolute/path/to/license.data" ' >> ~/.bashrc +``` + +## Launching the Interface +### ROS-1 fanuc_msg_translator Package +Depending on the use case following launch files are available: + ++ fanuc_1.launch ++ fanuc_2.launch ++ fanuc_pair.launch (launches the nodes for the operation of both robots on the same NUC) + +Example: +``` +source /path/to/ros_1_overlay_ws/devel/setup.bash + +roslaunch fanuc_msg_translator fanuc_1.launch +``` + +These launch files launch all the nodes seen in this figure, including the parameter for the ROS-1 Bridge: + +![Alt text](/imgs/landscape_full_interface_ros1.png) + +### ROS-2 ros1-bridge Package +To enable communication between ROS-1 and ROS-2 + +``` +source /path/to/ros_2_overlay_ws/install/setup.bash + +ros2 run ros1_bridge parameter_bridge +``` + +### ROS-2 fanuc_crx_descripton Package + +In ROS 1, the visualization cannot be directly bridged to ROS 2. As a result, the robot_state_publisher and some other nodes have to be launched separately in ROS 2. Additionally, the /tf and /tf_static topics are not bridged, allowing ROS 2 nodes to create them without encountering any complications. The following launch files can be launched: + ++ fanuc_1.launch.py ++ fanuc_2.launch.py + +``` +source /path/to/ros_2_overlay_ws/install/setup.bash + +ros2 launch fanuc_crx_description fanuc_1.launch.py +``` + +The following figure shows the node structure in ROS-2: + +![Alt text](/imgs/landscape_full_interface_ros2.png) + +## Functionality of the Interface +Once the interface is launched, it offers the following functions. + +### Joint States +The current joint state values of the robot can be received from the /joint_states topic. + +### Robot Status +The current robot status can be be received from the /robot_status topic. The custom message type has the following message file (fanuc_msg_translator_msgs package: FanucRobotStatus.msg): +``` +std_msgs/Header header + +fanuc_msg_translator_msgs/FanucRobotStatusTriState tp_enabled + +fanuc_msg_translator_msgs/FanucRobotStatusTriState e_stopped + +fanuc_msg_translator_msgs/FanucRobotStatusTriState drives_powered + +fanuc_msg_translator_msgs/FanucRobotStatusTriState motion_possible + +fanuc_msg_translator_msgs/FanucRobotStatusTriState in_motion + +fanuc_msg_translator_msgs/FanucRobotStatusTriState in_error + +int32 error_code +``` + +It uses the following message type, which is also defined in the same package (fanuc_msg_translator_msgs package: FanucRobotStatusTriState.msg): + +``` +int8 val + +# enumerated values + +# Unknown or unavailable +int8 UNKNOWN=-1 + +# High state +int8 TRUE=1 +int8 ON=1 +int8 ENABLED=1 +int8 HIGH=1 +int8 CLOSED=1 + +# Low state +int8 FALSE=0 +int8 OFF=0 +int8 DISABLED=0 +int8 LOW=0 +int8 OPEN=0 +``` + +### Set Payload +To set a predefined payload, a message of the following message type has to be sent to the /bridge/set_payload_num/goal topic (fanuc_msg_translator_msgs package: FanucPayloadStatus.msg). + +``` +std_msgs/Header header + +int16 payload_num +``` + +### Get the current Payload Number +The last set payload number is periodically published to the /bridge/set_payload_num/state topic (fanuc_msg_translator_msgs package: FanucPayloadStatus.msg). + +``` +std_msgs/Header header + +int16 payload_num +``` + +### Send Trajectory +A goal trajectory has to be sent to the /bridge/follow_joint_trajectory/goal topic. It uses the JointTrajectory message type from the trajectory_msgs package. + +### Trajectory Queue +The trajectories, which are waiting for execution, are shown in the /bridge/follow_joint_trajectory/queue topic, which periodically publishes messages of the following message type (fanuc_msg_translator_msgs package: FanucTrajectoryConverterQueue.msg): + +``` +std_msgs/Header header + +fanuc_msg_translator_msgs/FanucTrajectoryConverterQueueItem[] goals +``` + +It uses the following message type, which is also defined in the same package (fanuc_msg_translator_msgs package: FanucTrajectoryConverterQueueItem.msg): + + +``` +builtin_interfaces/Time received_time_stamp + +int16 status_in_queue + +int16 status_on_server +``` + +The received_time_stamp is the unique id of every trajectory in the queue. It is the time stamp from the header of the trajectory message received via the /bridge/follow_joint_trajectory/goal topic. + +The status in the queue is: ++ 0 if the trajectory is waiting ++ 1 if the trajectory is currently executed ++ 100 to 130 if the trajectory is finished (counter until 130, afterward it is removed from the queue topic) + +The status on the server is: ++ -1 if the trajectory is waiting or currently executed ++ one of the following values from the original message type (action server of the Fanuc ROS Driver) after the trajectory is finished or aborted. + +From: http://docs.ros.org/en/api/actionlib_msgs/html/msg/GoalStatus.html +``` + GoalID goal_id +uint8 status +uint8 PENDING = 0 # The goal has yet to be processed by the action server +uint8 ACTIVE = 1 # The goal is currently being processed by the action server +uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing + # and has since completed its execution (Terminal State) +uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State) +uint8 ABORTED = 4 # The goal was aborted during execution by the action server due + # to some failure (Terminal State) +uint8 REJECTED = 5 # The goal was rejected by the action server without being processed, + # because the goal was unattainable or invalid (Terminal State) +uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing + # and has not yet completed execution +uint8 RECALLING = 7 # The goal received a cancel request before it started executing, + # but the action server has not yet confirmed that the goal is canceled +uint8 RECALLED = 8 # The goal received a cancel request before it started executing + # and was successfully cancelled (Terminal State) +uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be + # sent over the wire by an action server +``` + + + + +### Cancel Trajectory +A trajectory can be canceled by sending of the following type to the /bridge/follow_joint_trajectory/cancel topic (fanuc_msg_translator_msgs package: FanucTrajectoryConverterCancel.msg). + +``` +std_msgs/Header header + +builtin_interfaces/Time received_time_stamp +``` + +## Operation Modes +### IP Configuration +The following static IP addresses are assigned: + ++ Fanuc 1: 192.168.1.201 ++ Fanuc 2: 192.168.1.206 ++ NUC 1: 192.168.1.202 ++ NUC 2: 192.168.1.207 + +If the IP addresses of the robot controllers are changed, the IP addresses have to be changed in following package: + ++ Workspace: ROS-1 Overlay ++ Package: fanuc_msg_translator ++ Config Files: params_fanuc_1.yaml and params_fanuc_2.yaml + +### Modularity +Because of the static IPs and the Fanuc Robots and the NUCs can be used flexibly: + ++ 1 Robot - 1 NUC ++ 2 Robots - 1 NUC + +![Alt text](/imgs/operation_mode_one_nuc.png) ++ 2 Robots - 2 NUCs (in the same network, e.g. CPS-HUB) + +![Alt text](/imgs/operation_mode_two_nuc.png) ++ 2 Robots - 2 NUCs (in different networks --> mobile router must be configured identically to the CPS Laboratory networks router) + +![Alt text](/imgs/operation_mode_split.png) + + + + + +## ROS-2 Network control + +To use to Fanuc ROS-2 Interface from another computer than the NUC, the message types need to be installed to ROS-2. Therefore copy the fanuc_msg_translator_msgs package from the ros2_foxy_core folder of this repository into the overlay workspace on any other machine and install it with colcon build. + +## RViz +The /tf and the /robot_description topics are published by the nodes launched in the procedure shown above. If you want to use RViz on another computer in the same network, make sure the fanuc_crx_description is installed in the local overlay workspace. If ROS-2 Humble is used on the computer,the fanuc_crx_description package from the folder "ros2_humble_crx_description" +can be utilized. If ROS-2 Foxy is used, please use the package with the same name from the "ros2_foxy_core" folder, because ROS-2 Foxy has issues compiling the xacro (urdf) files. + +You can start rviz with: +``` +source /path/to/ROS-2/setup.bash + +rviz2 +``` + +To visualize the transformation of the frames click "add" --> "TF". To show the whole model of the robot click "add" --> "RobotModel". + +TF and RobotModel should be shown in the tree structure on the left side of RViz. Make sure following settings are made for the RobotModel: ++ Description Topic: //robot_description ++ TF Prefix: + +![Alt text](/imgs/rviz.png) + + + diff --git a/fanuc_licenses/license_nuc1.data b/fanuc_licenses/license_nuc1.data new file mode 100644 index 0000000..4c6526d --- /dev/null +++ b/fanuc_licenses/license_nuc1.data @@ -0,0 +1 @@ +Dejk049IFca6vvB5Or3aDFH5/kVhdjBqTA0kuZKs0JW0ZwWoOypgXECZxtYc3w7Sc71eRa1iiMyxOPtDDyNusxLCjVdDmecgyi+K0+6emuuI3WkwU56wzxSLtlq45/8Wnz6Omix3066/eXCLv8pVnjPrXmvYYYt3CSKWSimobCPwVBga0+a0xjcIc9O47JAuMoxbUi7g20fJl1UXtUQ6eIeWEfpZ81prEtsdyaSvZKMMxeuOUdn3SiYtLe04/9E6fQUZ+qCBpKaLuobjf/SajQcgpaq+X+9U7m4eQa0zQnBZzpxHj3qbL9HJMc4Bp0wuq3lL+PhZd3jZBXmAHSl0Zg== \ No newline at end of file diff --git a/fanuc_licenses/license_nuc2.data b/fanuc_licenses/license_nuc2.data new file mode 100644 index 0000000..292976a --- /dev/null +++ b/fanuc_licenses/license_nuc2.data @@ -0,0 +1 @@ +Nd2ivgRlJZETuI/xfa/Li9tkNQ4mrfDjciAK6Tz932YrnTWo2lAbLX/G+8Xl5aAGVnarySlX3deJd1ZYegGuFEmgIT2hXDSIFSSr9aWOs3KP++cpsZIDG1AVsdgvT6DCPJ2gth0u49H5Fl2ICfxqL0WoRGKh1HxWAxFyiD6kNlhQFLK4Zp8XkP8tH9a0fiImav/kgm3PEUCF1gwg2TBPmkWcNv8RpAvg/R67fgRh+uouq1rkU8vdMHbADHoCIWZ8j032ir5jvzvmJoBHiebRhWrSvVd9jqYRTztwvK7EpsSdcLb9ZPqgRwNxVzN3EJcooH0gDU82HuNE1j7GPMRH1w== \ No newline at end of file diff --git a/imgs/landscape_full_interface_ros1.png b/imgs/landscape_full_interface_ros1.png new file mode 100644 index 0000000000000000000000000000000000000000..e2608f394dd82b705246528a1c62ccba2a7b9d9d GIT binary patch literal 84422 zcmeEu1z45Y_O~D?98l^YA>Gp5-3XGBB5()+=`Ja0=@3Ne5L5(%loUinq)QqEB&0(c zzI}+1se9-4o&R^|nMcpN-~H}dYyDPkLzER|E2Wo~J5hMGg-=od9RtC@|1BQ=L4H9I@Z)|T1W9A;_{vvOdz zHgN<^;JuZNvH2}?6XT;k?5yk@OsqUi?A+H``KUR>SUKQ-ursr9vgsW4hnbpK9}jrV z#@*b~5=PA~&Be?LhN9DAW25E}2fx$}ova<5j(#hcTRXXeHdkJ5eQwU9HhX6#vvoK5T<%x$cXcf-ca&CGT5!qLsvUk0useqoHLDmH82&$p z#PQjH2WyzsabIPyT_&&~`1Iz-XJqQ);BF!*X{aE{<7Riw>b8PDyEMGV>CsNcv~rcP zhuNB4voSWY1Vb3R9xZ{5ot67&P-C~F79KXvqXtv^lX;G(g*T{~yB{xz4J;PE7*i*6 zV-ttt(TUx2%b|soBZQfU-xcw1S;ghkbI6$MXPQ`rE(#X`A*xas59soT)w=lbx-sEX+t- zo0ErAMcYh6hv|g!&M-@-}an!eV06%Zrm|HvQJ2=7|0mTog@8IZmLI@LM zK$qi38+%7H8&ex=n5EQ@R&je9Cu`$F0S8%+1Tedoww&ECWk=4kHx^R2*+rNQ*4k$y{@PxIO7-*BE& zhSLZv;AAA5TeloeAoj0w-pO7-&r{p^%lqe$IP87M?0>E2uVmsk51s88D*tO45y+su zn-*XjR)Fdp;)jpg$4q+oAPJ{GoXd}%;G~B?{RbGB4?gE#Cd&!YPf`371G8~(^Zbl~ zPmup#!oXto_At2ooUpGgoShHB=8x>*_k`hxw)@#mIC%dshMpez$9bIy+wu6ke8=M* zi~8R={-Hn}9mF5s^#2*zKek6s$-bD810H z3`ct#OG^{bM;cfYmNqW>M|#WA9(Eg8AU1G(hFdQGUfuNrGEPtd4j8BK<98qfXj^+n zzzm0$iJ_&9kp=kvuu&S=yg#9g@h`iWSR0?}aJ1uptL8iejX%P_aL)ZL%?W4(C)2Sk zF~Ow{{`}{I9rlx@A8&D$8GENx)M`qoZX|3jF6gKd5Y5dR3mu(ER%vCWTI`;?rVQoz7gGqJw~148pl4g16QgS&YyX6BA2YPRr>9Fi^|Fag?5`FS9A zWGP`|X=4xGQnPaybD8iOa~`Tadm9UrQ*U_L4LP{E!JFennbw-K+2;jMoYEq}7iPl(C!8^k>E4o(yEr0u_lm>kFPx>M8y zJmq-nS7iHh1!#_U1+3q{9H2S!M*n`PW@2S#<>fl2{s}kyD^1P+8*1R!Om|8RfS({r zsBi0J_$wy-oAkiZ*M}(d??QFX6SV#lqWUq{{u~H?P8JZ!g@$i zWN<3~c!EnK{OM;du#qLq!NL4Ug8owWT0 zj8uRbf(+`<+!dImxhXu+YXqnWC!RQ5W0`{#rP%QcD|2IGc$!Sy-o(M&9cFl#GJ_-A zadaDaIb7n@T#}&WcU9hT{`B}`(CrxQPdhljnM^qnhkp!&*pK<=7=?~c^A8jKk4z5V z4>*!j8LVTK{}be$K;R*d{>Tvg853N;&TpOK#iO4`EC>&0|NrBKoh0o~+g>LQ*J&s0 z#76rsa>9O{wK#Ob4y`R$`H_bF{|nsNPw4yC(EX+)C@ ze~WY{2Iy(U{8Q%fzlU@u4)bZ+Ih(uxN+bVGRQp{k{hvq!4z8aY-G5>{WdF7N{N!pK z78agJlJu|AsM4l3Fi=DJ3laNusOMDn=m#YaLrJdYj#|JuJB$#4-`a;BIXf>e5G51v z{G;pw{s8Cqldpd1j-U4Me>n6<<8g5F!N-G_h5Z=t@ad-!;ZMIF@^pae55~EUPUD{v z7C3g~{;Fa3_l5;dTsU|ji}&a3d?J^pw806=oJN$Bwtuntcf3%p6VC!pHE_;sC(kE% zc2rk-T=oTLO2Ef|D8To-?k&%WgY$b+9ueoCGUdrG{)|TMiAFkw<9`@K;J);)Q_`nE zfE4L5rVi(c$0ScCxZPsjNPUYy+_ReK3Jz z-Os?}_^ZRVe@#UE--#r@ovi!s1`zl3!YF;2O&>C;cCo9Nu)`I8G7# zbujte3eta`VZzMH3NLPf8zV>H08&POvuX05wIdEC@{dG$f4kNbo`e5$*ayET@Mh;Z z_LKgNLjB7r|0mK%B7LlZ{t=Njf>|5EugAd+yVKR-ze+6szLoH^jPuWQ@DCf~v>HB2 zTpt?=a5?y;XTi&H2nUD01l&sf$&mQrtNfN{@yDHn{~7r z@~@`+pUfW0Ea$InY-Jd@@_$s|@*8)#PUT3Beu8`DM)u~mhnK(pg528JntM(xBaAuPknUa;Qyr6e|&bRz<+#q+FmzuvUmPz<$qjp|J6Ir|E>~RR%Q+!_MbcD zJjd49f0a}IQ#9`wEVxfn82>u3_^C|iWJ=CoI1K+VSRCCG{ZS5cTv7z&<&VJsQCRYK zgOlvPfLHDl=i_e;dxHK)3;pAZI$a8MLZJVSz~$kEjNkbuAdW970aw9q>QhLp0SqKZ$i-NS{?S5u5gs;5_9PD@*J;JvkptuI_Dy`-$N zykD;#-5d!;!6io(uJjH|ds|2TnFVX9sUQT4=Ju`i14%DcKhgBm4|Da~;M1BEeu@^L=MzR^(yNO@E$6;V;`mw7gDR2p^~9!vtpxkzZ&8 zmw_E&V&ZOYPo7N~(hW^;DW)_Fwnf3CzH*mA3zbl?a2w~`+b&W$uV*z=N;bH*-Uq8& zsR^#@6YRp?cl=Q7&?xO|U!g#${398lbZajiV^qL7e#)<@eV(u^{~=2D(e*0hN0kN5 z9aWtPi{sxClyY^+UTQz2nunkES^A}kkA@YcmB{TlxMI2bMi!WH6NJbp!HarB^_dno zFxkAWNXqHd%LJl8w`I8-sQ}$?X&Q_bGoWB|^0H@#8GV0zbw}ZG&C696%;|5YyDD@~ z8g*!zvB21x3`;Zf#De@hxaqa^k`ugrx>gZgi*mj>E*N8b-(-SQ-k{zM3Ym`*Mhv*v zNR1H+PEmmFg?vDmu=kFX8w#;U`Wrv)j`u$4H8TtwSX`Ev6LKti3qI{ehS_umcaZf& z1bt{ViP3tX(Fg0WP3}3yr8EQ z@IlUk%-Db8yC8Ey??85pAp97tGixG@Tv@>17Z3od{*o0F$ zVz1IC=_JOXZd`J{N#$$Ay>3oPDIoX2(D*{9U76bSbX zezNl+7G4A>bGO#OqsyB-NV6xKaehye(tr1fy&Trx$LW)ceM z*y`AHc&?gEH%f%uv%v57-P_n!aZL3o5c&r?zO z12GV z)Rv@0WAWKZ`HFk1-K57xmh?UI#77k7Gsn%=9|#uC&IwnEJ=Tp$r?BP$n-M0bnX*lDzD^PSLr(L%6>h8UJB*~R z8wrYhc z7X;(apT9upAJ24y!cuD>A!cATtPWQ`@Ju#*g|p0TJ(rOOaUo|{cKhBqSqP;r_7^oZ z4G+CCLA%7L<+HUqb+9%VO)0}_`~fphr|6?hHEByqLjsF_gk%UdxzYQuivy;uL{_aF z7d7W@5m=K<2T!A}k{dsmw(hZC<=LovB;)GnfPp~)~H{Pyk^ z$6aK!TScf5;$yE(Tca2>nRP2%+m)#K9H%k!^(yb_6y5GKDalkWwV%9dIZ{O&ORMDk zd4bcsW4fX}L+W*6Z;B~Vz7{(Y9WoN+>~)urmxuueDr9M`soJk^tzUv{d5(7GD7o%! zbMZ#HD^vxDo3@VYCQWW&q%tn_bI5>WsNk*87@ds>3{I^&cNZChQZ-S*x0Q6{Y2B?$ zIzpDx-=TzsuX~^02&(ZtOR4aH^#O-zgx9iZYYK5VAy-E%vi^4U?n}o z9}+oo@>#CN(LLa?A^Fk}S0Z>LS?%R%s~-PEK7pC=RzvvZ9HAtO-u(JtEK0}W za~BBB3drV@ggyCVXqED5U%wB(Y&6r6-7nl9BjW8fq}Mucyt6vl6okj3m!^~|Z1(v@ zx_WtQ5}#lG&GIk(MHaHr6v*!*Neh}xQygbHU>gfVT7_m<=g{$eFi3^T?7qAk{Wv*T z=HM;(8di7C_(K!|kIitG)6#2)sTSDg(%5$2OQVLn2G?#dS#eD(W4|W44n$P!?S!2K z!)Qc`c+;--D`PpK^Vjor2{iL{-*!DwJNs^TYjfF1NRw7J>P$lfvBY4h-8#{`0}o4# zsq0=Mqq{A9PD`V2QE=&@kV}lg0xkV+>2^bc)R=RSrq-z$)<#c)ybhS_@@G?8*k5)*{1ed8Wppm)}LVHarpYl z*$pz2n8alfpOWVOeGWD7{`CSq;_R#UJ77sH`c+*luC=7(@nj7lciT#>2DmMU-l!|7 z>TXfxYCO}preuK5GWqUZqd$%sP?IklrWE(K<_Ai+N_8xzQiMDz)}h$0p_iEMxv$Tf zyM_|+y(;c|<&MvF`}*^Nhg=qz3>u7kMDvtMIw|B~If}{s^w5q@*?~S%|21x_{%KR{ zLKnaN7;*bo+L?IF6y~Lsy2EnCAdaxDiz<_tnW$rUzS;+KORA{np z@cL&GFU1$L!wvEHC18%gEHs%wg%TVBh~cUOoBiOc-uxi63DWuu?PT7*aS zCqJ&K->Zwt*i`iu&$%)egv`O{uUCbNL*s+_E`b>#a;9X&tJ4Evrqbw3XmVSFx@7)E zd-aHrG-;*Yy`7EqdqlJs9uHS~_@#3Z3pf{|K_r4MhUX}yQUK;9%rHAIWaLk#$X$OA zSE9^*vamNMw!Sfzc6~yeZo*%om7Eqwk;GqpKWw-R2*!*zt-=G$o$vFV4EGg~n0o5i z^NM0U$ScuElldGTpVQBe=m@=yz#U0W?XRtvi=LY8yyl3lGw&-N_};$gwPF3e?a)BY zv0N`+#w`ks4yvFtw z@10$o>qmwpKYu|QuVh0y7DOUmm5UmLu5J7!>%C_npZ!GJ!B=|2po_$7P1Uwzwf*1f zC3C+})izSy*<70LdH!ghPsrY8q^g_Y@%Ona6HmthC_Cz*LG49I>ts+&3-7~n!O6dW z0jsOQ)j=dnk0RmES9rw)M5Q5tdyxf5^%8=Awp1% zW5C6vbIjgWEzxHfwN{?C+s}$8nR?;F?u`xMOXWa{3kfYxYUML^w~R!F@I~5@OzOUS zw}>`K@z%Q`6c3{{Riu|h^md&UG>qug+*FAudDGXy=DMl8=5c@Vmd3Ds7=_kKc>`Fz zlXl9Kox5pSWo>^&YrUbzcj!mKgd1CMxY z*2EZeyN&SaXfdnaZLJIyn#ZP`!599B>bG-lGiHivY5kifu`s{mwDN_7wKcZ2u4l#< zAl?UiF2wO=hV>B7rEA-3GjG*}_F-BKu`+ZM)!O=iG1v8^Q{vz6q3IS)7^ z$_2un4x-7nJ}z=zAyBl8chBo<>6YuMw8899 zN%0)`@UYhM#K@=Q7fPnSFp5kiNw<>K$#9r_%xWbeGiKLao9lb+t`d7glsAC`Jq|51 zNv-UHf2-D`hBDqyQ5u1%*qmicL~MqVd!Drbw1a6ZR)yn&v$bJr^UdlOcF0H$5>Sx|yLFJ4P9Q)>Ke}ypEGE#MW@^ zcGhGXf%U_wta_nXbTN~1)coT9#>SX+tWlKM9&903puRgvU*74jRoCc$ABA`Oom_~M z{Rpyz0%{q0;@Cu!>84A6t)IK2@cvLeH*T6+)sPr&+s~*0#Dk zLjXDZaktSeVgOo7nyM$xEZFg_Awbqb`GYJuNk*L+G0Cp#6IJTUWItus{arU9eebOm zDVvSaDhcWKHnheM6wEQ$3n)pu3pD|nH&%HwT~X2m*W=JS@?zKf9yVAt@1Wr^ccJC! zl6}3yvRb-4tbrKt{u@qpp=??kOLyEWxFuQ$**ph9GgXR64CNuSzO%!!Tj{ zCqn4FfRvgvile2c%EsSAKlgip5XO-%%``^1QRmlNE0= z?R%WU`9nj30m7F)W)YM*`J?3m8=^g^hOIVuiB1l>bQP|6A~C=p8wHU!8c=I{lD*gH z**Uv{8|_~`;To7mU7x+{PFXBt$sU2ICpJb~6hop*9B<69h4eUrRLF--!X37sDv(4` z`?7AwcIyk@^@5#)6er5!Iz3{VNP?_N5+;E)`+IuQbX^@HPV{(EuepboZbVc#Cz?Fh zM~2MDw8&r}`)|djrwbvS0j5V5uhnp~*+K4WV%^$qK_%iIK5 zlv3x?UtA48r&VlAGhF2s{&9Bkxxjim?e5Jo$BUKx+;v3^cu{03>}$mQ2yBM+QUQj2 zOS>~hP)3dS@;1YF`(kakYPEHFJs=nhL(=s+DQ7Oa_ z)xB?)&d9prh;x2pCiqRbj!{#f$nwOZOn-!y-IvU%8a8~M3Kk9K#LQHN8|nQ0&hrHu z6mH!YEv!s;=BygVt4T8)p1tAq{F2L$#6a<8jUa-tZ*`aUpn_nW&2(1F>B|=mD#eG` z5)I9&^X1vA>|EB}1f;{&o#ZxF{2SdOkGNs@!_WMlZ`u@azUYpP#m zA!PVe!+p8Mm>r7%#DIPJlIt|UOO#gk(JaKID(#KW8Ff?aNqcd7M$oLiiuN``sk`ez z#JLB6%_-cTI!=#N79mEL5Kg10sbtjGbh$lSR(-4R{9Zu&lPP5=v&zMKha73Yuf)nP zZ{N(jStg61O=>CRifXDzQq-g-dxqe1=JRuC;;NzBxY6`hG#5mvS08tpBrs|sQ=W6I zUo}-?HT<$MJ~P0XAIPSLXFmOa^_2)si%vSZ<@&3w2SQeix0w2J6=~4#26oGv2UB{AeSO^H*b)B6Si2P)2((#JuBlW zV!n~MvNG8mcgEDFQYxD0N}Ev){sfbjf;YFtN3+R3fe?NO4XWt?hW>uK=CYtUtL*)^ zdv@RbBe5a9&vnDHzirI0UusFoo1f+~W4s;55?na*+Ke@;p(BPlMIb;(fG1P#88aay zlIU}|oWp(>DNnxkCF+kF(tY>3*QN*Q5Q7ATD~J5g znyJqpEG8Sf>g_z{dTF;vu(#XhmE2w53M-syi|KfWky&xGM5WAFQ9+~aKCkxGz4qd3 z7SM`o9m=u~l1l7%A_Xrzy)T)4dmW4KHfOoPJ!My^`3qSkVdjk$=Ja{X6@j%)c&&GX zVu*xa$h$r6pj(_UsKf{#OJ5_QQ6Ycbiaf^A`^t3jO0UOs)&kTg+qGaGeV}`)eNnDp`FWilwC|>XlBN z8?HiCYq;<>gR6W!McYtTZ3D+N{TgA?PcAoCQ@RgsGkMydeop~YaArzpAi}anCUnK$NTf49) zGZur`d)=JlOD4a9VdJj37Qc63;Af2s&kP3FvPCS*JXhZY%F?()P{ZQY1WWP`)TWXv z9YNFu9Q8xN`_09vg3cfEo!idhaVQEpA&0*apK8oa z(!uzs&k|T_QivbriIYpD^~aV)!mB6C?d4;D0P(9pdk+1$Wyo3Z0vgX-O8& z-(Y3apC3{Gyi`wmt1Xs@N6au! zSMV~)P7sDxT9l|I1F6$0FF5^3W#06gUK@M$@$m!KeG-~*AovJxMRbW)L#ySrg?rm^ z``PZq^`>cI7w`yFy($z<4;djw4A66A*7x5vq>%$b%s~l+))evLhp?<~G z)A-ZxC@nXuaOJwZULpwfk7gs*v2|XucyNz|^3vl^`hJ=pDc=j-_6$@I{XU4S%&1Av zY1N54`K;?41}8!O_kAlh4@hf@aA3NpfKgxIp58qrrF5<{Gi(N&?6jd_=|-mH-qEU` zOK&9xGAx+hsItA(??P&Z3vsLYw3~>-g|reXyZ4m(zEx3SZ;OTi{zda=^XLbKImF?& z!-ij=4QQr69&#JsWzw z^G}SY^SS8qMhb=OzcLwfkk%{5=lj=X!h60$-S<11_gsv+ zuiP)ts}g;j$Jd^k6G?AIu7G=Gx%{HX?(XDk#Cw;_K38Ni?{oxkOb&1uSN%GDASh{;ySOmEP5g&eSU)k>#aT;gl!l+rqJh!8Ga3g1>jG1JZWc^c`; zize5tw2J0-d^xkd3+_1&og*`AOVcZ^(-@eyIz-);)O>CrQ=*)ihmq}_?@AqQ^w5{Pl{Wh;f z(?!$wGNn?W$O?HiJtYC(Z2VG64be%t{ABZw% zfQY0BA(OJ%!v5jItFDtVa5==mTO@K!+flY=bqW`ZVS zf2qx2P!wgL9nR%0*nigY6$js* z4>tzTqyjp+%sH(VYp1nUcrq~IASZ!%eERD+F6lBvVA{UN4>1g&Gq44r?F++VhA9$Y z5PqrzK}N9gLx&3EEPOPFNLzD|>X89&x1*y}!^pwfIVE|5v49r?!cVNCP6>7IAwc-} z1vdxw*Vy_ax zV_4*66EKkSf$!s?2R>YsAA0!9f0INIfxnIPk26G12WuyPBNm2F^srb1>J(!9D zgPbHC;gby3iNZ%4q}0`+g=|KHw_a3PP$Lxh@w8ts^ryp213O1o9-4dsvH;*)48le- zNNFbMxbXSgS1Z84ZaW$}G!R~SFoo$Ai!gg+z%Aiy*!2*Vno+Pb!V154ft@%ONGt~vAObLgBZ;--rXx11~N1+L(!Wu{=D8 zZX$ljV8!_oaU5^H?sM@L=7)DyaR78Od`94|+Qvh|Cz8uhkXw`;SFyxGMt@$DqPDTT zwvLx|jfUisgi9R0shTfHeUs~K8hl9Rew+(W-e&k5F}$XahZZ0_Yt026HZ7=aHe!>r zUR{EXSQNFBuI58>r%=R;47O`?#QrGTxVWp-_Phl^xZuemkMW00CuP;>;a+`nd(kQD z8sXWHaY^Y1%H(ULpvnRZI$DHdGrZ^bZ6jrDqJAe=mlc?G;V`7mcOY*GMM(o}b*?Sq zb*Cjle-EyVjy7}sn(b*xq;57@n!8=Q;{@BR6Pepehj4khWdr*ZC zBP<*FOX)d%%q5~9?_iGpD21R#2c+_zbzvXM57GZwp+^Cr{92KJAoJnQ+soxgb2R0ob()1Q{9P2gGRAN3#)M1geRIA-8o!-Rvu5&E9)un8{|(U&)y zMuday1tHOTUNG*dx{%{ktL8lq17#>bnR5(J3(Ym)I{cjWhqr`tHJAvAf zNdXqy*?zS_kKIeHdY+;a`VwEh)@fRIdYR{1;L2i-YYOg-l!g*>p?6S6gc;jWmiEv+ zxd|je0j|cMyjc|q$NC{ciW;Nu?l*k)nq$6u4)vZZ8zqHwoGr?_ye+%}sgX;5Iisc( zQn9myO1i)0e_ly%yvJ{9b9=FxE{^&lJ5>mUDjZJfMlFE4^JGd-M>~|xwKKTmk_eOx ztPXX^cQ!Y1`8cQ~0W^hKKK=YP5K`f`fpIbEO-LL0-88*MsCBLnr#4vLt|}1V>g%1Z zCa6G<6WUzACzT<3MmcRNOoHwK7lEPF9@iNy2AVgo5nV_t-&NuCwwEv1EHL^N!uNIu z6g8x?AalAp!)4bGLxoKV%9?^GWJ)C6PSl9Sq^dPeKzk_!Q3L9_G=b|(TzOA;{nb6; zLjc)?n?|IKmkik96Q6tVmOk(vqO`I>JcQsHCM}_%44Ms+1HjE1YvcvtJHF+SDe2BH zjh&~W&%-S(=nFXZExbH!YbpE2YNm{iZZ*(lRQSh$(vIAkuV?Y11+H;sCDfTB8g7I% zXZXm&^FvQ|6$^CX_QQ;y0zFW188t7YXq93g?-Cz zgrD_g_*rMBEU&_?CqnPIdjT0f2+&a>|8EzErTccx(G9{MkU=(eeboh8M>hshqo|7g zMR#d$p>uRY`x8?JDx^o++y;&+08>I~`o^y+i&!^1&Uo;!hGn;%i$eBSNg@#a?Njw)(1aK@r2nNm5QT zOr2uOkQcCI4+D+X6d^1jcgN@VZPdc>*_M{ZBt|ZcXYNLXsd&(TNEYCEtdMvY)SUFK zmXfDn!3|N~W)yviv1Ee~*m?7)Xi1lhzt}TE6>xJL9zh zXwHqRTdSrQVtYEkDPw`K*rU_|bzi}WC`8JH6v^+7s94nE_(3a;bs0YGP}kkv3lT|W z0nX|jmum|nNkuY1RRbY}sqxuH>Q99xH(5SznSi_;CWTz{r31T8Ezi*va!V6;zg=BL45(69UfC%^ zth!rE2|4F-QzyV*rIX^8za$E-Ai5XorTzk|xRqU5UvJ^+x}8XyrO`b$)(w)Bb^vl2Bpb-l8 z&(rtXlJXeYBxz1yA=RsJ^%eHqp5DkPavZHeKquzEp0F|c_N?*8I8;#U(BZs3KY;g4 zv!JJMdNQ*i_^2Kxf$2sdsI3_TZfL2;1~Vub$wgRO8mkj23NmSkB-KxNTa5WtJOGlN zTJ10u@g1u7#u2s1qPNEx%A%*6Ahub!u9!n?$swd@+LF}n&Uz1TkZ1GYZ)qcxpC7V%caPA=*{N#`m+T;P;O& zJxGFM@;jOdZGeFIS-_^E_;FZ58Ri)Gww)-9*f4;B(Hh zMY}11MJA3;#c}5{k9D56Ua_V2r&JOBv!&0km)gSMl{dhxe_wsD9}0+O21*;|axODr4MmWO_s%?z zWH_PvM)vb!?M`}`2qIvAz56B;2CCa4({1Nx%06~NiBL1MamCK&BJz-=iW%II2;uBT zG(!us`VI<}lq=nx{Lu-psjtR~MpH;d(JGNxan^;U2z%ZGdGT*@fFJV+&yb3E<r;NcBbwrN@!l{{5BBtg>fVH1#kbDZ@mSS^6`w@O+t7B6{}Ee$kuSyR3u3W zC~HZRi6r44Otrl#nvqkWn9RT3Bm!$kG*Zh^>~6(oFXh$D(_)KbzNu3e((t{_=>3L! zOA?>cO>_(DO(>HN6hvA&Ux)=$KfpA`w{CRvw<=y&H0?r3kF))_q!q7TpeH26WBWGR zA+nzGgH*lO-u6tHkGuQS72`*!V_k`>c=KOcR7hlpmwbWRoGd5WFzg7_ zG{)4u8h+G(!br4i-FFj2lDss^Y+?63>-oamJH5UOiA-HWZSjuZ=4*HvS$Vg%)NXvX z%mEZrx#tg6dsinYmpXmZ7?O@4XKn$fp|OF}G`1OnNq$!^X%c_3I0`WHtQRcRj+rL7 z*k)w-_5ey~PoYkQ>r2se75xZn%Y;Y}dfi;VK}Ho0i)g#bv*4}k?u!2Q?0K;#gdY8S+43N00v1QtXd%4`VSj^HI&l>bym!eHrdk%0zTMdy^!|%f}|z6}^=MZ7#eT;@Paum02@py})z6fWK1ES`1}x(QvW)++~q+RWz{K0EtGp*#l=Lh!66{vlSWp94+IW2ddGPz?(4WJ7{Khk7mSbswZ(^EjC}UZSxm`|QqgAPX)?=bV7>i$dh?pN z++LwP0e4-uj#uN|DY_xW zqU5yKytZT$*|WWpVo5cfnI0`ODa$UBRU62ylmV+pxL47hPzfPZlpL=S#mb*WJbiMn zA+^0+Qq=GPN!^7l=E?FfR#`1FB6h4#C;|R#foIt{BSVIT13?)Lyo!oY=c30;QS!m!L(DzfKt-_TD4r-mxPjauT$A}e3N4Rsw-h@M3Dx{Xr(=>=X}L)yB_R&CMO)2 zlJv`9PzjmO@!X~Hjqh)_kZZk+5V1;HSxS-~wO7}gh*CaBS{$1q7WmYjEtc^0qW1Zn zMAnaz_|&`Z=L6#XEKW0ySiCCEthNZ zCCT!+6@Z?iC-+6umxn_atfM8AKS-Da+L(v36Fe#{w|;DKFgqUGR`d=DN%cT($+etvml#JhKlC&^$d+cy?pbA+JyW20`25r|6gKTZ&|vP2F;4A^D2 z?z=IC1$jcUVZp{2X&}u)ByoO5$Y_%e7QHBl2tn}Cqp4y*6&!4B_z?Ulk>i`KOzru% zb(Df`3&i3Nx#*|_v8<=rzP!~B`$z^|ip&-SNg{?Bg3N}not9}fqueYmx-8mQ65d*B zP~D^1#vz;gMNfJmfC?RJlUE5-HLtRhKvBS=hw&zlTDo{Zp`Na+F%s(AD2H?qa#Zp`+tto$XuGws}WZ`+Y$HPxQeti3X&ikPpI7PY0tO=*wP+!f4f z0nlQ=oFH?s^+Ua`^adskpLE|ySEtUvgVuO>^^BLyn@p#RVqRXW-?2WE-R(h)t-=i%fgU!2YPBy6L!o$pe=)i&|VX!F`@az$K$rwGqrZC?Ow)hsZ)WwI(TWKJeQ|27g z=?W5G5I0Pe5x;mfF`?=M{4G)2w4mS=;>h#OOP(?;VUyQotIiV$D@9Q_ww23bjta!u z8u3~B2W4u>7pFy~um&2f2q{Lv_;v~Eq?pdPU_wv{*UZ|_2}^u7NbE_A3U&G}ANd?7b)Fu^j4?`NOl8CpOPgYE$WMor_3xOpL>eal{lmlb`)I9Y*2 ziIh6Yet89yW)t>5Ico)@LMM;eSu1tDikWkBjrUb6qkEf?{Db2AD4jim0Z3ZRG;ITo ze9`TEM6{qva6<`OS|~-gsq6uXIHFLI(gW7?b4C_cMhE>J_eRc7T!oBRULNYB2uicv zT7D8tAdE`kZ?~{qzc5Iie|u-O1Y>!+``YzSW_!lmntjykzyXCv3h9K%oi_szrG3P! z&4T(qj%px?W4;Zo5sl25L{d1gW=M~EVby19uC%uXwHG)`p5QUv9FMXmcs-c45mWyz zjS|!}_n81ySx(zvL2C`3KLic#FVIZ&MnQT0&7keFH{c={xWff5Q-RwE{GYOXfNJq{jc0KD)MafRx(C5@FAY-so;FaB*p~_- ze=ZmTNCA7jJkkM-BS!D26P0}LdxuN3s;V{jvYJQJjh+V}vh5qJ>JNjyKn@rzk+DHj zV*X0b49|X_a@Ii_$0^t8D3o8G2&T5~8Kbeu2L+P8q=JloLDfqiycQB)4W2c#zmnw! z+-`#$(8(EsD@uw(hn_|}h5kAm5+Fz(uCMI+G0`RDQPm?(^NbCy&#|trF7tG*esHK( z7^(8?bh*C#!Bz%a$=0IpRkm<+OJd`=xoy?+27B*#nW1XvKJhHxAR)6D8r>vk2LMWYJc zgs1%Q&D(QP!3Q1>Hm)vXkAWKsd~rkNP5#96pF)F>A;g-hX>E4RR6%yQWY8)h4m?5o z)P!;mg^Go@uTUCTRcZD|#z&s-ed}`%EJBf zlP3IhuL?Vua8p3@ZX3^i!6>lJg(_Gcl20E|{{NkC+Pi{Gy({1VC8U(s$5+6p`3*A?rn*1!fa??{M zk>9V~T2b}r|IoQ$hBlv;6EnF&LhS{c5KwWSRY3whUhs$QCT9m@+bweU`{dZVCUoFv`o<7gciFe zfC}9%`J$T20gnHo&BJRWEDa+nRW_R*?mlu1yzRtGZgvFM3&DQ<6;6EAxzc;m@x(fr)Xtadk-*V)>T zs&02bHK&6;ps92~3I-n9<%+HZWw9Cx1xD>xl69nG!7|#bcQ+U`^QW7>RKi^lf{3fF zq%167P2T#)YrQly=bcQT)$_lRqey&#(O(LYZtNcHNyVoGyv9{_z2Sj(J7J6@Z>i*B z()6pn2!}skToeq*V*oDo8&9cwP_Y8NO2<9jd0NZm4t>3zPx1jgz>OG?$DdRgLsE`! z{r*}}oP2&f`+J4jy&9<(lhp0I8M5K71S|t`J5TsTl;Y^318wE^kZ#`oh6}~c=yO3* zD&7JyBEnoNF><=(`%liSmxU>R$Vu~1NK{LW+a_%t-xp)&gm zyN6A`ya&A!v(Gb@4I*J87iGzEO@N~dN><-Zw`WFkm?}O;C663tyBi|}imp;8^J)4e zBMHgxD@#Ngy)>*>1~&YB0F^~DK_A%a-IcKM6cJXaQ8+&rUhDJyXMGgEV#^F{>dsL;PJj_6Op zykC&ImBcd9WtqlX8DyBQgP2sm$4p=OblaJY$vS}cP~}&buOi&YiL`$k8Y+G#XQh$? zUY;Te0-_uEXF-Otz16v>!%SJ$20uM~Ns5k&h}|FDP)rEL{Ge`yc)q$u&}&z#jx0UE z_JbrVr9bOh+zz(G#D{cmMH_uksL!d~e>MOKAMsKwGGxZYXy}vD4Y!%4na&(G%g?Ny zb}Vo2hmc5%V^+H0GH7&(eq_0MX`1}gvQH2S7R6`efWqXl2MW6)VllAzwTxxqE3;B< zSyR#6EH{c3^b6&EGD~8H)j<8*%}qWWiEB^L1|(X^B-GtB2?nH_wa>3php{iqQ%Y!6 z`iTb~bi8f?73>5TDi_pfIHU#Kn;+{Q!NoQ6YV~BVIcfKy0sfED~HvYx7ty z)sGs>^p^@$#EwG|U2|>*R}QZcw$BA2~*e+0W}lH87nZ2S5qg9kIrIYN_dSn&BG!c6KeiDu03E}Km%hosjFJ2yEyhX{ z*;v#=RV8;Zg7~Xsx3s%rZLhM>A@tHJ%O-1m{}4^d#i>SFn+2>_~|t6iVxqfx0Mnnij`3!KWL7UMno4Gz+AiA{KJLPWn)E z6cpHD+aX zL@_Y7L+vWYljrX|uL8qv?IQM18>ZS98cFa*pVT7H|?Lag#gm@n ze^gE~qyW0`e6x+^(M)TbAWna&7kN?(z}O6mL*Q3YaU{8vqXT_wzx2r)%zk+id|4!7 zXhpaD&IOBv=ThY<^K&iZAN&MSGUY?_bKBGS&pBTX&VH2Op6Iz&!$zlFg#?NtXJxrc zU8YEMy3GUbNUfx+CoG=#Eu}z(z7cnN!jVQdnyRb?(juR9E5s@>aQc{9yPKw7y7wVE z&hdR-5R4G~umNkhRK#ZAaYyEr+t%FR%((5rf|cVpo(`ptgH>)!J^8x9cAb@8nmckP zURobM_ztN&-6fTcrwAvFpLJ3J727mL*Qp>6q`_u89kaUwH!nlIwl`7VO6+cMN`icX**(~svdmfQSgvcZoBX04m#+okDHxJ`h_0vf`2szUH{5vh~;Hrc6$E#(xlxtYhmty$|cuL>!ztdPjg_4N4pD_wt ztKAiG;gwo23fdT30U><7-t8-u!cV&XAA4^ZRMi{4jY`9oX4Bn!qXJUW-H0F!l7dpw z(gG5jkS;-x*s$qN=`I10?vPMgloTZ1hu{DAk2&+snR7mzne*YD;R7>l_FC&%Yu(R% zU-xxg_Y!iHk8nqa``t^2rqxe$-unq-&A%-*n9&iZg=}AMyVpvfEA&Nz;Uff*GGf*@ znkg5z`U!uwefQ4$S4L40-JH*-5~hr%w8&MF?lXG0q-?mjh-5pRu6KxgzfQkAJ2`u2 zGggEJaLAC7l=2*>{eDYHI8_@Af?) zDD+c09us|YxtaT=iH^Dr)My8&8uvTzSWgCO07ZiQ+X*w`E@i!KniKNZ+W7<(Du;&e z`aRiS4~NdIXEEkSP03UesDh@Lb&+bTp=dyCXMK(uV1nuujolfd7|}WCo+&K7UT)H6 zypn8j-KO(#e-&!4&&?#0W3?srI>?8p=l_wG;zTkk+EVE>*D2-wj-QuyD^a55Y{T4+ zU#hG6ynC0==ERv&V2Kp5^2WBfa?j=g80pqHBP2EG3S(WicL%d~vb4d2)GSkC{>N`n>q! z+?&78a%8eaXyg-k3R7{_CNPzySfM>fHJ;Xk#Jn-dyI`U;M&FrsD z#o=@zqKWs972-N%Mo~UwIyy|sci5nc5foTto9Z1ylsr!>p8LJtnq$CHgUW9&zR;}j zmPo3&5Sy-8e2dr3X};b`Anbei(IitgXfcjKP9TXxH4V3H_tV(ubhVpW(wApXQcQA; zU7~1sAz!mvJ4PeqURQY9ETXaI$8?-eYz73$K6~MP42_`{(39D7$IlYSk7bllEOV`U z=y+;?`jVl{<3V*I2w^IL z3!j{JUB2{w01d2c(BQhU%`}s?m>TyU&GFNi)N?-hbxlv;%1`Mef2gxP+U{%L5^$!6 zL678Bt))s8b*l4Wl$85ddUC=53tMZ{&XqYLEHtPqha?+^xOD$D-|bWrb~`KtOC-D6 z!Qdd+KwN1wSy8wg_F**N%`9m+9V}6`F?kf#sBSA!mU&N)w^5`}bcx0Aq{0^9!c*lp zI!`^3k0r-(pwXTBHk)_G``XroQ6?BmF7`Ut#SCrpK%v^aKfWZD&jU9{K01`6thpG` z(%zOy>}(n)nDjkKwN#QUkn;XCx7w>d%M-=%F$gHN(1 zbPbheVJboub9B9f6xyq)d3D9(k=HtL!s>Dsk51UxJUbUJY8thF6esUR&TG$@ zcFz6iPWL~S-xhx{YUVxP=706_5!6wWx6%0u-J}of#?I?I1XwSYGz;FCpj5Jqf-ORn zN&F{Wwins=78;2No(WzOLFc)KSfLcdI=HO)_)4Mosb7EaOA3p9Mj~WvAl~rzPDYxiB6XgAP!C@1rtA6i3(>D7loig$-^^gf)x<5u zL-DJ-)Q|_fz%W9w)TCL@Y}EhHFN;7~CHZ7)j1cq?S<@w#ok=(W0<^iWi0Ce`pwn8s zt{Yt|7kX`^Y0i}8^wl#7ynX^>kN_F;R#vLnOqpm;B-0QrH+Js^CsIyfpRoL!r zP>X~?n+*lw-g4+IF~8!&3k{3V9+FDi1H=8Q$%A3;2gfVBg0^9gD$I&uQH7AWEPGgHO~AQT{SYW)%0rO`i|Nqb2+f zvF;p;jCKE;8g^Cbe+K_PWuGG+hBw;q!rH;@)%UA=#Y{D?ki)`WKiUq9Lnlw5Up|nU z=wx_0n)H)kRVP9Rj1sUQmau{P7=v!Z}PGEC0ETv9!{1f{?)Jn0MrZxV~Hx zyI}b=CV8>$sKo~$vqlyCDxRku&{WTVarC|@Zql9xQeoT@^l;~GDl1M5i^?IJO+{C8 z1E+Hk#0|XV76~CYfgn5@X2^TjO_x&7s|&x?n`+}RI%gx%n}1Xm5$*eR zYftX4`}A9xuSoX12u5sQjYY-p2_ki8_gt!zE^-~xr(s^{C}bS3h|~8|MsFIOdl9Nr zJ0)ip0?o)@@8)ThHE1UiyeD*ExsX^LXZQ0p!(XF`-8dfbulh9KGw4ds8l!2;Tfzr@ zQVoJ?QgC1k^z+ZEDusunsv@W#X3a%CWmoBArp+E-io0d9nKijBl zQa7qg&pxDgjfQY&I+jz!LQozAOlI=u+meN@js^d{AWkE}XttP`|IRhZ*ED`#fJGr9 zAIVz+nYwg4A|Vf@*4Q*W+k8&1xx2|m5pILpU{C+Ma?46 z|CG__jA=Ib{^fW~{|Ga3dT&~@-RlbjR@0}^Y#(?}^x2V&j6?J346^Z4dC9rWz#qn` zXW4O5mC3Ql5{CX*jlS%DaS+%5uOt%vXTd*#ZE;(3HqV=q!0+)fltMqdw>9MPvl*xE z!}B3t6ND-$q`4$QDg_d4l_uqfwpGST>~1qol1}JwIY##V@G54x+qa0AWtIRjGuhT- zDi;vi#eF5VUOiusqJ>CsHCwJeA4--O66~pWm?g|Dh#hzLA!Mx6qd=R;E#TEiYcZ&D z5Xn)DEgk}w#7*_H+b=3awx07%&#w!902;)ykhSKErxsW*Wcu8g(_w|LPo{+T(o$}J zHRCccuCq!ed~kBRzw#iRT?+iZQEmV?2UfYz1JfsJEZ<0F*&{%?!~|$AUWXf>HPoBk zHVL;Le*FN_naZFFWToZNJPlhau4hOj8f(E$K)cs9e&cxmSf;E`vJW9$$>{+3RMuFo z$L~ek$-)_Yhjg9(dbt$;SrsS4_SMAWgZ$Rat`Z3PU&4&Sp-RxNW95N6t0xQPE|>I= zj^rI#+k`tzRSpu3vgjaUiSg)t@W;>bnxpOC>+<@lEi5(YT3?zrz7K50+a{9GYE0jpwl&850N_!1>yxO*c_MbWA|65ok z0DV7_C9^H?qaW>ooX*@L=QcSsMlbC5Wl2}agVQWAKjXmp2f7+>K;R-cyJy6OyV!E@ zvHlAy^l&tV4vZe1+&}ukTD6`IQ7hQe;~%RH1YXC{I2dCc#{N!^U@#Wt`g z2G+D?*8WlD(2P?}9A2xT4DvkJ4c6wB6TxP@+%|;wHC;fR(T+b zirW>N7Fw8YukWdi$cX{UYPA+Z^35NdRvlV~ zn=8z^!Rhh8cefG85XgdnO-Tzz#8{4{o8OvkG@sy9=5W59)C=#jr|t26$sBXMKHqG} zLtpD3bRPecrS)q6>1PbsavlTZ3Jc&K0qk-@x%;LvW&J-xVeTlU?}onQzxLp7PIi({ z|LL9HWMy`pk`Z0Nq03D!y1tm3+$+U7P%X>1qP*Yp(B(pPUB8;V#!}M$QStPkd((%= zIE$GqPQnunI+P4iUwEx>&Q;fmp&eR+g>tadSe={bhdR6WRTKPeeI?YbR3>8)i9ighX$kOTe;>ZKTd`U zi)1w#4-U3EC1&eg1YZ`mrijnx$D@z_D;5(?Ign`C4(v?Up}@4>m!d2X+}e)`xA#i}-JO zl|J>n%a?rFifL3bW!{Ay7#3Fa%CuR5@l?}fiNL^Y|H!iG%_`r8`%Xn0Y*B|f*=5X4 znFyttqDp`N7bE~$@y-gK_7xu8II>M8dVb)!9zXGrL^#1fzK_nkY48)m}|Kduu++?>cqNaUG zw^fX5{h2ex{SU8DI_`d0XRL&D{C6I%_e>Vl&4Vlp`NLbo0B9`-`*c^hxf2Bj}VBA{rcP?n{?Sew`T@MV6f-NOhVX#2(trMMNe zefUSv_WmD1Tm5>%e9266qLF~sH|Qh(=U9>J@uDUiCW^glb5nnLqp>-jeWrkpy8*!@ zgx~{Drqq-t+o{fhVra;C{cGx)9Tq%<%%s@g2!5wDiFN}R7q2i;k*KTL(@8Vi z8Sdv}2OOLn?1m9*RUZ($F6m8$5 z{#CTauh@C(-Ex#~S>f$^lLp^K$RW{FI#qpQSg$f9?E>XOV;MwTdtTst0eah+;KN1@ z^2(2r7q|3J1cSw>R=yK*w4k2)0V9$(Lv*!9tL`Au<23*5V1?N_&0w~O5M@DC$Tq{p zw3=H!WoAc-g`NX2JhZBry-#yc&4EOD%Hco$)rFf-J{_3fS^?Vu`LCauT}ZjGTaxH9 znAi3Vs=ECbvm;2phI6axqLYM=c6=|+E;g;4I=y>AmQ%LxH=l5 zoMP<$i7yVK+_69!S>oH#x=REE8+)eDh2au@EgehCJs9R5_n7E}{A1cWOcHi)S5o&wQVeo9dmP+Ym6sjmOa-A>vIz134`E;083MV#!dB5q7wQV6sy z`^P`<lIc(#};LGq4cyIv*Y>-8FC=w9=2GSo@q|E)xnznf+&cX2Qbcm<@wgf-b`I}{Z z-vclwJAYmtEVp)pmJ;A75;Y(FIqn3OW|jalRt8AFM&#)Eo03E)t~19dLK*?w2hZx| z0d3Mj&+;pOTh&?#-kL_^UMPW<=8tA{Calh7j@4nuj zC%?HoBB}=MT(qc6Dp`y5zUZpg+giWmcL2$gCE)t9;q^8tjet#dYj{Wn=pL;DN3BBb z0>WDtHPC2N@;xoR?aHnJ+BM)mGcC9IMTQd4+NA@AWUfPl$3Be~N;wc1r?EcyC_G=k z+8q|W%qYve%L;ArIZ^e!oUeC?1YGp%$xJ{ev!z|@jVw5jF=_X24Gr&!AX~q6_&V1s zGs4;-5%+SwssS9i=OCgqy?TF3Aj$UR1^#5_pB@Lsb5+1Z?UwUw*7imQaJAk4;_ZSrx%Vv^24IxpI7qct z-EWo-L@(4UqXAS>Gq%U6nwt;I+AfJSm>oV!1+@MA1f11!0D(E1GREOq&CBSYyW@Fk z!R|Hq&qU`gB$N}_@LYck7aeHFkg`L-lN|Qv_xi5CS=DpIbf)LHR`4x77=WMCexCqC z8*pf~7Wh5(48;8|pditm@f)(D&hn)XwLW43e@K@JgSv-Eg0H4r| z2d#1f5emSQC7r)G*)2dKh`V?$Kofb)yf=VMoGM0@C{_YsOU&)VfW2!RjJLW5uAyl; zMqyw$1&l{uP>pb4W0-zq4Yrc(90pTilg6G7m6pFQ|i<_n$WdhdAVdO;zydvtk{% zaoZc}TW7q={)-|wS{O1%BU4-kaGC4WC&$G!m^-7Gd;x({{v8w#bnqs4d#_onNY=nz z&a1O%43S3X=u9%=y~zr=E?SVuzGZu3a|Jyjt7A0)TsxDQ?nB&gV1zkcPxi5NdqX$% zL7+SMY8s##-YXhnZSlcE;NN55vkDItI9&i?!ezA!i++6gcL%sFA-4AGo#RrIQ)xoR zJ(c2e-#$$NCWXT3=3~&qxZfb9&#AffHHfwmbZ=PCVrGBXfzV*GgrU`L#$}EPV>|w* zKh1y!vV7wCdo{qLjerl6Djzf!ZL@)wVdW|G=fWoq-@?=_JfmtWJYc_vLPot94OWO- zZO7AHMgV^kyx?QPhb{pOXo1TDL2CQ+b#*wA9bG*<=a}?9Ew~7v7@0IxmTnaJZetUz+sd*PLoH*VQbUiUtQ-?6O)U{qe?_(9dUV zEy?%vpB!kj!L%d6+px>GeNHFhiaNcR!$3@C%=3{*KYBHr-5OLI={)pH+oy9Yd4m!C zve9i*Ky&N|FcG_aD=Vqw#eRqX1nAnq^D`;!0le(?mYVf3U>5#2*H;&t)2|O9w_bc@ z%&DeQvK)V%K^bQ%%k0iU1!9JFH`56cSdY0{bgWZ-=b!Ei?jO~(pC5fW#Q!R{?0T|` zN*wQ2l>5du^B>KTHqadLpXAr}{v&diHaZ|)&ZP- z`h2@{5wu_6l>iN&0S%AJFUK6?YD%dReis5<`sJlZMucx{^Z9xI_QhOHGL_-*5yxu?aj+Y_{J?Lm z*zB?YdZh;6UKFIT_|$nn9|MA46Y;kPtGW2P`JO5BWVO`gyCe{an5XY|y~TNlXLBh> z-wVCB#!Z{P;Fk@-Eq_BldutoBq=hwrg9X8``XthC1A3ENTzP47Ae#JZ5UKdKOEH>e z`^x1uNi^G|&it&Y`V)iIMj?vosqa@n+{Nu8w}?juUGjZxwYqK1|NZVY$a&W8;zZr8 zv@K(4P*iqX1H!BdVM8eE=x-{#C~F>%y;-RzwCqq)ML<^x+5DPi-;qt}0Fr7wWE^wF zaT|#Mo;D*3a*YKzq({EmuxxpCujZL-jS@e(B`ra(kJ5Ln1AC`%XAzk1Y~aEx0` zuty}z(Cw%cO_MhS_{?%|@C@)7uYj(Dknu&pIGNG_JEp4{Z2!40kO#cb<;;?{0IG*$ z;cN$EHuIa=y9kDUSnF73KgQpTD_JVw)Y+u&aQ`cDRM`oqg)kFaVAtDGHOWs;vqv}Q zKX8NOZM#W_W+Uu2pF*Z;B@K}~3qnc#aY^vSj`0zfkC?+X54R^c_hnd6zp|+r{v^P) zIa*gDnG^7d*vyGdabq!6eHgq)@jDY3xI?)}q30j#tnNZ=SzFB>m!^DE6>IQ}$rR;~ zW$q^5?zIwTLq=!9V&m)sS%+l!k7Gz#w&n)oS;Mf+x(Jam46@fBS0j%@NuPVY#XI`N zL@Ub~m>5=Ru=i~{AK!(2ukya^eIg;G$7BlAV9%(sEFF;xQYkW<&-e6INm^wFCWFs2 zKnz7mRN?RA(+O7+KFhma{Hr|5632(1n)%en#+GLvZ~-ux=j9t-vN)6NQHu^r_?8Bn zn#oEHJ>M#Rkn!s3aP|;deYMCx&{|9<7V^k9JI-=+o$7^f&E{|E3SPndRyvFj4G;tP z2d!s?f~q#JHw*}IRkC@RjuXB*0Q2-lkNhFHrcD!fGWIzVf72)cVx*bc|qpqZdf~{LshdXO7S$2CilA+psuM-#~eGVH|zI=!%NFATBd+C1cmb=ZA??;FWA_QXr&IW?)GlxF25!y<1LU$q(P4N))=6}$=AZ2e zYvYF37*&oVcSQe_3t*`rx1qd3WvS~eUrkp886dV5wR z4jYDBWQyK}1ah+Mjj`y);;U#<^$8_N=e>`A`E zUF}9{%qSM>HKqy$3=St#2|uS;Zt)9y)5vErHXMjcKIoCkjdbo!qvsM3=k?f^h(SfH zKko}+m|s8hts{gzW#d%TFh=dBwp+2LO;%(}Aev7ZMtDJ`L>nhGz=RN2VQ@ft5KD7fjGdVPN*H6d4W2gf? z!vXp_6}ZBWZNzF(x4`G`3;Fy1B{_J9{!;htOsKQd{j-4aqg@edG{|4V4>7uT!&o&& zq6%mBd|9-6rPK2(R^U&6>ee)-1eF`uh+(_`_Jm=t%-PK&UfftHkVmTQy)R`*7{|)2OR{VKZer?@g|ac zqkcN2*c9poUM+)_3s48bp=YKCxqC~gDf*AB61qAbtDcDLVg9I?(en1GVzc(N96wBcNJ zxYjlHLNqC{=))mR-_ro6sSTnYRa3e|MGu*CzVj)h4s**sRCcuiuI6ktV|;aAFg&dg zH|FQZ$QX%!7N_zkn~A-@@IDF{s^95y^2KbcOYyacoDpj;PdKaCrujsDaD)3MGe^`G zN-AB_n*7Iu(#<%WhweN(H;cKIgFSz6d{E3A>SmlMh12{HLF4P_jnt>KB739ylBzVAy!7jH}Ei<6NEcXEHQ^T^mg zv&w*!J&Mz0;gL@Jvo@dfcan~#=ZW%B`Ucfjs=4E;Cx@T=8C7o>zFY+g7C!lea$arw zoWSPj6TvtkqSJmFnjH3_qYOuXs91H|1p`3^N$HcBeN|VMZ~UGO|-GK zj7ShSWI0)RAV!#onx|=XqMb>i{q$40@3?5=M_KcD{Sa)Qoax)u#%SXJsXa9>MK4nioX(WCf@-A)DM4IH8Q|h|<)+dq7Qy+g>{_UBK9|?}A|7j{ zZ~i>hP98iz-gYaxP!Kb0wE1W?l4>;XPFvPmaJWrN()uln|01o6y*);Yc7SQ8;ZLl( zDrwbNR6O)OEJ11fM={q#o$_iw`HFsgM<#~9&Mxt9yAOQ2X+wJI=v8XAjdl-`{>VV$ zf4n<=Ot+-KZPo}s(0^4rP5FLOsOPt}iyGv{?@AS$#|fTAVYB*GsK$|p_>aR^;qCK> z_4(H~$X7f%WaVmFkZwdQXISE$Jl>CYynUoe%r9)D32Iao^n|@GV}4S9m+8u6F+oq)1eN){}o zePQH6LjK$2NpOOIo+~^q9~D-`U&zf_-Q&A0XPSNS2!_-;>Y|;qR`fDoi}HUkeuuT@n+59OSinv@K|bzrQaf zuAkZZhWkSz`LR*Am&FRPu#fjA`B*x2u9s&wWba0O9>ejYi31MQ(UWAI#=qD3slV0Q zvR^BW#YE5Q*qJKH16|K2w01Aymq2Zmr|=i~iBv zYk3r9!`zmkwVt+|I-a|SlfNwzWOds1Mqi!ls|gOr3C9-9ckTX3?f6`R!#3VblBX5Z zK`EP!gkE?BRW?1sjk^5)R_8%4KHihN_QVEFzbk7?dJmlJqd0tJ(A${JU&4XY(Y%oZ82 z1O&x_ZeN^Ln45kZ{ayLVzx#bWgWvUZ`e6jEMBwQ`0Y*XCs|c33`;JD9XB+QP{ya6P z@D#m;7qzvg6CF!BeKxZ&#K+-lHr|UFsXXPMwFyiNjBn1}=nOpn;2F1HNqaC#-gA($ zM)6(>cw>=P5}~Og>-t3(wQOF9C&hKpn8YZVM~5vL@dsStc|X$9`J4>@u+%hiZ4}j! z)zAG|tRhn_T8sMrG`~j}rgBF*cu1B}yEpdQ5IHIg)$kk6Ld(0t41t0S9`;|rWE`vQ zQ#Y+LohQxi8CP{wfj4DRY*Q;5_o%gc>I}Zl(vvcwIgw^VeGaa@db3;_I>UiRTFC^i01Iad zsg@+GinM(xoHr^U_hK%TLD=7<{@UGyi{h)@oMg4-G)Lw0T@v^Qv8s)cxY2p~7YAU$ z#h-u$cR``K%cwHv@n&;aDMurrX)g=!FOAv`#VQwX;IZo_c)kD0DP}E!zFEHbUQORg zE%@DsvKf)naB%&*;QCFK_GTb3M3QX#6KPMb0%((5WWP_Mbh~YHo>eD)!hH)mC%ta_ z#JByp#w{ND^$fxfBxs?>vx45t;PQP*vY|%4EpYJf6T{Bn{6hyR2=*mjq$J&slhNW> zeMw(W9ZR2?q=i5UX2KKk=FY0ais5md0$FoUiI(?wrJc{T-Y|`-B(`;=B z9FhNF6`TWpav6=!uMGmj=ChoZ_nvI-)qjjsZC^z&2v+w*G4$%u%^Kd2-9EYE{ujpF zX6-!IJSz#f2Q94MA*eWDfc2-{d=4K^5COS`#g{C}wXyjtyU2KPmju zc+C4CI@oNllHXpe0RKlVn>6HeIhD7V;3k5f`-<#6Glzd@ZHik zE^PhXlu3p-cyV|B{o&QJ`6SYz%*+bb^5}Lg$!S&5*`)vZF@K021vPplO$~qTCk!HgOkvC1^dr$f7^=-zP<|W1#0vJEia^D zWROzHRs4<22lxLvd>r^!k93SEC?8lH5e=~FnpMdE`gRId@b$geN%68XI7y^yqW8?` zKL7rO^k`0Z=d8=CN+7iSO!zW)C#!2fvy{(txigrsx? z_w#K0DoS^~zK|2~{ob}1aQv9GCz{)udxhX2&s!3&MTW_ty2176r)2~^>pPSR#WOAT zcksq>&bZVumU!sxYv%P41b}sAjGds{SBOfJj1ScZf*3zQBDWOO(PtPN*px;V6KX%N zt6k{evDs}Xld>9Fodi&j{=yDa(#X7feRDi_SHycY|6`+}Z9l7=@|nXl#ojKrnyWSJMrhmX>DD+`h66iBr8R9rz9Y_ zV`B40wcS=M?^NlWU3DWI1u|QeZxQeHL_N>_w-*Y-7BJ(;tMhqLaX@m;# z`~=MCOmRbCO#|~j`aw{)3_#=0pqY{f+C4~y5=LH|Q6^g;Rqc64KJ?wqSmampL0ckd zzTCYA7CfQE8isXt$-_X_1Qd2B(=Onj0ajn$p!NM(e~bT>kx{J;v()9UV1ZY&nxLh~ z1jKU!Ez`gz2M7k)T-W;uw&!XJE<8W(Zj%}XGH4S0X6_yc!Vs(MRI{76c@v|mvbnnH zKY5qQvtacX%aM#J_PG0^Xpa{U$Tl4ZGMdj&F+`8DY^O^e>)m6-(YKFskf)a`t% z_qD+6tS5%e9%XD#KF(UQ9_`KXZ-X&l39_|PY;cf4=Y9M0_w3+q2;2)#JxA8=7@)u# zpe?ACs|d_9L~4v1oIAHy+Y-8f(GJ(Pn;ugh@QQse?DEm6;rn2!%&}S$j2RduL5d-z ztcn6prUDK(B0#@a3Ctk+aVqYdCvl-5m)0(<$XEj!Va-c~xnwW|L+3zbgYxah|JtSa z&ke6C@}|Gz=YtM=&X=X)Tv__K5<3>2dV2xpq<>y~_qWv%NoP|d?%pNnQNIBF60G>t zQp1|T&8z@!;5n26?y?FHBI{ZaWbFc7Z6fHO;h~&|-al|X-7{pDeleI751L_M&eu~w zQ-An8;(6dmjCc%kSpu%oVg%;JU?0 zQS@SZD*d4U$PRFPRsYd?;9D{XdbI4i#X5XIbbF#fchgI0HUN5%x{RB{A963i#I7f{ z^R-3NTEN;X-#>JVGv`hCDZRLtrb0WAF7gCiouqurZwE@q>X%<=RN|NdnZ~j4SToL+Mw7v$+=uCvrUJR0k^<}4C(vesOOCwbZUh~- zWH5=W1O}7eE6DOs0MLCQjD40x%ch4ueq^){KjCId-wa*_=9V?R29)G*!9KLdVD{8~ zAW;U^QN@McHNey-%{A51>u1Re4eV7@;1Xyr|AAD{o_pF`lIRDuJE z**64zRvHZBW-zvCClEVlH0J1&>-WKG@1vK!#8^j7pv|lWo{8*-puL{?JkUjMlESZ3 zSiexS)A`bw{ud+gU`i9SdGv#GzDVh9>ov}>CWe#FwKAR%(j2>%ontxYGhqH zaMIs(Wbf%Mc0KoUPMh9Erc|i4LJV7$4Hrk{pw4d5TO^KgQh)dO$DCSRSYv}$ zC47!Gt3%RP-;v)dPWPAp?3~MR>9uIyO!{5Mij)tlvpZT;>(cosdW(fcERJeGHeJYp z4cIg7{4jAMnkRb7WztkjIs@8gpTX3zaul(apzDV6iSM!de620lcak8Twm07H;vtx> zQKvV558C;_93l4_qWHI7(y30%E%02WSiPbw(0$em!o?fQEsbT6(Ap2$6SmZ^e>L}M zTxlXt&3b@9_GsDn;4^5xm;6xxCQ*cplBM#5ET*8%q?t#&4+fOgiBhcHEy7e&g1_!t zN`B}T1r@Ch1?B6sx(ah2i7^3GwIQhAhX6q~`YJ8rXptGcwi#7?Tn8L47}&KppcXhGDE`oVtlMboev zNyN||7s&6ama7qIP#v(B z!U_Dn^hc{giQ%aYBuXga-6KsVqXrelp3hr;p>H0om5squNA-1 z?|4ip2xbqAo{|flz`VHW3bTrwP=oX^o8p=vWoAs=>JZ#}ISn>aY-BeCpQl(6BMo5+ z5clZ|Vd+;l*MFVZb8T*b+&LLKk|CzAd4R+CCi@4?V7_{K5;REgB60u*(eejpPcIM# zUig9yI+lo_S_@pdoc5R_%J%LzotKL8wEJMnTvCFH-*5*7Ul@!>73i#!lAf0frw@f& zt(}2K_UTi(QtRFuIO0hGYrv`ndQunhTP;~}@r5pLkr*Xmw8LX(l3D*h?=Jm*X1+1t zwQMNwPE_ew!JIx2g z87`hLh5>NsKJ8`mwk|VVi-n*bU~H<`?(kb8iP1ttt)2;FjN7@V8!IXRyn#B5%x2+# zw)X>}Yerz_)@u**^4J=cdFZlt*FVh1na+R-iyA)c1Gtny-!~ z)&UO`zwLcraQ!=CQlvZYOC-$n8m@&RMjaxBmvsOQ!+1%Wl^(kNI=r5_jFdzuoScQH z!KH8hfxMM7eeODmUnhZt)`{%Ad5`iFrV{0CIVkRii)*87KbKHR03 zMy3|aUMjke?d5Q)s&prD_0?z2tU|$eajJ@t2d8Ls9ZN_Mh%mf-+U5lQK}Qk@==prJ zTC${q+1@cuBwSe*?8$wbFT<(c?|^R`Z?@|wIzdaz(s(U`%ro@BVFOt0f^;OIrB~yR z(q!y7SscOzWG{#tJAd#f_OBaXC6g#G$W0Cw3MZ1GG+A`X+Leqr9oLuzl^-YsLcw(f zg~OOpB!{8tuUX+e^P=J0EQYgiGJBS)mjt`tMj1T1KKS=a@EbDPXl52wqrCO36Qfpx+MNAzlNe2ZZibD$tn#uC{ z9815FsU=Q0+pTE#sY%PWXVnT9&{3xKh$b-Qtq;FoUc+-#X6&0+Ld~T$YC^t<`yfHf zSQ(D*_a1YAB&q8THEz0)h;K1KhW|*8{sV+#r&Wd5ZdA_KYj@^prpUAy z(A#JKx)#|>v#B*5tRJ0qA*~d-1#UU-fU~qoqki)5Hk~A^Mp)t?mZ!$-(c9z0X@c#} zG>ePHGy3wM<7C_-TyBB?1ChHwr>Tl$51Xpb7|-Jc>8>l_&pZ+pVIY*&_4+4=TI%k1Ci4D{Ul3Nr9vb{wezZMve2M1(xCuT>40gfPCWMXoqxIUs^qgn~0AriZr2C%*@_!$t zW=Y9iq(`lz@o%9+0S-7q=s%yP`rm$9$L0VYLboP?2>cV|zCcI=KJL#U4L?4*{ilwd%4fZ`m%7eAy+C{?%EI$oKku4$GkBsGv$s);6K_{_bQBT z@#ugr5}$Sf@9o(O_P0_`j&}>>W~GdT{vd(BU%dTlCjaohpFgG5na*Z(1F` zL01V{n#g3uL_cP<74URkgx0j%-3H<-!L!Bk6s;{GzRYhj;ChITMX>)7y7UYuKpD)^%wjru79^Nk$%589FIVgz^;k7pL$ znoU)a3j`a1&Dw#lYcL!rl@vp-q7GN^=}owBxZH08g4& zQ??t)obs%hwu@*KHp>nHDnB_hIKEc zmKUg=z0a0Blc{LP#W98bE{>nM?s=8ovkdhC)i^UqUcGbE;(k1_ad7MVl6)$hNvlQc zOozGzLZaiXH?L2gC&}uo{1)~E?-m^KbC|N7K@EO<&woMx3B2|SS_!?Qp~j3V2CQN} z!0e5ndYE%-0Hqj3#SEqwL*?6v$wMAr9ZzV0^P>oa0=HM4TRL^8_1_RYG8CYQy8;_Z z_nKDV0ZQ&o3#h0}qGzjNjDs0so&ckf1jKl2RjbULS7O*1{~t3a|j|@?Q~D9?ES{;#~lhDFC(^5o2jxO(s;7o|I1UIQ#@ z91MVW?dK=40jTJC0Yq=b+{a}5 zz$d)m^}({q&UD#5F!MSA(9P9=*Y4DBWgJA(H>zW_ec5&rTe$_g1&|*H3;@Tf7XVdw zGDoe#d_nw?b^}Wb!rb4Gy+o`Lg@>YwH?dZrKECSm ztpecU-S56XJNpmU5Z<9-WT51|LqcMAd)$j;!1QcWJLEC+^ZDxVyelAtWb zX{<_w?3-XBy$*cPJQnA!4Xu{-7-gQczv8@6um$8vNHY4i^2*ikunp;|83&& zT?HP(`wg4!(eJoe*wdUs<+=6#*ktK%eT-6alk2T#%i1>?+$N%cni~185-Hu_j1g`B z4Z8shqTktU2<-bJoMVr~!0yQERUs%up`N-Eq&e(T{tD>+b=$ax!_1VdcSxJ^0Hgn|`5sR%_3b(G5lFk+g z? z0SFF3EMrW`5>yRL+yxmH>K%OLz#9iJ1Hs9McexQUrC`;I7^p6RXSQk~F}*xg&xw|e z$TdVLhsiENN2fAW{QCOu!Oo@)EsF~knIECZIu`fEWp85`5u+Z7!!adaEDlYa{3ZT+ zR2W3jo!QkJAe(b7-Zgeo454pv`sf2_Q~$!kIan^Lw+!iKgAM^-N(|jQy!4Ic% zGW=8%g4zm?;B*t00I(;I$i8(PIh~o+Q2@* z1d@8P!Qh-*tW=BOBumZm`=Pw}*0=H#T=@P}+A zYDmV%N?r_Xzj9BKHKyFmk#^-}h-2+Pe#-jOB3@Q$+J=$ECC+dFno}I3h3lWH54il= z4&8FN$K;k#jhGg4fp6BYJ0H&DV=K0t?#+=21h@;QVuascYXT1VT4R>tUeXt^=>VE3 zgkXZQU$60f&Fr^!tUGd2Oxs&H;I5|Qzf?s|Y!8`*!~;M8 z(>W=QcZ7>4qwn`GQUlXzc90IG@cw2>B>shhimFEELea4t+ko1rV%pc@C<*NNMKJR5 zU(OTwjX^e(CHfi)U*gKc(*0h+f{#@fHCefWEaNx|)jpEE43CQc$fSy4*kL4Fx-MJH zkn>1+O#TWMCp&Pj=QjY8xcs2-9AX1jxIE_F90V?l<8eIAI~%%-2wE@s*P|52?EtK` zBcR$qe{?NOkr0^fQ<|GD>TahgMmM39QN^#ysNhpf^5~cno*E}Jz@_z!c{ltmbL))Z z7yu^a(%8l=;(y{A0{{CqQgVG1Z|y@2x6<56?GX2A0DDz1VUZP8_-qjNzl~iMk{72H zdR55cER1c>Th&KQ#7^ud$GF}T!5UsKV^!r6waj4M!mEEAMk7j#OO@jmrzQWMImo~= z943?#sOWx+mq+8U)B%87*Du6CD&Tri69PicZuZwLoN-+q)0V<%gskxi4#s0f!OuA5 zDrqVptxU5je&;hD#^V9{Za84akSeTs;zaT*2`cN)^lHWLEW^&u87|+0$r5Noz!Gtx z$Pcy+-Sk)HWeh?|ftYLgR8OgtIoL3tG7aE3_ArMkqanOxIF{mNTO`qna+P^{`nZG{ zi^9TXpO>X@BgS$RwA07Fc`4IssgRiPCCK8E=H$lVqsUmQBeIzJLIeZDiPtt8By*6; z)IC0mAA{8unf@1fZ{b$e*0m2SAt6X3(%q#Jv4=fv~8*Y^*6*M&#UcCWSOnsdxK#~k-P?vWa1so>1;bs7_N zk^E}i7Dl%pLhQFydA1{i2}sR1t}Xpe{d`5twb!5;sNnnWjS`(=a1)1Oiq! zr1%gQbo8zcl3pz0Xl)a+mi~@~U|jeJZ-NYbA9N<-LRV;026Hjx5+loUSl^5Ue!>K! z9gRgR-|pf2%4k~R3oV=~`n6$OuaRr-SBtt9oA>qULnD1jaod$hZ{c0KO9`XYZQY>5z(r@2XL?-qvD|Wz#gtP7;?r+pH!7ficr}S1Y|0SylrdZz3$!l_F3Fg8r z{5#iv-BoW-3#xCX(^{1F8{R_A52j%&0IPXSPKqaHWui%ZW9wZcy0J+{oLJPlk}S_o$EN6 zhQA~zB|1dYMbln*tQs(8T@F6K?<;!*NpIU@aS|XEPj#3*=ZVtuXmgVca zvtoid;+}>$Zd)Qbx&G7iSu*`uv&zA#HryqL6e^FL^$(MHR@&X}v9Gk9M#|0N`3)=8 zbp?+!RY(@{S5!QW2&o^K?h_|-Z%nE)M>iX~(RCh5UZ0x|I{5i^8&erwhv!TClVgs0 zDL+20Cnszm8I#bU)UMt)mp}LVk@DR3=Ot9G`Aw?NF1mNL4iut}T=b764`1GD@Vxf4 zqPfp|T|zaMAH6(Yd2`?W9uL%LkAZCH52a;a*nM-07D3>{H7;bbB0Rm)Y^zWcRL*|l;vv>^3Y^Nj<FZ#x$D)NNrD)+Uc_iwU$ zlN(fT#vbR~YjPf`@GP(hHa zGhcgN%AK7bwQChmGFQ7Tn-j>Xrze=I$0}|$;oK1``(|@(!jRFn4=W>xl2aq)2IuEP z5Yobe%H$M7qhTrhI5_;L8SHZ?-L_6V7Ot0ubZ`K%C5!1Boe5UF$&?v1! z$YPemcO%9msLh7%UTbV0t_bq+wrsXxWX;d^wZ@OF7lSOn4K_|jH^&5dec;iwxvH7M zHdJB~E0rD>OYntSZIJ#!j^aj9Uu8G`-V0ad3!{*hF{Jvs!kC+Z6>V%Nj#`-)U&fPk zn+dy|XJGPOV1$1`G=_L0jW_3~+N2o;yXiaga+?v>=i)B08tIK67gB<&FI1W}S4^gq zhc-Pl-Z{?7_M1)k*)ktk?)Js-`LD(;6sw2Y^M>2;vGW3Sx}6^s#=q@|dS?%|ui0Xm zD%1LZRZw+rbSR#C5{Vao>Iu_`DW`@pH|}G<7wn(P*1EcCJ*SH#x`c|{oL@>jRV-?0 zuHi2tYYE}w$MC0K0MpLUTkxOpxdmE6p4My5{>OVSV-@S>q^jvdlnIyob#>j3Tr_j^ zucb<;Q6yzuy5H|_G&R|m>BI5sWqiwBCbd0tgPit&i>Pu9<*nNMD^Y{2-gt9-nw%_m zZ9N#znj0i-JH|-`Kf8*(T+)xm zoiBur8;|2Om-N(L>lzc~+#htb70u|(^7B~v$e|j?{+yY%dhvzd!~HBybbE!U|8T$Mk1AqAOTL%XAel6{9?4Lm zOjbG1!s^8RjtyP-hM^ZFO;Ip;wB70YT*l!UCwUCJeTath?d~Y??E4EL*s-DyC{+_# zI_Z{3I&}+jkN97ct0Foco;Qwgp5tNOyUZiwykMZsJ3F`0GPn3my?`WIv3+}a^0o2f z=6lleHZeNcHG*Fja!EVda8lW>p%j|a`mVi~L zV;5SOW}<7fJWFkwqT}f#R$c!rAEbr z=+FDnv{p&^k#NyN|E~Mot02_Ql4FkjYpL=(?Y%GV_#T=uE{GpC?v%Wx<&nuyy*-&h z(J$)CgIJu^(Y*Eg$H$kMK8>G}_#3p5gI?yt{=6HT#YnTVl#XxyhJ;q;0-0gX(_{DSZFfFAYPYt3or2r>2KS;t zw(6ZM$FGeScr=*w2=r&NI|iJh8xY}7k*^1h<0%(c-mQ@;2o!YOPMm15I$ln%y!=Iz zrAw!X;IfU<^bC`f6%(I3{k?qEsgDBw`L@z(EMmSq34CwW;+1&?7Oz@XJqXgOte9j| zuvcK0xH(Gn^K0Eb=haU<9MxVh6KpT1rs9P}{puXQfJf6s7&@B?FkQ+eX!qNV$sA0e6?fa^r)x&iIalh^1K&+0Dqu7h9bZ-m8 zr=NBF>Q8EBPg+0BE6%BXnWH`UrSIAS(FGypNg)9$b<4!>_BCo-hQ$3z_0yxHjiRGT z%`JF4AA1^7t&W+Dlv)Ge$j7sM@pc7yLB^z3JnGw(gl~_3@O89$RpYwksvWFi2bG-V zIsDZxTNzZ46>R1bH##8K-)HpXEaF~R0%48kv|YUJLUk`uA9uRU1AgC7jUL3$a;dxh zts}A5)r|%8F2Cmd_%!F);1H;h<-2}ls;rDB%~JXNweuk7qxwr-Vvbnq@a3%VmFL&n zv(pl`9~tYFIS5r#X7;8U`f+@%5cP}he3e{D9Mk=@{R#0`VUx!uQWpNJ%c?I?VIN0* ze&vkHzck6BP8xorooQIQG@w z7WcO0$;L*n6Izp(0S|YUrgK()??qF{09zmtGGROl+wS|@Q8>4lU#L&N3&NX>eg{!d zoK%JcQS>{<(L^Bw=1Gzjft}Tfm_zhqb^m3#f*dnN!cPCq{GuMelbLU4?SI9tWvf1p zDp<`rp^u$NHRQga7S9>P`FNK7>gwSlZP-Vvu7vAtS_V@UiCx*GG5J*L)Vv*aE(f_@ zSIxCFDM=WHvqlr7O{ZVj`h8s&*;|^Dn=$>_Ev03XG0dBmVwZ6fL${W2ccB4}7-&y2Z*WS-fNau=( zzW224!_JkXpOdRusSWYQqx)AraG~xO4&-HZiN`iyx%|$)uz17h%|URsM!Z=6g{dOq zu3;t5RAoY)3vZ@zW^8gwSMI^6!)tR<{^Vc2v`g8 zAe+(&>FnW8Fud}I5c)30>|uWmC3`@kCKN=RSm+JpMI$wrziu_=CF|@}+3&ol^byQl z|6u0H#pbR;QMgIF&^U^`6c@l zJ;V8g0i$wz&5e}UU~z~19xW_(QVg?p)a4gdG5fw+}C5jLFy zRxT@WjRx+&9oNV7@rr5-1+pm$zUEHvwzT~mWj$VI)s1X2f=?z`>1c*>Fth**&iy

yrFxc0bW|>V@Izf{ z09|=*w9=Mb!0_@-51@?ALA2}UNz_h1$F&sw28h`Mi!n+gUCtQ3^zt|yX$GW6D-hNA z*(JS(toPc=2C^KjQ`%lrqZ6Y%jycY+>`It0~oEIVSI zXIcqV0SjSfCFtchsw%4CoZ!IgwY(?<&wkJzCEyP!7SXRC!fY~zV3|kw^CeHrSl<#6 zqc8p(&zDHVD5DR696tor6X8$i$??vWdlPkUExS?-Ac~$<5|zg|;W7yJ4C$EwHt>24 zgC>fb9fZ!m0hoJ#czrY{hG*GEuz7DVL7L`WEHK+zFrrm* zk)aI?nELjP9gUIqd=Cqce(4K{imMq-V?H0CQ3cGHSpP;&+-4 zEoPbwrcIv=N#jodInD||J%yw9HCMuz2dRz$%)+om-#+-2JNF?*35dG6gVg3jytbQRUM(#lol}*#l*siXYXlhuBFO zfi1S)bN0{$qB_k@={eJOEWt!%iiizTf&Q~%e(!9#pw1^30AdLk5bK8a2WGM77bs(ZjM{5M^c@uQ(eU8u~E0xd(xLgh4^S0Uj8#Rz&=SQmQKJ{&e$V2K(F>gAFug z8k8e$6_fGWM6OOYzN(hwi+bhm?EVRkCb?~*yXVF|edAsa$)g9W)+?@F5zpRxY(d}t zNiCh2WeW|E3CK@3j(oRH|Ap9 z48F1>-e5)68qC=9h?$K2R{)6ylrGdLtnRdH!R*$cU~c9N50S>007iju0l^U z&;lg9ZeFI0D2-r;a;J_F;+GQLDjTZ^ld~x%iyzF{n3Y#p$~$`yLHxg0vNuOwMhC60{$#IbblO!3P{c@ zDe`QJI!z8yN4%T#Y+WbhaOU8d<$5=*`e&U8ozNkr6M6q0?;#chT6zaWt*A* zD#dUC7LUFsJN7$#sXiU5J(VjBh`rk7`?Hb6t?Q3i5wa{=)eA!h*uAZy%-45ij~VV2 zOEiE7@$d%H?sf=635%=e6~RS?%S5dBa?!GgCT4t30rLI%;d37-ELj1fzh;1wsED6S zCSHn`moHx*Wk+%iD<+j0Rn1BrOi=*hS#hB+!~(-jPB4?d2BoNI*wORdAS)I>uM`$z zh5Ot^9EBf_o+>t}H!R+{YOFsR14>zY`%ABIb#8>!PKZSawK@YwLha**cZxqOmfEJG zXp6E=i8eCxv(qi~PAQGIu}0owKZKFa^F8CbG1N}PQ%8EG;=&qln+!Td>S;58iMXGw zK3x7zH+O!>jT22H{mF>mK;cAK%jq1W^=>)%HL72C+%O!ThIBW`Kh%JP2J2=8i>ImN z>lFZ(Uaz#dNu}JPDawA1jMVO@)g~= z4Nxp=B~q>5H`qS-&e*^^Sf;C@6NyV zCG0Cuk#G1$OMW0eezFl*lw}O06c4GZt{aN|XNTI}a+6X<5FoUlP%7SLxl1Z39ORm5 z3ZNRkR2wNSU8}i;FFy zKy#Pfnq>0b)amh@O^UWbP_X2HZrEF|)cD!4K>Q#czb6mh5(m0+qHhO>p7!hsc*yXH zr6Sr6_>@X`>&m8NnuvGRii8(`_!t0pDSPFh27)@mKavzDwUC2ItUxv3Q{}O>xTDbl zFLOwBh-4Ro=`6#j`@S-xRbFi10LRaw}vmkvnX6fp3q+GnNF+(LLI zUX%m_Xd>_-0-2MM_6S*|EMh-RP~{y5i4HyfIWec+gIORvn<&UJKjEGi!tgY5MUf*2 z1y_Rn7!2K^SMlga9@B~<`M5d@ZMiHg~-igwySoIzsax*)j7J_lJUgq4PqS$@?aBzup(yzme=JXqfB?nbnU z=oXL#3T+jzE^;DohERf>mGQc?Z(T1F!cXT4>mwwIaxiJHiSH-U9Q19ro7A{5pTNbb z=Rl|X?dPlMDa%@mWWM3nuib?rbOYzE@*rwN7%hqD#Q3fGA;clgQrRFFr)WyCWA6*F zgQqu&u)dxznNQjWZDlj9&ST(bIIQ)ILb zfunIr#XX?TFLLr{kI&zK`taol$QX*(u{SKQThiEGQsiANch9j`*?K$5sJ9!uMWbe> z-?33A&kneAYa|~EF9z$;3^y7m7vesVB$>8ICgoOa@iAnEwAW^y;ZA5e8*LD=Z8T>n zom1UD9x5!^sp!O6cl`qWEyA7Ukt~NQGW%fssa%FFiz8ar01%YZOANvhb)2}hg*_9D zPdfMnmcn>t~FC=}T@96Ce<^X2H%_~+P3712xP_Oz(;3|}+U zSw_D_C<9E0(>YRh`_cRbIe!)%TtZ51yWaL_Kz?`Sf+~Q3J5SlwPAiSfLr zBa7cx&-h_4WC0Xzb9S#)O8LWAu5_Qw%--Q%BS*S6O!`s*!)@Y)_xkc0O5OvMZD)IL zAsHG-$jA`JQNQ#YMG!Pw%;w?S3L0A%gXGOuSTeJwf*%mxp}C3(ySRp_?ZsM!6n($7 zaq6^vYZ{@yIWX%#=O3Jd$4hE*iQ~A^K8aY zdU@-K>7gz+U#j1X#8#9RuQ0Arl%9OrDDIU+-zRv-j7szl$GTWTjpW{(*PDK4};o1v8?@D_D}pAkh3f2)Y~nR-LP5A-{6QG^D8=#|A^CeYKW-8 zg#qQhK1aipH-#2*_Ce0%7tWq@1Ev$o_Eaf1qd0Y!yY^W|9@na@3u!j9ZMdefo)1G` zKC9+z2wR`rbv~^g5nAYW0nA9q$0u;=EV(IEqias&+keRQdAGj7k3~YO-8!Y$!F9jO zZ5}VpkoGfyjO6<-$W3fhZ53Q`gD(BqHoTRVr#F2ru+D@Dd9+tuSZSaZxufw;iuRLc z1mB<)Ggjcsov4+INfhte&-n9I>nMLD84VD!u`3NoPAsK_l_zf_MVBJmlO+H$j6i@UW}Z^?ODi6vVJw8qyn9&M3Z)5*<8I|n9v z%H%X(m&$%GPup{@f58q&mp~5-+Fd;p8Tm&&Qn^a zV#ETIAAqS}WHul*pp>~6oTtbbZ5Y_EDWmy*gY*e-eHzMEakNCs1SG_$@$cbPPC=8d ziXdtGl-`kQt<$$t(-F;o)vCRo_}XHF1E)7+*Zf)lgD0yo0oI&d;9EhHF83@YOA1uJ zdPZ+bz^7U|9#_jqt`g7kaE9G=N`~f$i-TX!=zPhFh^l?1aJ+N#0=IV2a?h1UE`jt6izR^OB&3&)={N;VpzH>J3a(YIh?#xpJ=vVNf~$O^=UI3sawn3)iT!Fnwdm(2ULzFX)h5-wN*aqW5zBK66~a_imhTjU<{>xeJ+Q$% zkZbNYu_Amy^sq6B zj#dAYt=wrIOekmeZ6L^;&{(rIZ$}555HMdSelGfoG$jurj@(w2#TQ}+E{2IBgVD|rbbWGUZttn5 zNxj07k86nT*1j@R_sAABt##Kde*3EQBel~a%3LFD9U@ZIn*Ud)}M zrPkHFX#vky@v{f7>0gCbSQMRit(-cF9M&fw)6%LCsPHP2qq--gp9Q+P8$IVpwszv0 zwaGS4QIOrv?m+~-&y5WrA;5V;nQ4<9!;12>F_u-!AZc$Nx~W4bz=>{1lLvjQWz2j? zjH$YMg$KP&b9XxyXN+a4Iv0~DM6Dt8!`(fxf26S1MU~N(73;^zae6lIrKw`-#$Sef zoQt7)NsIa8SL^#EOhDYG36pXo_x|(8It_?bS~bNo*I?wQ?zG12ZXql7JMFJeNGr+^v7)jdYVXmB)b= zf^_}xb9)93)fy5G!%ysK`O$g=G+0`Ux8e)$im8syI5z%_h*7kE#*IELqBlZHzAhaY z(?}m(kmI~p&tM0t91olNB13bG1%`%jyfd$v1VN+6a0FKw*qz986ZJPlp4GD19U0*; zj!Ch2IHtzO?bX(80Zy6|?SBc#8|QHT7T%KdXTT4P3AlhS<8!D%T_VYi-N<7T^1VC~ zzIR%2>U;R!&#uC+KTUoLYck}T5 z17%`mR@L!|y+!UKM!m<1Q(9UPD~-AI=oO#y z?k8Cu<1q2Qw5bl;-6u`^<6P_>HPt9~Y4OMFlia0u$c4EA>A3vjk!vzftHWO>zs9!P zGQwFkk>(fT2x0%A{S;gdKM)0Kq=$#6HnngGWuI)0_f>n5DYBftPVubne(0v{Ekver zxb>o6=?1)a1K0ZgfQV#CeG;on?_k5L6j3j9Q}0R^yUW{!pVxwsn5etncN!rztOPb; z+kuO!&-pXhVZ(LywFq5Sn3@@=bzT_N%r}yIEi3iO1RyI=W)Vw?IWNwxpeDz@C2@<% zbiHkF<>$4yY{R(HkS|Hkef%C1a53-! z-?sWw-Vyc%?~7qztpPaA8dHZQ6S1u7R^g=6FVlg?ioJ`ZjLH7HFrF(kWu1 zaUQwl?&SE|ST4FuPl2Vb)^>vcs{(CDO+Z5-;l5on=6~PRCebP`+9enV$?SuZcBO&! z{5DbC<{oXxnxf2CN1SV`2L`C~t9&t;9GR3MVuTUDa~-%&dy~)0I3@SzrFY~Q8_{G!tn`q^N zSj)&mkGoV=2t{wlDIQNlx*iQ#^~wBOqO?lAhT{t1(=h=&_=k1YFEhsJUh()C_}aF>}Q#i9miO1TcvQ?_R8^o3<;D%(@`uQ$46^w9WOrGz;t?Wo)F|+e%LJGABgkt#;~c}|3=BEgi(=lAd`psR51pzVp_i8>w+Gl z?q}0TNZM$dMf|(s*hd-?o`owuAzjqWf}pmqgr)%%!Lz5J+|zB<6e0Ul;n+2n$L)jU z-uGn|Bl|m8?Oo&1#RpodPtHV;COx1ZaVHnXK3#ON&TAJhoSH3zUBh^cNVDoDony*Z zUM zKBMjQgb1FQkBL^s>Li5z#dQD;ogxSulPQyTNHt(p?MqCYcS5OUbC-p^*TON8@n(Lq zY7$-eQdjNaW_rl(Xn1rI5@RCw2wxjwCQ+w2Q%8;O`MLE4qgcTQJ{{4Q0)ga|8BQkf zTRJTz)w~cpt*NEGdoCt{b^o_i&~a``ji>rgOEvDCUpZ5@Tv&da!}8>%oTuxi7|lI@ z9MXnUO6InzMXN$VSw1qh_P%4L>lE*w4K7zRd2h{(C_UJtKk;YoP8*BC6MxcKn5e~m z?c=3b=5elTrW$K%Pcb8@_nqJgP^R!zrZ&DLI?wlON_wnhq|`fWmGXS{cFOE{-s#ct z2uDVZ+5Ts>^U^9sIF)R9wkE9+iYuJstq6OM`}=Q6j87hZfB(mvS*ZW=bG=ROf!A7g zou{+W(*$pFNiWt1K0gr8UUg7RvXip;sXW-8ui+eXs_5_8B^Pi|36BwOL`0?zvgKir z?k5`TCNNk2BishRd_qhC0M++G0sHwyix9*k%eBvQm~V<4t&|soRsH=lMTP|>?-M|Z z5($uBj?o(j#<#f!LYRq~2Ck+)PFp_ zDFlZUYDvC%75fhIRgkYt>g^Z=vcW#>cP};xKK+mS85qX!^8iMU{tLshhL}+w-TM{b z%k>}aIN*DhUO3&(oiX87d-W`)+mn5XN^Aew9(T@Dr&}GeK=C4aY3P+YXm!j%AnV~c za;2s!8Uu{~x{Gyi?H@0Dn+*%9jKo7`&&O(~*=!J9!9c+u;9@ICX6P%oQhyHm2XTCQ zT`Gvr|)vpv6jXD zqcsOF9Z*crgN^AgBY&LIU;la!*yl0*vvSPSbo|eU4JTo8k>N$QuAY(x(EqQ2yX^so zJIth9g@;`E_d_s%=-&@nC4~}D!GIiVKur_6#e1Nh@f3ubIsi{ml-0d*8vw<{BkeNt z_s)Ctdgl&TYu79Rd5*ngr3L|tM_;Z(?q<$}j;QS*|I7A&Pyk$V7GGGbD`NUv9gufL znQkMZF&lmo5RYU&oean3L6G|S z^>xK*kWUJ&k9pVSv%UP>b#=@@b-Lpz7l%>^(Y05^PPP6g4eXjp{RZr zirN1FQX&a9WE_R>7iP#j!`PtRZ;>Q0rgf5ZV`vRN-D$+JAHbX#RU)5__vb;C$8+S3 zW4b&wnQ=>^&7U*?ES}cJmzv4C+pFVz`KX*&5IM^87liCcj3O0A^oLdXQJ(F!q|2(H z<;(_RCkX)csbwQ$i0BMTZb@QNNHGa+prpjXrV5`Y4 z9^8gf8I~Lw0CL>4cLeZod7|D31I|SWL7Rrp#NCA*5hf$|A0`#ebOvK*Q&@qJ8Ta82 zjI0m6*#S`FM-T^!J7quFU~G&VEAF#TKLhe1rYHAL$$}-#@8QvP4AE zipD~UCQq3whuRsQVEt>)FDV;?G}1)5+mbGo@fg%#DcDJNY={AZ6*7umGEP227SJ_< zSjEk0P=C4f;HM=f`7pK?lHEFiiWLN!LQ-yvH#n+fy|?3lM8p^F!hymM1eJ}4K1W+a zYByLM0YD^r1QI2AE>J%w7T_(nTabI71I1kwh%kw^?`e68t<|Ar*)Ris9`3n}K=L9v z^20B1sjZ--l3)Zg$?v3o^80Wo#4Jfae+6QU>K1cA*sXzrn;aNP7D5&$(k4hx&HrEk z3M&IQneQP-?1oD-ASX)&*eQ8_evoTMHJuEwzoF3^U>|I`6iEi(P;|W&-z;cclV>|w z>!DS7n&&xCBJ|u8(&Rvii6a~`bF`P3$n2GR+0d9=S9^JOQVjp2fH+!67DdCRLWChP z0E=F;gO2qnkWyS#30aCrd(RNl=Hau?UH06c2k1DyKXZjtrpOz#klaYI5fneVQVUxz zd;=6!jhCf1EP@qvwm10x?41zw@AaB_8ICHjkeCgh_<3UF^dj+@_d`C=5@wTT#>;xU zbD+Vv;$fN0pM=J00Uag}lv5T{fkS$9_*=M!#aMsx4J6iX{Q?SBVZU0oQVlPf^hWk` zDK(Z%$1qAov6#hhFUBi={Q6w_^DO@g|HB0!#$?c53DwUa4&z)zg~j!P z$XMPaFux@5l7Gsx_fm&JNHj8t6%E1aOZZO5Q$Zv*4DUhy_e69v3~YWyulveqzSs+) z`7FW0upUfSAny@nui|e80&`#~Ff5PTR~c3we|HBqS41ar|%2In4KD#6m`8yj;z_FPt25(eFW?s=!t4&<6^|*t8^ZY9=9} z_`!f=v|_e8r+UJtdtA&(?{e;Ur^)ithFY`D5#D>2cLFxWn+b{MpokCRO64SsGTJeX zUtVgd2V&v&(;~Cq)UcvK;^8LUsstY-#m7SuT4C4(WTD2jT%+01*SuclC8Cm}E7{j?YR^C>ENiBM83mSNU3IUOXnemf;2gUnTVoC4LT*L&udlkZjSW8It z?D{CA-RM$@YjX@Y+vt23%GHRTFx# z7y@;LMb17c5btA3_%aEUb(!T`v~|qQVVgJpu$R-nK$!uvb$#FSwo?B~3Kt%OY?}S^ zzU?PPo(h<@{PiOYlrT6PqpZ^!^{W1oxBcyoVZ@Lz3yIfZ_oMUd|G0+v&qqy0EB?|j z{`0D)r#S1Y%5{Vf|CpXlemLt4rI0Fq;3lL0WbdaJF@8Gf@bOx}DNKX@`e~~A-LkLO z{M=Li@iF|n{Mp$0!AIi?!YJ#V3;%X4z(9a*cY&v3ZTW8Zzg{!|hlZz>{&se>Kf&J) z$8XQWodcA3b9zc#(vN=c^MCh10Ev?(_&tZ}fAz^9zmx(^4L;vaJzAFhhnIrcZ`jb! zuy0-e(1`Q*U4CCv3nC}bl|yg4{r>3+!3Nb7TAdpmqj<~#zyI@RI1wx&M)9D_Z~MRA zKOjc&)9DhPIn&?AkiV}9FeVVjxK&GIcN_of-KUhGQAm~(^1u7{cSkR)2VlYgzIU&9 z|I?#{et|yuerkyFr_k@M;_u6vN}wab5pi36J^5c9xz19;WBGq{@HS|X0!G#FI$idk zUM2L)ZO||RmhxWW?}7OHcDMCFVHi9|shttW|LVwH(jm}X{of8g0HsopGoBpjPW!J8 z7Dk0hHi`ZpqsVt!1?Gf%>cO)3zj{9Uluwu~7}5WB@c*}QO(p#wqZkh+5vN$&<-48y zZ!10}*D4AE&i~uN4Pf`6uk5k?`p4fr^1Fi|#sA!W&HrN*)xadwGK_!79ccc;orY^p zG0h}_O7;JCuqn7j;;iUDwM$eXRb46d;{V}AV@?m@RD21YKdPOlKthlUQodurCjbhq zUP@ZI%>eInS?{V(Nur$#7td1jM+3P{y}@ViR=(8yGsxEM02*@+{LPZ~L*R^qXae59 z#s)TKZNl;BW^jZs)zvuM7W-`;)%on9fEr{iVGKE%7*1@Z?U33`Yq+c!ZaRpd01HtU z1;waUJEB>FzSt^_0a;E6JT^BkqU=g=%}|B90&hk!k|S;t;M{==PX{hM_a83&U$%tt zP$&oC_vY@L`?y+W~3WX~% zvJgiuP~EQf-8Z{}0-pb*9`Kr#g$F;fR%dmJ(E*pzs1qeLQs5M@ZPk zP(LvQMg^QT01eK6I6o>5iX|LHAUhC`PsWM_u4DW%3krWj$rQGK4$Pqx)DNLr=1oiR zd@lL!yAC9R9EckDfddyo+$0W2n7sLii-oU1(p6%y`XTOF+Nupm_b>35kh2{ux&$>S z7kV;+9+l4=!q>T}vCj}ib7`e<>nI;=h+I7*K@tJNB1P;K7;%pk061eYJiUiF1pOO8 z<*OP=7pPVLmp!EcQ`=RCuscPP4WovkBaS@Z#|4KK9zNY7ZLA9419ws0=sFC~H|g>{ z3?WXff?0r6`9mLuqX~`G&BQme>(7f}SBpc2=kV!VLb9|vLqX8R(R%Nl1Pp<5eg@dA zH|jBx0T`VWD1(xLL%0$S=c8!KOcDri#=r@xGynR_xG@GOnD_@HEV>Uq;4NDL$z5w( zt@u{JU4xr$0-3Pkc;A+zAo>k>_-B*}odo*ddTyAjrpdgODgowYA3TBi42C^u9vP=w zkpt9l)ayH%4~`GtE|0yvPQX6*0NjyFKz{B%QeId4*JQjc0u$&w$QQf?MyVQ58zHNF zhB*NEuc(;UARkefkFBco@lHz!aSqVooHu5aw=lv71^AOGk}mzDHE{IIOSkyUl1-jD zTkyMNsPO>^$rcbJJBmyjL2Bja=E&W29#x->8MNU^m^IxaMjn0)cMzL3kQ<})X&>OT z5YvniYylUQ1LTO+CP<&BfH;pj3f~MJCT86uuguKy^4*uK5CAF6rnV2AG8?ymvse%f zbCLwG!8y9P&kNqtMiGoCTT;dthH(bdks1E!FZ^eo1eRjv2~eIISjt1Nc!I61y3>qR z&Bm&oFd>yi50Hj@3fdF}_{^DJP)ttmN~7ySY^);k{NN6Tk$2<+sxrKl6fu4!Rs>AS@YW|xrm5HfQCgN;p1i7e34G&PaB@QH!S*I% z%$zj?)h56rq@hT8hfwKyr0S(vF_94Ml1S(0_XKIwnqM5!c92q;BSqhe>Zm!)#wx_M zrM^4#U;B2FGU>GJ+cj~pT;Khx=tsSY&?~2|2WeYHTgN3w<4eDM8f}Y33k@kUMs8A0 z_#LcVq`g`}=A=x^*`0pH-!H-%oE!=w_4EM?WO`Qz#{v73X2i0MHi zM+Wh+d|kPt1+7rvqPB-ksMvOhntNz?SW zBiQoG!Uj^^M|nU^Te2huL0_H_Z7a8#L89zrS5bNqZ_1cFIsk{A`7{Ai9*bO?a*&yD zqylYC+gw=4J$Dy}a3=JU&+d9ur1x((*-{3zlGj)Q`O=wGs<{_eSm$LFT@%TZR z+oN^x=X?J7t^TX>I?t4JkhE4gik4BDmb5(C4zYuhARw*c;NLEb*cg6WVaw8t^eRxs z`e!$BpE<2;c23#sVn|eR+~2(icSSM3;J!hbD;%{F^jD{19@fKrS~(-L^j*fR{XcIM zEl-F;iGI{f*;eNJpO(Wgz^}CIm>Y>nxYlX@>(R)-fJ|+jXU!5-B>%oq(C-_a35|NA z`o|sq98(@rZAxCk>oo1#3jey1bu{Ki!&5yQV*lzmW?ZaCippk$v%_*2i}<@$#9$q~ zgmm;$6P$k-%b)+0EibQ=$E{&T{}u0FH+rG)`$j=Z?O*?6Ucavhq=b>7Li0pe{MTq) zMq+MccYoe9`Cok(jfLquVYHJS)4y+Yh5&OT;&Tj+Pyhcj2;4c`b;tWlEot7X7rG>7 zBZMJn*#mNSrJ!vq4DOvUWHSjvysPxfHEGeX{(txVX#&bnc^+k!?*@0CTQ!rb^OGeQ zyN|4Y66p>GHL74elLs7i+oQJApffHIg=?SxuW?`wG$G|K=9by&zurQ?l|rg~TQ|YP zYhkz6B1$s%JhJ}gKdps4THXmiPM6Z0H8U82C;hm&>&p4|h^ia^^&JZwH335Dt7jw0 z#l!;Y)c^Ib++u+!xUN?bk)hLUPIAXc=wEi%uk~UxQ}{7;n&(V-2}hCtp=ap7nyY;u zE9X3@cMB5X(chPs*co$aL8%MeyzesV^DjG<$J!#xGoW zbCVqk*6x{%J7axyZ1k<(nec8oC%sGx!7WPoTll?0XZ}Gz1N#fdMfLs4D@Kzyr1@TH z1O+tY)42DGQ?*>HD&NAfAxGa$dvHgiSZ4l3P&4RxHyhd(Q|X%eZVkTa;<}8O0u@}M zC$ii6&m>*$Q2qpQ{&T>>zOUr=;3>{e4f)BqyGwPi?e}xdM>+?^uE|gKOVl=0U!Uwh z-|u^80)La65Q?x;iH+TF5q21>uB#m1?nj=|*NISOwl1 zw3PQauSc9}GGzOOAJ+IIMf$Hzf!N~#IesN?Yb~0C38wR3rV-vvb<fHpYeIzSlJkJhI87S&KNlj})n|lF$e<%YXw{t{%~J zsgs|=1VZ7ZAOXfTC{la<4Ay?GYjKgI+EA6%{PPALW4@*2zRF@*Z|T5CnfKvDF}?6I z{TxUf*VK`--QS%K4Xqq9`HFwv++9H3V^ed%&~P%Y#J;mf#P@oQ?x1*%t&z8G5I4P? zkLQ$9>E8F`PQHs+ZzjBKpUL@pRnKQWCSQ6!&VvnY{^Q$UFKueT4dS;n7e)uu2ABzl z^erMi88h0iWsBeX-kr`=HRjy84#$s|Lz3QcGMMW)F;DrQ>+nbz=}Ge5WUI;_&Tru6lZOyL@+p7XtR6~^8OG85Zh80MaaPpppaM~)Iap&b+ zd&`yND&Om?sTSf^OUG-LBM+QL&s2FlYA%mDooZwtV0!2$?f%%YW!3A2@0TjakM%Cg zxpv0NW}}0Z9v4otp*iT!`aOv6nGbgzDN7DxDRfmj$hDu0^ZqfcIa2eexuV#1jS|hl zhz(yF-o;(3v3N6eW;tVTRNVd`cTBq7;p5;<%3OP6@0Z;C8#L>kg`idBImA$lEB+!= z*d9Bf+G9VrBJveH`c=L6;{Z^yrzenlLryCjBPi`oanUl~!FsY{CE0n6zLv*m2>H8N zDun7XXAXZBOztkXd9T023x%Y}5T5I~!4^+s#dLpyq~aAwk(51L^=LfHS5j?$MCEB;rZJKxN{pik#hWiJW&|o+=gnZGuB1`WzpJ4_WV~)d{8*@=`o2ZpE86AZ6~3P<4@$P}N$#fiy}^l~+!i>Idr;F=?6(X{CILiRAu4(I z3SHI6o#geM#uHiH@&R2VG}Fm$yBWmuUp1oE@{$8A-Z)sIYZML|tV#d@5v6zQ*U_Q$ zn`2`lXx#hk*lbf+JXqSe2bUj-HQv0Z?b>iAaCgk58~2>$n|_t1G9$W|nI<{Dk8LEs z8k2w{AzMNIR`-W)BMWGt%}c1#iQ3$#-d`+i0VnZ1##2MX`pW6E+ro6N&cM_RO||%H zSbC9lYPk5U-n8IggX8n%^NqX8`gUdSXF6X}Xvti(EAQYm1L)wQQU;g5%ZODX8iLZe z2u3`Ibf>lpX1nXt41P;Rue%5#hp@JxzS|=&XOp`9kAF=! zpB0LTY4%=y%SC^`>9iRr@0$TOHw`W-$(r9z?OE|E!|~hg4uu3e_D7>{9QO`3x53@0 z3Uw(-%XBH6qz_X-Dc3eQO*(f9v~>GzzZSkf1$?xvs2TzZ_aznGJi3ZCqwiA7r7h+K z`+e#{M^#8Of#Z-c*5|})-jfH-LygB@W~1{G{c6op$@*tUKaod@eKX<{p0oD{ zZt9_7+j70-(n2im8m5S|!1FSN+#O!{eks3mIxZb0)pouW-bN-6JAKhSe*s zYay#LtofDCH@@lglf%2iF5R*%=Ns11&)i1`9AyvJTc+PM9@$4=r9tO8X>LN}Cp^NM zA+Uiafj*snem5;VrV}!OWii`phX2X&9<79=b)CMzE}uocH^qhO))h7Ij%JxoXfV6o{i#5_ zkgY)@A)ggn)1`GI$oRyEsDjVfz$WAsMK(6V=+3x3ckJxDN)}INU!fDhxmwzCF0gU{ zK?os_lx=yt7qDEOc|kQ#y<)^{G14Cb&L5qM-WZ*mL*>_1fQX~+>DrNKJ(!IYpE(zx z(Jxp%^^lS4UgebzK3f);ENGO|E1p{44WZp6moCYdEn$Z;-rLL1nvXlQ{L0%!KV|#) zfz6#QEUB>>_WAWWE5L%H=#yjW{bmBE7XD0srrjpI884;9hK1Z@sgk|E#D@N|+;x~F zE|iH{vRgNX@3#=QX!-qoTKbW{RAQnF2@ql1Q-k|FX1M`m=T9%e0R z0YJ!9@5{*QNs?_z{!*Hk;GK4)yMe`qp8#6ulj+I+&@?Q8{sM^}-o&=zo=aY%_g-$* zl$21(9PiG??7$+adwpE$O_J~fopS_nPRkQ8GCJI2uwY15Apc)wUmgx+8@`Q{Ez2+@ zvW-22?8a{Fl0mY|PWD9ELRn_WT9NE)$&#J2Hnw_Ymu<2PvI|*KmcDy>-}Jt}?>m0S z@%hv7%>CTU^<39=pXYhsmrt6J`hjFhcFit*m|v`AoRY1T!N&QdwZ}&t!uLd*``y%R zC2QYzP`WWu9p`Sa1+t6hBbsAHV~U>Wpg0k+4?YK zY+Dx$zTmUC^`3hUc3=#xopNM3J&;l2#b9)Ys3J8N?=FKsRm4g)_gsp`IMUTLH_~eE z#-u)OEJ!wc3G?fX;q2M4V>>Xh>KUx|E4VpbNciI?eFfdu2h3!c9XB?@ zgnU<%pSRi3VMaV+Us^q=jRSy9?Ce7c3X8V$y3&upA!hl^p7sC~e50{yg&2)uE)u*z z*c#Sc@?alCCFVZ6fLSyz1_j|H@*I)TKtrFoRVbKyR88F%%N)y16TdK3TT#WOL2k4{ zlAEw=uXu=~o>Ok#S;bBt`&oEdmnIzh;NxDmaEqK(lF*XV`Z(})ugbev1KZnri|I4p znk4~8v*?Xf#D@xTeLoMcUQ>`C&u(b>HqzYW zU;9lv+md*NAp*!DiD{&D^-T!+WYnWr1Dp?)X3J?LQRRT-m-*t{nbVM-Dh_V676C}* znA8Oll5Ln5Dwo6UCK?JOhr~6y*lK8|Q^d?eUgVoVI_77rh%y3MeAdQ{b@FNa(%DWo zfJ7BuX{X~gg1*g5j{9)wmM+)#+!=}m;2JdMr)!ozP3&%cmD!~=@$R5M1qnjX3M(0~ zHUz0}Dej+bXE{#nyQFA1w)5a|am|QXu`1M2?x}uaVFwpKUE*$K@7(UkAUft(B0P6( zI%Cvgh`*|5*G(5^91%_*1#Qsnes&PvemNJfsPGBEWi~+Qvh^7voT=3^U-fq5_-jf_ zJNLy#dt0kWli3bY;o8*e!%X}LC~V#l;R;r@4!>6DD_M6I_1Z`PenP&^+w8P zyYE)SPyhJfq(FCMIJ(G5>;JkV=w$=u!b8eOcO@~8WEi*m`hvgsOh#jF2E7T)nI5{k zQW_lia=Jx_of^MNx@P!2)$}3z%3W18Wv;TSURfMCz!ay4(zL9-7bi82((2W-eGB(& zzFeU)3?X?p56X>bPRYVzm(Kfgqs<*sEa-B^$XqB$G6fc1{vDfA*u^P-GWuR8V7L27FOh#FO~WpaaYOhbNus}+Cd|r z@>68g70-3-=7T0Akvo@u9iP3xy(umh|M^6G_8jl|s#0a271zZTCr(1lcDmxe9gb2s zS0rt7ODdf6Te|;3szi*+Ak5TGm4m61qe)tj$3QMk$~pfft9Ls@G? z);s_9D7B;~$IU3QLO?DFH23g!l$zll@=XTBMzFgAf$1u~1{%E~W=%xe0Y% z)meN3-`GD?VGwk1ha!dyY_X5)9PbB>k5@vyyLFh!mvvI5xzcY-<%_;iW3)H1}V zO{7piZ*ZQm@)FIlyFX?MO;UN^&FUA?-dA8$F40Vtm5Nq|bwQg|#|VdDVRE!f>)&oV zg|tQnl0IklY^=yDZcJbBx%wB^HZ8HW@m*x!r|^y7FLpB2r)}EhKg6#xy zha9b1&vmb8`!Fx~G`{OLFgE?6(n;&P*0|m4?a>wUQ(eubM#khi5=HPi=<1+G@z(Ms z_uA*8AI%T;j9NlclvqiJg~RjHt*8{w#$Bf)3nwJX zWZ^W;IC<%WNUpHPxn?r>wk@?c02mTUcRHoEGBUoOQrJFNtGcRtu7|uKveNU^Hs1nw zqj+utSx3-=BZ!GgTQDf06(2I^(=IPqQKSKd5nVTTuQAc!As?RuS93;+UsEWSOCcag zrOFSUE#9;tCZZ{cjmDJui2Qi}Msp&m23-kmsdc12Y zxSZlDH*zdZ_!W%O3u`7vWXTz^6Dn>1i`b7e>hxIDy5Y!e<>w%rqe*9n`3NkSws$@u z_JV<+X?{YDI)eQBxTZ~Xvfit!P4tw&htEcC03s1o3F_x?NdHdm8V8AA!?s=sO_@S; z(x4m5)oBuY+6SMwU12+Kh`PMMKG|bkPJUdM#FzgCZ@tVPv}i&|C4->bbXG5``Uo+x zfxuN{?jRQuz(&^hL!&KKq$j(?laxhLtAz*UHhm~vsPWuT8gdkv^1}F(K$stX#s`(c z8HgTIuS#Ow=oGW1q2ZKNWXN~soPJ}fx)oXk{F(VG9K_>B_upG3|BN$iFDkclsaYRy zpo@^cd}|7lw&wPitXen+hU~fW@vxdxxGDe|}wh5w{PaZcv6+o-}c)yrR27LtA<{|gTb*2_I5@0m+Y2KS&4E7vf z#2uIIedfN-LuG0Bl!RhD@+NV>YTBD0r$%~3uiGlL={PLtyUk+)6eYuK^b*}0yKd3@ z**bkgF4*rQ$(NUdBKOzW3&+mkD!VVmY=goQ&-m>1MtnU~gWba0sParX#G=n$CT42L z9g+;UTwD}uDe}!bf0^V(*06qM|5Gu{vtVYL`z0Mb^{vmeCBLXBT?bP>fc-P&FLa=_ z#Yl&HdU;NABW=2i#?(Tu+<6JDpcRghSMp?I-a^%E;IA1zn|=&3)bQx(^HRv17*7|FHTnZlhG}?tSuC*3VL%e7aQ0t8svJc zU$mD=_-IsAu1Mrkk)NByF)&)dx3})9r_eG+e2bSnCbsHZDX-dN3x5M;vun3KN@1=| zr93lZ?h?4>QtN{~p^&U8X~Hg#xwV&*?=O|Oy?DY>^YM^(*eY+YG~>y2h7_=*^|h|` zpJnSJ2mI~W=)BhUDhSOE@2+EQTaBkL6U9v?=k%y`Oh}z`EQbj3Wb?U+&d3?R^6AdI z=4L1aP@@|Ci(e!r>gsC+0=ronT;d7vc-s1;IY0saSFCDx&Bc6l%Hh{z|AElxBV3p( z!<&Yr3fyo1YAYiVGl&P{T&`H}$HDz5JTV^de}i$H5%`wQ^ZyS3?FMzvXtN7e>hqM0 zpJ8nofYVkd;A%GLu25?$Zg6u`!+_^f%81w1kpKIsR5$`g1H{Ghh1NzA}xR&*xiIy%;RvkVN+LkSG%zkT|@ zW!8B*%lUj(wRzc?dG+X#}PDeGeJGA<4>r&5&yUuNQ)6@xZPK zkS3G^%&nVWln6*8sLefIJKR0o>Z1GKK;fngr53fH=5JI$m6W@TKsE@aPOc{XkSfNT z4p1N*kfi7p+wB!X0SLeR%=G_-MyHFr7~EYcdX51~^UqHh!+@|gBJ322`haJm(g5jF zTC`)u1h&}oCHM>$;zOJHLnK{{V|K3ez+B}0dG$pN_9t9lMSx6Mp%L`m-?L@C_)#l( zEi1z%3q}Tj{>X0Z+#=hN2jKKHHv5`Tzf?_h$!;y4qF{M^uyFoIVKeTFA@*u^E?@q6 zpaPB0-2}{mXGn37tqv*8ceS;6a0L_hu6YshgfgHWsQy|Hj%+S!Y791W1)Vc%s}Xkn zD7DKSoHglzrvfNt0FZ}ySzN{hw(a$Pb=`{+sjc9`6E>^6xCjyduk$>kZoah6il93O zsdX#pABDz=HB-&(fIy*GDfKUGE|Rb)m1rS;Lmwf2kf2IM_6q}qXk18~wi>JSAlocl zMe}Cr)5z*2!2p%fEVB#9jU4&Ayr97?jflTlj$OJXB-DVr;TouGpzx4YUKW2pN(tDH z+4M+^mi%;?8ekxD%Q}3=86OT5EsA)oy?wyu(#hqTHvKRcH;ph=8Dwh@H1mm*EZr>pepqO zr3oTf{Kh!k0EjGldhCh=Q|EH*X)wx*p^3+JVAQr_?~NtFau)dunwvgqE_!miv_X^j zCPReUijlnguZ;+=0N9RSub+(;z$9>}uDqUfOfdb3OgRW?EIDrfXme5Vr>X4;vzz@H zI5;7VwNrR~PtH8p_}1E`;K_soMHVL^ z+2e4fT1Oi1G5;QRNIMXGMau7uaTZpapAfxDaDa*y>#NfMt&lV*MZ{;}_4f37c|;!= zmbM;y4EwB)#hk_0w>Q4wX9zIX?f|_kAxfiUt-O6{U|X7HNT zYLY0et7(!#Kt#qC-9IT9eYD)9r4TD`bZ@H zg3M(ah}We4qfoQh6N|-50{R(w^uut&Ey7_4F z4V9>^@X@K9w)xczIU=-A(e(@{M?+I}dd#BpPluval#nJ+opC)fP4-b@O*W?#r1ja) z6S|Um|8y=4FTJ4pXB|)U1Kjxhp<)Zox(UAJ_0d^g)29FQl|AeS0G?N!j7M2k%Njg% z`F&13dsFUTL3~SR2CyY(OE@loNZ^5WZu?`x^58|g{WoXKcoKjO#isRph1P%t=DS3w z&;`!9#j!jEw=a?mo*R8!3swq0BkW;%_|E+jRQS?JZ?)6qF^Y3HQaM}wvm6OZWuO~A z?ySszKF41#%&q}HEd6X=<2S-pF_NIVA@uw6`$x_3BO2IR{5xtES@ANl#+myRa-${j zZZme={Vc!Y4}?>Ff40-+_e3gv1?>gf+m3MdfQ>xs^|wE`bPh;A0fgKJ;Bse+ODeTZ zs-2N0^%_W^IlZG$lYY|M5u z|5;egRM02tQXTRlcv9^&0Sbes0Rg`%w1vyxy8Jy$+S?WyB~Oo-Ptv(GKIGv0^XO~0 zF!e98O=dCOaHy#i6egg)dI(cUYphqk@N71tzG6M|_qr(~m)QAO!pd@K2!LMl>}qM9 z6)4ASw7+t_g$WONg#$8)GrH>(wVa50EFPZuMJ(aD8;4|59()Xu0|n@8UVl!ez~ij| zH&=jgCb*WpcAPoieW}4s8i4X`K#YhH>yrb###5R-03L4wIx7O`1q3ZXjd+{ZP(s{O zyErnukl=6wk2I^;0~&6l-VwOhAPu;4ABAwEepP~CM#Xyh?|uUbMLd{%dDzX3(+ECI zP6WG&nQC@1U*pjpwha&-ti7_UC7S>x=9T-gl!t7^Yrbs2=%_#j6K{JK0z$}W1gHic zb&5)weXSPjvDF-N=?&i@7&m!}Re%dL0#64?13AYj*TH)L70Z~!D;J>?TOi)+p#*J%Gy3vpcqx+*a` zx{BG>K*{W_3)Lfx&$pkcWQM-Oy1r_{;8{9Q6ZG7d`nfp1DS$!J;e#4ulPVMsGvb!= z;^Sfi0NvUaD>cRV<@I7FqdXVoezZUtDtEJbNG}Gn2}EK@XaFGDzF`2l%P0xhz`HZw z!4R3P?tT9pH;il8Xog#<+KbXfd@S<^K>PGa+z8FZtEDC9=EbCdeA4iBx1C?$$;WgK zIG}V&G6Rz5dKpYobzVY-t`80QgT(^}fyjUrPb5EOBL5j5ayTdYGK!Du<0EG_hf&Kr zlz>Im+do`XWE+wK_jArtAvFV*dD7fy)o{R?XgVC708ZT(#1r(bVLBF*sB-%$)TrHo z2TWjFa0YgON#%2q@4EyJLWuPp9TLdm)arzJz<4#PN@<5$0EO zH-UtRGU~!DO~Bu1eD$y&Y?EtCYFtu?H#E=FcmPz#z=B(!Gd|TuyrI?# zBgo3gQH|<+?4|$*LFBhZhSkyOLmBK5A{7o&25~RFR3F}F>~UPUPvCmnKlMHz*Mvv4 z$T`Of$nST|qe62QC#246z?!xJT@F*9qMM%$$uOvRrzp2KW_PWa$Km_|KD)i( z^FeegAa3cMYfe)T)k=ky)q!opNw<{XAW&en8r1sCfI~R7S}08$<{RZN0EpuNxi>im zE&$#y!RsCPjGvj(Jf8-4F~eV40C#Qzm_7l8TnKVMF+PZkRj&nn=O2gHjL|A<6@c-H z0(1&r^y^Ke!EAdJSY_IJ_j`&Xm8CTzUp-NZ?f?ZQrqKXit`+V$k<)YbsJK*i~?X zXJl< z0$X{JhXLN11qhNFOJP^N~1zyQdF8dx(6>T*t-)jLzwlY~^{O|l(tMx8LJEcQT?^krOGT-|#l%*~% zcLzjrw$}-?48&eqQPB9ESK!5$hUK<;2ce|nZdEFGi zjXiMh5A=ARR}pOsg+$*_Hre`=ac4?~l`8%zlgJGvs4l7QL?Vk(JmVqeTr0-*{7|6tx? zMR52&1j#44?U(bSwulnutrRu#cwkI-k5~iOkToHsliPiYisVjZ)*zFS{yzW6M^@H7 z`CnmJ9fY%elcjFUa}bc+hYt&feDAJbfGDft8l~GAkjgMy1OY!vXk-WSSyh~tkn_hL z_$Z>T8Jlt+AI5qH?uJFX+q@AB~Dy}!q|&<<0WCoI1-AxbiTmfd|=m$JtLV`vin<9tZxjwbhuC! znIKOesM+g&z{P~rT;X$xL#Yg!ziRmMM)MG_gpr;_aoQ4lffVuKG8)>>P89cU1RQi> zRbzJ@r@4#5;MWo#=*zUA&8wCh(TVB+mxWxx3$UPqDB*TMziy#S@@Wb>~@}e9B9H^GEx|~^Es#E#GPvxdM zUr1DGmpsB*9T&9VMdl?@-byX_#E2^JHhlz2cTki6u)9jDqLhogc=wf99q?}9mmpT{ zGA_CQjvrIN)$e86c(}f!YSb8}5p}z>EJzM9MdSj)ToDi1bfTDCQu4jO1|rB3MG)s8 z7u);06!t1a?j7#e=bVMej0{v*#qJE0)=kM4J~0-^k2j``$hS7&Eqa`ff@N!d4+2;R zv!OVDMhB&BvN&>31D{zj?#iuK59Ok`KkfpxFFJRtD(lGY;V>nOY_+Z8YZBz$^_tPn z-NYy4M~*DhmUkxUv8|5$ZltO|mKGJhy*80reuaRK^V6#%WYH?HY_wk)&^vm^auLzx zXwJvEj`foerlWTN`8I4gqDOmVFVC%#wAgQz`J^EJOY^~(YX_rL$fqobc#)pDLhbeA zhu`H+B5MCxUs zkGIqKS%|Wh(b=2_p3-yhWRT{T5lF9kMz|uSb3VDlkH0ZcQ&73(X!USJR{M_z-~uCTas;` zL*2N3WEJ(c0b_jrn>VStR)V(h-yvT!1Ee6n6nBOc4R$p9To(!FxI5iPSJ_+5u5>xD zv^M_HVDH=qxzxE$gXWLBk^JUTY{A=&Z-d6(8lNOiAnCK4VIfAb-|A&?I;?2!hJ`uO zz3XMZ{ZQgxKH>MCIQftTlqhXPA2dG5kGi#{=4YXvCH3yiNo!%W;4?}d+n@B!(1Nd0 z%G0(I{@!N(+VfU}Oa%y7bpjU6%9C$gDH{YgNp$3KD^wlTL5R%P50wc`wd+%Oc zIY$J_tTUo`%((Pp35s&?+e>h&3Nb?p{ddlx09xL5N%>S8eZ_fzz9HL2h!H zRopZ21T~=L;{niw=z22N7@Vn>u8sAzXI02F7n3NkX(VXv1V<}Lfy`=X>PpT{?mxD1 z1ngD}<%?B0dmvh_%=c#fj?RL~pzRmzm7;p5q^0 zhpqd-2zzBpk|WN zb&RFfXC2{;rg4OKNp8F!;W|mlx%7#_FJUI{B|CRI@o*wQGl(TiDu(rD+Uc&I{be0u zjt|#vb}c;lGa7L)ngUVZ3V1Y)J*b6{0=xBwA=k!1o>v$yX$vaD(n~$y_)0D&84XHT zXjYKiFHQNg@XoSeX@(NbY>G+Q4>f&Cs?TdPPzucT7UqZG5zFXV0MXWvx9t92N&r%F zX@hj)g-!Q}Q0@&e#}A~}Exgq_oEZ~4Pg5|o?+oRtK_PAF^qPqBXG@$!@5;(by8mta zn%S&ihyl+2?qA5*(=V#gR*BJqyN@ilG#>&CK|~IK0Kq&==pCdp(CdM7A^WZdi2q4@tjNg;fWuyjT;6Hu<1_4dKH>>@h2TC4+uQ=`O@XCo< z{k;rOH1J}YBbB8mEBg1o@0l)uB<-_}|0hDG36@)}GT9w~vHxzV-=63vwS(eoebyfD Rrv%_nOHB_^rgG!{{{ckwH;e!P literal 0 HcmV?d00001 diff --git a/imgs/landscape_full_interface_ros2.png b/imgs/landscape_full_interface_ros2.png new file mode 100644 index 0000000000000000000000000000000000000000..02c09acd4ee94d35065f669425487152c05d6180 GIT binary patch literal 70539 zcmeEu1z42Z+O{GFh=NF`fJg`k3=N{v3_T1bAUQ+V&@EDebO;*Xoqb~ObH4rk$IHuW-Zkr8`P|RCpL;!Hkg}rmDO?KNLx&EXl9iEw z9Xf;+d+5;Nl@rH630D#EV6s0< zE?W&p6HX|Xn5&=>Tti$*k6UeTcuokEy_t>mK{XCO4&J>l99(S?d!;5eHYSz`OesW? zk@Fg881ok*zP~o$!P>xTzpgTvE;|?yrhBvfHPUe9MQ~eLnjnodd0b7TA+FLYziREE zO)D2^l!2|Of{ii45;S4#vNr@U&;4N;yY7|n3hoz}pbq-k?-o;_YUZ{-ATBUi%wS9$ z&5RND`>pNI(8k8n!OZr@LL(b%YlPAMhV8d#fI`_g|5y!aW4S-O{W`W_;y<*GDNr>s z01LNkOy5=0Ff(>A-76K~-5(yNwhY3|#PpzNFyp;ZS{WQv-Y>8>H88eu-g|$y==)vS zTgQXdMA_JY_P*P+@4r5%WaT1`u*59(!8-2u18nIZfA^>XSWRu^Fm7JL8E2IXLCV`5`%U@7@?sTj(}(b{+ywZL@6 zey$^LV`B@}5`#l?goA_YzU3G=I@o|BQwJ-{{cjO2W)7O)ebxe>IXU=wK`qQz5*SOx zG`;(PG1A=!YX_7o<}FSR-rbs*=e;+9{esGv=bvBQefr^DWdzF13gLi2?KikLbIf!> z0eJY0_1-VCw{b)n?brJ4W!!7a!2o3feA{kozgZ8U=SSrK+K7HOC252W7%s{cm=g+N zY2aYy^y5Gc_F-i5Q@y{h?Sme!p-={x#t+)DwK21Hu>X5U`2EN+E?*h*HfU|%%Wxk! z3(OXPHX(d}x9xu4^1)bt)jl7_Rb!mdzt%oP96)n#A^tYD4+a9N1HXE(;(z;{-NyG_ z!td4mmFM_P`{Cl-o3xXGrQ^OafB~Uw3~e0rtijevnPYZA&)&hn0XXR0_4x&|aW#e-`Y&465y$gRQ~O-tD)iyz8O<_VOKU&UZWWlOb|)a0>G6 z;_fF~*?;;|K=ms_W#@uG_Eu%zQrQLe9uHt=gGAaN5F)UHzjIC;O!Yr(hx_~dvl*gn z?DY%*TL8}VmuC0#ae+A*oK4Lf5UREYyZ+P}5EM}M-O&Izq@}oxr47bOGjcbbeD{qppCKPF-`_I1?@eph3jcW{65O}e{VhE3WzIjd53U1)HvNuyKn~tJ z*z50IHRgri+wDKzgY4V>cMb%mq{@zQq}Ob1EdlBsFbwvWTL?%EAa@uS02tFQmo>7q zaRjXGAKXr31B3wbH@B0|NC07o{5NeU59G)F=nsPiZjV_i948_~)`Y{vQEzF#3ONS^mex;r>IK|BG?C{mAP(PYhP`J1Tc@n(mijIGyAF5l*)Y zg@3|1>{CiW=^)(uo_PO6{x?&)AJM=r_~WVYS7dbi%lZ4(2)L@At%0khje)VAwWAfV zSrZ!rAbDWC)lWcR|M};b z9-|FlHvHhNUqM?FCCeziTx5Hs{Y`C$AxB0HGHUlE_b z7x@2lTKpQHyK2DS0_e}!_y;k{|2r7{NnXVO*4)v`_JEh}y95l{|7Q$i!1)7)_utwr z`wr*3!XL(g0GRRbI*p%|K_0=M3VwDYf21_{r%8U_`wsrS-8+EDucMU%5dAN59sK+p z5N^Sr|NKJr_&0cx-x_G77%Owg3d&nEiPdhyQ$p`|b{IUtsU$?EEHWcR>Ccs6XfINc^0o^T%fLV6dmT z8+-GEw6Y&gSHVB^a0P1P?`Gxf^T|EC0fPi9^qV;byXx`3bXr3=dG|TeKBn10I^wS5 z{8N;>KlQSQk7pn1`%~e;+}mJi+dp>O^ABFf{Q7d}uPoPb|DImAchLjVD2-5Nw!eMn z{%=L^kJvo`^8XO=?wP~yOXhzhM!9zJ^)G>x8{~`Z8uCvV-8byN9!9wjZeR~EdXVD! zUySZ1p#LHb_qV8$RK^6FzmsOT_ckWc^%r@ne_+xe5BHDvHa}$pei!I*ANcL> zZ*C6K3l9j;e?DuF>$lPa{%0lc?~(<63LO35{Q{=jnrvnF*{?5gM`8ptXe=GnJ zV}9vQG3@@}y8h1>4+MC3FaCZO`uP9j>cK(O`@4SRUsn(K!5!oGfyqH~&|fbu;XC*# z;l69&JviU~RBZhp(+>8d((jP^9T~#VATuL9Z~<>^kF-Hq{goLJ&q3brcPHv!gb{K7 zX8P`b)Sd3RkUvC~`MZ7JAE3%`LVlDR+5c4U_j5Mjeu5RxL3h9OSO;Y0kLOR21E+Y< z$ED_7=C8AK z-M`hbkeED9mS22lr2Gb{95VoG? zHrGptP~VI))Ws^mXW%vPUL>ZZ4y$1?meyCk0O#jD5v&SsGknY?IQzB+nytmg zYQEc|ZL%ZLJK;Egu?w3&uWgrbtd0v8C()P6EknF8$A zyDfo{*G`CX9id4sADPv=Tz{+6qR~dLFZB58tx=5)&$L%D(s>3@ou5tP&KXWQ)-UgS zgS1UZQ}q2gWMWxM?mV(hntR!Jm;p1J5g3k1C&9Z$+0vP*?pbgK8>Wau%lzxTO=p?c})u@5&C1RG$IlX@>DbpqGBN{ z^IEs>eQGR5xkpd-53PjzG}98n5)Xc~_sN#IT^QT6KxA;>>x;{?H7w!Q{c$Ez&Jv=xpQo-h-VP5B)V|l%KTP}K8c&Vk8RD~dDg}!>FAu`% z_@5j{Ay=-_99@f3ZP+%KdzTjnNwLdZKT^roZw zuwonn-ro_^e0gMf%1GgA`?2@8q}})#6D7B+lsV&=P@7HDtjz&z{QV(UqhRF4&SYD1 z#dmpQ_$aXkG^lo%PiwSiUmG${wH%Hw-gO$bbXfRf9}2FVlh}L~^f=J2X(Uzx~nCQq+N%rk}^j|3i7iB@@1r7RBwe8sabP zI6m@WmE>{zSE|tKsWT?P{BB;xISg6iV9DX_Mej&Ai-^_L!a2O%!lGLYf2>-H#&!XE(zrH3Rb+KP>ybj0lLd=2(WB5p&l z6>0Ib6>S%DoYFvKl2py}d*oV{gA58BzP#m?IeZ&DPd?>!8$i!smD20OSyNveIfFtS zTa24Eed3gU6Kzz06eBV4= zFuOK%p87e$YIb6@Q{zl#5K>iv<045cdLa$nOgu@*36`XtT`H@L)3{x?Z*XJWE$Qru zs#4nU_m!i%Wl3!evGcn=tduTa{*^q<0J89^m7TCX*_ z48^1@YQw}Ox|h_#PA@mV)P%b&e@f_jzPb9vs3nGlOvvG}Y|nkSw_}arZ=c%e;gNA( zt^Ydgy;HT+?KsnIFjVOpFYG)A>6v|BK|0nDT33j8C2zHnFoS2ewbZF};r#=MiQ-_H zU0s@m>)R+sIpxR7bntA=x8v@3q+VZN^MCBgqvbYH)ZvgXZ}=QAajfF(iOwNZk^Y#L zRh2Ok&M{%Ly0YA*?_x~kL|g8+sq)rT`zb+ib8%U6K%9k7+~{R6Hm&RIEyT&2Rv3L6_c z{)}2j+}uzVrH_x#WA&WtQLyH3A|7i5t8?# z;E9>aWme6=GELjYvD7! z_Dh6Y#ZOmxaz5bO49jd^RTDJ^2|F8z53+K?pMt! zT^8tpWu=!9ap;g;*_uBBjb&Yyr@~lL%TlgRIpJ9*MF~w!vH(2tTOU7~!t-uWU)k9z zY9WKMy06ZKO5P!1Q8ey&c?q(^?+-n?ih^FZ`+N4i`f zn9y09%7p+zzTmg52@tz)Tds^eF|5coF)^{)X=CWIbi{0b$%)ga)eVa*;+)8;)R|$~ zPf-&s7Z9uotDQ}W>@s?QCUL#~%v20={P&WVWV;E<$;63UOJKVC4YzeC!X zp>Y3AzJWMnVGLWa>5FgkQ$$6VYPMhs?`Z{563rH!849D*)9AE9sZfefUbu{z-T2f( zX=zbCHGr72CZD3@V}4#~JNg1*r|h*}v^>)@_T2Y4vwC)Xluio=qPM3vjiB-`~xL|2Zs29D5<;=+W3&;TE!s;r&Km1oXha>v^T2DIzVo5TvO!iIy1 zFGdJETRT!iDr222;gw6KmR-yxwi$K>g9|-d;Wt&#cxz9OK)b%_2$VDX+@wCM{NbG>N5All z^PSEYt=!+%#=^4}@yNNE=?stMn7_+1XFp#Q$VPM#$^g-9o#T4aAokWMV5Yysf;Cmj z%!r)J5L=++Tc62;g!8fF5ai3*fv0MCF|@&~5W^VKmK#OL*KaZuC}Vlkv#CWrG@HrO zqZT-yG@_V)y1q{6LV9n_9Bw^<)dFEGO!Lg9j%qZ8zag~%rDPcE%a@Cg3QmcX5 zUS`kn7ln>9>Wr~OX5v&a&|pExV~g%=mCwuxY&u_LomxF$tWRx*a|`|1h)VoVlBNJK zXIXVWw=`V&-1lx6Skc$>nKdTu$vN1`TI$H?Q!nCd&F{k$kLd)|av3+o5n2SpQRWXk z21+b4MQtlBh2C!{p}R~&Y99};JW{L|n_vA(coj+DLPi<5&E#9W(`fjn!jWaxcQkq@ zGyQ~5+KJon3zAJoy*XfJLl3zJnnHQ321?cVx$T{2y4jb9W1zW3*;+*z8^T35A9!t` zqw*R;DW6!9o~#celur1%xcGup&*M>byS$FEaaxPZy}}G`gMnk{L{ZOY_e3Y*!bTH3 z8*fvkxeQ)lbJn%sQGr#o#l7#3dgUU(o}91f3x}O%iEX`JXlov)TDRq1?Xhk<)kYob zW9*(tft-Aof4bvbZ1#OC`>&C7r-9-4wc5g1o5Qr^NP=1Vz>X=st6w=u;(=Ns&fHF* zo-F2OjOtTcNq{vwF{3lG(c>GiU;#wJqV(J`1LLGtd8e6fg=Q|njrH{^IBUW}nhZ=m zfftz(71g@YoTZo~GX6huWg$ zgIQ+yB3oj3hq9j1$4;ISf~WD1!)49kN zFl~dxXOWN5%2i5Zrig|jVKY5>dE+rxOje>3WEH(Nvf#2g)ahxcd#h^;W6%tNqwSgk zp$c?H1Bn4sya57)P{#U1)x|{7%*U|GBE+i<7iHGXrRmg+K9>85b5qx4kbYOz$Iq4= zi>>G?=ZNZqDSAiKX4ap**os=bp*Wzb%;H5w3uT;$e?`h%k{xc;DEid;{dGj-sh)_V zMhq3eEV5d81`rJi2}(#UmXt*9Oaj&G>AeqX8?RVO$En9gzO8RhE+*|;u4q4JA;s@t zuG4ix0V=Er1#z+L@wTXZNmhl-)sJr(c#lHOcw+nr8oR7 zzs|QGvwhd}W%mPsiYK3i`#HE8!NX@(H)4TsG$<)uz4+17lJYEi=F^zJrUdtJVs#E3BtQaGz`m z6(Z^cC+Wq4RMSNvBY*Oj_@Zl9w{I^)NRSrfl$k?<>M^RN&C98Y^qJZApOOjNEY^lY z{3!$DStjD`%##zK)*|Na`D6p zy{tv|68oJTM!Wd<*|}63L(cOr%qv|cs%t|T6>u_a6&`6@Ca8HC;en+ZMdhH#IR@-p7|imjsJLUccFUir@h& zJL}!1u@_Zc8a=sweg;W=)S^r8v-%Ad8}zUq<=tkaa3=s_&2dCh2^|bwbU4x$5MpKQ zc(ci4oc1l%H}Cg4Z;;&UX0vXyLgf&j0CA<^^P1ytt0ZNKmgAP|)USS8Qo9Wo+9tR+ z3}l+G3C+|X!styt)NVU5$zhEg<5H209T-*7EL#`3*Bxcno2J>fICb%xaM-Y;actwi-!K{z^6@!p80fo|@t(aVN<3-5-pNT)6h^Vtte(;eqL`*(Iaz6lpe3%Lix z8TJ#R<+;SSYr=xz8MW8qI8GjBI#+vS$~AyRiDbkzbMWmBcR5uKwe?V%x}9-*)LR_4 zseU>d5n{h3vkwbyx&zf87W!v5%iJJXkDOEOBsU>!ALu|_c!qlOM7bw7!^S8>nOR^- zrff6?h?k`Uif;#pb)JvbTX1=-8%I|~nL8XN!KdVG{5p|Fw12bBe$)6?-inFn6(yIl zit-ixzIej59P|TF`cy|c=@MFq1U_~k=tj0bvXah2J4V(o zZl<^#)^kC0uRdR1=nr_PN_xv~r9(lY@nwoZy2xX-3#2fM8G-aez(dTl5FDUS@#@Wr z8rR37&fZrpMF-4pD!spjKb)1*eI5Fi-)CfCHGisC(xbcJL+90UEo7a~ImKPY2K z-6zkgh*$h~s)eIu97b1D2#BbHX9F*#D)#A^>M&jsf!upq+Q}mPE$X2ptFD!V!pCr# zbexEBLZBCXR@C3#ST^lQlTDfB=yy16){)UOlopZC zYQM`&){n(MvBa3Y?>L_aqaJcxYIUT-Eel?htb8ls?w_uau_P4Iu|gLF?@un6yH0@a zdLJQk6+rv^wR7^qe8`ngoh~^BVAIAs_SYG7BB2(_F+#xF@|k>GXWHqFr0`=nK9?OSo$b>zdsU7@b=m%u zHvWy;`=^2*TCWeby(fpHkfM2x+T4#eT`rLlLgXvKyb_y}T%qW=3p+F#M zBrLPtrXjHs4Ri{9CCEo$rhB6IX6+fPK$k9GW(PC%)?+2Y8PG^*qph>)6Z+WG^_N0V z9;VZ$_Zi-~9BO$ZnOTK1Fvz(HAy!*{!p~1ie=He7)>n1U{%EpHF?}otSIDHJSXzh3 z4O9tmXJK^n?-I8^zWMB(w`MO-)R9Gy&+apSo0;u~Gxpd-EIyT z`jtWCL$K*GS4Vo+2YNl$j$Q9!VbSrs`ReTLpwPMxC4pR7(vGuLD{TY1k?qj5E>riNNQ&Gg=cxiaahr|%=K-GN_kP?`g3SnV@x z8uR0cjUpa?fd%0Nsh&q~oND~m`E>reFL$?$5LG$} zFxwmF2~u#3Mq+Ifac~=b<27|Ey-2k#LrnA1-52Y3R$8*Rosp|dglJD$AWDx&VllP7 zziKHTTR&iHnz( zSloq7^I1ni-=7Yh#X5^Frq)JlohZZd(PgsMuV4AfoY-?*O>QFAF)EkyamVpYCIT9A ze}>FkZ=S?@>FEL&wG^JPPECO3d5|zjhYiE>dGeHgVc^~&qNP=-1Tn$L=a;RZA4`{1 zP6(Xxu{z%VNHe+hu`XX6hY<<7Ya+jwk2w-Luo&C#e-lEe`D{W2t2k5u=#k=1c_D4R zM}xpfM0^BhdBY$({k|;Q%j*=hx=?s%eZ=w|64;7jU3AiUbK?P-uQ>v@3I6o! zsRt5?w{WuG+rhN8wXVCrH#65&0Vlva+g>KJNa&{RU3I^k$v9i{JzOp(%Muf?Z*Hem z4bK8Fo$xtwy%gp?#&W&ujYcUfjr*u*?k;mqemTNhDDbx^doE}AX@q^tf(dkY|4f*gdg1o@0UwNIQ2#%t_diez22 z`4}8A{*DRD!*lHIq1nNf?)1-Hh8?d#JpQ_AB9{Q|P)-+n8pkJ&@I<8(soaimIPjx5 zEC7Kzw{H#&6*9o4#qi_Mx&{7lueH&@cp*pD!NI{Oyi}vcFqfU}Rh7IORp;|2j!K77 zJx_p`ym=&kJUW+uIi)e2Hq~ah8l#up^7Z91e0e)=NXWQ}03+31c3X0pd{*VYY6w(Z z%~Hz*w89m8U48v?7&$RqbfYPIvu1sga%rXqA2i7~BWiz%hR>30Yio<>qMTe?qM+Sa z!zsBZvfbO0BB>cX%9)DPTU%e-nbn|Iw6Kiq^vdk;Px70QL(f1}1JrWQU@1zDjIdOn z6`{$oAnlSI1c)L#wt39J3LO#@^!(v9-xxRr)Y6izBZK!F-)Z~w#k`ttFM$5Q<+xsI#e@X-zV6j>#>SvwMY50a4jihw&pQ>nrvg2g%9<;)t>y~>jH1fj0MrX}5`)YNw zYnPG{yC9t_9A^U7)?9dx0hzWwQP7@fb9-|&6{x^vjx!{$@6sJT$OYg=w%*qBT0ct4 zp;HUAF!(kbP;453`kIr=Ys{*VtAjQS2@6v%;5?0lYJJhr^GwH1+SV>K#_{m*fbRey zIH!82-y+Wd=%3J$vll}t`K5r2o9{GxUBqqa1WZ*5YWh^kxKel#JL3*M4qU7iUhG^XZ-tKsr^t!;>Z-+It zS;4hQI8Y+gaj?B3zmkefJh@(C4kb(QPnE}9hd}e0W9jJVG@n{ii;0WJlBv*>aOgZ9 zkA&F+DHx81Nj5+4&e4u;g~M0{liFGtAYMR>eF<iVCOMtZ|=0vxst_ zP(HR`Vd*PGh+~w=EVYY_{5YF+A=H~{Pt@7pkz`J=C@S3N^Uuu8j3S0|)(6nPoc5jWmHJKvxn7mD&{U@u=7>xZfdRhs_p+=V(7|p!MGJ@!r|iu*+CDg*}AJREbb+LuY72*|k+4}~#2x1%wSYc_Q8jF)fV6GP2S1c|2 zi)GnmdjVMG(orB($O`ue0P<`gP{*Fw8D94ADn!1jZ)*@X>LnN?}fjGx$?df*-NaiTd|dYKC>E$di|Q2e$L zU%vJGXW)uI_E}&yb0Co!&=7AEv9t&l*%660RJnddR<2Lpf2>)M@+=(o@-ux=LWT@u zQDy63p>7NPMEGhEe)i^gb2PNDsv# z0HB8v1d9QxK0R;plE(Ny1i_!p+21v7&jxxgfyxH64H07tW2Wf(<=_)X?{tPFa-_q7 zU8pvnNBE+e#R^j4ut|ZWX0#*;lJd&-k}6{wm~kfb)O`dH-ak_eOm2t7QW}QQT+Ygn zOsGm(gR!24(ofulHOr?yx)RcOE;dndaycZri8 z$VCBbA~jsDJ}!%vR@$QxeK2I?Stw&;;1!ccZ1x_#O2`X>?-cDW7=>LP7!goKYB3kZ zOo6+Wu_mXp(a=REVWcZLew;2RgCcs|;WDI-?HGDI3cC){VwYY?=>iMZV!qw5Q3?)c z39V^0R(`6oTNY1^l%L$H9x8rxRSwYU+E3UtmxCKa(kr;qy>*}TSXui60h-X>XC{Xw zb_-#xsU5G(8Wc41P9R67z=$M5^+D^9-NyaGW)=&hl4u~1LS0U!PqllbV8WU=B$PP9L|${RXbBG*n;2aFo8DI8^g(bIp zlO!ZuQ#=c~(})Mj%+|`J8#9T3A`b&sDa72q#aTOn^_g-a%IK9HBR*1(WhML07_=Ng za`#pu6?)t=+a1Ub&}YrJxh;d?+ymw=Qsv3fT6(#4X(5Z`6E4x21=S1HFEyuCSbfE5 zF?aYVlJt{X!tA;PSd#>67IkMFEYqqOU$vKJ`kW_@mO;S$bmphJqoCGlBRrV~8Y^F6 z&1Q1J$06`mHpaonbu4m7AG``wLe;nwbud}Ff1g4y_JkkGxHtRxYsLnsA+SoS%xIPz zBD(InFLuucFfz5Qih)!p*E~fF?hMa`SR(PEI!h*h-_FiN#Y{L%zK;eHocL|xnOyg4 z7JVc#K_T@vSCK4Tnx);n`~ICRv>x+58#cLC~ZgP zu8l8y(D5UM%k2W}fYhwoIk+V*m|DDef*DEHd~dOlH)&A0ZrY@@Im&jGe_{n(V7&z1 zD|RXRh|y?_AY;r7k)Weeq=`)g3baR16$z}L+mW@DIL#wBYbjT?I3o1o+(kyzO0u*msr@K}&?nKMj>6b5Hu~7Gv@Z`!lhjyQOoNitnswjpE8a!-bsC#PC@_k* zHi@+%mpXH)&KI*RIJfF6-o(UP{KhO+XZR8K$p@xRLIS~+ayk1wj|@fYw$W$GNbPcP zgP>w^slaZ5jK`B{qu9HUMhl|>u-vJQ9kES3Q5pR0^iVbfETJ%2_}u_-392zV!%X$% zILi0R0wO3;X=Qwet2^(@;p0v=&-GKs4uP~Y{g|sSx5?N#+n!K$zABjNz-Y_IdAQKy z8Q62`lRiV22IM2LB4y+JZ(8FFR#S$4A)&n%*RAG2nTmY@NC2}qTg9eK)w9}^)@HDQ z>H-O%nK_WTHS%s%!eJN6S^WGd`2{XFr)q&@8oGzxSoYn?*GSssnbn$A8B7Y=4mN$N zA=l*U_QyVT+ArJhu5bk@pD5$-k+i^nN=)waFH1I`LF!(}9`Xox_M zuY0z_7uhdGp&bgY-31L{i6cLY^>nM1j726_epB7ugSgsHIZVZ?-kYfsq65hSi`*|T z(&)OomjWYxHD6PDHqc1%{T%vOaHw!9{n@2&y-l%}%?#1IwI|0oQHzELOBSZe(={ex z(ZS5#b2$e06Ao-!MacDS&l1%!U(2w?f@ql8$hJgMOD?Xb*%Eemf-p@+e>P0@v7Tt= zh1f86JAV)ndyqs6Wk%(l9G_X-U35LH?F`erFQ4JkHHV?bdu+3Xz42`pQj}=9-Mq)? zEZ+s#H0M&7g#ZiMLC3hG5SUa3!ARF?HRO@0a{6tSxL3U3wX{PZc|jnhDx=`U;%2i{ z5)tR%#&n8Ix>ti3{TZxgx_tdQtumAOs|oai(e@RC7~%OOq2}5bx+P0BLcyX}kzyPI zl^e5B;EhHp`m>-5GU3&8pVT?Nyd5+#O5dpvd>sn@;SJP*Rup*4bM!>E$oS z-RK_DVpS*&)~-jG!Y?LiT)8HD9?V=IrgnnTK)`;KVxyFO>WzTJFZSoAy*goT64I^^3H!i)A-uzfLjhp;U;x-9T!f3ArU12;+c4grjlpG!nFexqt|8`|BQ?#v{fGmw*azjs%-GqIBbgIS%IWf6E{GQW9M*Ii zU~P%eZZ$tCZhW zD3k3c56-#aaEZ)@dIuk|G#F`}{_r`_)hq4mXR*4^=dab+&(AmAHeC12(aPy!1Y32M zP_tx0;GRZ%;D`0XPxNm4@jJLuykujha6&V>b`mJyT;qp7sk0itHc#ikEMCaXp^WMv zrL>M_8hQ)Ai!ifO!C(Vz@qCIjUgUc;A}WXSLyWK@)PXm8bJXXnhBX7nr0Df-*2i~T z!083STRHWT1h&4mV6-$lKnmz;v}{sy0))wWu*{&Nq|&rGijf)qn1EG1+jQ}AhK_*! zq&x@!kDk3CU%Q`#SG811!E3G$7%=NyKLij1Y@MAOZyr7(Z?@uZfoBJQto(d@^UH8e zIE!kA{>L|uE(}Kxo}B4I`+}2*JRKSfwI==~DkrGb;R0*_$Up4i>$SZ>XFvIJSjM1* z_wGy6ma0gV0#a{#@QxBxlIedKcJc~gpGL6mgb1#=H+Sof+uONdPXRKyu};~bgYIH$vY9OYOM12`A%U7=5%M~+aeRC*!r}} z*Y|i&YUJIJ1mQp=qa4ZBx6LoCMW)#vAoHrsX_mriw%@<02_w+R)jNPm64#a6PbsHJ z0F|*0e|~jUqrh`>_No3#5UhEHnb`TukQ#X-P{>ZCN`<;*T+#Db@DHZbtM(uhu*HaH zIp@!LXfD(=Hhe8m9a8lmYh<_ed~*;`!dV;d^78P$Ipkg`+-V)e*Vku3Ch$$vIvL` zkOwJFZ(fm=LRzR~TsrP~@COqF*e06DIWxysCOh&-rBZ0`}%kP$B zlH0HB=;(?U80&mq1?gOH+EaGQ_q2b`-fN~GU{b{;%zS3^{+U0>QbWf#aiirK>%-_h z7RP0c+moq*VXAUBETp8VVA)T#<@Dy?fSx}ZYbZxjxdV(|eS75iEg+ zuCJq=G-;0(0gGaF3XbDayrg~M>gaC%U_Qtnlz%6^?wJ5bX}v778;cpY8w7c!fj}EY zGm?AIXyUaqBL;iF>XXr;cpCy}Z{hXK9}zbkGYj9jgP&C8Kieqwrcx2dorlQ^LlPOV z&a9>uSbnt&nMT(z0!duRP5Co%a0ys+m$i8V#vr1HOVgcCvftd}wTL;Pa#Isv>I&m| z_m$5o2`xbTdxA%P5~6aFltTibB&Mt2H1Z9z*p_fQ8+saO6o{xk77~!^q|bR@dchS~ zklL}(7j?|bJLXQaX=axNV;H^28rS_z2 zRgk?+$YmBJ`m8%BFhkHp5=f;}cAU{oy=B(Xi#;HruS79AMSKC9=+# z2E(I-`wErych;w9V`GhVVvH0YKu$JhGuNyg9(fsb7TQE+KhvG_0Lqw`x&?cvB^5&E z6CY2;=m1i-UI2M9rgpKe7Ko@_tD$yo32~d-)6sF{5Z-8da}rYEynb2&kc74g(Avo zC7+Pnx37X!rsN=BPb6QomRQR?$oYF)?dk5AXAn*3ANaxX%h2WMw2laNV=5q1Yp6E0 zVsk_Kaez6jGEdC|s$159-jH-0x`(7#Z@CKMD>e>Y@OT)`|52n}k~`MT z7514duq1u4YIR6;=7<(1k?v;at3=#MA%S2Z_xHh9!eFvEj}le*1mDS$k6eGIB)Tq< zLpsi3k-Ib2FQn)V@oh9)c!>*%1u1H(@3W&5E(c$%k4mT)aa|O7KdXRFYX#7#DYKsn zBP2pDkX*W931<~Vw11|RjD<<|t$i+PhY!YFL7pW)*#j>%eJiFghMMAG4C;XyGTRZ| z0C}V~itVZ!%&3W1aT-xCL*^F78rAMb&d3Qm$|a=SjA{l-=2^sxX$vHALTK7N=iSNI z_n(lltQo)Zf?R9~Ilo!E@bEmUuNFv#YVQG%2#?}YWY&z0jlEmqZ;Vd33I%zTGlt}( zoA%>PXHpZR7-BIZaQk7Su|T}Aa5OAoo*coqwLaxD)@Jvp^}!WyQ5DQGcQ-Udb6e%1 z1m;OjKR79#6pXr&UKKAVELQs#``dss2?E#Uk<@fz*y(!HP2kL_NCu7}z*>l?hzVG2 zRKh8^6=LoM;?ri~kuU~QI+ht^fV&X$D#}b3!7ABnkG7OWS<+fPP^qWuW61dwOJF>% zNd-|LzfTG|tl7&^A7^Jfdk*5y76Vm$%6+G0S_euCF~DK$JEsv4D%9Er6N}e+0y0?% zOc+oLmExR8-mA&lB$f+?CvOV)D-2PJ66kS{~w)poP3merZge zIhKf}K|;{vQT|uo!_aG1ld79vna8tHh;5!eZJ?@V&9`Jpf(b% z`?WL28HwzOa9&hs2#ISyH1Up%5{Yy@wJBBLTL+{Auo!f*0IWaH0HpW>6Kt$d?9jX+fu9SPGZ6hBmes$ zWoMeAES+%6Y|Ea)SPh%ThbR{BshNji^cnEd$9kt5FG-4qe(LbQS~*mP zD;2VN#%joeQuwL$%SKNjqc^v4OncK}OW{(&{fGtHHOCEOw(C_#j^Yy6M;)y(ocnA> z#=lG&!>mg~+Lm-}*xF_!`clocF%3QUM~yq#njx}!-a&$LJq$V8*YRk2!Fwd{`nR4l zC-q%Xc+pUD(e6`ODfZY)N2|^o8OEx>aC>rfq%1#+k6((f%yw=TnG$4F|C77CtaOR|0I^k@=eODGOySf zv+|+kb#CjSYh78&1R!Uy^aPz`mzg|k-@?$B%7De#tkLbm;%|!8WtTP`1g@8Oq8?U1 zlBW^IGdU7AHg)B$(MP7LNUc}g7h2bHw92uat%qL@yx**@MXgQIp3_LKbg9|VUoLt* zqha)E?Tlvmbn|*vdtA?bczvUI^^4WvFtNB~TG3Gd*=Hv6wHv&z2&k72Ia2b~F|&`6 zyMEz#=42Z1f$^2$z+}n%!gAe6ZA++@0j*eG5FxtxA}I_+VqnqDy3q?9=vwP zP?IZ-?=Hp_e_1_TRASaq_Q?LJXmI1EZvW%5J0zDvYkIzjmk?I>x^CTTf#>QjlV*fa zW>6bANe4}S#OaJ=ui)QU{dCiiv1KIB-+o>>`m5AETl~!p;WH`>MqVSv1R^DfPIhyW zH`_aR0F1xSP{}7gJhwF^Jnh;f8V8y8JKTbJ@%d}gZ8G@{Rd@V(i-uu7#FJhf^w3l~ z$cknvX0e7&gp^+#iDehQ-hDBUfpjj5krC%r?87@s-lf*d!)qVLZn$JN2AY2BzYi@= zt`Qxr8Z~f^P^8qTgD>Epm1bDmQ1iIF-W)`Ma}tti^VIVwNQ8S?sh4Tc9=5~j*~aaN zlO9Fhy8eo}2r4-?YLS9SfbZXqRxJKaR_no-w-*BngDr^qTC}in(4qau;!hysR z?ZFF zk3)K6%ZF-^iuwXbe_Vy`ymw{_rH_Ifj)&Pre85!s&Jl*Go_*+%PxeiIZMb`b#(9(S z27T=YOPol}QX{Q5ykb@B+j~mCk^I2Ny4QC4@GhS&Gf+Tm>%VlSOX@0bFc zPPszPa}isDlmg@3!xN;n z0L&{4{Etj#Z%UU)CPC5W({i!>NSpr~QF6kW>8J9Ol^PnGe@6})h)3=9OQy*UIXn*2 z8t)qZ9;BvT9-d%wGqhT;M=L0fDhED0|IGhW0wsb?`;${zYv0!k-&=y|B|@hE%>qmy z^5MHM|D-ub_t||oRfE9rN6~*cjh|pDs6CXBj%ZUZG*hgK@az5htW4W%A2|`(m*m$S z#HUdERTSTMJ3OCasSguR4qMle;A@}&*-ME)GiywP-)si;WxXt>`EQOB7)yj^wO=RX zcElI?wYreNzgXF5q35?X+SIgpH#j$GP>N8JAQzV@xvus#s-+py0w z!@kj1k^1hs@(ZPstG$${Tel{QUXnSS>Q>-S65TZ_4V^m~5VO zlr>qvKV=I4Rcj@jQulWL5oeLD?6P$8D;7i0Yn=bdGtzKxiY|uXqPeh!ieqQ zKL=Ee)*GaJJ<64vE?$FQKkW;7^=;Y(jc4Q9|Aqq^p;twqBhqV@Ub!h(TF*G$u0sSfNvJAE^;MWK5Sz-nIUxaUw`jS zPPTT2mi`>2FFi>mZoLU;Ya0q*RJNgD3OYx*I9!WxZQ)BsiN)75=+St2P1E&(Q_i95 zTRvxT#F<`w>D^{*{lh;xm4(ZmuyB#j9gEhZA09-+u=yCn z{_SUm(a5crw98>;@jvlf<=V;;{Gh5s$shIBW;fk8!t*W?g*{>i7nquh4>LG+#>JV8 zZ+Yjg2cyk`5t<6Q^jNcA;{6V<(C9*F_fB)<)w}c2cW(cA_K^J7M~85(q3qP=*sH}= zL&@4I*3MC>k5pLQT90MbSc^q7>+FGp8+)VS&0qIJu^&RMywG^thSa(*L3%(WPHc5C z#I2kiQ&*strdC80RgJ0_-pZ-Gl%vvu9p|B5Dh3E#iqu+dB(QY*ssL~DJe;W2X?fI- zRYwP;mFLDQ$tx*#U&~nULv?GT6I;jFSMUcuS(7%mv?f>IU*qXF!^1;`z!JCMn7+>PoJ=MjvFQHy4uVFf8XS$Y^Mnb5R^`(%aDt;U<=fl zO?|E}e{FvM;3e`bUw+WD(o=!}RNa2}cYfNUh1YS#Oh=|kht$V!o_*-p3i4zd z92bl7F^bjC9vLU8-#+sZI^3bN(Z)+pBKv+^md?K7y_3T0t@H|HaHm_<$w7nTqpRLL zJJJ6ypt%z*si2SF`@WgzsHFz0e)L-Wg@M{iF88DCPtNz(vX_7`+Bzq}GR*t4dKuPr zKy11~>6PW)na_WUD=^f@Vu0M}TC6`DbKu9sW%a{ol`_XX1Hzxt@v6Mi-TeA>-V<4Q zS&Qwqc;8ZcR+B+?sVuceef_~cr&m~jor6k}sMXSLYnS*t<1Krlmv1eY=1%pOF2T4VjIp;ryFd z&5|F&m;-@)Z>|A*y}H9A5Tg+JQuX-$aG1vNHUWHPm0;N=GNhai? zSHHMkZz-0{t;I|?7~+&D<{2_2D-r{dmp<~*mYb~gbN99O=+=+XX0%1lyQNHqF;PjP zo1y84_OEHtEHp@Lci6(LoEvmogt8zPsG4#dtOWK3Nv^^>9)3 z(I0*6-h|4aISIR=>|dD3{p=R6FrKE$;uRKOrg``14qPFZajr$51Uk^w=4{wd$w0@b z1j_qfmQ3$PstZ#i*QlC*ZQQ@~nXtwm+J7qHs)m31ug#xKvk>@GZFJAc{-KfipcFjh zY&m^bz~uvW7FN#&DPg52d4RnE+D=~o)awt8+g4nvCRnmlx8m7W*9DS)ocytket|Hm zB^!FgPRqwX3vwW%KVoJ`gg7oqEq>4a?0rXcV7cqB6*!lt)A+gJ zwNU405@J}KbUzNVY998yX(37UxJt}ok6$vZi_YiGJK$$iAw>fx3^UYBH%~_U!16_v zF20M4eJ+Djv=&;49U`i#i4=mFk2dF)t==<`oc>aqI4A=>=YED8{(O=*GBI8Ei?5gN`7N6BQTpW%i5wWMP)& zctLQx}O7C)giJ-qMa&QHQw2Wxl^IkBtp|H9-Kr+QF_wH=VAVBJH_gEd()SA z(U_Ydf_CArwH~yVYO`;QPr=DUuI^n@_SgGDo(#M{Y-1+Ex zu^{x?+xF*dC5y#&&C%gkwg_w9=>ZG)fjb2)JcJ$1xPv5G$Wg8M*=~^j1~(cF zm(O_+){!9rNG=$)f)-!(FVBQw8EBqmE&bI1?oJU3^ zyGEW>I}axQ>O#-=G2qy2Yv?s;%vnO)m%Pso)t9HMHiI60wkQbpOSOFAXZ5-h zwymbo+J;X{|7z1~?uuG6Bx4{bp*t;5g?)>x)aZ0mRjN+80Vf+!V}9ajT-q)x#vPcB zIrM-!4k>KAQlVtpZxBXHfS8U;Tz7csvRZ)EWR*hkBfTjNe5x8J^I-zv%-M)g+?1qd znhzYCxn~^=9Ghb|y&+AKF`{V3DfXf9@P!A5wFk~{;G;=TE=W>xh^UrmXzgK8nokSY z{kUTc2lM!MUvP$~JCM^|MG`CI?KcmFhESM+jZDPk_Gj4HxF-m+$1tM}rX~xmeLK|w z#i{hHJ4vw%m-GO({~57^4l}Y^*0m~!bcY&R`-{+TsNDKZ_h`Ml&UqVP@-ew~=Ux+X zRM-Mw1dUP{fp$gG+5Q^P%|qAM&EtrtQUQ)+A+b0yOW`+ubbAKn;1SOogPGK`FgJy-@lwYN=?l(D9lH zFjFwrY+bk+D7E&L1#QaK{xd0;7d#uzKkqCPioD{$(iymE-HFXNEl(X2@{QwGrPDwB^}80 z0>~5SM6p=O=>ePz^gs=I(ls8FGt$)Dh(`ZVi{wBs5SldhN`V$mNaxv$!3Kxjr#t}b z>!Y%IG%mv=5c+|=K^T00#RMo5r91(Znx&saj=JCd9Eg0U*%5f-ZQSXph(60&-~ARi zuyldfXL9xVg6_0(3FOg$cwsS;&K^DNkW4G94#La_04^ggE)H-G5=j!lLGZcjKV3)9 zNl9aX?YjeAD8ffxe~#> zdlMjSU+33%vtYhqTJFjhgTTieHh+@kK3ije_b9$Es$Vz*#72zTt1r|; z)o( z1W^eIa@D%Ev#*=M|CeVC#}aWC0dIQGV1xJ`418vtD*R6a11D<%N0p7E>Fi`dS6f8q zq4XA_k9Yx6qu?GpBMNXW_QAOk3d9`bW4tA_`R5j_~km% zmx#hR)UuUXFfgt=d-@ve^v|{OUzB%-K635 z{@3lF5be7S=|B1TcewHA-S$Mj9+d-@5|FoqKOU%Cy&B$OJN2$p;1nZqc`d47yNuhN+JMg0BAU!0-SKOPX z2Rx4~dfM+@{hF0lg9%xbHgvpJ-$GEaDJvdqen)5JJR)MGHb`NrG=GVNc;UwR-=sA* zI1OyN<4h!6Rs;dx4IB?lm>6l_sLQ){IK(3+rSCY4q~t)8N2up&N}j3`YZEj>(yUHM z31P_JBQ$YYgwvj4G)h5PK0g*U)YX$Z-)nurM=_m{7%Boj&YtaKE#;>BeHIHRC+B$} zj8zuS6Y%I7%K*!c+uJPo?i^Fo53ps5SF#0MpV|05b~_lZMZ6FCfqSJhpW=v@HKtO- zrKK2J}@S zOzx?rTw9uyO_qUa;JFS%>lwYVV~U z`v+(UmdI~i!hU+&5es+IYO<&)@Sy3_!f(UJl%MhjvEdWg{L*KZOJlal)t5`8tSt#K z5QoKET*I}7(dJhJMzZF%a@tld}M@wgxPSsL-pV8$S|0S6iO&tQ%Kim2b; zvJ_YhQ@PGl&7o2H`tmnT4Sk@IqjUQ0#s<)0nsN?Uc^gN4-D7fTZ5EQG8w>E=m$FH; zhL`_p+Q*@k?q9_Vr@<`0H;LJBXN_&-TlHg6kQ^+3I4V`c0CC&VHs<6}N!|@uB|TA0 zuM`w-!(}*AEWh$a!|%vvbzau#X)~9gM$wp}_)eR{v|GQ{d8?&c3Q9sGbUJ|kwa;oO zr7AH^z=r(ki8|EaJ9v=KO|aBGI@7OG8aQuBmVbI#ePqBle)|!dAcA`X6)!kAn1D(t zo|JF)g-AYurKPl=wM~i=J@e;ky?WiaLmIf{Hl^h1aQM%hvCf>;loPdtmB(CO0=jXZ z7ZIwe@h2wNthUfoYm;Q<(gf5c-9iIkr+or;Ylv1d8+tHHy+O0w9pZ0K{&J+O!;Ka$ z-Z%KXHbIxM8IIpGabAfH*4bV}O7~X|W;joBF$$!as4DVcegPAduto!jHr4SYjnZpE zv$(CwV*7Sj`izynIc0*!fpYL)HPsBV`BdgW)s0pZZI}GbwDrP~#?g)>6$3F+kXMTWA7V^#4UB_V(A&;0` z+%cyY`|CW2Hp3llbH`Zj*V!9mN8l-?W*yD)@P0~U0-9!V|kv-$1Q^;641uMYBH z8xf&8W4a;z_KUfNOsnBEMRYb2&H2Yl%e&_# z&(WUtC8`8WtdDT$u>FZwDE)$#SC6PvlHxc5cvMg7v;s__S3Wk*f&@dKT3vzvnwxD? zmYAgqSWNOOqLv5#YmS1akuwRS*(9vdLr=>?gyu%`UmIrQO0xW#6~rt}(b~jUwqaq( zOOv=y5nzNH8!2emFvg3(I~da(FWR3a-Tll~{qwtwP3v=}%0`RCP5-Vf;oyLGCd0-* zVAor}I>247NF^3hbS_EZIgmB8eXIQ=Cc3*|+d1{3$6vN)12IU}^+ zq76h}mZeNQ$!B*7di6W`#O)x9hOeg5D!-jEdFCulItb02F}-P!FUGieWY@_ip@WUa zLiEXENeK@gOm(H=Z?|>|PV=ZS<;Mg140d{Q-uqm#+V+H$MJF50j)V-Vg1C6}43pz` zPf_4nr^ZU7Sj^?K;HBs0#fWQcux!NWLin?#98Vq_uKR~X_N6r8$0dL`NZVL8IPAN} z?buw2^n*O7>n(f20$2*PyAxH1XpP`gt0wXe$Qh_OR2jIUWg1vt@OEswEHz1t>T2Q= zu^U>A*u0+~Q)VciVhLPneR%V8foK0)9BYUB71H-0kF1cj;m;D-#foFN-_~7jD>!?; zu%0{yv566JmJoJ=T?J$6*Qzbt0Y~CLFMYX+&<^fT`W7}(T003GqH7UZtTrRQ#yA4r znI6>LJsZCx2w#?6T(z;d6D%xc)+&7qOk7cK{E<8pZXtwla_An#vZ&=`@}1BPA(02JQT# zZZA}aY3X_h5bIu={~k^~p4g55V}Ox|@> z+7a6A0SOMCp$!-P_Rt7hP7kJLeDEc?sr}RJ+dtFCDM~S}gltj&^UVj+>jzs#?SA{u zI$J^76w^)5@iR4iC2Kfu`bpMif;Hiv>!;}G+#SoJMANyi_V-C*YnLaD?xt;L-b?nx z=X9K8@{Y@M$gN8&VC^~D>Hrw!qe>>XK3U1?<`etX(Tgp(wAu<#OJ3U~!Cbi3r?oLu1-yl3@UdQV@WcD?!ZVg?a5&Q+%V(APIgp zxxD#F=K#PX=98IZ(9lAO zz}y~4M8pwUVDuMP_agu+5X6n^M6+ybyDT(F^)SdiE>Xsn)^A(8^otG=gNrqUwhzN( zIKccghISzCj|1Y`Us>UIwbKy_r8-=~dJJV?Wq+L*ehpzwc@2R>EeiZ0 zPTb57*O2R0R@5W5KmYgJz$fA}WLS~eXd2vRgh~{1o^8c$wUv-|=z+&P5#95u9>wkT zA*G$=wwgJAMooLZv~jIuh0?!qa2Y5v8-v^KpcvZ^cM|qJ!=Q%7(#CIh;F|74_Fuf* zR;SlvoMo}?!Oo?HUz3=1$D4`UZrP(dkS-SNGlq-=xe+#)ivp6!!NZurL&Joe>^-v zFLB~s&9A@a_O5D|F#lgQWx(c8Do1a)pSReHaMOsFzfuYOwj12cHaAqp^Xk|am0AX^ z7XRVLSWvi~bUJaSKy>EzvhkCHq_ zq&EYUJGi*Go`ZLo!QQ}|W03hOHtq4}?5PFI)>iTR~H(bd3K;Lt379G4_t7<|Q^Fgnj4)nb_&qg#WUwn4o zn`Hr^F|%mLS6?VKNx;hfh5a;h;|twOnqQy7F*(0^eR5PG;ce6UFSJ#3W_09zUdbz^ zxEz)f`tE<$+{ePOI}o#Vn%kb59j>8)J2?*jqGQ$@rMeFq{JJ>nyD1E2o->v8?^^-f zZ9Xbp$Ux*J8ohS-yad*gWH0QV_deVQw0Cq^Yz@ORfeZoq=KTj`%_(V(2F*5wAOl>W zeeq|N46LN30aTUCdFjOqyGaNL3TyS%fPbrbf7$APE-Oj+5Y~LF z4!G`uc|D`~w22g-Q9HD)zXdq`oFl=)A%I-sN*t6}KTz6&MB@ z)xZAz2-frBN+4j>t?1hx$-sU@V;YPD+-yaS33w}<3j{9n0O5ELf0AOuqwRV$}m%Jwo#dTPZKK)`o*_Esfpp+2la)tJw%k0+@hkQNsv*8pKtxO z_Kom8{5xS#ty|5%{QG~i0JXDs==o+BmY{L|EtLtI`S!7#4x}O-F;Gus?*&C?qNQvu zi?=bMmSfxDEBgQ9NO)(Php?&N3|=CX{+Ew{pjoc!+(J1xVe13Lf`_kbej)N2fzG#+ z=+7N?!qx%^@JpglWRht=QOTenAmHr2Wri}t`%1 zxMSq7$Z*P9%~}mS`g;r+V&CrF9v^ibXD=S)xDB}{Mu9gp@9z*ym&!i%qTta$fIip9 z_`DXKdi1*{m3!4Ow!Y3y+S)vxrrh81h4!9XL?jPoNCYoHN#_ZWIAUP4NFc4NEJFO%1SdS2%Q*&yTM3IYl zE4Ow9-T4E0YD|rOqcmU$F#8^F_%z#2=&qwzi2D4=1z22}=jh<}&t(HEv5)j+MH)=h zdqYh5+Uw0ui#&6L*XRKwX)JU=2+07H1)bq^c2=VgF7U^!_HE|)lUZu)Ye?6mtIV}| zPAx_7?MdWlo`@cRil9a=Exv=D(GmtTdxL%|0d8) zM=1(nlRPa4%R7kn(hP+m<8R(&1%@|H)qI1f<~3mQ;_=$kHfXU+9?ccvrGx@TN9CJH z@8>wEPJBQh+WTJ52?oCQaR!SP!_viK&azSI##vM0DMfkR2`;1iwjK zPI(~uwl3@1*;RA{?F$2nGskYy+4A-VC}vd*gp-t;vA`TQkA|$1_6|%G z2&9Yq^4!(l+?#Le9CodLEj`h)&h7N!!Xqd^yf5tcavr`ZmtD46Smt}<;5I3>6=x7@ zbu#V6<9ypM6JGbDrP_1%IOc`#AB%GBiYZu`qgNXAWc|8RhP74l30)y>e<-RTHRL!2 z6io;!yTHO6@p%YRP(%gzp$4-Lpy$90#63+Mae4?DWq$<{_T=7Nb#?v*LR_R!Q9v{T zh9nx7kliG;4x!^JB*K>%>4jm79nJaPoEEl+jP-Lxlm>iuLv1N*AY|xRJx5RGP2)7{ z?T+CoqNJyQA|Qr*0TJ}7d?ZGM{vB*uzrMSRoNJ*XO`sp@_#ucwQ0ZkfExv=>i>l#e zB&It!C%X(n81}Tt(|vwci#)Q1Ue_ix952>`1&87CZV;zjaP`ueg&m4L=p!=j^6p} zg$M=eH${mw^8Qjpfwx5m07k7XLvikAdDvz&uwmB= z(Q4m|=pyJxtwG*G;F)DFkx{6lP^tP6unk045a5rZ+;KQ6-#RWjwv!}-xeG7{9J2Ay zAq&-doag3VPoUg+HLmGXg}5_4Q5V$HD3g*VQMy1(mXei8hQQmv>5#nw(^Tc|oY3pv z6>o&KX^UcR8;H>FP;wCym{fBssL{|N5ogm%oRyWDciWJ%iV9`|#pYIUeOh)EMA*<9 zP~jJz%RK=fV$$vaNd#Jjk%OQO#E}&6I*JD!8uHekg|^54?jHnAhx<13Nxy; zprQ>8vFIl*>TFX-zvHU&KiesE8c@Qz#-OrfL%2+W9Qj5!#CyL)3h)Ot7M7sfyvg@)Aj&6`y?@^sr5Jxm?aN zaJmc3Ss=8la?%V=SMIwshvGSg!-Qj7ZpOz%+94SFW}#bT*f51*`e{Rv*y%Vc#fsb0 zoGg#u2eOMj|DrZ0GL)X2A2H|ozo8k?bxKnvnHl+dC#*1{x5v`cnvhmOW=Km7u!q zTNMM|i=-I%pF6qX`o8)k^2LD?`Hb}GPFW=0+gr&Tpd~sNej|iVQB$so1zc$FuQps+ zf#Mbv7GWWN?rfdiGjx`LvN3;}Z?>D{h{Xc7)wicsAvyIujEg?*XQPm~e8x%sdcKrN`s{J8THcMbc!e~)Gn>iJ;H*T;>MyX~DO6c|(CSj^M6T;rkOv zN1NsP@>Kx6SsfQkuE6M70RGd*+n5i9cHB7GBvMteHD$5Xu#&uvfS>Dwb>V3$=imq@ zZ-nC59zm(|c5r!BAH}NL1%)7^m)QZE<9#-B7H??=qBZGoI(&w~XS_zUUQy4lcn)*= zK7Q~S1EO~C(*4UUfxwDx{l2m{;=fR{?nX2hTko0dr>j258UZt6b6%Vg3v}0 z(xgR^_UC-XYkjp(&N!j;5=T!4)On7>VxH{-p7Nn%P8 zH(*mEZdwi~0toYkIi*JH=QrMfWyME~pvv?Lkz}X_mOdszN$H1z~XKMu1!P-YN34EPo){kND_1ze z?n^V|gTg+Hv(FuQR>*vIKk#X`{_^Q)c7mHBpCQ;}@%W#W!P$31Axd|-Uef!cj<*|3 z542jg_k{&Ku0u~wXRzOGp+AKsulf5lgq11L4M^<&PJ7)AA7ZXJOAov^1s_x7#+NusF}73Q`dxm>Gd~f! z*$u|{yxPN*<1POU?l^U7wV12fsL!wD`Kd|W@7OIYj_l+;zX?%s0neY|h)YY(h`4N8 zCbj(3#)0c^6PWkuoGlMWORx3cR~xC^7`UQOYzUr#*|qPODoboD))zIceofP{IuVPC z*F?ok!14ABN!{=Ev;AVXbN=n|nEZ)#jILdgEJfr{7|UM{q2zWt~#rsapp_W3_nG3ify64OGs5=c11FDrS9tFU_E9EoSoYiCDZ&5TA=?Ca2ZX zRbH@rOL2jY2f^q{b!WpaYZp_IyT(#thWN=XrtAMWvn*|RPc(D?G3}V;>xvMMQl<27 zm130CwF6cHH{DR9rJ%&a8?~YN!19uhcvoAy!}Ck#wgwfVZ(e9h(P`S%Wj6)?H6F^_ zH^U7s|EE4wS*vldQkP}i?kO9CKg>$RX#)QfDDNQOQKG}O$BY2|8YG}J@2DY1ul#X~ z`8L<--ZtBFUqsr}+0-n%S6lB+HBpyXH=VkjK&duqv-^mG-B9$upWl@Rk!Xi;|;~B)-zi47w?Ucde61g5x zi;ybmY-wqIS{5z+qX@>r>uP2e@9?cV!&`6d6d z&C{`pAdmG)_sY9lBM0d9eC_gdgDkee?O%NsUHbep-{7=1%(HnUoG)QW(q>v6=JN`z z2&ftpSHZW%)Og_Tm$Hs`*eaD=jNmbd)$Ub4QY47JJ)Uu$6IND!Js;SZS~E|L+x0o$ zZ`TACA+wBj{;|ul2+WwSy z9FOBouS&hut{<4sT;PiVP;;|TUZT2@lbMXo*$zkCY{qa=1CH`E)?3%4;i@6dg45G2 z$LYqKZ3jKCh_l_z;-Evm%bR}+_)ZZYg$D)MuD|p5E0YRPi}Tp2c}i}Lb||&1{t~dB z=%v%_w6drjjnr(Aq>NNYzx+J@w=OVZgkdZ_gLF0pFWJ^Atc@SHtB*+~ryl(3NYnYE z+uW4nvv0fSk9QJ*Pkl>+CURa zwB(d49;Hy@-BPEYT#7lu;gPkMy}tcY4CCzqUE9wiVL=P!t8{c(b)67Lo*V32!~1#f z>K{|R%?7O=EF^cbYUSQVT}$a2R|xQTWei$mlx|Mwj~7y#nj59zMVWT3u7}jkwW{^u zz6i-nl2&D9-g|LD{C?Ggu7?LERmxWp9VD;iT?W^ZiJdFg#*BREE9K(B?gsD? zQssyeSRHNhcU6}RSqZf%@!`gAXB#1L$GZJer8q^%{uKTtxMnC)CAc`ca!{nz{R1ij zF1gU+^7@fY*?>~XKU|d>KYvVE8S+uYv{MH>%TM0UXJcT|x(#S!#v|a;480oh8CGN; z&NRL$fMFcoF5wTQIy|V-W=%&%U1Wrnsj%!yYby939etXcHVE zp_=V454#h?f!?jYb6LoDQ(<_PKL0bt5xV+3O}0YvIrMmYP+>9fpeby7l>SloO+yrT zmllz0L--Y{YaU)w63%j^N47O!A^!q07g-u4h0|DbDlRiqe_SazI&PM&P#gWA>r6mP=wR)u6NVaL=Vnw{pDONt68bfP z$6t)8U*6`Y7Pc}yA0<&s(WOcI(6=4??9M$_)U>W(6HUoA!oZ0aLeM`YZuBoViIN@K zzA7TaauWTDJ~upeqW?OeB}IMr!tMCS+vq&4Xr$_s9=rbx=n!6vmC5;7_SH9p!~0Sbju7s10|A0opZ2yPY& z2#$$RRL#0+j4tvs*ik1Ox6yv2z7gV8Y8&09XT7)b5R0j#`uLVJR_1+A5ygiT}ZjeG|$IrS5%E$jHm44g+%F*1%2^zx}xMsK?kwm>o+B z@2O_tI-EdSDl3fBWELHDD4U{;WjVeX7CVLIy-g7rJ%4Hw?G>(`l_`DOvqeCyZMY`; zA_;tqikZv&m%qJ!SBsUx*Q3lENtZsSS0~wlnmwN0mHM+H@)}^;@X(*MGXjT4jtve@ z9U(b$LGa4$ld#{ubzS|YudjaSxk#eY{Mk^c>D(LB)JXMRK6``4dVFf_YnXl8OO%R` zIRZgqKUu;WAsWs(_lFg!>VL@>9d-SG25jktuOnK5>N5AkO_-%BJf+xdTFVf_V2;<} zx!hb9N{RGNvg&*;6PcMTx7sF1$vAn`UG_^)*6} zF8x4Ya|aIcG6(Um9#v|lh+>JR;)AH?(vP#Ys-E%*vsCr~RfR-Cf;X>d3#XZQnsHpA z>rX30!3JoLWRz*ZQjt-S0B}#hLeWU)G<$DnDmJkG@!b|6uO&}Ts+W%lrZy^NaPR>5 z#`*bM;53LfDL6UR0IIM)Egc=zuwGwK;MK2K&JsY08Gmu3PPv+Zj>q^7Kq;(%(v?E< z@=2GM*wtq0>EVYT!)g+D^gcF;FgiQ{{hP(_oIT(GRY3jEcmqXkNkp|^r&8H^oF zcTElO7h^^k%mpiCG-BBq|8()N=aeeWvSyvW8DaP$LBXy|uk9C`N;gOT9libC-Y)2V z*5HK-1tMy3uV|83fcJnE0(~#ws$xL#kOh_M0!ml-8pJ13$ zFqlbhJ!)_E1Hc^F1UVR(fIK=U0*Ipd(sPaH2&i4116YM$K{nV|Pay`MU)Fh zf8&4>o(c|~ms<2Q=N@txnaO^bKml&Dyv)SjY$Y9lHzYj<{s6y#Hbh0H`BgrHG(r%LuFqI7n|Y3;OTZ zey{?Y$PMetU?zWWlOPjtNdt(UDupdTEZB+{SW5zy5e)1SHs@n(!RqwL+OY-~8X6O2 zX9>KBt&Z*YsX#7=nrN0OS4!@us)=hP%p3{^-L~&NhE9=_CC~T@38QA0-obz-au3Fu zBG|cX^X}h|3}8^{09S_<=x^!`ww%AJ66qRpxNv~zpw1|^?toh-@5#&Ex0{WfxX1y3~s8LJ>P@IuW3C135r$Y^irvTC`)$@6eW){s5;Z((bEu?=ndUK~$*LsZNI&7P1!vfU%5W1Jtn z$XwWAmKo*zQf&AL>_rwzb^A6S*qjET1|X@uL0A6m1|*lE5{PjKal~|O8$?Tx^pm$5 zy>I;d0Lo;;jNCKd0v)j*haVudRN}Sb{N&ZIKI5rE~e)x?fr0gk9D?%7TXA(ptitE)9QAkKE7P=$H zNr-7*P|u9|BG~>@M}YFU0U_iBFt{t*ARYjgq>~iAt0NQpTu2770@8A3ZwsLdc><~W z_mvQu91PCCCZJ2{h=T~`DF|R!ctu31gH7zT?#PohXG6Qe#*@Wwt?5Hpio!E5T7lR- z4760iSy~$HBGrJ-I}nYp66>d4M+;u3>K8w7m@bJPuqb^;R^(DaW}OTXJVuw)Ow>jU zLGXb{**&q7?OO?jLB!ugd7kg-oO?j1XgwnN;viD1Z2&%0#cTtnU!9=t%ysK0hDc3? zBAT9_EhUPna`5oqQ7yl$QIZ{7B88i*hKlaN2741wxVnh9nAc;2o^iN_K_@6 zsh_Hx1klGhLn`Ph!sL9jCckHW;t%1ZUZvFjRf=+5R3BwS`>{R*7AM4b1U=rbD)wLy zR&~&R<2w}VV`OvKtG<2|kIJC;d-n8|*U{0b_biokDW~Wde|J^LlzKFC4CVPJB*KD- zT_H&Z%F9fDS!wMj*cvk1&vgJzM_od~YcK6BOcG;WV9!wryu?+O5po|MIF;ar#Io2K zRmf~&X)qgiXJ*TaWD0*dD}JVnPJ^RC55eXCxO3MS4wIRHaE7SSpAk()bvEvzYK<#I zxma9#fe0zou=0WYaDYQb)A_I=942qL@D3*LhoE?gwEhWS^hNly$$=?3>IG*^cm){_ zKfR2^PrUxjXYkCFC&V;<81T%&h~H5OwApA1Na_}N#OAAnP#oDOp1UDW&`?6WKn^;d z={7zrgRon{Toe&%=KB*xhlm`EscZ3n3QGSLV- znTGPx^sOK_iY;aR2ov)ZSqdGCqNKApv;kXrHVqI$8;y}TrNN{T|1bO*ya7*rbdwAP zv{M*RY3meM9oEF^Ck1*eSUVB>ZhN#G(#KflU|U=|_|m17r_Jtk_*}TavKyFXDr-n~ zD)jjIDcr%CtgP>7wX2*q61*R4Oo=H6)BSpj%5VPq;r`BHl`bg3?m7Rhc{Vn-M;e0m zFN=h8*92TiJ{oNofB+M#!8t@$ST9VxXbi%}QIKg!f@lE3n&utEmj*HX{Pl$RO^r## zXKi}^gMROp&?w5XK7`>+P5Cr}CF)lw)QHNEBuFxZXEv6_P`PJmsqiJkfk%m~bcGD^ zn1-oc%+9K9eqdSIDK`O@^VC;)Amt;x3Zayt#G!cUSHq25B8&tNae!nMhm|56vzo%V z?rL8$6b**x)yyE@f>#R#*#YkG+T|x^M@y|riwLy{W5+1{gpTy?&2q>D_mN{E0jrdk zm{V4gG({s(3PtS8C)LYXNpd1lnV-Z%YX9&;nCDGtg)#HER0~ONqZC*MSAk2R^O;y{ ztAdJ?x&gmt;Wyt*&qysk?+ZMKo)};X2A; z$eHEoDeo4&HO8L{HDm7m--7)^rV9U?1@K{k-5Y-}Gp*N?#@K2L{uIGk%cOm+>D;zO zfD#u5bMpWAk_h`xn0oZXhE#$Is{({Ou=rV734&^rCgLgNiEsNai`d;$5c_8h`N&A& zRMkJrB&m{kxrjGNsf~yXp@Oi=%tCdlN+@UbZ*03Z+GV0~_k0$N!=AESQcy1t@;K4K zGjRg}Ep4t-NxAh^AXx#LhNkil#B>OD)aa`~n!UHWAw+Bll2(`_2$P&fBAykhzw)!klQW#ji2G%w z2JB?!K#x;K&}p2&xpxcf|tWhKs@lA^GX-Osp1dk`52y_PwY%jVCs zp{iR!Ky1qP2Jw!CrLYNXl-rrKsI z?iG(w-M=u{NJrR{j;auem!;K#)4@itRV^vszm+MPip>si6&eqiG1;TS1MYNhxOdVnP#~2UVIj)$`6jDTDTYa`OuTaslM!?t9J45 zv5|<`GX6f;ZG0*x=)7!xp(Uc(1gCZuZ+!hrB;hd%n;5%(pz{15aXLO$!dVD!wX5ra z)QaKRn7%>tUFMU!4<&x9MJb%}6+bFMUuU^{pd{#GhJAJoMtw_Ua)4CcXM!KMSP3CO zb3kz`5KCZs`3Xnwk{FT@FrBE`Ou!`kJK?tFAj!DhU&%p-gWiC*6w~3bd(m$cxn|K@ z`I)?FQduje(wCz9e;N?!QUQ6i{flU@kk0=$DhG5{GziMEfmUt=B;@1w9Jh4l@cF&y6f6#6vHq#M@fqZyjHAkyUJT4LOd%T5q$4KIgYA2BJR!&Qaz z7Hg^@h0~qAh1Ot^t*;dNn6r6CDas5GuSsA@(do2OM@M9R5`m^z6i8jDIpj8!diTS1 zju$NU=k~dqoF5d0JWf+YZ}d$ojaXLBVQji@)$O?>C&|A9O`@}oL`fZ_j&d=~DH!I} z{Ij3QnI_Bb)3tDFF=QN*XO-#)J>*oKYa{uLx8NYv5iIcq-T7hZu3{`*38ra0;jdwppM>Zw?V`BhsOs!M=^R<3 zv$d{o%Mr0nZ_(_Mrex6py``q~_Ajh8=Uj7bG3;lmTrb0xuO9O3vv|b7f;lb&qnS@Jjq%#%A)K?EiD1MAV1cAi@YiYY9<|Pa$`_WSG@MuM)`E^V!XeF1e*vk zTKdDJS&ZJP^U0sfqzs#$juoGsnU@MNy$n9O{m|e%`sU4)@9!UV175M?NC&u0yZN!f zB$x#8j0nC@l;<1``gPZBBFy@pE79_tm0zZ2HV^ZgB-#9UF=aTRgx;Jdf8)J>@k8An z9(_kLZd~enKXv_sDGoJU1=r6qXVHTGBkA>tWB_)~cJek{hp`2|1MT*GEM)cWyvk+E zYMlnUDIau009xqX$^>)z}(8E^Q>8Lb**{#5RU{!(ye31QdBR75pJZ>P5? z6|8J;^93)w%tOGqEPi6=!OD#6w{}o(%)VSTnmEZGHRD8#~ zt@Sr|-uj8)wpBkhmhV3j6KGiN?4&>O$j=5h{YI$5Of;o=Y{0<(9)7{|M~ED&Nf)Sw zaDa-4gzf&i%^SsZ(A4!X7|||pxgMq`_r$7C*EPUfG<+1*4w#q*^*f8nv#ah4>`AiY zdD-5ZfmP=Qg|bW(Jzc}T>o;6AVpbQDHW|0Mq^;*I0xCH_-EX}!&B{NjUA`Lr z((T%x8Dc{1@xJA7-FT8N15cxU@OS4hA)%99A+IM?n|xe}^rJ>X62~Tu3U*Y;S8aoE z3!arFQ2AwWV=s5ArLb-+{wslrU;W$;zpLaxN&T+h2tCB15+|q&f6O0ziMpV_%)4Ip&t!JstOWu=cgy}i{R>e}ja1l2 z)5iO>IzQhngk*&Vz*AG7 zUfe{0Nq`hd6kQ-OHiSmjBB0Lmo@_%Kj=R4Rhfki<`H%M{%84k?Qjb_!jQs>XrFc1_ zbshTc9_D25nSDRkpPQ2KcgxJnGq}~*hpVr7HZkt0T`$YfU#GyZIc$<701rt!^-3FGtAb7 zaev;|2MGYUZw=o&!iss_ck2#MIUGJ3vX-2GSUVK#Ls_4(aFvJk=9F-L@Q8~cnhC(q zi4?m`WMRGdRB!;MzZ$-6CPdgux$j(g9s#lU|M_Z+Epn3OENPS<)APG`DIXRX<%^5v z$nU~Y$QBgOPEY<%Z@r-Z!27Y=;qV-c94Y31-T{RM^1vrW2w6ocR`PiGNBD)i805Wc zpv2)S9nq0EA77_R*w@OB;f*YGkaVA~#^=}n@lpD95Th5zBbtCVE){B84taSkbKbT|CJVqW}r z3;-1`flt|2KNQOPXFya}h~ZQ6(onuSFAnAFr;gR++AU5#Sq6obKFF2_9CA8GOANWV z)dCwLqoTT@i2A@j;18mW^3=~m?c}t~o1Ei5#ZaSRT6aOmDJ%Ys5A;;z2627x;uG2g z$*)Hk&&j1_LOkq+&^mAX0|<%unWSJzH)`r@jQ@_gNI%ud&&749Gv(0zIR?Lc#AxEK z?~G|@uG%BJ?{RT)WS}ojX(HrA30TuJ&CzU}Zw)=~J^gA%hB^N}6sYt!2l%ABHT%va zV?fN;qL;REgGP$G>lN$-{>88ag*V?x8I}85Der5Dp?E?=CaH#kBR=Tz54!XfUJqUy zIt?54KD3+A!*me?HkbDg8+HKZhgVUqD* zFb-$1#cY$L7B{FEgF8Ed`0_Vze7boTbn%(00e5E&!E~Y+DWf0P5#_qyP>hW^2rwhNB7 z`ruszxD+!>>-=o>2Z>df>Vp-v#vOp$U8wXAD7a-HzWXs;($yM_y_CIFZpIlhnm~S) zYOuEf+U|+)Ivg3w>?M>03L`{hJiGg?C;=hYFb|tN-YXAzK>Sn;?4T)-vedS0?U9roRJ)L1dImm9s`xX$A^|9PzH1w z#jw#H2gOkZ%~~*rYe~p1dO-6Z+wv1CGKo&XZ4@7~@5t?ZHWoVK{6JYk%)7N8A8aJ{ zynL4Glda%h3?=>EV3xnO0+myhbf1y(5Z*=LcS=Iz<{@Cb^@!5 zv^y=!XKUM&h=4@qR2*K}UR&G13o*plsi0Wr)IWr*zxQWkc@2m@Kc~O24rqnNsU?Nw zZtBZwaJI$M$s$Uc;Xmgl|Ke-UcSW+o9CXnicA2Q8AC5-ZUc+I3vy5p|5GV$5WK2mu zV!N;mglpvo=pBeJEGjamVl#O`BGIj_z>zIcPSs!+I0dy&gcD$iUXsPr?ps}tr*C_4 ztmz0rXe&xz)Rxn1$oVV8T-UB7gZV@N9meh%`zh6eP$roOMv~(!K3d`jIPjN$c*H;! zk1#eynT%5Ox&yZcuhPU6D~6tcnhb*C6R15>MUhYZT8zm0`Ms|w>MlA&lmE)7PUHqu zo|zAP_1AVnWSBfi#Ii*Bk7J)|4?&26RAFmmCp@MlN~BTAlHCab?|07QP?kjEkUWDo z4*LyAKSK^G8`?&k9(b~`2_)pujXdC}41wu0=hhG{4f2`ln(8$~4MpOcTn5BA8LAWHiT`hx^S96i29lmPtOt`6JzSxsF%P;2BmtXe11l*9}Naf2`)F=Ls~v6|4gjU*G3LoM7R*u@ifNL* z0$OJ*ff`nnF<(2CEs@ria#e6SYR0>YnX1<=g(;r(DThqyv-|FEOACE}CaaY{=aAE2 zcU5Jzt0Gh+XN9(()h8C^x+%^IEHl*Vs3^75;+-CubeI&g4XkH;q7|XYUl7F_0##fU zdOc3r|0NQc>KsD%kTxiS>pCUCSLag9f!erG%9bmPwc+&HS88)myuphq*ihNExEZel z?t>L(htmBDtv=5da1sP$AU4eUeEJ`80o^``zvKpPKRxMFbt-u9IJuM?~kGH91&SI@raqO0ti8K+2}!g@kn- zKmHG#<>!?jOMP~nm#x+PE2e~6pK4S*b>(^RrM&vgrgg`-e6{B44Ny84#t+L!0cg|%ZN{rD!MhGCkvY&-vA+AG^9(c;CaxnH(J2>4K zq0)C#_gDPaa0;Cm41D+xcgRkHU+Mo-a$|cJE|GF@GGdyZtj;nPEk;K^N#by}gilPH z{EUL9(SsOp@2@3INK+E%|0y~9FAoB6yT-*sSpo!QLDPH(K>|&d-WWeb=ld)6ewWpN z&;I@wpOrCnxl0+`t6I=cE2Po~86|xZ#gRP)a=ofuyLdFFP2a&Q0iqN6U#I>#sWP%4 zCjGzOHd+@G5wsTu>SNeH=X3DLv4pI76#uawHTY=H&;vs6H41z3mGA(MZMB?~K^H}ys+#xJO zgJfiv#)|khXmi?%;0@92ZUCn9tOL@^jVEOm5SL;Ud5d7*y9jSaOr?$XH9ICm;4Zr{ z3+5J!MDJY|4CU*hd1l!1V+l0t`;pK7{uiI!UvX>g%K_~QS5mit~dq|xDPx(91)Y*^Hw&vXvN+^;cTaPNuF|_LH(_8+)j%UM2)oHA3;&- zomgJQlhDTL2voy(-PN(bdwKo7tn%G`?683bHknB#`dLg#M-CJ<8*;HH2Xp#awK@msh$2HIdKiQ@fis% z_VKT2K&!0SyT_q%5F#v+0E4`Ndq<0YWAgP5qsg(RTQ&Ub_3yaL2Y=jzwpRX=Emn<} z%%L09jli+hD`%m7xKWOh2`CnR%#}Xw=MyGdCk>60*)X@(nJ0t*;K4kgCySeCSp(U9 z9Qq+4?V2z`O?J;{p4>oTvDU#$I%vXl7uoPhH$+f_CkG(duB17!`Gp;kUX4eOKfL0~ zEn`cJS>1t9Wx1W#vs}?ZuR=db$P|pohOGY%rIW$E&HO9O&f779xTtcBDU1Z?-p{%> z=?;6GgLb2*9o{y&mK7$~`T$OA+U$QBO=wvgwvq$uGzWe+kle(dYYp8g2vvusQ>IW0 z4&G}qNE4WT@SA(&n5PzGv9>3W4Bfw_&OHzy(FvGB2&=ydjjuT9v?y08-LEW+n=5#{ zD_1bj|6Z0Gh=YYuG_Dk~)d2OA)_`(}K#-mc`B9}@E$vxtW>g@=mR}%ny`2C)N}Tf> zI}p;Dhd2iTs7Ij&Mt&nFHkRt&sHZ?6)(L&8MWJxIky$PC*D18xS^D2TM@oKgzOlUd zXX=oG?uULjVtKcihYMCnGMEbLLt*?a_x{A-NSyY?i=vKjD*9T7XfT!HSf)^@*Ez?{ zvJ~8JqbTufAXciR^s6LP6i(6)RD!I=Oz{v_5G@N)=|0pxk8?zhVx(_WAQb%06N=fA zOxieXSD!JT;4u2!aA^o<4V1e)W1Rj$6qBO3hKxrRN~w(}{`4k9U7`>WUQ_fYdO$Tf z=j4UJ1D-#KIN|`Tn5iGoS*rEKD*|sX zHVUU9H`|^hTg$(NN?X$xC2|I!$??BP=`=*~Sv}u9EP+Tbxpb*pD-lu0j})MU#`eE` zU~!r8D0L~Adm5teaeH=5GK+sMmh_yY1C+4XTZ!}uNZ?WwaPquT1@FMf+uqjAT_W! zc$0!x#+U;C!kB|q13L>V@er(EQ^((mEAf9r9H|wERBp}0ZP`{ zX|;WF4Lk{NZ_My(aE)so{J9m~m>+E%MoAc{vMid_?MgY6faC|)Dtu5@ko*q5LHm(p zuFee`huee603nQ}L^W);IfkX^2XPA2hSYg56HW8!4<@>ShKGQa|5yf@&f!VD)ImOi z@^TSV3X}wzu04x#J`BCJdKmdsnkGFr_O@8I1UJR7Q08WqYY0dX=R85kFsn|=q;AgG zrkIAxuD9Eu?Fzs*jJiJTE_`vT}EVOuS56@P+uUTFDt#L>_MiI9fynN7%fZ|h47um*gj{6;^T zcho8VHmE~B?$JcKGe_Ent}%NLxy^=j)r_sG=xiMz~Eqr zbDYvQl`ittMomdQpba=GN<$vqTk(O5o;&qFykM9l=Xl|PP*liR@Z4LefYmI+}DLXFoR)Yucp!bt6}i^Y~# zcw&`MMde(JdstqG300ZvsFAM1t-b}KJWfogW^^(_!cWqGj+yy%mhCwAfbD2ok>_CD zS3S2uSqcm~b&*k#Bog{sR?qe@kxTX5vn_9-qM&W@a@cmt0xgGs+@$~UC=&O%86by0AbBgBqoNPFeN(B+;=7J>>U0+nxDs8HM9vBD=WEN`!-eZrO7ovhIB+Ldd&v z`_$yBj$;s+l^Xo0wKFPEQC?v+F*b6ylATfMUKqQf?*=&Gsn_=yAeX+`San9Z4HAa7 zFa}#Os<}rgqK1y;l5mJj`96}<#k^1J3ERVl*%|R`_|?Z?`&d+g{>$s^5kiI6IgYgb zwgVgp{P0_X$QXDg{(>(R|53_~$q2;}_rPZfv4lWv^WhmYxDkXep)Q~xNqznpedRV% zllH3&r9kuPGs6ZkA}Jd0Qk?aD6YQh?-4gSZVjZ`P z&^hzOIN7Z_8(n#$@?$uIH?x9-z|uUMG%>Xeice96A5&K5+f=i`Do9qSogkHYG5|eRrpDSxxlELL@b&vz_p^`w$JrNo+!mk>M_g99uZH}_032k53#;gmN36OMD3 zuWr-tANh5I2`r)t_q+WP&_hJRE(azpWy^D!AbCFou8OI04qXojJwwa6_dds8PU!yv z>g`lGgu8+76%i4^g6E|;K!uHOUxB}HF~o~^!S%=Ql}tmdVl}f?Nr9C2BRK?}-}Kbf zDsgIAX=m&^dh^WqB?f={*yru-IPevkzdCfj{1;?uB2rQ()j=9vqpt+YW|#4Xid0EU zxt3i}wHZQ&vT*OK6hVFE)zRfAwEX&a&NjZAjjErz_4;cXD-*-+`tzZ%aJ&H-_^>q@UN!sKVvUfvkDbGQ&4G<2Iedk&h&iq z`u~*W$h^@=Ije9fR)FmaKRPx_Qw)H}W|hR&(W5V^ht z3#4Me<1Q`mplDiXa&&cc3_uw_1q?tc5Xa>Y!4Oso{yw=qj<*|P%$jyOH=3NWIa(CM zy+UgZ)4oC-^DqQH6}nBd86~bl3UK=>c-=~Zurmp+Q9*}@=nwvUmU{cFP1xYjL?&-b{J-$g~A&s@ED`GMay(R9M0qA zuEYJccG{Ye%8;_+T9K4wD&oXP{@C|O9v{d5i}$nJr{~fAO+HRzb@oxv3-hO>)rqC)8l-oKj8i{-JYwFKlm3cZ4M$;R7tX+EZ!w1Vvv>^p9i$zbOSilm@ zE%&n6J-5OA=wrdlorf+tiQBUDlBih1hanXu1I$ZD6auX_qL87cM9C2kC`buBr5{De zsB3wC69IZp7=D4-A{!oY@D6VU;k8j}hp!I=upDR5?MQg+*}Qb)+8rP>UIHk5M`Q0j zEEX%Sq_wNyK0dlYJBya2AR);l^(Dlu$m||OIOe?(p{Qom#e>Sec=zM%nn>KMZROtm zOaaB$pvMo*e8mw!7eSwUdmt1QlzzOLy!!pU6>v+6P#1FZ+Hbwb*eAn4Idns*i}1&f z9~mAZ+zjNCVIlT^jhHOprR;pdYSatqKy7(qJZy7J&UzAy<4NoX`IG5`5F_ ziysJ%zDWPb_V*s?=KQT2OH}1lB#QCg8?2q>a}ju#NX6JY@IO_#p(db&JE|D)XCs;> zgUfVHGbH>7MzIN-2q)h5HhYpZHXVh6GC;+@R}RVzMH&^1p*n&%hN0N#`-Iy%U27hT zZ7xrx0CjS^oQq8Z6^7b}!ef6WqE3_UzIgsze8bCeix+PRJ(tP+^sLe-Rsl8{dVe?2 z!p9`fxPTAM?9?YnBu?X_D_qogX3P0&_vAM~-fqt5rcLDyx@joX@*5IE?V+!YrsHYP zIEoJd_Au(+cv{CpteQ7896iYyqO%Q2+f7f}tkdOqO&uCm6YSF;tZP(>$8p3iFyuen zs|yK!Wk2Jb5I<*yZ*eEA^d%Mog#fyp=!JD(o4JI=*c~k#`o_O?qp<;XH8v0UxQ?0- z9TD~r&11ayXxTGR;_$3mtf-pVDgvOcS89CbpcKP}g)i~z)(R2e) zw)82CmPPCMMvo;3t(6r51pqesZDv-y!CmUjdXPFtb^VdHb?z7 z|EOD}J|EHK6p?$Ce+T_d;KEI+MYoaaTbD+-%dy;gFjBOsg0ub~pHg#1>xg*5HpHwU zI;&OO0E{g2UQcW&dO4mgpDpxhH;OHo(z#uEAQDfn5oOWanW`$z3%Y1&N}{32+c*`dGfDy$QH>?~c{hcEF&ZOFBbyeB(>>3B?#2z0YiuUh;Ou0zOI(uYvn05h7<;U)_g6Cy_XWX7JH7er;TZ8P2qQ zSfcc>@h4_m7W#WAk5&2H_^oht6mA4k`>ywogH9W(*jJ%fQH@(CuNWoSyNj240K9?9 zQM0luau2{BV0DQqT@-G+49FUc(l93lAKEJLX(MrpFCj~)y%BJaebgWI&lHhfid|ix z#MJe$g;8?U8KGLxuu`d5=Rw!4FEUH?SX2qV{(e0}v-bTC)E#Ub-=bU`>7XmD&2UE% zF6@2kQIx!EdXW$ksCK4xkJrz#=RTO7POFBYYCtI8(A+R-o6O{#PH!*Gfwg{He^0@( zX4rmtT`2$2plw?O#IJlUIV0>imL^8P5{s+#L+q;pVLrniH-h*rP6mvwkXi0!8M zK`<5YMV$uItMsh?p%KpuM+EX~ff-#|7@OPEHkf;-eB@s6nKKzNsTU~sv~ljV6J!h1 z0@Z)THO8RMV-5SlMj4d`)A>j1(U3-`BR*l$G{oa>ZBJJf@);9jf7TXX1hRAq99!6f zfLKyMji($sWns30R2bZ?hgSMtW4EM|=@tzDj#45~}MGr88xa4t^{snF7tD=-jwcETb zRPXCHDFldjQ4As)P{0^kj$&`4^?%|kHmm7-8*I4 zX_V_$pC-L98RpUJ6KCE;-TFc*Mqe|r0fv8wMsO9)Y%4O#$nuoQJx5&z&^k~*#Lwmx zU3_DKb$9Q!=h^SY6oM{*>37s|O2xrO=JLqL84qcRLj5;g z>H5xBg;VK2P2W;J>E@wT+@B-{uT0s_sO>%qyFu3*lg^@-go`zIj=mgDr=T!ndrR_{ zUis?x$7%SP^C6axm=OX-Os>EbV4Xf0tVW`YF@3(qF}W7*ycI~cfFhH4fCA38 zIQqKm=OW)$-aDl+w4R;aV^0B*>WaMxhYPZro7Y5N_CV^eMXl`;#w(oR(LPuPNvbFb zx2-Mri2uwp(zk-gk&V@7R&eDUjTS>B{gxB4ozLAw2x6ryVV(hyf#o)lASzznbEE%& z@RLc0k!{kgDX0gS`DJ^uSskdD=_P)zkVAyPY10W7wE^ksk!F&b1p`ZMWKyU1 z)6+=TCw#}W%?ZEEUw*!|n_NR+_v_fxZFw%7q}HlGaVhWYJKS7W2XEn(5PQyU$jv}r zWv4^!A40`V;5$2Py__CqZdz>Q^kPXrTNOWf(yigZhvV8Ys%t;Ku4SA%O;p5=$nUww z24gmT`R54d-ygIZu=3`pIwCmZ{Xp(y#t1V9DO&lkQ^Jlg^=;-gO4mCsLY}1I)tlt1 zPy6eV6`gNFzPHAD5g*{aV%wS6m>B6O<;B6Y64QHh;d;NmUI|_af@(84&xvN@euk^9J0VNGZU)}#5Rac16;SRx`Kzq$ zMGCK|L6=){3Er&hQz=EW;6sUXES#VB(+fG(S4tiJYk-Cug}og|lqB%gJ|n>oSOVZuWV5aD-1pzUb^9I_w~&4WAUsvm99CSF-2SRYtoRveJ^Nz>x$pJE%Mdz zprLi@_x)E6Dd64~A2oYhymCwBh2`{b&Pm23Z9!Sce%Z`Ot;~+dKnW78m5v#jibRuR z#|)`gMw!c7Y}D=>eiFG8$?35Vzq5SB$zL0)=yyl>I!M1aWA|;JM6O3iUjNbFrMci- za3P^}?om>ETJ!C;-A3V((W5D%2K^k??uU90e`S>IRhtj^t)#0uk|#%XY`kz*3@W?G!zC^N>k z9QiZ{rf-47$ZwGQiBZI*|KbfMjK#DHH2^zD%9x~*niE3iAL&v)5Y=)(sf^@TLt`N` zI5NeKdoNbmM2I-ZqYK+0HbbI$ZxH#QW|ExV)5Qp1cN2XWvJ#8+*fL@;cl(^_E$N;` z5p~}vG1&Y>5{KZJQN3Uyj~Ia_S@H2ey2YKd2A~@qe3pVh7{9^z(BoDxh(eIev8zym z#TQRsqj$?n`gFo?sgI((J}euV6iGp0X|bEU2F_R2-^F?#Ea(>(rM#aDnyYRoCA~OW zYZw03;Abqug8~hR5)oK?w&bRSegRv2>y^X_$}Q- z%m9p7Pa4|?wuV+(+S$O`J3sPi}oKcO9xjLJ)E z6Eqj6#uq+mtAi?6ed{hxIx=4>kF=_5U!Je75fyQ_=*+4KoD3X46?FCE^Gnf90hZor z0oktNkH2VZm83^9wp~JWP)Gqa^NC+FsGtrh6ZBWk{XiXI_4K-5CJEn?=Ab$r!H2oR zZ=-rlPwJqRz;On(!!B}>hB1T!&B;*LtE@I%O_$|Od-yCR?XL5zj0#9UipI}4gi}^+ zfeEobSk{)nX^S2{dNqncsSG8Q3b~aaemuz)*flv&eq^fnRr_2xt9m+l`>gkf?tw(6 z+Ge(;^x|Iiulso{2&SbyJ#zW}(jnXh`)d8c7ZKiy zQo3@HBjnm^asIVU%(_en>rH!xeRN?QB;PZT6Cd-OI0wdEqEP&c9yWwK`BjOEXH*6{ z1>gZI*c^ne7$F1E#)G%6%oQDuyV8Ln=6OYk64KT z0zn3$99|s5f@c`4K5vB-pCD--pydo{L@%>=doFei<)w}KqlC79=cs{jv$YUL#WP@7 zz5tUF5sa$c2D}ZAj(`jCh=^1cQ0(3YTGvKR?-6K0K+9wb(ugBry*!vn9|Sr~&tWu0 zbj=i|Xe|eghvZv@6g^+dzaB|-~Z^K_afhum{@g# zVWSdmAZ+cxLMih1XAFTHZv3U`T26ceC)(CIZw387ieP=X8hXa!Y7B!?4ct(`os1Mj zG_65>0KWIjw|olCYE*&TOIp+;sI3BmUmpz{Gfiy@;3 zJ`Xx&3_K1&pcmo!|A-zENfZcT5W2Hv0Q2?>^qS&2h(O>1NEHwG^BMwyS@B1siab_2 zeD0wL*HN?ZHatoox|p)WyvhKbc2*)CVLIWq_j= z?O;Ie9CVm)^!Br_ok?TZXrj2+htrkVd6#)C4;hxfkC1; z+|{-y9HdG8&Qw55Ocy{VVd%4y*x)ko(42P9AJsODAQ71tl$gm#in_Ww;C}Xx-E+^D z1Y1}TAxa&#sPZZlsoyXS2P(819=ilod8Ux~&5Soz78_;ur;AY;TQ!SaYah~lZ!%$a z&gVoyzx?A26*|uSDp#wNB|(SRgAnzdK>B=vt$>cam>`9ax?mTAXc%U7Y~jbt&}D2p zYAN)BXbt^|%N(zdVbK$2Iq6CGnP!Vu+>s239SKZvF~IbgpH9%~rlZM7FDGK>mnMp4 zG34;sxKGhsru37)Wi#%Ce+Bd3g=I(jX;oEMrn<`tQ;l}-wB>6?d;x@idFZswrk|eC zz1)$=PA1!xG!xM2Y*&Mf!;#d_a#(^m^BCwkUGY0#IGEkJ)q@`(CFMu#ZN1N*l>3Hr@``pJq+GsZoI?z>szpEmyoD}Vg+JyhaN4Cc_Ql*-%Bn3q?VQ5NF{ySP z?{fXJKCfhz26Rjt3P@E|c=`0C_do-bQW%0g{1*_3c?`4Uyzn=sD*G@t_nZ^?NalvP zU3|Vp{>fX)vqYcLHUe??%KMtZS65!25%P!lX(_L!sZ`FtT`g#~n8F}gBnjkwDw)}1 zQ0}lbawWm!=!m?1^rQ(9fO0v1U6r8OyA;iu4_JWq z^<@wg@kVwhZ<-??_xoS=@s6;TcE#4Oud@#Up2$E#w?UaW_*&hqTGd3ff zrH;s}d{Ts}Vb*e3jJ^7E(1F@N!pl;w6*GC{_tlwx9i(kj%k$O0CEdXwd!DUb8>&2Q z2*o)$!}NK{2maP;Gj)$n|9f$_FK_k5)ilTI(Y9tn+ieDa?+~i-kO=6l5N|r}kVTRE zPQd7B7Ng1?qT;Wcp7yPOR3(UYH)u)7^JDdfe;dn~LdU|g1?~2KCoy5_9-Btnf_cMv zFa0LPWW{4EH*Qs>Fk}=EAC2e|?c29scETJ$sP^b!fz!N7{qC6v=DF9Kb zIma^ed9rXlw(_NOh2>AZ77nmVC<-Ga4ZuzU!0J61{&x4rbYwn*j;EUWM3wbajmMs_ z2yENxZ&pi8_Aowe+?Vmzh&uMCbm_giQdYCx?;4_o2_(WU$e$2nb1729^ z>XL`e2<Efyq;nI%m)zfGQ?9M`l(OZ9lz71ZKS~8A_W1aAC|J24FlGn2z?K65cPAQE|@W2 zjia080D|LO;OJDjiOE zAFO+6I!RE{h+49oSPARt1FWZg2l9_~o})hZSTn=*j_e&zC^2{fEkv_pD|(+cQWb@% zU5P5oLf?RwEeSSB-s2oq{5oH*yi624nSNRHGZ<>zINVR$8Fr|Xp?D&_JChzg?Om5h2z}l64Ie8m^q3o0Hykmw`iE0K^OO&w^_jGBd(1du>AD#RB=>PNQj1*2i+;17VR8p;$ph z&xxwiEjV_hVJ4&@E-)*{F0ZoYvvr8Z0T6nypGkkel2`t?QA5zWhx~cytZFTPKB0sP z>KV;HFaFwGSq4M)ZxB(`!R=_+#eiR95PeEi86F30XP<6DX`4y^Y^q^vjc*{l0t6X}Kqmv_>11wKwub)2-Dp_=5|dHMtD zfmZMzyaqXh3d&C2V$+a}FZ2GQI2x-wDSRM+dZBin;&;a~!^SjJnIuDyTKTy;|2*h} z4lwyVHa-y4=-emN7=K2ZQmKQ-woRSwSGaK9VpuE}R-{kCx~JB9|N32EKyT*>n+9ww ze)L~hSmWiLk&(hn4~v8D(&UKZlQ)xjAdwvE0U6ie@%l4|7(a~jex+B*7*%^=QxoJj z59etZ(7c;7WqI!;JeuTw{k%VQ?o${Ibw48oo|~1mfRBf${Z3;k@!9XB+CEA%4@iCE zTLtI%o+WXeQeBD+RGML#4Vwray`Z=ILYrzbj!_ZvDEi21o?%)&*siHYQBtx!i!AM8 zqN=G&6}aY9+dxa3Ju%O6(GDoqoVn;Fdc0->Wc&9pKY$hZ(p#WCTkylEn9ZIin=g^S zmewC7iR!PVXSnh?-#>VXPUYj$aYK<`dzsaZGCzG2MRCkiCZc8BgcFJ88WKdN5X~^O z2}xvZnlkYlezW!W&Z#?LFK+S{Dk`P0B<>aPO$Eyk`kMDZaUoSnskdrrAN_*h>~`B; zyd{VfGmra}Rzb~duRn@(Q+zmrP6lfGPCI%QrAm3mz2kT=q+Y?Uf&`wcZyj{P3pMgJMGJ)=Bnf>i zjn9_gt0omsx=Q<3b{xy!l^NV2Mag)SKQN#&#eK7B6XDCz_s3Iku)KEII)w&XUuo2g z(*>bVky|51nH(GNTR`N5PUk{7l%VW$RXw>cUIFGlpI zc}>xH($jAGhQ8L~NJcYI-UWWiEPzVdpW`~`;TSiwjeaS)MU$xO%Y~7YJ8 zC|^6GXjLAZ`XQgb?FUksvPRLxa(u7|kCJu18H)BoXOI|Fa1VY@YNLADLNqUp))oY^ zqN+|n=MbIYk&z4Y`3HLZ8fnS#!3^6UX*c%L?@+$FaKHkHvDdwkVEgq!^R#n>cxrq8e*v}1EES&fn{UCZDjw6PK{xY-pkunDOa6ck|k%MYpMFHLr& z9&4eavc*yqe=`wQeE>-Pj}1B0saQ4aWX^S5Gsi~<6usGZk_;NNErIRG2`-w!H!hd+fs*h#_KxR?L=Buy-{j`r-Ex>CAOm-RQ{Hn%7SsPIgcG- zQKNiS=wY-#S$qZ12s>Ujq2gXtX#I%d+qoT+P;CNN$Jr;R^*4CeX3Gw$f-xh8?WR6o zVHxWE^L)0&8(d6kAFrQIXc*TL{cc=qoVTlcJY=VmY2!isf@XyNi-8k^k5<4uu0n>0 zE+rX!i)hTg$2t(%btn?|)|HEgBGH7lT?R#`@D1iB>Y=_e;S+VI^@qjt{vnQ^OhO~x zu;>i?8SMP&B$G=<24f+sJYX2iAbA9uD=8DRX zS2=H;ST|WweEvaZ^nQCKsn7S(Q>t9Ve0AA^?4k8!*gCD>=qK&zl;d^M^L-8hc|V@a zuLnCfyMz6CClEKkdJpjZ1s6m94@qM$74FEShpy@oH}W(KL0l&Rlgl z@~^i>Q@gk~-GrVAH`yB(MFLn=g1DP1Y$ZF-)i!imEB(Bkq;uhTU6`hd?(oW-pJTj2&Gd)~0AF`wqx%eeD?V&eNx)4Q!K zMXyZVKd7I0(%GWPB(lWAH(UGsRRq0Q`R{l0N*BWT-Wra+jm{L@?zBiLPzwkN&cIbe z8}pJLx7S&?SK^tbKa2XM#^lqUa93X3x?v`pjoG1)Vw4!MwQgIk1@(X$@OJ*Ux? z5ZgC1c1BYZQPr_NPB&#;Fjj<+C$dh81peH|_D0n#I{ILY`;V*X0T1KsFq;)777Q`;~{Kp^Y&wp!F6h2XGQyQe377%K3 z*%`y7bNAz%lIE9vVYw}jn^srXTenoiyc43!zrEZ|el13sQK6(RSF!0Qnbp-ienV%P ziuFcd@(rf`buimJzi(tYs!j7%`^6V*;z1MBoN`5y(bZaZHq*U^i!&-^lbwOpfgguX zR|Ea70&{TSMZmivu2s6-`2j&5qOF})t|UE zY@cqacGR^&yKO1yw5zd$wfi$6pKEm5Y6jY~Rte`F*IrfiF`+y3tnbK^0~#4`zM>b} zyC%X|;i+~tbLeQjt_sxw{(#2e|Nnyj^F!+9<5S-pxQ3}xpk8kT_uBs)% zk(|s?VjV7Je8IA@I%8&OVPbL&hXJ8fC+FzPJ|!_-n)#{IX+)o{E}UO^yeo$JdMERO9(W7U z0%avV1yJZUobDu4wE_us^u2b()FRaZ_9&;RLvMv9bCRt*jU7Bfvz4h8_Aijh{fw9H}zcqIf7Z!G1IE6dRP7YRLlYZ zPZ?r*KJi;jV>&bHI>?D|Qzz(@#C9pO%uU(7P8uBXAfDplZnnQOU+6i@YZ?(7U20(wyvGH*X7j(jt90?S6I&kLz z`)9AU+ub_Ix2%%B$Cb)uJyeXjhIE__ S-mjwIKL$D{vDI3(*Zv;?;li5$ literal 0 HcmV?d00001 diff --git a/imgs/operation_mode_one_nuc.png b/imgs/operation_mode_one_nuc.png new file mode 100644 index 0000000000000000000000000000000000000000..6a23ec3b1c89681ee42253c164c63707efff92e6 GIT binary patch literal 35937 zcmeEu1zeQf)-NH7ARq#gBB->$&>f0&cgHXw0z-ExDj_h4h=dXbEjb{a5(9#O(jf>8 z4N{Vdc=r(J^*!f3b-(XB_uP9AKYz&VXFogE`mfw;Pnd?9JP`p60Tvb(k)py4Ei5c- z7#0@JE&P+9rT9x=9Tpbjth=m%yMy;lTevkA6Q9iCUrfA^TTX87Onf((czL1D&RkZu zP#agMgBzElwL546&mEksY;W3HTOIb{h4AumLWDSZ1$7`IOnldPFuw#KT!K6zMu+{O zHr9?u1FAat+QQ*bCSExKE(jQk)qsbGiSIi2OV`rF(cRWLW}BEkh>15f0wVfId76kZ4q1pMOxO>(xb);FENYjQk12ZLjlYV8iSIb5c^la;QP z4!@J8mz|1+0-wE>ke9*X@;t3w-E5s4k9NbuCCDXk_`u!A+4`{6#>vSBZjEW>lVyTj z0|R6J@yQ&~27GXYIvn-Y0NdpR3&KoqdqksKN>B$oH8)Rn9V2@lK2;?iL1DQ+AMJQd z2XA>-sPipVCo5|>7{bc?a0xuT5W&Mit$Yq!gn0N58*E&U=Q)}d)1YnZd$b@PuvpAu zY&>kOtlf@AJ8W`ya)P_tI{&^A=H%#T4Lf4k(TGr2S0}IEcf08XKib_q1=O#>ojLgq3F8TcdmIs04(jLu13NgH-Ob(SnCxy|whnNpBj|VC>z1v% zwYD=9hIz>gpbWI#a(94(Plr;7fr&Hpw}l^#1|-DY`WT0pssA=Xecv z_V{&((6M+O!I&rUs@%vRBvf_A2P`JCbt0UCi`nr>cqm|p?!@rNCm-n^|#5)Cv(vI z0J?v#=U*Tk#v`xfz+>mC>Mf+KC@=5s4w1jX3D}Q8z%Q^mZ1@#Tx1a|~(bnNW+OK1v zVGCqj1!`#x*Kl&Pbw5<4mQL>OP7VNHaLj}2P?)`qD~2L6PH-nzfHy1an@|rp5Y0c0 za1Cy2gHginP8e81-JB0~&`n!!jHS7LFyXc1R-k+jTfhsq+}$x63}|JbQ{`Z;-dr~^ z!oX$i0X}*;a{_(ljuAy(IS*&J6BNS~U^jRHw&gJ5f_a0J2Vx5a9f4`GbaI8d+j?4a zx;lY9a5*~y`vL6JpG(Hy6wCiUap4s@ocaiqJR)2?0+3&Rj!eQYvLkfV^eaet`1!bw zY{fB7e-#}J`2N141AUHA^iPBB4~ccOpuYt+Ye%bV7{ddY41+`6+-zZh7jEuQSNFec z{zZ=+0PVm%!NBC7h_^{-`3UtC5P<~)z6Ww z{{>WkiKYKIYzG$h59xO-l>c$qejoq-A+e5J(Z2<@f2G5A#Jm4EZ2xiCfX{$QU;bGV z=MO=A3sNqB=Bxca*!(+g_Tk(Avl%wtQ4jfg1Zhtd1ewZ!+y#VC?(BK?F_%Orq zxB4A*{IB~n|8Qmr6KenK^L~8)K+y8v;z#~9NMQJR@a(TZ;;$;{zsu`mef2M7_Ag5P zIJ5YxemHLXhcWTDBiO?n-{EhJ$Mt8~#^c$JERTSo$RRC{mD7KJZjp!g_Zdz8KTrJp z-;i09F$V`x4#L+Jpl;r9OAQBoT_M}!6XajALjON&(IdD0Unp4ru*Cd#Y0-o1&|f*O zK2CH0Rv7TBoE|(qE=4$eaP$JEwBzuwR;sPw9TpY?mg0?TI^Jeql22La%5I@Zu3UM! z&5Y0bg0=euGBC^FTH#{R1N`$RP7vxfnId0R#p%Ky5V?>db02VVSzc=@8UI|ufqzNX zmqi+X`c9pqqkqtqmC@~)Q9qkyAxA;R3a{n&UN>)xh~YhY#-J1i9cN>X|jLK~H?xL(G3!()i@8q^RPX9gopbQj#Y+ zU}X37#_y9zjvIWi3L;Yzz9zZ1Dx+G0q|v6pGUh1=k3R?X|Nf+9(q#)oNhQd(4#G!_FZZ#WU#xHZ*<4@1C;yGF;+1 z6)oR3h=ir<=IDjdUK;1PjE#ON6RK3>yBVIg+@F_dA)@)n`rTtDUh6jUiv4ek(=&-q zaXc{8i6J`mE@p(pJBn>fGALcCh=5He-TZJ#&b`&_%oKJKiH%1~WuI@a_oz!X_eou) zyn%!I9I&1I#&Oh_yQ6MzU71=Cp5Xsub3m)aPIta1Gm6(@cYPY~)yC40_G{f7=AZl9 zb?H7|XV$xwx!=7#b@A#2QTIoj#-*)$yI*w!YW%k2z*gngzkcnjbNSI4ecAf$Jv`UB zm!WNqBvM!9F9vLwb)oo1%ACwMBpQUT_An-RCg7tBJF=@*YK>PZS3Xs^rNdety1rwI zZ*}XEU~%@P5ptwMKqVvv&OzuU{mXj`%KUAcX}P5C9T7;lH=hCgz~qT1;EG0b$ip?MYcW6w!?3-u@FdzOy}W$7q#T{JR*I_MC!Rc1m-9m+KH9RE^g2-RVWH z(@N9VE_(E8-rM1`L~W0HJzsYbnJ6^`g29%%yMNj%#9C)W~ixTjVV-B-uo5)`HTpk|ZY9)@$HyBN-3RbP=t z5I|CdoKk!>AC$ZP-2XAX|9vGsS- zb0`Cs?ZSn|yk%)Q^hq2HvX31yh^mNF%fs{lT5m{eH z(x8~B>YD^zlaXdQPfx&VBy1dz1ZPonBqUw=+!c8SkALgcinK=GKT8{J%A4CJ7Z6qRAbRqqLOTQdt{bHUcmAqbfrM_4!t z*0lz-p6@dwS}6SWG!9${s7QaX;*^YjIjTgv3ak-Tszr+D{~6}@w7Gc!;Z(UV`cx8@ zF*UpLB%|Y5t5{EFqFv$#jG?iAR@j)}rc_X)oYTQhRc70xx6q%%VXs#Zdy;6e{c*E$ zy8o`LYoqEwd*D9qo+dwzIwN9}M&vzYCaK$gvB<9YBr4CijMV++_VQ?_ji$NS&jO1x z+`F$6xnme9%@>~+otFv&vwSLSz|4}2?z@SHAQ4F`!Ep{IpqSeJ9G@*Ykfo{o!w-$x z)XFm=n)fuJ6sa5`<$bX-y~aP$g=Uoo_VE%lh-dbR87+%eA_c^8AU}C&5UJgtYsh41 zXh=}Yx?ERWT%7K^xd2osTm0yl`u->DKpnUJWR-Uv9lBjubE!u7u$nlM%LtLojbY*F z;oLx;+Ywc(d8SqQWY1W+MMMmX9E?+NT$4pN(-eDtOqV;FTF>SucW22+P=7!Z3>Di% z;kZ{91$_6!`&>5Wt1Rk1H|{+ukmfJv^X_vBOP_tePFI8$pp20i;(#*f8+Ls3C=R{c zN6Vw?S{AbJx;{^MzwNVHn{39366WSsXV-mwt1Ls7laXkX{LV6$AeRs*=HBzH69n}~F^{jA!lPCV&+t@QBqxKu3+35jVB zNGS9XkZ|o~D1FAaDu)rhp(1NH&CjGM(h08=W0=`H2}#Otk5;-G6x?*3e>cEBuIFAo zyB;h(R^k?4S!N+Chn?W{WjMVyBsB87W*e+81RaL93FN7E-K(~4j|*FH-0%Rx{xz5s zm89+Kkfh+CS5I}pVQAgrR5=CRqw_%={RQS6-@gnfuA=c9wGV{_`(aHy)C{9;~q`qtn}oU?g2rtqB3htbiOK zGmH8Gij1f20d{!;JRGt+^we(AC~W1H!g({$9Iew=@oop4#i zP^3-lq|U?yP8Jdg8xZr9u-v0vmAy)XXP#qFgnO%cN=9Y3wNsw?Rn^CVvnbyVNfzjbJfeO*L<8+B%5iOWr`nL|o;JDOgO}qk+_|rltD||X{Q6D2cUg}#$Ejym zv^Y2!6n0&wV=0$v$*(>)Gz*YQH3?b2&BsTeXEC+H?)@_Uc|5m|*g8SJ%kp9`Qd@j9 za$f{M!yg)gfrfFsZlVW7&c>;3@%*kenxx2fpDVjNpJBhMcuX+d_t>4NmpcN{QeK*t1gVz zA#lVw0AF?5aBlFLzWE)d2ue<_h2pA;#>nkTDJ*v{%jO%5SulOAahm#mJU+9X37O!_ zN!E@A0ocMAKf`o3L{O)C7~6AH)Fa)tCu6=049tKTnBZXG8gGaGhQS}I57Q_dg>mYe zDkm?siqa$3!%6wLKJgb>{wU~vF@wF}$3B4KN>Ev&m0Js98d#h=@a<@@BPv&5S_QhXJLj_H}jrwAV_UQQaJnZ zadTO*X1Puk+FdhYe1r|%o|R=hvx!rHwPY7YtEWY7CKa$i>x!zFrPxz(Xy(FNza#fk z_M7-#meHN15XEkLwL5kgTM0jRunoyl!5j(n;KSOV``?R(3}^H@v9oC(&-G@f@@JW^ zUgt9N>3OHDSz#%QH}qw>y_RZ4q~|WA8s^VHes9`wXK(k;PY#ynp3jzmZ>QDs4hEIM z=(UghR8=*zN$WOrPuwhD;#IL&D)q83R!@;g?nu{Ew|l+FB@lcd{M@9A*1XEaT7}pD z$5<}4>+(}dg_>`h=R)et_!jdx7tqoL&+xcol@lB*FOs!=6VBX+C|ilck}tb#Ee+YN z!`%gA%IlDyIJ+qb^eq^4?xs5%m?E8ry4Hu5xUE~qUuq2uJsd5B$|QHJ)o=mRKcyLh z%(3d7C3j~)#3boIzx^%y9_KnOOduptjw}UPRn$OaSbiPtTTc}hOf0@yf8{yd9`Gm3 zXwRbXeC2%9NKtH^Y(X55z*6|otH7oF+WH7d@232EeBE*%PM~F2IE~)u7>+%vZ*96x zwOB#}-3v|8Ox6xUW{7M~gkC&9lQC#`_Pd+DnK1WPcJho#cXZ2Y+-IK^&LO0TdWeZn ztS>TN;hvwWYM&O+)v~BpO8Dr2O~i20C4@jHTeYEF5yLd2n6zgMVe|52Bidwj|IM8J z{HHC0?77?z2@-cQOuF43p!(Cw*uiFNgIwPE%GrWN`_4Wwvc+bA{Xn*vPV}ziD~HH0 zWh}biMXc!Nn;72o-{sEM%g)&N;t{5F{e*OA1yDYDGF0*THaaup&?Of&MnO7~Cp%vW zxEDMx{dAdNCWW)Vy-DU(#ovDshGW?roQR%G?`nDXfKOhT(}r_h&&JOqLEq#oivE;Z zQhVwdSZB7>$y55;S0DwC%DhJ_Jx)8=%bhP1x!9%oC=#!TaB`52dRg$xZhLKfRJ>}u z(sWL{>g=fLn`zNp?j3yeiIb6`%CGRjC;_MNp>#Igxn2xOU#y@qMk-TRJtGpY7rz;) z+u0*5St2syAt+VM=?bpkSrw>;2eG39{L8+6RbipNEnBhhWJG6JZAwRue)@hgnM#8m zuutd1Xn+VP(MtunP=B?XFG}w`e~U#5iHjbsB8VY~bq;`M2*s|wf~+*Nbn4BGb`nYm zQJ$1O^LA92SF%x?e)}WUP;n2o^A>%@%#$jDQe80!s;e=9@+pKF5u+RE_S$_KAI&RA z@$f1)PNv(1$GF%}R>PG?YQsNKl%pc??ts`tR?OZ6iCi93mELGziDJc9M$uDyHxaSF z)YwJfP&LXBqq7-QoU zAfY%cAUYgINSTx)wApg{ag|6}mg+Rea@_s}dGe(8+4|3;Mv=aY0|f>?p<+qJnk9!Oy)Tajp}%5@ zT_5>bY*^a+rh&jKdWsg-!J^+gu?vl{%&OByo>l3ZMnG_DLmO2!%~Hh71UuVflWsm$ zyO7wo{mq^Jbpyk4#@XJLluI~sWsakjb7yYv!B5(Egc-6bPL)dA+YH zYqR(XLve*}+)ehxLK>+rNe=;ginrT zOxJDJ7rGcFwZD@#{Jax0@`4;5@LPghwD@LQF5c0BJT#SZ%1QrCBD>8Z~59v?Cg=!|C7 zC%A<})a+*V*4w$+R|>zc6JvRp_hZMcKJfbD@}kYHT!l5e#)!}wANt%=jnX3D7V zC+$omPm{z3`8Lj{tU8cmcufT50QxWD#-G+WV17qeYzj-Kp8VqSIRQNLSthz_^QMPh zQ(rX9II+SP*M>|ZmQYXo=07sg72Nk7?O@0+Lwvxi{k*u*6JzIB>2wLP$xerX11UDcCZ;dBrh+G=gWIGl5o9%$(%Q+Lo}+a z8FKP?z8I?w5VI}1<4x8@hEgQT)^ZBRm}Go(+Re@)>-O;ey~+b4QWk3pNAjT4V${M5-pJ|$ z$&94N1FUGi$QR^tnugQ7w)z%RaFsFFRxzy@N{OH;a-O>7;;rge?s%`TfCAp(3xsf8 zO9iQ=tP3s%+Yy^}jw$#-tg8*g&nHMPLqCA{nw1`d%b<(3=qvF&{)pq;NLK)V0b* zG_?5DD+V5oly51Cl4LySNLrx~-W(E25X24SBsN|imHU=vJ&X834J(H|gvqSaxj zsL9A;>?vID0Y&tYAlF&?Tx}1UAeY<$X8Qx%qAf$&-aX0>RK52O7;m3;^yNEq9O$Px9(3 z?56`d^sp-{Y~u6OFA3nGsCF^$mIsufYg02#?^A|#gIw&sQPhq6X_-{X&gZWEsPv!+ zT)X>q;ZbnMkEMLR5PcP@mFSPD@+^XF-nvf-1~Hbi>68?dE|tR4SU48<)cs}m$IZB{ z%ja+5Pv5j3iJP5DHK@~Mx)Wvj(k6FcK@f!I>}$yDR4uoHgXazUL+;;*jwYI%qGS%2 ze{b-m*6ljE0{I)q4$=AkJmX0vV|OOt^(XxL)}UVL*Gb}641$PeR23a7+Tev9N5 zb(8&Ab;bItR0E)}^vbA#0E9(RG?Z)Pbk*&c7|{)y6miUCp`Wzb2rot?cL|r^LQsU_ z@Qr%qYR(Gdsa4`omi!`X{c|W^B0CO1x9UhT@G|$(xz`Kcl?LVrZxlbjer4lQ*03HL+T~eL~4z zrdH-gf*0PNs~EnC!2&N1K|Ujbu;e68RppH1J^?6JF5?nqit}h~J>Rl9y!(|8;fkHH z>nRCXO~@NeoI2Km4_&$y5+r5N9g+)Qy{(&6?u>_5DvNGTuA=Z=EY0g)7}vWK#9wXi zxOV|)9Ws!}?_^tnU0H{qUR>iM2sD^ZWkpb~xW7Q$D-8DI<$r-lTXz^K-OPU@>xGeP zTTJBrnD%0H=vqTCVY*R?9lP0?v#CoBj$*U8%@RL}83}?o@L^mI%8svNZ^t_T)uiMY zbb}tX?Br5U^%6g=>&AlyQ{yvE)G0i-Pf|GzmNRy@4@2J1QL_jQDOI%#VyG-6d5H)n z?Fn4EHV!>{9+1Fvd(WfnnAMN3GH=AK3K1o6i$=6H`0f~1OpJvYT7$`xF+#8I2%#Ms` zZ4eerCBGqEsp5^o*Uu_mNm_ZibTx=4u5=<*HeznM+AWj@nlzloal4EYLl6g(8|P65 zx9=mg3>2{oC@%)`yjTiheRLI{kuW!3I?J*>jxz|!H-?YyWlqjJdf^<(8*NF~~7 z8gV&pwYzikVV{orwPrLvD+N?(T|t)6+_AA2whEHSojIFl{_72+eunmqo-{HYQeX| zQWR`(0}JLp9^OKr(1-w+gavY#n&7{<iR@gq_Tw}3sF_;+wvl^SJE!9GTGUY(lQ^wm%sjwEH{a4FJoNKB z`-XWh0$U~{QIgM!p26^v+>Xd0)IG974{W2o;;NvIQRM8sK2x3v z<`*qprVm;|q)h5_AhL{zk0CC3Eu^S#sN!gWr@&6K1;}t|LH5^w*6OrDDey2yDW;0b zJthg0Hp}ZJgC9Z`HCsZMOk&2H>HDdxwkzrRZZC(hF;vppbON^vD6k$I&5L%EgyJ=q z5)X!hF@oWC&`}g7(J>9dOmSI^3MP_0VfbRt``E)r#ggOw{CZu5O0IV7wzAG%dG2La zInkU%pe{U+74O!0XOI=AybAAgOM3+YwV%^j>?yA)v9Je8KRs96&FDpWraBUZXyYG) zBMc$zQS+r`QTG~w%sN4^3mSO>)Jn~Eij|EG#|z6uJ|)s8$psMw0-jxU+U>n`3N31M zSN*gXBViG^o)l4@{VZsDuS~Pt)^d_@l+u|es)>TfL|Fp*Y@XIN`W}zkLV|#OTsUC&0Z8TPPoksoL4%E-vs_YZ1j8A2H3srcHw}A3pHcDka}*t-m;Taen1YbU zLhrq#X5v63I-jop0%Zf`XKwZ#dJB^s34hPKIhbfZe~#`J0oCP@B^=uAs>w+=N5}kc zLe(~2hIHbq4&WFAGKg`Fdqd5wpi4?Z`^_zBW_>6>whEX{3cRb!!)#dhk&>Zq z#O;jw$SJ8{S~*ub^>VFgCH9j1S;aW&bh44s74c!am3i@PLSl=*P#;(&vVGh(qMdjaHQdM_br5J{E;we!_ya;KBd z6RjB3G`SU3K)sTy&Jf2}RecNh9H(F|Zqd7Sr9wVy@=cGL@=J>S&q|=GK)emYm2agp zs{=PEE@z&m^KP1H*OZ#Q^2zJm?X4jjyj?E3E-Gl)U`b1Jd}($cRi`K{H)}AqPC1|> z0clqF)PNRRUDo$XI1?X6#J3%zE~&}AQb=sr9Idzr>)(wqV~U3sU`0Z_UUkR7p4(AF1sze}f;SL43&DTjf~XhRPixpLDr=_Bx+&SKC9( z{PN8teMR1+=PQpKzKbK3Dn!=@OUMM?G}W;KKih~5<+n)Pd^mgjLlJe)rJ;pfs9QhL zinH06wa7ew1d|)?lj5{jxUgB#%%!&?nZb#BMmC-?iTM|@|8NQWQ4!XS{e5bWfU~ex zC(+qI4^JZg;-9<{#F?afzKZTlsxYZ_2{HBe>z-oN{K%@6PQr_^;GE3%R@fa~V697- z5!?NI;UKZl56S%YV_v<8*(s8LY352UB})r(N}(3coomSH?shh5{z|5oTEtjPL47qX z+_S!Ba`ZxX`UnrN??&=3)UDY>Ok#4I@3V`$#I?_h3=Im3=3H7|FU=8XS_bveC*O*A zwVF=Q*9F~ydEnLRXKPW|4(End^959f#O>(gfkcNrfQ3Zr0hZhr_*vd{wNY?bMYzRX zusCz}@`T{IQ`psx&s2q;O7x#cvoGGHiW0;lwWE2&PsbSCSbozl^wca6#Tp0knEL$vizBB?AM?gZa_qv%P_} z0oJI{i%N|lMAnP_Ummt3u3Xt?TMZd~JiXM(u`^50@&tJe9Iw4zr`CV1Gql?p{j9|9 z-H$sztKK+$mTd0d@e(`O(hiA4swhZjkk9G>)0Cd*rquGf#NIl>t?et9O`@AwN{o}G z-`jJ7Pu4phiepim@mV0WGSwvTCM$z;SQiFz*~pkxm5>7aqu?k3fN)=?D+^#>I9No$ zc^u1UF|RDWou{SMlSL50x8^AdeE`gc*ci|Ga}mX~U50HlSTxox55;F~X!`~>7loWH z+YAX%M097-`{(nF+DyG76<^Bkk76{zGYHoQzBWvr396QSr&FY8wd^w;x3Kz_Q&HXP z(_=i>&kDb7pd7~)+mTq7rAzKDGRtM(_*f8Y$aFZQg+U6h&FoaNDEF#ef9{vP+-f@4 z)obeuiv^h6wU-0pD8;2$_^i>FW$CWqxPdINbx0nbMh z4fHbuY4kG$LgiGez!WG<_)DT0pp(A+*#117mHJQ%iS8zN`~f{{&@Je<1s9onai71m zzV7v*tTHW9r-S(xleMF>BY~>51D-c1H9+Ai{{51y|E+S0zpU)~R}Ld#v<%9$bPWeY zy_T2O)cm-BPdCiF0Fhf5(l-y#?UefI@A2AKhY-5-ab3W!R|EGZsAZ#Hc{A$@=)##w zjJ8Sfkpp7J+$FJ{v@zc!Ur>IsPmanD(!aBY2Bl1-?6!Nra&b_aINuGe`cm-(khDFk zu{^_#cnZ8`Rrg~n2AuxRQw+QSp)m>SHE^HZvgVjQgGRmbGB(ii5J>%LIl(#Z4kf}9D-c#h4^A>q(F_D-u;t!xHgkbVXhC|Ahx{( z;QdL>5EqbA4xb^{arjh@ylPl#$ryf&E00*2AcE}YegmE>Sypq3GQegj;t~RsYFW<@6g)@J2q@K% zwikKBSIn`SOEuWS*qFTX^K2HkRp7ay}3BR0bP4chn&iyXc$awE~s2!pQa$WDESGU zyk!D3P>D4;lrCqy(qpkV$*9UR&kRbG1ClkjAVJK;B2#B8*4sEF#%#N$54L;(W#6Bx z>1MaN(B~U0kShpAd>cZ1f!$&FO*ErSh<9~QN;^;$r3g`kex6bKjLs9U63ZK;DEisH z@wfNWWkQKvn{mAcoM$?xU*+BNL2*q^X zhYbW-g0}af7${$i)nsR3k-xUndO7MzJ6Dy8Lnz9(6;s3cBaAc_bH?XR4&D3OC6yDa zAmO*Aa~754+Cx~qHEiFVqhHW!?VM_pR9}6ao}j6?Fo~$$38Z0|%>CDbt9NG-UAq-o z-hpzvWNFSV6UK{Xqa-@acZPeAVVU9shInd$7oa+g#bf&Nu_ka;|9KwFpn zeS3ww%4AZMnIq@9Hz09UtcwZ+Yp+o2pXo?E8>-jkvJ^(TW42smxuIW)?m>GxM6#)BCA@m8U}u4y_g~ zbm^@IzM@3{Pmv0CoA679aLn>HSsSU8E?v1xIfZ+QSV!^RD^R2p6(?_i)9&bOrVlht z?!dZcD34_ezPg1mzgDkY$yto=N6g=2MAa)`{!74) z{kFYUsQKw)qq+D|d{{9`_Gw-pk^1PS;S~=p(=~f7mOkMzo!2)jM*-AQ_`n84$NK z-i{>)8*&T1T6Gs9*z*D`1WLfya;lO15J{)U||WuN2BYJ9&~H!m&0L4G~4dZSxetIG2WFQcP4uN98Zh(A!xZ|O`F#;k-%j^MVs^~kxBv8Zoq3F?si>@r+BN06rJE86 za8&61wq<#=${LhBtOM@1MhcCwf|FzOVGI8yWJ{a6)Q>Ab*QgCtvm(t#S9?vL7gz?Z zLIIWCJw}6Fo`56#Tqu79?kSNcPE}t7buVN2v@(Xaip(aZR`)Y0$F=I}n=)aF)j^3_ zD;}i@gV*PPvikd;66i#yT0>@)1O`y%9b2_rsf@Adx&z>lGBXN%@l^Gy)%6n(upQuJLmjJUCbIY2-ZFXY|I*e;%pAgjyMbLf2S2yvV2yWx3 z1*PHX+L>wuAMWh7n_EpZ1h0dVSHf|zo9`1YQDJI@2@1QUepX{nFxNpTy%O*s@Z^!b zIr{2nA7c$-Z(ypqF?w8NvsW8a%e@Ympajf6{{}OX-MvxUDM;$mzUeZQ$W2(NSJ|m zZ3(FVd&+AaPN3?))=aq$RQ>!L}(77k%d#cY&{h{@B(R;rLXTjZBMUZwH6yJ;tNx5Pcyj*y1`P;dbuw?yV z9Q0rU^2Tc^ zN)%GRCdk2|3`}79;sg<%73cy^YQ_yvR)d?+>H9iLP7N7Lt~(l`*BQ+_6f9P zz&F;y{wz(InjPHtnwSe074sR1Q{PwW^mEv-tb-sL8EVO|7eMu5{`+JxeHo{7IoB~# zA8)|DRMRF$H6jVJ6MnNWBfkucz$@F&5@mgIr=n$WF?t5nX71=l^!c2iYOMp1w@xej zecgN3YrCS*L_dyEsu3sS4s_V1?3jgcAko>VwG1taRiJ#3viCJG6WK)fDta^*C?@Nm zy~&{Od0wbv9|&)4$}>YUs7h7r=JiJ@$fxMkCcVW!Y2dRc#dqg-RBsP;2vflnsTtPl ze*RFO4iVm+is^gI2X9hHx5&IuQ~?gNRldCcYDDinj$PtOtsKD1$EQ0+m}`St7pebpx{SO8b5A}3l!2H(irPj2cwT)rxn%nQNNJ{3p6lT9Kz0Y!yYsnX zlJjXXz02b8^;KYc3&Lere8C8m*5G_DXF7fqagWEdhLMe==p`e`34(J!7@m>{8ex4% zPcL|EliCy38>`@nm<@+j*gC9P=xOV?ijzuD$=M>b2zT2juvDpJS+Ux?;Hw__j zT!@Lr(446ow}iCdm#S!aYoO1ix;-y-@eW5VKIW{HFdW@v8sRox{%Wt~_c6kaz19fO zgo^62rdY!{aM7W%jcnq)mElOWPceaZu4z?iZ*QD}{b^0jN9s89KOfZ)i7o8|e~5kX z5-u&)lw;UQ1OO@;iYRm_9+Dr%;T9yT@cfAb#v3jxwNN+ zjaX~P9?1t0gc{zIRm1^Ehi(tKJ_n4}tP##Ur`^U~MU9L8`MvI^c38kk68fv^;%hg; z*e}Hx8D?`bvWs^EwPxZ8YFecua_#Y5$Vs%ZZUiC|`-oPra!lW}g~+YHl=`{b#lGj# zZ)o!lbH`!8#4S>ZH^`wkkcZ(X(1$F7ylv%52Z(h&MO07^fRv>IPG#9JjJV6go84Dn zZaz&e=X$Oz*SyXwnCsElxrv}6E#vDtQ)aT37s)@}Up>))pZ<1dv7k;bWeub2Z?>s= zS2NYrH}Wa_hMoFw!RwO?0g6OwuaMwQn$dwe&ED$T_zuiv*g}&?Y=YJS&1FjCIE~wY zw&ntbF~#fbnqVdu)1;!iX%g1yr79;-f$VxZ>;U6__>!%{ z@_o=mOai{qV}Y=0K&svWj^8ZDAnoVP$6}xIY3^$0)eG zAbGI=!0w>QkHC&=xc9%3+p!jE7<_dt6{C%c6&BJeCkKEtvCBOZE{T zbN+cFyIW$YX?bj$9SzE4@7`aAnsR%N)_h;C`o6JMaOX!3j)1r&xp!6|(>euiIH=5v z29Yko<1>Bvrp9?cgJ&bFDf4aU2w}b0B;P7#Q)0mFfE8SrRV|J*GOiqCn-^x?X5L31 zM0#(fm#w|49DhVfY$X`65Dnsv55n)Qylq5viergC-FuI5qHC>A6>x3`V~)CoO2KO&bE2abp{*t& z+ecx1HUr$wiliBrHNe3;9q}j#e<1z@8Ymkh(TjJVOs`gX&?F2tUhJw#5coG z;7UhM+wGYUJWGy+k+OpD&y(tR$fuswN7RB#i8%&qfbJAmkPA3GFznX+=pu;y1j6>kg zXjZ+D%Vbjk`3*;lt5BH)oU_gB1Xl8mgaTI9GD%ydBaYhK9he}(2V|gh&zE#tASeSc zUf+F+6i8fu>1D<-Wq+JYht1lcboKvF;+5w#+$i ztFQ=8B$UAaBKNLy?m0c}7iUo}9kfpg8!*NF4Z^%JJfj!-YREB>=klGwMG`VZW4>;} z@GRINzIM<%2-NY=e!d^x{U`{$iHiYY-F$}%Evx&_71}==lv=nu67Z?c-O2I5!~**q z=ki(3p(cvtU*)Z}J4O>~TR8Bn8#lGA`JnrCIK z|MLz=sRwXbeP`>kuSpQ^l^e0Hbfb?sEE-xF5OVSMF#{Va2{@)uCd7zjodGiy@m z=jf@{BsH@2&qw`8~5&UCE($lR3>lB_zo<*@RJ$!e9ePp zO!-=OnF6oGkDO3m{U9|#45m8>iT*R)Z^YCx(E!B&hqVCzHiZ3bu?M0jC2&_>hOLw{ z5|i{k17b3{DEho~IinlmNZFlfV3g_xa3P}eYMY5tF9D@;U{bkbUQdOX`GA9 zu}-zSasp)_C}9>b{?X90sT>88puVG!lUG#OcXxMr1HQS>e@qS40av5bG9o(7eeX65 zvi1?u8fU6q*z9{IV6OtNjT0n88Cj_$+T@mb%ojL-qYd6$9~h{G9FsOyK1=-|IWtcN z4o^bfzM$r{dLaF#h2HOK5pF1C3v%mRxlS3#U0;^*Pz3k-tw2zyRpw}F2rk}d4bRxX zz*}}z_fMAH@EHg9JWi_O#LH2m^6$qaCUO8%7xpGbhKdDZ=&ZQ(;%!~3xHC9eIHh_o zUX~h#Bv$K9rfU#>ds^H7!@=99iJzU|j$lVbhzV9P_lf{*K%Mn=tnSfPH)>bg|9Qae6QtL4 zy3J3e+1nAEy^(&ORlvHVGBE`y@3%&I?hd059j^;F3*t0-@+FNg$|aNN+Kn#ZyVoYy z&NU=}nGvxzqE; z2smq)G!8qXu<`-{ztflrvBbuQUJl;!5X|*fV0^5dNwl24fnbpV92N~`zB(6W+Ms)u zvu!#(-b|~4?c3HDT5IY{QZDW^7wg7V#n=^XeroEkjMZ2Vzp<^%5qK>r?9C+Nlio0x zHJ1Joc}6?!nvNc|4<5KL5`cdem3~WxN{e5!h|N$VaUe;grW0#^nq{dDyh>89L#pHh~l6~9|8}MLD{MH=x?-zBw>;HizF!`WBWEBfi+dj4NLOTW0vFy55pe%J? zDnWfCtsb1YSp&tDvK-ddJWU79QaRn<+0hY;i6TJKDV6s;VtE$G5)-%)%3DdIdCMPE zW2Kwd-PW9YJu7+cfF)3!z&raPAKBqClz`IQc5A~Q0EI*Q`QZll0DDgpG`Bb8VL|B} zzZZI}0cN4?n>fyB1VRMs72uXnG2dyxpa*V!8$(eFUiTmm-|T*w7l*>5I8%qo8iZfR zmF0d8LRz1UwD7`5EFkrR zSc5Qu-b3k&r_uOSL+f1UP;s=v?4y?vsg|~W-xaAw>_-$f!5dF1@|Lbb;pv8{1HjSn z6)ekZ2|_xYkGypUAN_!4?3E)K>O3`Hn<*nA6&@h=O^s><+S0lW*0^^TVusZ)=uK9H z3pO$%3^B!S7<4Br`k@4%g!|SV(4mL3b&Cu|hkLj+InR43JS~CqV7D2@kG^Euyyvk9 z#tA}F+_Ykuqjo!!kdFn0SKv=!#yZ86IkG=naee9psajfZn?)$m# zYdEj-I-mA=BK0CuUs@bX)Mb(`xhPG$6h^b$CjX07a^9-}PEE(T@!d{G8%|SV?AslJ zdUPmWTB_y2 !V8Oj7^gZeh_8yO`1B13jy9cE`gm5JEko>_POohFnoZj@Oy-|XKa zpoQq8KnaNc$&D~)9dUw;a>N*GKB`+L8v7*5nX&iFRAuSHdn&hZhBLRq=T#zONK93+ z?X=5|ppGPQrX4TF%C5@ofi;0-{$m1BA9ltI)Thea<3jBF=OoLUC^Bry{ z7<-+k6S4`I?RR6CF7u4!&QWzNc|q%V$xTMrw0FdQIXe6q>u{qU-(Kev;G}=9mXwo6 z5yVbKmfe-0)AWCOX@PH4sDzN_&5phCS5U8W=J$kgAI2&BSEIX~-ieRGR6pts$z7wq z7NEqRN5&vp8UcgyB7;`V4xOl!Zs@pQ<{v)K?MoY35iUVz7^*k)g>RIvaBj?t{einm z7tw8R7`_zN(gLCqhEflLDE_m0)2HY9(}asuBgr<14hgT`=BdZlJ^IV{i2_hQHlQ-r zpC#{82u5xLvb*m^3mPoed`~UvlR+4$?8khIrAM>I-+RZnEE$@>bPqwbNEhO(`YCRj zv`JaIuH3R5cW(TF@j1Pr8h1u?FG5OVJLCEiq>+RH+BfbGyt58kL<_*lOySQ7F$~)L zb`mOp=?uJ@+Ro0!7avNU(i^9!w3zNy^}0az)A2v|a;!mz0^4|PSdEO9jSmcX3Z$$2 zn0e@f>Bo_fey$l16CMdh)SW)vF$NMF7fem_U zEWH38W~d)kH118{5--UPdcr@nv%6fC0jnbH+2lO<==x>F5R)mGONm#I<#}w0+10DA zjqZ#s5+4APM@y(tBf3tnA4u}fJy=I-jtIMBb-HoSK2k#AMT0jzncjgLsohG+)b*fr z_Y?`{-ozDP&m=?JlJ3_xkB>!5qHKyTFhL49sFaP62>ANgeeg2wQ!;wYl*P!zC4|U+ z8F$Iat=20}Ht3kM_ae9)AnufEN4Y}Q!Y%aHLGwu<*MnGXC(aQJVW3NvcQg&Bf;rM2 zXlCVo#|p%af_w1GW99q^{RNp*ttwWi#+^M%)kt|-1-n<~_bA(Gnooqz;pH~Sd-Vfw zY9vT1AD-A80UcUvEH)vqxM@khH<^(mQfC|zi zQm_m%S9qIT-A|Br3bMXVq5OBh+384-h0HCEml#g+vegs=0ym%EIYH78Hh#`B6OC)v`y02`PPU0hnt(T4DDeL<|&5fPB z_fdQ{VX}CyU@I%C!Cb07%!|FS`088#chYoIXtwMjol@2F)K6yRB&K7c2$S2wJ3phz zlPzp}Mq4|)6I-HH$5pW8WzULTd>CCBN7h{B=w8cm+qpFyd}Fn=RkpU~#`_AgUQ~?o zmT0*VD#V{>Dj)Y0Ki^^gj!DkM%EhgLgjHJhV^~Yje?QXy#UK{ImlhANfpry4zxb4k zoxE(3Wpic|AK8G5{tAQA4@U?ggYqDQQXRI<{pCPi@gRsrj?QpG;w2l!JonhdrklQ+ zo*J7CEm&(Z#9DJHI#92alvDrTtXB)V*cbhNw6!AVTx{$Aq^yy!Qw)?8H*7vI!q3v&&62sBhn-?+G% za4Rcc6??X0{}38mAk|d8F;ju3+5ri?m5h-P{i)+vX=gmh)>(J}x1f0;-Ew4`-Si@6 zqzq-3rSE&CQJm`Y=g-=Zy&>S!kce@|d5CR}J?)ic5kyt(K&z%1{hK#$(w`r0Rc*%0 zE8&eHt{ZW4t1HJXGqwIH_J2*Vdjh_`EZw2?)VQ$ULazVo@c;Rai8;EQA4FY5Kx!=+ zk`Nu>=iB;X9QxR~iv?A%na+|8W`YtvUoHaw?xz!I0F8h^TfTLS__LjS8ZIR(FqJ%D zK&8g=(Y+8so^TM7trNjC?cwLU{|&)};d1GYyo0b)uaSHD5>!;oAv$oo!#YWcgj&VI zFpP(4Lk<$1F~OplK1h0;i$rHFaMg>1;S72xAh_J(OQaHOl|5A*|2Mn|wg`6#7pEED8L~OR(EOwB|_8$j}Ne#Tmf% z(R>&i7iTgHRy%FlqgAhSLUeL+aw(WsE56X&xI+LoW5Mg5US>0tjbz)LIkxXG^S%Lz z5yY^1gyYj!^3jA3lI`|%j48-|ZQz`)Jnq%*(DA@VlKf5?k~&z#uZkIVY{f(2W6)f( z?+yXp1anO5&-8L=CCi{UI}YD{v0?B%~lSB5DU-2kU=+Sy?HE~sVl!nMT7oH(I}DaE1%1uRmuL6QGMy|han}`0#;HXc7LpBdw>m*Oh2wq4t6GEAR#EPyb zeSZK{nh>;OX&%w_1H|73csRL5VWw)BeMkbg)fXs~9RQ$P!o9WhY&Ur$|CRkZ%y4Q< zWoMqy$C(1vtyc&t1`O9UAO{v5G>4#=v^5|}VA=}sETeLJ-()~W$1VWyTM{7a=D>_! zY_*U(;rYJFTMBeGeS9A9*k+2)# zT>ZMPl-@sw;SL)Pfx6j9p8DPV1OV~MpqXk47vcLRzz*ude{B)`RxP$h=HiBUo?H2jnQYAXe|&{7+OW-i*M?>ej&#D{%jl8kC?s zw?0DG`q53$!=C5)ZmrV*v+9G->wR1qfN%=@$U5~17G}7vHQk0+b?8P_d$Elnp|H3E z!s-PmfiSdDghE)^B!B9Rd|X>5;)pxX?mqVaU~q1E%|2Em2OV=I$9MdS6qH>nBggs6 z8O|{DYCaGQiGy^Z1aYX4i7-6tz4DglMPicF@l0d$d?b~oJs14l30$+q_cOo^?2LU1 zr1pNGqd5X|+0|N9s?yF0rMr7P0FH}eR}|&aDX!Q9xX$fqxjaq?&{gS!RFo*)oO+AN z0-l>6oo@1Ws1GO6xeb=I)D+7O_SZF3R5ysJLtLTaqwIBQy&xt+qhA-%X8QD~w3~JG zullfqpsf*#SCa|A6}%2xNbT3p{7vDtx9UgBo*QCow4aZwDk1sb0WLd^mhIPjp9CuD zj`?=rjF{B;r>_Y~xDh3MrKlKx))FDEaVxRbU1b`t&*^gU84WdF z;&=Gdt%bmlnCCEq!zB*lyEQc32`VoocKuFU$x9@ko0`5nx-shK&b$X!d$o2^NwMp6 zL}w)V0F`|gF+$9*Xo&_d)IL<*U7M%A=G^wM`#~&Xu?bM+V7;?7C$bIE z(X_)rezxsAndwED>mx6^J`i+~lnUX*A1rj+CxC-cY%o?tfcJj>@LPBhKOr3NV>+cB z+cfQ%9!{7@uv=Ns%`QrQisWa!2}fcdBbPmuCeiS+QhPJLP^#+LuB$-sofS{HJFJ<^ zi3h7tK{3_+UOmXN0EWg)Sh+t#yz0$pH{}3A;Ox)DcPo2y3mEE#0k?9A`!b(!*NCE( zSsQ!s3c=NV3+U(On*~UR@>HW|RkpQh=di98hi@uE_sknjlAtTPV(0;-$(pFSGTYgX z@FmpXv(UZh5`#OUlaQj?o)b4k+cKeMsS=fbzLt()iGN8(jwOwlu=al(vF?%+TFm$~ z0ixa+A1D_*v5xx2U-N3__Md}@$n)#@jHm=r*=}sv#XJ(D2hko6N=CW6 zS*VO&itfDN1=T7=+Mpv;AcFK+~ZQ(H02WLajN&j$fn!=lY2GII=|?WqYp zRpnL8Zq#DJIX4xC{5*)N(rkbYGXmt642~Ftici(4Rn?c zbvI}OF{9|bEiN=A@uS+@9)p{JnF4z%LRcbo!1cBt-HCzdK(nPmxe+_ z{L6vTI=jHH#w&(r_}(eg9#fafi-nwx z=Tf!-#3Li$+=XZnlSa9=a=7>LkI))Pbk789tM2p#*FC6FrfS8o1cP{2qWN}oMqrO_ zn*`=lAJRx%_VKjKe4d=Z4uHZnS@c*ou4XOzt>c_41cGy5l{ky>`H#} z?~j?MnAR`xQK?C>GXG>!k;8}|U++rlu>tF%>ptLhhafG|SNPE}T=2&~x z&M;sdjL4IZ&lx*C#^^3r%M6KQ3szt1-%ZUY?i-Fb+${KK^e1R3f~+3FNJaprbM%}AH5l#~Jms}+g!UEHbWSO?29 zj1*6;nhk-QRxH(QC%Vp{#eVYTboh!FaReX2LcDU;|GU+ebj7J?m$>>?qItyL+8I-^ zT-yUl*+(kEeDZ4F$PYRnU3Eiy+u^NoL|MhajnAPYfvybl#f)woT=F*y`!hQKaRV1i z`TxM~G2WI`pbp%-R^TDq;ipk9Qsj+WewU+aa4Jaq!U?J!S)yFcTO z6Fp2u;qs0?OV~{zB%n}K49GJAw$Z(i7MQ-;17&g4R!9d{K5bnW{R_1nc0AzaOWL^o zF%dt+tJ!G{wWE$hN&eg{!U*4> z_#H1hnlPTWOIv0b_OWEV09lC24Hxmej<@YYSelhQcZ-1WBI9##=tV$Mgs@|@sOin6#uOkQ!?&$HaPRg!%W*Xh z0qwtzdO4KK*wV}-s*_??wYZWjv07SlO3$gM{2&`CU89Vh1pDqhJ>;`YBB^qu`A$-k zwU!`l?;6fqhA}rrkNOzDe(G(w^BTwvwGhD%+q{Toh}67_vcoYFys~=3(JG&uSUN2C zF`W7|o#H2>n7oc|SZ3Yq7Zkd?@$t{0e-R}kX|u~$RsOb}^IRy0fY;Ej;K6{OG1ANx zR8vtE;XR+v%WiG5Uw4e7!HMIaGckKfEuSO6U=77^d&~sxoyxs{rE@>p3KXmz)4FwK zP;_?p&r25o1FMU6?R*j?UE+D|eCRq6dLJQ^4;>^W5o-{7RVnd?@+Tk5Lv^9V4(qf6 zNW3Q?;VR?B&w9`Ia4-@bC|Q#+bHUm_?#ZSeaR6PY^lZ^9HGGNPwhSqKx>xqm_L63h z7h6pSy2>l?2c&vfjlCQ679#^29D`A?q2MXRvFNQ?t)q{ssF#w^N8Qc3=3MtlLemFz zYjm|Tx?@1zjYac~BaZdn*Q8%89hwmw6^*@$fq{WSw5Jp-3O`0Q#wTJb%dMJg`cISp zU@cd=OrPFyoo6j;AVTtcpYHj6HG##?43C2{j9J=(D&$y|LIPU2dUoFxLN<2VuG?5N z-LLb+`Tdk0eGKya1Mw7zEKU28uEifrc3EL@q_@!uXWY^SZj@Ne#yOH2nxf8$u1`>o zbJsp70pFKBs8Ej`XrR}9L4{^+W$H*)5;>qA=q&RqfBM`%iV&u!Zo(@oJ$r{)R=t{7 zg-ZW&k~6+ZKK2T-TP6pLZV;MD%IT_yBTlhV%`OO-R@wsH^nZQ$kmOw7;d;XDfR+T7 z%yN_;kG%%@ctGs~#OtQFE7UU&v{px;$R(z!^PSzPO@q;)=8B87P7rZM&_O5h zOHU6LOL9iz8=N00%T}#p{ z1XE1n;jw#ov8Gw{)2*7CO+X|{uFk9E;M%C5&p8otNwO(ArT1Kz#2*ge4TOFx{X18m z8%eetC5GHdw6QZ(+|%rSb8|Asn14bZFj)KWD>JVPiJ=)CrvmY3ds`al!}{H;HC`M?fvy_Uojp<9z3u8HNJGMeZ9%=jyz8 z$R;>5Zv<4NcLd%Ju=~|}!t*8Mt&Scp#0?%WNfdNs?152FN3`o>x<#(MzKr5;m=(`N zx{pJhon@t0(ys|q&Yw@KS!qGYONq@>KQ;GI&)ukTaOuNnQ5{FIe& z&Pfa-L_XzUc+Bmg!3*OCloByQO7K57a?p_=~35!?w`HvxFYi7}3>LRTnY zJ?iYAwX6c0nwpwX@zRmH`z=ZaKR`ini(yv%&zzm|Hql`N(y6_*x-~`nz3tVd4Cb&h zlL~Xm5L(CBe+u8kk1hCzvE*~U3t#rXi*8kbDd$3EjbVeNXX4>;4F7PIPtQYI_}au&V=o zZ|cKe0KY6P0u?SvQ{;&=;iTlz`R;B}zu^#nnSR^P$sNp^-icrfBW-~`n0C-T*I6Ea z8oDapB>-LeMQv+c)DbCXfG}0AbdkDbM~ICp9oP=uhBfP_m6 zr-nVkt%dxC9+}GJ{-4drgOtLtV4~^B|9NB*H(uTLh-^3@#=!pZq51oXN@}?PAE9}x zDUq)OK<0qF2+^a#6wzbD^>WehKJb4?k&naaVJqG3pm0M201aiNFWA37j#3H#Lmu+b W{jQt(cSTT*Lg{GepRZK2jrbqPn5fAB literal 0 HcmV?d00001 diff --git a/imgs/operation_mode_split.png b/imgs/operation_mode_split.png new file mode 100644 index 0000000000000000000000000000000000000000..32b1719800f1beb8088abb6bf75396708fdde301 GIT binary patch literal 75550 zcmeFZ2V9fcnm-N*N|BDBbOl6^-b)Y=qzQzk6e&^y1PGx72%r=zMT!CzkRTvc0YQpV z#1f>ah*Sju4ZRzR6e<7nQf8dFGk5Opy}Q4=`(HnqF*)yfPkH+DJnw^@2 zgoIXCN7ICagbWV;yFj@cv@{f}kdu%|zQLTZz@V_sNDl;wfV9TeHvuULSF|riKw48k zO3L2LOUwyr@8V;R@)h$$U_cXijzT*joskHqtv*r`QqrOl@}g35W)g}5(&|zY;D0g- zVzM#{R$Kk;T@aqz0~(-%kRBfP0#aJCViI7eBNmd90@BC9w^I&&o*2Ka@A^njKP+g& zD#+Q%$!xXx_=903B^1RZguoMRgrhqej3Ol=DFHr`ph*kqgK$QJ*R&)hHwTB7ion>r zY%Np4*+J$M!Vx8X66@_?=wsoh2shhWogMy`7HC^ti2f4G^IyQH*%o}`?D z*6&B#854!o_ObVJH9$KdJiri6*sUcGj)2N3^FW!f~5n+auch_@D!R+szs6vAw(PK3-ts zzZo5BFm<#CgxeIRpSqbNoiMIjtqQW+%Y%CBAdoJuJ2L~$Zmkk!ztefU!PnK^2_3NY z{$|t9T-l=I4mEwyXfWPSO#AuqPA3#r1K|M?dxwtO^8i`;kH7oNHhq4P`hR9Pb4dfc zlM1o{PKu}PPH1_`!qq*zM5VU~<8SZbw@q9vdrv<{u!HT{eKCPMWcLj~qCD(9LBHbx zu1E~R)XUxxdMN-%8EA9Gpgh2@EiHt^#LNEIg>R1rGz5d#kwa+ezfaI#$*PS&qYxOM zKrrmi>k{%i>a{J#(%aMt_*Et(ciLQkk_TxC1+ndY+iy#v%P+(KV@vvVVJ1Mp?L9Yj zdS_*d+w1uAW$pC%?W(p|v9lz54-CS`(;kC3j`s6(^4)s)*K)M8GSCy~|IW7lKAEL8 zHhXW1?qBu%8wq!m)Yd~uy7?GjrB#-JgwwDNzX5=eW{5x6D?w2wUo>5mZg zL4!Srd3gf=0sPbNHRJE9<-bl{q~y1z-WEzpMKMWPiJ$&#yM&)~M}E8MXCal8krvzb z6+3eJv+6*?_t%CF^x2l8|FE$AA+fd>^!J1f;pwCfIUc}dM-O{nU!)`8g)he52lKbh zKiRQOLE8*ZATjxm@ebki8z=Vnx4NUXKdG#g#814~acw{IVyDdq;jt-aU~gcB+lKa! zxbu%J;n#&2p^=cN?-(^X88HQ!pX6oRfc_#*Qev{(!OqUqzGy!mN5u9pkktRRY;4W` z=WE!WVP{e~NQk$%vNI`QsS5)0pO|#p2L5+g%s&+39S8ZVBNmX7+cawq;EM}n-%KDo z0_dm#%#aVTFbJQWE`YMX^xA22fSzu?x6|T;^xtVR5tWue0)dt=Kzbs*`v1n<{>QZDUl<@jVg!lZjmgZlMkT#H@d>kWG5WI&HILCpi0w1^*YYZH2ji-&X%q0oxy%pKV|N zlTiJwEd5`=w&`L2kbXN#`F{c1Z}Z|Nnj*#yH=09*S5EcLhS{fnIHPkHn&%$6ko z22KUp{?^2Q6`sp&_xtxrktDY>p}%3o-)2bvc8vIalJq~B4gVXm3M5L*G0*|w;{|N6 zm=id<(?UYH?-pzgFyEbLpbaRxl!UaTw2XwTB7n-IB_yH0mu-G4uvL+ZZ^*9DNiPoM>GU=rX!N&5KaPs?rhxcNg9I&y*# z;H_T}b^jO-{zpCHj(z&)J>pNC-C_3sJB(ObVOy|v(%$D!L(%E z={G09AXUF80t#EGSF@-Mv7`iRdqHZTA#)@v#rw=_V>8=H&~jP_&#; zP<0w83K6yU@NxxpjB@rU0PGz1@^!R_jL0USv(xD7xCPhj{01Q&=prKlHn#m5hyy{3 zoE$LO+b!PE;j!js>6->nrR`Q9gfCPN2%Z3b`*{62fbUk7-{uG!KacF_>f;MlNjdvL zn9*@(52V*=@DuX$(03hZ67c=M1EY|Y`K?Wmm6a7!RQv;w0-W@2hXFqa!wNEDJ4noq z5&3_An!96jeo{>hBU6AG>G(lM`dbwMKH%HtQ9dY+5;a6%0?zt82MYy$!xd%%r;4h?Z$s2rUAVHpPx_KA@}=VjOhMZ zpuQP$LpkiPG56-LouK<4j5D^j^q)e4w_g3r(0m6U{pUlKe{&#M`acF;c%nCpYX2;{ z{4GTJr)>J?srqjPCP*p#)?&!*;2S$;;9nmA{(j1x3Zk7E|Bd3m%?gk|DM{ZcW&5@G z|L1Cw&8Iup4YnR^zW`m|*eb}@Dc3V5A>k#_)l@gb+D@kK2|HESQBU6!FxHwy&H9M% z=8=fk>@2eEBI=G5`!Xe&f+O))LL}KKVj{FY9N8^v{K2)|f{fjLufLiRDFw3i=G0`s z`^mnA;>qdYfWD^z)1Q~^9)B9Dxg+fxI`TGUBjt{ATYhI1B^zZJ$<9Yji`+^bhQL!r zs*#Xyf7BSmu*Z3S>O(@t04F_rP-y2R5=u4L!QH>Uz)M0Jkwfw*o@HkQ5^`P~!!BMD zvh5E;7zy5##6pL9rvVx*bB|7f z7g^D>mHd6hXJ1_)@@y>C&v&~Q3BVk@g2yPoxg4!HY7OQf9%itB5i77Elff@9Q4ya> zw~LvP$<>9^5*n{4U12wpD5T`2W1!?cyN5JFPd^qFe z5f*YX<}fVvwY>*!hZztWcgLl-mA*LnwTsc4;h1A02^kZhD*q8B*IfkN&aqJ$L}0fY zt@qgnBSz>hu(_wh-swNebYb@0h7Ds9%u0ZYEsU8Y3=9Y3u|&-411>EW>5o03c=({` zS#n|RdJtp8C-$cs>p$}BYC|yJUhHvk7cNX;*<& zS=9GWE>>nL@(I`#6!s8!yx(xfi8}x-T*X~ zmLOF9t-dr>}CIE~XlH4ecdXs= zEV05VLhx%t`P;h&soCNCCKda&@3BaaRp@`&1X zG%Vu=F9Q?co2g@nNW}W``%shmSS}%X`CHS^et53TrETbgUGt>+bz17drpmf(=bM#h zj0_B7^yFPzc!PdSRh(ggSNC1W`HBmkR+ROr<1<;6kJBWw93OC>{`}OeDY8LxWc3Jz< z7M!VwUHLwBQpCxmt}WL%bCg)mW3Jv>6@VV^t5L4`FQ zKkg*w5BOcF#(gM%ldbS5Ms%Ep><0PWeQ=R;7H_{@@Z|0uK`PslH20gmS6Q?ch)U)N zRGNM=(7tj6$NGid!#1(WUBm+RE=3+Lsz2gqoP!Gz?hTqKFtf2SsAi37Q-kSVK|7aw zjK+K9Iw}#JDh+Cu2+?k9yhVzub>bl(7&uqWc;Qt&UY}U@$bHk~Qs)&RYmO4!9n|aB zmG^ZGrxKiREXXZMs3TOnRtpg4KWOvhT^KU++{=kmU8)sJ;RCkAe2PwAHndHSy6Z3ZTy#h)3$-*kJa!#;fxXlEp^ zUWn{#&_yvY$W6^K4?c^R+fRyDm#`f($!yctZircA+~c`)AONWfEaQ*!u7h;EIH%&w zw!|Ui16h1{0ZyaFhL40em|TB(y6Z6U5>okK&MW;2w0p#^Gb&eusROP70pMi{48rCdq|>Ca0)? z)d#54jC;xh_b&J)fo(j%y`Oz{5LZI}@rbgLfhDfoN`v#`xMF*cEO5_-f!3oTC?@#r za%LZ;x0eh_2tpYA5fXAu;AbgZnN@ zkaO3l%;j(^H#+aLc>_kM5%5HD#ODr2IdTwCTq;C+#-|rU)3nK><|zUO^Heu{9&S###JW`uHNX`(V6|; z3@W~flw?ZaDJJ(IJ+7QNmK2lxQcYC$s=}jo@7!`<@Z_%V)3>xeGP6M14y3)(TLMkL zWj-WrUi3-^9Mvo#T#S3ZN^4Q^@~V>%bT4FFlmh~s8f$2JGpC@FVNZDw-GYA%AhtU< zTcuqJo;iE!(p@^~bjZ_lNm7%LG6Gs3+TSbfkbo^o*CuJsOH!v!oignYIX`-NB<hA`!YF1ZA<_*i`qxMicClNJ=Ts^Xwadl2WuwQt0b8Ku|RC2AS% z%c-eNDiE%=O2rSnMQNKDp66JK9BMWsVWsCsr~nSjGH!k=F5NrFh9$Jf!boG22=lwB zQF>{qhK3P>Ty71!$UZRZT*I=p|BV^DARM>a7J&buFn&L=w8yi`7=e&2uzq@%nwmP% zg79V|z~25~8M+@gJ3H(8cE&J0jb0_SJ8+}(sou$xrw)j`wXOktQ{k!K+*bV^i)cqq zClmC2QqnF;ek~B&IoXN$jknjOXuz+v2P8kMc z-fs@G;Z5b{bC!) z#xCb!w=($(p1bg@LuTlupzBn!teKIS&eNw)&EoA^4h7ntJax*ZBR;$PjP@xIDs)<$ z3POAz|8!L8{QxEA2JG z^k_U%;8d`K%Yyem z^NP{x>Fy`qd_%)S`L&h`9cJdi4*7;^Wym(I7_Fy1>afNjrC1<-i4WtXi&^Ux8t(V$ z>>?{<1R~JwU7wmX)6^u_dWCj^W3{2p4~FW>f%B9ZMrz-#^cy>_95<=$!WDF#NvE!F z)XcCZEI+T%IB){@@d2|TKq|-4+%E{L=Z3zSp6}CPtF0$QYS%2SO_ldFNA54#jE=?m zKV;88K_t)+ggAm4XvjW5(>gfypeim3#?PvJHI+ZVxVHGfb)q2HWTI2Rt-YbvU-c>5 zzEa`r=(uOb1&$8Jb%c60-Mg_H1zPv2c{b3jW+FHcMY7L+3+`CRgv0zQ^8A^nti=a2 zd>!WnK5cp?f|Yh@o@>u(>j7RX>Law|1URoTA<{d|d$zIEXUfWIMupMb%uMq#PQj`o zLjC*sR_%Wsiw%Qd4eI1x0poF=Eq>%v1LBPRW$3#>YGvG z>t_ls&yw#G7aox{{xMktUsXv%07Zptd+=RlgHj<&y9y`KW^V>AibQfqOB9Is2Jxyv zhZTP!lhxPA-1Y};eXE+*qA`l!n1scIPG<yC!QAgbc~wVdiF90os#vVX?P%;4~>?JbbMt`gz2N!y1K z4!&~7A`IJfiK#U#ERZac1%7QIK;Bx{?%`Tu=eweGxvGu=yZi;s_XmE&p+BZYRMkpD2h=k@b5D|kMGiOxdPiR8+FnZg^(ZGkYWy3kvUXipITWD+(tV^Dk)P7U!BCh_}7i(}9XK8bzU>JDiL$ z2|V<+zdQ`}h+#nJMLDXw6=W9-8%J7l58@Mcm$H_8Y(-`mG_KSX%bp?dT2nuwgDCDw zoPTkb-t~idG<)?I^p&w9^V$Bh*UjF++dF6;v({~%>hC++yYFiou zX>Wq;{5}=G6--iOJ^Ss|zU4Mw5ihJ=&Tiwu7==7zLEAaA+Q#9MncDl)TouMedAsH; z)H>o$=ZR8}Yv-+gILdl@^;}x=?)i|pJ+RvEFHse(MCK6fp81|DN`B+~Q_7j&At!P! zr6N5x1cfAWr$EC)G@c+UVH6fRpzs=EZ=Ux>`M$M zk=sDz(vm~E=>XNCvKQ(#VGbV#Yx^a#a#*i*QAw5|NL7*MY3s{5X&ITJa{1FLelq&0 zVJjn-+(+*#AAYcwwu*eE#vO%p0MSrAaKkOxPUq9y-jyp*#*vF$1mTpzLEJgE>e;5F zrF}i+_mTw9tqN7DEOH+2t?CdZfd{Azq`G%iKCy_*@Co$}Y#KGg2_|FbBSW!n@fG4< z`e#;0R57FQkmEJMi`lV#idfwzV57IoX~YR&rccLVjkA|z87QN}ObNPVhvJUctc*W! zE5;@XX0+FFxCPa&UKd^Ov16;_xw5)gYa4n!#Q!Z-d)b+;Yjw$*=UIT2h=R->gafVoF!xT8GNW?^70b@OA;YSipKjP~T;hiJ5<7RV&iB4V z54ZL_?#uBW!D-u657-CIkEUDtz)FBMT_H_9Y0UhtP5$yvZw8lER9iO&z6ZBBbRr@CKJC0g*9&XdrMb<0Fgxd)p8 zv9qIq&KR;Mu>wI^bYed3Hlp}?q8tU0h2JEemHaIeP~;n`@P6W+^((X-iD9#8%>$Q* zR;NC0s14>RZ&+8))Y=&UAI#-9+M>>7;V}SwUCGy;YFfW*!iHzuOhuAc-yst^vw3kD zQ4)!}$UcGXH{sGtz5!^ZBMoJ46L3Fz!wDx(mNawz%y9DuyA6D%vH0qQWxlnY`asC? z(X#l@{TKCemC{qfu{TcaC6)@j&+cYXO?-hm8i}GN=$0G2V5hvK3j(ruG1Wl)gk(Eq zqTs#NSC>o!ghmMG(&v}WeO+g476onVCEeHGV1^k7$laL>g*HQzmob+m3gkUa*ZbUb zJxm$k_F7CH7sEtAtZ9iG*M+efRc|CD+kTt;@#8o#f*C$UoOl*S=(4KtG!TEb5#VOt zdR;3HX3C}X_JVNpEdzp3Gv`{R{a{|8cviVkC{H9+($3kKRsd%GV2W{LZ1rl0|*Q zP9Y0dJi@~vy^#WU{VxCBRM#-L(xW|wR{J^LPyOj8_Ydq2#5cBNmy^>GS-crC6c}3g zNr;K0Pi9m;m|0A6&7U#S*_X7BR&g~aBw3m`tvr*D+KX+E6hBseVy#g1Ox(t>u?Vg* zMe2vv%o#8-M>UxJ@}3kx&u#S@mSx<%EsF z)C~YY7%VSp<`;Y?H?1l2e zcn4mGU*cuZfTp`!;_<2E3Prz2)RM$mRyo-C{c?U+0^#wDLQL(=v4J>M&yR{9H@pT_ z+*Ws8+a&_`RRSQTP?YqTnza|)@5atdo>p7(4 z|7h;W|MWfy8^~BjN?HNZo-E=9p)R`P6XrypsZVuCWEb+=5KU(Lq)74-LFSnR;X@Vx z9rd^lzb*QaX}Er5AB`Z|ZrA$9`=@bXN;A(NOq3s4v~?i8X%`Q-Q3{Ccbxwvznf&A= z6w}W!j+t`8^~}M5y%}{fDv9fvMPhM* zZB0O$SBq}zo z`axm-=?jgu7DtF?y{}ti{OXIbZJw)Erx2+YD-*${$f;@*;qhA|pDc=Om60=Z?WOl> zBM5U=(R zJ&$gP_c@2LMbF73t0L-^BOiO2{7?)$)RdM#*L7lsBdH)(ttHq;`b2~Q7HufSExggs3^XsB!zgC z%A?&NRSLtpg)h6LozKRbj<@+e^CI*Q?Hh8_jHFmA(d}Nu6tjKRxyYR`yFJ1DUpLMi3y*1~rU(eRuBrJjXn5*gjz$my(#$n!j za1ufug}>c7A_WNBv+au&Xt+bY6{0yn5|X!|X=eE}DD`rpY6jlfQh&J(z3!T*sx;I? z)K0_lz2k(tE?31pZgKdbah2|rUqlZu|4|%O+2aFE5xcrs04b*!{m8>H5aW2~hi=*B zb3M0gd9?JEC-e=ez|HCt{jf^Bdz$c3;f`EJ8g9e)wQDu^o;c1ghPdS?I907*xwG!d z0@+=@IG9u_eM~hykw3b3lUfer>sLy3-A&J-e(x z-9B;?Y(R{*Q{G57upbnU~4gRp9)lE?|$R=H#yZ59;903SPWkb)8)4%ArM_RG7~?h15Kr(&_|Y}(B^w%8occ+1N4#P5B<=&~oD zliq+#@*>=N6qwXj?F<_4cpRBY7=QxQV6p?56f~^4qGZ??PgKv3h*O$#*mTZ_HMa#! zbQR=)!w7}-KGugIVCL0-pGX54u9e%~2kBZ()u=&)4#??z4iBf;w{M>;OmYMSL8V+9 zk6Z~S2-TgD@+Gjrcn!h~>IFMEN0C4YjxLGlryFEl-9t>oF@pIy0oWuva5?MbEjbu+ zWM(&RrN{0E9^Or?6ubtjJ9syx@Zu&^`?m9ytLYe3CBvREAzrZOG-%Jqte*O0brVw- zZ3t_(R(*%DO|fhdb7*dF!mbO8;1~p?1SfA9@ImN`S!x0G4J>T6!*yhngfi)OKrQ*HQBN`Tdq|j)F4jdiygQ;Dy9&HkIQ}oIY60IS?}(5WG*eCDq?Z z#68}93Z;%L!h-D;?vo|#^d=HonF%Jg1j>EoCKwoQ&el4Hqc~52c3}Yz$RkJPN?Kt&? zy>G#ABtimIcvA^m9a^$%peFdKv(;b$`rx!WUvQ%_C(Wp$us0D) zxJ+2T;LVLBL~pz!M0Tm5K0YBOj0M!1UTD2?9;Yu`$UAhn7$5@FOr(Cug#CM72=VUO zqG(MVRy?`9x=%>8Ke)0ms(Pxfqk$RlHhM9L5KX}XBz0`8s|?EM|NarS_>gL4Z}>?^NtiwXd%){dU}Y!}Vqif&=-5 zZkJF$vsIz(mbOHil;%+kJ`dcf1^Dv$Ant;+1|5S0fRr0En|Wr>-Q=PXT>pv$w9Wq> zvShOHJ!Cc0QVzKAs_DuHRH1d*`cQ-doj&blI_GMt?z$E)hxERuP5N}pB*Az@t)Ikq zm$@&#a`2uhWA8Jl4#|)0`o09|FCBsE%sw6Ysr!ClFF}kqN)=i%!>oB3LP2~Z#0LlL z&l#SrMk?V-<`(@4U=e|YMTj|7ug6f-3J*5{Xq$N+&GiOmAR6Bp;4iQTWhrkT`cjQ` zFfI*RaFZR!-?9>EuC4iS*!IW$SXZLh`nyc{xx!wsAY?=Q!R&La(LMmsC?>g?&7=#3 z=kt7Gy59HTq>AdmqTXeL&yBp#DNypCry~=)_ZfyReiFb*V|R}KpcfSH;v2Zf?6W9oa$Xt0H%08 z@+nZeWN>ICFVh@*)w`@sA?`RaA)qgpc_T#|_w2{Ca)e;CTx02`MYf2cHX(n14xGe@a-V8VWPl*YM05KO%Ir99I|ECWcU=^`pkAat= z9B<8I9twOZRLg5O#XTK&Ofp0ux%#@`M%Y>Ii%koiTEqnZwUveFW(`SEDp1fMsmlO& zHT_ht$wc4{rhWuUDg?hg#9CEjCCiA}lS{m3xlyxS%ESm$Lopue$*Gw^q3pY-703Il zbMI>7mKNmtNM9D(ZSjk_01V`N1t1CsMZ(lr$nS!)>ZRbisC{N;X7{rvY zK|8J01|~cNpDJt0JEK3%!#^o5hW5BP*G?tf>Fjrg=bN|qIh(`)Mg!60#fiq`wFI{oz6`F6O)Gixey;OaV5WW^Tbx3NM}ChVY=Ka^ zUdmnD9Q`h^*rUtShC?f3$&b|#b|_1$qFPAR?=6jL%?MQD7N)I zjNOTQ9U}w}#6BVekd&7RtRTOCzjS}k{)8@>;z!7Ff>70X^7!HYqYdIl$KPzMwUi=d zRzS@{dw;fpABRUiQWc&^tgE_ZPE5{QLD4VC_BGxuny9ixr-lLS{c>*v|71@e@MXH1 zq`2~gbjqW=497@E@NE|;XmZd0_?|dH#nH!^pdF5ticuC19gn$8kG|1(qsi`v*)%HF za*%7_U;?u(z zH|BRMuxGA>uJd2#>8+7-rLQ z2SOhkg!Hr7Jd>EKyPbAZJIw;-y&|M+5RRoTF8KJTL)UEdFD98U2`Sr(G)KQYUz|8D zX1Dq+c-^1;S;K4_agWWoOzMV`IRD6b+-miD1WRpE_5|$f;0S_f1~P>!^gP@fuDW^Y z1~jiFQEZ;BfElYFz5p2PI}_gYNip>VFYk%xibR>i#+QNUjvTDZg5Y2!0r{SSLqvoGKLQ29G>vg7npw zFlM*0!Uig9gh}!Bh2J`OGpcJjW)|=c^*nb7#`*2&tJN{#-7`W9v!_!YESUAJ8?CC3 z(&V($pJ=W>9-YQcaPO`3V}KLUN7Fl7pc(YUWISSbDN;Xzj$6Lm#R`jy=XBYH+7tv5 zjCpJa5`*?(gH?$Wr;<*&_1<7Q-8Ve|qpk~9j5vL+vU&6b`)8HnOd8>YzH{J)ZErQ8^xA@bKV-Bjb%Cu@!ryrMYw$%P}k z&qu|0VCEIRHjtKy<|wPY$hC8%3%&VSrG8zuwC+h!H7aRM)ir6WLNHc)k^Ch=als<{ z_eaFU{pNK=rHaya4DV)%c7^OA6zV7l;XaDKe|xvF zCSMR!ePUqY4D-_Qoa&5>>E~zr)Y??z3PUnaf}B2-@u?NxkOAqe87~dML@O6ad-PLR z2Be<{eII}N>2>nCj}o1*%Uu@RWi0d{mE%iXU*pHCuT*JLGdxOzT#C&iIIlTM+7T77 zF|3k|rOyc}#uv$3ud+wytaL3^h{s!Ci?Ptj6^Q!OmdTF#wO_P5Dk^$vhB%s7`;Iiu zD+wh65Yu8&0M2PXiP6tAK-9Angp@-XXvvHjy{ur%@j2^5V&mQAUCwWhJ~*0No!{Qm z#G9r^-7Qz0bBT3^-L}@!`MP|oS!<=H!2)rVnTPD{g(fy5*!bYaR8gQw{p0o-Dci3x zJ_Q!fE@)lb&zSW7MAM5l|3mvjBaXt&eq`P)x%tjQBc*kKj(ESG7DQ%lAiyGx6t}5N zl=JwkmKL&_*VLG42+}*#ded(&eHK{k)^1Ydxu>o=tkT`6kjz!qDC$)1BhV;)|2RO_ ziTCgU8QZ#8K(cx_OQT)Bz`vhY3rr5Nmwc!+WejTBjKGA9hzmX*(JYp;uN)1m%)xT^! zbMIN+Yh{}EJt$64^q@dW5VDS7JQGk1P`4ADPDkj-OL)P)C}64+XVA4-%_RfZ1##sk z_Zh-eM#S0SDlE4zGe;k>tt}4fa8m*x0l6DfDwTduW6A4=wqckJgy)x_po0;8KzlOG z^2NUXiO9=LJnvqbkFOi9&!^Vv9)@=j9lW^%tt$MvxG*j1WU`UXmjI5hB)lS^4nqmy zlHE-6=>x)cm~PCa{=5z#h^O!o!Ql>s(0*Ojds4^lu3o~H`Pf~`aQ#pM~<1@ z?t;~S7Lqf&)tp7^=Cg4p5oDC;Kcd`Ad*x@~bVb_Q12s5J!b_ z8hZ3iZK_{5H}zK!=Ve^-saZUl=Ml}+Q#!66U^D+n%^*V>1R*cm{6ExPHq#Y@ju!Gp z!?_qJ0g{nGGVu6tY(`UeOdpQC@0meTp9ArNRZ}C{<71EI-6$2}V3s5Dluc1_wVm=1 zZO$99%H#JAf4BqH;7H^|^*x+$UPk`Z_3oP0l>|Z4u0k6Mh!;R) zI~m|9a~O!DjpafXyTTPyulBS+Gra-*6iL?6V^z#0>^pB8|W zyIhYd&){JeEWKtS7_qpX zQ^O9Rf9^Fo!@|N%9o&ZN<>b|Y&Im-7(vMiX5ysu?@~T4kqNK#q^k-`;Ei~^{#f=h1 z^}*p{MrMW`lNL_SWyAqMbggJrkVqHj%{Yf%*3RX7k9W1%SYSiNFUy<=}1P=Oh!b7! z&1wV_t|LSiHK$eye{IiN7pn5)Qf@8P=6P2l_W=QLOav`)eiz&vVxC9J1#rZg0H8Ql z%zK3aOwjjFBd((%Ka8JNl;=HscrCvM`4qr7!I|*t>&$`fcdHAiVCr?|2*l;ZKC6WQ zP-t5tYfPaB^IN>cJksy~#UJyEmick6F~)Msu!)J4hzi-HI9$Jzl9JG{Y2fC!4V(~7 zXFX2dz00{yI0cWI4wiO6<{=YN6@uvH$&z#dGgBO?`-Po>c-D=djmw86;-?T{eo;nbK))$O~0~-r~9sd8~a?5|Z_z&2h-K77i!pGe+_x?4t z`G86nKB(~Rpq`_)iQ1v{5f?}AWNI?B02(9Bcvh@NSt>;6 zud@|>LD4=wKCYk)y|W?pnuuHsbnv(?X>Mz42!|2Lxk6WoW)>FvH>d&l7m*YH{G|vb zB`{yDB;Dy6dlpDHdIS2AgN9nH5O##OnUR^P-3U?ISe+XS-@|<`!BDAj_pQq&+Fb*@ zEV&ZYWCuY-DK#Z1g3FT$S;giT6lAGxEWgLRq!J`AjlVVsm>z{e*jn{vfXMwzE2@RuqXAXNHN=7+jEVHg&3VO5WZ1~yuA=60Zs=<)Mh}fdgbcun~tk6yH)j# zZ?EXvyz9Bxp6f~7fNoc8hO8FXdkSr;uE^CPKw*9~tGF%aY476l2_H^;w`49Sr3@&p zW#Q$AE)a0Yd3+Snp6RPWe#kgM`jDSb2tcnqHd8W!aGbumZQzhIA+k0RHrv2A59-&= zSW756tz&l4SYH&r@Z1^fOKNX~^7Ipp^9>_IL&m_C=2liFyScfw)5E1X&(D82V5O%e zwROzK;S0*UPNQ=3^P@mfy4r=j_l8y+#Bu*4qEZ>PrcxR#XPwE zz#OMQbYH#10GED?Q&HA9*{I_TFo^Ic(W%2AeKA)WN;DnKe^6*bZ|{||0syhGk~d1}g#B=5sc5n}FgbPt%t&qe2_8*WvERUauX#2#m)S zp3sE{c6r7*G-6NG_yVL#fD;AC!p7}0H9=)=rVmaRM1>+Wz@d+6gqJ-#IXQ6r$mfH3 zmFgFFe-IB{J{j}5vEi3OSbMGMrlg~%Qa~O0iQ9GfzVZoghTuKv7kG^z$IizBO08i~ zy{hZyC*JH&6RuN03oQ&tesfFQ9Mv>r^FuMiI&Rme(-iK!4BWt2(3X$jg2iaLVYizV zM>w~qdRc0->gf5Y1d(qbYEvn*o>(exF_Qy*v7KEZ2kU z$_Ff=!Y77+nzq55$tMO+&&kke;XGXPa``CRq3D*EX({jC0cq!4=KkoYs6^Lpa7^p^ z_O|3WmbEW#7+gpxX7>pg0#1LSG@5_}N5|v39elA0$0HAef)j6T__1aF7*55KuSl3> zH?eHkffL`wk$Zqr25edA)#w-BNvz6lH2is-DLtn`eBb#+o1o!4E~D`pbm`FMwgm!g z3g$Q+DTuoV&ah)v7AA7O2N5#k3ah4-{F))qHR%ySrQN!c7iT>yH{Ib3BD(`YakW%w zLF0Kq-wv1U@X6d&ZkX;K!T96XgKiUa9@}lxG;iEycMUm z0&b8Pf@>?T`%k>?&VJy{;GT2Ohqnb(b?1=SzW{z(j&FfoC8$*C>YFkez@>pg|K#d3 z8)G?Xh8*&q9wb)Q*7`JTV)v(etKJ+hf1don`)s(o(Ful+(2cLKurCAr;D*iHEA&CO z8~Cea;Ch@uSdtU}=4B_bKFRvb@;vybH3D1hy{p_oNBWZJ^85h{!!KJhFn}D0g~2tB zTP1?$!Ekh!J8bF8#cgxbxSIe{r?wopIlX=2&71iYglcTHX^x@X6NBnlvHEZY{r%+O z3_wCDF1<0uRM#@6k-a~Z?^quTy|1`w9A;z!qhfg)6b7zIx2HcZv@NU;e-KiCz6VN` zUb(;w>f?-|6MaZH>oz0QrFzby^Mo;_W7$~-DRRUjFCE!SzuGiG`+J4AA8*rH+uWgN z@cbb<{Z{Qyyzz>Fl;9W&K@H^ilh=R!Rfd1Uw_c0R(M>qaxbcNL?KuUTwc0A5Hz=4e zT77W^lk;@#d(WHG44ugW5};l~QmNIO_q61GGE%_lFmIxa{Y&W1Uy?-*-G-dO+1bIy z(vH(-80T(6HF#o%J>G(_fN5(g^H*9lwB$@|WzWki~o`@pEKE zG4;x}#Bw%t(6F1}JIijIqSTQCkQ%90)GQ7#Hi@aZk9 z-=1&<;8LR=2ar!3hT5q5##yt0^SM891SPJ&@zLW<^5asKlusGcybLZt(Y(LMp6$I~ z7h9_G;>>02Eag3BI_Zp%N1|X>TNxH3YRV@-dKwwiPDXPfgY7Fx+x+cY{d&qvKVB~% zDG%^k+_Ysm-#)%>DuLSAj#}&%=Icf3^+<=|qYh;$p6q!{c1W0tj1}Y)B`rv$Q#V(b&D;pq#bsa^#~`STvY?pU3ZO#dcDN#%AR_8f1(@(ZTLNE z=F7A?FAOaDYjI2xVv7hC;Mlv>5726p3J|T{c^C&UL`VY(RS4F8BzhxophO@>@={N)ahZa?hw@nQHy@1XV2zJKYyp2<|cm$ zA{-X(9t+FOHV29~YKYC%?~b=HzAxi~3_h)=A_Lk0zz?^93hmr z?n8l@6A;}SgD;CRkc9IyV<+ssB29K={IHWinhG?BN$I-Wk6a>g$O0i17B1DGDp}I96JHN{? zw>zH%g*%l)H_serhJ$O3s?goXQinQfl{n<^4Tvo==%bk)+ho5*S1OLPb^|cRSO(e5 zMKvEP1yLM0`BnqBXbWb=Xp$jU3c{cqt;-n)svx50rs08n-$%Ay1NSUNM zi&-AJ)dq}xE~=*-BuMft;F?{L$2*+LnXF|HXylm}*^bXhzlSBfj^WT={OlX2_ZU>s zw}Pvae9RK3By+QG;ia0f!xCSbNv@PTm-xDj^y z`)6OcKyKmFVRox0UI#(oc^>b8B;X@y33&lCeR>Qkz%b9(vDvi%f2jrHqiin!kKvX6 zQ+luy^~bMKd<1u@)PkqV*tkNLzLtXMWMwonF4yHf?t0zjO*J?WahsK2#e^Rv&Q<=J z(0Cb2>%@e=9i!yG71l<`D?Xzg!+rv~S;;Qh?HH#r`tWhHNk(MRvGXfN2!w#>nevC~ zur=VuvZb39F5-g5g#gCpI954PXqss@P#>3bl_%u3q2dsWK=tmu`_%+-*h4Cy11N7F zl*{&*)`ysXG5~D=z+ITG=Wn^Qx^Mto1(9)ly;t_sBDhT03Q%B!dQRWHz2Jtan^R;_ z+S;Vcd`0bA3`p-cqc@t@s!LyXb%V!Hc#O|90$%47VGP7`IdIiAGlN~Tbu=x3GUM;$ z`!8XoT5f_6>)8Bjcbv5=nE7k{K0T7~Crkj*%qo2UB~PCFL^3Q;Y6_(CGENN)?9$GA z4N{d(Eyt$iA3b_BbLh=2`D-v0Ae5Muv7ENY?~k3-=JHEq4EgKdBC&L6G8?!Ix z8Fa*eWmusYfaT*ePs;b7du%m_Z}YE~i=<#Ja!Hm#L@}L!5eCKg&vX^>tj*r4xG%6HJHWrM66yA$dvWi_F;L*Z-A=UJX=`JLgyJb{MfyVbQz&*6LxO&f+5|p z6%t?a6u1>D$Ffs$!5?*4DyCIej}oe07L{=!)^)iT)o9(a@jq}L2=q8onbjDURo~SH zS1p+IA8Wnb7d%tbaOfl?12oL!kOe*CQYA!8oCiY45@MYWZX6sX6|6J0PGxkiflPmm z#7yt*o>smSt=~P)x@N>eCgRT73sUOODS$x}6B0S)x>E~){ZysBX^a`=Wr9;Somtmf z+vl~DzBkMF)B^i`Ndq`3&cfoy!jSj5Ottr~9L8Z0P+&8rq}M~!rYhHSb65oR-nl$i znG$~o1Y37&_$=h1`QYD9S4beXEt&mFy>kz=$Uk*>KmrfjRG>DUmS^yu0D7{oj5?qg zLzL`E=4$`OdQS6A<@pwk4py>iZv+6x_(R6BZnZ9tq!syd(+916r4Ka<)+T251O^6< ze}?tJqbj5$#y5>$27#f=2iSh0U{_O7?Q1M9wJgYB@0fsg8gdWlt{48tTPVK*kWBDG z$|7=Qv3A1%x-eY>LJhY$z24}>^AHZ)K0Qz^Ak&EQYTUCiJDjw-c*g~o z*E)N(lTn*f9RlpDLg(zCLBS-)S$~j3hKur4y;P2!YaVFJHZbMWx$F6$pxh+I?%Ddv zgq!I*WGx)01=5S)U{zbVYTnc3PZmrYBgMSG@?W)=#d|TAMqwO-i*R{Fxn(xdN zH8tshB)TTK{0xYxm;~=mXGDu-2&SDgp-N=4#fH=Y+XYH+T0jaPe25Pkj}< zYfKnTG&M9fy|B(G3ThAhC!rdXqmaec6MEdBDk4vu7Jx)_tk3-L@@9Z^yFjHhPyf(^>62`s zwmLSg-|vr8D1(1ZA%$7z5_V-KbmIZttO{^FWAM-w(}ZKs07sFlOT>AQ=^s6aC%dYB z%MeD?44N#iZ@7D7@mLvN#DCD!DAjvBdQxulj&B$G<>9^mr2- z9xuW`l?{gLaoJV5Buh=_H&4BVTE9zG(SR~H21-3%MgnqqcBsAJj6CE&BI)@SiU6o$ z8+pI4CiuaaEUQsk$Vwj5iE{u&(T(~4*n8`!D!;aClTtH=8W!Ao7&46tv4zQ$b}IC@5y=ZF1e~v>OM$- zvXBVqGOh}~EI5inumDte+D-<423wfn$H!~M!V-B&g^Mtqkirc}<-PN*rA6fEb$28= zc^C_c^mS*tiQAv7hNm@v94Y{A8>g0rhNaXVN_q(U~#HC%3Tw!&=6i&J&MVZK_4b9&<%SNtsY z*F&7OeI0qhrQJ9@P* zR8c0}e_@RkJhMbS&Z98^tp@=@u%%Yc;hWAFdZws?O!ks%sVzuT_ii&^&xkkC1}Sed zBX_qrV8DXHwQG!>Zc^zkEUhL|sLYSjDa~ktkKI~ef!6k@+8UIg zio^d)Ll7I#_AAXeEZim43(IXw0a7sVN9|@5>;re}tjvVGC=yDvN8kw9!xNwof)QH8 zh^D6qY6+RbZ5@5+M@C}JRGQ$5Jx9jXo`{6{;qK>_g2lz> z=K>KANGv!~Hil9Qqy3NfzkHWko;JBUTE%wv7c#h;Nf$2ZiMyG6NZ|zue|RD)?S%xN z_*XX%9v~D0*`GfF&~d+jYhq(MynhR_B!{+jkXwEvcq+EmNg4xJQCAOgr}v@yfLi6Y zJua92xTojK(e2}F&a{!CQ-utzF2aQs{1Q}ZnAHC9ByhFqPUC>VxC((ohGO$gH^s|Q zAg3uD9{UYNb@_Pj->;Y4lI9D;yT~ygET_dAuj6wpd!!+g%4hfo)&I3uR?O&$WvlYj zyqt3ihG9%c#{t^tBUU5Ksk(v0tIT1M-C;z0IXzEyN)P4 zfHiPRO19`9S6dFK)R986!>s>csn#k8L{J^&P|qKg&kM4Mj7Gj z+qH?GKu#HBYa2b1wa$iN(>$y>D_i^ zupz=2G0tbzid2Lh{!zQaCarM4M&91$;xIWXi&cDBchmK*SosA|#L3lmJoV}7(pKWA zRKVHq9}IFnF|g#92m3QTI<&%ycX?sh_?Zqsnjs`|*mOGi!oi5Wlk~Ic&P3se<)RQ( zrs``@h!$=0XXKo60Tw13uTjy`Vzr@%hwu{67PtbH-~G7GwcZx*<7y!J0mN=3C`#M* zM-8lr0C+_k4EbBrRPWDex1kiukpRV-$7+LX*XBeZss~fga{{F>(N#Q}mC&r4|3c_x&-OQ)6S+f{vvHbEousSdw!n+!<^u?HJpf;>L@`<1C4G3h<@YJtKXui2j zs0xk&52XJys+d~(bQ#8mk}iiJ<3zxvt3 z*5-TINZ$geJm357EY?@q{1Hgt`l|xG{~(u}b1B!ADt~|bS4fw(7SvRC)S;z8n+08j zV&GKNec+&WR|&g9+lfshz(qno)vaN;WgP*-B$+>#Z~rKuQabq_E5_Zyf=EQ9bgLyW zWy8~iJgBC%EDdtN3l#()vFdRr!{b}{7F>xdS}62F=4fMS!mq4j#4l(iKtCjbZAYmY zbTv9*M2dHaCITRAxHWy^O(Sf{RcR0d*FW_ zG5AkHD(9`j0p*A1F%)c}TG@|+)0XR3PN8o89^jfoC8;=J0wwm^Q20Y_aA~pz; zCdSiL!Yhvj6A+{}QG5rK7rs(g>c0cZ9~0R1dBuUGRsF=s6cb5m1r>lU(T@V|3X}qh zqyGgu3?LS<+KS4%4K)aT;6Dv)gO1sMGUfh{cHatri!7cy_yjYX+YJtP zDdnpL(K;_Yv={*Y!0gQ|?s9ib!o<7WEq^~~nLRo)@(p)X0lkj zQ0P_VS4Ys)%{d*B%mg4btqT`qW<(JQ;*I@FU=x@0k+IA{+61(=bqoyH<>f_iI`5;% zLM1*v_k)Z&?M<50Pq>oT8c$x&7{0D4o>$IN4$}c_gb4Ko=R(H`;9MjJ@(i&kvWNb_ z7098ap-3?ZR@r}ERMvqM8Nos^_xfN_|B2U+{`Ue;jq`>9jUtW$XD)O%eWL?cQUyTC z0;Nm~xJ(|qyUXinCu8+Si7rrl(P{H>>7wsGH| zfB&>hPa3j@0|4njdrfc3uCqy8sm7BY@bn{N!TpiVsH(q~ei;vQIksu^HFe;t{}Yr~ zU7avrZL@xsL=ei7n;qINO=||$7I`kc@=fff{e!ooK(6-}F~PThfYoM)lwhVMp^g&O z&mSdBy7i9MfMb14cX)y-4jP}WeYC};>6YtUjGx}JIrHQ2Sko&aAXEU(LPECamF#WW zt6|_pL=SxZG-6mz31vWs{;W{)rmwz69gGBNX6*oXSriNS`0n&aZHK;=D;uy0&I{LH zps)486mt-0WAVW_L~>6#JZ_~qif2~M0o?)FutH$RI0ia*S=1jdzHs%9rk(deJ?~cc ziV5J3@ka@$hLNIZBr}-R(u(Hszf`b)s`I}+3Xv@OhzVgz{|k;mv(u^!gefR5=?Ue1 zP0AMDjR)MDhS4dtD!`Hej!Z;@Iw-}T2i`@0;n!WKT{e>5moj+_M(&;_{Azi=?_?{P zJ_&e2$al&x{GDc>OIaclCIcr=8PIFU^CMmBdjLGX3hia7_*0a#I7~q6h}9&P3<(Rg zz{Y)XkCBe^@C7(6{hWNAti{~esLaZN*C#F1qzz!|j5l0ES6{F}s`ul-i^YpYX~&WC z_ay-j6}CN|x_cN4HmO1eayxuGJcD|ipePX2deG?pY z!Izo>2EaHi=COGaM9I7-?MRE+N!S_hS1ubzn__$ z)F*oY%Xyh|rI%1|Jx2fQ2iIFAu;$%4b|$o#fZrSiw+Y;S-FkF|6}csHrq6}`Jz*E~ z4|1K$7r+uy8Iyz~)JI%X8qX z*vv2+fTjQuNRKB9?nlhLZ;7qH&R3yi#qyU@M5+d6k8Ty+90mJj&cyd^@!?hU^}loI z5F=3nDRLe@9GJ#YEXxYh`C;0OSt1}~pwP{t2YY}G*u`xE(STzPUx5B78$}>Zmh}}I z90wyZJRY|)G+L7X@q643R(NlGbLcVXFN=K8-$pdx2$3i%?r$U8R#xZ}*MD8RbfG=;Bdh<_ z_u8t{rLW+_LD36`sRY(*B(xw~aRI9YTVIM67~Qf2q5!t z@Y~U#i1oGP#w^&!YRA>!lmGX-)t4M`ES!%stBgf8l}nv zth#GBIkWHoewY8f=>B`r{nH}}7VH08i;hk98WgYj7yApPlTlsTJ6_}|vXyA)S=!Nf z?j&+;>iVs+PXUOp2vQG=P%i*p-!b(duVkq1nwp*-C$~zIhT7CYn55$ntewro7?A>3 zu%E-6q3^-fd`1A84B-b&r)na=ps|-!9dxB~K}$Ura%c{ra@Vu$23mgr9@2v_lt8x! zz|&-?R}UJ}IiN*e^c>g^<^c2IhJ%LPt#I~Fy`u#0K=1JisZJcUwl$rd9|Ehzcff zpNkPb3$io!eF$x`TR#IbGHdOcZk0NSDj!L~O}OJr4OgQ5dE6I>PFOz8_BgQ@2LVzl zf*qy%n)SRuHFfeSavd10N)`=}p@QaoKB&W!0GYE=5DgRTnY4KHeyxBmN`4~f@tn4G zB9Rieu9BryJEBg?7yYP6-~pIS7~v>^y7%KPzV-dtayzRDe0~9y1yjSPv-ox)KAnD4 zZ)7-u`WyXWmR##U987BvkdqPcr6`fwgF0zV05>lF;h8%r7SM`Hx~5c$In)FTl~27Y z`eFxm!sn-Tqc?wP9vCC$Vho_~5 zHesY(FL@|Sggi0EnptCRqw!J4coo8Evp@`13b}Vu1WfaIB`Gd`|D~8k`+bB?`#)Lg z-jPK&O?;nu4&bRLir`GS1N)-*R}YfvO~KU;Qia$dr(4!}J5)pqm3L_u74Aa!83Q-; zI|Me4G@~N$e{T>V(Yz~He{PFer}WvNCOz5~6!Efy#bEPlLMWp)7>G5KlxwY8J=yca z&?pT5;1RUHGb1qf#$jItFRNL{$xmg4@Km_#BS3uG}6`2L6k|tuO4I zo5+8KaxN9!z4#9Y1gw!-ObX9k>TXjf@I z?xt|iH04oxLmy`tpp|R)b)zut)-+Og`V6i-&aapihqv+Rn1Vv_&vaK!o37k^G4cf#H0>Qynmek)cWj@_Yr& zOjVI{P^cCXs*7oc)xH`Q?kQTY;#|BVX4*F|xx67!XP%z~%|}ImD)ZcI2)1M=^IDA; z7iK5}LP{>^;D&g0&^-fHBK`xF0AE@_>6oZpaC{7vnLfby2Lc~${;Hk;v-Q*0pTA~G zo|JBZTPe`5veaCtbr5_tk*5^D1>ny7t_acz&M%7y$Bbm1+bVxCYd3_dVBrm_fQ%IR z>+(>2cjj{;=m|Zkp_2_B<)3*jD|xf6J`wcD{u|J(zQ80VM)bo&6JpOud|;@2Jp}Rc zAq#!fdmatI0=yU~WNfR8!QSMzcmfRF({RL&q(Td&CMzG?-`OEggcY(b=(xGn*uK5( zJqG#?>r{u@Y*38jF{sb+lYU2m$LsZlbeAm^CpuK>H9ptJJ!fkXT$aEAJ&;f>3*eYR z{R0EMQcWHNp@przmBYR^jb-??)~z%iJW~Y{Kfezl_W732$FWbnl?ER+%~LwuZ8RbQ!K$O&R_8!Um`Z?_j;s(~Ki z{xKjR$O0I#$}=T8GjeyLFy@!91W;5=nT>Ho!czUALk9{}l4U@bi}4s?+IhWOQ(D^3 z^Q5pIlR=$azQBYB_*l2wx9gZ46Un8nU35oG{@iX*OBdmvye}!43Dh3#&8v7HWyONf zNDHK;AcPAwzKbA+(G370VJu%^xXF*Xnt^uq@U1oo#QVU6!WF>W#rSN0*2Ggkef?$2 zuQdgZMqtW;-OJ9G12NHmEH#_$&T?m#@&Fi$%{uI4{<$vvH|9gYwijC+h8DM#1O=`UgMSM&ZVk-)QkW z5rrSVsWVPBf)iGr2wSDQJ!Sln9lM7%%k7Y~L^Yq;2*f{XqWgR)0uJ|nY;G>Rm90Yr zN#P?%o#pgWQ#0rTCHZu%7*33ny?C~wJM@e!1{s`V|=)pL}0D!;(sSO6&(jNduUS-{- z&YUZCncMb>zMorg37P1L`w1j!P-Pct;JKB9lKpuC-QpcqAnsj28!Td0H2c zT9MP!@R*}vlX3fk&0S#aBZi(BXtD)&$Iz%lCWSYE_csKp5;;{k%GgkDR>S=!+v&jopk|zGG9P`#*{> zDKR-T(TJRtLXH(Wb^v|kfpOt;TDKq(pTyp_ysh4Fwq9kehUMpxzNktieEqjLI>R? zB|3nl{zq9H`R{iLpeYdx2sgu){I?PK58nG5()!1_P*6=5kMafrZF&*zpg}rNiXqwG zVL6~DdiOFoGzuO(C4o?a?!@>PIQTaJ`0(W4?h-&#TM5_@Zg%}&eeZ8b>mSEn{nK>N zVWQ=MYYN1JhsP@q0@oZ|2u3Oky!`i>SOj;FR2-N-0DArn0CxBOefrfu-6cv@mbL(d zn;rdE-}@WV`tL>e-;3_Q7u`RD_y0fI>7vl?B)hhgtPOzG46#-jjKzRtFzP|mkxa@% zGZY|?FZ@mFM*0WxQn9-QG*Jj{w0j~V;!p|+YDMmi$PoVmZn25;S1X~GYA=_C+VOB=V zKy#u3X^jXT-#*dPD>7MwAA1ZjNw!9_b)G#_ z7MlX6GqirOnFzKVN|A$nDgOG3548~~u<{cvg-q@pqDU&O064S{V1p*|{eAoUP`%1( zWSIjMv!weoGItmhp{e2Do`rQ0%BSNIfd4r|scEZhajtqAcCH%y3IGMGrCMoxQn*bK zrbXzqKm>XLW!YH~e|3~BpM=GpzQBxqqm$}p2$Nk45A`(r?k{L$=cDkxW7f@Q% z>Hx0T@iz@nb3iu$;hLb})Rr<)gz!*ozu(l}q2SbNo8dnaSv{76S>R|GIc;ub5E=Nh6Cgu zPWs!+N{fM_f`Z_Z($ZqUd)hgq7WXX51Q5&wUA9ueFPW_ z)df5K_wPR_POU9H3e8wy(E~$B~ccCMwWHq+@D;0%XDLT zTnoQIW|nIpr7UAFheTA4_po(%#(N)UZ{|Qs=ZqLJukqES$4H0IB+AOj&g`v%^e-%K|05&2!^7KixQF_8NaB8UO;0V)_TVMwm|{O!%Tg3Dr$JvsUqP|dS(=#|68h@GH;Q4Tk&<=PF7 zu}3O1ZDgP*oUTkLO(KmK>=hH{v&Ap%lX;@$H7nIRk-&WPU6Evdxs6&YFDWT8%f}iu zkBLdZqG}pYZP6&jJ_G~h$x|X?; zjkXEEISmC1l@b6{7Vgm#71W;@mfv`KiX1dw8g+JctpWnwMwie<=uFLn*(L@P;z+?m z81?SQdQZ=kL0ttF1)*8dtZ+JkIby!aNdcRg6jb*ng*qO#yxOnJ_Pj!M;^V2(r+hah z$yd&+mqm<^3-(%{y@}bL!*pKw!e2Zx{XS+1jfhlt1%!t7wJuCkD?0_Tk8gdk|M1tM zBoI^=GBPpHa%E15%WrR6YTQo) z50Z$*YCcZv9;~aTYx7eUzt##>{gro8sWmBx2-BJ!4l+LX=6;%x)FDY5yOGMKN=^Ha zlzLfW!>{!A>HEZNgTv+7t|SpVyJm*ic}SAMQ3fjvh<~U;X-(1FF`IMk)WAn?p3c4tEE;r!bcXy0Oj9%(CVq<>`8? z`oWX0h6VHW+uccm8xnjuMkVpci-+JcVEZ2B-*jqngKs{5ugz_A>sh7}O&Pb?ZRmj^ z@$g_gJl)xLy8rRf9~4yY8Y`9yo%dPBhhLA*oHnecnG4A#RD2z9F&#+cMA7Nn(*E{Ce+sx#5f;wO09_SUYo)+0T6I4D z(Z!{pNnbLZfJdCIhMt^7JdW&MEQ8$EiHkOS_68d(cW6ps96j7Z*k9&vFvjRPXT`Ir5G=k^u+l+X~rY1_9zufF%=5y{{m%9muBdrLd3T~Lw zeVd~8K?_b7dYxczBE0GUBq~y8JxS)x`MFy+tUfCX4m2es92>Uf*V(KcSfBX;G>D>S<{_F0D9g$wd1B-kx=-Msl1NO&O&k8FN_?4q_`)=o@N5rae@c+P zF{`GSOGQ8E-msOtJ_;b`@=@|~o3ltFFFcDc)&~o9*FM5SYil4wB`%)fT**70>j9@6 ze@n_ZQbyY1;z~D{_^h&WIQ|OFsMsJOO`ws)xEMUYTg~8iv)NB}9LX$pv!B>D_w+uq zkH#k^sw;JMZE5O+StG1mP4aanCADVIpJ==^P8;L8*H`>gFEjB|QCV@L-U!XF;9wIf zA7m=@52fhU)1;PdoQ!1Y?IM&US%fNaW0mWbB(xTqPl+&9H0?IGwtV}v3s#hsMP#;w zEgc-JkmiYCkme67{SVN9*QVp&Mr7=?`vA7#L(l^;mPPM5X?=5jtPl@RMn)D2bS!X) zs5oMYjduJCwHVz7L&ZWl(N`{Sreht(J+wnrQ&=p-pNu6Hvke8q^~9M%l|MnGbqunA9hd0R`muZ2&dMIHDH(&sZx?hkQD zCM^7P?{M_4eu)H-5An)T4IjwYBev zPSI^$xBtYnwg+L-3CORuf&_g(kmepc%+{c=&QJrd z!}SOA;GT?v69d^MVt!e9xf1G&$2~4q(*qNTO2(dwN|LjbIO_uDY~D9FSSy4ug3>9b zhSDdelX<+;JnUAM#HJ^Crz>k4;m2;Zz3i-V#3Q*eA?*F7w&fA4wHku2_XbA%s-nc7 z?~{e(8rz}o;8D#|lZ(v=OxD-G`YIyQm~wcK_GL-t=4idv$68^vo^aE^>!rGVzgoNK zg1d>3pC&D@c*NsyJwZ3YJtD0Q9)zo}gY%QuaZ2`VZXPLrl8iisGv5kQRoRkr@{Y4i z8_i?Ev|#K!JOoe+D9jBddVNgM$_;2}$yRUl0oqFGi}%h{1LlE1qcEf> zS+;)_DU}MZ{`6vHRt0Zq3ovE9fy>oyAbJROYFwpbO};#BmJb@Q)vsFV>b&?Ko0@cxl?&C$2w=1*8sQO7Av=rK3g!Tu|ECSC*v%~|1Nnc%|O08><@h( zQMx1tiKK%gQF4q{uj7!>_t?3FF=;Gg6nCqAXkdvFMZ|I z*5d6%`w1Su-chfP9g+QXt=!%i*>jwIFvzk36|I%Wy2-wW``aj;tkC_%Dm3n#b3Puk zDet)t0zUV6QMq`tt?fiF7)I~6#c#QG1-K!OQ)~jG1&8JD8^h^ddkWtfm!Q^lI9JQ{ z_&pMFrIELGB70e*8V#=HTR?Cem{j3 zdy|NQ=tSqy%>VmYyFQHDX!zstSz=PJ~jN(f}!QnsK^{%n6j>oC;olyx=9M@3Z?>v8v*N<`_5&oQ4pvie3;>Dq?l(ktvzr%apr0u~S` zdWY|K=k;y2C!cmOJ4)IY?NL+X2h~lQUyb^R&u3YVlQ6E7F$M5}z-(Fsfm^H!8|v@U}d`%bEL zg_UAC_6j}*^d%cR!m(n8o5CIJ(>d#HrH;UkjK11ygZAu4udtWgcRwcBs&GG(v9p^; zs}_P0NWII9ORIff;3FBe4O>8M0* z@6~E=soAW)$Ud#COmU@s;0-6tis)V+F!PJV=)Rf252~4Xbu<3GE))Sg$ zqLPViW>DU-Tm7*bwG}IsSGY;bQ$%IYcA+->Kq@Kvjd_uMx#PeaMkhnB`FnvsYdiAI z8dfK|oVO_P18pwr>DcF}FW~vh7uF-OciBg?a|tOg;b`{PJdr)H_(kbjswp)mb!slp zx_>1+LTd1$ul2#JjTPRfp!78)7uJ*ICN|a%ZVLz=g%cRvI>btNXZ2pJ=t|P(Grja! zjh(I-@QmOT>}8qFc!nhgTw#VM-6v)~K58LoC>DsFVl6u#Vl~uY!V(p`Ih*+S`IW*L z13OG4Tv{}`G|-(9wl=gBxBbmimLxvczL65cCUsm#LT**$XAzs+^K9wYmNHCQ>f@7^ zBOw-W$te6`-c#S4g7@7Gk_!uP93slNrkPn9ktVoOBM0VxuO>x#t@d)yhDKABKM*He zK5)cpdH6Vf*~}4ZCI|^e%h!ufACdD6~GpKt{~6Zz(O zn4cgvKknExEyL&8z>DE+(lCsBOO5jLIT;fozXnl=m=6S)aO> znC5FeroI~S6&pWcv%Xt*^J%u(T+&b!Z0nx17M%WM^_JkGzvh4 zI2b#hYHspZx)&0`~(v*DXr1+U%gfnMZJ#e$_?p&F6^v6DGWbs7O9NQpZ` zTDz@a@}=wPiNFG()4Nw5OcA)4X-qUClivfJPmX+Xu}LVB3+0VVj-t~+CCnUSKj1)1 zM;9UAu8l8Wah30bfRAq<(s@%;#MHY@V20b`je31;!NXHJpz&hCH*TH2!c!Xuqo2L} z{W-n^`iX4XbLa9Lq_}+qJc@fNpP41SZ+}SSy>r`n#E!}J+KSP9!?eGSj7R$i>tM+v zvZ~){-VXR%4l#>MHAj0&yfbQxB=Bm|{^A+lHmIIRKii`dF{smJkGnP;$f%ZrhJT;y z#lz4hes`_J4|%Ofxo>}a6})ngG@U~@_wiOU+nRJM5HaK=_Ps$gc5#^XNMy^KF{-1n z22R!s_W(s~++jnz-@d%@+>Qu~TAhp=uA49Bybo@Cs3t z+JNO5_0_{XdaiBHuXC7tL1Q-a{bKwc)&};7b8}rE1RUt^?>JPrs0od-6JWn@G+FPq zB~iQaOW>S6>yn^Ux!)CTh^jHH#VMOhUm?MUEG`n5<)v%PVMr8mbLNO|I$q=#W{dSlagDvNt9uzmP>*hN&SFj4l3<;7An9wC)q zyVkISm%$^sD>}i?X=~>QNS^g(Q_G0e&x+bTe7sgWYB+F7rqJ1+mRVOkl!$Y8RcVd4 ztu3Amm5S$6ot_p@SOG>=f~$>$N`EE=MmqbZcAb9Jzdv?Zj?-5@F@IU z1d9_~3`Zn&^YlIa2sISf-*C&k)?1ebR28bUP_ples%Axwxb^33yk}&B<}h zN+j_s=&o!kcoK3~T%^5%TX*KzX|zSn@OC47(3mSO@K(m1wG$p4HDWZk8Ff)~c0K8R z{cL7p)at|ZqvaA+tf41#{c}`(Q$LEBUWueQo|fY5g-}R0a!Kp_`83$6GSbm&noibO z8uBp}yF0Q*PD@D~XB<_;HI_>2HUG-!JO>B886*7fC!1$Imya*wwoCHX>q&AilbU_&>&J%*Vt@E)z)xo1ug#^4o&O~UcGt={T&I~5nFKdEeZ zy7#qHRi5xoD* zvop1}C3IL5rF!>vRqbO~Uu`bjZ^J|$U>Y^3`Lc0PoO6`S|B24`7qK?lQ@AbF{V!o@VL=RD^KgKvLvz>=Q4SYH(45c?4A z$wKk`Asfc2qeY}>fhwH z2462|Pd+ehu5N`#6Fohrqz?9I+3PadK_IR8wA}KUCY;6C_$8mdDUy0vS<9DZzHc8| zqxUGI&aP#i^VNxpz3`)HQIyC2t=sRBsqsjX-S$*qCgJGEYSvW!HS306m4D$>scz~s z2cXm+)^zP^P`0Cl59>b9(zHpdoiFo0u65fGQBbH7drZEW-VCq)B7>;5G1HCQ%E)a> zlSakl_eD$a{`X}LfyZmdvfgO?H9sp`%R>r7#>}@ZWN)z1(Yr2&Qd1gic7JgSA)uot z*M&C}W@Eh;cja7aEai3Dx>d0^w@Iw|@l)telipP#&#S0T9XV%2lHtc~+v_5xrw#V@ zLNGKnB&B9i*VaLH*`uRVuL?oYjzMFVXOx}X3|#&knv~-C*Fv9fyq}NRlw-a?6*SrX zBCtie;y)z(L+GYbLh+X+?(<*|`ch_!nkU#!bGxC6f}~9?wD`;9*m{O>xD==cl>Nh9 zbK;Hb8n!6!Jcd-LCaE$VO^V`Zzm^r;TW?e_`|Qc9`ufarhjso ztaVLMGg$>)8%hPWzD3LGx7^F)DCuxV$bmD)^=@{ipqyPYa+F}b%)2Dr$4ML|<9+ul zPsLO2eViQCw_FO6st@Ia#yAaLs3t3QIA}B&SN2ZQMk@UD!iSH=N>+AFW9E3>=~A9b zc-iPWndxxs{SsY^I=sm73c%c9L*XjP>ml>gCrN(xdU$^@4Ix2v)z)w{vKGm@oostqT28#4AaP z>)Og{Y9S2g>L&*10I>NuSl#`m+jTeiMS-TM2F+Uci;pFwEXlUA~25>e=9i&wF#U%Rx%>W08Kx;*?{kvYbDpKM0_tpsbSh2rfry z*U!I2)H4;ZiAGd*&%ps{6WZks^k?@G@v1)Dxz? zNTp#F^Sv77k(Nrv=F>126sMBs6tN^vqS~xHCjJ~@Jr_TKPy5D8Qk#+1fnQB~#RzZ6 zAX8y(EGFwFPzO`Q^=@z^6)(onkmVhIW3(SDyAb$5df)k*VLIMO@mI+Tf`!-SW^auI zuG1FF=Zk}xUOW|Ki?3lC(X^Y>jc3mcE#FWxaTcx+Z)Hi{oxY|nR=ETv&8DL`i1cPEhIfpfztMbc|2#g*z%sb%dpOJVK3#z925b8Q z{Es&^dLk`YC+EvD8n1krf@Ji29;C{r$TmDOHBi1E-mBcO(71AKG!{y}7e4>s+*;Q$ zW*!3t9d~Z*<08q+!I+-O-|eGEwp3yVRb4l_2i^JcX2*xGr`H-PZpIq>(Z4+;O48Qt z_-P+<9Vvzs@|&))93$BSxhTg~ygFUbz496uVxQTRuE-0X;S82HzVPHA5O|vPN*%T7 z2ALP`r%Ppfe)Qf%$~y0ggX?Ei1a;8==>n#aA%AW!TO7`gJ}ybT!~ei*g_Fa!mM-pf z5y!E-lL&?RCAOafIOn^PaKao297pDTk@4$wA4UYf!Pbj#dFp4(qbpnXxnSBw_JKc z7@1D8fIQcgFJ-~$@6+UbzAinRsugBpIiFvb#Lzthub(V{wmn9=dteywMz+amM!_KN zsZsBinmCFZPDekY(w5@K@kMn@lOKcwN2|fj*Iq(t9kwPT;}5hmw*4EeKFWR0pqqWC z^Tmtr3_Fgn*H){5g6gJ5rtFQ3~@nxY8Ar=vDh1D3A1zs;O9=QUW z!WY2O{)2>%XQ}8fo$242!LxwXA8GUg$gp4+b5{DMBHd@_z*>)I&0YI6gwIP9LxM#u zt+(zxVq>Gh>(X%%bgT=kD{K$3@A07l^r=$+;L-u~lIu27>|kxGH|M!NMA;=zGcRs* zRqdmdr+`^_?o?EEzN`aiEg-Ldbho`R?Lj&5RJ7`^!Q$YIUg?jdknm<)hTTl%N|60j zuz8?($e255TVT6;=|glVkl#1K7U{NkeLa8taA4l_y0ARGbpi!I!TqDuNp4k@7{|bs z-vl^6l`p(T6L3dR_f5xkcyLABR#smq|B&!yIA;GcYiDW5JEx9U(z7iIQexRe!#|=! z5B4I5Z+s_9M7;la;voMZAEb0^U-^JT<{3svNGo)hIBj}uGu#_~U(QKZXqrp4qxI{> zteoyCb@3;dBtP~9bpwV?(nv@8Z^4|j$O2LE9E5G3#OHcgqMnjN%`RvNg|1eUM;2+z zOemiwE%&Y15+9hhUHS7Xt7i|~P~UTXbNv%e%*_r3qtDku`}u9FY;!D?RRm}1$(Y8= zfRWml9pW#)h66f1Rno(k5u)O@M~t@5a3&*2xg6bkIAh3?x7qSwz%PV?n{kDKB1pVR zbEkmgh;cMW#0x>a|GxH?W_QLj7J7OF04N7M{F$JcsU_TENtK07Awbr8zTln{PzYQQ zG1K*UWZ^0}1t4JE%3-UxkX~50Yb$;6$&ZYg)Yf<--{m*EA9E!>^bV&-T|K`*x<5jH z#JFK2m_Cp?-udpFirbe?UbjPRds$C^j;z+8%GN?#z`^iRC{pUl6Kn!PUZq-QK6GIUMij= zDwK5-*%xYj0k2GTPeZ@+9lMfiz}j1J&jq?_W5ERPdohnlhvmMYB$TTxryROCPY^Cu zm_0^Weq%#p^jwTIg60kS6Aq~+Q(chhc*US9(%8-cu$9$y;=0*f!7srU9d$o38!WbV5GadaRmi>OPVW~$?JWnO% zdvfb_NOj)!$SthkL#hagqps3}DOa;Zi?(Qog=o*zXU>0aZ^-0M)uw7Ed}QEMC^^QX--;fs*jK4`*RJ=(ve*io3jCTCJrl zAZ}9{Mf-_AFL$wGlOL+~J9XsZ@S(#L->mMaE#y72amOfFB8tAuTu`W}7hg^l!r=N8 zDf{`L?aFaUq7(Mp^vN@V=Y8_nkp;;tm|Cdubg6HYu`-OBsFScLTX{IUj*i`W6e0^| ztNtuUAJm*`wf``?~-u^KwH zA-|ok`4&((RQ*MAGwl^tFaG*ut^zKiEz-U3wtGK*oEI+q65ZH7Y@PV>?M(!*&!Et( zg-g-P0EcMgPhpitiwDW+6MwA+ZDh(_{8%Cr$!`hidY!slTrWb1?(Hsop^>5$ZR}%a`ooCK z)Kgq>7ClBV&DvHq!g}4(a zU}qUQ;9EWU|fYR$5SDR0_Lip`7tXxth5);xHhA%*%7@8PH-~rX!7Ff3C=v( z`fezXcM!T@v>)DTkILv{i2aRE6zSSk@QBXXe}cTHs?geY9*;Kja%@j$aw5HHG#5vI zcnS@}t>>g(xXfcSj9N3gD7#sz{xwdCwjTTOBx6}!HUhdg^%VZ2IFTTqW<+XF7iMO| z8#Mb~+9iqwnnuINntEChZyw<d}uVvbmR7zGA#$$9aLUyC~cs{KCuozGJfliF#8l zrdjZ#)uBHnt{UR>W2@eC3guO)Kok0+=a%!sQo zXlQB<9*FxvrH2v;-C8odwc6B z6ew!aUq;JO*MhdM|AuLz0GyGwS8-ME{eJ*2LD0T*=u#>g& zO3=y83ulauMRs-tV#m1Pi>LPE@&{w_;*y3Yy`UVY({)^Sd(_}b0&2azDHE%;HR*{m zGBWV-#~=Tnt||LXpzrd_FaJyM^#1$rF%xBxTZ#TmAgoK1vF{}z-3P5%5-n~`y=V&@%6^tLvs2!hmblrXT z-M3iy!%y(1wovSo*kLg_Q51a7n>X*MI~GmmNqQuO>;#~yYimsb)h!IWHKpl#et?N4 z(ka?9on5T6`rE#JuoXNtWnhov8qX-{m!7!oDonleVU$p- zSIe9w7dYbMKEv=x)@~fk&ci2LUc!_z7Y&HI%ibk^6g8Ikdg!sI-^_LUys01gC~W&1TvI?*4kP@ zL4nD(yY|{^&6k>N3M3#`_(|G?zha&;Gcyqz8;eIDebm?wDBJGmpMS<>mtAHk&40=~ z?PNBOtPW&f;P3BmvJ~}pY5`B*efOQQRFFnu%9JUl@2!F95qOlgt*!fbS;13lyF!6G z$l_L!oypG1LM?SjwKVY)NUEUFTHo`@z{>f!gy9NL>YgOP)^%9R>t^{;CaFY5cBasm z>E;AZGT)TuN&DK!he}i0E4)UYedbx}v)m~_cVK8x*>;u2s$l67t9MRQ#`buwE7ADm z$>+g=06yqYI%+ug?8!QPFy(Z7zGM%6Wc|3eZ#fOK=dMB|bw_)%@=dm-ldS_z84!Zg z&hUp*-%7kPIh{5K)Y@_G)l*|PhHmu3hDV@&Vi4}0G!KtW?}PaX*%&d~7J=J4BROI} zlApCja(F2^GK}}`Q%Pi(DhQTraq9!4arZsnp{AB0JYF9YMn@rHp9`G2d*bEATkzq{ zBXHB)HJCWAFOoMT!zt7k@3Fq(oOV$_&meraemf>i?t+YXdo0_10RC?7aH_7yhFn^M z*g9e2DP1wYq6S|tSa3XtzD?}=sKJu}hP;V>&(5@#qgLkH%{SkSwRHFuP!V|fz0Z@y zs^E|MtPC2lR1%UageE{E8v}{Qf8YL&dD5Hcop;`87#xKFr%js%0V)f4l2%IKNh!}~ zo_Qu-ef3rIpg7)5`Yvg)h7M)b$~N4rVY}mh@}7U;1w8u5Be?FGS=h~&2sftnD{NNF zhd>R1liuicor%pZWf5Q(8WfiBS}CPa+@3lj0bqTWo0n(aiY5Fu&g1%=rB+k}ZzaR> zf7L?iFz({&(wMk-_rynE$DvvPivUTbTs-WZ zVMlO&=6RtQee*-Woo^#0JqH`BSf+)aE5tkggPW*ndJP9s3lPWfT3MYfZk*czd%ti7 z=Luy103ZNKL_t)5SD#XR^;#B6%1d!y=RUYIZXGT;gQbg5iMZ8i*qN74I0ek6&(rQ7 z3MfYjLj?_59jjSPJFXD>BO73oR)sG4z@y~{FgltE6Wr&Hlyr>g-Wl^Z?m*`Ne?0PV zFHD;CGsbm|!BQq_pjTIXyP)-vBCTx}9W{8;ft-Ez*@oFUi#4aL?Zg@Z`B{l|dbbGz z-4km>tVi=tMnGWVPKK&)n0-Cc7$Q*kAU8M9ltpM3ZXY=mFRa{1@MFs|DsISN0c$&gr4Uz7+&OtD>Y4uE(X|Sd zb;USXTa0e@F{u496AMa{QA~&MfSztRN* zwR7tVvtf*D)*q z&1W+76Wb(^B*3Mnx_9zgYv4^kpFevt3~vdQ+3-PT!}SD=?6_~0N)hucK&F0F(Y(@! zV9ddQC#gvqnw(uUW5!h!xUc-xRzdsGgEu6ky_I=t?upjI+lz}kge$JR1Riu2cS_5| zGpCKfL#s9r9984Rt53t6|157Y`?HLyP`l8y=aq8=>c(fk(&` zTiY=LPui?BL1LaRx#SY-IG-RRpfWWVUwko?^>iXMYuN7CoW)z{rB=-XxMd8pxsl~5 zEh{s?$B{SsJc1g5lm-G9F)>91M$#JDQWGNPNm-==<^ncik_2QFN>f2yfe!(nVm=f+ z8KRRxrk2xJ5#RLN`T7u0v8)7*YUJu|OMq37PbcNWCY9QrwxKt2vokhnki<6SGBmDm zpEoo4^m8Ojwrn8qYf3wp=DU0M?lZ@0e4Y+#o`R`)`spWY*sdvKd%V}(vnRorWjYW9 zg=XY4gjR(C!GYM8n}sO@qVeJSz3_JMhP#Uc?!B-VZhU_!syHw0Irly~=QPavVHJx2 zJHwOq7|tvPeAB!s@cwWw7G@{HIh(BNhtrpH zRiSKV|J8E40#SF~HWsfvyA1hU&W7Q?+Uh!-AKd|w<7kcX-!z2vX@|`}C1L#OQAmv| zMme3!Q#et-k^o1V zBk6l8__M-hwge<9pjuj1N-YzC5W$bc*h+6JB;awUCP_F(;7IFhdFes4fI@a!TOLW$ zFj+v4!fyg+3cp!GbvhD(FzsJ#mg$G~&%S6GIf&cwfg)CmB$Q#aw4C}VKqX^eW!s7Q zvbgx?6L@JGZ@u~EQArR+j2vmUD*&lu5?~Zq3!&-l_pP94x`3(@e3WI})|xUIm3@4? zDlY8XmqO{nf9T`40w45@!A;*S!QH+4Fhc=hSMvdFXI9o|h*kMt4Mp7tIus zXn!!)54E3`;mw*v^rVl|&xwa{Zde5N*RlRfMFU3KyJ2qDegwIBpnu13EZDu>gbDll z1R%M(92tS$bjM$1UNo%jk4K&lBa96(%$$ z-IH$bT3!_a1fFWRKLI9%@)Qyj_oU1|ZMT|l>y8R15-b(7-vVf|3Nfr1mv^I>oSieE zEP+WUN7A~}&O`ll=NPD;`dP;oN}nfX(jKoS(4<1=FHo%i{PWMZS@5KAu#$J=DcI5= zs*H0zIXR2TQPVKf-3MRq*@rLAJO|04MY!*Sb$IssKDg!Vtr!y%hRun&$YpUlh3yth zy8u%^`vJZLCl_DW4};E~id)CsjM5s;Lx$P{+PUM@@$E7G)~9jb=!rOxUWhsyUJ0D6 z_6$2uzPKMg`*;iIaV>5d*auIq-GEqH3dENcp{k}1SC8nA4Vk&9EUCh9M<2YGdH_TF zL?CHj7JA#du|h@|KIQzK;}wlN_HDxLQ-d`B}Vz*Ge$O)j}Tm`FSSvCM}V|WF@5~hP@G^ z)_Z!R@QbI-rIOfxe5yQa_9p z0+}LTf+mFom8qvzT3pg-HNYpBGeMcamYR+wp4qp5*5n_hCR0z-m&4#m*U$noJ}upT z3!3zE$BrFMtafcI>Bv{4{v*+`2Pc?&}GYu(l!r`#nnW!~7&N zL{)hGD(Rn=8G*O#3>wHtg?aj7__%OX6jY+Kvk#tIu!`EI8Z%dAIPPxmfJZJKPgW=y z->=%i7mWt=>(idqEW!}CBgcFVI)yr@gdzmfsNj_YTt=)GPh_`{ASBQQy<68%bn6&` zFBWgWbsb|+*4G36rFH1Ii?$zK?eWm^4ftrqTli+&J+K|+h0p%G2Tz=J3Lg7uJ2L7k z5X$1gb>-EFFU^NPoy~i)Uf<7Ii3oJ}M1qeSGf|rs(r&AB?nwIGY~abVGnMj?*jTmM zq%mmj))L_9op;_b7pbLWijLt(z>`ccRg}27izVxUAVAs@;K_2nGzOo1@`(xGNf%;m zC&vg}J!_T$HFEV95D)_+W=X7(elDbd)yJF64?&IqRAp7Q38QHl7lIkRsXLmYyRsc% z{W!8fVsr$WOcoj$8G#Y8R0^p{z%9!H3An{#8S%K-EHO{Kj|jlX!b2WP5|PVC$I+qD z9bA17<7Hv01hy>ND2vOtK#*7{OJlrd}a&k6+ zPc7*$OlxCeyP5Ecm@kDg8w&&T!9=TqmIP0~2Thh4tBl#U7_zhUU-!K$uDIgY3$Ud@ z)Xtp;_~Jbk4xCFtN!j>v%y`VA>v!iK9$39T$t1wNJ8d-Pe6k##_D*Il5BdOxPl z^~4jCk}zw|nJC$vis!#wLGV;-<_a+u+S$0!_P_?Y1pRd~R;_2)ne$KKW;=!b7{c?k zbHr=6UWDsk`34z9g%qlDeQ{UZsS+ymuXopu7}UEnKKycppgulZ{Q+hUzZxYCmH6P} zYjETAcksl6L-5QS+fZKAfP|uaJaz8~{QHTuh;|_$ozV-Iy|{#$EJuVnxnf6gwi)Z9 zut02})sMCP@dz|Kc+zfE%H;a%uQ%RC*IaXrF@J2X_E+F(?%cVCk;-Fsj!Z6P;u#$s z4KYu;u`OG+4Dx>(J$f{x?fD}LSj>}dxMGmByd1WF51v%!MHI5$ilz5bO22O4s`{Rt zosIJ-AXSMKX~5(hzKLm{`b=I%fOPO0hXhH(;0(+C`F zkWV1vOHD;dsr;9m8Jf#C-;2o9c#~}|E+GTO5Szki0yhFh7G0FdlH;=ayL^?zGPxi2 zFw-*Hhn7+3KunT_i4v2o^^}3X)B?`kzS< z%WFjJTY$gc;p@?c$ImozYMzvhe5~7_fhO&@t+P&+v9qvGza7h#0#WhtDSTeMj#aCd zA|j(0A3Z%5>Cw5k@!Ty2%t#!5Zd4~MPe{kP6kyl%ri*=@9lrjOVPArw5j~^Pfi?gy zEnbZ(f+xl1oT!C*ZtCf{_mf2gIkkw5qPG+GqmZ1!*ir*}@OrExNb1rt5PRu46&~)7 za~je&?vmOJ|5Ri z?1Q|r3hdaFi}jS)%)DSA-uP+_{22z1Z0C>li3zx2^gygi%R--?!T4z77F>Jp^TyQK z+WvP0jtO|O>_)&r#dVdn)sICz&p6`@11g%*{tP^c*6m9ATn^w-QBj6D(#=nWeg&RX z;8&n0ls7c7W4ai{j{Uv~JauLn2)&64oQO@*o3e#@(mwRLv<#||r+RmC4%ha7%RI@I zTgNZJq;TIo_uOMxDfM4Qn*u-zQ3xFU^wUoUFll`BclB4`DLFYAUw-+esUc_y+sRKx zpib+wlt5n~PM}VGXp7Anw)^w5mYbVnbTQ@S6()qG=0OHVfTobyZUPgU{{j~Z!O34q z%#DDL-k`-Mi7}G4$z-@0GfPJUREi0%+zvBCC1R%J>TN{be0S!TfQ+f(csM*}ECr~2 z5^yS^@LZZF3-crvNng%0(Z0G5~{t)t&9MZUEUh3?GD1^Z;a^KUv1^;bYk z76)p&4h5Wy;U*b3g$4Cp+p`>#zFS@b)!jSqxE<&7B}q-1C#@?FD#NJpfhmTq6T@Xq zDJS!H*V$>Hbeju{sYM^-`>-dwz%C0=9* z3wUvz_ePAtlqEl*QpJ8b@9(;CBA$BTOVqFoj1QkbWdvqbyuKU=w5Z@SS$vM1|6L=4 z;X~Vwtb_7Py{3d0^~-n8fi@lYyBB`(oNV>R9D$EVrxYA%hg+8#MjsN*D%}`76KKMB7ys# zfhU14g~|kG^ko500!ji^D%YYWFC=Ljv~LyAwS?`Y$p{V(Hd#1VvEsUZj*pKw{v6F zZLL`a<9~d{=G=ILu>uen`&0jeg9V<*7I3>-ze89D zd@=8fV{*9&+>B(FpI#dOs_7o0m#yD7{cY5!QRW`gRzCl`%r5~!9n0^_XEnzO*t~f+ zX3e^cp;#w;^T-^e1bmG{%WJUu<5Gk%iNd`LlN3sUk-Z1w<~u(^5q+SPsCM_w7h&CZ z8<{-di}!!oXuuQUIR=CUAuFu_Np+PhHOzzw{_~(6f`dba#os z!hMGfE9J=RvmF7`Yxi7*OYVQ!SQxz2YZz|ZwGK0;j>gYlt;d85N8r8B7jrH<;;|up zaNFX|aB^mn1jFcF?#@V|k>)f$Q-0>09x*T+Yd0q&xgZbI=m$0Lmu=`56ozFf@hIyM zj1B9op}RktLoEWHwBx6qddieXQD{wo;b_~RfhXM@#R3U{1n~_}RDNJ!;IH6G;N!aM zt~0x}fGpkMB*50qTI;A>iiLT)l^!-q*&jcCJR}4cbtwjE@#4kiyO#fL6POaH`K{(@ z$dDoCxb^m@^%T0382!pCuf*1^Tg~qp6NUcNWHczCrP3_|Px8)E4L&vXU&k0m9YqYQ z%WJ)sZURv1kEKs7z5k=#pA|g)-;ukTq4WU1c8!`NYKKZ0juWWxB&ZSC$jr_)LU8@8 z8@E^#0U$9)0woHI8&Ji+iHQ<;(d)DTgvA!XWYZB;Sh8=moR}*ET*z7}{A__8|%jtt*+EvO)?#PUE4MY~gf_xKk>@y2DF5noV(dzsaC=O;@T z&Lc3VXgq|#DkG-==a1-(PnT{atHdxHwMw(P_r&|VcOpm06f)K1eDknz#H$OQ#eEmu zhm6Wn7GY@&;qjuud4s#-+qHX4HmSmdA4HGA_4`(^WDJuu__w~y1l(9!z_Kv*xNOo$ zEL^Yw_gp?6cl>7owM_PS=fi7o`SjNj72%IP2XioUQg6Kc*+x7%V>ljoXEl08wMRj2 z8TOHh{$cqXoIdbLPx3`lqJ0KLbx< zn4Wp&8N&!E_4vaNKg7a?3x5Sq`kTUNYTLJOH{Kx$e;@+=EqKzh(l+T~Apj-NBw!=v zN}4G(0UDKe5K#KPVEn%O?xTRV%)AY09qEV0jT>h|0#85vw6O(HAz&Ges?DE2-w3pI z3<6JLq%2020#DLN$yr%HZ`-!*xCpt`r`fY-o9xB5(yU>-#xpgW*Ptv0l&arY9;F`X z8JX}S6RMlCn%E|pRXXx5SS_37QG97iDfUHx#;`t|zhaFnp)zIRDcmM~kxHtRaLx-f z2_PBYCcY_410)*)3ChI~2{bik%+YFq%Sq5Jz#?#^CeWm7OJGQ~=;Si4?U~RaHCFD- zx)Z~rXN$z$3h7DwEdi~5SChqpz?eXiK$Dt$sAQF(7bo?%tc;r-K$GP-cJGd-HuY^RU-1h%X0y7SK#Uk57cZPei-2!7>?VsBiJ_q(xc%Lq zXgknA@whXYNX`9fjPDHNh=7iG8Krfq31k$M(b9WR~=jFtjERC5A~rN?=O>NMXGfm~f!tyB~k{ zIe&f@my>ywUQaI;0#*WY5?og@M5jzWfh2(th14uyO3YL-0g^&~+PBsf!&FM`lYp9- z7xl}ct1=*m07zMHTHb)C!!Qf_e(O zot+%;)N6gvX@4j#dFDGjbkkT=WYysQj~1hzHCUd!{|anfvj<<%M&R^;G5BHaZZl8* zefCH`i{kJ@LAo)fd@TGF+?AjL_7alYp&J>_9ei1EAjqF~NjTp9U_V37br>EVg5`%& zF~`3Pp2?0g*G@3S-W?j8v9*+*PjV%fzK=WcVAh{&gS{z_bS^XT*7DjF z$PLdV??CwQU|hb_9k{kG{UC8UKFf@?QwAC#&joZwA zjv088){v(;6&g_Iw%RC^>@9+ z{vCMI=K^5bwk2Cm8m>E-os_|Xrvg$EWa>sKKrwLOK=ka{)2yQmA7%N8F}m!s%M2SP z8ePj-9s**gB-~U}nC`L19y1StzXDHMU!rvZxKmF(wK<3Ph_?MER$OXi#QQ^Qb)8v&6#q24BQJ7wBbli?>uM_|pcQ3PKWqf7x1 zfvGYT0ap1J8T#=$R;W$}oVI*;sLx`Nw7#w>3Bg_Y-IBrASZ9vjQS6KHc+!1CtdX%J zpm5wUV|w85ZQihLGVE*=nHvU*-z^??mC{2IXz78Zavf>{iSnqjXr#1`SZ-}s79YCi zTe|%oM74GH$-+7v576}6bGL5oHe7wpWen9h!Y8K)w?5dD&flM^UEiFhxPI`uUmRZ~XAAw^6p7!qDYtr>4uC}%la|9Ho zl9!7s;FOgo{gWew>2-W42vjLtXG*y6Glf1Z*@brOvk4`#X?+hjcf*8f-1NpT zO;uJ_Cc+t-TSP|MQb2nklT0MS*YWFR>v*=`f+*>t+M?H!*mjGa=~!x-j^sS8S+j+@ zr;Fjnc^sZsjUazFq_U`PcV};GFJZWwxcv5sBk;s$O9^WT@||qafhLrD({nMRZxq(E ze78hcGyDvd{I|F>4{dhaIR%C+@hv1!TDHeZf4!(Wl6Lc971G}sO zcy;zdD%UHFFGas$L3rUkk`9A=V$sfn$Sx|y*`vB(-KKP;a{H6V^hHr#6+%lIFwf70 zguuKb8K#qFnPUQ;h7B8rUw--Jn3!aqG-sxjAE*TIG7%L6)!N(1Bp4S^6f-H$r1VU> za~}pxrDQ_Hj>u<8Opn-2{oZI;>0khsM9~5v5^5`KW=fT?{eOX!jL$~^03ZNKL_t(I z#oILM)8Dn6z?qEtw4Q)fBkR=Y(5=52y8;5MMk7mw+8XQDX&C_*OU9f4m+@aBfKez- zfKQB-C6iCfDx^`vv}73X@TUIJLMMVWY> zWUOZS$Ku_BeWoC=alxm-rYH4H74(7<3*||0fAjs_aL>OskjYZkEM3eSoN(&{6XE_% z0v42IAeW7c+JkAOmumeMz^`AAO&@FYNSC$mk}Oiel7 zlr0%<0tyN>iDgoFP9ZyGql!HexDud}?nm2@<$$5*`LjM(sKlcC(YD1d>BgX_?f-G+9FH z+NZQz0!P}9z>-3G1|YF7ax#}jNj2;Qdh|C7IMa45;X4aRGjl?2;tV(HXA6)N<7Tlq zFrDB5Yh532AM9kJi9YMuyZ5i_bnP68dGn9G5oT+?zD}0DWoBm6ZYIU}J$0xci^=Ou zAv}SUdnOLWgP*Lz?GuJ#?tj<8fecauYp|5nRuX_WV0iZk?Ae=vC%&JI%y*LU!Z+&? z8B2X(O+7a4NkIkYKfU;=ZK9VGLv^w(uOgt*^`%hXBY{2fP|j}S301?8ICbc_#WxC1 z4vx09$-y6SBBc^FnUxl{`<=zUaU5_d{htg9u$i=U-=2$T)j})j>#Ql zl78ayFFZUDxj7BUXNi`4TX%H&JP*H=XQ0oh_V{sC61EoRP#ABAT?{iO(q2a|4A#~- z0?i7ZM9oY4qcBjuh5gx1W9ki-z{vE1;k41Enua6iTx3vu^3Y7cj>7F!o)}k1X-*E z3g|Gd&%|(6w07(BVU`p(g1vFUzl-MFMPWoNzi)pIVeq`Et*m>OI)c>pANd}>Z-b*cVsm^te|8{%av>Nh#jv3rv2RBqx`cRP*MV$YMS!<#^*)^K9*8BSnHYRt zEZ%y34F=KQEpl`K)^E#(7yYA_?npp%SUa3MF&d9Nt&%Sd>~9s$xMn6Edg$LL{)s-q zBWzaiBmuGBCMD{&wiAB@GaF!(~id=w%~7BH(3=FAsYy39u9sggr&ek4K+)+z7z6 zel5cb3KNRGu>do%UIJ4V8v~n@7ba*ek_`pY)HhwT(`))Y_xGe@ngdsRK1Ydo<2IuyQLVX7( zeEgM6Gi7qHO4Gc=9mGjKNo1{ge{eY zsN(gftUgUxXWAbqS|+juDWJgB;_3ZyI`X9R2Y*N|~w3KS+8XWwi;Q2mo2q?q%NSORpi_ zRFz#SpkxWP2|x&F2&8Cvc^xUFr_4Dol|$hnDf`Y8H$Hwmj<#ey9+#k3R}Zv2dQX8zKofs7%*c;(CELU zP+XB1ZLX(~qjB*zp+iU0cP(cL`&ml7G-{S=Oi^NKrYzt|AWT{Fand{4D6>%DNx9%W$OdlvRJ#7JJkG-K<1-6S&b_W!z8;@_{t1>XUyKfg75MPF zb5YgR4YO|k!ho9@XAQ=tjR|n`CZqK5bmUa5A;76d_~5y?uE!|kRaIbAcn2(sPh_1t zT87YZ+yH#eCnxHcTy0$O%ojaS@udR-SJY#A#!6IkIl4T-i)?NeM|Z?k6rq6OKqE9i z{Lg`*wZ}#c!M~QSF9-9m|mZ2UR&v&Y956 z;HfvY04jtTK}2h9C&viLnn5)J<(A%B+ld&qdxj>fFViE;m38PU$f}%u_Bqrph+U%L zC4qu!!zo;*P?JJoVqWwmosa;Em@0i2TP1c$pg=z>^k)GrCjFm4Mqw+3msR*LH?OlBA{>a~>NCch<iBw#5^>l<+)Z@0E-H=0r{f{>6gf~qw|215?xw+9P)@5{=e<9MxMoLuPt^k7sh9!%J2 zz}a*6o{C!^UyU(CVsI!f6P0$n<_Q4rf8>1JbJu)aGO06Mb~$0_L|;sOcqxHaf4uYh zPGm3y*umZvhZ@Ro>HYU&rd7{uW>vE?PoqbVHsHzJjIHgY7y&u3>%5C~Y_07?7K{&P zW@~0fy74uV=vqw<*8_(PHU3BniwP(xlqWEyhkheS5ol>Ff-51mSQ_bt#4JfDZkQ*d zNove4Yb=!8Si;1@^axN1Y*kU5-dGx?iU5RSS1u#5x6=1bxQ#yxxVRtI4H+$y5s=Fq zvoYgO4;TYwY@v3`3p%9+)s=$i~_@3_A|-h1|damN>MFKMVY;L4Gf z1tUF!5m!~t-)u2^dOy7U#U^C4B#ScZ8f0m}c`NW$Y*^CHfWEu0`y?Xwi z(3il60F}T(_inN9^$#>ca#Isd{zyvOXUIw*rjb2j#*M|h>2SzQAjM)oAf`tEO!^^- zT*bjC!%e_DAUDGpLMWK1p@eo*-m_01v{A3k&# zcJij2l9Fl)^NOi5?2&5b(Kf-BpiF&MCZ1ue#Axw&1l-h50VDZEnHqHjHzu^k?Q0!{ z`UG?oHq`Ozdt-6nMxQ73-;`QWb$f0nH6__tBIx0zWyMI@5nQ@(-;z67>)^_rYz>hyH#m%=~kCMu2Tof9Bq~tsvJVSOj3`5z@3Vgp}8v#u{t~h5HURm%9 z!4r)Hm{oULSV#Plo(w;lVj>x9>*Fj?yYzF=ZsYxU3uEy}J$7ysQ$O?3i_T;N&^ke{rPE3Z7J>O*QP=Qr$D_ENI#Y^ytyU zl%VL&tfSW2PQ2fo0RbUtT|KOLFOno|Z@W1-)CW1Ok5 znu^{EPzWqpyq~l$qfe5qNZ~y)NdgpF&H$9dzDr`7ECp(%OR|L51Tty~P|BFvE%r-* z%#EUSX`~wXb8>n*!xCQquf6jCx2n4G_*S0u2S}AFC`}zfN{nI@HHnVp8xy;NiV2@3 zCi!g1XQC6Gi8GU!XflrD%&1_2U>Oq&)=X^ii=xDWSU|AQ6h)9CDn*?CZ>_W5y*^PN z@jZBDAHK`I@7{CI*=OCo_xbO&{_DStOb)mSp-MbN03y6ioF7k;$s81Q>hNaq9aiZf zq`6+6EI?tDTj9E`xUYp8T@gIISuUI4rD?d{*OdU#K{i3Yz>dK)b?bePZs!i8ODSh<5`_|X4pW9Uj7I^5P$EEjlQ~J{b_oTo4%h+_fftNnya!X6)NMhLH&QqkB>{o{oCZ!QrxDc>po2F73RC?=f|g6UFW2W z&X|!_t`QGWV-S%`gfVYC=FoJ^&378GA0i>n=hv(dkP^UG5N?m%`lK1p={(|0u})|u z0{c%c*dr}`ZdIyy@V)f!OJA@|)QLT%e*X4!d;Rr2cTA7{b$+_=+>z;5zj-E&9k)li zVe(U{O}n;fTX~-rY*;6f`TDd>i+njsXG&n|KnGJO zbb~Muvn1RG-^n>q9>OC8$ngL;fFrgbe+Rb;;6q<9&rsndvap-L#%hHCqbM-P>Da!5 zKvc`LNH-Xcjq3_EZ{si(+Dw#DftZeW2=Ihg3a%69FknRtwI)@&p1qgCL@Yl zZTc#LJZ)nq)XO>Ft8?cH97+9L8`lBw0wCdKgO7!Gj5=e@!Yp=~; zB58|sw0u&tz^qww(yOm6NN1ceUTOcG(h~Kj@BQGQ)Ui#cbop;?N$;*&omv$A2s-#4 zqjpY@{$*x5@vxEUrrVz}5dXe-N!!W;^}Cl#%gn;-}Mkp&0;tb7?>Q;FRI%>Iu)M4+Zk6Cfr>8^}l-Tk^b=Ef^^%5 zOVY<0E8Dh`+J6V}7!}rDqw)8#_SKN65`wk4gHBCYny|c1Z133n49U{#f|h6*zSACi ztjYI=S_MxO0{)eVtQ5Y@TjRF?HSX{_ZHWTKjo-R8zd`_0@Q465{2f5xm?Mv<3g>+S zOew7Qk+>4@q}KCXaHaqyI}I9`w$j8NpeX=S@O?bQ<(YVJf++K{wLCPCu*u>>joT*Q zLW60w75Qy#VX_dRv}`%G)r;^dgjaZfIQCj`rjZ#y8?=3T ze)a+j51)JfN$H}0o@l(L77A~#p&XFbI-UBj_oUX_woBi;q)+M9AY#nedjXILj~jS$utbp}LWX$2J|@uuPp`u4m6h!kUD!Dd8njc|XP^Bf5u)0X z8XMiZb+u4>hYlUIpTsu{9wpy%PZeHk7Bz4i<)ubWL~{<~YAYFp#a4?Jo)i*X!-mq6 zY855jNc?YLA*Zdh{FwNSP0Lg z0R*}PobW^epxh%>yw6QQfA{UvJ1twjBJHg3Ec#4%oQw;k$uBb707{U~BlFI%jwWF% z988Tkod>{U6Dw-oh59$33Gl@C3Bj2(fF{@GEmhj307ZneTzw*=K)W+`V;av_fjV zwpR^1iBxXw^?lQ6-`+1>b^F7qfBTN9r}UDhPM=|(p|%RSeISTJVc)}#-yzL>^n>(> z#4)#~&#Awyd0z_&k;>`o7BVwg3~hKyCB*3=H2!lB6mQuEFw-&4KId%fyH_d$8V)0U zI>sX&Cs*6|nvi%^Ss|yNyEct!)9*x^-LQQ%X3iSnw!;q?nIBw)b=m1pxinRM!Q8+nDxX04?p~H z0+gWfRNuG8P8g4{U6fG?Fonkj(sq1qY4-(j8X$A(`0rMErN}e`m^>0%Rw^gyi zYgpI@c&De|Z`uSgxY>zv+tPZA;KdU3$Q_;Sz_07#=n&P*#d z4X`n6L?{{H#0OQl$oH|8fCDDoxc%>9p<+j6e5v1?w@Bj)uW-xet%^lUGh6uJA+k(W z_5BvDTBuq;rHSE2ac?|Ac%eIY?rfmynP;9(Bfm1zyvzWhZr!@sA_akDfXSdigESX( zvvGsBYtp1i=|Fj7dvx!fTIqZh0)N!WL`e3fS+ml}5hEpK)GzhZvF6WTknX$pp7i2N zFR5LfB)4*yyk@;@PQv@f*xsN;-C7oRfG5oz<|Qw(W!;mm`NZZeJ%)$JO8V&_DQ@Lx$`sKzycUE7xSJb@0SV4?g%{BaR<*&_Ok6L*AzWT7c|2 zJd9*m*7vQkgQx2D4_*>rg4YnV@z(G<1RHg z6${HC#kBIv6~>;oV4m^)IL}-1 zD6!a>uZ&t`PPi|ym|{Lyym)cC=bn4gj2SZpkiL~h3?C^jjXSevf;=hk4%63;~#6k*XAQ`aSI%9zyVf*2bqF~ur>Cu zUHk?i3~AF&QFbJrEpx4SFxhw+6K6kLxXax85$aMg(G$jcX_SI=?vv1`3FsWhKU<6))+I&%iuOW@W8DkRe0lEtU$pJVG;`c_s~3)rhHg-kCj}1yEG&_s18cR~iRs z1O#L$Srn8Kkj|wWDQOm@yJSH^L=cdYMnLkvzVHA2-7|CV%$>RCdCqh1oq6hfKk9KT z?%w@+L%HZbKYvUcSeE!1Y$V7e+*$Wx$kThcyG|eW%MtvD(;|3AlEKdvqegcP-mR)V z*+v^dmK$LuRWGh7S$mK9K0PNPYSA4f;Jcb$d&ra<^C~Y5i_)Mvg%Sm9>F=ZPmgw?cNdRFJ?APWs6 zsZ}$Kdo6Spfs^&>Y8%Zba-S)YV}Jf+a65Ct&0voa&ub~Ohyt+m;ee!Tr-ruU6sOev z^|M5tfCY`s_?@NTi6>icT&p4N7pIWR{id9D`9E!|*P9FbB~zjW*_D+oWWTx(iQSXF zR*3#C2okn(3pMj-7tiKiqDBHt3`Qs<-NndT{P|*giO(L^rVmV^GrtlswQy+;#AdI} zZ{0^u4=GQK7zt5JdAx7L1R4&SuHJbd4z;OLA(QR}t0Ew6K3i@ZTu-9CuKaM7Vp59) zh9nf1-@FXj$cACi{?#R3yg6Ume6JXZ)rYq>Mlug> zsnta~ol*At+$3+c*0NehO6N`bf5fM|q+Qm&ktNIoEu5{2rx4?GoL&e%Y-&iX94vie zrL!AzJKcp8j^+Zna(w{bUg^%yIN#}cLz?_e7Ebv^XXUfV&GpV*u-7&g<6ek?D#%@H zv4^51-GF~p&9)*qV>PiF{Xm+mQP!G@2%l8JyGb7oy z6M3!LvN~{-p3R|Mjf)_`aIaC+%^w^&h(X zJ#P(3dhbr5qi5~&&~370Oz|1OFl?G;<`#EoZsQT$mr5(+)1fIT3z$zb)z2pup&s3< zR%aiJi|#bb=iv|A#|MJwBN(NhH-`etUwc}DXt4;c(q_F1jJ3nu?%~XnvRkCmk-V=# z-z#l$_soHXL@`9{SWkj{O19Hb&?~|*>C~`EwjeWPwpZ-g(5W9Z(WWe3pi6KCV0Z=q z(6nl)D#0Bt{{$Ml&IDG_kOX}d-~*sr`R~rd?!AeDf_2TY({tuL(D|!B$58=U`vO5N zb5ceCRkt52(2$?4CTz(f3G(E+GyI6|G>Sowmh}_~wQ$|zF9$-NIfnQCl7>ILeiBf^ z{tUwH)>Qkwc<~ZWR#+ZbbS{L}pOJ%gB?~}#V;`_0*SOI7;TuDm8{ve*R;hS0tIbK# zCM88O?abEc(R8nhSHi|^QRH+04cUy2WhT2)A zV>ve{-QPEP3_~$s3UfJLjZ;WR1-PhRZ2j3VZQQJ=M(=eh0sz4hooYJ2KTUP_h|8`3 z#$a1HE#6kOPMs-tczlI_n}F!X@n^eVOKUPlTCKw>&kAPFgKYIlAYIC+%X#i2k>bR14`{hGI{w%;6Y?oL+vXaxwvUn zluxL=nH}~`4sGWXYOc+2b?Wc^A?VJVE7ITf;3Q|@ z_{3B|8_jWTSS!`tA^9Fs>V2T9!s5S12|POh2b~`jOLQ=-HH;_Ukk0!ci?M(`vp>nf zj5SfuVVp4@m6+tW$LDCY=QE^0;Lj(O7s@{35{0kC`!0);>%9qWr_9mkV?L;JPn_aW zaaw(%(^jHuS{A`^$=qAO)|cjK%>qz7hSL7qh4d|4IeUM02hbS4} zZH}5LmCo|E@Gb!R*hw%j5>`GmzFS$4OX#`D7r2(i73CqzCsu}6NN}LMbun115}IB6 z^hyI{KAiA+c`OjI&NiS?R%G0Jcq5C8iUy50H9jC0vg(*t&c%WQvlsZ&UwsjVap!6w z6Qq%@xLghKvDv~kK4V^_U4JT_OXh@@`DHM~yjg5`b66^c1mBUNf{g4_eneqacxC6IsHt;E z@{((5Re7dDP=wNMrCm%BKTmurmQZhr3sw&{zW-Cseo%z}@>ke}T~bNDP8PZjVH zBv4}&nlsnso)$~VkkenO7==it;En08Q&}z5e@LyaTW~FNkbaus0MKS2FG@;%>$Xaa z>}Q(%b(zmx(+#_D@&H$z-R(vzzq9rCrLBGPt2YkA2}>bE+^H`G(6p$}L>MC?A_?k) zF5t(fpE<(Uex?U?mK*GkI5Lh>>$D-o5Jf?u%bmd7KIKB?;q?eBu@{t$YE0BG;S(si z-4^{I4(d2zskc}3>%_d~@TWQkTDZo8;|)t3-uLU4h(52pI|`p7NR&KZer@2$)M*qW zQca*|lOF0JaIg1d6|XmiMCfWVylwmlD1XpkwUBK^Vs z?6&_A=EI|J_KEv*iI3}wAHV-HDu21}VVm;!896)TQz-s2(30-^N&}=r=2_TQ`7!Gp z@6U>Z`fv%A#4O{CNwtAyJ})mK4Syn%nr<{ht4r8ADuIp5yl{QLswPu<-t!=a;4Zxo z+f+}p?#Pk_Px689Fv_eT*h!1^F!W?YK_LrEcnfjAD<{7z`q^@?#_sk9U20kh2?dCS zWrMcs-jR?3d0@+{jx9P-&^s8s^lf4vgGnd>J-pB?1I`GK^Z30@t|k#8+g{O{jF^Zg zch>Qz+Y<5pHEohtT?L}@>7b6JMoHkX9gBu;(Br?PGk8G8Ie|!i#Z?8BPvAmo;cv21 zabmfonph^DaMj2vSCPv&c7?V- zj;>b7L(+7(;X8y+MZbmIUOQS%N}14t#VI@~sb$B_FpY}8<1M9Y%E@wZtwj%e&k#JT zL=Oxs>;#m9I=ThDB#l2{k%f1*GAgPChS+Ir9J97l z{ZT7ml$dv+SH@#0h`QF^4&Uk}WX0L`!#zMmWYXCkAul;ZD&l;Y;qluY`arAej*FukD{S$e8VPuh{1wS;6T+qeyNKUoI<7+$O8I2_KwxYG0a5&^2^OZh zMOUkEUG42ux75l=nbE>F1o|rXXdr3P_s#9O59B;4< zo~LGtNCmI$qly+hr<2aU2os?4DXHsa(3Yx?@82Z=&t&+=6O6uN_5tRXz$h(o$39^J zvRg8g@;JKo$aky?OJoCnL<%dGqh@t(k;fAXRu$6ymT8UrN>|z`DlYu^_49)V@a01fB((e$Iz4Kh40G{6pKHVJJ zX8FUia^Lqw^e=V2%JCLkhlk>;sM~-3WfM3B3s(rnhc{;gv0)L>=?*I~=^xuH!&fO8%texZAAE z#)Vyg`PgJ=nA3R&olAx*KJ9A%-lj-v`IOJzVYPcAx%`H#2Hhplj(vA6|P$`6by{D zGk&Lo(yQyvIc=A?f3%WBqgMVJiLT|V8x zjy~z7h8mxC)jMMK)K-K4_N5&Rathk#Fe@J1ARUSE!IU!oC|1<&G#BSCx54 zyESde(jGUFElxvG};k2i@5*$%sY^r<;BKb6isa#Bo= z^A2&>=j5>6ug8p+HD$4ipf{fr1(DyMYa3bes^OFM3MqNW%np$F;-WL1EK zu?u@2@d!Vwcp2UUJWfA1;oeILOfeVBr1YgY>7 zPK1Y9YLQmafgvhZ-Z@0FU6g}LxEC= z`|C=ggaJDZQ|BcyMER~fMJ{)&8JX>{zfz9h67-;mHn&@kRc{kBa)WVptSUcLJ{y~uD)9Bye$C~RcDl`7pp%3GfOF3Q`^SuAHydWYzYEP zF)bh%qV6gUr{3HJ>DB78E!N~!l~92m`dv2q>gF^la$k9mSg=}x>kM8>`V4{9!zRVvHv{9P}c z+4X4E;5%XZO%Ivu=!s%;CkbaR1RiVQ{&z~y95s?#K z3<2;Q3$Q;giIi3LoasT%bm{$mVE)aRmsQei83QUE7Z%#ks%<)sHZLGXCB437GfY)9 zMwZ0`_*nIkVj}^92%W}FJ~8apre|QqiQePM{1XhxL=yF~#p0Lt?f{Amq54#?5YeEr z)38eH&!H(RTmO5d$7-ZDN-jnL(hMSwx?*oS69BMGv2PNydfssfz_0{-%@0FV`|*YG zdZN`LsAY8^YBM5|w$m92{jUywoiNe;Pximt-Odhjbe$(8b_msJ10nOkgKd2$G zFCG-whCiP*i-<&5Wx1xWY<_bQY&KOw^4do{8U#jM77Q+V&)iw%T2XpFAv&NG&Q#Fe|0@U!Ze1W>N{d)awRn+^Q_Sdr7JbJe z*NXBfyO@n(YODzPr1k7cqhh1tu4!(7)FMujuv|G9w#kd1B!F{&*5~L!`s;k-nwmJ? zr|0rG&pBQ{I5!7~z;@LMx)M~t@lGhNP;U9>9noXKFQ$U>-9rCbfJ-RA04L!U zFMTA_I?IPS-cDmg_JN^4J*7RqCdmWUv*yjX;|s2kGIpF|9w4gO(>$s)vp_di zq6axEDXgEG8lm8|d zVYuh@d_O@v>FQV?A$Py|!28MbK8ZB#`3chOw{wMH==wF?SR_yc{lLO^#$c=R<9HoM zGZt=J>1UBO+QJVjHYU!%&d1Ix!h+qL+QrRHUO%6!lE0N{ai7PX$0eP`1@PEDz=_80iE!az z4!Jtqs>eLm3BEX)*M|&mjDZIKXM94FYh5sZ=wC`g2H3x@=#u*Kn^R73OvIRYXL;4b z;m>++V;OwF1s3AAy+n5)Nkv0uf8X(cc3rDT0L?ix0~7+pr@yYI2L#ZtEO`wu!?5D( z6)b2Y45>+Ii}yw`RzbXv1zkLNm?iB^wGIb3gE?j6n-)GQl6{>)2_L_&!~fT4is4`} zy6bW!XqvRQV}_`mI_)OT`2pKCRm(-A`&Uz1R}^;HJOdScY9eUQM6O+|Cr-4C4**j1 zchF#a*xyXpsQY)u8~+UcZMS(`$Y|b&S7?MkK6ATlNIHClUA>f9FhO~0m z2_>Ue-&KM32lbHzBW+GV`+p4E2NXjLGZ%g~V|%;Ha1G58d0@tdHS3S2Y*_Vlm%X66 ze?PQ;&u^ZE-bFE7h@^eZ5sv?#)tCs!cVQeQ{p9CUYOry-6IX0_JO1Ne!V+8JG$Q0{ zkV81Wm<`x3{6BXK_1N}oa2^Y)3~*7F`$mr(5gR#tTM z^4}=uaV7u02FY6eCEkDP`M0irEw=`HyG8Kdp#D3%y}|~!fM>UE@$vr~{okg?MjZU# zga2NwsfDl+@X!nHXZ$a!f8y(c?cMpW=zp)7)}gnAtOM>amzk1N0QS&Qd#qZeZ2jv0 E02=FG=>Px# literal 0 HcmV?d00001 diff --git a/imgs/operation_mode_two_nuc.png b/imgs/operation_mode_two_nuc.png new file mode 100644 index 0000000000000000000000000000000000000000..1c2bf9b5b5d502cb99f4058abd4727023a913d47 GIT binary patch literal 39502 zcmeFZ2Rzk(-#?C0C?w>N8M4ATjv2C|va)wLj=eV-$u15>nVH#pg=`rIS(UxAD?7@F z)c<{q>)Z9czSp?#`?~M@`rZGlN6C4A-k19C=3ez!a$RZg`+0Giwt}D_oix zDgg$@{Dn&$(FT05Mc5qmRRY`P1Pj7UZ*fE;b6JFqrJ|GTZ8aS$7+gUX#xE%I`_Yca zv~j=Th_E+TuroHX216LTA1(pL1LZ#))cEdUivW!Gu))mnc%GwaF%7B~9!Cp;fyH7L zW9DLEY~pk@+F_Hkot?F_h5es5BJFH#O^`6dPr7RJuzhpmEqN6W+XzG-4%W_~;~IN8Hh+8~ZQA2m3cBaH3b4&Og$ z`t?)}>3B>{M>{((-Y*M22Httd;))-!_#t6j5!Nn8#FatVx*)+0j%IgqzI#k|CpQZlYlJQ6C+TKx z;cTL6k3eExasylj+RUA8tih*4Da5deJ>s{8AB_ei#M$JS4>42!ZG!$r)*B{vHYU!F zcfqj7uR{fn#p{TT;YZYQ`;8}H$8F}n@B zk5?viw2r^Ntm7VkzN*8cI9?LM+S$a>7U66nY3E{V>~#3>@AJ{|%0N#b|Hs?<+hm4I z9rQk6-M`oKFE|_tyCG`>vvgE&7m&Mk{^u~2gaQqk!_=T+w8-C>`bHo8CTG$*& zyCjA+EP#y5BaBR}mF%1>oDZSY$j;f>&Ia(8HRgdN0%>LDh@ps-owc1K;5TCvQ-q5( z5Y0c0AYpA`h5=z`I}BSQoa_%V$kf6eqiG}$CX_gC1>k$w0$wn8cE%tWKxKfbGDt^v zE>ny!aGAJ(k8bvy0MDE;qR1oTVsCASz#IzD8$5uwWiaA`d4m%MwLpN5Ks6cJIU<}b zTunF~?Z6(m>}`Sm0Q%|olJPgi@}DOzJOYPPA2B6NhzrIC{pHV*O87-~1df`1Wl|U~ zoa;ze9P{a~qJv?+zYlbv&k+~>hnejUiFLG~zr}1Ow#E_|#RCo*X^n7lvOt2faB@aC zI{#(!FF1Cc^nQ&&wsq`wPDu0qCFDiHD2t$k;ia+R4tv5ovNX42J9f zK5rb({@2%VG{f$ECO%e>zbRs79{vMZGXlSu zVem}_gCl^BQUHb=0m7I#9(Mth{Zp^wHY3c_gZGYGj4fP`n^ZXAPz%7&Pz4KH3-F(k zwF>~V!}-8qzw|sL?=QIhcU1ph!0mrbYW|4^0)~w+YxFvra=sA+$!;l8(1tj1Pl>+>z<6#)$Z*)9n#s6bQ z2VC&TkvQ`3_;`N@0{{G=5M1y`6CF*-EAYE1|DO#B@f@qzUrmhPIr#q+JNZ8=CnoL| z&cBEk_=J(J19<|!|0Z0R5C3)9Iu@C~D_cjF+5d6Tg8x1;_1_^{e=g1N>+1VnjrGIOc{Btwzw?6WAnB3rjAz*3Z?0omA#sT5tYzI#6mkiKfgT~*ChCenT z{z`7?pjieKt{hGNS55f8Yiaz$hQ?9H|2i7}!+9o5;QfC-3kd%QLYV)n+VVet*2ie| zcQxO!r}|X%lIM4ViJ{-6G!#we~7TFp zU_5`G-{k$hvi%p*dGIHx- zrB{;5YGg_w1nlh6*b*76%wMU_Ppyb`pyh5luDzGvT3!Az+bMU`wKwrwZf|LgIG!8SBSI4q$efe77 zF<{-F_!_I0G0b`xsyf!`VWo6`U)=uz!({?;_H;D4Trqij0o^(Dt5u4-6-m&+F(Eu; zokzT77?gj&36?K_$k+60(ke>I)L}#^Z0em|Qh+RxCqoDGvT_FTkgB2-%^sv^k5(4c z=AuO|pF#7>+sW59c9)9i=AZ4Y*4z#vrd!2NuG@Icp^~S;DYTSdCZe2tlU)LGPEj!XKZ(>Flu|!$KVt(?G?94?@AQ45Kr`g!`IP(62__~ed|l8I{wTL-OpHTMqenO zyS6>lNvq*gq<0Pv!mV9;T~Tm4fRXp-dK;a|RHN@kCwIfmhv%8+ zUUL+w5urjuNguq+QDtG%E=~8^UC2_Yw7nAtMfmZWzY&k;v$|a4wiX@5p~>z^p=a;w zwKZZE86BPZBW!7{>Laaoxn&f!&-e9>E_iQyPF9jfi`6XOGk%-+P2r|tj%Eh_O(+Rk z|Dr0R4CHyRUHaWG9~`^+hT5%)>MqBARRi?m4|mzg1r$&am|%)xSAQL8+Wwfq zapob*>r91bC&iHP&Kq>z>Efd$$Q!uGr+J0dvIRfAJ|?=6(Q^{f%jcjytN2)3UwXx2cuZd3^zy1jQNm^Py*JhGew&Y(AGIn{ zhuV&mW?a!K7AK+=$u1OLeK|X~x7N^0ihiKUu>84$B{@5e&$MfY5^myU{8~Sn+n~@$ zC!mA`nbF8@0S@hIrc#l>dv~dB)ZXS23wP~jN#Ab@mDA#lf?1E$kZs{nsZznOdlH2+ zOuOT8pg~P90VD7@%v{fK+gu#TaGZZ#YCqj1g76x%sqE;xEyn2{Q+TJwRm*?`jbJ8d z!M)rx9Ev0$&8k_gmJ@AhPA8z}(tBA9^JaYveP3yptd^}LFH?E?rEQ}1_)F#Pl-ok{WD?&gVY6+tp7Py}D{<>F2KRDIrz$7!)%XdSq0y)_ znjDL#A#EP=(|xNMG5WcZr0$CTA0;xQ#G4@WxYXHLHMRAjh?Tc$j!bh}hn8nPVqsW$dWNpl%vY`%Sl{f=bI55Ixm)q@Tj|E3Y)L zg5?d%w6>c1QvD~mH>^d?&>q64!4I&E__R3K>C_zCL0!A86LlWv|Cww1CvEZn!Z7vz z>v#O^VipX%*eom-RLV36zgh1(t9s9lU^K{`Sr>?t{KBT2?VuO#tV|e{Twn+}lgXD0 zIeHn9`FF|`XJ!aGXxs>+--~+Iq?u#s2SNvzjJca*k+MZaUrIk*ge2QbGD;wcXs#N2 zQ*4%P{v<%hGEaKB8Bo4i;@^I{xz0g?_DEb(KbXZy(5n9axztuvbRR!7lhOvS@(jY5(1hbRgspyWN*jP$|l4orhy*t3@v;@f>s zEJQ|@-a1c8O75k+?8Cy$d@DyKgNcDbV)xpxRCW0(Cv$<%4b`pXku?1iDa4ixs7;Ue zq0kSp@0Mn7=6}OMyHiw7>lW(aa`2L{baXr{wKK@Yas0MHo*~n{=qNMBA9)XYCzn5u zwN6-{JD8YG<35olfQ_OlVVhB2i^2Rjz9lYBhjoX@3NdxrD7G|x?wc6G*l;&t2=j=s z#8d<&U_DH~GL~G>7!n!n+8B=;^OVnO5YMzFCnrbcg}JiDo8r_L7EZa}x0Y1cTrI0> zojaLEO1x{BF05l{0Tn6HzO{7EcUXY2@i}p0D$EAVlO3 zh3Wgl+MeqFl(Fn~hoq%$)w~oHF4U_E;bT;ca6Xe{(it5y(;CVyI#_szqu{o%LT)(+ zvs9s%e0K=xm2(t|vTDTNd1!a1OAHt`1@0F!7Mo=IO6Wv;Ybb?g z*?bBa0E?`;Q^;_(x*uWv@!W=9-`81kw^qk0HC@-E>No-?cC*It5(9zKu6y4GF_^=E~4Uq~a?synycQ)dI-69{r zzTUeeXlhjtZ|aA9lZ}wD6{i99$WmnRa;b(06AO!6B<@&ZjcW%`eNh((xwDz1Lzv}$ zZf(mtMi}2xl-DRjij%|ju=sdgt$V{)C}BSccP?EB^GjC0GJ?ZPyTOp@<(T(`@$JMX zD`4EMeql!mWq#ciO5ihi1qrKL3V*fHJL*z8;^%12HblTdOC&ex>UJ~Yxine885XkW zou+k4`0NXR%M9F;4>`!POkZtDy?PlSxVg6@xo)}j>|AmQ4&#a;`b6D}e%@Q6kK-M} zTns`#a5gR2ew_qhzxsveV7{x|R`vccs=cY^?bmd|(H%Wer!(B2pmx>}XP$d2(mgG| z2I+je9LFt59!oivQB1yiQ}}Uo$#ORV4f1lWQ=1|=1z@Ps>MkM!L;kSj?X|HY(+=r^ z;+rZ)k-WC!!=l{P-(>+MU)2#EFh@^!JU0S`R!kDn=3mic*?Z?I*X>9+u)$BpJ4~c7 z3^x$x^^`bES*BM$)3h5ev?M2#w=YCcduz~9uu-@BIcN4*=eXes!y9<%*VoU#OOZI? zR{Loq?;P3#R{;CqsFI%WO*Xl|LhH$fqqx{ZZO^?v>N+GSI9pEfuS2FAqJA}+_l)zFBF2(cs^o1pg`+;>i1#EYwt)@EBJ` znCb0vX{Q`Lwpm}jmprYn<&^VplHiW)Z#CCH9&z%+MRbL)2P)x3*G%vE*)>Et^$6e2 z)hyyN$rrhBj}@FPcl;@2%_g<#>Q{eBjVrv!?dv!3cj;TM+#Sr=J5Imev?DCVR?TUgC6<;A@A?3AahM;Y$rL4dk!|FAQFxsWHrOM%P@A7{XYh zlz7$Ux!3&gqzq(f6C06`YWBE|43W?a3$(|*`et>ahWzo$0EPRTV9F9ss3f_oekicN zW$QfJaeX;SPp01|0Azx9$z{zUzh}9H?lV{P0p{>7_ z6=in#-pS#aLO&buue*7E+$uNs0z9DP0%aNM9Qwu*|VK!c;8t-YpK+BPfrmd{Qmka96KA;fABu`XTD!? z3tjXz&NU_cz?m7iA&Rn;;x-`zDor|~j56ZA=6VnxU?suaq?fKMI#IfpMn)TbcerQt zSozJR!f={cx2oJ-Z_X4o{7~r#{OsweVciyjZA6WWyLh4WzL!+Z9@+hM4lEj$aC(-~ zA)~ec2ek>dp=W+%nNyfUene~R-uy&A>cj{E^KfyiEPj+LoV0$&w%4(b*rahZoQ3Y1 zIj3DHHxpg&-5c?0q5~mk%o6ehzE!T5nhho8Uu`89ViJ8u{8})k*RP?joXV9$JvUv& z-XjOVWgQ6y%jPHSAersbbY12oJXj*6oHuEUO)Ff@ap1^=Ro@f0NaQpw(UvO4R%oag zQ}ow=Y>r!NM}OsG4??M?OLdxb@5!z|XYQBCDfY){Z`LTc91w|V^MhVSr77P>hCstJ zC)-2FIns?gA_*SchpCv(n2DdyV=69{O!PLx9_GU0rhT_EQKoq(6nf%baI=E)`#nU$ zvR28BNGoP7e%GAIJ0pvy$WN6B1UA-thv237G~u%t)A&)TOA$<62I7z{5l87HPl8qs zOPKGBF=O^`E9G@54JPL=mLeOrIDIZ}v*p6ml{W!2niZ#qw-R*=wCzsyJBT$=r+!>C zxsLiN%(___C71rzK_N<1ZxZ;r*^35`1%RD9Ku7?15N|eHrpK;fKhu!9+N0@I$<-A` zmxlOtoc8-A`%{X9SC+)6HA0d}+|bcxU9l^Ia7FBrW{P6sPnR^Td-K=rzTaDWUkBnJ zS${Ap#vR-s8Y5oAQrbh%7(S$2f7N{9>Gq0d!|B)+N^bpg_7%;9Th=2%y8h9TUZ599rcHqQ~28MK5G zr_(Bx>0pr!&DPXi7zu~x^`$up>YsL9>89VZrc6Eaz5dI$k2ln}{pufrh?Kn&P(0F* z8+?vH9i)}!GrS@`zdhX9T^!OxbPKE6^(9V&>h$UR{k!4C{&ln?L}J7Di3qg~_j!om zt#0Kl!+supnF{GLE^C*QSWsz;Dpl{vFdTMpJex~HW(D8Mr_T&O&o;3c?8Vbu9-bUyKsU%cwOjY!t9QVe4Q__*sJIpW0CA$$>&NrqGAz+a&8rK$cvL&w*`|*Y}=73z-MBE@a3?sW=#k59<>m z#M;kHd@eEDrnMNzRUc0OGJOZpLk`ra0WQXZnch2#Nbr}*(G%_)|YR ztZTvz>~6G5uIK7f{%6^}PXyqs;Qm<1@SM-yLC_uvMv=|dh?`p>c*1JFP~3Vfgvbl2 ze8@$3&$YefKkA?6^K)OoiaD@Om+NZ{jWAl4pe0NQPBi(}U3!(^QrO zgL-h^Xul|t1&4t^q`29w>p=wc)7+EW*JfBVK1V+D!393MH{>KZm%uf6fCGQnX9t2D z_`v$DINY|&Bf7CG3Um*c*GB8)bdm?J*1o=0;|GYV)ByZM_R=4c5VJmfVyegVcr|lG z)6PUz($X?UDQcU-!rqsS(88|EpN%!j+x6)7)dN5z|3rkS(Eg?v75zw!M>Joj<;I-mCo6WKzyew@yZ}t0`fjDSGmx zF7WTw)b&8hjGA_e&tBxeQmT*6+fZxl1$r-}_6sSRL5HCtP*untYF-_6g;uHfZo#YHSuQ86%<2hI!Emvv+|TmB)sUlzW#tRZ^BLE z0nS6eicIUM3Y#&R!WWMUnNXWo`wpimI(INll(Fbbf7S4^Uc0c#m0-95Q8xBzG(i%sAL#D==3tW#qToz?jB8*)URP<`g>xXy4RfVwt(VAt5 zMOwz{%qkQ5m($zTw??7>QwQ&o1E%iT#YZIMP`Khp6`NLT8KB%963SnlkPc+aU%OvS zlZm&{ENm_b5x!_VUAV;oCTqI;qrCyp0V-3gC0g5wqR3MxizU}x3MF}t^%xMFMe?+Z z_C>_9^?hl_@?;D*+#+s&38bK(poBBMORd$9TO5@@w$o%vEPNdsVmDcRXY_>yX%%3+ zNI0^NXcIF@!X|0c@H?x8(hQXxBjzZ1TH@8^)9$hOV{2OXVKeBO?bXXDIxnR<35Udz zvRBb#1NQ=eGySDr0-_s_;55ePpp*9FgI{|+6t8`u>Ss{C-qp07{!yeFu0o7A@$PMP*$Ap97A z(dRUPtH7hT&I8B2kDdZoJby#k7#-Tj$(lxQjYvLA$jX@GHH!{Q13>@>9+Jx@)HZwmUd$v0p6(Fii=bBA z92z01cTa6b!EyIw)0+RpVI6BGP@JCv(1UhBh_{ z@}`kp7q6D@LXi|InN4apNZslUfJIkK=jqo?t=5*+P$3c;Bx3e$8!+0$Xa7<$6uoiL z_-T_YL6^rmF66{(*9SNqe&aUwk;8atz-edLz8jbpgRFU7%CGkpfkOkPyN1#U6d)Y5*gF_UH0JS_>9Mf} zu%$8<6H^e~XRwE&pF0Pz+N1A8y1b_uBu854PM_p(weI$lI%C>$n%KnH?hNP4K_cYT zw);+SFadRIK#>^4FFppWI2O`zasyZrvf$f}b|n`^9&SrOuZerKgZ}bar4MT7p5GLUji}=EymciZyV1tS2l?H7;og8cWg8#O>tX2g zCh7}w%Efv_+EdHU2|J12A?=?-n!`@;Ao9&Ve>;dL>`J8=)>;m*v#IAkZP86>F(vL& zArZNcmnv!4clw-7Tllu_GttNbn?7LilN%SPLoCN$;Oa!Jcl*`Wc~gB{nBFe7`gjXH zxlG8kqdWSF_iknna3hoIt@FvBm;uP$t-dp5sMkfHoHAT8mcKTfIbYtlF~M5^B_1#%(^iTDt#HH92}$Q4vfl!6&=K{T&l!h?X)G|Q+tgd z$EAHg&2UFiuFpDl#%^n){LPyn(KI4LxnZtX{-XKtinVgHuALg1%=@2Q6Yln|ioUC` z(e*G~UmDSIj(eC(I5NzuX&1xbY8seH&aXgRSJ(aSLwk?txvZ|UYaFAc<6I6o!Sj;P8Vq?37O+J>OT$*CN zpWt0k;{790C(~5os`HfL$TJ-~YMm>^dG0UDuTgFf3vWtFqrI^NG>lS~$E%(k(PX0w z1egtC&XA!TRN6qIvA_r&`)~?z$6T4^y6(>mnqtMhc992UHD91|6;8B_B%-Uh@;0Ay zcS_4SxT|iK#uJXMn|j{5SkI{EYcv^}K^aU;3uIx_1j!k97RZ|S1eX#t$XYc^p_72G zMfdTGA?&<2ez;m)2{vy=#oxc2HxSA+;&b7YB$v+TYrDy77kmZFMV!h2-vM8{>hZcq zY8i6#4L5ul7^r6G-K(V?(egn+r`9J?2tuT)*;KP~$>Q)YpjI-hcSNV2Sr*tU;Rh5m zwDhn&^47>_It_9G4ZYtK_Jc(_LMSUObohmnP{cKB0a(TK)r(lufqV!|0Y=vk1 zyCREz%xIA5vOZwmufZVK_f8>6M2OL>1lMr+B}afuTioZ?wK9Txry*uPh$d~Oa%~1K zphC4y$K#+MFpM>#_bXoR)SLCvZrXJvt(Z8(`mT-DJc17P#e|j5oCXXt->`>!0bSud z``$yJJv!SpAoBD(RTH04+NIPx2)1~wOG|bH<2QdisX{P~#N$(NYN)lQz=UN~=&?pm z@tBTo^}2Qq>zkpp`NADWYc0y0mxp0Llbqk;0Q0VO>&y}M6C+tR_Cdn7)N{>NyTUlG zny_ppl39+R!hc30Stlc+s)dtR!@41eW~;GOpd7!&<9?;(0G(q8^PL1W#t%avb9QG+ z03xg$j9e5e$3wD+vW%6h<_G(l6!blZ32P9q=Udwj-!bF%Z=T;Otk0)$kLy@2A*Z^v zN|GzMR{Lc``OLN*GiuWk1k}tld9so0y!ml=o=9F0k^C~B-QaYNRur${=Z`&<7sX%~ z1o7}qdD}=#Ma}?Z@G3GtTQJsDX}>GBM87!BJPdm6os|T&YCuU)gs{&Kug%XyOOMrS zAwL5}=9)d@X-bvuUcoX-fA=D?8!14mscLTTH+>mzmXQY1f{BVjS|+`JCcc*Tje|9j zrP8CDukJADJ1aRrW*A%RmF_kfLui3z~yS!yq)Xkj|xw zTC+6gh24M-eB^XalWiLE}i>k@lCPrbYvM-K?40HMn< zI|rQ2e1tq9^?<7DvRuSV^}E^<+=f-LOEXHIqxTGIw{J`LuKjq}O{e8{n-3yC8uR(O(7|6!}ru(@- z*$?>qqm#TkrshE>%h`IgRN7THON8!4g-}+e&bP~3W>*kW56fKVu-jw#PM}%mJ2lnl z3m;d7JXeY1;rWs1wxNA-+ZL4l03Q6AWu}CQVn2cnWZkxl<6j}Q@E)}&oeUwIm9KT? zI9uZMk;}>z71(05f-Z|L)xIwyWKTb^J4UqW1gKFE>-gNy!Q@QK%Le^s|VZ;WAIs( z3|ZY0WaG

&c2cfqaYoh0IT~yHoUIa$}!)+Hdmmlm_6UBVRqU`q9#;Zo(QNE`BR6_wcR6{LoEL!4RoS_#uUz^#C z*CZaSCqaz57aQhP> z(~}Z;Eh65=G$-NigdP`D)ga!f1+s4j0xXGly*kMDTBcMY{u z7p(N&zDL~*m2nuRjSIH~6M_bcs$pj))DhHN>9obHlq$+| zv(L6Y!jv5?k`JG=3UCMrr-GZJ#=W;Ea{E$JW^2EFc=oRKYAmlgCQZLi-~1A|&)P_W zT#Y;p1&|!i(=?RICqa{3&AtBce5t1!THDPvN58HbqzNxep7~LQ0&jJuH0@My^f}3k$VPTQU+-n*+5D21%zT`jk zBth=ULi%lb&m$3vbhc&rn{bKo5WI#& zpS75%F4s>LwGD%YH%dG}q?Vr1z#hF710fKY9pSPUo|@us{E31)xk zvZTS6Sz$f$TvMwVkbsCL=uL}58x0F6CQEA;-ggoLagG>?Utt?2Sz@3r{I%vKuNR1K!cADrrJW!XMdAu?Q8EmKz4&u zH0X=`)=J35NuQqse;RPLdMO>0JG?705c_37Wd8HUSb_}=^Bxo&lp>O)%P{9o{RV>fM4Ti%IldeE`+3_o~u)*bj;jaSPq zQZ6*tAyN|g6K&Rzi@7tiv$)BU5soRkm9`r_!fT(%N3bvquh_Hn%=%OzT?FUe$saVt)q{WD$5hP&1&*zqjW)r7mAv<|2#ZtEdm_FaH z1;wlEx0IC5AeP^J!ILu_A?#TqIH=jV_6aJp44KBa4wVTR1-K)aoz#1y27lJ;K}>Uj zL~w~dUpJBuI%h0t@~i7;lHdIj#hZdQx0MRrI_(0ln9&A$P58eFf+F;a zCp0T3oyRza2R$dNb^S;8WMkE(D!&6_3~+Dc7udQlR(xd4NwW;m^}m|?dOcH*+`iK; zpybij)Zah4+!X6Ao{V!aX?=9O#Y1T3WC|ADRNM$L^?;6mh|8E$KZH(S9`bBKt@1k> z8W^|F*ru}-lx6FAE%It^=1acpv|MUCqgcPc7zUCFEh82zEI*j?rNp%wUnqZHs_nNh z1Oa^SbTiqh-R=Sjn-t!p!cyIPj406w!UT22ZF!AKQL}>e$pKqJ%b#o%V;8FC1)2ma z?hWoP9xQSYO=aHom+u{{bdc)jot43qtz^d%n+VL9$R)FaqQZ+w)hiY@`M&6Js{T{5 zvkUAsV94RViAL>t=VsNvoNlsd2gq>*DEy(DZcR^TvKXrK-L1o<($}f zwuTrlyd(T-2vpP>18alFYVbe7_V=oYrmJ;a!Ft1)mityDb<8XuYvHWFWUb z(>f1It7AwQW$;YjY<2Cd)~rRZ&$h{7O07ZVb95(Hjr>Twuv=lZX-6cpN`VgF<`=#p zJ;oEK&OW9v@KU~`TBI+kUFDb&GXck#_(~Vf7+A z9|x_7d+`g9l*9J;^d=PpG?@Bi+|M*Zj>Z>Id74FqSbLyC9aGZE(6GPtjEqA=-kwYj z)ZF4S;NPba|G8Y&i-B;*)vAxLfyr(R)~`}-sZLn%uqyz=K@{2?-#w!y4XFbToW(~% zt(ArqpcEN{g4vWSw^$OHhV(rP{GhU7RD5%dz9&i%%|TZn7=zoRN<-(&jJJY=~b7-YD-v~M@f+#P)x1zxD_>g@4hA|jjviqU&K|? z2lk4eH7HN#1=lcI{T=pO9+H}T=!)ZUSyU@eClHkf+sZZGOu^Y5^uSY(4QfBA{ z>`3ZVHKegj<1`{FVWDF!F> zjSD`nsox7InZ#s;C)c%7IQs~1PizsqSU&|3ph2IysYkEw+-X-o@l}~#fBmI0W{JJC z8|3br03~qWKfYggAA=y?{Urw&L3fKrT@^f0Ru31L&pmpC?}CAkUmuZx8zZ}9Z!j}` zE$^3?3xMrM51o+cL3J6eIpWxhaYxNJr2u1J15845Aaa;s{5u3 zSeW8iFD$Ck$o5+|D+Ian8JL}{z|T{eEK%HfW>+79shb7-Tf~pNu3Nmi1Efu(=1Xx$ zvjqbxk^MsL(gYac>3l3fQMB$oI01TiGbml8Jt#=z9P7=m{>Ima&9TKlMvuM=A8=mm zza<-eCC9amp^BKN3L$l4{&iGYt)ETLa71w8-J8h|DY*(cbStb2*#y4$!5k6e&V35( zLL`e}WY5}HgXHaoKRyE0J7uWd*=qC9)wq0H&$ktw+}l-r*@>T8VdVOpmETRzq9U?s z5Dzg$^Yagj&y?na6o*_O8!$E_tt{oz%LB4m+gW_S`n10fqHzVq78QP+JjK}JThZo? zFXiKS-o11{MvV}D3wM&Mio1xidpUh7=T1$9T8@hJ=Py8qn*bAq9h>C68Wyrv$Z%}) z^K>)$<223#zIm~-(dlhVxOj7OCN@N#?O-uJy9+E)!&yE*e{3|J;hxLB#FH~0HG2NJ zkxaGWD;y#B&nY;ZrG*SF5u)c3aWn&}7f7ETi56w55bBMy=Tg=)iD%-{a37Q;vYSjp~dB7RIFrFOsT(w*CWHOHD zYplmA6au*(zdt`6P^+RVsWzuCZA3>l?*I8@6JFJ;9dIQ=89vLVnmHHeND6UicSZRwj@c^YWcrhiYSKZ=1dHR5>Xw$o=MFcIF3D9BcgM@}S|8 zCskz4>?;b>LM@dFhgr0Us_q9|WB|J&xboqmbJ}zWpouzy;368&YA(tVE&$nH9FVJf z$ZItyU+_-+#}IeJca?kJ*KfSaPl6JOLB2Z%0&D1@J}9&paO|{`c?Bu;UT>vXlo$fa zIyd^|^ebv2g4VNS%tigtcV9uWZp=dPD2oqQ)8+v|gD`UF#600#_Q z8Y{{sO_l20-2{=rk4uF$iiun_I>k>3g?EYxkig&3-uki_iOGULefl)J^vwc>p-hRS zz00@GgNXK}?K}V=r_jSP;8Gb22X4tV3c2QRu^;ZZ?aR1h84*@EH6QFb-&q^QQ90f= zwBorRqMCwjzFgbb)Jr{ z=*QUyCpPYX21R21gH~hr^e3=7r$#Gmo|&+0a4}k@5$IF63@JO0^(nJFu>tle<6AtC zk_x$=Gj3KIG2#7H9o>tP5+;fdcBvb75kR6*X*!-i_qREekTNJgN_NACUaj|MM$4@- zBm)Wjn4|!_sV@1zzR0{k<7rAwfE;c-yNl7iLQWs3agoOLIN~MIFF}d%;u_G^PcY`i z{44QQlP*`AJ)nbYbyx_8PfQJ4`%NN(!V>Rdx$}OD!>ElqbKxR`!!m8hH4^~a?Q!eL zK0nyN?ISgO*9}=A{5RMh_n|yxh$lCf1`EiSm;ID*o6ZEDq39t;k5$@f3UOX_{*+=J zcp-od3u&Ep%AF)yT%zd`6GPLc(5szjU0da$S%nj2woDRDrXXg+{VB{#hRi1P%ZZ1} zAax9)XwUCG2=`CF{NURR(%sTBmq3)h_Oa$&aOF;&6(_C_S|+o6VF9jLs2AsQ(dgC9 zIS`#`qsB%Go1)H?2ow997Ab4Xwt*A@v)85*eGzN%pjUhe zY~@)zLVFrVxp5FpU{ARJ`1+?V2m_9YU?-=13Aj%eb?(PQmZWpy6vgGCgvdFy)!~vf zOst2!<^GUl;<*bQ_~>C4azxOWo@Xn znzd_D`&~q50;m?>*VTkf&ZLPEI4Vp@OnzPHQ_pvwsCFTU)N=8Sg_&mH-I*hYqszgC z2#WOn>spssAhUeuPNSDEtQ)lCI{Cw`44U#g7w+K#wsPeM*<_WUWN z$R|+Ekg%8^i;uLpqXWa0weuqrO z#M~y*9rwUEb8`tTY(r^z%60t!-r`-Hr9fMzoPKKq{Vl)l1u)3iM5gbEidlM&akK7f3kxiM04SNpDd9ng@ksZwH4h--S8wsPI`-is z(#799l9x~;r@ykLV8&Xo%884{L+%n1KoXxd$x~DtSREjvw{-1hNI*&DcM=Pm@eSRn zCNhu*@VemY%9oEXb5$|nR2Z|ZRtP|}b|gaQEyfg+?^AX21^`^WMAMU$+@_`vAF;2V z+j8qc!J{PFBq{{*bFO3Vj(%Mlx^3d(xjo^AKl_;WI^>4%xMO{9FLY}OI6Rx-zKr=M z!LT0>R^GMSp}d;6x*%gw5oS$_aS!LdfLkpZKa+qr_4=W&yyh@f*j_{`=b-d~{wu#$ za&JGSaric%Bv+&I6B=}TY0wj~;?OnVGobL$;IiR!*|3LR9ql_6;67?vWDkWQsUu$j zh6t^aq}+9;N`}i>z!jmG!oxvD)LeqWlbAm~AJNqkS~@DAD&o%-aDwyg32n)wp9Wq8j#A!Ic(L1VMU3Ew~4)=9dbtes#<~ z65}#UaFD?syvoz}iwPa%VBRHIb6SD+V2~RuP;}Rj;?5V~%;oVWfQ!!>7QC42ni7(i z(i>W2QJ|3Kf?)w8{9yIcg9JbIr6JtP$(I$V4&HCOi9j)J2x5_coMkx8Q(DfDz7D+A zJf%}pUaxQ|+Cg|VOT}sip`Ram;PhE}8}09cP|w3d(vh;Ev|Xm}ho7 zx^kQcdYLnfclZIYJq#a;XuDvT+wu|n5c`}X|7v*t-1%hZFg zghl!*86e1~f@2K)Cm!PmDpa!Pst}uIVFF9*mRtsK zKrWp)P4pCm7A!2zBl4xuR~T_&*-Jx3MU{~+T%Y1_XyiX`4korzytbrlU67SmmfZ;TjN)`_2HS_YnP!rEZlWpBfl<>lua4DNh=bE z2-}~%+I=7U#L4HPKfizRT@ef@@mC~$l~HYmCaF!&;>rP+=B(e>YO||l(}QdA8)_5d z`DYQ!;x;vXQ_=Kp)J?+@Sr4b)(Kin#O@UEwfJ_GMr&~k_>Q{!Zm{Su^{Uma1V?Z%3 z^OERaFopyx+WTGW0H3L$Bf<)gg+V_=*2B-GDNTZVCs{r{p>7iN!}eEn+TR?Kb95|a zx_miz{)#(JLVP?s=9c*s=HkN1MD#0Wi9pz8L1DL5HDm{umV$DrafdiM9Df$?6k&8p zYBP#fR0l-FvJA&F6)sjSWIpRxq4uoOJ(=m{fDZz&VG;rBppu;n-0_K&@ITej9>F*u z2qNDA*yh09cQv_*9?@;RI!VuQDiCe=*C^8GbXn|I)-*k>{AuzMbUqZ5Qn3Xol~h9y zk7_0+CRUgfAKreQeny=Q$U=Rh^ZWEkfGPO=#)dV)Npf^5kCH#*e85|k>W9H)d$;Z^Lam65G65z0Kd^v7V2c1C!1FHD}T7aoA z(_W+y57{*Akj3zzNmd42Q9%gb+B$R8glYy&!U5|q9cE9qF%4uZGv>d%SJ!w=TEZ;I zr|*Rh_%ecV_t`LZ20^(Wq{qiHSv*vdtbQhyODdt)l+_Fj2HWJs=KL7h)HV` zF5j(c8qOXh7dN5IWW`dp;Q34dm5=bGphr2q4T2Jh2(XG{vx&7P5bk<~(k=xDK~9gtpDj)dfd9M0 zzv=LQn;*in`<91Gq-3MmGYY$}!HM>DucO^bz*pDYV8h4_31KMsc8*&hN{0E)70g$` zbWS%1XMoHakNF#V?K+S0D>^S&FA3K^AW-r>i)-2y%K(xEQD({B8o(i7=0~+XqT{X{ zcMPosm0s^srB1&#VN+_y=|QkZq&B8Ky2cIyxlwa-#yQ}Q_wEEpdKmxwvA^*~inv2` zdt53f8;jgN8w;%pzQ2TwP35|Zib}fIw+%~q8bNz;6;)LloiA(i;M&OK^X8Pafavt} z^t5{)C%IllD`VFY7)E|+JVDI5Gm48OXqY|uQ4AC}S?_aswjr|K3PUY8V+o9t=j{EQ zoW%foKrW`z1SejO{cM=G`Tv#o=HFEQ(fjamIAzF~c`hXLJcg8nWXy1oxm1P>AtVmT zkdv{@nPrS~h{%wsLm4WSPGqJshA3qC?)$yI&p+_2&u6V?t*4)?75DJE@7LbfzV@}R zTbxP#%@mdBH7}YOUVq{#27cw$qDSLr3_Ln4+jHSBbU06OV}7azHDqdrE%j2%JVjdw z8dBUzQ2so76cLtm=96J_oTbKdzWV;^FFUL z{Z0BjVDt za2B!MIQ~CsyYc@u&B*_Vm&pIxO|hTk^ackRaqDVHgo^p*(?xHil@0v@4R9wyniQET z-nmE%Xdie_q0kWUbTLFa`e698@V9Yg{LZh(j$zxn57?!|ft*S^*!vZ34&Cp||2h!^ zn*Bgs8*jDsW)yJmi;?yoVP-W3ETOKuBDT86+==xa-G-4Sj@eHIp$S>U_geYg+m%jV0V z%Udv-gpGas>p+NO0?3(4=VcRKXQ=OQ&CFF)R;K{fVh{DdIO1Ld#!dQQ&aXdc8HaY@H|PucVSDx)?Md``IXhGly?UgmfL7d)1^A;30Y zUxmM#aRVSBLf1_nhV!i=eS%(S2`C;A4=FYk?cUmRn7`&B!6KrZ0t`(wcyAN1xBF;0v?*j8+k zb4PH6lhk2uQtXs6SUfR>WGH#0*%}c6EnzG|H)y1SezdN3(v?7`V5m@+j?Mk&mzoJ? zIaiI(_CPOus<4cgl_rNRN-Ty&675`R8CTdPv4W{5j8Y)5Zx^11;g;3OOD38kK&gRe0 z2158=bu{Mpd;$PoeZuf-UynezB!|6!vdti4xmUiEXH~j}m2b7e@FG(xh%@4x?1b?5 zmJiBoO*r*L?5dHW+5b65qW`rh^8d;o>HjBJ^PQ8#87pZ4{3U-96vbxL^t4V)wWbs& zeYRGoilRbLDd`=b~DP_1hZLx3eH94t#;ZVubcfdiH#MYpn~>;OmpC}OHUzO z|G5Yx)E671T3lq+CZ%g82mc;WnS%~tu|t%v|J{7(AEczD97p+>o2P*G-wgPA!E3p} zCtMvr7`$yp=eHwGDJ{!=Fv6?7^}{$WKK_!EvA#aF_F|F8aVQu4n|~I@UwQjTtm5dD zs}-EqLev#mx7(PT(9yi{sVrGzceQIBQX67+C;t1#yV5JcP*=sw^9NDO0q~n2ewN(= zJ^P`S;9FcsIQAbhSi*v%;cR|8pq|gAy@*|4ZqPK%f2swhFu49pGM%bBTC2cJmfhY& z5($9H$H%(kKMoCj(vx8a^Thp2P5?4%!MPw96bheY)>fN=KZL5C1w@nTCBT&aq41aN zf5aixJ<)sCkVv{wA014V#@R_Q~Eho&HP;{z>@02$KMROA5t87&U z@D`jgL)m5XC|=JWo~i?2*Qt8IT@e6kt%gUCEIkP4k6N@J!DO&l)Z|gS8ig3=Y1xaM zN0bdpHpN`xllB;p1c_3c32rmS^MezcrnGu zB_F(gWz*;0ecCNuimI$ec$g)ZN{z#Aq?C@F;pD)bN_ql-#Jm;~4w_(`YSDfd6Y^(C z3`+_IEYo~2O%bfy*@)xa10(@XZQlwLGMx+1CnRw6e5&F!G2pV2gO2j;xFLbyU6AIO zIfTrYphMZRo}w|OD08Rj)N$yI)2--Uw}Co?!$*(s`y~UXY(CC0?t3}T0h8o`enTMP zxr*R9&y}H^m(KQF2l46KA0Z<*N}E>QLutg5!Z9$oJc#RlGbp(NFK2U69isg~yzq=O z;R!fcO@aZWMa+Z247skp&l~n*)UN55AJnz`gz*PT5lty-#0em#X#!30Txnj|x;xul zJDE5xN-B}FH;GH2@H{ai-& zeRqd5m~UoINatS#f>HBW@R_!^W?=Ct_mdT|l0;OdLru4SaJHyBrqJ>}LoqPvIzSC@ z?(I<_4D}2rO`;C>kAdtS9d6g+(~f^mV-nQ9bJp{>LFRrW5{(>(B^>&6;)`r7{&l7i zSh4p2PY~nEoS^AAVg=e!Zli+^sBN+6!V(HraP1&x4rKrZ%r)bO7W;DESsUTmo+4-})`1dLIXRS`M(26@~k?;bi9kLW}Oeb>_xx*|b z5j_~_R?ChK*tC?uqdOM9iqm6M>x!{F6UOTK23Vn+2B#x8}n*+J)YKb7hp1f z1zY9xVGQCxS^sGLv9-gR&aKd|hdRlwH}66teYUcu&HNZ0yLi411uq3Ww3;^n3aYwz zy;zgrRimKE7O1;-h~7N=j87+;j;%Klee1{IV}OZzpdd;WP-yvrfsMp*F5$ZfSRqIv zap^f|p0Y-R8QGE`zQ4JeZhr!{ZwdDyc$w~y4UqP%m`Y!o)Z&zFt-FJT6HHCJUmc95 z=Yiq!VX?!ApX=>-kUPJD7+IlwpI{oH&!%qzK0CS(^uZpi_{FL^BXX#AnqW(3m?K}% z{s{IPAuUgx*%}XlGMMS&liG`UcAd5uqfUft4t0{p;ES$jeHFDM*(Go_~Uwd39q0PxNBD(YUm&`zx(xt=MwNxe%2u)xG znsLyOTwLY;^^yH3>CmY^k1iRT-D8gHw23TghvGx(W2s5{i}4T%)rSn)hBU5SPw-Ey zKuewqv_Y3$=Yn2gI~?cfIF7=VJsg4w&&oTnU+L53uos4Up?ONmd9zE5;4^g=5t&_u z^gbm$H$iWKlU06y<7?$Er0qULhK;0rM%%6vv&HQ&2S1l{YtYQsg*_bD!++g1f5-3C zJUVH1cCPyBS~?nOl8?P*g)4tBFk8Xyndb#y;43|i_A=B9|CN?D+t|ob*wwf41l0ZYX*r}N z;eR%Q4F_(H14DlGOSS!auTWyf7}KzpJA}8g5``Zmz*%oV*&uOxZzEOhF@vd5PXeFB z>HV!Db@@1vMhI~fYkP=K?yc|r$<~f{l?0`fi!z~lF&`z18s}U;f8VALeF-NkEqkN& z+7=jlT8_GVH_fsCvXsUt0cVtUL_q5@^tZX%hwI*ah3lsr79E6FDnR}mU>o$XpSRLq z7;0s!3Iye-V~eHS@Ci30uBK`Q%3OYWk!u^YNhSXCL&VB+ILBZJa|_xy*w+{=M)`?? z>mLflXEz7Y(8AJQqEBZdLv1)Y;4{&7SNfH_BZ$g<+?E0u*-ZDIUd%jR)3W~HA`FWz zvble*D6zVXcKW5(n`bbI$utWIw`1eiK+-r7q_Z2>E%8OUeBaGI0SoMkd`p z&<1BI*7(%A#=#!hfaS17I$Eivcq(B}RxNH=><$^qJpRugSm!*;Zz#@sGvr)1I2p?x zBdACH_Da?G&m|ZVyR>=!3xG&mMWerE1VEG{)cHKPRoNpF zzl4a>%g;aV4qvezsS8?jIU_xdNOV-xe+B_z;b*n^IEL>9MBQGmHN_-V_ycaYd3E99MT^rj-3&RCF#UP$lB{@A5t!eeA~DlC zUE^0iF?ohRUI7!hL_Vgfy#c3)^f7^o){>t|7_ZkGd7pL`vRnWD8H}PBf@<~QrT*OY z5=Iwt`^bv(+^h;wzNQ+>1%b!49-dp!56a8UmBzN3Ral4xyu}2T5ltfmA-Ej=uqa)x zCL*HyI``VU+-K8e)DeO*=OOE`;b&%ML}2QNpg`}D?TZuNfB29Y%RdZ=d-F3;0Oh6y zk%sl(`%ELqkYsw!-=1g_AC`o4+P4mvOoC~~$EbL*n?X_g1z_mlYG+c#J=oE2fyDSc z&#`3-Qd_X1thD!1mCNk;@~`0^)l26n-~6$fnl(BO=||v1ZIL9~3IbvGI{}bZpSPkW zHNd1aQ$3&}OZWD#ar@U-gWp#u$K5zdLbg&MZeAwQl*;OeCz){OX3N@nAg2r?RA}mc z-5w9td%|Vi66A}SgOL@st;Karnf4jDb&lefS}!!g9{lmzGBV?&@EOZGJB)fn^jJk? zvwY1o0YhVNV2KI-fck5=FI_~j(+6+j#o{{Mq7Cp#p zl-ABqA+@#cqnZ|#MU|0WV{l=n%@e>tEzG~H^|L_1T`nDFmOwEHDaU6L#W35-1XA#~ zMql@3zsAU}vm8>k!hmdIs%+~oh-`HzUkj~)sE_nS`3y03TMSahAZ1Vkfn#Up_la`t zT;y%AioYPKEpL#BVc%T_*@P9*O`9|BZc+@VM^SPIgW3tg zDW(bEEM=FEy_Wb}ORIb_FI|k3+8+*x5fZOxpIEq(<+x|%*h%*0m%{x4hoFmIpR_BC zQVmOupUgs5P4=j6IxqDQ(WF_r>;ay#o#Q(cRWvpqGkc-eXbmO=Ds5ErAI9XU4n6QF zFj`Ss`TRsS(8NQ?@dmv2kv4LIGcl1Wto@Nh1tvy8;@C^Ux3H%~kjyFgRil%aI^Bs! z6`+?9^waJNnP5;7{Toain}!|pCqUNc`%I0j7Q0E-FOU0Z*|NX-QOSAhtRB3(bvm;Z zD7U~Mr@z2LUJ{|F)$T*kgt6B46}Iqe1?U1~tr(lcaa-bnUnuw`cUTE3rIQ`UtgaJ) z4}iZHm@R9M#L&$?&Aw?afx&J_;9~AVuiV#4e{lobDa=io0O z!NW8!PKG5kpinG~$TtF36|4?T796!QTkTgia{1x%6cnT4{vFTrF_m>R!!)i(TZ+pQ zG9DsPg0@kW?IjElBF&7)vwTg_5KAi^XqxW%E*we=A+olh!KOYLM(o4~Y$73IFWs7O zH2}2Q`ZVRaYr~!K;2$)@qtkI(jBhp)eiQHg0zdyGz?31S=2dZ(aHrL8m&fDpLcNTn zQT@x8b4HA!dFemgyzWyo+;LZA_C6`@8~Nq{%SCwE^S1eH`jVFT>;m8!IH&={yE}aL zK>2V1ZK(4#LBmzR4tHmN!$2J3pZ-kwh9G;tOD>wctP1mSY{o7$X%H$+cJD#~P|@#9 zo`3C9jeurLntwm~GhJ^AVSksw5sFd<>{LEi*<8{r_LyjEeIZU7Iah*OcXOim0~A*D zGEXJ595&L^iCXuEiFMf0w@0Op+`gi}ncRoAD+S?U@PXn3DH>P_UaRB39B|#=5mXBE zN$t&#uMF@?tU^&$;pqpmg2b6S!S|YA38Hrx)PiK1W?2x1yFkjR{ zM@?`qX`DUt>ynL@p=vWf>|MKcDFVFdbp{e3^7i=NB@B+Bun8_Wq2r z;gcm065Fa=-ItNyb`0iq#1qehMJs{^lMqaqWXFYKlnRTH8|<$H2{QC2gz|EymY>2N z%AOXh%nkB6EbH7bUmr=JVVDYqX^(_5?uNfE4fuyg3S=8(It>Qm;^O4}f0{lf9nG9u z^7M;g;4>GMbmdbTOuU7j0fpHca7%qspGrU3Q^j*?R8~Ry(o=kYuBIIV@~=G!NJH5F z3+d9!TsFy;jQb=WUPD=U!|2z4!!9Uudz4`i@=Q=v#;pZ=Gu`eD%m;6_fB=A1Q4U6p z4keu{6cVnNf%ZmqL+1d#t0M>qtp6sGKu*BA>hZZ^F4Kq|)E@mIuIpKOHhGZq+Em*1 zxjsOKk|7*=<13w$M)>}&P$x%FQ6yhCoS0L>Y^fvydm?D+J_oJKxWh?R6w23ssneAv z0XEc`wl)wqf9k3_^{eIMt$MJV_$2YKpR>*+>e%XEP|7taQB6I7Hjm9f77@>=@a6rq zzuPXX8_n>_h%;@Di(ePL%E?ryG15VY{1(3Kpiv;Piw`2E3&@6?J(*`2DXZLDfE|wh z%9GL?^h}UH-m3)$75*?=b}dBPdAC{ukbfeI^j&M#w_NVr4*WSiI(l|mwB-ze$`E#hVED|DQ?oB$56RR# z2HV>57^5Tcs$ukID%_h@1fy(!+aTFtBrSCbST@tT>l$R8UKFl>IcmX2!L>V)Lb2)% z$@8dTH|jbM2`he>)0L8bkct;(wL>Ul1H>%Kl0x+RSTrDHc7?9Yv9U!P%r`B#&*d?DYERp+1kxD zG)%uW->!j)L%KpMoNR*aOY(Ru)*W;{2yse$M(wCMLF-gU7s&Pfd9L~d=|(#zoZIzs zfWI!$o}GtkbuI1nWej1OD$j3~z-$MlE)qf;Cx9vQt@l6DS4*I)7Nk`+bYj{y2OX<6-}jIAi+(LqkI!>3(;wD@%YD49`6=2!MHzbJJ`H$fc9fY`Ihfv8ONU4 zsRYPBZ&j4FwQG5YBnySTz;n-%R}UG!K!`j>&5fjyn^kp<6f;n9SxR}(X|@W(EQX7| zIm|#vJ~6T~TqG#IlL94bPqswbWGjri+m7nEj$1>e*_L>``j}f!?;MVcy*=89RsDj4 zY#8Lm&-h@7SPPqkREEB~oGa(MF3PH@*$nusks>+8FPy{^pK;SfDc}57mO#+Mvn~2U zJtPKlF_tSaU1@H!&FzEgo=F`OgfvbCkJ-(363e%kyyf={Zlva6BJvOoklCF+pB3J_~J5VO62QHPROy&R# zHG83`!U@=CVu;|ZQ?IiEfY8z#g%Y05!}%6xen7bjYoARKXlJOi_Y5OAw zqzQ)frxu+~`@7+VRw!IhoKp{v=|q>=C@dsO`k=(Eq)`pnhiH_Jz%KtL2LGkXMhGcf z4@baWu5#$erdpv`8at^U8Kn}pG}<*5N#Vge ze=)AT7w|5_$VHEb{~X25WViEm&POtY6j7?vebI95bow*&hps|>Y7WEwn3O|LuzIKeOJ|JukZ03v?G*wA?rMPGRY~VH@%;8(!ACs!HB-hq3)C~P9FH70iF~pq z()VU2Xv>dyxcf3Th>psh*Sg|)pCrl8_#Jh;-v=Uz;U?dg81{Cqq$3Zx@&ZS0L^evu z=T2!wiLd%F87w8I9X%kidqt_6Ci(MEp3h;Ig%Y&+ZGm$ar&l-aVO~DA_~QLC4!5l> z*7j*Y{jLH#z`XpjR5+_`uJ?wXltD3bU09nrn|<~DJml1YNaVSlb;j=;SH^QH;*L;L z>c{3yD>AU6SVVJCEnfvDr@E7%Z(T+}ubc^s2kNUVChOqe#DRtU9pOW@?*?@k+^%%# z@St4#GeGe;B*{5iil2Nq2kAErx-$z&pOPQK&klU{7%A*70_GGZrYTtEpG*}sR>K3M zINW`SILxIm1{1xNG1pPNoviT8`WRfJcw~?2o>0|hITpt*WlP;~Bo7)S;`dJq;-d_< z5;mUb8%Lq3DI4{h;#Se?8Z9uY8)-tD;XBj8$3lLWA*Z7m+x07H{AfTg4e1Z1hOo9R z4B*lRcNb1Bbs^hb)9DI88lawbA4p#9z3(Av^yRZ+J11l7DsDg;`w^dn?i9>unx^2# zMVnFz#&Y?=GSzl*)==bkHMDYrJxWp@r&=n7n{ck49ffBOH8R!~U;?8W7tX|SNsT{} zwbScGe}Nv&#jB}ZOI(#&rc7z=w5(NK*axeaQk`>^Ick581>#j$qYALQ2wOy%H+_ap*>JK*B|e<3y^6msZ1$SlS{~d3 zW9S2+drarsN3iVS5;&|z+JQ5MI{p;`3;zCq&{U$0&k&D4U~50Y)ZI1jeXyM+tNg7L z_(ux~#?|5{BAm22ATn@IeXznS++q5z`I#`jbul~EJ^C{$h;VQ7xnzeaYP5@3L8+#V z-G$KL*(g(KS@|?DnayJ7V%OZ-)y;QmKX?Pk;_F_7ErcTTaddeoHM{|zGa6q_BkUxL z<6?sJ_oD`+B=>=3Q~s7tPL4jOLay#(If6-QVqo-wuLwPIQUuE)VLbh9MgDKc{-W2n zYpHZ7!0lEq%aCht&Kr&z?$Ruyd`D336x@q;r=YNWC$pvGK9cjkzETOH7cy2>ge?<_9EC0Th7~n~#MS@j z4VsnHPfO5fhr2^9_A(277Zo_zQY=klB5D1WF^+7XXTQAgov~*eitfmm=UD6h|GP0c zM4czEAM<2zlDk9!0tls9EGZCzYxY;_;gMu`u0l=yO^d{H9<>L>t=bAQP z6w7oddE>{VIOdEg2k>JD~>yYLHN$;o-=klqu{TyDK?#~$M0;Nk2VA5Ur&n9yWb!JnH44z zT`B8~*+<_o3z69U*~OCtfZf?G>$!8wA|Dvfh3D?4-?0J}CWUbBNBGn?Vh?96u~-P& z!mnL_Jaac#92d~5O1l7zn*}3k&q9`tbh8PvyXd>a*(ifn?E8W&XD86=K6U!(7Yx9rX zt^l`;R+tO%Fi)GUjQmVqnZ${Rvu;1g`X`U^qhBo#`O${J`MzNi4V z2lPeOZY`!en52&!2A>Zm#<_~LsVU7At(hd3Fy78TB5oaGbUH>BQ&v{)5RwdUx257Z z^j#{defnjp%9L}#M9wYl9=QPfYv%mX9YX^n4SU7=Oh}<6l;v)(wm^D z5Q`WK(HYoUKplf`t`m9sr{{ea6 BHcbEk literal 0 HcmV?d00001 diff --git a/imgs/rviz.png b/imgs/rviz.png new file mode 100644 index 0000000000000000000000000000000000000000..5ff4a9d303c6298ebe4975b0f8847aece3936da8 GIT binary patch literal 159568 zcmZ5|1z1&E*EQGzih?2_rId7c8Yqnt(%s!%7Ah&-p;9799a2iVIZ7P5TS~g&pZk8- z_j|wpJkJf_oW0jxYpyxR7;~)S|5X0T6&z9=EG(=mQj(7pv9Qjev9QkSUb+Ck>B1bG zh5wv$d?2NK30_{8jNZe~Bu)})PD-{WPOkb6##p8{w${chj)o4##x{;-woYqjYeeBq ztjL=lIvDFancLb>DVtjxV?A~-r{d(Nl6JPD;$-LKqGIP4-_?zL|leVLB>0cK^%p*8>lSbEE9ZYb~R>N{h4Rw z_w@ZICnd#S+F{B!oCAjyTa#@JWp?zL{Ybb>QXGAJWgX)UcR27o#6;#M1?PuE`^%#@ zMN*ayk9FS0I-0VWphyB6UkzH(9op@jo{}~lke-mu@IoJm zT}asFJpEzDt)Xjr#q?Cna)6adKU&0|==SaQC??hSA3o6Y@I-BG1$E5CHJ(w+X+?E- z4WvjFSY0j_(;aG&&i8-+?u4AsEBOT<6d7m*nZQW{cf@}wMHX^OrXwtS0yzE#l^tTnogejcf^ue z_D;+XkG7Y{L=J8@Wfv4QBnmwd;Nzq1`gb&sW^CDLX-Re+X8ApLn42CRo<6C+u-&Ju z^q;>g`1cc*)!g@9)*2bfno+sz=;2}BO!J@NG=G^~V`cj0CH-{0STej)ID z#a56LXNSq`e{S}uu$4W5BfgV}nJE3geu+|J9?<7VgCKNSjF-&vm(_7u8>f*Zy!J*OERq@`gs<`A)y1GVgcW#kG1LgHow| zszr+|d*XNSOU~%EWux|Je^XuE*{Q6t!!~Xg9A-8(nMqh4sJfW?tHtv)-j*dr{hki> zOM9gZ!e9B=qe8CC7#Ad@B17g}$lY3XLL3|%>a4n`7zE-B>E#`k8>HI4^Z#Q0 zd>vn8AYS+L)$sV}rd_e)hI)Jvv!u15V$0s`rBiwPx&32MUKi z47)mPY>{}lEE)x`Y{i*9_bGpS=XLT&ErHVTAv3sHn2`K#^99A@YWAiN6#faCCgt-Q z56+a>)E@IpD?Q6+n7u( z0lulJ+yeW}=Ls`|(Ud-Ssj1JtaQUWrmfie-IpoMAlJQPdoRA@-siA?J%krL9|I++) zea&6dsp*x@jBjF`Tjd4B92+Uw1vzTlwD6cXsY#1OwpGZ~EaF_w?U zchStNvMNr<@q!v>K(UsPiZCHEb0pK59Y0?AwX5bDaFe=!lrj`7InI7N_|RHoeRjwe zYi})j?J~*Mxf*gY8@X4-)_rGEf5k2pGO2w1v8+mWHZ(rIjR`e(W@2ipg~hB5gL7K(?2Gu zt&SJzFKn&VzhxOes|RDxR|(W=Hy#{sZ)wrP9GxfQ_jmNUN6dKff?n-|;NSWk zKC{MW&K{A7&8j@eKF8%U!|rl=BvvWRl+}UUbGHaKE&)L|nQI8Yg zE-h747FJ}08C?^5{t?PoaXvddz4pr#&1pWAtrZ;1wBzvaV5ADf({XOPnY4%zb4?m| zm~frytdr!)y8RNAia5Mo*f2{ym8Uyjg)c_OAV7jd{HzY$A?lPXu(7Vrb=-6~WRy7g zaWdsLp0h=73yQ2i+j72U?iK{a{_R*%Pl{jjUC#vWz2}?nx}euPaEsshfV;;;f?)r5 zuK`Q{mjF{_k!Z6W^ss_&^I}o`p3uKavEL`y1=ALd&wW0hu1mNrYWn10dqaC}HN|(b zM$`A)kJc=_l)U|bTl6(`ff2g;U9Tic4Y-h$yUIu}pL93JLS-yb=(dapWAv6X{9nS? zPoENny}u8%cjmZfXomlD%ZWS(l{E_OfdWr_taerJ+AXQ+93_$73|h;6+x%*qo(=4v z$7cm7NB8^fEGz=H`?i<-$wXZ44lmItCqu}G)l?*n+tRVHM77uGHYA4a8_7`0)*QPG8jx|A}(W5Qc@Zi8rrfJCK%b;qH9i%ZL#E2MCFW(Xp)3n zO?FpD%gW26EUf;H(!uqf%SMj-<{Y=x0DHeZAUXyYaoR>R?(S-D&!r`czOTQkJY6xl z+A=jh$I=}C6fz67Gf!9St4j9UloZNu8pQ@HL&dzCUK_3S$~kIb$e&BBH7l#C%)8SrpB}II zIx?S*x{jwmOMUF-?*6RQMw^I5Bhps*NeI~|)jS>LTrCnYF);v49TzFRo<7jjbo2N3 z526%H{@s^7Jv%GW9?ddX>F!v)8AQzSYIU>%WjFZ%p2M%Slu!G+)8s&bVJU;fzX1|9 zoI1dRCLkbq9~g+Lc5!k_la1r_i{I@|mvLJ7iLIcZ07cK<$;s&CXn$*YFhaY+Mc>v| zcO-w~208ha7cnunurlS7KEtC5uQw3#3knuG&dXoGr|1Z{$>jE@_TsnAxK5K~-xGI} zj@bKAj4EpRde~<#;88I$25ii>pJjKPlb!2IYDb|(Wl$!a1Esc<5%da8eSJ~Ql)l3K zZV(k8V9wSmH?Kl2KiV0#)v9p$)=;wBbbK~6GSX;s$cne8)K>Q@xnKh>Tcx<29eaxJ ziGcUPmi};wwKBvNdUkEB>h=rU>ir8sLPAYJBoFg+ss^e&cUcB~|HeT2r-4=!g^0&M zrO(cwX&kS$#-}-L7^u0qxz~1|s+*e|*3TkyrQeuu?QKy^i{mxE_VtDK#|O?>U5Ntq zFrP3%Y0gU+tgYXD?IuIK)m)%$X}~zTO|S80n6;yX9<5R$LQO; z3O2k}13&P^j(z|}`ZnC3t1ScpCuL-0R9!r;sHCJ`WOiLtR1}L@t1Oh1$KubRX-bxQ z&fopQ6_6yHz-4;1@2d)`dS`Q!X{%DR)FvGUk7*zg-`|)u|M?NS=4eC4p9Za{sQ71h zx3oG}Ig0>Uf!f+yaT5a;PR?+6yZ!2jKzDbyq=G`G$M$c5=)N+0!=?PxRBE_)Lqh{r zzG3rKxWK|7Dzj4KJmXwxf(l9bd!F7f`{Nw!Khk>~EJ%6~G@ zDoLY!a^E*iJ~Zsh8MqahpwoL8>0o6_boAT6KpFdog;1Y=#Pe9P6XPj=Rrde!LwtGp zWN4(ou({BA={cQzqU84PK6^(;LzwNOz3C6U?HqBk`~m`lm8PbqPaGTyoi(X8v2g~~ znTfCr3=AA-&`^G}pMNtr*jfxC9`Nd-Ftt-*yr@v z6*jr`7`mn9$KasA_^hddmx;Zr>-U}KQlzgc&tOKEv#u=CHKKLFle*-tmk600h< za=oqYfq-n)EbLNagQXcGeX3dhIq9X1R z+wm@@yvhfVy50u_FgoBh&Q4C=*VCg)@!nAnvA^*8&bYgyOt^NXTiD}Z(kL~r|Lllw z%HgIgnk7b^@jQEbdrwQO28XLp;EE7nFyhkc7=Uk0!M9wpA20N~~JpQKh7%Kg%ZxO2qFr_!B;okWja5BNuWB zdVLX}(`)aK=JmgoQ!?vb)XbpR>AnK2yrZDYa?78|`t{AtX~<1pr^mZcL_%`4E5^FF zg#-l&u3xYHED>lnQpQ0P=qD9H7Zw?*JTs%-7;uwB$b}h_%G^k~Be(4s8DN-SsZR!r zEpMHk?AADTY%b;1Y{35OhC=h|^=tpYKtsrNP!0Z+&~{-BmD(x<60t1wW#3AD9Q@g& zGrpm@8D%>zy1cv`%WrRxyy@ZL!D%-kPA3=trq##*63n@C=Vsilz5aK{wT$M#R3;}U zTaA>3nfGLHxNjIuO;4|HY*=?W>L!pB=ZNa~T$ z!9ZGj0mL})7TX*Yg~rxa|NMORgPoOxrLCJx&l}p?16x`oS+&Z<%N=IT1`BDGGUclV zI~fUpoIwtb74hUs3>RdOpBn>)AEI2y9Bz?t7@Xta;KNO#WZB3Sjxokk%i&wBT5g&c z>VHE|aj4hoKUA6qU;4i=PVLo+qy5cv@^}AU>3s`%^HnNt?xLdUYyTP1^Z<5j=iL8A zETZVYi00A8$C>{n$rQ_2%tSH;CLsX`TLLz(hr8Ui&eEKHwEi}=&0PgrC^E;&Y@BOkOM zbf9)#zP~XFScKpC_YJ@-!Uqef>Et0Wr6cDyX9Lr6+!D6Vda_5_*WJ({Y-T;?xbU@- z`R-l62-6f(ct~nXt)0nNPD_|zfGt=*Vb4_WO$8F*?yP;y_f94k^GWnQUed)9-t6E~ z&QhFx{+2eKMp!uU<43Bd50vPRI4*2rJ{zr<^?bH1Z@2xzYp-44c8Vj>OVwbX&ZE#@OyrUJ}aIT}GB(!>szU^rG zG~aSVkKxHZ0GzLdEt3Ic&I@W?yLj=Uu!zXFdIwJ<+O9%+bfkC%AB$T4ixRor*Ndbq zH4E|k83iBpxzs*?fkJHl#!Iz8jhTjq2J0Fn<%dRtT0Qni2j#or+Ch^9JuBn-3J3RH z;#4DD_#Nu9ZELxI}LHIMs-G<>bjI-K9xoF z5d^%ht6J>*uWHZA7IU5AkmcfLd?P;$j&Sm`Src&3wgYp1)c3@r~8XBX9%QI7^T zV<15+V7_UZzkBv|s^90q2<0t*bPH9n^cAhSZw>p~3X(hDWW63==qDg7E19b&&|O=f zZif4{Iv%~hPR-fwc%xc&`-AV%>(Vig>;{7lnVo^v$2E_eIj!ApXI!y0l>6-eKJtxl zgsHk5k1ZLic^s7;41i z!a~cBmuCk{tZxIHGlXa3=jZ=fVE80MF2N+J8a}|=4s_{9W1}A-z5GDs_@{>#wY0SM z_UBV<=QCgf+y~eXB|X(^e?vL@d9Z%{Tl=|=xM9-f(NFI?FL#=LljBD%k5G+U0q$h-!x+o++x@qV!!ui z(rX?q7*lvU${?nQPsT3}coV8rJtStN2Cg?##<-~MrU|XYd*n&7({R@NaHu2+77X~@ zq)E>gSn+Nn)warzQBW|2Z42cf5Z0vo%QNcggWpU`dwDe{LmoaJZf;Kj$|A73_VvY0 zt=-^FZnK{+K-(QFwC=P$mME|G+WPfGfPfxmp^}y-)KRm4^fUJdmKRK_x$Gt##C3Ib zkoiACQotkOe531oyd7<28x0WCvNAU}_l=()RHYfu-0WA`r^E8E1YVzWybyxF-7xd) zdWG~DzwkikfzPt7`&#Pq_zJ)_JTm@Jh`|`Mpw-pYj%1OFM=|bPho!dT)xvvvlktVm z^K_0w7?vQTSh(-FN5gB$?pdrX-Ghe@%b^yj0fH~qD>msQO_=Ns4GVkOYQz}je5)_` zFjFP_xoom9?m$Nk$LrLnW=%Y(PlLpWb0)q zWg@6xa~?epq`+x)B(B)9U$MYI;$$D~Tj($=-QCjz8ujz!c6FcA zVGRKYTseF3suAEuAdLh!Z#G)yRXs)+CJXC7%6~O=ZoO^w_11O5%s?L7s8FiM$Bsdr zp03?IJZ$hU7BM2`4%8`M*iQR{<0v z8*=1M^Ib_mhi(QoJ^=W4xVuJAOX~;wr@(F9K%>a4*7szSl9bmfmh0{9x&5sk1^0u+ z%<|KdLt7aoH~5UWxOm73BkuR=8JDEho=k<1U1`Q9&4LllMS1>`T-_RZ*q-a#+q2Uj z#4TW!2;R&}nkEuvGWUZ)59J?CZ}mjT>_`WzozCnxWGfqgcX+nfME3v=%Q zuHX|EB3#&y!uvB3exklOT%(=KM#!q@$(|wPgn9_G7Wl`ET&KiJy;{K!ssion3s4&n+3oD+75u!QX#BHQ|O(Cm+;jy^U+S+=4H9MRaWCHe-Pc1y?pp#0#8<-eVbn+~qG~vT# z6zDmVtE*iP@kJi>WXOH%$9eLy4vnlFxq zwzdj!oW?o6>hl0v63jrg0n#hHH}U#t&G!`5o@=RG1qEr? zWWO_k&$RyS6|5ZXifEwClQ2dzvwM&fZE`u}AoIb~zX!!jsn|jV>KK4BJxEvLbH!=8 zH9r69KHpu}x)ytUX~Q9@t5v#jOioU^d3bEp;j&#LBz)K$LJrhoD(neG!Or!I`zdP* zqWd&3{B#K6-dybjNCkg>XXh!x@>Nz=B0~p~-Rb*o^h~otqRCK07ZjF{lBWs@0|NbN zn)B8~!W@V|b@lK986-gQxP@}pj^B8B-mr{Xg{=HVFtAm5VSfx8s#iXMcIm~`i!Gb%| zBm=9mv$y{Qo2PQU={6`(FCkOT-j=}#pYAn_**Q5CVIFs`9d%ji-gN4$46D`4FE25w zfvm*B@4i6;RbT>iqcq^M+%_Y``PL=sy=xtnU44}pm0s)0(bYGGmJnt%w6p~leTmWrwQ`6q5}Wpe6#HESt# z(YI}4l<^g&xH=k4V+Bq+GnYLV&38g58y3HfYm6&6=f$pZ20f+*uy^j_#m$A(4;o^r zI5!#XKs8x%LdFT(q9o20WDbDIe);+N!h|*ut*HWPGcefD0*`TkuDP@-AG-Ll^|F zD<&~13Dz3K7s4k`o&b(^#H*;Nn6Fq~87@WSHo%O{W%kpYmZPEjuYV2?CrAVm6@Y?5 z;l1@NSEs5CFq`|)dh=kFCtqIW1`b+emn?==yO7luuI>dA8;0^Dq^KN?;sEc%9S&g6 zuwoL5iUe3tO-&($z2L(@4L&d^W$4-3rYwE8%>-!$!9P#{zGzqQB4X0LC$Ab0rgmBwoL-Y}I?O-oL*DB2Bs1J}1JY0mrv|V{WfO;T} z|M3EVNI+(9HB{se+KUosmt@n0J~UP7m z=hW22-Yi0pCnxvTr^$rfLeJw8v0L=s16k!|M_ntV+(8h_-(4lYD=L}{^t|zV4y25p z8ed=dQ}fSH4}qk}#&bjCPrktW(8XteHsB_$eUNO4(NJm|wGiuop|_#F7d zRu7>RlNT4qf_IvLpy=ll4*QlH01z=-)fRziSK=oSI1nv)sXx!KKy9Hvk8-vx%JB5$ zIFaA}6-@I@i*m@3(?|`Wqk9Wd?c7l1m_fmedvKdzCdjEtg3ePDwXcEH;`#def^cHZ zwE~MUn6H1f!gUR~=hoVI3J9+DQw^6vYjFp$2ph+_8enffvrc6!|2P)mU zK-55Va!{p1V`J66pg*ROT#+~wWAiJ|m~-u#as3AM%m7x!YP>oLCJDjiM@L6E#on+x zsTmmjAxzfCJlAe69%yNNrhMQ0C+*@9J!(Au&aV%Dl*_CAl24)P%=cy~mHXrw^`}0; z_ksHQfW;9Wk%o?rfRr?TZ9i$ensMPU^PWQm5t1$-L2vvxi*E!@aC)#SDqtJ zo^#X;?--72T|u$?rio?$ZTF@)G{=SWF@ZQs0DTb}0|5{EAhLikjfukU;jk|`9A+df zQJa<3z5$9hW!i0+;Cx=REW4@QY71MUn9I+(szPVdn-=Q*(D8$KXy0w}b-8@`GMRwG z8)W&RK0+E)nUE`cmAekmh6BWGB#?m7gQWlLi(28@_^Xht+t!1HegJGyfT(o5w^beo z5n~(e)Gp1>H$#~ga9X$qs{cJ@X4;kh1+}>#i*`%2XiJAFrP0tIUW|Ru+tSG>ed}1k zqAPiLRj5Ppc55LZR4l`H9N5~q+@q6|ZN6nidh_!E;ecWXr9BXZ;tEwiOU=(u?CE(Z z{0?{XT*aS1cE9`c@Wp|5z4!NTEsnnV1MtNc(21e*(`3Z?3v{k{Uh6j45jj0Z+vlT; zSG$sgl(H0QW$6e38P)am^$oS206-xT^AYy(@qs2MB$Qx~j%~85zg3?cSZ2s4wN<)r zz7GnT31q9*1GSS``+Fqh3{bDszB@4>aSPm*9yD^OgmenYiKbkGfL#j=8gYPo`+@F_ zDDNaSzz^WBK@}B3aG%OQb-2vB)nqTmsytCpnJg#GU`K4Nj^1vOeF|WuCtH;bhA0=$ z{Rs#~j&6!{~iRWrmSV1>HD!8k~aLnFrc`1qN|?a|^UpFaVHFEaae z23!G<3_<#P^vTyMDy_pL;pL6eK@%bnS9onk-e+dgqs2~zp)cUHHa0p`GZIcKL(FSM z449?fh;toK9zc?aCGD9b(RL(38#EyE#7-J~?)>@d1OyIB1u<`cOej@(ID>313&kNz zr%DiV3VUC+Y9^pC1hM?nml-d2G(|WZT-kBuoh?x1a~CcU5EDx#@W%O-@>pVi=BRTa zPq)0XLc(cu2@(>LnjwI}TXf$9og566{_54M=f`qd3_!|PR=#0xZy(8|8Uk0HiKXM< z2un+&foI*+3aP3R0j%8I*mxdh3{kC0tcR^KNJKoi0Xfs$yZ0U#20}#v&%O=}#1-+_ z${#CW?buK5+a)zhRz(7-y&V_eJE4N`%Y=ksmbE2%HtpfV8;hq$H=N`;*AiRTGz?)7 zQ1G5TdzO}wL2%>7o0=NmPo?YS^T}s9#STAfrP!9XN2|pT<4<_5oz^zel!e~kWKr?Y zQQkAL0)B@_Ash=xr}D?ScYx2Oq@+MVn-M&L#>1O8Zzk5((2yU$@d#`R)oc!{p7%bT zDLKipl)>m?@JH*ka5oeq*E&8YXG@GW4bRF8mOy#5a`ZkqIb4H{kKlID;js37--*}G zetrdU@CvqsQjL!{5E(QSU}z=Wg$!_+kWS5#WqYxwSp&tBXPA3$_U&+Eo{H%di^)_c ziTlZZ(Q@P(=gHdX$%oL;Yd}STh%n_xTM(fJJ7!uVke(ToeWY!8zT`Q>0%=O$_oiRJ z!swITKL0q00jzVLT#3)3_Y0_=aXg&E#g@%LmY_|^)N5*2L6c@=$4&Q=dY)j9h3=&; znl^vUNZ2z(+i>32ewm-NxzRE!o!sQ*YShZLa@E z1g$8IvNI0kT^5*_lx3bC*kb_LAS-LcM2(g^&JWc1ib3ltbi1md;Zee?;LJ?uWg*=c zCIMO+rWaH?6nr=j*&*MiIg&w%-);g65#TFaRtkMS)ogXk za9i}ghh3{ls9s%N?FAKFAlekl;2?@VuWE-B7FT#@zz}nS3zZJZ$ikodG}e3C%p*#s$IcLi~Mvb2OAF@K&$rJXl^eHr*=W2=I4N2_d3S`f6Lxm{CLRRy6UVo9`(6#@Zd zF39f=+DHOG8l^C?8mtTpN2}21%02vQHCVX6>YK_j?=1(8h?B$d)1k`wnHl9TmiK** zwQueSaaoF-Ps&!WKkv;pQxaTSpX6c{#ipAK(u&%+Ews_Zj<*PxFyE#@$6@_L42Hw~ z=s=vF`N8=VUwN2UP@zj#V*syDPfx#2N=lL|2MNS`pTcoJ>NapW-0l5n?$Q_6+W5@6 z7LyVj$tizMU<^bOUD|u`0t@=vp@!o| zl&lM+Ybz_(jy@*dr(<6}9w&@*I8WP0c;5zMwX?GWjkw_>BBsu@APekOS@&j_)175I zF)T~o&AfMIx65ehX?irM!V6{h`hYK&Lyaj&$6Gh z`0P!-6FXdek(uH%G&E`I;?A?i0AvFZ8knBvwEW6}@=5{=2gv`M?ilRQk|rqC?lWOe z_Mkg@2@fv~@FRvz8GtMz!_lXBDNeW)Tl57W(X#hPf9a&fpg;}!)p*40FCgRo1oj1K ziuy?iGbZL8fFN+iAZ*Fq1T2007dhyhj}4` zzJ=+MOW>siasp7Z`fyd~?N##lc}@{wVTVLRxPjG}l_oLd0z61U zfl7y&Q&cY$o6H7w>IM54D%PL51Y1rZ`DAj=&__qQ0g%ix!4S+lUD%Zc)i&R}hpzf~ zM-z0U2Czz8#>HjAxU0l&iX4iHc^`0tP-Aj@u#Gtxm8P~=qNRBsW0J$NQ(4Zi5FbA- zp!Bmi!}s(A;R1*Z4&cM2D-rQYgc!~>(btW-Ro|RF@T#b^Rcmx)bmPg(ry{a0UoKMTsH5n{3qzn=)85Y1d9K24z4J3d7f=mvqN-aTZq-?dj2&^BlFD@p?gU&pTa74Wo z$4qt|-(%;K&6LvtCyn^oUr#8FLHq`x_&OnBJ*2E}3M*}-r=W@y0#vq?<9h)LaUoD# z(Zgjf%PRpuEgAahY(d}51nbP!%5cn;+q~Dn;0{?=4ID4FRog_NgQg15q6EvvqbE;L zF4pTle;%03&rUZ5qj;qRd{2Y{Cu=A70J6JIN*Vxr2dXx}_o9KNYLZ6l5_87G9686F zg$1(=g_JJnyhuaG0L)DWAQ@qNa8tZCq{iH)uk5Uj1~wYpfh_FooOLh9fxU9Ye=Z_a^O@U3$b@hW`yFb|r5 zxXHy%^?5l1gS*h*04RGM(QJf;bHwayxIqHOS68PW9RHE1qqRHBa(6%^`~`%H_Pa_%AcKs zD7o|St=(cbEf8iAV5)FS3~8e}B2vrB&cLG}A{Mv+qrt#&Q(*3>Ywc)9`x5f}pxKkz%uE5Jv}(E?{1}Aa#}*ch@9-(-Qa^|mj+M2``1A*dEB@qA zx#9XiK>pE;3qwJs^%=~NiCv`G^q%riw1tjX@C0Ud(ZEt({v;X5OVsw z4!YOEet(ACui z*|r51!J(=>cH9(Ty%4NK6LjnTKpz}rE3Hbm>n)Xr)nL(q>$ro*(snX4x&};N1Vltl z2)7sY;)lM@XAqW=M&@MwI~4R!EI(&|0gAE@N^PvLJ12BG5ql;SPMlk}Zb5N^-G4cT zO*aGb-J7>>HBz3>E-!b05`d^zh`S9+WjZ89%q**V;TtgMfD=m%%&N{cqhBE65bqBt zW`GrOA3S*A28rMs{&iw7jlzzAEB=Cqh7Sa+Up8U@@~VF;m5>uD+3f z#CDa{8N+MK`e@WHp$=dMLf9033Cb6j)525e z#(WzN>*r97bf{n1nV2Y`i3`H`bP)t!7{a6QRBHEHDehM*u_8fyv`2gE7@yyTkcpyU z&cCYW$(P!U5`)>Lm~FIj#&z@_18_(Q4wq#$5N-kh_J9h?@QdH}xm&)a`8%q+yTph9 z%<@6(#4Y5yx~o8;>R^}86Y%(KkNBP*r)6dml9INa93LWW>i{R$8HA63Bmvf!8^Y`3 zp-D;PAUKvtJ)Sil{q79rkw1`tu;b1r6dJd8XDOW|eQX=e1Thx$)gKyuzM!d*BL*k19XDJ4-F|JqJy z)iKP$M#q`9XMa}jKK(vwv?04HTR&$#yD->sk@U@ejFO||bp{T1Iy6qWi2H?nz1lO$ zP_&>F;8X=c7$reeIf8U@H}7=q z6Z!@ExT7#tF7!{h!A2c#92 zL(UK9CNY-@9>Q(tx}bINbV%QSBtm)fU$fN=Yh;voJ1J3^CN)|VjiZ>WB>+W?F2X-3 zD2M=md9BNcQ=d11K{Yq=Kno0s$iTFKQ&BwCt-4#PSYVl4UQq$E5d))YZctJZV}2Aj zNFf09?Oa{|uO%#L8wVG6x?k6K7R<$fk)n)bADDECy1Kf8Xe}*-99%+PVKv_pzH&l- zDGm?#FVnu#@_!lLR-Ik2U}5jA@c*@(JzC{=!D7)U`u~3gTGan|>mFG~%FEMnbKgk)rS`=gW&$)Bkwn9&{RV#$Cd}nSzJ@_wxvW z0I_8e^pb+P@iKdA$Xu#t=gJzOb8$}QG~*VvHGLB2NwSqX}MhGM!j#@x`*aPjA-v%qEHD9>lL^%>v^0%W3I zvAbiQc@5DFpjn=mk(EW@nHqDnLFehjYkWYd0R$n^$Utap%jwXFBjm~P;VDm85_z+w zpu=~IxqL_u5F4EI7PX6C!Tz#z7(vH#&n?}>1u20qp!?wnasZ+#L*u0rATUJ2)lhW_ zRvMafrl#}Z1J7ZO8H|y+Do8Hgog7>d#zYAw37`h6k&y*xZ8Eb3 zlk$N54qCkkKynO%Ub_e)*-<|ZngEVV4c1V|_@Uw923(_1@}a&k1FX`6qa?CPf;VAP zes@`kU-CdSETA8YL&b>FygXi$0Nl!W;CqE>JhlAAFAA$YVQ!Es1e<)9lvE9=Ze zC*QacTnr54IB?#ARj0BAaV94mAX#UXNBR}AKf_1O}CH@)6q7x;g#aC5% z7sOl7HP+T*!#Hxm`LMJHqBnA8gu-)~W62Y8LmP)SJeK)*wFnk)i8<)adcnaAs1k)4 zo!#KtKiQkc|Hp0i8t1#yVjVOlk?toP^u^MH;r3>$;)5Rp>nf$FEQo(r(fywuzI$K; zhZtMN>#M?r+kGC&*<9f(b=W(+cqFjg1X>-x(}Fm|6Ix%u5!mosyB#a;7u%QrH6bbtQtHjq@Xj(9maYR|d-w~AwWqT)7-gD@D_kv6*e*!%@_{b3ZSif*%VRk1 zCKV3Z?sF4*1yYd$1Ev_^_GF_9_5GU}_27UgwzvtBRT{u&gdvTD`vNcQSU&*iZ4P>Z zAYaVHib9tTA`NL!!{kb8XpoYSkU-nLQLytYzVHj^!HoMHA|QYtG*Q4r!HDVpJsM1f z(AatP>Q%tzb!3C|tVYemMOH3fz67V36&1q;e2xa>j-TFO2+4W#0E6G~{(Xjk4~>b! zs!57M^Vi6toN10FQuWlwa!ZGUr)UMtdVJJKUjbudl*nZKF=^a!#rL8J^U?>^aNyd% zu*0V_U+T-CkP$qc$Cn?Sbjaxokp_bT`%cvR069p5=uF@>dIR_k z7)Ob`E24btBVmih_&g`pFb+^OY%T=mK>!1{DRR1I$X|PZ7ZQs zBUS6M9YCGFHJPXo2nOgcF;bZ#+!ghMSAdv^%D*;oXOk;3lH$6 z2{4UKLYIzr`XBvvOQ;0&FlbUaeshinZ>xqzyqtA0$nY-911|#u13Qbr&y9Ff!PpQ1 z+SmrP?B_{zfzlyXs&TK)E1(hoQ&^3ZMrPt__3lkd&OC2RW^QNAp3sV=bQ;7RhAmsp zn?lGS#fQPXOuRgnGh_2yE^t{c+DWTzCEA_Lgdz|Mk`SDk2mNj&bfSvS;*ovvMaYhu(7T`6lx>Vt?f5DD1FH;(!J~=|>VFC~@qN9U%xE zlWgHU3k2&^P*kO2iS{k&u{w$sW`6ofSZNl8erR!xu)f}lJo0f`0SSl4^|CV&t`l$SUOLNcrh zpVFo*4`$V?yswu*x{z6H@bFXHnDU|xgIjwNLn&#PpNI*HFSR|-mpd%n#W2OQoE$Ys zSh*{`LRs!z%?q*ZE6E5a1fscO@t8Z{=srJ_5*4RVPv9A6^F zyMQ=rHaAmcVpyTSn*e)sRzMdfV;{_T>Qx>*fTl4y^jj0m}F(aB* zaWzBTCRX!H)-!NYsprmwGnkZ564WtKwXfm(pt-s53a@n39hc|k#+xS33ik+{MR%5? zN7>MuaBMOOGT?n(aSOl{xoYCP`D?sdUSc2xChgJgp{U_l>TN4Ho4cRE3Rwf#b zbBC{)-hFfJLF7#WVHE4zuXv>|!@%fQM zRr|J5aWTy{p!@T&=b4%0R?B-WmLav=D$2^rF3`-!DcXe0tcwY%^rkBuBP-eWTuCDGUh-qqi3-Uim znw`+Qxgri7GU?B8=ixxntqASmNWAmy9h0}TR;JES;lI9H`YO#Z`kZk_T54+QId_Rq zB+|Zo&ujX0BHFa7+x@oh$=BknRA1g#jppHAml{V*y?tMALS;E`@wyHs1j4zphqpLM z)H@y|MQFk04VKtXKSmDqK?!buq%j5680j4%A`n1J0)D~=m+l071Yn7HF90Ci@;ENc z$zcwm5RrytF8#&1F0_t$!&Z8TA&Khzg-7e%9Klk)&s+MBq zQ6hDEL*kRj!@@7e&&AX-j!~mO57Q?LYEh5?T~P62iffWaO* z0>83^&8^||BH{%#8_2%{SR=zG_~3Jb#n`5_6o=*MO^obPfhV9kJK~aLVeEAIN zW^SUDEt<=Uks=v*u{R^Po`v078K;zu+F4pyXaFX?F`DQt!b8lN70o^_7rc29S5kTKB`4xJ@2o1;$D$}qF>cXZ+&}Nn*P8p@;%goe zDc^3q3XgR6CHIo?J-rLjxBl=%ie^^H$M4kmITsXt%qti?Gg9L_-n(+`fm#-1MXe=T zoI7vssYe&K)G(N%ANS<;GT?j9)pz%B1j>koX5_3<%O70uoX%Wtu01yclT?PytHDq`^`G@Jx>n4x^pNyrRR9vTH00mDYq6`Z6VNhz|8fK###xU|61LdMYI{#QbOO; zc$)Mc?v3Bg-S0Lt&UHja3S5?t)lt71J1c>aLdhPS$7=Hs!_d`o!G|7P!hMP%+UKKP z88jPWkR*s@zj{n^WrIqadx*iYP&D4WWjXN`N0Gcn*F5IwL3Z3zpRt$cd^QcbC)7V= z6~v#O9EdeC?NWeq8(2aITg}k}(A2@4;j}yu24_in;JgMFbbzyA#w#+(gR%~PEG>oZ~_MZimC!W zg0!8kUw^jX2#av-^GwU#(~QhCDs%LouDX+K_0FLQ_2N8J; zP|2nyC&NztI~rgoEp(^jLN6V3xyi-FRB&)lj&g~sBCwTBMaV%k!QqA1t4BUEN1V;A+3gtBxBhFw+D1EI(?Ha5S z2re-Ae7F0sYe2A`W1>*E^3Lr!YQ8GA!pU6A52GN|V`yRZ@~jzD`$vx-7s7}^baWa^ z0OLH6&Snh8p->5hLLovZ5S1f931ww7=SU8>mzp6nng9BH-nM$5E`iUMw{5!`jsmA9 zK0yM=kGht#o#y<74Z6kHxhFVRZX})Skk-}Vx))`=;jQS@of3%7C}P{|@$)Pb$R;^R z6hdQM&rb{<s>-?#9qD)@2>-dq()D3adN_ue@58+ z1A~LV(xeEXVd}UN6BpMC9tx09Nnxb_p0Mpa=u_221Xt+oBhC~!LoNfy=RU2@ zBajK&>mbrvoG}f6#6k#m0swzyE-R#1(9f=i)C|+#4d=OgEqJbwa#PXKJ$BRrsDY5v zQ#iZvG)wu5G9%>QOm{YB=A5S~&2aJu6o}hMH@uZTB@ILar^RkRDB+9C@TC{`LHm1_ z-3K=GU(gT(d$h_I^h21id?JA?U-`W~?z-m8>#M62Wfk)s7yLhn$#@-+OiiO(*ib|d zE{l>0?VJtWe35x1#==x|SmbazbgWL%)e+dOJ3Wm)BjEjfpOrvht0uMh5VbYioqkN7 zy``QWE2Dmx%L2NF)5GxalduylymUcYrUtYhL3`}FW;@M!xw0zC!^ycn%eYhg`^|0S<}4kuqE? zKE6@|Zwj%~BQBt$dY}=1>9YWp-hDAWW)E}+>;X`OKqfZ;FD_zJ0x{MBJd+fnUTPC) zBeegsS^6@kJyQA;%!c`2HS$M~c~ubFKcnk8}H8$RY0Q^fkQw{azT1BUBO+S@r?YP$(! zLTf1woM7((jdxlWYgn^8LwZO+j$uRV1)THP3q6_mpjW_gDNTB{G{vj|Xgwhu`v;tr zhI8mpNF^YSkZ*v1s`YDm4J?ik5rhEf{cw`Ox2g+b`fWCl5z%9f}n59IIbn=1qf&&gY z)dJlk^APw33-Om?7m+$aK%z0DOVQAF)lzOT(n)qnE=njd-s8^249j}N63 zxn!PK*K*PFXHbeW$xg^#hlE66Gv6VssQN|xBIU*JrM5VUGc~@VSSMnBs8kW$&unv^ z)quQSXra15ZSH_g&7B97)vzgqJYi`Mj%SBQMEfWkr*PJvd#yr-DoCtvh|9~RVvHqfeZ zoxAG1DBy^Opo&;kRTVaOEyPTG0r<2tWaA#dp(`^0ZqN>4QuahDo@0!vgzUawu~m<6 zKB`FXjdC+{LXJpiv}#SXsP$mcVde%(&C^(t;sK9I7JH zgWTMM1bwz#iFkBmq@}BC4oY6UUYL)w3>YqZEsE#J5c3%*_#N>)fdF)-r>5%Qy9>ZY zLc_yTEWUdd;ZM*^Ew`V3TU$H?-|E4AXx?+x2ph1d+0gT+e*3~;8FJcrX0pSuD+q>& zll^&0#O?yR9h?IUy3H2?70b|2>9@?vWeA1GnMYB#XJS;s_>Lpxjmc>pJ!2!BWIuJr zGrF`{B^EvuqE$cqpea3me(7?WR1K^5d7VvJA+_g`KL-0x7wi75rVoXNdh%V2yL771 zv%~6X8N)x*rR3uc>b|{uvseD}n|F^FTK&_5^HA;UtGy55sWBZ*4z8}va10w{T(KQD zT7K9|a-AIvv&GWs-Ek}#H9wCbgGg z9tr}Za>YOKkj8w2?a}>ML+Q*k!+=-$4FO36YS%E|<>Ot(pErHnTIqiFE=P(Ze}f{KA^ zy7dDzZu7CqaucvEtLl17czArLb9RJtVsI=SX|jRjr0CFjG6YW8PeW$~7NbG6Gyv9% zn1=;#@`3u;3{6gAP9w?OI8$gx(t;-3k`-GHW(+~s)g1R4XpQW5yp9PJ&R=K0_WozzZr1m^KErjrr>kUhm`IXt z?Y={o1egcP(zu2kk~KKJ?|XzhZBakFQ*$LH%qUf_WvRt{mME_BBZGa)nk#$#dx!5| z9N31Zj{j9x`8MXL(C9Q8#Z z4m#ZuNE?c=h3%FVJg3q6AX0aLr5(dnphH5X%X! zpGY)U{?b>5wP{q%!+u*n0%)_VxTu?Y9AvE*PLs<>G=MeiH#QD*pf!V{&~Osz4(x{N zIHvwB(+@4kj88zp_8g}$DG>mw5=8*|*lUBE?aAG{*6cw5TZ(LC$^k2N_NyIB!q4!j z9k$%Kxte)}`XbxAc+M3Jm*@ABKb42S`~k~N z?FOpg(bG}oajeO4KP9hR@n_M}3el&&)4iWoNGd?6ZWK$8THDy*+}JgrrD?+=OgiwJ zYk6|#R<2SJJ{Xq&jcs%Fnw3_ux-&2McRN=+KAyvF8Z9P3F_zTWEc5q=6~AlFc2=Om zqodnRoR&xjLlv{^zP-4~!b)8W1!~6%yK@%NSy67y&s6%NQEH5fZO>4ohp9T@{O9wFh5k#+Z#vITxlFZ(2j5>j z?as0($C~Bek5Hn)x`R_RL-2NwHs?|A8xY*p{_MolSuU|qRb8BOzj*M*$`X<9!ELGK zPc_ul>z3Z;HKyk6a3T;1o|kb$wp8*0y@9IU0oIaD6=TOn`4F2+rvmLv;#cT{R#R(__vCaxtVSRqQ7n@x5i4G99SxGtqyf+!*B>AL|cz6CtO zs`;s|t6AvJixdhC2zfZyV)!_fH2p`f2kNg$c#)-he*^E=-igOw1ZY>3Eo)-*E$=Nn z{dy%hmb;lIl)boHqcp+O9LEzB{a-p<(CkCvE1J}rFem%8;+Bl-@3pYEuvkC%^G)$T zt_AqPz`N|I^8wu@Yo7ZB@u$tPE$rRxd_pqF!&5k?wtu3z*ko%Xx2(cUcIqkXW~v*U zjVKfNp-F`vwR&)(qnI8wB)gRTBdUR#+DbeFLI;@ecwK-myS+;H3LCp3RR z0bm2oa8aOy=|FhXqhk+2IPa-wVFfCcq!I0BxvI=FJYdiFt~zZUsY3;;e$7USsZIQt zn6bPlNq5^ZV9CzAhx(@E{0ulAqO3RgxkoVHP@r6s zK$A%FgUCgKY@Ykot$w^Sb zDAZx&vPZxcZc!8bIf$J_U4LIBb`&rKo1hINud|^cr)X;T%}my$*d+)?^M%jid_&qt z(7nX-MzWGXrAzfLj=o_gmL??a5UPPx45Ze>8V>vB=(Sc)&Dn{yp~|pspYOqytGrA1 zg|bth8&uuRYiF-*k*k_EuA4JsD& zY(9Wzh~f?y2^~yWqyQj#K6L7I9q@v|E)fRt7*TWXw{1IzqMPs@2+gFB%mv_*W?2$0 z&d!<0E{MJc&?kLD3Q{)U1>{8%^<~8*>9@dwX+tGNK~l(Gl=AN&&n*EoOmRYiVA+ty zPC7;`z}?kYUK)q`QYa{^8zrkiLmvSlN^*Pg?Df_eaFUL^p5nSsOYVSmiFl>Z84xdi z(j^~7ZxO{Ms~bKA0A@Y77_XtzUbaVlH9)dyzlNhH^=_=H&GnK{@1MQZp!&(uMQM6? z&o(wrnO)duIRCRNbI?f3J1&9QyPFTdQhb*;-kB0uIB(dQMO!5*KyUzzZm(MA4rUQ7s8upi=p;ZlH8KW?l%V`}rj- z9@K_Y$Q`k>LFsV%`iQ{_Q$aQPWe3oP6GVeN@Ri}#ZPL;lAHu^^Ib{Zr0aN)4?U9o4G+#I5_k#<65go(!GUkz5+<4}EB7=y znnhl=J~;gM>3seDiA9XiD#Y^yR!%J`0r=mvA3bbq=$5E+Kmap;EQ$yo6#Mi~1u)#L z0?`fWLQBiXdAt~I@>YoK5}MC4Q=l4dzJ6$V)m;=(0VsAly1L#Vm`w8W_Z3*4^q09_ zyngkH_z4}Nd^L~Sc)>76xj51$ixj8?=dB$fA%n{a4Ys@ z>JV%)sOw13K!Q#x1!(`{;%mP=&p{TANbVD&ZeD9kzWj7w_j!RSM|iK#&S8fFD00-`;ER=`Gn+0$3=Vz&Z;)tl(rWTuMx;fNMEyXeW zm`OpJbBOQ0zU7;5j>~?-9aGyT zbno8vSL~;Eu0Ge$-4ztx(S%4lNC6H&@Lio~30ZeIFr?A4T^Sb#zwASGN$7Yy#Wt+2 z!i5gyG9YO5y>!7Kp^%e9~weV&7o|UdPUE zc|(tBTba}l#dGOKwU9*9h+B#F5gQrVHpM!|)1`i~WIq?8-`R}{@uyw5Gvnh&j~-d$ zRTC1TKL;d4H5LX)2*Kvj6%0?=1-7gPydl^~VXx4LMOeL=9XJWO7Gr!d`idtlRcxbZ~ zonlkpz`q44zZr}2t^@PSx8E1rq8>kA-90>v2ooW-Gh1d-KZ?}Vx~jxquicp%o|KW6 z5%`DXIDz22yQz^|Z?0X&cQC7U2WOp>>hr#!DM8su2KQrSp_TirT zgib?)Y9P)_QaaxW{f0sZs8lAhP%WBhXUO$>sIZti6e=_!DPPkoR?mh?l zyXUbnfqz%XYsri)B^U$rcZUlbumS*#gPDB$qgP@lT>J-(pxyvFO&{wzP1d zjKqp1P$$m9-Sy%-HNq5de)u$>Gbzq0wKZAzSOwK)DpK(TgYQE4+4t(oK*Me{c)sY= z;rB_zQbIIJ&X=iiWF5xqq=Fu~`gDrij=0^(zlW_suy^o7r@xDPtxb-Xr9Yx-TW7@d zu@!y$e=2{O6`X+8$HvUdCqw@+F$$8Sw^(A?(>gNoP=3!jjTP6*uDp(S%Qz!k60vFX zMiIWUHA8aT-0p1ELsLDI(Y7cH%R={7fdQcV-M+X`ilZ+aV*<$>B{!}&!5W#m_7S=K$v7N7epfv^*> z!CFxA1BSsq2SMR|I=$!J#0Ybu0H>=U^=P7vXuxoNqT%Ss zZZx8ggCL!-OmJkUeki6rdc<#SZS90+3MizPLi{keG+7c?p0?J}t?XoyHj zgLi<=U<}yNF{ntOP#2#?2GTxM=#Yn9w6lBjrmLO%DarMP+8YEGxIa~Vzt9{+OwGfE z0KUS$nWRxf{}khWXOArbC!RMtp<}3G;e~l^I7Q;RG-pmDHv^{Ms*x^URL+3KiGI+t z?;lk3jjg(nxuP3-_vQ_0#(|nC+S}U~G?KKtzScZZvR?^`3uFORqea_UB!A(O`xBLV z{`1Q0(*!h|kj;4JM(8~lra~%T=AHs5~6B^$BF{xs3$4ZC;>7u zYvg>Oj9dpYOGQQHfm|q(E(k^S&SxWpn8vt@kxZjCu>gbt0kAv(q09l&lJKvhq9WI- zSsYxX)d?LbKv6+FVNes2tQORbZ$WT?_c<9;O6=80_(A$zv3cyZ_cxX?{YL1==)?rL z8eQ61ROJZB+=iM48@{&CebKdLds+)R3S3ocF{UsxND-A2ERjS`j#l{-3G{Rv+=Lpd zZtw~U4=7$h;eD8jAlcJkDv?ju)G>>+og~zwBx4UP5(!`-^$*J2KX^bP#6I}xa!e6^GU-Vo$P zFb;I|;2S7t^~^>iu#?V#7e)i!mw2lHF?2W%0Zp!{xT+3~8G~*y07_{6QY&+SNRV`l zhBSTp?}>rP{-mLSfJk0!ND#->;W5;L^uqYov3=j+8xxxn$A&`9oML$dR(TL54Df$7 znO4mLQ$2@W7H&q+goXyFwa%UmWwWN^dzBR{_8@5gb<5Qi7z3LdaNO<$K5>+8E3U)rbK ztvB{%2;6)o*W4F%=*&hn`ECu#44J_dcFD2L$%&$#V|C3terbep%>T@ZY6|1xOEu*0 zQVQamcc@j1K*s}vLlKA(k0^!HhK8gjFNWk5FVt$%07^9UoV`%&ZIzS^$3{U4$6I{x zRKq+GA|yoTKh5w6j72HlC3I`qe8NdktG=nK(lU=92jtH#5F92k(c*?_GxBqGLc(v~HUM`N>H*Xw%Ijt5p}bHp7+Pya%%n)oItQto|5sbA zqB%56L;(u*#TZlrq)T6I<&6t8{|J(5J z1!1!>oCBayPMAl6%q)I4@oOp{%ebkjDNnFhAOm$$q;1R3zN!zj?Cj628JA_}UG{uP z3nEVs><PwS(*^K3_VF8pcpx8K8#hiiS{bYxhv}c9|w07kt%p@rShf)MU zUd+;8KtO;Z<20(U{?R;g5$^c;^?)bqB5@^gcwNN$gs{V2Nsik4I6^NW01t`b33*gV zRFiE1>m%-@6bK7(s3BJ%kg72=GXok2MvkSZ5`+ivE`PDW7zX?e~+T_M5NPVBcOcqi;W2ejlqYFeauFEeGP_O#T}QSSN`A0@(^a-5CfN z12$KS1EOHMha;MD0?0$&wb`7?1!iu!9g>og?Gx}`Z~{=qj(5n}m2t+Y7G5a_pMWXk4Cl(#+wfaprNS)Wn!1D4Dlz?)3Q@kjJq zXV119ZrBe!u?rxd|H_8;gkRReH?sf0z^cnSJ;;NI3v6(PvI8F^Mf8*QibH_u#Ju*i zVj_kK09cY(8DSibIHLQy6*w)QMqG2pA%S1Yv<2D$$;;=S{v1Fa6IlePbDuJ9a=Chy zC`B~y9w>s>LLPjf4+-EIu46@0drD${d6asnTWMvbA5Nh3q4A>aWowiKqQSaK!VyJeR3G1lvb_w@2Gc>)0ehEG18B ztEyUo^%e&>x;ze@BGIfP2Ra;kRR;^fibX5R0-=lT3U&&2u zPEc5r_YTzz$u=dPHeAYkf0|F>d$&VO4OuI=q=Z_5R$>@ZwSDNVS7To4D?#y_8q+II_VT_kPCq+}^sF6gGn zL0Hc36(yJhL6p?8BWg1diYo@R>-)pXlmhefFWkApn80Y2#A&E!;lF`5sqX97hi^BY z+*s1ONl;8X`@Fbj#A2qYd|1wP#V|Ue5zoQaLJ213V31acibVw&I0?50pCsX6cT@Nd zw%zxLeaj?in|?KNf2x8j3n~){olmO_@cbMS)`ZdVQtKA-!{tR zUxK;)_=#Bc1gT`lYRV38zO*AI=9T=#;*1G*o*yoxC>&LzMfYTv>#+4`$mdtz|Cd`f z9Qe=+ttCm>{uJX(y#Nsy@nFG?(S-^H7QjF(1Jw=s5iR$i__ zA_93*jG4BjowYn(T7OpiOcUQtUcsY}^)EfKUuj}FzKddNf4^QanY^7(+Blia}fL)Jlc+;LE5@komn!RIFHrzCy=XAuJL!au7qexu@e} z+VMfwkfZ$QH+%++i zy#ELNEbLHscgObaO1*N>j^gw(N3D;@mJKtm=u%B^sq z@h~JBxUOk0N-kXXBv%=G3I{yNzu$N4iPze1V_P_*N5?F0`fF{k@SMoDa=$$Ih52o1 z>^`5{VF7WRVpc6VXPyQf-?s8w`&gZ}s3Rn#rv|?qdtXrN$j*_F$ZvY2&$R5zzS2t% z=U$-|TwWoO^i@ReChxN!;pRkd1}8~llOB4k_1W(a7&&)uAaSZ#b;txEcPPv=L^l0s z0uHjnn3M;l)V&DGHVk6zNM? zNLBa#{VmiV8=V&af>38~>=rD*HQF^Y!d!&T`Nie#mFQUa+K+0iuoFjkS9Bu;U~3ShtrfFmA3Uye-SBIsH{Uk+@Egt!su(8vZVL5%@# z+eIkadA<@Nhm^>;St4wvv)z%Yfmp~W^v36F6@n>CNw;Q!GXy?Xk{V2GifZBO6U08J z=?5aL2*)c0)>v*8H8p~3H4b)t|E^4?UFBcNNR1GO1~R^8<+`eg~$B0+l8 zp}unehpmN)(mpq8k6K~;7mwUR+GoF5_d@QOZ_K!rJ8BT$m}HM=jwFC7=K3(1+v+D?q9RZlZKmm!+Ge?D+}& z(qxYMMJj`S$r7U30@T;#yT7g4Is*=1G;{Tdw+R4+zkLxpD_2)n%8M%_F_mdg(OIBO zo<lP9{sL{pk2u7X66}>rR6IRy4_Xynn;L0v;KfC@y21-b-QTcH=P5`5Yb4&5wR2Y=*<553ZX9;<_T2RKdeWf z%m>Ulhqe?HP!jPs11PvS_xn;0G5|6CDnXZ`oTSq&#Rt@;inxlx_A@5va~~;bjU``7QKn)0}`bTTtgy|GKDvv7%$aDzg^N>k) zU|bPVgF2kxj|dZTm~^;wsm9p`!F(4ZFB^FvGm@0>G(ixgf z;?ltCLj#F(eNj8_vRTDGY*Dlxiw9<1eu}`79rTJnIVB8e#UpUZk#?Yp2J(4ZF6Qe*B&Ik9kv~Y>1jtI8%&(m5^md zup>4JNhb}O0B-VMh;1K-Js=D51^X8k%0m}P=8i49;Ew!`Rh5ZW2$?~RE(`d4k6z17 z{>P}O@TOB}Hn2}o;HO>gfo6xymO+mLF*te~8WjJAR+}IgcxKI_EP8hQzO7thkw^Eg zPaqis$3>N;=k>$y@R`25%Ky&$>6uwteQney!_hSCB!Xok)d{|75E$}KNZ|8jOGgkl z$+5#cKp$vw2vmb7GY8MnP6*9&gdP&#>wYo!u^g9 zW*se?GQuYZlcw$<6P(u(4yhMxMTj70M34p=Y|KGe2^>JQY}&@!8e>L?^-SEje zIl66J8Stc7x4j~xR+b=Vs^afef1}b3XCL+gSh7PnOOTMi3anBb7@cH`99XM#66O`Q zAIz%V#{4@(RY$5K)Qyh9uA2;vlTfUHCw1k2=^})F`Jn7>|4VrPAJ-jPu=nR0_aCn@ z*c3W`|6wBa1HIpvg?#IqLT3MQ58I|J-Ef5)OOjMqQciK1^(4bG%DP!t7g9n{9pzKZ z(vTfY#|$8qHw$@yh>KCoF8=EgeZGG}1K$A(Y=)ubi&4f}!$S!jKk2EGmYU^?7xTj3czW|o2Gr`0 zg9&y(Y1LC4RT}&+6MXYfb?k|U*6Z^=T5qD$NvivD&QM<-9<$9oTf}r#P*(l<9IUD3 zmSHkqd`fG$_TvGvY`_>VcvZ+@A z?p$HRq9VFSePx8ee}tYwr}dcKoCY|bmod7B!&A_xtoXg2L1xTzW=&-{y zumLWo(DpuPJ{D!_OQ2DbDh*Hz5d+>BYl)`W40V0pqRL5dq`-!SSd`t`}$e;xl{d{%KSy%2hEnV zn~D@D*YKO}#LwIpbqg99dEVb1YfAKrr3s~>O%*b;Bi!=)u2i{OXg{RmjOo{oGbL~} zSV$sTNBvy{0uz@hMjB`!DT2g`aB+pynBdc@qx^t1jii4=6;CEJpv7%Msxh8s+2tk1 zz@4Dmdsf}ZUzz#-CvH$0YBeG&M-m)_enjvJ+$i(hM;7p$8qIQlo?Aja>P~WDCCjPd zvwdD>br~06yG>M`$g4kxazv;>GX0AsNh z5-kI0?R@rTq;TNGuShporj@zuHw2#;(`k;R=Dap&2=_q11&?2k^BfR!A}B(&tGD4e zG_>24KWcML1~1=Wr_x)0)V#*6`q}p^Hj~#v;z_zLQIb+ps^^o1+2{8K=~~1^Q>iIQ zx>RR+coscBFJq|qN3Egf#cqwZIf(_$nbBeQ?^1B{vm5zE(Mq=VP% zjyL}oAt@4jPfrHfh=3EuRT*Rzi+>DwxDJ9r*W=U*e7S^ZX>X4GE(}p}tAx_V}U=h@=RQxExq) zYH=ulH?|)AjlO|Q@By+Xbb%UA6hRv5i=oa#%kHUr3eD|JyAE|6%ba-1Z8NJ=afYY% zS_z89xh^NQA0&O}OHUUZyA23{Ov?2f`GuHTtd5OO=&bzG%x3(;>obh}o94~g`oH`y z4#T3$utfo|JB&7nNdJIh-NrFMRI}@40OS&g5x_hJ6I8S?^Xp$_E7H-Fcb@wGU+sks z02XnSh(f=CGvpqwcu=&jCY!BL?9o$j&!h2uMx%WaSF-sZS{tXq%w_8~ZajjzC0xuh zfZBq((0(#AJ39${fpbh3z9|_PBk>LQ=J^AnC%Za(9v>FUmeoiWB2!0vef2eB$ZEXl zb&TuiPxH#4w@N;6JYL>LQ4)OAX{qTdt-gZ2!U~5neQ96iXQF| znrzK|m3w7d_ov`q&-fADHv%I+)s)~PqPtunWdQ#*j6D(VV1Ug=fB$!3ub6`z z`y=cB8Vw=a0L)=XvjL<)f~X)%jnjKVa_)eYL>w=_v67j&7ghK7KrOjqwDizcq9^!> zHgrOE5<8oW6M;G>02MzZGDI1Q23hDh$9OGt?^rp+{Yc1qNPY4q(bQ4LzRj7h?b&aj zy*Ll;a4;HBQ8cjNw6|aXql9CPbX@7XPq%v2iLp4& z@*v0EIsHsWS@XcP*oiA`u#Ejvz3B5T=sV%R6(wjE;KXm(bRoTD2 z%-8+GXlzDLV9<<*hd{@2vp{qyx_BsA?aeNQG5 za>+O;Af`1;?wS;)A;ARO*0Jw@Qvn}3@41bT6_6^CfK%`r9sT{pqJZJHj@Lc)%NBES zo5)PTlplw0S*nFZM&s(@#vk^HO5TOyYK4jSK0&+95x)Y2sE^|(On6A;ffqZ*EF1+`0g4 z_ zD%JWKnwQWCQlPnB@_lLCPxC+l%jD)E0w+Pi+|X22oq2z~eSP~BxDV%?&lq%!cyfZ} zz_R;X&l4G0fGSQ6%@UgN&*h`zn7N2k2u0jl$SL%m z8ma=Xh#xUWOGYLg!C_X52tE-}Q35RKLt#bKRf+!4Ad=~!BwrgU2TiCv$>eB~TLIq* zt^wk!HgcOb+rr7|@YLkT7m&aNQX{-3Dc2ChMH17{-e*>30*F~$EZmZv1a#OHgiw_9 zm7_bI^nnxt7M}RxP(^TNP-8^Ik=tG{7Rv3X@s_egL1w>_mb&-9e$A}9BiHJ<=DMW*19w0tzg4*%qks-^3~l|tMb)X!@ z2cR5;Xp#YiUN1vI*#n?mjWO|j#R#hOdFT*a}T8UMFiz&#|^IdM_^V8UY{jwo7Q!1 zcz5Nnc4^JA2M6hnTx4indu-_jdsnm8FRUAi%`Pgi-Z$aD@aP54)<=W2)#5f0Q~qK1 z?c-env!;4qzDU%H>HVnMohW&wY9y+iXc%#8A&PVfl)vh`yi`^}*QHL%`RF>vn7^D|r15?w<^FgS zlGPb!3*%%LQFPvzY}LsZ6lr;9;HbyJ6z?OZjG7PHGv7Jas&Nr4<_8QTJfAyOm%NgH z68H00O}~-wlKCorY+4dG%ug|kp75zHV zx6OOJrQFrXZ+O7+I6p>btX9*@f@j0YHtW#mYEp+1$LD76Us+Fyta#t{x?SMFldZh^ zSS&oX#=n`r&=s~9oxIke?W!=sy~6tg`-$+*zST9y1$XPnF3j6j#Z+Cpwo5!))MG|Z zlJ(CVb(Pn8GQtz(o9ya;+cv-UTr;w@@b{$$w;nrLQq9br^&CU-2ETL5jWkWpAi`-%nq2oVh0Jcb*ul!)M6gLMx~#?(V_%cb%qh zQ-jacrM>cH*nFN_*NKljp~>!`CA8Y#%;P66@claB%t5JV(>l9SNP1%U7KhphJ&!}Y zRJ^|B-Q|`G2OX3KOy3*tkK1#u+kC9S+}7^xrL0yvj4Ss-#@(2Ckp~?G1>F|U;-bQZ zUm498Bq*SX51^DZmrZ#k;d66yZc7E&3F7}E<6^8O_PiQZ1ou6}(z^!u0FbJsTRuSm z14v!Wwk-;mO3u@W-8?+o-co6S5fO(M7kXzKE};UGcA0eLdd}VR+GeTi5F4X;(yuqh zzYf}d4A1pXN_O0nxe%vvt$WBvA~IUmrQlJp+mE64Ho2a8ulw%Kj@R@?%wy)KW}{nY z-(QPr9F$?Oe{?GBoJ6EPd{agHY(30G!huAKBDF)jt)c&bLF6ID3hu?RQhlNyjh%YU&Q3VB>-4^q~&mH5n%%4CzZ&6QGxDS z%`h@Dk_gIwqrhpx6h2%IMrS0>;8VpFETtwL^XBVJPTo&>WYcV{(Er5Pi~3GH5g*B{ zDY<2c`nmG+T%T9u?=w?1LQ$hCP>MS>QK7j&4y5~B7k7ajlIt{a1%d^;j}+>KXiz;|db_(XftvXzw*@rOISlh+Wo4~b$w!^?2Jj=nH6h;2vhJI{J^#&T zuL!O`^qI;)mViy{TDQi?u0q_@}j&w=r4p5?zxsjL$Rg01W_rj8= z=^q9{Zjn(zB&7!C((JdUaN+Mg{O|$%O0V9UPESu8UhPXF`3A2hDy5~K&kcaoZ$3OKL8{`u%IF` zM6r=&(-P8hA%AsB-A5=q=oF3}TL=85hgK!m1u1GWI(9O$6F2j71TjiE^e-(UUn&0a zC*-Iq0DB^;aiU+!l-P^vqaD&JxW<;H)G-zTsQGl__5QE+>j}+_g$IUWW8lZ*osGL!->&QXj&E{r zAfIN5wM3{B0Qep<7lf3MTlVtv|M_tw`oK1J8?3|U6M=`66aAdj<>wkT8E=R07FQLm z*%5TJtUM$lIp8Scka)x5djb`^tiOYscnl9)ixqR>Kt;1sVFa`f? z4kREc#vPT;9~Be^24RuE$MJ#tniCBog#c6pqb4~E?F*B+6yhI70xOqO2VIQIu%zD> z$r3mTDmU>1 z2Jn=nczOFF*Q-RSc<)npNuPblmts&Km2}r{UupQl8)~TY?F$%j!MT@7CL)_w1z(jx zT?tl$419-bDY-&eS-HeeX>;7k6Jy0L=g*&hZRD+gV^=*nRu*VAuiRNrs|$a=jmK;A zWhgR```UCxrheAo)GhN1xslA17kY2?+9vAO**SM7he}2{ht0ORQjWA)4zr8izOegA z0arkcg^;*~R3tQlFlztC=!h46$&pLAq~QjHG7*kHk&YLix_L0H%LA{4-2)4SAqv9H ziOp63I(_L2DnET9wG0_ZjKlKZ5gT}d9hlA1(Tb+lBO_hU>P}aiX`9uqaXco;hr%g` zSvx__l~7>8=*M^<1ktO~caHec_=G7;OpCj&WDkERmLpsCjy3cjHpBz)4+&gDJvWClP;9!*3^x(85vuD-( z?#4AyhP^gdQ8`aTXoeH1yTQQL4B#?)aY~FwDyUkr>Up1vZpMgmF{_?%-YKLNFD-ve z#&4%*lSybj7!}=(^MV{B1zj)+tNXSV@?;onX2VE3;(r`S&*jH|GKZTmpbcmxgZu9{ z+-imx{CAQF%|U$TVPv^J(%w=BlJ9t{{LnVmv%6b$Z%lrV4tsxSx2|eRefGEbrWo1S zQ1@f9>-I=H-ZFEditFp!cPl<0fBt(a##iRog1oTt)@^*(r@MMTJG+o*VUih&A-^vG zcMzHGzk(JDi4`j4a=F*qY6x%ov3^+$-u6S#EIL=Zq)5p49%nnEO{HI&7L19;v19`L z<~;X9M!8}#@LZT+GzICvKzl8dkw8S3;hv44cI{Fd*MNXW#V+hN=S2305zgJq>IyiU zE?62H<*PB(D4H2>i%%~Ix&B#VQLeX8FK{NhKB&Gvi-A2Nm@jDm<`thtR~4NTyHt0d zqiOQ%^6yf1biY46Yf-tQCD2c?4QQxB{tf z0P~YEcf@(S=C&vL9}|)A7rikqh*#)=Ri@iddN>aMFF}CFYrrOarQBqyNn&6f^P_=2 zUq&%80T1d#AyV7FSm*rb>9MlAUJg9PA0O_(IcElYD$Y+DkY2RfML@}_UcT=z3qA85 zUCeYB_o50;a2S0|ICG4YmDO}l8#7p3H1f$3O*wwEWH6%Z%#)9WZ-rXfWJ0UI6&4sN zF;}RqKhLrHri~Lrb;g;qwK}yQzJwm^4XV7?FY&z6JYHsQ^o=Wu9del#h*T8Lb?=3x zFhqW?lNrfb^cd6!Q372`QLk^4UpHy}Q(c-VCF6S8r+3fmpE?UOjfEt} zzFw_`1MVGY2}-~o6PO7h+O244$@qEk%kG#$5RV(FN`7IC*=-{7f9Zo-(L*j=C8s~? z3#gq_Z9`JLz3Vv_^@Ti^(6*xFNwWNbGB^1fFEuqaTInCXdpDVFEqX2<_(JPt`c<)V zg_keGDx||*%C&0r!`zz2kLw$<8s&{jpK!l^@7cu_m-^ardZV{WbTb$pMB*|!iYg~^ zHDfF?^uJ8a6U^))J1nX=h1$H{`P`$=^DRDt}X8vb*uV3_1$_-N%U7$|3u{y zo0kPJ%~eN$9D?_t~S<$ z&+ZXsY!P>D`%P#~1NI(!!>u-TJEpZ=S*GGx8PHhXlLID|Q+16PavxbRlyj$L%nrbPy zlj+jtdyRYFsY_)SE6m5aH4F3q{UOR6SlsZfhq%W%xJDLd*>2*uQkNMtwKSx>R>-i7NAeZzkSyt?K$XC&Vsh za738#87<6LQ)zXDg=$htzKXP4=|(rrt1ismx!u;R^2t%a2Yp zr+>ZCsIZQ1tEecg_TU$AXXjI)-uUIi(5Z8#Ih;0ZK~E9zNvYyQYlH94_1ZDoEzi=z z!v1TSoh#2f<)Ds%B*FXhc{3Q{z-2$KopM@ya@J|IVxF>T^~FPl$*Tr8`R^`!TO8;- z*PE}gChEhkDLLn5hqA0#-qp%SEmugP)&yVh@eZoGAU`Wqk+CK^L0?g9(n6gxTSa+? ztAKD|bKKhWNsFGl$AePJmM-2JP90 zD}#MgZr>lQUQYSl>k#ei*rGLe#g=b-zBtu2map}9Yp8;8Q%|4F#;Nqh7~iu|Z_kTd zc8=u}^Uu{AaM{Ykn|HUhb;jT3T+e|fDcevlt!ch4}D>twFWNuU60=Ggy%Mcj!cM(XPii54D9e85M%^ znF7AJcdz?26G$CZ!$U+-J*D zyO((4pBsNE*wwq-Dvs9PkKD;*SDirvu(?Ny^$SQHB%*}{`?R_o)-^Kai_fQ zvdZ!u)wi7(c~{n`)iO|KM(oP}qXl3Q66{Ok@}lY-bI36%0^~^&K#^%l)NO=pBkn%K zYrj5YiVcasLGkzkvrR~RFm%OTIV~5Y2V^6s)1`ApPVG5#p(>e1Wt{#a?VoeQfdMj#hzukiX1*vg(_=c(w(JOiXQdT2$0G#dpE{|gTBlF-SN3MYQv|^DQgg` zzjLTN`pA!#hNC%k?>J()GA3Ui+Wb7T(DKtnWC3;BrTzKbYg=*h;+C#{nN%>&9pthQ z9V){$EcPSh;=_PS(R%l!mx5bjJ}Y1B*|2eADc(p^p50E2v|}KiVf26}XN)$+gcjMn zIi2~VUA{x`@&vv)Cr5*i*&pt`r&THLQtu5qbt@{gsAsR%cuz`c)AVak!xW#Ag#Pqg zzS?T`)eKavAMZ9yEUqs4tR!{5A>6xO9Y@W!u~lVN*Dgo6#A*Bv*f(nQTWVz-I+j(_8oVZx3`|{cDcLaXJ7TrJD$?dx}I#0aNy(lb(f*F zwtB-}jtMTNjm;E={#}a&mb4~xmTn>Tf?|OYdgdGqQJM}nL^HV3yMA<@{6{}zV0p^L z`HmnR?tunDzrEZC3g3>s_^^U&E_MyC-&xT(=WY%`9=hT1QBXriRs3U8(2dxo;QG&CHmeKi~UIsPDK1U$!Qo&H8Yl3=H{vWd3zxe6#>kKVCCpM<7tuRPvNI0ZkA+laT>43Gcwu~4c z-3jCUs{N8)ICOb{;cPn zT&wXQV%hqj{AR%Y6;(!88I7Detr{}qb9EY5zu4=! zUVmA4Ozv>buuSfdxlxltV!2&`YsZ|LY_9k5HdF#1%F|kzW%Iutg>uL$^$?zdig*Wi8{j&%676#>zgH+a1rhqlEU}cbk0sQN57BFQ?SKGF*O_ z`5j>TN+GwNPunz|hl%AKR7iu;dy^iBcf6E7lAUDJ^=Pw2p7-&PuNUM8y3TS+9irW| z7_8agzIQFq^O-8qC*=n*L_D);aPaFagca7zjx^;&R=WkDgOXnP!nnduz&e-jSg!WjXEQ_dM6LJKu)=h+;8#ShbBOcMrM#YT^@gGL1^nhS4mJ|`BVj81k47WR7fkd|c#3+wRi;#( zK73*7_$n>;kIdZNB5yAxmQArf7-g{$zcl-0SYxr*{nU$L-5E!XhBVL`4;T`D3(=ZS z^BZo9P`UVfYOHKhdeMzZurH|kSn6u}$Lk}U-@Wx{8Dg0EM|f`a(cGfnjYi7vE&0M! zltd=?+c>+`H43?p7=#o~rBkD^s_N~!Z7A9XucT+EL%l4w?$MdJdz<>XuWO+@a)Iu} zqA6a}g)1#EL>}@_F_ts>plGdOw*Sh}{J;>0<`wH0mmT)J-n9PerFV1g^cR2K_ag_i zNs{~G#FMN&fhtNm!K*3fJ#&T1)$wU7#zPGB_KWTEU9=Wk>^-&^{PJ8H&HQRF=W~|z z(-y-*es8%uW1Xue%KOZLmrS3!94)S-tav1Ljb_+^7xY7s&7_7Xsl@ySw0MJ&s@r+Y zzgRo!=+>!d4q=TTqh>F<)`_^=6>W66SE`3Ny?s6cW$$2Fs}0DIK8uC?Sqc+;Q#tXsWlcTU)^6`YjqiK&vYz>!x~S5n z9#u^pZ@$%MUU*TH#zsox&NwDr{d>vO3u`eNBr~+JO!mK_yp&>1P*u|9o_+P_l)^nK zvFX0xzwNEM7?Wnnu>-bPfcU9vC%Khq-~Jpu44I4Q)F8_*(r~*N7iKKgc$a~D)-j<8f{NLas z*^75tZ5|`P5gzdnlWVg(dW#W~!V#{q?t%tPDEf}0Q$lep5!PiCP`eK$C>VPT$_n4mdMBLj`BP=KXg$!oz;L@VI4{6?Mx zNn<2x%uFCU#GF9_VwzIenYqWw_nw^=SN)%_hNM}04Mahqw-J^3)wvA1Ws zb&PIy`S#y>F};TzFD~zox9Z+G5?y$iyKF=z2$-ba_ZX5zgaVf2)AwW%qZI@hx8Kc$ zNf&lIAYVxxSsl1#`L}JO^*JhDav!-UWN5NO!2k!zGWZsWk*6)kzm&iBPQR^gWc6gn z*;nZv%i7x7&D@$BoEO?9{@kSK$OGB8_KReEjNh zzdT>ta*CW$hWSHN@gh`40Q(<}jQ}-kLKXug5yS>eIx&!R5wm~C(N#{su_g&?vx(zi zD@GI$z7XFIqXbVxPebP=1KN}Lk0UNS0NMFHzRY?Fw;_nI_oDaaJ}5N5RR~te(Y6V= z8Pxz-w%1Wk zQ!xS27eGpBNqBZg-o-5-ttxF^IRgboeu>BTqyP^PhY!FIlE@|W$wJeeL7(t-r1ik? zNc5Hoa3xAQe|zsE{Q(NFfO6Ab;1U*JEFmqSfxaiTrCPk`r$kUt5N7PH)%3cGO`-Vr zlNpgB5z2_&rU)m({d$E@#{i(M{ic($&@MG$M>BpyB}e{5@t>pD?N@U&T)xRfwej;V zd)@I6EqBw#{VnF1a2VNN&(LMD@4+6e-&k^~CMDGid0Q%Y&r|yRk62MI>JMKb3lIMJ983tM)IB(eL;%o4 zk3q!3=a>9>A{3-lX?U~VA?Sa>E`E+mAQA|Emm74oR?_;{nQaS+0uI&o?kDAR+pAg|+RjP=>tpeWbN zmZ49*+f5FxZOEt?bKR9Y^VoT5{nyrE2bcdElV7bjg0yFW7@zEB8&EWdh;7Rv` zgQq~I3kJ!lRqwPDSO?ASoea_qnT*<1CKW37X(`w?6^%WN} zU75dJ@r&Q$w>b6BQdg7DKB?WR;ho8iBKZsRGEcnQPve6Slx;X$JFT|n!*b@=sGlY? z4PQ1Zj<;PWT*{}(W(EuQ~XghT(i&I?P(<&-->E8%p(0%c_3>Q$gf zaTDuX2jc!g37>kLa2)GNsNq~;`r1C7I2oE%7nz!V9MjidT>5gkhk0Yn4aPCMT&yIT z+;U|vwifAzj16(LXSDS>j0)~PD;8NQvD|*VWO*$Mm-;OY)1?{DR-0xR;i%vScpQHM zQ6S_gJk4~bS!V$F)<95f4es|%7QSeI??`qgP;v%@=kCNv8%Tg@Fj-9l^IFnJbGt?j zJqO5i^$<9HJ`}4Gx&;iO2ga@zd<_y_;r@96(seQx2jaQ44?Gzg%e=k8aUFqpUM4mK z;L7PAp5!KRE*^Q}p>)-@I6xB}cAQO2$%uDG2uMw(27#u6TIUTkS&*=3SSz+#RW7 z=oPPY*uF#Qahz~NCPMmHc;)UwDM|v_V8kY5KI3&?yuvl(KVzcti%{qjYYhlUT!VXY zK9KR^IH|R8A9>((fRMul?PB5I3TANuy`ehi*3F&TuH1(g#0EC37M`Az4GNh-fsi zsZRVpar6*PF%D;<2!2)CgO0-4J;7*$r1Tqy#9UhC#k6(LDHay5MApaA@+vLFzFgaY z<*{XXiSS%huNaNhM7@E7H<`i>&Q``vyNHi9UoPgg8@ixHrS~-Q!7&X3c5G zEiu$XF8-Lai%axA7eNFZv7x+u{PN}9VDZv_R^Ne$)2Mc>+dJ)KjIWGJI~0w|kPm~E zR*Mf)@H4yiYP%aUS72+CaQmT)5Lpe-jD#F}4`%Y}&_;IlKIa0*qHasCcyd4!zdLL) zBq<0dI+?Oes6;6LjV>_8m%)Qgd?ir%22v?z0G}cjWgtFO-{E<{%C^1qX1Rj;>kc~z z(OB>E(A=<+wm2}(aF@E&t9p!Xv&Y;xaM48UOZDQG@J7m+Z1cb(d{34wN{XNC z)9?Kcz6lsIe-+Y19s+BlFWSVfv(_GW7_^TJqq6}ln>OSQ{f+dsax_}Dx+~%+C~*3~ zi{fV@oIPH$8@`h{JayB1O*eNJjjgfi5;{7zaw>NDvel2F)>Fk_Ur3QSMJ&o4Z874Z zHRjL|ZqK((X!ZYZ=BZ!-iVlbuXsIesO{8kIf`q@Mp##V@)_L`fjfdw?$%K$rl0jwS zz54MDfBT~M@&7dOBX#!US?}-1P!7=uvsi=dXoyZ+&^q(W+fb-K3K}v)CMvgJgzL?f zJC0)&@t?1oJkNthU_`d-FnDEneFBj+ZrrIhqg_m-UPbqzQIXmqZ zOFg!{B-Fizor$FIs8+;Ll5QwPP&Bo7iK;dy7Uuh#EZef$2n!{9SiQD9KI34sRl2tM z#nDJtUe~+uLDGNgVCk#sz(~(gco-#FeC)=vol$K`&;we`gJ6+>0E~7|G(WNz9zh%>uyf}m^mb0) z-k-#^fn#F_A_O@^br6fX3*r)}s=^{7jM~MsvslfQ{L9((@jfK zSfZLV!<|@ahAnQ6^d7E|cUxco{Hb`r?yO^v*K`)1qN(hWNA(?}fB&_c2Pf)Pj-nZ# zKPz+`D^+gaxm%I<@B4H+?A*P3eNG38_O19K;7S+akPKL}NY5n)ZP7l&oFUU$$~Lmj zm+k^Q5Xv#KYs@%!uf};U_pUrxmP(Y|KifM!ukZgvGp6Ys${uNXjoELci&Iv zh5IQP`i~uVj;N}d?x7cBjE;yP(N9?&cEsz7%PcD20k#d~B5r!xs)?gN8iq7AH8mQd z4TB~V)8Bg)yb*wb9pi{3z@9ARE+OUUcFyZA(>>$uWlIrcW;HYx5uRWEuMJ03MTJVw zKCHuPd_5tnaNfd3OrpUJ3Y>S)kooe^`fkM>@ZG0Udz}kbB$z>wWawDVfQZR3q>Uq@ z0lJ4fW4~b)&n)^SkJjTb<}^Z&K6u=FuGzqZ43hU33)mk1ugC1syt2~6*&RC0mKLd= z>AIrEJjSXGVhe|Ia4}-2SKQ&jh5=D8o*J zKJo2#NYi`ThCyt6;Wer-plVR2a|I@D=XnyQpm~G)I}7>>-Zj+*4JF`VNIoC>DMECSQ5D{cBPONQBv%%BK-xrW zgIW+~tqrJ>Es*^}^Jk=e?bFr|C_!l7*Vf{sr3~ZB7wII6_^;JbWF_KU}LJl65IY{&ON{I_8U*{jd-=p(#Ey%$yJF04L>2Le1aMUJ-&x$){x^%F|BY_fg~`-IOB z=OX^C2UJ1+?ax(JxoW7?q{KHG(1RYcq-|YBL30*5DO2a6NmhL8mm1GX7<1grI zJs~Zj<&vbZKq6%Z`VNk;6+TE1mBh?7lYA+JK49zs;f&Bp z6UiXP)gKPwt|D`+x<&{6n8kMGjY2U>iYi3BlVD)Hjx%55fZR_&d&XGISkzq)-@pUe zi^gvXK>PHE9pR%jg}#hvvx*^ax{B)gj0gv*RBMQs1zpA3H;5x3(Q=5=$sYUXg2WW* zzKh=TJV@5viNg>nWiDtfX6p+;N7j0I;Zoc%XLI>d>6|J~884J38i1dzKIiX6npeJ| zm^PcQD5mydx7lME>Xbg_8N(_|7WVFm_VsE<|Nc!?E$=f@=pd%<2B?4=>Bd(z(# zwwL{~5qX%#Qq0uKGO1=tjxA$gi?G9`_1dw5W>VZl>n9k#8cz%`%*zftT*t&djg)bR zyztoAYWz$XT)2ZHnBi$_P{+^JZ@{!TIc1%B&VlcTkOruo$=3%5Z$~yQjG_1ka<%~R zd0W-mO>w|LY@gBg7dF>kM^j=nyn0POg1M9CdA_1TMv<;zjskz#AfPTw=z2*P#)}*` zwO|g0xF}ed#$UDC>=19rc`$$j*{P@-_ub04{>3?*`~MPVu$u1SeZ0gPW?aMj9!=;h zo(S&2-o#*VwXN*zmU=FG-Y#m19r&c$-Cs6W3m~cJTRg36jHvpC8i`N z-wFwtvKK?=hg91gf`Xl#nW!ZYGL5)HtZ6ci2Rcp{9i14QWl!aqnu`0k+J=15ONwqe z^2NIrDkGkcLq0)FI4nMr!vWLU_=g9t{x2;6Y;RAQOqyYdV_~F&RCKl6uft4r94ndrQVRv~nXg&so+ROABl3-& zy<;NzKPKw$VC;(Vn`hGEV=eYL6fl111Nj>>+COX$RjeRFY!GD-sUHf-B{j54fF&dM zqg40Ic8j<#&cd~&_yq9Uw z#=vCpW>jn$KdGP|MgFnXGrgQ*%j}6f*S92G>jQ7+(yQvSt zbJB$2XUZJ+!eYm~ROU1D%)JOidUqkK5$cpTrqAZr#+UH9wp-v+ic_#S3RE5Nx1 zQ)w5sbpWXY622C>wC)7m%^j1>-|$Q_uS*-y5|&ad_3(uYe&T958zwdO#^)6#pZ$L{@R>T( zF(|sq=DWx8v6YFAwgc)D+`6Pa#Pv5<&ja-^;MxmV6s0lCkQS3h6tN3OF;4EWNi`99 zkP;fYY&sbpl66J21OEMjD?Ao+Kq3f_;lhwCq%Y<@D&aB@dJeBmaAI+2%R_u+jN+_^L0=TBZ5yVv|K zZ8^aHtdYBja+YMjBaNPcm#%>&H-p&wU^1Z{z{D8VN$f=Oq(Ou@;~30Az(!{A#0R1M z$DM#2Sm3>oJUwi@KKCM&B&;|ACKes{W7Lr+e9f~smG{O{NfZ;Q>~^#TKiwJb!>+io{HrdMQ-UWKITI5TK{Bnv%|MEK)R$$EHif@MoCg0=l>yb3 zCQ>i#o!6Av-xpKPnT(?@?pWGI*<<6k-B=j6@7vd*Z0ZB_ZBMioS=Mes*vof6e^v|< zE!R&g=1JQn#kQ}q@BQ1p_bi_b-&1nt??`XFiR6TQXt#-O`+7IW`t$&jn2wu_=2NaU z!AG9AOz9OIR^>)@_kWu7%6ktyVHsFk`=yZuT|F><(K~P7(xak=N0k9vMo^o3nfosL z`K&X<|BLEsGQ#*Wom9gXnz5eXt3y6%ye-2b;|x~D0I!OR6(PLFDMUMp>TkQOEN5QP ztz`b=Dua%3gMX~6UyP)&-;0l@_EjEvU*|frqUgi>56-{4FO|{WT%kSwOvjbQBlK5y zUW8}-^dhy-5g#<2W~`y(#H`_oFrkwFSOd3U;R(B4#DRwiUti)=^rsyl28 zsq2j5!TbH~2Psxm6}0MM%3@K>QMC+j)HsdaM~ZgAwc$=X1TY3I#~^d<0-e-aS<{)R zwPgwYo`C8%pp-?SRH1VE%@pb+;P3cuaL|;l6BQELkkg@h@L-a-YH(=Y`JAd*6)F6J zmey@?)u(57Th>g)mY@6)?VA)WL$@yd$yXj0DgS%N05RxTqVL#5SW|Ur4~~uomgrZF zK`*o)HEO-B9Ii{#2zSRPfp1t667hFf>Rysn5|W$I%zezeF6dFQSN!6-LDo7f39yfCe{46U37g7*>3Cx&gXP$Fj*Ys^?Sl@ThM#}cswRvW5x~8P;yN>CTg+*t ztSsN0Pa9(bTX@GBOfHr&MRZt66FCn4qZ>3$m*wqgZUg}xzoli?nccf~y`@N!ei{nI zEu}LT)}ky%Vi#@wzO)i?5tjnPQdar}%OuZbkA}%_*6%jZ#*~}Bz3|)LoV@sf7|S-z zoSCH&){n`_{9cda7_T>RCVRFkPp)l37()eam5eOD7|TkUy2~ioJ6o^ET|8h@lFM>)v40Vl>TL; z7(ZsPN-(gpY&$r4pvO+eOeU62Me3r@py>9gU+;!p<@d(!SMa!OnY4)|!G%XUDD7m5 z$DJ()>cRKH-Lr!lvjeESH-QZnLpO*_34@spo-DXLWS=aX|<4=ZdS+?Gh1rYxnwY+-HAe)tT+#vTo1ZjDiCdUO=7J%2|vM z9-@8_qPO#r?#)ljonKkveXC{fvPo`-o%`JM+Ma(a3?-P3=+c%ufa5YYJ6lIat52yO zsb0s<&Y*noAT4m5X3S~mDcuYx1a>bItHJp7gRG5jc#>)J_i(dvh3vSV{Z+v=GS%Z2 zMIw5akkG{bw5X~Jzi(Johd$hjQuBJbvaYTG4XQYPw5X@jB%sOv54d3n5O#KUsFJ3P z(fYAHhht1~a`WZ2>sRw1Kck=hsJYM4U%ThO9-wpuTO#J?4hbz%40vd6wcL)2vrF8| zc%2s9N!r6-sYgP8m1Um3c~Mp?3cT|zNsEZ3oJKGypV9KnsYq>2)NNiK3G%lBlu zm-PgypO5G`2o!V-kuSo%bjQ{HH(V_&MnA&93U}%wiiM@+yh;{=CWC?$ZSS+Qd$w`r zpy)uHhC3(VWv^{9-ah*Jw_s;J$*(w>p?-^TMrP-@c(bcK^VL2>RLxmgdr__}&t0yk zw{|ZYD&gm^@UPWV*4LK_;n^AX;K7@|%AGU6t2MogR0UR5*kAX3$=X0}M^c&s3VFNv z(r4e=fv+&CpU3D7a>Ze`wW(~D7J@O&Av&WW_Cn&$EVsX_z8R78&s^8NMsCAdn-DN> zsS}i>bg5I1-1qSs0Gj$e)!su?$zidv!L8f}QEVzJt5f#))VfjNfFGD(u&eTH*OZLb zvSe-gz|@GKWy&5dtfjBto6Jf>7#6DDy_@N7W@EZMHsU41U*YlsQ!Y%REj7yScW|s< zEjBhp7f|U-r7(A}GNK{6f@n-GSqEO!j+2{XVM@duEj$$>d!G=TDB@rasz=5kdxFOG zuZ#BQ4G;=S()S2qM1<|CHo?mmBhKZHi)?rXL7>gU=3xQh5vh(2cXVZ5)g=lRq<9AJ zSYuvsA3l#-d0~x+A=t#P}3l8 zV6%yHX!QrgO1!61F;J&EufVsPZ|F+t`}aR}9wKm)G4}bYfPU9#`}JYH&T7F)8SO5L0@oThGvfh?0Al+eT|6Ay4!azV3Nq^#N03X+jwqxC zHs!oNDR2fiJF;Vt$MC9U?J+dc2>`H1yB=2NJDqM!IdU9|x%cpb3Cppiqe+gy;g6CV z-|JAowYQ`0rvL>UJGSOnS~$vqTan@6hm4K+#7_6UuuYC%U1XTa@9Z*($0_O-A`w+P zz#|z^RdmkM8n8`Rm?b6H;5mogYq@7_l0_CAWl};yL4Z~9GhZ$8;0`(bwcoz%i*V+r zoH#)-F@hx_7RjHgzu>ffwKP7rdG(#q(uUQG^AE@7tIoZIk*N)>3owLt$ZLSa$a4Sm zVC+SbZigl%0rCzB$Rgld_nzg0xL`j4C*bGlCyD>ai$Jzr6gX=-!{bmoOCjDaY-|m3Ew*v2 zTfKv1GZXO+U;vhxMgcVCHUDwT+t^tC{j~_s^lKL~AyMYs%UD637wjAyy{`C6p7#9* zd2I?MRh(w>=e6NSFB{cPhVi5|vtcix$f+fiO#G%0@(dYNut!y=NjG=n*IBk*b6mWyea zVaU{^TH$kvaUSgyqL$9?@ymTF+J)fV|5vdD?GTpLeYm!H$LoHOR5~)f1q}}ku`VMh zU`A6J{d{2aFv++h`MZxE2>@ZO1hg8BQv(Mbn&TiabOi4s{&(m9)l8f_t6FXztzZ z?YQR&@|<|NL6(N0iNMw=XW%q^0||;(yODc`Me9O+a0_o<*XaDEG3SB@=nMflLJhn5 zpaUu}-Rh2`lKTg^l1lfyRF}gIfi4B4%Tdh9a*&0S4>}3$^GU6FgAejtCHX5KzJ)1<^!a|0IuA zm}yKza_r)b2K|^}&!54Gi+|5NDs?H^FIhwwFBpsur&#XPKAsqP1W&1>W8cP&9&Ji4 z1&ZZ(lVKMl4RDIj&U$)SCe1eRPDc79M5hm)43jt}$CgX`Kr7X`{n_g?BIu`QR1RF^ zDQ>Wr;s&lr>C82Lly)V9v-4FgU_!;rk~ZqTAt@j|>p`YK#RUi=?NpizDnd~hJyMWc zhjx%oX4kr~#&7X~gRIoK=>uiQ5@hWx6MQYba_}T2K@-xnWg68IzbD9athLNB#buw> zU?1;A4b4*D{s%wY!8r2e#qk8i)gBZ#e3#Jw!VYh)+5CZEhXBL0a9HDT6U{Ss0kjtb&zn&a`Bammil}#NUzBh-7AGdY$!q?Oa{USd zkvxB-rvWMF!{`1CITwnNo!?~j?#_uqw}9M&G9pERWz-vGSlY#5vjHgs!2wPyV)GVTtWhlFgDx))Ch$JCN}-^@28Zw6zWgitUjsMfx6Gd0WaaR%Bkpe0K+7rCIQPx~{7H2bHk9mkZD~BKbG>#2 z`BnC9jn?X&x;%b)KmBzo@BU8ZT>=wa41QttCoX;CZT)I+1lQVO3yU4#=EkOE*xA|D z@4ZDw$sB3>Lb}hMkeV!vBxs7{A`!|bRV&)BXUr0`2}v(Rx=HnZzN57=MNrMiKSwkN z8$uOcICweO+M3}#$KftpK-lCE-l+oQAZ^vCIh>%xz0{F@imd_ID#;AR7q+yv{zf|U zB-T+JI;?DrnKw4x=4;wZvM68_lA{}Uvv6?Np;nflOTg+Vp)s2Q<<$2na=$7 zh*RaiQ`z^%A#Y@4V!Pagnv}iKX^S{8M~73^8$?d+?UV^h-dbx=lH~j2R_(`+8e3^nE`{Ld7;)k4C; zPDP=c-3^S4sM@mKZwd5|r`|p?vV9#3N6+G~OS7XFy$QJe9)IupuNU!sSIlVl{F0Ar zU0uW8XoX8(d`3@im5UCn?k`x7(5nM_%EhuFP;~`bLn-cU@vlu^bvm2$S_U3Y5!kT$ znLhKHfD~m_x~XW!UGEiYIU5sQ#A1GUNPh3K&6GN!wtvb)Kf6Pu!%qLe4yWN%3P%ymdh8$~N*K=91@!4Yf z6{|BcGEQuK@|0~wjPlkKn_hkGfZsd)`Ev{0*Y~5MPMtnojkpva0S)5z^XhB|@RR>N zId}$#P6K98egL0GqC~KClX3TL$-|;V=vo7WLQ@xYZES4|5F1A3TSP=ebo2ECKi#$= z(6QUC-OWabNT`10_pc$v7?Ca!un_yBL9#*d5coHeUP4BZ%v2v3Z17%^qycrioycrn zzm8m<30+PsEX0pYc$Bxq&_~LQ!5G_d4@DH2oDUnS$vuchl++&cu3q$hwI1pw&J(bCN?W#uw(ih6L$rDvCc7zP8~dq3Pegu3a5;Q;3;rm zT7r6wA61`g2_CYweahEc260(MpG>#(;M8TpxGFt7ejwCNUsStwqORC@t^QLz@x>O2 zCV?8C)(j@wv-+`uiRtryHw0JhiKV{1;G~njv8w7?Muw2*B-NXx^NPT_RfpH6=qsK> zr415gkfb1B&rD1>*DFqHA)I9|;vzcIyhLFy#Bjj-P;3$MRma%49u!r@^Sm!-_hjO6 zV&25a+WAh26AUjC5KB#m3+-n%Pg;%nS4^ZF0x|oq%Kq{61qGcj(%tB3@O-x{jju$w z{#&vNAhXs|Q)9poPgBH@k}Jx;@;o}HN+KEqr9?9`5mi=4fOJ%ZO9AE*HBh!-T=Alb z7!;REMq7MMUp~R2!<2V(T@4fpt+G|_S4ZNK{+Y~aD9r-`%1!zXqs+~G@ z_x0{8_qOU%#bde{&^rBshi_qji{NIjgg_mY-E))|(x=D_w5 zhW8OyKB(XG@38wgWVh#uMS@MU3^+~|5sr2v52c5px|${Wk00-#zkcvTtuUD)EE5}{ z%D=DiVuc1+gAs`h5w(%3I}ViG)R3TH2>`hkIYe4X@7916`}={lc%K z-U5RbcV1x$k4(X?nosNI2a7hInSK5;5$dkG9w}hU-*ZR3!#JgWsIxcp>!@;W%2p1YfDI*)y|9gVI}V z5k9E}&B;vGmTla&!G3>`7t_IJ93MWto_nHhY!k(W7oh;$w^kal|L? z(iH30F1M0Gzt1f1lJPiMP(VZFq`C59&U4XZg+`U6b?Le>x^jg0oQ zvWC!2rs4zAR`>s&XgRffsm_U@LP+Li*z9-ZdX4!7Oa@D7_rz{IyyaTiLo@+d4R|7W z{f?W&qB^qPUrMs(k1_qm7O0E4I6XgeMK+|@2U>mg;$`Z*KF=I=^qznF$d349&5ey` zdihS(a_Ak2#yP4wXzk(;O+NCm{bI-qh_ z5Z-2g$@JgGwziw?BS{%H+%(27PG9`Y$ix@AGPIiR#MTMV5@Vw$lH9GSt2&)pW}}@g zk~%&YTuAK53EVz(&Sxv7zm52xp!M%R=Gr`=5UX|<`m zuy=@;qUlf|bNJwVclf}wFCEPg-ycg06FB7XELoP{Q9fQET*FXoC6%h8$hPV*)2!HR z$(5ch_sp1nYi-48y27_tz)T>5@|VLcq3?5E-6~pp)n+DtALlob=h_&rDhu%UJ8vrL z*4g7oMEqyZ;{KVFzzrxAK~SW;E>sZPVyWv`UVrnOX#EwZ^l)vshMU!m%JVoe75VbS zlHCSWYB@iC9A?1>#)>}e?&eo}l` zf;$A#glGCkcTOi@D=R7TjlGoO*zh%4`QIlk*Lb5YO8v>)=O}z-`ZW`0=dCn`RdlUB zEA_rx(S6=;FTiDr2Yyz>fIsZLXsae~>t_j3y8~hB9~&EeplpklS|42Xd$w4P*S$nU zg4bbtv{v8mCu1p97j`=)4Q#KK$Yy!|{5+U;APg=K6{cF+z3(LN(mj2;f6^0N+RW82 zal05ff;Z)LU9Y;(G@T;mVkX0>R2oAS?B1Wsce)17;6GY2+N!4%u4Jr{mfoUG)gBRA zes3o;Qfn{6BNi1tI2b9G^BK#saj)ACSD*7vADI999nw>z3hVCNa7+rZyX+pxo+Qu9 zl6&)iX#tw)4;>WPup_?SG|Sbf)H>_T`0Q2l90NT5q!YL*S&)u|67O)z>a=Fxo-sNB ztjCZLjc59{^%0LFPr17$4Vb+;8zz7|eM!T`g&77=T$Rqr_nBX`UoTITui{;!0LIB6 zQbScZw+-!vcEYW2UMB9n`8xN<@#!?e4AL0}Mq6Sfu zxrBy9^jjNk_FGns9XB}E1bB{>?8lluw$Fm!y@(Y^Y}aVp_1RJPmF`7GoK2uH@vFgA z$wkx_Ps^8Gqw(3F1vJ>pCQNMCNV2N=Y8`fq*&US3Ycdw|OJSwZebPj*4Ozd7R7BB%L19y-YpPHV|5L%6;1Ke~VyP?8EkNxY*{$HRz9Fo2==#cD6SG(*Fcmbu%D1v zVlqbEdkI&n11;j1zQSul=_&O>fTTr!8p`t35TD>fTwLp9`~tCpiY|94sFdh;GVZ)! zO)+USw5+%xxNhS;&Bx4d1xLp+o>1DOctRKr#dZeqWACNwazAZFqAx9K>}zG5IURnr zk10{s7w%Q3FePU&KkxQx!!8!skAvdSgA%ES{+jJ zNGZXlB3fV*SR(a%wBa=mTprXEWFIvXtA4h)AQ5fnP%IDqojgQkYHHWeSIPHm9Cl^O z>CjS4Xq=AHe08a%#n4tT{Op(AahBMsN$(_dL!XG#9(n#RP=>fxfWgkdb)zX0OTx+q zkq4_%ZdZT>NLxotqc&ht|XPE@eBOOG<2b zl2pzM+(qjApZi|1JF*4NoQPey>ZYIj!KeF~p9$wSda0e9eD~9x2a9Lhzq?lX&>=Sc zr)py@(V^7T$kQ1H7i4Z9Cc3fJsLFo)uz`9M&pw&IOlf5-HK={0%0|znRzQP)Bhz__ zbQREJO=^U4J~n!&x?@WxD*cs43q>XH{L+&vh{9N|7x5r+0X7C zv;6b1!A|CBXlu-RE9!b2UcF(<7QJ^iUu2oIW7=B+OA_i<-d~=7qKQxP;?;g0lCCwE zjYi-eG`Z|8KSNc~Yd~W>1oNaNfSHmF4TaeThpxz_DepNuez|0SCP_+6&&+%`Hodm# zHmO2fowAGS?x>YA+y7`8{>shDCU#mlO#SO8I)>{($-DejwxLE+7uYc8b*7a0Xr;MC zza!V4=$18+X4UtEAKsU{I&?VV$$QGp)`g*aB7ae`GvGiE*1p_72+Sr_Ju6`~Px5DFzpz1Z1>msZ+f3 zi3kjE2y}{ne!qJ43a6b)(%n)!NJ2lmHf!&%KNo31>@e9x98x-Gqcqb?M_2&%+n(RT zjzEfG*Han~O({~EW=M|*v@J{^5R!xme9>kk+UAul+SA}gBNQjKun;@&1L^94(Wj5O zKsCX@Z>`7&7{D1-)JDTo5Ml$tT=@nsx&f`@`1~R?N~y=XV zTJ37X*XR`8WL1H(=+|;LBypz<43H(riuL{O9ivJT$B&VbeR#dN_p;8!Ip(9{SC)xA z|Ml(a`;n0+@U?DkkHz9T>|}(5gm840n@bE=K&nz{C3RsB*UK{^_$r#Se6boP?Rsqn zGO8^IZaaFgc~}a~iz@#?p$PtH zt>I(RRA2ITIY#*`1*90h2Zq@<{qO}U5{zkf4*>h)$4U_`zDoebfXecJs>OnD8whfX z(e<8Qi#QuA$%DsRtb}KfgzDQG0aQT3gmVGqMz}6Q;=DY6D9tHbWU_M0(p}6X8VBW;4R5d)T7IKyyegn8Ye}v# zElHouM{iCv@914AX!Q+&_7im$jmVjoK8RJk4}k!$53(`9-FX0v{=<@ilYhI$2GE&w z#DVunXE&eMpOXpK=BzVI{&t!f+xqr;5XBC7oqoWpBJZg<-~7VaM{hd+XtAb2(njez z>YTEdSG@6GR6c*sCs1o{)Uv0(?5E5xkAz_W%$D*uDbn=cpF~G%z4KeQaP_>Vp7o^c`J`%VYa8WfpcIt+y?gJgMT~MezIF+&BgI zjgV|4TxsXgq>)`qj!zQk3Ywk}{s6y-*AD4`@yXT7CAcb4A!A9R zKsk>WNqlv9?Ji$Dhkhf-^IyIf7^0UL2XIVbRI1omJn6)(P^GzBSoCK&>C5I?U;G_< zzF}3N+R2TJ(@L?_Yzmbdwwwct!^Z&EMrz>Q{%1LI1_0mC zRBQ8>AFm1J;!mxc6Mq4|ubFoV3{A z7GMXtSaj+aADg~{r5Pvtdvo2adK5`H9Vq!2oD>)jT`{0&Xw>YDH$HnaI@zb=nfuV^ zqDx!S;w07^=pU6g%X)ClAtvWp|GpzBd%KMyH6Q<((0V?rEFUk34uRLf>~sF_uP&-v zxo9TFTn=YZ9(Ii( z(_!G*82&pToSE-8H+Q+aJhA~OMc2SJc`%rc8V=8RF!ulRr~^l zWSOv!8FCgqy&Y&TzR`)$+R0(>cDooMxny}<~PSI`94=H_N;;B zX^T{vj%UwSE(ixDkB!_vCHSKYAo*fkuEp8aPa@B^wQ=mW+M1XYXf^D5b{Vgl;oFN5C~9B8B~D}QlqN|>96=f((n`nVRWWCJ}t zX|%Zt?!|jE90ZT>#GF%AoLM6y`otnOrb|P(%atwAwfpzUJ>$Td`NM846%I+LyTuPO z!V&wAgOP+rsjMed1Q!Kw;v-e6RI`81!jR~T_FB%;JsPsiR>{%L!*4HSZOo@iHPxC+ z3|@KC&+}`FX~Cr1UGZs6uSEQ*@&4ozIf{7NnZht_&B{z z+tCAlNa02kL&jhNQI#dhj7ShDADhmx?~;LI%}wjK7TbHmn=V{C0CeiZ2h9zE^pJ&q zwEa2%0Z))=FwT1oPy>r+sEGia2N02$#sd``MNE5JiZF#$M<|zJBG;$k3%_ zeM89s+zVix1E^_~ejGtz}D)B|-we=l(=IIDm0iXUdd6@;HGF+aXlebQTOW zilI2SHUk>8q2xgSRWfai)(hv@3e%;9SrTgSNGF}I3ds69l0+_BHmeO!r~Y`(wZ+RZ zF)?uD+rAizZvf2v^6Yb?gi5fZPV%iUNz^-!#=RL7m{c@B7HGqv8mSs}cWF1ev=_7d zjBeGEIPlgN*CLjumzTCc?ebByaYgy>@$Ru}QIhp?*CA)Si!)D!;L+t82d~l5Jb&6^ zRT9WMY9%|qmGAP((1n|{i3JV(>rJ9k7_MKZQW$`E(9gchxif2WwuVw|p{;!o{w1|@ z=Xf4JevBKmbo_<}gG0{5gv5srALOO4W~6U|%-~yNQlVl}-E9~Za42PecvL*TZx~MLkiVgGZSFCNAzBR7A16o1%aLIrX(d>yB!Cc& z#*ZIAJbHas-W3SM9Z-0D{w&fc$q*FiW~K?lLUj1>L=rl4BPZubKZnSfH#po3@*THP zayFglHYDdeWKM~g?%idkI9VsD%D*0Zs={O14CHo!rmh?k>OX>vUP++;wk&=>vhbC& zOgYkmym>+d!QN1R>iGW0p_8*$<1YV5Cz|$!AE(P!v|LOke*%6F9E9*6xT<~)pu{jk zIT7dlVK*u75rDQ zjh>#K=g`Med-?b_28rtjKUTdqmxvfC+&%dtfAsEQFM0P@%e-9kv~|8goI+1L%95*X zyO#`f9z5Npbc%kbaA(Q!r6|3W=##<;&k@!F#eqxp=1bVk%ATJ4;P(kyCY(N$O`=?<&z-BqyP68{vfp&##IH~6JTi8sNG~vQ@0W_! zGKA(?5%JLrzb=)HG=G-$3qe9(6*QmQ>pe_ z`kKP>!>ob{W@|So^M~2sFT+fE!_4rZ{nX_J&r#`D`yL2{jrgbE_|ECDy*67cVf4$Q z_}{Su%Gy*98kF2jad;bmtGa5eBgJC|`X^^`yh_RDozT%S+!|+Xp0nxpVY6eswh!Y( zgv}+awFGm-Vjk=47SQ;3Lz0>lNf5-4xdQBf^?|C+Uk$I&`GMt=h;GSSd^Ee2mqyd) zLZ_Nk@SLR&jql`&5{{hVbW?VIC<*-oN7pXE4&RV8zvWi}nhmzQAhj`I zo9+$r6yAdeozM01e!U*>(@Nas=h0SGx-a}Hyf9Q$SJ9{c`;F9xMu(Xr$vzx`x@@bi z8Z2K?tBR!|{7zi+kH}D^n8O0j>rdQ_;b>lUHK=xqJ6zC9=1KJ$`oZCLp@$mbOP4Ex ztu}iH#KvCNN?1^%$$0wINltg@L3Mxms5@Q8_Z=D=a7f}<8O~*55)vS zPd~@#5Q= z*4Ncl-SbJy37$J`7k_Ii6H`^rLV)4p#B)zXYSDzn#KvMTH5*wqS>QVfr4?* z{n(<}n(QM(|0gMAsyuuq#xwcLo`l=E0p7=X)~_uJQ`eKV{jzhzNymc2r&1qm;VK?U zm#_Wdd#C-G=(Nj)rg*D1wpq^$M?z)BhtnQHW`QHQe|mn`?%hr8)2~$7ThjYblZ(@1pcbN8`06?}Wi8@vOCJob5wI^FWK`^T%wfXg9d+4M~ zNtSuYhntz0w-+scO%dJlD%c7x4MsiHW{IYED!nh)HPQR2TxJM4@I_@HNBq?;Y`nm&FkEn5(g)svHKYHK@u^eFRh z4~$kyWX9|t)t=Mx@!K{so$NfjB19sr-Hd(>qb}|9n_mL0#!jCI+rS^w`>oGh=qShk zVto!CSeM*UbA2vRp;$~R>ggSIbFmXaLX10_{1ep${AvgICiYFSYBzCZc*+bd?wYRi2}WJ8|}G zQ1kFlJx*$+HOQO$kx$)}LY+}k-;5#i=`#Yp*<70!<8{>^*C7!L*hH#I`wm_rh zqc*E-*saj82Lr8QGdoTUJzFiI*6kqam^*N%E3BM)j)!GVIK~>Ci%vRypz4Mf?LqD5 zI)$59n2t&*$d{Af!=7sT^vS>HMbP;gbD@h0n_Bm-f>!E`$eJhhIm*4O^qBtH@{ccLk6|G3UmC?y>Q1`xvocoxWS$L_qh7L`jx_~B1 zSU{b8p|OA;`NOtGXf}WPq%63-|F_5G;so|zOhOgx^n7bv#gn7)Ss2!=oD)d4UbS9( zkB*!{H)Ym!IZ(EuU?B1wN=xx;zk}o3b_Z1;RviCmvNRDz=UjY*&+{9X^uqN@G9`?H zX=q)esZXBVLLRzPC9A9}Q=6hOFut>ch`LLh-?*yq!t&DMLhs50y)CDX!?Y^#j}N-{ zkLU9OV1n`I`+eqoo(A$>zp7j4d`gYKJ9uMd!$I9V!y}AcUTvR8W5T>jasyh1FMEz- z&iLGpxSDJ&H@6)Kxk`ET$Uh@P6FM8WKHQZO4u)QW}uafvOUD@%L)?A7uk^zlwJUcSxA#W71Mx*vlWb3p4<33@Pp%Ve0Eb z-l+?o%6+AFtGZuGnt@iDPBcQ(>6^L_dd){_u&& zGqh`Mc7J`(GUHsJRq%6f>tf2jH#c|Ydz;JZaji<*^kjv;Q`Wz1Sif&`hWxr9xofnow^UrxnZ>toVBSd%ib z+rn!Gjh~jycg|p0LSm()6rqWJ+ez*xG>4s?6{`Guzy9XR7U_51w>Nrj`tuWori3-? zUJk}tNqf=-ot$jEtz193eyehC@t1u~69$OM))H*)_okm=cpAO})vSsC26txo8p|E?1Z+YW@i-)5Lu-@W>XV9BMKKb)`5D?g~;aqbMsIE|!~O@s#X1EPN-$|A(*d4#&E0Psm6Z^ZtO#XO*;_{T?n2os zGow(1kiD{J)+Jj=GB0uySw+T0R+1gw^Vj`6@B94qb{rkYeM{o^`;PPctTUGpC@l^a ztpy2d)Nl8J0FgPqL{*w-MIczzx!z!3Gm<|*2QMw5;5iC1kb@AGuOEQ(nc=ZXCN7p( zAb{*2KI}xH=Xd=4TMAnX*o|%})P%OL;^LV|JhShT3%^appDQtpXM?B5yh3aF=h}a@ z0B@d+eXYuOZIl!IxzLQ!taC(fFzk>HfaUlA0H@L*dpopImd|$*fEvF#tN|Hm2Mt{8 zx6Pu4h7{-^Vx|2_&yQ{fZu$qTKeU+7iD0n?hX}|yz_u^Qr648Q^d8urL{YcTl; z@qPoKgb>2gd($JE#}T(L0hT4ff0HSi@Y`>|>K^|}$QA^hI~YrliX7JN=7{g3E~E^H zIG$*Tu7Q0G8qgmXT?s-@*q>S;Gr#N6vHugl48uEFHk8+?+i z{WXA4LxV9VOOTy3rg=Fn%@u_JQAyj*Zu z;1@6>wSzssv_zMdZUQ`Dl|Y7rv(S1Au&*QpG48+Z@u9|PTu*awAQ_&XR=;xxA0!_D z48nMEAlJ;Q)VLCQYSf`pC@2U6!b#>7Qi1sS#WE{!X$F6lh-L6%16uLSiM(^Xe~{;r z+Ntm&H9>l6SS3hH{^wvDqAze37Z(p3fCz#sIKQX=sac9V;_@c~~j)_;j{JiVCACaex4NVOnWS{Kt)p|;FCchI26Zb%QoF2E$FAsx;EEe+3 zJ^jt`Rl4R#^+nRjL!RJ%4l}spuZxR$UU)w@I;?#Pmwk*l;Y73~y|s=*!h@6uf9}R= zs?N2ng8&)i$Au`eR8ajRXHIYYWwWJ_#pY@pq{sgclDIz{`#Ara7AG}~jS9-i%|!?dUf3D_W(Wg6V(oL6FVU&RSW@&oqYI$i~$EW5Y(~1oikMO(^JITq; z6}e}q$8E{+@$sgK%0dvLO5fTj#>t-YuXAWv2p-Zd`AE949_h&s zhEPw=3cBL3)3D2P$xB4pzdq6ZdX9nZI{)p3ZQ_c&*8Vy=5FN7hT)Q})5gj_1LAj&b zpM1>@NO90-LzquF_NvzcfRT&M-;M>4nT{)-kjaGP=pe~4WFIwPmZ^!=Dx#Q$zk^6x z=?8I;Fhx+n6uA!rn(wjv=~7zStNHkOq5+Yx>p~erTEfGH z9MZ?1zPjmp1Rq4qE<1UC&h!-f^x>>FtL71}YfsIKA?zHPg;*HKHCmq(Vo-OI03+o9 zIcw%q;fT&#FmX2ded-T+^dsJkk^`&EFk!jP(24Y40~Jrv^0&eMghIm|3*Qjv&MmUl zxf~oF*(t?T#h44~;-JnRHwyp^a=yd3$n>rGZkzh4Mj)ppz5a|yjCjf?-A59b5N-=V zE8{9nnr?7?>QtHb;}%x}6CvC@6?6|yU4*+qe&d`#2v{tVhY8APgir%AEp~VQT}FL4 z*T6B*Bq#tt30Famy|c5^n$`B-#~<^9JOnO`i^;Nki|eh`CJ}45ls;$j{mmEDe5TDy!IyI-8IkyY&rk&2|M6eh;Teu23M#txS2rr> zdN=-5TM`KQ`TcO&7e5OB*?6R1%}LGJvhfptNZS_e^;uA^+2Ge})<8jdVXwAC=|~h4 z*i!y_o>w^?FIL(YdbK%b=NUJZyjgu?Ur2?xiRK%3RE&+&R0{6GtA%zNfG|J+p%jNE z41{hVaxO~A@|37JJ?@DUdyw*_CokdI?oNx>CQG(Y;U#&ITUx~$xG|gk83}PTx25n6 zL8#Dc8y|GK7qsc#iaP!L^inV~H5G&kwOZXEED?bJ5&>h+N4VsGV!%cG4PY}w_Uppf zk84O)@~?$n!u}W*Y1KP-o@|(#0Bnv-*1ZPYcXC1cvG^v~evtu>K-(SkYCXPAS;YSD z^I>~E6E^nkj4^;GobmErZVtK6&b%eR{?EF1r$V!dCe0s_I6K#7^U_q5v5aZ=Ls1{{ zSLu0q_6DY=`9VhKW&jAvM3o8;JmXXebSC-~7n5sra^si^Bj;5K>nOgL7Ia4Pc~rCt z9hQQiOOh94$giz^1<`-ndU~T})B}1Ces&Fq$k7jfC7~>NCb$x2bCYzL7q}iz7)87i z?3%t4L8B6&P|CLBBI6`Rzb6`66Fz7vcqg5A=dA0qXf_$lU|} zyvA?mfpg22A}|j~!Xq@wNCFR(3RS?($*|gi2m!&6!Oh#(-(ONzHV-jpa`Bw4m)c>x zIx<8SF(o!YV+m{=5zH+W2h-{Te9rQo@9EObHY=#rk?`JtRg-V;;l2Evy@iBzvG^@t zDlJpE*!nsMy0a57v*5#nex{fwwe^7pCj+L69UtBV0V&Wv_P70m0n3um*T)}LZ$G>L zT%O{rE~9M_!`Io95H1UmvdT(Hf#HD%Z?#QLp8_gUZ$Czrj+t~BUNgktz+&6-DNpD; z>qm!4OACd6i<#mIAXETL!yiGZS6dejHXV==#`W5kluCHdwsns@-r!1TjfmrjihRU7 zJJTVpcw+a0a#&OI>D1c3xYY-=4M-0E&d~*N$5kF4YlzYQvt}oY1n8}dpCBcaO|10C z^Y=_cy63Inph6gy*Kk84S?x$X5I|AyeivNZ%G?YnvgkJa|9MA9itAQ^z)phHu5EB@ zd;_BcAj}6}_uf4+#kPV)3V{8OP)Q5|C8JFnmX^i@!{Ks+@VO{|M}&tH2{f@-a|3Kl6b%hVt!C0`DK888J{m8y%U(;hukt0`9yF5S&&|O;>h`ZE-zL9zYw2j zwC01NCE5A&mAX1Yw7%9eU{e=NeE|nM$nUC+->iL=j_!=G!(A+1Oo(omY?!J1x$dHs z18)PSU4fy2m4+gs+K@<*64DOQ!C`WYKi-n!AGtM}+x(M16!Y*~Cx2SV-| zxdDesy`s2}HnD^Ba5V=&Oqx=Mzk>Sh5#M4rGg4VY6tf0b!pg`y4K5nkK2p9QH~m*J zjn|>f`4>wWlWF=CFZbBNn96lcs<;CL`?K!iK)3E6KL+~1po}o8t8ZgwviQ%M5ZEiB zi36Z1o>RzsjRE9uu#FmVd`tT8wtxNZ&M4XNTaK50{Thdv2xtV%obg}w+6tw&H z{w$3Dh@VJJ1On#ZHJ|tV#CPr5YO+1*#@;Bo+$|m28l#et6u{$d=V%Z5j=lRryHEtE z7xJAyudS=A2ui_B&DHm6B21q>YCcAnaZwUeQq)_C>|(16ng@hsKS{b-zLrOWM|8q5 zH$R^?q7zJ@uk-T>lKV?yxBOatS~D+P0o`JYxl8iVI$W)n`X@rGXS_a*j(J^4D@jG= zXr`jzL<1aaXB>)jcwE@+-R)MX8wY3c2?CWomza-<>nCQ}|H~49ruOM@0vTqp^a^!q z(oJKpFY@d&qw{A4;Uxf#1M*^F2nvOl!j{8Ls-PhA=W(0N4VGAV1Hjao2Dn9Kbtd*2 zl0+oHA_IaFJR|B{!e9pd@uM_jm9H1B0p)^!;8<<;GTX`eDj6p-JTSk-JpRNUMCq$L z+Isos3Awqsc=h@cnK{Kh07tCWI%#2WV))bIXfP6|n$UD}B`~@Umm}Q5o9Czw%a@)K z(c`Om4Gj-*T?GYG*E~J^LT%XOYlkCT)6bqoyfFVZJH(1?2j{9mW3V|Jpn5mu($Xz2 zJ%y&p&%tnBbMyR4_*dEqY^8#Za1#hhy!~@746g2c-z&q@0z=t$9SFfeCBR9o0y>b# zZL#WHPx$Nr9uRW-P5=j!vQ(BOj5T4F&{N_boxFmpfsrE1Gv{?Oe{d&ES-xZOM@A7a zpr8L$w!SlGmuqDK15-LCjTgfwz>Qf;aR70t5F$kv0nLp!6po=2(+5ITvbjcZ-eB!b==1zWzRWS{Ke{N}{fClWz)3Ao7roO~P^f6jcls@t+QnRpFF z{#dZ7f3Y3jm8%%(hfB>f;UgtW-i*F5e)UDf5}@2 z8F==y(S(4#!2dW=hDbN(A2xIv`D_&Ard4(z3OY&O|8?&aB2t`Ye-*pc8 z+PEj(^Pk()sWv-44SyRG?L-uyVxXsOHhr{|Y6mjh8eDNrxFw+3w8*aW1??s>arDf> zK2H6#JJ}7BZ}?W5FfkQ6&H~)@ZnDzgE@BGeAhjP@e|r(7KG zF4H1Qf7TG*{-u7eVhwze^4esMJ~O8=7jTyYUJ1GZae8+PAXY&<)C{x(w5)Jtz>g5e zsd75}fi0>l6f_nO-Y#3~+(-w(Cis7PZAp!i0Ad5RH)xKz1q48-2g+jNh$%78;uugj zCqTLntH*}GJ*DhmF4L0tSzLG^;qYGb$s0PCGvP@0-EIs7?Dodl)QJm8!27ryNiSseek z7vaT%cME|y_)HsKBBPZ+Oe=G+K=XJPoefnYxUFYgwX_f$S}2v4)rQdteYt|!3mKWd zel>8=K|JMM1B3AH`LS{FOwGS{^ZA6{{A9OK-8R8`vp;`abPjl@D#hZ`)|V-9 z16Rzv$mrfGKV8(u*s8kK8BC1lm6VV)6}soejXuWPM9W_tKqEj*l>WR+?}`zCoZtvm zPtorDwTOjpGimDa{>XuJ*5G1AXvZClB{{H3PidTpDV@=CO3&;<&ErnbrpUQUN&WtG z2c%BhpkvW7uL$o6|5xk-x#TZ~#v7+z{q4U)y-h0wGc)aQoY|>ZKaKh3$$a;efOQ0l zFP*!0Z^OEO9SPC&^{|?ZO*I1; zzkvZVHqm!eTOCMMEwHz@2WI9vq&QMP=VT51?RL}dA0kd}TE@?3PSuxOvn!rYluN8S z-q>l8^d8j1`UK<}Jzgo~>%VAfCmn_AwT-l`@gU(UZiK?d>Um)e(`x017VKAX0NkU`6H>{PvZC)X&31P#MQU$U2ndi1i=ZI;{?&cYCdyTW>1^qmdML z$oTY^BDPdGHGP(-W2l`>-K7ZXk52PWnO1!5XcsE8BSo3tw*40mxH_Qk~ zvE0-wg1pr58E4ROpwJ}XIQ;zJR??y=NgjRk40uC5XZOl1ieZKW+|4L-YA(AhFh8Iy zhK^?fblOlE|I^ia+pkY*HB(IsF4e17tp`#-8OjRst^h#NxG4t@b+c02-j!{n)$pxa zryA!@=$^s&B)>NTQyswgNlAm3({i+n`+p5IHTglu3))=ZEo6>=v&GwjF5U&AK2DXO zm>QyYN~tpZM>$@ek1JO$oJm7)L|&L*N!vA`*crV7Hil*;V!O@(mHEHUe2U6F)Sy9J3Q0g8fSZ8~3c{lUh_^)mcqGQ*^c20fH0(C| zXmYbC>8r_`&jygiRCVd&7rsjbS5l;B3GqpYzT>2di_cV znDT4tocVPZI*&^v1m<;LLO7qk#0?KV%g|y{H#%mm()#G0{`hfTldArYy0?ZkoJV`& zN`_|e>zF2~IqUJep*w;M3ox>P2H=v52zmmkM)QCdP)JKlBk~Wall^%d&4-@=2R8yl zDf?i+ZXZlWn)mL}pZ?Z5mFG&BYXjkU_>P}y0ky^9Kgs*`K}R<=B~~~gTuKJUZ*;-9 zTzf~y1>g-9pog#lYIE9q$_XdNa0^m9(jkzb8To%C(5eND1xUJzA>R_CXdrBeVUg%= z7XKGbO%l+{Ak(YvwH=;^xI;Ah8}!$TfM_NIvhZ?D*);%ZqLATwLv?^}Fd8LIG@Usp1k_cL%yE75jaQ@BbO<6rg9KA1rjmH zb=b)OLXRO_=<4+c%}u}LJX^Hp8y2*`r@H2zW%WM`UD$Wm>1TGx$#eAWRK_w92N^Gi zI7lF)e+o%|3pySTf`GfN0pTIBY&t?bT*Qqu7qiaU*RY2Ws}ZORL0>$5sf}es1i>P@AukLEVFf#p0SpK>2@^7UAhkVH z>*q9fcxDEJWfUzeSPLDf$%%$V z&Z=D3{!E-!2yKFne&XE{5D9TGMdy}|72Cik&CHzXUHl~?s^MnVaHYCtu4UD;*g8zE zo#)E4t_OWss@#&24w8*)iR89M;^p?J=S~rWRu>}em%P(@YZe^7NoCj*eKi%nc@U5V z3x%}EXlHAnWZJd!hm~12x%{{&)q#7)cju+rQvt37l}mVMLk!EujD(w0ZV3vBIe$Qh z3~%r6Lg>~y9fUM z{)n_5DKw?0WOqsc```g;cdY8v?Qr3W>`DMDF#$3N9qLQTH5+r^#q*?LcyP1rI$D4m z4FRL!xQJN~1SL4j9C`Ux(*@@SxNRstfqfDX8ZhDRNk!*#n8B-ha&-1Jrrp^4U+5x& zi^-|0EcQ!u`i|rD{uQ8}Mf3mU93D!5Zi;z$zxnjZ&#S8%@_FX;u|sx*$5X5s zlQGv!L=qMsDe@de%mOt;5OC4o&JF_&h5c53LM4rZK z?+M2=iY8r!H>;%dN5EZCO0#k4j(kf(zb2Bf+knkYPEFz3ySQMX!`NBVgzz zYH%!A&op@<1to~+fvD}gg-%<`sH%iJ_D`qmpC{ON*41Lg%c7JDI>ZsJE<}3zZ-|eW zmEoMlf$;ApyXNEA-{4VU-YPeq`3<>$&?f!)Wp@!Z`Clyn(7o^v#m}pwFS-i;5~XHl zg`VJ^*np?ml}yd38l1oHB>b5^lk4(c;KtU~J*RXySecm0gC4<1o*%y7=t&7nDmPh& zJ!9`oI-^4v!oe$hM@Nrurrbj6$;r81fB|U2T^NW`UtIpW+$7pp!c7`(CFc78LaD@b zxHB^|U#VV(a~kx=(5>fk19i=*l8Z(^iHUh?_Y^IG5?6W?BiG(%`_R$RlR!}NrWhr$ zw#kLg&3YNz`gGazUDPDqsv;iWl85NI>B=IuSs%!6f6_!dyEihImP+J8K~3!r&%(V0r)6{#NkG%DcB zW5<)P+B!$9?CEz)pskYXh<*HHy$ic7sVQBVloApaaGVAhStwWr<_^lo)jAO^Z^M>z8U}N<}@K^ovwYkCP6Par;ebcZaHGN}4psA_+-0$rJDKoPf5s^`k zgGJsHadg4^0M~rx4X;?jTnCTu(Eh4A)~6aqJs-+HKLm1LDVE3kR!CYK;w-c~LW1-p zBqfoXMCu5J-i^?b658=?!+;Yo9}G&Y^5Mup@&Footsxtz3cmTC2#ttD-_Dus4dAAW zLdx0?*2lXpZQm^BaG>*>h5KtEHs}url0@ZWd+qTvJ;_)Ik)H)<9*#R+X4gB5=Pb zhg*%YyYB+u0Lv=#=jWZt$=&AN5Rg5H;ygY*lKr_CbgG~!<)+y+%n?Tn#|mS=Cx=Qr zN0WV8_>f(oOLKpKjD^0N%D5M7i^yE~#;(#u?FT$)oVmNp+^Lwf=w2e%?pB^!xaj)p zC~#q$8d8ahOI0C^Wpi(S4_o57Y~+jL=NEn^|9)__s+v&vsHx+PQ%R}lvDLSGJc-P4 zpHL$5!kvQLw4^L?pO##Kmd`F~m7beGHDlIx2L=ZPKpg;#Yb@HbT4gB@@4X6JaD^j|t4f$EP;NfM8tMy~cw4~RZvGjOJ*ENn2_%56$XD5Z zYD$EM3&g~Guszs54(Juake4`%ly^|LAS0iVF;uJ|E=0!cf)OSS zRB~BxaDq)231a+@YQ=LkKudg)774-@X#3+1S|l+jtC7ME86yQ#?)iaLL)hw+!d}o~ z_`(#c1MnJ&F1y_;H-r$CIdEoJf%!GyJ54sjF0v|4Ha1UU5E&U#Fo6sPnVz@>ZuxA` z13atN_|F+CT9@kSR89Dj=`~^1ngRGT<=J&a$sV#n*p!XTPDxbbT=)>~ac-(ciQesz z$o+sZvHV=_^LTNEE5)UEy<<}0Xe})r{8GrNGT2i9xW5;Z*m;EEZN`~xx2!B%Y005a7BIGc9FNe)LU z&vgn!gMuWTo$R`tCPBEFJ3M3m_eXY^v@XQj4gw7g4-a9aPlkS=f-(Rxi^Fb!L1K$} ztjFA-bipDEM*8Rv=G&jMu(*(sHFIm|p(Q2RLn<7o?@6w;{-y>Q*EMMH5Y@qS(CINU zD&ynFk2)54kSZZ`zmFCX&J4;NIhqH4PRl+StAE!8CxZ?0twSR2etO%%g~u@Y!eioo z^4XOJz>|^JySwX+_@W|jQrfgxo}J878ZhHsv!hvpb;@m&_Qw#pMmu=r;D<&7fpm$)?#6|iCo$Q_YxIlMA*yq|gGav(^sa2H#dF$D9M(MfvmPMq z&uXGx#>F&2h-Z*quqdLdkBBqGnAwy2@7}wIC032+6hE*4xY<=qU4-dYJSck;)Qv09 za%{ohg7(K*pgfcCA_Y{tgeRk<^fsTt9W%4Vp3-Q({=x0DOE=JDltk7HL=%pHCzX>fgAY&5?2cI-~04Cjsx|TwGWW0$9w(UxKuo>kc>V!nL3fh}FXzc>n7xZE$9L z8IXr6`bu;fBh(mJdLeS{;w~mQo|QmEE=pZ5unrhGmI#l3XmHkST!kxvHY&|dp6(|x z>c)nta2fe)GL?AZuuw2Gro-D&>nDee3B3kHVPdPjbJC)7eY!o*cFK((1<3>ks&osb z4AF~0zFcJPr^%*RQ-S`mH>{MT`j1YcZ{)lj?4s{iPp3o8eXL@}ictjBmq;M7( z{oPLv)Nr(EKPT7}tTqX+2x&9lr9H18#QUosr#o>8L!2<|g|9J^5sKR>xV*Bm^$H*0 z;$IBKp$^721v4`902;9|R!2oTk-gV-LqcA>`PkOZH zI~l%)Ey(c+eU8ZWAuLnoybYJyxa=eW-fcli1J@|E?)PGLYW?cnPFyt@u5158^-B+qb^^p&od%7kU?!_@PQ6@ zjGzAzSW4vcKHu5ClcRmma$isXmi~Fq8P~@K8`)Z-YvY@Pk33{Qvb+@~@1&yZW-1e8 zd&+r>D-Zv+a{3xMZ9mvHm9J0SERh#!re#ZAgY>()7kewjF)!zDOF{nno=Ho=W6<8LabgvZ2?X}Tch{bZMRuD2%giuN=q7Zq#mCi$&O>f>=AXR z(BUrM0|LCy=wTunjAK2}kGl;Go-?n@$`YVgD>e4D{w$A(1Sf^cEBNf86D) zAxE6@t2SO7?@r6JpK#>G?qV6+LE6kzl>P1*lrNJLsK!C^?)!^pCvRrn#T|Kd@ljeX zH_OeW%*4;Kb@tI>Kbi)=w!X19jsuB|_z`Xl{y?8PFIBX$O-S6c#lCpXUWbjkkF*b8 zayA?+K^t~CVdZLb4ku>`g@O+At$ql-7PD+bLwnY9otKsrpWt$@5zUcSv(YGuJJ(1c z`3e|hxoM@G(OZritFXc~4qqmT`iar%v0!=G4(CKqecD71q)IOc{|9eqP;r z8k0d|B#)j!1?z^giQV{L61}(TDf;Qd{xA2{r2qU3LdI7hH^wv6jorO)D{US|`?PP1 zeLsfC(c5j)M<#^03bsa9n^ROFQ4w0t1H&|7MSE75=$#aWS3dtG)P$SXUA*TH!4q7F z7tqlsRH=yp&n0tF62JC@CXb06I_%n`JN6}d?uy!%Rd}!!J9b$U*g}V<`4)7nM}w(w zm3$kBJ7u!FMKrK2zYe5YTU)cJFdG}re*XMt)ZUt+=kC7Yv#J#$&toTZ;(OL5--+G2 zElTB-OKkt%$=mV&roaIK9Y4G&p@!#ME*M}!UV>{}HF;AhBKm^G_decx2CYMVmw9#g z9;6hCqQDrG5vOQE%fy{Ek&3FB4r=4;U;Ek`g}gg)l(S<*Dt`}mTkG#EM z*(eDl-_h3}Vt`y1e$B>^LI>bWBVPy}1wagZmo=5fNDp>9#x+UPZh3uOVO-SiTSbNQ z;UV7{wR`t&LfaS7BPuEN`NIdB=gRV3o5?GyBg$M++-{?Gt5RH|1D!GnAAF zyF8lx0vE=&Mr`-KJbDPK>G{A1olD>as5~^Dwg7xNudKgM7|9y$K6({_0SIY-x4uo< z-amHsiyff6(*fHUDDa3CbSMrUd4rbye9*blRxA3y96!#nO*$^yjUP%ba2i7XZKPd# zp~LUp-G4?#o>Z(>lnakERzhMIvL^lfR@T?&+e0WMBqV^vhF%z;1OU(gy{$IPFDao~ zK9^Ttk8g_>S4Tf}NXnQNeK@LH2<4v~+bpqNuDoa+$kNghRkS_Js{Ldf_K1Y*=F#q3iHgduDA|=>g$ra*6d+dw zpFuw)@$o)I&j+ilOMxN(&mXMpp5wy@515M3jN(WhGwacp?u;qKB@WrYv%p5>p!r#1 z^GbPONCzMRqVsNPN*~}MH>_4PBMcFbOfL$ z^Ox8RaU>*)(VetOcZvQXJh6d>yPGSago)0D@P}HAE3nQyOc$KSQ>_>lwh2AWlt#*_ z2BDzt)?f6FHF}>)@;lZo4fR}`8$1ARiZo7h16)kefZFm5eg?4I>j&-Kl3Fx|Wp4nx zJt#h9lUL~Q>*UBJ72=oXT)+6rm`GOu0f!7`+NC#u>o zNYwBpXxhP7U))YyUS7_xtc*1*_x`Z?WO{XzWr{h)cS(SU;q3dlD!af~qBH~Q3iNzN z9>{H-(enu^{8_y<1ES-m!VAY9jngTZ16C3;dI4J?*9X^;sGXRYn9@ooSgA_eqXeNk z*vW^Lf1v~%XnM=-U%Goh3rexN+3@#(tU37iB2LDv;a)NrHY%(uU^FwFEHXc=FxYY0o2OfGtX^4B?{QrK=KWC_G=P7T|yzNe$){=V+%C7GC8z z&AH_}?X^!nkbXe`|AGNwXkM@3b9*v6!}0Z8+S&d2l(#tRUt1x-0|}%?hBLxyLV~4n z5O3Oj*w_Ftf(5Y$W;GaGQpLb{Cg{f8fEoY+tGb!lMF0T0L^P1Z8*oy{16|5%Q2rV{ za&V>jS~9NWA3)&b(h$EQT+>3Qt{i=?K~h#@u|EH~74VpnF)EJ@Ixwd`=Z=&;!eS z-=S333}2Ok^%ha?{r4!D_364mo9!9MinEJb8Qr^GSGQ5tB%S{DLzd?xb*^JIPjdh8 z_;@$umrt~{MeptszyJl$N38NXuy$z!0|Q^F5+RU}?*Ntzpw8>5FXpYGv4eouwUKGZ z`+13~m*3A(hR6kt6q$&jhm>?^_4Ky5!qZCgLVXKbqx3>Nt!FTMB$ zccS#Q+QaoO=pRS3c(gRnOO zaMRdBrWXrRG|vgJS^fgx=0!#~z=??@&wyn0I)oJb2nekQ>KlH@zmy_K?Gd3iy{RiM z0EiUAb`>1r}= zj!+}Fh~+fcmhwk7;u`P_=DFIx9Ge`#PYDk?BcLik2I!`9jiy=9%vdo%@BrZF3B4~d zOCW3WJ9r{Em3TQ$y>R)*4^XRq8Xi{Qq!z#isz8kl|5PM9lz!Zasxb-B{r@_^d)x*g zy57tVkZlnxDzLJ5RQ7J1JnXinOlmqDr`2Cf1_gN&GaX2qHjaM^FpyuoOU{$1T0x`} z?RX=i&;ev{)rKDgRT;uRmpcS;r>GW)xxR*8E{=0~ZS8e^eJlj;6t~_RM4=(+d+R9B zh9whdtRC!}RelAX@KFK@V|jL-kl@=l$~?$TzmtB%sb6($(5y{LO4Y1OrNqQoaP7Dx zLAfz3vJGLJX!rX;8=VNy16t+f2`oS(zoy^89F6@RC7JigjzSWA?EC>W0|STq$2+G# zBV?-}{|B*kgc6eBKzBI@m;57^Z9s2+0spZDOt=Tc#Nj0Q)WYZ&@Gr0+{=gT5QICY; zw_6}H?UP6}GQI(t85~zA2Rz=BT=_YYeew!{dZcznbrC`s86}+ov+HmW91j_q1b&e1 z%G1NjI}&ZKVgs+PCd~wZLOn052uf!on8ak4=|zXYN-zsz_N)KqBDhlEnD}Z1pyGU> z-@obw-sAW37tFB}U#umE{QSyuac=I~=Vq?lPrD5FyzrrYv_UC%ol&?Qs5l# zz~R+YF+4J&#z}pNDO&8nq02fBLd?HyUP(qr;zMXAH2>7kp_VY>RI#3Wud73=wtrW@ zAcKEQw(zRT-7p{2TQi=)GwYU%AuE1kjJ@hbZ(h_t$W2Q0MJ?7Xx+mGA5Q+;{Prqg@ zUf69GmG~Z{;$-EM#PEfz!bqE*8ut$zY4~ojH9V2(A`*UY(q$}m_I^jQv+l%cX!PR> zH8uTeAEsF+NQerto`CnE!gWM(HMh(9ZEfv<=QJvGK3(OFHI&E5M6RJa01kYeE#Qfs zkA<15^sp(fRK7dpSzlk*tmpuphtv@aEEwG;!GQA+u)S zaAZs%!GMrF_+tMpOH5oA7A}G%Vmrh?8SrPG6$@gP1u~0$JW#ElA_HnK&XFUt5nx=z zt9#~Kb^Ig*c^G(0%K>dbHY4`8L9uyq#0qz^XmN6%dFXGXdFWR6>W>N1jL1bPbXTTs z@Lu;qqlNFHzNUnOdDrgk964afz@!L0fMVF~OF+N5ojHE8@N}){?o~j)Giwl&vKTWD zJvA-t`9+i(uhyHox-qIkT7{f~`$UzkyYzp-`6@fDG7sl)9d-tCADM(% zPODfSRJ4yVyD8*UWNOkx`I@M&jVje%qmxP)g;kL*h*V*7JHn`Auy9VaZ6r0;kdNTh1hBsmJ#a%qSckPwRS;1rDUsD%x=o# zl9_IbQzT2<2mQWQFZ+#bva1cxLSY>fLjh_Ec-py!qhdZ)XN;0E=mty$ly0OK)ZHLb z{=IWq9K0RFwd^6m*)Uf-0+?!&*MI&fc8xyCxlnP5-C- zN7cK;z^7gdyN#=_e{ooQoS)uU#=_Oq9k{dp&8|1MgR9-s8%c9gn>`aG&xubplfY`!7EUi>b01tbK5yn`b34x z!Y527?8dfDhD=@?*2=4xNTK^k`KqsG55a9FNRHq3jhX=Zz=MFVRG%Wd*rC2zjK}32 zae{QpO!X8Y#I7bako6XL>YBJ^i73L zjG*qBH>h2Oz{dawu$fTd)#BL(nxQqG2agOUA>>f`LoFALJ*ON{+Eyaz?P+4B^Ea;!bUWTQ;!bezQy9VQ2BGK?KacC z)Xz3XFDi_nDj*9}K#W4e2)CJ=eBSLGWj0Dqy0U`isY&Oyb9%Iiw$~M4IhU1@Da1KA zJ99C|RQc~YL!l=s3Xv~N|Hg~l?Ujo!|8xE5i}yPNV69=?u&Mo`zGM09<2H_rTWuzN znL$h2MmdMax05dytK1!Q8wy#JQY(nhA7RwfSJ2lN(YP}rQZrG`(e$^RXK!sC>$%63 zU!?~7c!d_ zp;?eHWQ4&(lwP3V`PsS|cuqmb5RHoVC?5(~5=QDtglz;_({m*L47u<%HAH7cI8UI$ zSb#zT#7faB+r^gO0sFsbhXO-pLhnzY@Nry$&w()xK5&8|9x5c>0ZK{4Kaa!)!a=81 z67g@3MgtfmQ#*m@EFH^Y&Is<4lY!qu$)~ll$W?=~~re4GE6t)5l~CxKbVN3h7+xuR-%C_q%}+uKm#U zi-?AZ25;;u;~3$3R|9TZNGln9w)BFLU#aO&=leHCC8ggdH_oHgM@(`pH$B9LAI=8m zXuotEJ3M7)rhs&lzWKVa2j^Jzfzhq0Yn6`RCZ{An<8M21eAFvFcvW5`1mkuk3yzR& z2n>ifacNBiQy937FgM?Aodq&(SV#OFUq2H0j5yTKu=oUn`44I8x@C5SVrNCZLK-FF zntpeHaY6DiVTFU8dLEea?@%CuRg2Uwm3&GBPrw)9wg2pF@ zZB_EMZ`x0B(t}$$WU~WgHlLw@xeNHplnmhzA~(BvcQ?;rvsN0VDW?)q$!DOWgVS9T zucVvKRt~{rrfSto)M#`|9M_O zm>hZ>srvPBonUn?jYoU8pi--^PX-17&<+4>6?8rhqCvtSbG(8xQW!STAk?`r(>HsL znt5E$BRzU?p1@`ZN=%Vu8Bp*nKrd3^N`EfAw6q1hn%&vk|Cy5`$ClDV-tCY?=vVy| z{SDu&jo^BFQQsMl=1(|<$)}DugO*?HhC8u2&tUtn2PDDvZ74`M?d>QA3$jf}u%|~o->jE0d#KhFy<%H7ZUXZSz5vUEJkla(o z&biX_`v?zmY7H6zh@TON*CB5WByD@n3@YM|*l>)?Qy=h^{jD@8)p5Q*Cm^FHNt!*6 zX?IU!)T76IeWBo?+h#CA4V%WK%C3> zUsv`Bm!XB2sIT04NnZ``2#{bkwyC#K`-5i3tJ_l=qgP3r4fyil?Y>{h8p6U;xZg2A z?N)vl$HgGIS*)E7v%BenKijqMGNCis8JC%!wtiJlxXSOq^8X%d3Fwo4cBK~0R(vOow&rLstwm)${*!` z?`xjse|$poJ+C~|bZJNi)r(Sb3996UW$(~n0*1L|%GIZUr8hYfII=@v)B-g&{bX3X zO8W&vcH{GBd6}ZAW4o2iC~E{{&OFM&s1+GiNq4MhSIf*{Ef!`~wwE(+#%5))KofB_ zk&oUG%KfgM{L9|H*Fx0M3(ruy4TTVxm}+zyL7#rpc)o)E{pQWn5L=UY!mtAX?3Fy# zI3=J@XM^musLuuq&!g!(EI&~VO|wt78))>87@lkhVp2HHkAG}(pecWkqY|pF*qx?J zM||kukgCFGAjw`oG3RShUtT+b(Y;R_}U0Pl^3-|V-DT5*|S zHsqQu`W9vo)g5-jAUE|w{gci?>Keu$huo|I&)nXVK=vd=LvQNoaG(I4x>C=Z z(2Mi3e=+ke-py-+6ZR{Dk2Add%GN7ec79nHjW)kz{OCD3MFT%fq(Y`Lr?C))c-9v@ zBTnjDIuzF|^?7xRKgt!Qwx;u`!LsAw&pNKCtEL_=M^+KP0%((K6bSC*ilu5;A%CEokn=Iay0*-@w98Z896vH~j-CoWDIU zbN~uRFy%L~AqW#IcprJEra#DwzINl3F5WP&LVwI*`-H!?ZANo>hB8OnXId4PB0_RH zhz*~x>yFUfVP59CUrV+|T+9>+L-gT+FXCR8ULsY(mJrY|PdRxvRR0|Qz@KE4Yqsd! zv7q?u|G9K^Ec0_Gy!nRtF2vGQxKD><1pHF6cS!BM;L`H7ZA;@dSwq)bo440Pm|o-7 zxlC#PnGxHv4j`!Xw5@dt%sx!Eu>MS`AnYGlGxGgIjS<`uP>FMdgT_Irhmi*~!#)<% zez#5RpFXZP7Z(U-kjn2+Jj32w?8;|X1>yDtMpQHZ zT1yQa%jbu~b+}%NUA^V^Fm1otE%)Pcj9cG|$X1QLH`CYf;m+r%-NWBELNBTE#dZGC<2gPhMaYhOp0)!ruxvT{yjQfsAZjhcAsQvJQfF$U9 zaq|v^LXI{Y)A~>lddBBTV_>8#9PjwySr3_)zxDeY)QEx8jcvuDe9#OJ7;p-*1mn>+G0N9kq%^ zGphtN|Ae6!B*Lx0&JWp*DJZYGhsB!0Hxr}N@r4Hu&4LZSriEKE^tj&_>Wr%iJo1vy zyN2T{^5(-5=8>Sw*Ha}C9{J}s7hUQm_G29=&cg#RU+8$mcp)p`SFe!t38RGT!5VwP>Ll?x6w?Tmh*cmb%!g1pJS(*$0xq%OzhyE%b1`t3s0#gm59MTXe zETVvetOu~1-LkVQ!d63|3e?|%pi6?Y0}1s;X5y|+U?HmgEP{waWITvyWL&t|)|=gx^l$-=jYIm}Km`e6PAtruVuz;2)wSw$b3ruQ3rH7D-P0mMm2E zX(FV|Mb|_RP1!q0%Xg}Gt`PF>@khUvd1J_t)<(eM@n)#5wHep2Wj`T{Z3Dz{z`%pl zOPy=w$B#mw_Wq@FaUQ-9N>z`CoFf;PA|QFeQzu~o!~bd?x$uJe4K8aiF2I9m^*4cv z1l)>yl_NBUk>?cA$YDEQLmZT1;}RR%g06=tYw~LX88Sh6bhmt zZ|({v5EJ1KI_c{_mwyj3-fyh!g1yaiz=Akgv@S&z~jtr8EA-+SB>ow2lzkgtjO-M2K&S~r?2$0J- zxgNs6${TQgkr_gA zA(S22I|@@YL1+Gz1qR;QG?hQ53d+%uaq~C3WlOVlu!Py=&|1{;Lx;SlYV~Y^+hxf^b5#xVu5AC1#iA zNR;ifx7~tEv(tiGp+{~*v$@VG6Krx7^0?(q9BR5rg6%R?ncAFfc9brb!-T`M8-l-c zAm%8`(H+8ZJz$mpt|A!(fPuq`dHiB!o&_5E47A9lWm4oJn_y@vHlGe64d(yxWK}yWp`I{4%mSIQ^ zG$dVJ?-8G4R|5twGxIjpFT5yiZ4e4zUpNarKJoI_7o}f2x)%a*6(DnZ_nnMn1sYZ` zB3oWxzr6d|$7!s&Q~?LWKyq9aCGIq z?Q3d2m={4VH8)cg%q9`@dL+;W0C_S5dcL(pDT6dJJ>^H88pY4Rp&vs2V7EvfVL)-ir7dw>6&>NA z!-GkyMgoko1CPe--S=%krUCvT(8S2_km(y*8!;-UeAr)JLOV@FR6U7>hqtw00k`H_TN#p3NZM>hIa$Hd($j{A&UTtG%xLJ#rJvy!Bp3{ zJdogjdP0GqKN;d$eWy<@bx+(r?Kh3Z|H7pXM zS{z$0gxx@)AhDSt1t_zj#}oXOpiC_DICMBVIzq(#HDJtFvsO8NfcSWEFJ1Yc_E=OX z{7%0OOSphj7SF-dTK;w`{sz{?IAQvyM<#7**2yNDH-0R2(?{==8(9X|ebb`6s8Dj5 z`Si^9Sr)5VHGK6qsPX7EvpMC6rmh!GTFAeX1hVO?p;`q5R0qCGl_}f+c>N;E z9m#@$S&s%KAnGOsj+~STy9m;-tsd4mz|88GgIMXPp?3TDw^ucd*WdgQyhwpLZYvV$ z#mr=jbH+p;x63J7`zFuTr94o$xReM({r>|!?>j{_e-lg6|3cS6Eg{Xl^gs0>3$2(u zYRBQDkgqV4Uqr*jr3MmVAN5n}6dNp&)>x4izURb^ikTtf$m{NC$S=SVN(irXH2w90 z?=;7^JobYRMPgW0QfadpQgYM$?onAZe4xYg+W+_MGBt7HA<6JN@<$a*jk z`44p3hdnPETOr%78!V;|f$0RMEc7QWw@g5OW$3Z>6%m5~=Ik(L1*I~(+kDu~``XdK zL)c0^KTJIVfx;6cZxB@R(DoymQu_hbn_(Sd|2=wxBFMT)B8=F{o~qk@XBXY@yoVyZ z?~*VoX4!m;c(aerZjHU#X``b-izF+o@E(wRbpQZD=6ur!Z8u#Z zHsa300i^jMBYL>~nOtWu!JSv#%RyC|kXDZ@V(rRn!EQt? zx0_E*KLhwH-eV!Wb*VdP-v9p}@;L+JA-bxiqM_e>afU?ffOLhT8=A-U)XIiT-!Q46 z`)xQ^{!Ux8sGbwvqtx_qI?N*;A?+{d7bN_~OteqC?i(pFZJ3_8iRrL$AVQAR${rS2q}xs^>hR%0PtO*cUU$D7At7 zp-AuxVy?51)u4ob&CS*1)_<)3Nh?E-H>!IPhM~a_%bxx==RT(Kob- zlx1+f2AP5b7jP7B84uhJxc&H|9W@!YW;0=ueH#z!!<#J!0+-Ib)Lgz?{`~&{HeDvl zZ^5_-kqK;FC;Bh?hZoL{^)-z)CdFPfNB=r2vy_wZh)On5Ds9qSM8Jh zxk$WTew$l9n|}P$XE||ob}Uei_tLyIuQ7aRB2Jtbg$?eEAd`SIZ`k?hD1WP7iA_a- z*5v#QGDT*?9YT}Jz6aeLS9xQ_g#S6j#p(ZMI?q(kmamPAjbFnVeBade5S3_?sYFPD zPt8t#+xL*DQEmHJZ}$0u5T;Xe@D2S~er7hDkTz@^U)QR%4XA?O9>(29rub&)z*p!97jPxo9?9~x0*ONF#y)E&LDbI;5&Dq{u1+EF zI{3A7SZbi!w)D;i(QZH`P*|u&5SX!KzvU_nKSI7>f&mSX?i|sC%T7TyA~yqcdB;RJ zSU+>!5K#%3c5D~=zu^=H8Wq(X{kLilUPq7KpzL40!6NwF)y-%x&=d@c%ELp$w?&^` zwx)e1KIEF+l1@l5=Nzt=|l_Gh045rVq+yh{?^F__>`6NBs6}jcDKw z4dv}*T8g>$^c_l>EZ+&NsS1LcZBte1E;x}Hvz8$L0qnFO#L)VYV2 z(y7Yn_j%8)YWe_r2bOFrm@a!q)<(y zNCj#Dz^)=Oc$aK#{`Z5*AigJ>*qN?Sw$^O0B|7VRQcd2SyM<|YVQ_f)qOPfYJ#mK2 z>nKqfxtAJaFYRvVMqj{YDG`wS`}KF4U!UcCW3gee$!v9bGRbIQCB<7`cBP~gld0D` zB<_ZFHJaK~?Tk9ADE~8;Za8T&zAbDJvwhcP`i|0|q|?{Y&^8v^=pwHN8-}W(gMoHTN&ir*V0BMJf(P7c_JKvoC-E!I5*>9- z+9Zo`=SA;V4-=Ts$J~2fEI9O0rlWp%F>=KHmCp&*LXps|O95>JD;ZJt4QVp@gtpgX zc8gR{g4N$RJ7ZYT7V)E*aeMoH*S)m8>kWIP9x%#v^Wzu4#)a+`kny`wlI>j4%1?xb zs?8DWxE?LMM;N=i&QK}=Lk+5P9Nzr|s{{~=8X57mnD{_p2<_#kf`V(&$_PV={oNH> zhLH}skFF#wUp{l+`y_?-l2H>`-J8|pWxrj{D*L~_Ul8AxC=KMx>iOMIQSP_-SglaD zWp_R7#(KpVsguy()hcKn&H{$DvoIv;kBJq?F5hD>C$t^jjEL?=Cu^wGU3?J5rY?w~ zRolP%7~?HyZ+v|;pN)UuZM?g%br&D_A8$~_rGrjJAQ%8eNM@!#U>Hu5A4O#bc*Umg zTm@YTKjC9JlxnNMo9)A+J`^!@C<_kYGX}$dV4-K$)gh{@bQYl=cJaLp7_&atjLu?s z&GybSW!hH$Hof%!+H^OaZfDwrwCl$y6;s{oyp*BuJYl`d6cZQ2*hXtz&!={>B^t79 zPV;a;FJ&!KaMsY0X7>B%h$cpkv!0pr2oO4YNQ0xGk#X?laqOgiwYyOo+B`JfOiS7ZbCA=>B?fuTlU}1}TIA3lBhV(-5He%ylXykdI>T`$lU4qDexd8O-fqT#VzHso;Jp3!`^le3pI~qiKJ?DwfX1h*7 z{1vX0%^B)AJ_UD^D8HcU06q>DZIH9U@D0e2Fu$I>11~qCw zs`DZZL14$T8(8`=AcR`5?|$ha9lf^~kn@d&IuG(2BfA%24(=$_uTu8I4IS}eY>7?u z$hCb03`#QQ_|;3iAFZ$XDYGZLE`nbBWUD=SJmj_?;)al~Uls(6kKs`-82LuDFaMt} zj@f!C04d$eL#n=pobfByim8gHu%Ee{e5AQZ6dgiV%s9=&kx)8hA-eLud-1J#l8b5{ z-9X1RNAKrXOcPGUENTm*_qj}IWBRfUTc+UQJ347P&8qb+4;z!cLk9gnY!n zzKD9_CzoY-83Q8ERoG!?Wfc@8b3I4^!uCR?`heA$N{%o_7yppM=1dA^k@VLPMJ#1i znjq6Ot0B=(Grvs<1+R|VYzu7O!t!|{ba-C&VrffbaR02`cnO-tcoiL!QkHKSWSAO; zoSIbjpM0pRhO(-33-%w4kAFS0v2`~n=;Y(CD0pNLyEinZ!>6^P6Z?{?Qa6@Z&re?p{`xGetz84% z`Pv4(_^|*?B)(sa*l&CI`gt@5;gtX~dAt%H@`N?x#>JlR3D!7ADtlc|i*2Xwlc?Ni zn+kZHn=1gRrc>V2`3EI0Q=FU5A#sm0RGB~atAGP-kiV0-nM`aq8YGj+Sa`KTWZ*fL zX<}TH1mO!0G&O(Bd*p9+QO1@}(bL7YzIK`VTsB-3@g^Dk$y-UWt@Ck2?&^d&b5 zj%7Nueon2v#5}>=10w*2O*15RImvA?9^sQfkUB|3dn@E`6E#EFVKu-KoIE_>9~lSE zDW#^jOmPQ5Ob#gA9a~$zXH|*w5i%*d;CuqSG+31@0kooC-dwx8?^d(it%to>T1HJd zo4z0ZT^1&Y5h2zAPsiZae!7Rw+VRdC?&w`^EXb1i0BBy zy*FzQHwOg-0vjSovgzjltd~>BVvxQ0fR0X zlOokWk`90k(kjiIL1~R^8Z+NvX~a)NLXCW*IRkomfE=hYU~yPBB6McS`J}aS!{g& z{6xMTan~`5=ZkR8)7*p8YoHJS(Lub*Wow#*Yq^0wm0j}JUxAOsN$~S0w$Iat4AYN?f-d138*8Nxw&G z-;kQ$&{eia8+kkA86?RQLe4r;@5i2>nv{B-;wXmavnH#7eh#pBFg)RpZC%-o`X1NN z4K*q7Z=%S{o`R$YY)Jc2-6Vbao4oNV=~nuZOc7G9X(jeNgM&u<`n4$v14MOW-MMOI zG0z`TSwa4qA-~1GDZ~>?#kfAywg*Rmla~0EFvi=O%=X#tS1Bq;*q<^Q&gkoIjxpBY z(ck&-v9HTu63pW~8Xtq<))F-V$X9>>?bkv*w{>uKvcSBz<0M?lH8tm2;cserxQ{{Hm6hCYNm(^M zSu_3F7YDwYlen#Jw*IXP5Mc#t2DXr$3-T*Okm9Cd(IgC>$8FM;x#IV=sj9|puP>L! zIEFL2vk~sn&}C_BexiPm>)Jh>W`faOBan)IasR~_k-Js48_8m0msK)OkgsPd4TNDu zaFFzQhusPuCDgq9op~MScy~kg^5%bzj`|J#7Z8n&IO`zVJE@ei&t;*Z1d0(%-4MVq zVwSj0d@~Sv`@i&=1fpl{^td^`NYiy`TY{+MvJa!g!|w}3p`oGRKJF^129C%Z`&j6{ z#VyxYw=(?}=-Ujx7Sj z3OZstGIMTo<7SnB^^g@}p=Kxgrqxu(0ph+h zI0-=YnQ^sDCXOoY+B;C_d@u?`!|rAy4~*7V%NcE!X^QH~6)y`S|3!-X4PCZZdf#Z6 z@N;#cr?|a%GQ22$L1!evSVhCuq;wxs-GvHB8wcihxw<+k65=5vm`eKwPp3l-FE}5l z3ipm*&W1N>>!sB1mob3v|L7|=E%KfU=C-zS7iAFt<$tN<#rC-&!=Ec-K7kfkR7sd% zDn^X>OuzkD ziiL{-E-ll-4AJ|dj=_`;Jp2nPV<9^02( z)g(e!qtXsvYG2ceNn1Z)g>DGUs1eVJl$N!}q1KO?8g_Us8IlMD45M6hfepD0- z4Sumni=U^M!oOP3{_U^ngS%e?Xz~0%k=}>s7*$mt;O47eAC#gOAU{J zq5qUWmQY(8pkXK<_wNp%aG@G%@{SV=*{Lr{HjR}lD4chyRmzI0HdLeh8kWlq;ngU} zY7+a7cK)&areWeIL4W-tQr0^|!21Q(zbM14GZD8Uy_O=68J0bTeNysmX66o(-aNm5 zx3w7JQUuw^QVANbTm1vjj|EDeF|Dj{Xz1Q7z8MC|;6zyNcONS#TnsWLBe_G6+Xocr zkm-#o_jG;ChmuSdoiU=2q4MRi1~(7Snx_GU5MOQKI3{R10Oq4q_$oleKoadF?mu`k zZ5U+5|Ft{@{g6Uz2e({bssntf7ldMCL5OZ|Z@+X_m+cO|e!021z@nxN0waj|{aBDm zzUf@}@bTkE$DU9|;|9$mm42o)LuCdg zwNe+@gbjJP^mfexEe=g%Z#YxrGg+b+^hK<9rG#7g^ETotlC!PA%GUjR&Th4S4LZp3 z@Se29biAiwtAJgNp_7x-i05FET9}F=2N|v0y-pGUFP~M>$99Ia0H1*8VrdQf zj<2-|IP8_G3gFTK+Ze{4uLqXd$Y^~BmgP0Nvf-r7WO;KhOLNc62s4Rm*_)P-)f45PIGoH*W4ENv#QroIvmAB&m22$dV-zV)S*?9H}xgtcL z8%e+mL7W^I9dZq6023{S7!ul*R`Y79wK2Ovo~3ygNF#=#k1VW8ZvxF>^iWSo>) znn(e&sVN{TiX4thh+}#pq%ANxFp-06Gz?Awu96K+OSkSCO)C9ai6}WY?6{%Dpkh!Z zGS=yjyZv$`5xOAr*j`4alG=Y8$n8|W@({F0h^3DJ7=B{8Dn9m(QWm!7{GFh9v-s2- zFO0P80UfPh3fkSuLI|hq>!U|cX-Ae! zFWQp?ztiG2zdoo%2~AxV(o*QEuxGyO{v*n8872_f*=z7nu>JXt&x56veh#Z&_%NnI zRNtZ#ve&^=vdIMp+47^uNqka_5+g|suqy$gKo!LtfVo^H z!?Uea;)Up-pqa%UYAj&sdbqf}`%=OmC0^w?(ypn!BbP_O7rXK&7#(O~Zk|a8g2w5!q{VKsDigh4jq3>=ehlOOkqV+I8*UoVAF={bv&_FIv>G z&c^?HR`{Orm0T^Oef?6XvY2{&`;W9xq8(x;Xe0L$+*)Zf74RrrCx{ZaV_n(F?S<$Z ztvZ<^Lo3A z>Vin#M@IuG1KvVyZOEsfRSeI~C3t8szA7s~{d%{S^6!0?LG)uz+K*%f*IVcqejx=u zA_(35GEITPdGMa9b=Uav*X6RFi51VY-`D96Iy)Bq+CvRV+Hgaw=Y%nP62)zb_S{#) zI`6KC!7tv_HHvx_^r1R8MsP*2 zQT~}W9s%$8Bs;&8QF8g!c$INUCwOzB`cxRGx1UqPl|eib_3MPYTs2Xo%+viX6k;RM zrWjkUZ-9g(V52vD8r?pBg@NP+f5p!}6s}s1;#JI$+ZS>kfPp5!p8`aXqgh)B=M1dv z=jETPi>G~q^F+Ui`nw2#k7#t?Ii{DOej7{Jy4q*Ax^n??lHPXz0r9be*oqzr`~~w{ zpuv6vdAt?Q7DerJq4}g&KF_|@N({NedfxlTM6bt6?Bi^F;fmze!Sh45-@hhb$Pk9G zZDrHYNvv}!hD$yMoHM1T^yR&PL4&KDoLz|zE2j4vAmz}4u=8dBtj8{1Z|yPi9PCy@ zsDjsP-R%!xMt4f`8B!|Ue0mh|>_0Adma68p$7`h$t1Y5FN5Z|+8cvrcIMewD_BQov z@~}3HkA);7+F&4)5EH{#UcPE_uxaY@3awfNqGv6g1kZu`sjEWq5YF>V7X%pgaCbl< z^+D6>->gF9FEm%84CqZXt(YPIix%>Jh~knU8rbDEDVA82#rVo})r@bU>q-9G-u#z5 zTwK7|c&o(Lhgy3}(9_j1skwZKE9k@ea5GebxV+evFO!IK%@g4`*rEtuxTmY~#3`93 zwHLR?4OKz+W`Y!pdi~_HtD>%(+hQu;iIp3f4~H&_G+{GeCdK_Z?zGqolv=R-)#Qb& z8wFUN%JQo;@OIRBp3N69YUxsHJp8#I;wF!W>1j}jPo74ssACD4a_0JxqBg`s+~win zAO{=VEANDvA6${(>k3dp87|K6S}-yw08{`{5xBUw$s;%jxSQcmXYB$YqYa8YXpWWG zLZ^*?=!*qS)~O6IxEWi!#K9q09Bcch_EGWA9|A-Y`NBm0Ds8Jx*}2?7n1C24lmuaa z{4#IFK!OY6C-`h&<%7Y3|KhZ=wUQY3|c^tLW%CHU3ihV1b(;K-zTHi-Xvun|m{AQMOz`<_)TRg2{fWo{jrRq&j$Q0^7nZClve zgDptmZ4!+8TC$o$r3PHEWoF{ z$UYpsIVk)mPTFOEHkizvCsFudv1po&QoZbN_+fQ<$|*oNk9CjAY#wCWkdTlk;P(%h zBn4sy7A)2lsYL^xgnCxH;Pjg&7=<+-0{v6Q#lv5kB10+%yZ#`m>31 zpH?hc5vtF#Q%$CCZmre&=p5GO>dr0m8o&JQDUIK@)-FCL{(88wR!uK?gd%(5e6sqj{0Z8*6rS+Kd^2wMMx|Gtf9L89EJv8; z63RG~?bri;S2e1Qmn->**b(rs{$f{uwO%{TNuuS0-jy71PKH|?z%nTQR+p$0O7i+( zd#L411r+*X z9{S_gmSsCVg!bXIA%pXGEnPxI)3Za@f>KNHAlt#6n+m1?SvfL+2j zi)!-nq)$F1bBtJfSbBIcE+_HpD3)%p-gEx05hLYh; z=QG%i9-)VKJHwU69#N0Qde+{Ej(C=8s%sOrS$FVzkIuvC_zjb`1xBjOGg`Ia&*Q|5 z^(BSLH^MH}^GA!d?-_d4W(z*XwScFtzkO;Y`C?M*Pe-@icBAfPtB81S{E732nT$!N z`wC`mr??yfOC#KK%QjV>ifc2g5TjXglKsy0xb0n>$e4PM&qeRaC+ek_9vlBU7wcFg zT0dSnc1eM!%w7CPFB_Kq^J9KrgF*8vXA&trUR;~P1Dk_dy(^Hkx`_E_BhGMo+D@YP-E z{SWneW-gu=z1_Vzrj5#(e8e8)ayslL379c5&y49iV=GT$E6;BCVpp$xRsHanf#+tR z*h-x8aT3Q6rDH!nE5<=jO{UviGFrk0+jZxi%khf04c=BXAM=Gi1|gY#(jZNn(fB7? z(K)>vcVBrF%(BV6{L7df#@N=BEPRPGUp#NSGnMbk?ep*D-7P##-0}&!g#9v$=fbl+ z%CAqSS8|H-xyu16t$aQmUbyn}rxuNeW&hNa+||er85s<*oeGF`7$Zb?f<9S;Qa)V( zf_#vYwUf@tDL{b8e|y^j-~ou|__E*tNiTlcVyjP!A(@@dhD($|r#UMvH?UL05mukLE3Rdk>pF4A_X}p zDscjsK8Q3GrpJIYA|AhxbUWAUedZ{m?z#Urzh!X4-%pLw(PE)Bb~pX%C0 zViHOVn}{UU21!~HT9+H9EQ}33GU%QKQoL;0pR8ziI$rrx?@0XK#dDH+5GqY~xPCf_f)iS>4sd<&R^%}2y*(SbHS^45dFVVFi^xZOAhR})2dD6BEjWkm^d{I%k z!dJd{LE!yygVO^BJxwe2FK3a)+NeHlOGZYtcPa2kx50LL;74iZ%pruR3>A$3{*5;( z_Z~2f1qa&Xee|JkYz8Ov?GTg-R9Po+Rn%p3@Ztw<2AoU{1-atlIp{x6gldfjW6nEs zHF*phtt#JNNw?zGU-j}3g55R;|Jr% z5@OuNVMQq#xUy~~bmW2L;@?$zNb3C33)NZkZF$FU8J**)qaB>SbiZD~Ys#BGUhNI0 zO{LRSRE(R1ZB*1^4!`(xD3+HV7!RIQTmd7SMVHLAvS)RJFC?xQ1vYEp6>Nr&@?B1A`Wj zlV-9$(M{zFt>OJCz>=&6(jNPouHzgfwy~Oe;n2>74CqT$2Uh3*4xM)$Nq~Y6rob@a z+cN`^!4sjuL-!vfTa;OOrF=~4Bib(h8lIq9aEYX?0Ch7BTn~?3>>?QthTa z_rc6SUBLN|mX@|T_=zDYN)ry9d>$}&S{*6z2XR=*Oa&No)Qwngbi7VJ`ITY+-nHvm zc$23YeR@x^<)W+Os)LBd=1!9>JLT}gS{I{!bvx0q6)BY zaa~TBmprQ+eb=4!Dar1G820QzkE7Rf$1m#xd%r@dkEQgb-L+~?ccsp&0xdgu-PJyn z)fd-Buh4jvjyuw1T<1UOic}HL@N0i$+*{>!nyrL*3FXHiZpA$=17Pu;4Cj&^{eQn&($5UQ_7=wKWCx3CHi)a@{=VftdM!`;a-Cqh55<(4P&^xX2wWADWd$n?@8#-j z1~#snAN{4%v}ON-A;vi%vXjUUExnM(fgONzK#~Txq8;Y*EoS7YV8Crvw^s@Bo36y0 z5fHYzzv7yuaQPfSeB;J3CEnzP`ceEf|x#<(MSXSdk1rC%wW3(l`Cx z?(B^W+cmvrmh8X3IZ{kc6RUdD{nM^R>bpN4Cu^t4Y{Ft{M#bbl5={arI}!9lE63G# zV|I1ZV}%UvxA9YDyl8vR9C0_E5eTn@zaUIGKU$5{a?)w^wB1vR@%kYrVqv#+U03+? z2HKr7aPdCDg>o)dPeYG6ycEO!F8YUHM)lSY zE03*0U5tYt`I#U7sNj{Tf0(nGQOb%Z!%fw8c41-f*$vJX>qo(uDTq|Y@ZQ~!2-a{> zKY+k2TF)3-W?Yn&l{vY&KhKX2Htl!yDQnjqNdo#-X91B)pI3I%I76khniHn*(b`}J z2;fMadP1Rv1TMMB^XEdVZ&frXk7dU5~@}PoH*9T9RCB(ls0U zLcrAIQfibQz41#hYr^ZhsG^RmofS7!KyC*-yDmFtXRAA<%a}bf&-5a)(vP3Ee4RgR zsb>`vzaMb#!Ir3YxKu_!s?kfzbC;I|4U@mbnfD*rqs)TbFgacFCe9b|we}pOs~!o& z81U0}!k;GOlHL9DGo~*7W<}`vi=IozyC+{~SH5hu*3A9gdP97W1?zexh~*QC;<1Ty zs_4>wEXhcXp0*_z)j~iQw8Wv0)rM5Een7bbbxV+`s?qgTPaJf!`9(dQdGC9WyEp7i z9ujcM!xTXg(GGFhduFwTG+OWViCBjZC0x|YZFD%2dz|cr0(8+k8MTa-n*}iGy!t0K{F{9WzZBB<#+}mkqcF>*fEp zKrHoMbvJm9bbzSGk`#ZLM|A)cI$vA#EA@4B+CJQU7biF`%;0@eVl!DA{U3|LaBZ<; za9gnNSD-0*I>?Oyz9&Fk0Me5n?mT568Lph0n-~}guJ2m|{7ytNc}v*(D3$E-jDC8& zScv@(pCJB6MKnge#bAvE10k`wSFD>a8^APSVx4<#-2Z*!!Ob3=r@py2VkDBTXm{G+Rt>T=%)Me?51nYbzRa!j!jHM3 zg)6*`P9bh4%&0!u))nHP>mSpV3&w(9G(68=$^Q#`e^ZQeRv)Hk;NREttjY~YDI{&5 z{!s{Cc@;lf{5)GcX>b=$uzEo^T|a$a7T`#V*9!QkjWn-gm+*^i7}tC#`h02Mj@8p` zw5bX_#x_x##4gL=P3&H;ybAxM#oKR-XgIAZbs9cpM1NSj2W?8^R+*AWzR(x;Nk0xOh{VGDN#mQG-{Vx|fyju_YF zENaJiG(Ngt7iR?D2BR`e+)vAhFDqFA8vQ&Iu57Ao=i!E<{HnLzz+};r<&K^k_{FY= zt7RI~=q7jz#e6&Dhd{k=^B#sTDc14c;<1UqZY~Avm;a#8WS`m7@l%l7rFcg}4| zp2||-;d~;+d7*DxNufu8NJ)g7gr1(EHXp>%O{Fg|+Mva-9nEgE>mKo{(} z^rU);pxPNg6cLD9Xn3G1pH$utwn}Ga4K$fN9{8sr1l!!wFf(Lj1 z=ZpVRRC{$RZq!5CsV}$hr{#Mymj||$RF)SW6%;C_x-d{=t4u94QYws^57Nc8=zDpW zpD35x3=wsKnWaGU(?GB!j{nY8OdV6n?{6R1RI8n?aiL}2zc}giVIcb;TAoPiKNBB$ zhPLfnWxh#0908)6B#KlC+O{GTjx4hKPsB%Lk*g}WZJowil2rY*f;_adeU(I!Fqn-1un-4svp{2N@Wc#P z%tVL}9v~7tm5KFqT|29UeOy@khZ`bAVAUDienlDr%O03MG&cK?j+SN>RYm}tD44vd z={3Ukm*L>WZNwu(A ze;`jzwO~}#oyP#Cp<3J(OY_c&ZJ%U>JQ-MUz|@%*w!WJ4U_$kN)W|&8Y$ZJ$?e%Jd*mgv*MknoY;FFyCZwNsIcc8qi z?x6nJuF3O36v|E$)j|1ECvmNr0dKQ1V^hP3@hpUb(?vX_okD6aGZ)=ds>Q7e;k3(6 zm($vD4-pn+!l@)B|1kC{w{UQ)DXtad$*K<6A-oAIh$4siajO6=4Q*@j9{137YZfIk zMKcmgS{zDD{vF-T)id36V1AI@n!duAB31RL$iuyVH_3Zda=rFfxOBrJk}!khsDVdR z@#zSau3-yg()G^|gr#=~5EWL>5kRq{SL1LEM&1}6XFI7&P?G#Qn2%VZ2je1;I9{F+ zrb37?XIEj@W=P~M4NdLIm*sZ%q~#Uqj3U}nTRj=g;?+MUxWu)>`5Qg^7#d| z{Tg#q+u?)Wd79X>`re|o-@i@%{_dAzdVz2_<*luOWi^PA_IDZ*o0SokNn%DNZ3 zx76N>a7;j|+`QkoFC`(0H158L^%vr)TwqYO?!b%~Rs-gL0+Bi!!zBo*$lmVzw#t<+ zDZhd(J@wl@DQ5nJmqz;*R%(0F2YvrhcHS_3+db*co2d~??O|s3(s)di+22(g_Drr% z=Uy#aZ+YoH^~V$Knc9tZw@GAf!~B@*SNI~(2F8ydEL__tIIfhv>+@;$6L!o+lWWD{ zk76BgdPz$EbZKK_NyR#J+{d^=!iRM^h4CYXZGWiD&N;Pbu-k*h?bp}O@{Nn601`s7 zhL8ptJd31Kiavgv0W(p|8EEOvA+5t^qWV(Rxaz%ogvhr7TjYhqrPL*Z=_Bf#<#!VB8k@hB_uou%HT@#!-Wb8~ZWmHQUCm?Oxl_=fYNW+D)hAb2q1^c3=?AX0e& zRy3wz)ls)-?KSjfX0$j>;0U-zz98nfNNJOq`-fj9y#$ILVt}ex`rJddK58ufOk9t) z2r~Vbx{Fjm^+$j5K+}bPD((#@w>*REkkFN;>FZRa@~^yvdHT{C&*J>7UtJD!P!afc zx1X~juArG)(D4Hiy09ElId`_aSWJS^hYaCH!_R)n#7;NmS69Ef&-n#7gRAaI;Bv_y zJ3k*Wtf8-eS7f}RAvZU9(6#~BV$t(`4JE2+?$UZ zxy7qr8h~VUxi&mP@Eh>l>;S#w{=w1o*o84eDSp$C2FOF-2nZ4rRT#5m>5OU{M%OKRq9qIUeYAU^r!{~2@ zg9CLq2u2;J+#py_`z!d3tAUobY43r70dySfw5z9njcz+=cZqxOh{5}K4xFS-w|{+i zKmS)dmQ3HZguaQa@|o=in+1aK^Cyh$7bpY>3mM`D(T5G)Ov^*#`8Qz>52Tc6<=vyC zT}eu>G&rwdo&+Ku@nmQ+SV3gKr*|Qjlb}Q|KW&@$UB7!$=kNYIGdonkrI)w2?@#ff ztdxCV64B5nO6qq`&gS|C+ftr^8%I(yQO4V=Db_Z-%@4Crnz>7A7kognDViEa1b6-O04C|(o+viJ$7Y(2^ z*mA9(DFGcuEFA5nj!SC)viyKP4I#TnUJa?xcTkP&_60#UD(!N3qQYMF9h6O13SA4Q|xmd=d8#Wn*2V_bT)oC!L}(Ye8L5B)Re^ zKHKUtnA=uXx_~2MT$|NJTlYWC)Oc^2XZtLlZ$R{6DcDGZMnmJs#ht;D!0u0Hj{WCp zb=0kL#jc>|fCb(V!1NRL&p(RQ_8iM0du&JFmtx^gk%U=&EAk`Mx*e+>Kbl14kR|z!4F{aXkj)+VVrV^x10w(br2i;xjmr5KhQ|dTlk3 zy#>+b?=&(Mw`PNx|C!ZCvflaUW8Bc_0+uL!@t1v<2Nr{q0uaR?hs}4=68c zYYP%#wSHT3v3#fz8GD~oKJ@|I*}Z{<(yOqs$q{*+Js^%H9MOfTs^}ISCE0F{}!r^s;Dws7TcJCe0s5e5A{3fCU0A0Bq&}2*CJb=y!xnOF*5!PL+Zy^!9iXx=; zXk(3B=-?9(1DexQK}2Pg!Q5qv(XIq%BrRD{7=8Pu<$D!WN3H$5Z0~(s5bJ05KJdKJ zUBBy8SC{)4cDFX;-iPk>eF68{sxnZwkntsU1L0a#b^Oz(<;zUETEDJEDuKiVt_5&X zfDoH9eXT*sAnkIK-N1FGH2vXOqlRhO2N+C2CbndYkEgA0hm>5|zog67Ku|y!kS392 zI-(e1f2~03A$Ps$LC5s_{I}~D;mLmv~L(tYbJwM=_lV%S4el7B6h+8W<{Kex<72Loz=&%;287|4Trvg{=ZMpU9p{Trjb`*42 z53ZN#xJurM03|ALm3Cj&XJ^|sNb?7X)+>$1Am{EEj7VjuaMIgy#a9Yyyx7RIGOh-; z&Nk26W7#u=PsQ4}sLrgq5%GvV0C&5RKXP5|`PULBV;vTCQ{;4=6HJ>EpEnLR-Q)@o zU4{4U-_7^-Ut#cmVP8J4DD?{rq(Oiu4y32}H$6wY^rB}6^PK!sRr5|4EsWrI6S7CO zEk4aVm;`2bV{~{?UpsrjY;XwP~0N=+%;1y`6;#KZz z{es0P0MX9aX?LwK{qcU|v?2d+W+_o^jLlx9p|G)dG7@d6ou~6o=?hrlpSqg?s0-1| z|CSavjw<2s^lVZslS2O0t!~Jd#>4T)fLs%37HXgA_^nOU05ApW^aP9D;OMtLvLGUC(enh@6%Eq+a61cv9_{p{TIQVy zFp?`oe8chM^1OdZdeKZRKIUyF&)vnwi`Q}8%>p@4|77O!2o;$kserhz^MWV5rpwTZ04Lpjf=iB zTJxnRDt3h~Mc>yDzAJReRnw2cv&G;XauUCV8aqzIxDxQ~CR=M6QVSp%2hgZEu9mb@ zOU8CCfVVYAHS~0#!UN@+LziIt--kmIdMe4{(TGk#iU~ri7=6kv%{9Y^|1Z|v6_Whg z+Q^Fo!hvLSb^}tPSR?gr!oU~R($WIQh*d8$n58LeMA87I-Z@#&EF7+Wcus4>3HwgU z5%`H1%TC#M>~stb!4@CVMv-%yJmj{89nRVsBYZ`G`pet*1)fb*pEbE%`Etb^9u^`A z1lAl_F7M&>B1Y;+^1y0oCx+-sei=wBTTV%bF0m>iQFO>LX@CEH%pQY5%5&&T5TVKT z_O`#1A}C9}7lP59v7OjAuY8%!tJ);$!mvF#*!tz55AJ(jP19aIYc829;^!wz?hMX9 zU6qwRRwqV5iE$CAJE=w19dIPpojSup*BB11r&ALIT0R|9gXp5#LaY%}qpOkdE++tZ zXBM#mc^p6b`dBa%$bxHH48kkuf#;s&eRc@8X&>7iA=l|cZf+wgDt>q%?7 zxNh`e3#nH#Fw3~OxMp+n3dhXeb^X8TP_s-Dfhho3l{TPmpYrp6L6htf5!oldswR@S z03BRbV`GXI_l>?BRsaArb#F!i_&2j33vO`1KZaHC?DfXA?Qr_~FFjuVkp(QO=98Ny zB8mSOZEqfqb=$QKlcEgKpiqcHA(<+f6N!|}Q7W00B9zP}VL}W^ueEq0)R@)EJK@L)3_Rmk z+b@3L3Qx?*_gEgIrL_s|KQQr%Hy*|_MiEr}VBxQkr`s%%i(pwqRqwBf6-z>4ZdT;> zdpls#n%3(4OfvV4JSEqi0@v?b&}AXkJoNr50RTaA%SG(FDdBfKzdX5B2$Y~*l3fM>$HwGsDXFPOwfES`hBI?axJD1pi=KrK4l!t_Ne=ITfdxL957Oy3n(e&-qJlJE!;emr3Xl}9r5aP zkzB}Yi~Co z3(oHy8Vq;)acQFOmCVBw9bMfm;$IHZdxGbLd^{<|;6WB*lSzb+&NHBq&#k(t)JF4;8_l&~6 zDW^G1e3hy+N1k;yW1ylS{L;7V4~PUUaFo``Irw;wGpUO}>Kg7hY9m3+{kGz-`KHooEugR{x)C#zOhJ^0vG-Cwyxd5~P(|B=tUHT>(TnyLUF+zSxQLj95&7e` zC$Wet-&4$kZr_XhfQC5i9pC5no_i54zvBXp`9m@z!L1SNt&ctZNcLt-|Bg(y?e*F^ z-OtChek;6jXKkw1ERLDW<#Ohxy(^#2&t%qCrR92gAxw^59%9a&;SW8g_pVlyMVF2* zuOa^zerwoVSw${Nprr?WB}Oc$R|C@iMQ46Tjp6meYnkLq!uF0P56PILpK}pi(A0$U ziM?nKg$!TcUW3{G5>&aQAb!DjJ$)A8A!It85ke6e&1D{Y(;LAz`SXatLktjoM8=Vl zHtWBgig*B|VvY4r=ZAmWetvHFmaGNXTK;PdnS*yUfaO-gZna49x}O=JI7!DU#yXaE zz3#O+g?#u6ZHChm$S&j?(9zN9be-u6VB1fNxlYje-}gtOYvbH6SELkfqM$V!Su@K6D~rltdk%r%qS z$xI4kSZ0Z)X49*7gAuu`Qq#u}1CMBE1iNyEo_uOsYKQ~KZz?oyFVV0r`sCBMSIjrT zB5!wl=$tzZ3CgZGNEPld7Ysq@v>Ll!#~U89Ol(@@f4Z6H z8j0nN++_eHiPu4#K~QU+W}n8!)2f*!*#*HGAI2dN>@xNiYXGN}@?tlq@v<2*!V){w zHLE_not~cN=qSj`+w8*Wr-)88Z9To2lJWmfuW$dM^vmr|*3QmSc!JZvX{>y2v$W$- z=x1G^BpU#c?1B!VdH%;abMhdFzT@aT)%xnieA?U;6m1F?Ik)Y~?E5)_j>4Ha^48qpOak6rjz~(Q_Vsty7g#+a*0mN5Wn0KoGjmg%sqw;OwsrdWv;`*cw!Nq4X!!8uYk9G+x7erEG7mbofP)-yg#kyDiBm0}TBi%l?5o zgEstvm1@GJF(eLp!BojOHd)!hlZC>7#LuFBr!F%rSH%Iw=v~b$dpkru=cU+}kAGkc zsOU`B4NgYsUljPC2k|p`M~LFiVJyf&84XoIH%4rsw8(7H0elS1xF%OC$i21KZ{HqH@Rz(jglt<00vOHvY(z;xpfy&Re6@>P*nY6nhDs}04J|9V*z_WP zqQ9Wyit$U|4H&?3zPGezNeC4{BLKEedmd$l|Qv{Yt9uTtIzZLR(os>>zC5>jf6(ZEJGuMlau0&c6a9q z@wj%Wloi=4vAig<717w>=H3vqsfIhgQuvpfEXVIR7`!m_VyGdSG3e&ZvWu*U$e$k_ zTjd8OHz|Zi2Lv2S)ObzD|ab$m@ue})fZiteEsKeun#uz{JQC)ZqE zc418HU7TD{QWB40iG45fmX2HA%=gbh;o&UZZVT4DCn6PBmX|OQmdD7*NOjxt@-j*M zBtE@)b4>EaPqnjWx4XHyF-~#Z+tZWkyz3M*`3kUvIM4E< zH>pLueEs^Ncm>EQC8NRJ$H7iFmKwV^=)9_)qSob0ql2~5;#g6C%Aw9{ONIp<*K~AeAu}a;mi#R z;`DxgezWuQY?x=UyzFtM^~AwK-3RhWn=5s1-|m!=>1s2Q77skCWyK}VrPvh~9euV} zL`6l#e!RP^W%~?sc2?F`0N3R6H+k;}v#(#jUMH3&b5`0-VXekil{NTASRT~FVC=fH zPK--2BeniEhr(JT)m^s`Bc^YsHAEZA7TZIW~!O0x5~j)Z{Gp-XEd6n(r_%L;^vo z@Fu8}^CwYYt< zt}Cw}-s(-k=Z2+M##lID%sqqelR^33_Fk-#Btj!1mKfPYW!4y}lNJ~qy*={a)pxNn z&THxES69~7`rNEkZ=HthZKY#2&t^(NWsVv3WRM1CTZyIbjm6mPnXn~8|Tf-=4Lbx!Faa%`6$is)P zfrbycFH58Sxb^yTaG4jXF_t<(nd^z|3#XoXp~cD}amlR7y-!Gl&fV^4|C+C zrK3|)c5mFcF>T3Z|4kQ%UlS7={CRg$(#L+74nJT@=nclrP2duH`_}l>ISv_*haNP) zvV)BiHZf60Q#9^TiC)LW(a_MYC=f!%Uvs!G+9o6Y%-TXf`b9us+%kufnjiA|4Qn>TL`wc5wW=L7lqB3}CL-Q!8#DX~&F z?)~~@6M4W|6{L_w(tbBON5v!tk-&Be3p1g<)Y;WFH*1`@VoCf291#t;DHgth`3Cb( zpNa|Z3wk%a(flJtqI!Myy0xplJr8K#)zvD~>cX|(np^*lPWKU#txss^=G&g08mZch z(gy?t=-l1iX=!QOFlq_=f_S*NZhifF;b%|9O0&ovFE3l1Kq9)MQb;&ZadGhgM+F8o zll8oK24BiurSN2pp_nHY5sXu(7vIO+%<IIjtWn-Mn`f}M%xS6*pNWttqQc^~Q8RKhlsV6Y&Tz7^)klb#&wdM0KV9x} z2=k#cAKv^(z=v@NIZ}^>-@dKcFB7vh&%lZ5oX5@!>%Xl^3}Eg2T`5yZZ9zj%`6Jih zgH&>e`MJU&vrP&tK3*Y-BRoy8cdXcqcgq;$Tj}&>)GoOXY}y~-@kt^ zap({wK)7GTmoLA$6!(N)tFeqgi0V%0O-e%{yjdLQd(J5c|Eu(xUZ_Gi1^$v+ylwXyly z{P+l?!#Qm4!>K1rzT@1N4}JOag;9DL$8o!yTeL)sQmKm_ z_4Txv5-%z$${%nECCXiVeA}c|c|ST$jhbft=URq~>HEo(scxf`4#3xKY-w3nv9dHy8`M}|&mShd z%I5m@LG0FJbZ`q(eTB&I7NhUNC2YA1ul6MCWuC*Rft-e2LAvRr&EMR7NK=G@+BQ5Y z>SK|uv1h-apx~RPrc7ZWMn*=2#g$6q%huM%^IeDDv70)BSA!<`Vc6M+3U_x{evhiE z(h?4k%3_dbp)q(}S64T6NdBO5JF?#Ky~*Sn3nA{=CtYqq*7Hd&ESZ7AGDKd3MQ7iNU0vtur9a`yD6N-F z?MAWJz=puvgYZ!e4FP6l)3&mK0lRH?*GMMT+wB zaNF9!nEzuyaO=7(i_{;1_q)RD*x7laX7Ae{vOuX*MFa?#fJ$IR$1FaoVSc&ep?`~&pG-KGVcrf7i z`V#&;Gmp~ev_C8!C0cB&J9UzajX&g>G*y?&85o!(5frye+WW$lY;0~`iy_rtuvA`M zZb`hix0iq{XolgHmGVS!1|q{)eX$X|_o}KYMu(qydE$g1;mfw@DA;@OO6LWLNCeC_ zWaxHcj|c04%Pa_kd_W)o3BY94p?kEDxm`k!KbE*T`J}3k!U=`c%7$mxZhr9apuifH zw;)A#e0*r!R~C9yPM#F{-NxxQdkar;!{*H|vGaWn^S1R1uNW3vD=R5M>ptHMAWpX1 z!ZO)xl|R-~5r^!GtO)a?gu3*^YLYx5_uzj1hUTSf_vE+uGZ6YzS)Z0OlNx)u`|ml2c&48w6)nNB;Fjh5;J~pV%2=PHQu2$fjw=F`f@m3 z;~K+NjVA{cHYIRrzIyp`^Ua$#MNHl>8P{^(N%0Xn_rkZdR4RU(C_59=sieHms zj}C_<1oMk?je1NTearkPG*l7UYR_)?)jGCp*|J^Mr7ceY(|M9#RaM=>9oL!Ludw$0 z{mq&3Z{HLt9(~PY?6d2R#aDm5sC>o3$mH^N!L5dUV`nyH91sZN)$(jK+m@%C_ib)y zB&|7;Dv-Po+YW;Bts0@wnvOByIH8$6o{|t4mca7%XPZjaQ2uE(yOHYNYR2VUVd@K z13sRe-FrbM4evzL>w2%dj>So&u}|x5*8B)D$fL<~LzV<@u>axX%}g_ zOs;`YEiBsxAh}(F|T+# zsO2hRKd94bG==9oHHb@9W@QOOML0WX2Qs%)Q1F?-yZ&$AUP25=`x7}k>v-UD+o`=n zG-S#@?pS^188l}u%#3FiNThuPB|Md?4f$Z3)MlgAa9asbQc{Xv>0|*Ag2m&+;lsDG zYc?wQN~&+PQ1FfXHu#D5>iBvSle7Ffy-rED)_;8F%d2%{Xm89!=XbxsqNByv$s4P9 zbDMI1d`XBoW4aJulVXhn640tutBM@HZ#nNWu|`8fgZScr(mUE7V?>h*QCSj7M$#L{ z#>P}s=7Kvrqh7DC`_^W%5`4A+$62*Lh(gngS5bz`F4j*KmmnS>1sj=-eYn*+0cwh` z|6l`^uKMzY)dP|oS!$G!m}uFamm0itvx0Al`XElR_EuMJSwiO<(;~{Re&TC-lDVbY ze!p+M7)Thx$14cZo>H^(B`>cKS zY7IbH$@L$EoQ4kZsmC@zn1}0%6HgT43f@83(9Dkx<;-(sSs;CNb$*z4#JaoCp?!uWF9EP^ zuU|KV4o2!?zP@X(^psmSzeCqM$)W%e#^@-%bLWn*(;o{Sk^Sz=F6aV2UU;Re$fkGI zR-v6vFy|X%upo)vx_oM6Z{3R~6Q=Y5^7&veVy<617TPS_~{EVQ8kavVTHHlT^ z2n@=gq(Gn)r}gz=DOl}!9naxXmJFd&IXOfrhlrqR8ij8b5*l^wQDtSKzyXV;joI1R z?cBZF7wUiyexL6A61)&7$!YR%O@FRf4kOF3@x>B8eb&%0J1_5LcX#)WdstwUgTqf& zE~Ab{C4cG^6Y#wmcJ>h4LVfn!+#H_C~_9>d4#}@!#bo%sZ?NK&A z?;kiWN#14tziKH0W{@iSheMYH~XObkP1T?n5Ff&+kFy$GW-?!aTsRMj5>s9D-oKoayPp+AB9 z`t|AAxv5aATuFIgAYmEaDCu12j(}sPvU;aZ#cLlP0r+UR(9zz`mTzzZbcF(78R&v# zJD$tk6Mj4qfZ95cVF+AOQB~~&{#A>X2wq%Vq4XFXzjLEgTwGi@E)%VK=P7rGSAE#&O>(0=-f;nk2ri0m2Pk|q-$Yapu^oprCo z#KaiVawvFIl5h0CW|;i_JM2!x-Me(CbwM7&dO)HyeGw8AG{Ida!{#nH_9H;>2Yjxo zqV#|_n`!&@v!ioc_8Mrn9d&5t+Ys{Lfz7pR{8KJOO)jT zJ~m}ObvdcfV#Isq<|kYM0?Kbu(a=w?^mDF!1%6|6o&O`!MkFN9)$ed2fb0?xktxt- zlBg|u1@b!X$DR&C=t1&Tx#{iK6+GC~d(f&SMLSFfXK(mJ5*-$qy?pyNy(Q7a^sK{f zfqUI$&L2}WcDmuriuQxhGZ#o=ksESy%)Z-nAl@L2-EnqNZ}^t{|4D`?k{;ZgZ?aBAdQ!ak zj~C!y$vvU>gHF`Q);0Hw8`Zqrgd`~ls<}a@Q5$}F@)^vdW6)2KTV&^lcVg4sAyUi0 zm;I&iDrX?ueo+ZGC^YsXAH48&1Vaf%xwZ;OAZ!SQjuZI$O0WN@{_-UPzW{3}17c!g z4ohWcXQ#AUwHH{w1;q7APZxkfen4UnOU-wH%RM^p7J(Z<3RD!pDoB!ppve0O(;}5B z*H)zd^JKu`%``l?;ENXA4LBbcuT5 z6I#ic3L)jV+)DX?D%_A^yy;mlj-9p&0No&+8kjizdcBe_^$>JD=66YacbFJ=iim7D zfBt-8OpmsAUc#ni3U!>w|HfTjb`833}tP z)eRzL6CS05OZVc=tK+W%w+AyZXnCecmpV=)WFPtaYlZot^dv0b?{#4aTDE&=G^@a( z?0M|(xK4$&D)H-#M(KwRgjnTzAB_|LxR<{72y*Y-`n4LzP1;Zj2WF(HP zVWYBAQqGHuPOAA4yC2C$j1GO)n!m`f=91kF?l*LnNYAzU4A)g*2?xe8V5 zlG4&#o8IbCT8*_6a!=Lc%y1OR;UIEZ>5Z#|c`-3O#J87H`e!BybMyQGm`Nq6D%w%O zchq#UE*F|)1jKI2Um*J|huF9jl>j2i-Nd_nT~mXhX84eveB}LY>FP9-rNCSX{uAe8 z))E+eLU``m7vK({%0bA91nIn9ue?^{7BQ%!{J3H3)>;_qjmB*7{p=vWgSLy`pFLEE z*(-%V70lHv+a zhA@X~end=+%$_}Rc-D@)$S0Y~6~0ap)CXGzO+-Y5qM{o$bs}QP@Ft7yZgz?%lS;k@r*OViBK=06jMq%niH&^p za&+X4k?zPbr7I{XSWQEdsGGiyp8gvKl#>x$DcWh*&g(&NhZ;2T`#04E>{H#fYgZQF z8Qx}CKk7fnjvcG)?A-1V5I~QUlf3ISSi~_kwSa3bkTzh9z_?DOe^|1x3V>$9_062R ze12jYT7Qmsbafi^;uLzXrkl90c73r0Wr)dt2dO&TV8*KIuGjT!$d; zf;NSpL0GV@UuY;NW$5^0ri5#F-DLIq#I^+0@$1*G@;KK}q0B)jm`}E6wpuY1r_oQ9_-OhW%wKRN`&_Qc!Fc?xVpPrwmyMe(9zoupga50h}Es3!uDGwpk5+I zqSz$r`25CrH%a`kNieanoF4q%*w8?FfBD1w@uS&hjch{a%hkYM!up7I1~x(vyQ8Dy zFL-QXzJ2@V<91#_e09ajvJ}ch)b`BrcuN-n+bHNcq*Q~0^AomPTJo(tqPVZL z`c8@;f=69-+T9X#l%7&W#VG9h+8mS`t+<9Rw>t%86L$WHUss{ zM+4bRv(zhG`(Cbdarw650$60ogSf-r)R++_S{On9ezSvq-K*74+_xr(w}NB)OG`_$ zh?@9j8>ccOEu(e!arL41cbHoHk-mybOSehUb1BM%hKKuRW@f&BH$FaoHP3EaRAC`w zaq+mf zN(Zlo-?#b+?FsSAyv6N*^VgjeDHG_Eus+ZM-EbswXCwe1i$msQZNe||zSADT%@lf7T=`g)U5Q8g`b?Ro#>kY+yg z+@-ED2{DJtdNfHB#D^edaAf-*?P0^i7C2;=$9~bz&dxHivl}LT2Ad!YPGMiUnkC1_ zNApi@=u8ZkY%}_JR6!K7^YfE{2Fbri&zaVib4)r9;^Hzpa~YkUJb9x1{U+z&G6KrP zFC^R1on2Yqbjb*$6{05S86yWo{E0S)GI6=5oZX|d^DK!A;Fo_PC{X@zYx<+$oh_v0 z`Mrg>j?)R;890X$aa(ZqcQ5P}6dZ1TOob@i%5D}xHi{#}vmCs#UCgY3P_^wcPN7Y5 zE73Q94;mR8YYEt{{rDM>o>1t^m+}qB3Kr<-RyLUhU<(FK3&JyTfGo;8?c)9B70z4p z+C{C?IM8Jk{l=AhR3_wPEV9ssjT;j#2f>jGwEYpaO|qE+(ndDAOATDWreC+WM`8}I z_L(S*=NOO(G&nSb+;M5(Y{DRtp$JwSnM%pX zuu}k+c`mhPNRG?lIE5k48;wFstW%9t(7r8esq4bUz%{xpguOtY!`$2)ZKfy9%yL(>{JjH&>bN4m?TfICR}k|G-3 z1~f_aqlAiA8tE*~)x5bjY$3pFgfu6xOWIeWj*ikZ**H#1M;A6U)e{Cl3tD{#q8)^B zQU;5U$?>*^IUx>N3;}KvoD%iOoX3tIPY)xNM+QHL8_CBic2n#i2VxDdB(Uqqj8d7_ z_yhC!;}ZI(Pyd1)a+61OwSvNtBVX{+C@}%wQ$emH#dw?*N}_JuPi&GlKeJMgonoqG?4rm%M%e8 zxrBx91A4uGrZ48UJZDZpYV0tI5rqgh~vy2i%6zr)jBo??XsV{xv@-3*2dvao_% zP%r>>92EcSFnih&_C(^?AXc7=rRk{2NPk&lBT2H~9i{i6%*=hTSeOGOG{nipfr@$d z@Z$R^Q+!RqwcU z6Kml;3x0TAb>3BDJp4~q<0QBn>h5pey`#PWnh!K%hYyZWLL+ZuBaElopXt6N5a%|( z2RdS6N{TOJ(>*mCfL6i|+`wB!!p~g%^(ji&=yp|cS63J8c&1(=-7vO*!iM5Htt#PX zJ9zLQloK@*lP8+_gJWZ7%?2KIBkCOiF-8{!ih!#~X({S}HRQftSh2P4O-)P~!OKaJ zccm*5@Mi*fF&nP)YaJ`#f@>KWhl+<{p)1nkoK#m=lPNHW8X4E&tG(#f(b8&8 zpu<#Blop#`9=ZE9ll zK;<1Uz7qBizret~xfs7;K}C-Wx6HllwCj5>Lm)aqo&! zdsI$`f@9aVi^Ycnh$g-(5PdKz=2}yo3CvT z=yoHh-wzI+sGKf)@j}9FQKGJ{?gchypFVSj>}f|8qXCUf>D!N(&Mho#yF8973x2|5 zsi|p-BgY1ySu@dJ%evnxv}zgD9(=tPN(#d?Ba3i+%k`Tx?{V7>IsMsGE^jp~?kA#e|gS+|RKyZk;OyYxp3 z-(Grjo74TAcC2$tfS*9e3Iz@?#LuwyxR@A2v)j)l;p=*zV|v_FD7*f3yly(mFv1c< zBe|ONP9JZ5%v^9(Ht?vYYLce6;rEfk<8GPx1{sH$i3g*&PDB~2rCE^dUUMChP%=E_ zq9Z@YL96lm&rF2uP2QOp;r&xW=>$u{3U>?I4D>RZ9Xob-z}9$eVcPn|ix>190L8Gx z!n8>2=g?T{U-qL~WnyNQ1Gr%2Cnh5k1G$;M18;v|cA_6r3zY|;DdqjRxRuK5xDv(o zBOB$G{)FU=Bk=6v;dzf6rF`!<%Ku5zaD>?5<&)~4=ZF*)7u)t$ukkG4#{hJ^2^7(i zHfB8=N}puCTY|wf{*c(R9lq;&Eu`Q;WM)=EY(v!M*}tC|7?}d zy9i~-eze68Mm9T4$j6!08fe?k#(+#^0!Ja_c46mfnBXjH+Omx)4IKheqK6}l6^&4E zivUu5*8G7X1pzqJqL2`g*6*M|MhtA7ozbaUPi4oFbchHBqZ$(%n?L^bBO$|!xc4Z5 z4YX??@FqPNxYS}GhCuzK>VZ&-3$Mpgi!Lsbhele{w<4Y9UH3KB>yI7JacW2(-fyJyhck3$aDE(ZT3 zaE#A-_KPSi&~L}M!R}bdM<{!>$Qt&k>3-N;-3DA9&JE;;3lY@Zd`g?28DKNdy5k`N z&2K39tn~e&Vq(TX!h)x>Jdjju=O#@_u=|t|^`P@6^oP0m@0rABh99ZHcR++hz|lR{ zM05o~CH~Uq=gNqe17$mxlr|~*;Yuh8Z*c7D8X8_UH3b16?O`^j0AuIl=l2J!wS#{W zMK!}T_Apf?sF|eKN9*ay0R%i^XWA}dBd?$RTjSa3?Ax%J<-)%I{A}@UJbP4tjS<5j zj3%jyC@LuhLll9-t=N4<79pIBDd6JeO|F(Wd-g1;RQme+Uqo91Y^A?2I`$W4lv4f0 zRw&+(fkVX40oc|zHr9aX4_D;9Dq9d%A{!ys*@EuDV)rH6mzYv)Rc#=z8|u2!>#Fx3KVvZB|~M7HA=pgNLkN#+j@dADHd0UG0!JzNw&vQS1yng*!6g|3{zlYaxvE74>(ladf(wVxj z$FFLBPfv3loJj@+%MY;MIzt_v^9%L^ez?ooPT!yv+{q|!!<1b$R!N8D}bxYXi)#>(=zGb+aHfa{%T z9U4Pmq1uWV2Ar~j!lWv5WXh&p|8mgLT`KW@lf&ta{wrBq6k5*D-=v>PAEwplfXH$H z_Z`QaKa3XTAz~WF!S%a$ZxF?T*Xx@+f`S-v8ULYTkSGTra#1hXUAu;=whJ`wR@RGq zP)4kua&5+Ntt7&!KC6Z&;}|Bsx7f|kzv=>}z2GWu#4m>f_wu*lw4W#=kir;giA7zL zSkWr`!Dbvlt(M*l1^!da4(eQA3C}`Xh5O3RLc7UtDtM24>YoBR#Sj!;!+ltvDe&E? zMVC|X&a5ZC4ck}gjiB*$2^0$AJLX@lMio!-$6r0M`oo6@ct2G4qoUrzC{03+JBCxY zm{}q!o>;TKk z7;+82#G|IAps)&|1~KR!r`$VS5z^xUr;mh`)HbOX{K)exIB&0T!$F&9gL=xG52EEH z)$0xaRW$t)#z;v;%_0?QHGnEOw4C(ClAPzt)>BmqYmY$4ffiiV$e{92`~q~WXHWJh z9(h`^Li9;SMQh=aZ{Vt|s20{wBXCE^x=JEhnC2=*+W}oAoKpS~5tdtC-ecSE z4+u}ev~goKf!}NNjw3ylC9#8TP*S!ADUjHM5AxZh9PwS=~bVQ}od26+_q<5GYcu(fUhVy_0Y zK^KR|$1(zYX?$iVJIo2F0lwfVQrFq+t2fZs{hS?X_Knnwo z*~rPM4p$%`oZ~Frk{pZ$vkMDar%qL3ve9V(n04#c0l?U;EV~XAK_NgOCFY_x4GkvH zR`AIuzGqfE?6{6!;Yq`ojAV=ylw;d}6m}$op~3u3IwAM(%M;^KVIdzc@6lBGkM5sK z?MJGybu%kJf1v9|4-bmEsLf_MOMNBm7HI$xY$NDhw& z_0^9`bvu3EOGcgvWWK1zcZxO)BUJpslsD#nInOy(i0JZ)bQC(+?08f8h*biZU(8 z5rcP~ZUN)-6uGqesg$vy(8$PoV5~aS`Ef-hAc7=4C?T$nRT;g_>hwZTaJV?0%$~KF zKeWLs<;qd^f>iZb2pl?>N)Z6~`1sJuK-tx)0P0C_)Z7G`2O2=3XUVKYP^NlF9>`-C z5usJrs7!DcqLkc+?_cl1AtzK?g(V76az)$8GvU`56h+!0KY$g<>#ge@9DI#CgHnq& zKW}tQj4gOqVa(O?IdAxcH8nMVO--$-?CFVvh{LpLQw{o&pKkyDZzl!`Ph_A&Zj-Dr zs#naf7k2ztk4QqE989Ly$GcBhSnQ5ppp*k!PFiL1UxlZ)m!%{n*`O@q#{yN8R-J0! zlq|r-bvX3^vUdU?DFt=U6s`v_TH-SMyqgw7BIzeDVif7O|% zbS0DPyZeLq4<393<4#!GJ%KMbz>{-vVhAorKj@lDxCrJjqk!yqMcrTPUaM8U3*@5N z*Br)efGE)M-eT_tL@dl+p;rVY0`*m(5pRZ!P@K@=G)YPFu z4#y;ieH8UU@1QDxFlmj_d_bVK#r)`54a0}{Pd)x}%qvt-iKayP^8-?9Qs1*2qRFA5 zCuwm9wZ*4rtjH&Qcp%iZ56{Y@$l?jp5`RqQ3l^wC%|(zw6ve9pK8um*Y%G#&&vp_#T9t`llkZJgXtS$g~N3gEc zS&l#FHeh%Cg)(B1^NbK8mGcF)upgd}t(G)yrcEBY>Fg}vCnm2?pDa0V#Kp#)DxV%_ z|9fj4<9V)^HG9r^@w#&=I*2+=KI82yca4JYj6eOr;J0t^Uj-Uu9B{;51NFK0eIp~} zn%33VbBl{_#wQ^@z>_D}Q=s8QXOPR8$#u;MB~Ulr!Sb9zTBrLcoQmr4+W*t3LcO5+ ze7!k2xyg=+9SbM(Hd6HlYC2!#2|c2iXPy z3Yt?^``_l^f$2}=6p^#6Drb^wqEKYg^SEN4YWJCU@7}>S#JY=V%I+!i=L99Xq`Qw%6iZsq${d}y#$T*rkCwJY_bsyIK(85rt z`i~T&AidFbvI~;hVjxp%^>7^=Wm#671#>vZ8i?)~7RfN|##CHdYWHVY!?V_J6CZsV z{q5VgB^-b4z(X;`#~^NhXpWnjb-Z<^lv_PRTaj6H!`xq#78UKT(YpKg-8&(%!+M+2 zHXf;)OXT#=4uEPU?S$}^rZHb(dW!nV$|Vez%3mhYKoixcuRw3hB1O+1{W8Kznp z*7^LoEK6FUT#Bl@c5E7~TE3CsFdy|$TJ_`%cAtVJjSojplmK&l1Rl zTTeD%$RE`EK>DKK@;`U(9CZ++<1nk5?(SF=5g(#+(R6Yc)kV<5Zi*A{1O(MCck4=KaLUtr_^pyF8h<#W#;s`F=5$7kk5p4rD-g98xe4iWR$)aUa8 z07V&?5Fb! zK?vw)ORr~W9yua~q5|d*R>@G6IHw>yQ`bCcij{c_5hU~n^1sbko5(;#T3fk~7&ZQCLrT~FPiRAR)kpq!wV@>M|I&sYM($j9fmopMZDL4M7E}my zh3Nym0JWksi`Tn_~6fwWS1Lf!M&tLchb3iw4-mC~& z6sJ`2#;Z^Hag0jW8c0h+S`i*1n$_kF9`ieZYxVS zhfc`k`HSQuNWpZuvg*$sU4ltO%L9W@k4s{WJbDod)yK6R|RB zpqd+?z^NuxT&9QPGBGM^MA7Ol~wT?mz$o(thI|C1r1*qRZ2LC}2g*lP%CL3+gZ*bgVw zv%o^$G<}eA$igYDqqISR|ATcQWAf(0)OTeyHTtU+O9ueF65Lmoi2*jA)2YRI5fkZ> zcmqFQje`>cg&WW%(3lkaPTYB=3|#_%Ah%Vc@KFUIs&Dm5-_<>#!i;Ajq<(r6p7B?B zpv`bGP+SM6j-}NTWS4Og2gZMa`ITUaeM3XFs5~${S917MMFwRg0-TYFo)BBnq~wb( zp`>zk9-Y76J~Xrp?K5FZ(RY~kqY1;|`~+(;FhxOI9ju1hdeao2W7vo+f@?lT?yT1o-|H60y3=+Br;Ot}{feNEAjYe{2CGh&14 zf9w|(lpwznF0)w^#Ld87r`|OWcOxL5MQf#OLxZ6d4ZT_?xbw{qaucQ z7sm4+U2FW-E`3TRzY1U4rG%=UKJo*?A)kOUtLeeVD~QAe8}VoU)A>v{fcR( zC)BKYq{6=GKbl$A7vS5hATD@vCNtPL)^tqRs?9xs-6L4MWoGZFKacF|d-CD5D)Ftc zeXV9h?W}Iu97lJeBHjbGKrN~kYSw~1e=SR+GC-=i_Hq~OYhsA= zadQuCkaO?vkU!SnD_8eCOp29qnyUy{NEnkF8#LqBd^)$M;|3jVvAtLv`$}Bd!um_2 z^EDL9w*~bmnDvd;@^7?Z^xmdqn^=^g`+c@mXXe?N4Kv*a`JeP>($0KO=}R+Uo;jL9 zw?@hPn49~PV%~<;t5{#e4NcqxUn?6jGyEAferRa^(&hPu^Sh2G>0e!R7gP%rd3;N1 z@odJ99O0_0vKtz&R95?0bJ>4!l9@j}*ae`fJlz8)LfZ02~Lm(T7Nbf1@9@3H^EgCv&xmDmplWM8`0 z*~>X!Ew6fCI)35G#ejC643WHh0u7U_#*JP>Uu3->np*dsucnn-vE>}USg}J?l0)dz z7GLq8rs)Ddd&50ZtA@|iuzn1ZtDbrk_v@$KV4SjHzmXP&o6y7Ap#i?|s4S01zQ=lm z<=@J_8VYLS+Q3@!=8ZW@$aCYRLH*`dcMEQd$urjEn(VRp^HZv~AS7%J#n<_YxX_30 zXU<0sPBuvU``4uUj8jr5|19_Pe6z~Bz9V^CY(x~xPOd%rN!F#O&wTBUYLdVX1GwQ0IT`F(G?Zb;ZGPnYGyo3d^`@VPWolRH5=h|=KGZrvzb zO$zS%<0fKjm2+uN9M5BorgUP7wR{`sF8BC$qD(+wzy-ZF`UPj*>NiU>%_(Xk+74TK zJNqr@yXHMx#YXTO*bH^n^Rk9AT*rU%h~DtTVG0jwZ?%v2ZX#{ z$G)PVcto>6dEX)1ZNsJ@xBbx?jbAptq7Cm;Qd_lLG_@stpLFf#m5l|1=MJ#+G_xBX z?5h0bv2nNIGm2QHTH|+d>Ne98G)A1}?vqswn}V`_&tEdqe_B61tlPL@>e0E45B)L( ze`%fgBD+^DVB(wWcHQW^FSDIBA~<}?z1&$(%*R)pyhmy|s|4dV1O$4_?R^`soqhYX z+fP<*xm`O_)HDPy5BMFZI9Jo3B7uX?PGwahf7$d_@WM~-GF`PplS~~Yx|Mho;n&AD zoPB1xbzb0|jIqs8r%Qu=%0H)#jAApc8hKjX4^>?_Eq0sP${dTj+{?t{%rp&FKW`ls*tb(sNM+!9+h)<4O!gNO zBE15GF)p`1$8FT8Po@}C8f23*G+_@h0Ev(?Yhu`eWwppnDXyKx|=-=yb ze7BD|#bBHpw@dk!SU3Lz1J)Wft!xWd%QTAFd-QBQiv2_sKAn5zv(lb;y6mW;;!QfL zygwt=nM;a_CH^`Vht#g(DU9VV54E`eP zXRl%NrO(3f-Ij~T>AoEl^Ue<5pcW8#s;zT1=caO3MSk3jIpwt5WBW`0R_D6TFt@jdn{8*|%Ex=>N zzvV%arV+h-@e`BOcCm8?g9ocR+7wUhkMs4VUri;>I`@Pkrz-oZMd=|$MW@5p*S`-G z^7fX0bX#l(;~jJTDQ;d$y;%1K7o{~KwknPrVm#cWt|XPHM|$~Z-!_{QmX2Tj^Tj=- zz>S|$G^*LmIZQjdLXUCo|FzrS^G5f@uI=dOF@uG45;(G{@~uhqK_LMt`W_ z8}D!J?*7^?B>dL=&Wd$lWx4M`md}+8+;oF6CXSO)gEh6YnW}F`Lj@lsS(nX+QYas% zOEP6GGNlwA5HBP1L6x{pcS{&^q8`K`xW1avmbwb~zz8y$7MuxOakoEE*8 zm($I6cy?EV#4?K}#m-f#-_-j3@`iEF#eeOl4eDE?(JaU*sb?#%!>94Ez+v&+W&_8L z_!mcvHt)6Y=a9X(dnkT;?2^;On!b<+*#$@R^L`1fm(vrle||Y=oWCPIkC9HxxMiQ= z=BeXbmGI27>aTKl3Ryhd_nU!fL-4z|$0;M9DJXnu^z9P&^A+DII>}mH)3oZ%wxNwD znp?lpUno2gsQPe~+>aN5=gKeUWm@?3c{PwT5|t@yR5S31|LW7M;&rbN+SmTvmg%K` zSdMp>QQu>l)7$&}jAy!gXUkHeCFv8+7S31Okq|U_U}HGTHm=1w8a0{ewI3rxHJ#5~ z+E?yzf=jG{PKe5Q=hx<#8?yt8cJ`WUUw6OeP57R?jpg*)H8rCp+;PDhI4Xi_{OyAI zemfvA zPH`a*Zh};d2s+yR#vqJlgT_&R*TCuy7ya+IRTM*mExScfNvLyqwOtdl88UuEU3(;b z;luw!)?0^VwLM|O4=RX&AR!%s3L;2INQ06hAV{ZlNOzaClqeu2-Q7q_E8Qt2BHbzZ z&7e~m{Q~{bYR&P0e8)9teP3hsFwC3~*ZL!om54~Sh&7rXge*Q> zS;lV*l@q?R@&R^3L(}O?ea#p?`WKN^0)bcHgQM^5pX%rp5K9IpcnK)vdm(`m-@l-3 z8q?56Z=Rcb)<ZqsKDx-}Exf4xJDtpkT~TL{WQ8 znq9{w$p(QZs2dcgdhXC%wS#Qj{E7GO17|PV2q(;iv1OW)@#n--AtQ$1OrKvY_(OY% z{>HKcR<5gDzu^SI#f_Mxxtj#q1GQ!BoEN`7UO~)_!_T@rqfC8%PYaEgFs|Y67D0|b zm2sdAAzkt!M?fp#7Ve@!L`2^$N)JMWZ*0U(KY{B;UX%ewfN^^J`H9vXS;9R$Vq#)} z;mVfUTcA-%1+rzroD%uUMU)!6{S85sCL@10=uvditb6fi37)Sk~>EoD%yp)q9yB?wSl?%aCwLUy;~o@E#4#L^wO^Oz$*Dk^T6$h7e)4x_ ze`G)^vJw>H=D)pNhA3C|GhA*WNnT{_vt#A@xCRiDfX7)NawotH7=sog*B&&bEFj&= zSFgf`6&ifT5Cm|B#8?h5TAUjvM{oLb5s};vm)|~2>4h!&!366%Wd_YLa&wb_t-h$J z0}0*4WZ@5>6n1tN#LG>`umR%|26|!uDs=-zXkfTN9AiKOgjP^pu!7_%bp0c|ArLD( z7bWhe6YF{^ykS*#y`4V7Y3aE79&}{&if$=eKiOTx1mW4oH-CW4D62QG2K|-W$^H$f z?gspT1vC@Ipy>jU(-knB2dbs_03!5(uQ4%8`n&g>9%CRk0%EsS6dksEg5?rf5qW$H zH#5>M|L5CDInA;+DsM%gxSSoc0-#?pjYacV2<-fAczF2e;p=~{eP6v36T7XX=kMgk zMdDL`DnvDcHfG=KkdngGHzT<~=f5(Y`sdM89XkGV)uz90qd=O+dlwL(W#9 zO{j$aji6RCnuz;w>B(|uiagth13%eKLkBkf9{CLKB8cU?B zn~IBTeHFYxvy?GbKWxt@B4Pr; z&cyV0PO857lm!OHHy2;sE$ROyh`ng=-=vocl}s}7otagFn5Y>M3ag;jIVUwxwI@4M z_)O0Uz6f?6t#gH{l$2c<`2a49^SsB;cR=zq&h3RW|JML2%M z&_u@zzJK*YfJPj8@2_1Dhy_)W3H=?>i(f=UU@|;JarEy(+|Wu?2zM9vLttB_&+6mP zIGM0>$=?%v-PyvXDd1^{%J9!XFYa#j;*tE3V!qfmLN2KRZI%yPH9#2<@?w77&h1xm z{ySgJi9eklohY@nVSt%QzO+C!dWQv;@o&i^v%uqm@m!D{s|dEx{k0v*N%%g3y#8No zN^5NYrXiB-Rl_A(#jSihUFamnv*{P>kIHqAxycctYL?-p^&C*1G8 z#UcdJld~1AAf2&#Cmh*KKp-$g!Y_f$6sYVGAs9=v3;{zF}0%2;<65BQcj6A zu0=tvjY!}Ac z-I9+_H6)Bl8DM}|0o15QHoM=iA*S=5>HXWUEBtLcuT)f{1d#K+A}Ea2OR%DQoAlqp zN)*A8G>cxln$lfzB{Wc?kpxDcrQ%1M#Ht?u&%h(JKAi6|o%-;=R!NM1&c=(h&lS3$ z)~PwLzS&-7EwzpI@Biju9D|I7l~hP6JN=`*$n5l>b@i%FTZ(;=Fm~ndY~E z;{Ry@hJK;Mfs-4pZM}snce48irZ`^F_}@O2U{25H)O#Y`^WO0?LZa^P+wY(m%|1{{ zSv2%&|My}$%Df&MLgY)QTjvTmLx?fqHjsBgIY0h zai6G8h>N5fVD&zZj`t+{Z=pZmqxzQkRAv)t3F&0S2`hyEOfp>_JW^nrOr3E*9-1+@ zDzKxY|NRd5!l(C22@Hp6HnfqyM}gIAhmVZ7A$;QbJ6^I$3v6$&VmS*vtIS%iDcZk2 zGD>B=^*M?ifzkXunoi^|k^Q$O49JrW;$Ee$f|UJYSe6GytXxCx|EA-?7&2@L{;Xo2 zNr#+^MJzO<6YqZxV3D-#4Vyp93DP@67{c#R{r5Y{#gkH(tguT4vHslS=A&A@{@+$x z0FQyl=VZHv+#aRkTHZZ#Ql9??mP&pXPt}H2`f4jUz6Yi-8Fc^s(p?pE!*S%ha{`)T zFLeKTO49pD1YUa8!~)3q$Y+kL}^0Kb&CIQpImxgz&k=DLfCO<|Ae6EkVnTw`M^GrI)PVjoV5YeB8S z)9mz7NK_WQA(#eDL`G%2ut?+@aRLct7`Qdk`K_&@h)aCj2n%_zL<8K6fZN6*k;<%G zY*H}45_dsW!?EiLtF4Jl-J(QANRam9eA9=m#o!8JsV`~FffwnIhTE;xZNo)=-t-zV zOs9mwMk=##v6($vjD5MdiySPhrrf8ZX%Q$ChoUeP#H$>FS2+sDo;Eh6R_YDd2q+1n zJtB+09wZVCZWIC*)pnRpEDCs0hebU2k91ptmNKYcg&WICSeN)ZZ$g?Njri%3E3j7{vt#w{V*gvzd&dscU#)!Dk*6yO2AYvG=HK-hd=C9ly%ipcLLyNy z9mxlV?yIuy8xv!!g)SSW3r{`?gD1EA-Gz3@rq#aNAt-9SNZg8$m-Sn+Mhkr5{%xPK zI{NADZsAwhMYDC^?XDWV{QPxrkzr@bKXj#V@1m#6Zp(G&=l!})4^mSM=FugfE^#Yz(NY=0~IV!OlJ=lJXon_-{2mtxna z^wTe(27t1S?7F1*CwF}>i&QJfZ(douibzeQ1b)kSrj8qF zNZ&kUL3`t`@DLTD!)@?cw}K?kU4jVdS?oT$IbBsUS<+nbH{vi=cxhW*R))WdIxOwz zqsXBAEb3uY*>Fs=A4Y0^6=QiEn=R=Dm(?v~F%$>lD-iX57Ex@?&#bqauA0r3;78NE zICI}2N6fV*(Xo2Y>uOZH+`O@~V`b|o9B!dGP+&?#OhS^P+0o18_A9%%&w+yXDxy7{ zB$RaIe4s&|2r*k@E`xEi<%ct-HkiPidND z4n8t|LvppMwFhVMc%+%TdV(JB+78H`SYI@YVvz_)s%SO1{ZUx+faHfEnyLMBpl9*# zPq(1}sAIWg;ZBsKT&zbqOZF*HRKLpzCj8pkdJQyTqFGFuCAL*&jL{}3ALr-3mJEVvNH~K307W8EJ14YQ zO7GI&8j2^s8X8z0)JipQDe*6_;R3aj){*ou@eO2a}KSj;5a)!k1`yO z4A3X(sdNTO!Vk-QN;sKe`|pN(47$RR`k;!HD{bG{t((m}M4zLmr{Ofi+DH! z0d4HsVjFu?-Lsei-*u`jPRzJ_YIpQ%BD@3y51)ZmSS|Hx`bx*A#I{3n8G+~Q6+J2l z-`o(P82`Q2#Kw&6F&1*&Y%qP;Is==0jiBZbJ^nEXU}8>(jChJ}xh>#tb;mv!6Oz9b z4hR>*IH+~03x3!9Ugs_XVZSykw)`t-d2C4>@ip~+m(|LkK`15i42q~})unS7y61zO z9~)A5cnCZk(O+n8x;}Zq3*NymBLkf(RWMls*K`;&J6Lt7MVlTkr@kkpMeJwKRMod6 zLBZd>(TZ`Q2( zRAlw{Z?vS&#foV{q&xSqm~npprn@ZiQki^D3byL_I5E_)dm~f$NzK10JlXMKhd^G> z1LlaA{!PIeG=tYXvWWfvFI4t^PK7x>KE6hslUx-o)*a-o4S{_C>xJ<0T$fL5d44TW zLY_Dwf(I-2Z-5p-{W08}7V{PtJz`OMz4^JwMB7}*aNFOLP6Fp!2WN2Lm+uyFkxLMX zq~_~diK#aI`@4XD+smkeL=FQ+CZUPd`ylTzR$r#nXEakX*ZJ2beWk|Jg?HgJ5Z|ES zcR$1$wV$p}H&VTB zaFbJO&|9(~U{qnDi<3yVXYhQ^%hx4M`$tMPGvqqJrs*RN%U2z%@E&N@IYm=Zk&y+j zuo*4vEDTd)EMnXDNyoh(SQ9Xjd;kGi$@!5qm&dO=jH0O;rbGr*Knf{zfIUCHi_;5m z^iG1L>W3Ax_;xWdDlLez?K=#de8FtSki!0qRx^l%vd*<;)gU)Ff>^{*K(NA9$(){4RN6hWQ2;Tdl+1_AA z7xHA`tLsGmsQoI(*M{@!!#qHiRj{}X_vJ)8u8dNI#-nDPegVa2+ND?1gV#Bv>#c>^ zzm>0+{f0pE)rVpk5P5l!a$Td;TGUxuep`AwPkXz6{^9Iwp`OwH>a?;+v)0(HVG}vxaBq-jLepwEd(vaCFkSg@OZm^zuhD`j-mIu-6BrC4*heFIjFX!Fv2&EXn{3HI0rN-KtqASLt3tkp@a!dHsj3H(GlLq@6PM$i(|Rr{>< z`+La@E{C&gXQm^5;}!QN%eQ>1wr1%0IrC;qK0a%id!5Hbo-jS9*noF(NELXrC75k* z_D+HO2?e(cRs+Wy)e60?{+>#S9qWvz zQ~2|bSwAh8Ag7|S+NW(G(%1e>3-5O_2R7yioK%CCczYk)i)MjnK(q>V*`jaJ{sus z!WZ|aTi=RiR`uQBb@&NCzc48{X1$TLhW?okH=K%JY`L6dd!Nx~i`VfAg3n|3S`>q# z$dU|&wuOcF9uZTrdbrkjozCa}%5J;OVO-naJsrP-7W~H89fA*3izEN7AY zLkzn$c|PN#ow+7qsU(i;Q1C@8s6^NvN+EcI?&W8(<@6mWQ0jmsyXA2)g=%GZly{e* zZ#IeUWr}@mnDOKnT(paF@~zZV7H3If0ndvNgJ2@VoKW5>3$e7!CUmU)01tPMYshdE zcXPJbn(fE5Xr+q41xDNfd8^W3iICme4{pNK<~4pyVz>@o4`+B0wcj7Mtt znG$$!%F7Qi@(bF;)_=MU{by2lRgzC{ki*;9YkB=2l z5%XpDAa~6$#VI$(f2+k`qqk9GzdTsMTll)#mqs+d?8heE%cP&DR4%D|jufmW&0P2H z-J4sj@PvArs#~kbeU3kfQFvct=RPa$l*9Tn*&)I#WR6=&uxViJ7(thQprG&B}E zzt^jg@fmXcPy`Qro(tfIByo|Xc~AyKb?JK>J2dFMu5n|`YC-U5Oz-;y5UI9$j{z0kafxv-nl+rLxPGyfItLNw4s|!QHqCA3d56|YXlVYXut>%cakm4 z>pafU$_)GPo6Gu(NwSG#iGm5cQ4w&Ghqp4nE;inIg+<;^1=0S~l2lO?gp4k$l$1i( zd7x(aCFi`mVaV!Q!JD?%v0k+9U-JaCkI!2%>~_QPaogN zRwqmONY@!gpNx%7#qa;Q_GoVRk1Y$^M^xHRMH)>r^{2kuS@seP84hT}1)<;p=c^9L z6tVjzt4w{K%V+-l+9Zr_!IX#gqsEVI#2835*5_6|= zq5o`^xi~o4vi-Af28UYFAX<1TQ5z;9CGoXElh-$yj(1Aw;5;rNAtc2IEm`q}>Y^Sj z)I%#|QmcO}y$d;R? zg22IQf7}{&;D<$r*)O;#kmJSyQeA&e z|1_7Gi9$Kmb%Rc)Y&)}eyAV*!SFZr6%2jMxwLM9|q(QvFYu^NI5a#E!lQQ(aFWWmh z*u2fjxxx5I)WqZZ`%S=D{V-y;x7S~4A*Ex1flVYPTA9m_9!q%?`~Q zyJ$M8$csXoY;;@1xUx2e4+2z&r*8}lV&6FQWJ;6LPg{(ZvnC3-`hz2a+l^- zLMnrSL>J*Pu(lw7kIV46hJaiOiDL0OY&MUWUe4`&qyx0cB=-Pr`Ve}itDDPN{$_&w zQlrtkFG=vO0QJ++UV@Y`-DLD{H9v1NYk^1nfSFJAK7-_iyL&GEw1d4hjIC5s$Udny zjw3g#8mBF|1=r9wPV%q2){bffs1Pr; z`vin52vq8d2GeBg+~KsCq+y);VuJZL{z;eJtAJTfGZApEbDPxOpVKfQ7Y&3|2$~zB zAR-^F`6)K$H}xQ3&r__pr}CJrfo0KzdVOFR?RiR*4)tVCh&D>ta=m2n+( zl@+oXG3ggKUM-Ff%eA)%)3<(ba=GHQO=^7N_Vff;+P5MHnqpStQbt zg)1%Ly~#v$Y%IOQ*0?`((gY=Tb1S|403;v@TrRT52InJ!3 zbWLVF4pwjfT=)sdth{|!>7Ol!PV<~R#V+mgwQ-VB(R{fwG5c`>2LEpoizQRP$^tV- z&|udsFB7{xKe>{lfT6Cw7`p?#g(EE*0m^{7ZtbPz)bcY^o6=YP*}0KygmE#y@Y~s4 z&Q~is`!oSX(Kd)WloA;o?L_gbj;(&>MWb%$?|W>iM}Lz<01rZuroJ@)mNF@lKn$Yx zL9l|~-LKzJyoRV}V7_*1XLW?3&ix1*X~-t>S^CE@0Nv?q_u~?CyFGZLa1>Axb(=}6 zA;d%QCd@1!0yoo7Ml8md@OQ6zpqya1k9rUu@!p;UHFQz=XIAx}{1A7=&O_wVIvx~! ziaADQ)~XwJA{#QxswTn1!}ptlkmpv35%b~JrLajo^YiDVu_>HsN2Na&=w9B!-@}!s zmG;WWSS`C|Scwc#pofAmNJ;#rejAoP=XmVGznB6g11OSf64a=OI;Wji*@&LNhzQ)u z^M)Jp&sw&Jl2ZU$40u_Q8^db;u+zoW;N&>+6(!~!*Pg|`7fMqbN~za43odV$E%l0@ z%4llq>b?b^pyx79K=A0*wVfL`&`pL=kkJnWe)GTXiFsgR?w^(Pc_#H)Dx9w)WL+A{ zb}3u|w<>=#josALvm@Ww@W4Xv>fO6{k4N(FmNS&;$t$ZRaU&#)ylMN0(x(XWdd8(c zK3D=U`oWftl^FN^q3v#Tv1j)K;EZ@j@aXL(zh`Uaqee{4N9G%5L-`?2d%vY~gOeaT z$aJ0>9VMiRKnK7pr}E%;;}m^WMj@QEw}M2D?WbM3b5 z0HK$-_6c;y5ate7FtAdy`iN%~XbEYKPZDZBh9HeM0RP|$i-7u$d>?{@c_%;QvXZV^j zlSz8PyV9Xeh%aOtwGg_xx>gXagix|k>a|OM9Tdg1I!{`2+TNzFw3zV1D=ci*6L9O7 zl6^n2H7JOm#9&BmDaz5W^ z{HBgtCDewoSYkDRCy`N_>-#Y3;m>aadXm#>GKoB)I8>?f_9>FwdDDP@e*OL&D_*xv z+rkjdlKF0yx^;{zfi1d}nO(J`fd z#g?s%eM+`4{|N@c0|ch6Erhw&Jfaz$IYUN~7Gs5qS6?Ra3v0OXNk%=)*)K}3HN1+W zn8Yi6`XLfLun6_FEBd$P#pS!#voYZ5c4o8KWSkbwkbL&%=>1-J)7I{xH2DN^X1%Rl zv*zmRtOLm)GIXZQ9FS%%IHe#b-~P2CpK;JU6l?ub6Yl(epgc;p)Z8LpFAgt^HC&FJ zVEq;w7ngHR5|O8wht~VL4&BwYR>9oHN`n8pn9RyRJz0AgWe`vjbKzH48Vhp=f1PqX zYG@eIhT-Rp6=wW#QHzPstCxm*!-sQKub!VAis}E_v#Z51JaCnh-yjSUK{pw}gZ>mv z)3rwkM9F1^;?AG2FZK*0OZ0iAClq9-f7lpBqn}x!>7Ug{jFx2F=Pi1w6n>xgH2nu% zgp=^SQV|djUC6zR3?BFU_-z}&>x9fhvv>rH-L{b3>fp`m*p$y8);-RFSWvwYm)e{+ z*>a0&=c2_`DiO~g&c94jZSJ#XQ7|OzgSC+sfai)$y0&6?Pt|XaFGsW>UFv}6S8aC7 z(QC?uS}k>`!P|O8l+B_AS?mAP0>p?@X1oBJqd>)vr^589!k6MsHs!p_#C= zW=ZzSFAjjIG&xyeiF=7GoR6DNZpO=gvC@fzR<0SR@th{U1`JBNd(j2RB$mzda~rd% zr{d}OARFXxEP-i->n5$v zm%C1%+~gwip!7btqHSap5D-qOvs5^}y!+YgaR|m@7f9lC+Vi=IpBNHQ3VOV~JlHJS zJ!N52Jr66;%%lC?t?orp>yTzGD~!yd2p_3t{~Z~tI^O14hB1NFQ*eZA(yydE?zXGKqTm#TyyQAGdDE@vWZgNWha z$BKuh*p9P~!t>AkSPb{kbw-~GapF(y-VbJRopCdpsJY3>*@m=!EV9QEDp}Cxo%m?) zLB3iUp?p@4P{zC4R=?&h7zI#sq=}!P{r*j;0+i=WgL}Y-`_m;r<4KnJSDFowLpPS@ zK0UhRmyIadY8j6Wd(nl*s2Y0aOw7zeddNm~+SjX9s^4&EU7Rw*RLYe+`@?Q@(#@op zSesC+Kj4N%`k4H7?r|zyJYYOVdyT)=u_dwoba*B@xQy*yVq$UGBkYb#!-%eL$tdSL zTa88isfwoe?z@XlPgbzFwzJ!9ji{@1WT`2d&6M5_PvY~2q@gqFQSgR3C&ogHfrF>L zr=YK&O!M#x8;kL>)o}J^IEhZm@^FTFocSwdq=7q*IY=dOlL64_3(5juh~JW4!$>hQ zG?(gHmb=ShwJmFRyy*&kXmqCtM~nm?Y1MIsQT_=3F5kl9(X8)wc8m*+^|DpdcmR+i z<+iX7Id{GXrJP7OWc^1a$w+P{rJkH(oLgh2!Et|+l~r-ayQoHO;4r?uz9T64>0#*M zWe+0voi1mawy8R~?Qf>9&_@8aFz&1otxj#ToP6 zL=f9_;_Dus7%pyhBDKV7puY4bLsXj)12!#UVM=i*FNxCKX6#BrYwp1H6-WdQLgn&l zf~PK9Z0`6(L;=7zq>1D_MlxT(kJ#+H6A!0z13SX1ExQ^^OC{iP&+Rhd&x`uGI}Ec= zA^g?`#96O{jfy})IsL#T=h=u}{r^pTN#gg=-UeM$bMgWx$;zk6X*y{f=I;&SVD(DG zKhEc?CBgNkm(S7>Q+e=ExzP6~Cuj8tlVr;m)->FMi+U^9{`WfBvJHF%Wh-CY^P~N(e-8;V=$z@@K^I|@;3{a zm_S+PwLfcgVu*CL4rg3SjG9=`sw&dTz75(#+3c6S`j1{KGxTj5-k*x`g^XPct|P*Q z=KqJB_A9&(=rRsmOa{~GQzWFMS`TNRG&MJ0iKdAVt9rSzkd6@X_W}P}6AEa8y8ryd z`E?u=#I)yf+`ONm+p{Z--8~#rk0mo;$4FL*pYstGGW7zio-=5p*iv@TSU8|EWz#w5 zeYJf0TB-&v6%`KDHAIcpU(Qj3<1)Ub@>(T&C@BhJcH}WZcfpraJ`3kq3LKu0`wDNE zueLb8r-fB8aXIaYWA{%gdRbZdF*5R6jzTU$*sFHX4(O|Z5^aSR%_tpnP`cISU^BQ- za36r-3VS5819C4$yBmD)a1`&S#kO`$HM64&(EMvzP@APwITww$gdz9O$X8%U-$zE? zGuvA!GeX))N{cv>M?(^Bd2aWS+7?8y@%P6Por=D-0oU$|hqnRi6g6qLJ8Z&k_JbS} z=r67kEKcL-aIczylb8Dmj*yjvy4jC9)TrE(rhohfa6x(*2ef|vO^r&Lzz;RSllM0S zZ*9$b%Bp2)WaP$hyD~Lr_K5&JY-N4)^*HDw#DBYe-q?&6J!gSmNOc1&#VdifiWZu#iZT`1HD8hpx`s@h7npTf3! zw1Of|7&BgM@(gM2^w}<3t-E(~?ZxBAco} z5~%qi)$-E&Sw`po#V`788kyLO*4iA9##I`l0;z-~iXeQw^KeyNH1W*6(sfI~4v4xi zrp@g_SrVWSdiS|c{~uln8URkk3NU4aOvXS$43h~5m7a~ujf1=33!Nl7bymwsnoIv* zp7d2!yI=69XRiu%bKQZ!N8Y?Wb8$?p-uG+oouHhmSl*TQ&eo_D@1ap08k5wyP*>*&>-pI4-WA!o}M zp@69Dy$+eT+f8T6sMlxMx^Kx$w0~eT!@`$&Ah70 zvc42f{1wEP!y{CU)6*-R(F~XfxNocdD|HKt%P%X91}ki7QjX^MDoeR+S!$^`E^Kwq z3x6utgVxU1qj%WNTyo9Bi8;_5D%(ojzSAh=y+XZQ8=_jEm1>Si>$ruK?HpX-<|!35 zorK2wb(}fx5fOyaG!2 zrO9U^W-V=@#)k3o3uUQ97Hp($VG8^6EAzFgn`B6;EQb3omf+#4H<*y_`f(6Y)>t4F z!Ys=Sm{0O7)En+w@a=#DJq=Vn<2B~IXg8Mwzz=$78Ib_MrMeh=&;EJFE4!7+s|RbS z+HHevR>f7qp9-g=o@GYz*su5_$q5*lnc5|Ti~S`EE0v((m+(Uh-i7YhMz}D(Xl6}N zUlOyM%;5DUHOi_vPP~f(yyJ`A1>@n?M9}sg5z-AIgaAzRJ(`>)>YImu6<>^vm~8F= zPJxsH!S2XcsUgO14{ZYI9Jrh;1)Vj>#|P5o?w+~N|K$`vW=i$gttVfHU;jGk# zJDM>eoJREBooo}#I*&ctmX4euFwt`0I3-F%|gI&oFu<5knj9#8t zxNbIELt<;#BNT*J7#JS>vh1dVg98$lCnFFLMj+AkI_FbD3f}Uo|A%&sl8oA(njBdk zPT@z=t~>a2d2V$kC6%SkB`u}NCNO8sj)B#&v1(gnq7b4rf0xg~(~WPnpsQ~Pu6UETidiWVG^{Eymft(#y&z6lf{x29e8Uzy|= zz(KsQ9g%jdx5aek&PtAoNhq>bNwK}yMU-(M7DDQCf?{vIxt~P*~)FFk0gcL!vsA&D)gD6Mul#zV#$;(86wj;rP z5oo=M6xHNwR9=HDaG~Y8Dth+!F$M-eudFtz!7(a8L*ov*FNr50$I|>@QPqR^ zOidC-y?3ytj2s_m{}5gScLUO%??pR-JeZtZpUAz7kXgYc1kgdgE+wcsa|CTrKyjUr z_m%PEDK%m;vNX}MOfFX@@)w_qS|{Y`=H}%{5!=)!S81g%Q19f~@!0GW%Ow55JayO- zg2V?Qq(a!fLsU%r^trOWu0rX^2YNDkN+Qq zDL|_&9KJdI*iB&A zBrT~3$6;#%Q%EVu;m;Ps@|mVMwd^TWfLigb?P7N3bAYH~ku~D7mnHu(8`fHJ5JtAy!_8Vli(mf6)drPn zaj_fK>9MiuaZ#!!hS4U!wA3=AojHc2tV9V~Q72IKqe!%WUwGTywh}g-&mZx-+7Y$iQLoeIrlj1yHR`sDi_qRq_Le0g)a@}!(i`n!Zh{?>ZOin6 zk+7v@`X(rJeq}r2OdNH2r0r#v2YzF7avQuBLV-`q$nd!<$>We4BN$_6sBlB}!8#)H zENseg^&M5!*4OkK3!%Mi2$v2N$xU_SeI6Ej(UP|42xuTB@OtlthGrDPt0Kt*>(ZfV zyi$)2){8Emh?9rlr67l>)8&-6kKzmiTwz3AVUG6VMVHOd??EJ3yxU^nv>Kb^q`!R2 zt=J6p%Go)KsbQO6cJBVx7!e`iZ)ol37(#r3?yzxjV<^$Hcdn*=M!xIuZx7AMW9#sr z^+$qVi%va-m%n`=v;vOaOGKBcuBZ@`C^dQHO^NQx_2zz5A2b0*H;eB2>G7>Ro_lyV z;#^&te`s8()}UP%YucJgMxKmNvevF2s|!8P%MZ97@U=EnFmh8X=3tyKgfI0;)V|sOfJAJ=a+RK@K`u!7OT)XQRM-iEgV+w?)0Ma`PcIr(0L= z5MblsUz#r3oNeI~?~OYhS7G`OrlIoKJ*2;*8CsiJRTMzATJ+>1zNiR?kDt%CIhM&G zO7ecUlfy4h@%i<2Mm~*mM+&q#ct=#bhoEG5QJU;{lVZ*=@6w?DV|p05Zg1V6@dmvt zxkm*u;$qFy)6x&Tmc#aBFB`b5cd6>_y9j@t9Io6971P`OlN1)xn(U2(DN3K5o~>g< z$L!d>IbE|_Z#loHIR9tu#}{XO=DK4%9)}f_s^104c1O)4UrZNw=REY*2kLosb&F^= z4$VbG#Ng_dEAmOsq(*(8#XUR(WG-wmNJG)4YomVY$jTzZF5RzS&R!zm+MXH>23}!* zEK2n2uC8a>3l50;n)Jvx>p8xp+Cuj58;y{6&x~W49QDM)pXumO)7Be?zH7ygCGiVK0-S>_W`bVC*BLEu8491g1KzH#u9noc7X$T5Pgr@1+d`q$Im_-7&D>g{rzJ7~nxmjqs&R@Z(w>g%<&BLX={Ql{9DTjtirGY8e zGx0DXsC|~=X)HZElYHma$9HrE`~2cM^bFHg+)0&hR z;ay(Nu9HvpSvORy=ETMW7#lT-=Q2-^3N^7P%hsJF z{Tq(n^-?|f9>5wd<5lm&Pxwd!@$w~(in{82HBsiLE}zrT67{j(_Y(KGtbbAgewL~} z#stcIZ@B2>g8P6OtP8I|{j_WBGxc-7mIKwR@b*Vp7ZcT#6pu`WX>N7q_bJ7>e?s)CU>5m8Z(T9rAk zLo*C2^<-Rr6~+WPcg2FAvDCE=TTjQA<(xL6E)Cs+vs0oO9CklkA3)veZku~mFlq<) zd2E?pHlEc`g~@~+yYwqm)YN^ z>n(h`otaZA?VrEsxu{H>4rPckFvH0C)hwLV)YPiq>PkxH&Yb4wn?VD1Xr~ZEkQO}H zrk%$n+`&Hb$9Bn@g9&@8xp8a_&233WDYRo8ij=OQqRqimt?ttj)^Am4tPB(|Al*yH zXrV; zrEC^1D+^{5p^>Xr8QQELYkOm067-YiJldkItxZv8R1Oy`fjw5r|9A|g;0=1_)SwdjTJBRT_pQc8Kf5wWXH6i!vQb8`E6O{ZEdqfkHZ zGP1{Ux)i#2D%WU&-}&2`GQsf{0kM})fJaA@aN}CVSwWZA)QmCTE z?(VK1&8J@G)1$F(4Yx6P%P}!pXX#|Vj*Vsgm^~+y-re1!{`B21fG_#C?sYE@ch?0& zH@;0mg2>?Mj#|Y~imXh?ZPF~0W@2`Jvj3=wk}b^pAhQ(K1WiL*8?)~E8mOvH9PfP_ zu+gMFx^xh-6x!k!yu>O|3Blf&n&$moKk5=y&NM)=Hfn7ijfT?CiOKXJdb3(DS~y-BZd{%y<3%JJ^=)#UE#ZoYB|e3}ySX_#J$j*Rv6~aB)>FwogkRp2$dlkAHU!?V9#LGwK5-Cb1v&7GA(BwnI`ix0=g% z#5)ukWnh+goACBiXa~6XR!uWdSWJo#5!wCL2`ZT8-PcFBkSAMK*rJgmV?pNDZCEMH zD78?2-YUJbFXF6wQDf3fXrJzb^-ku;qLc6tw@^8^&hb>ZzvLhoYTa4bK94RKuXN9n z!$*yY8+#m!rPnM5_ipPnZ*6)sFh6-xWpfmbpFxXTP37%3#hrFd>0FU-c9yUJEQFI6K2m+$wN z0-^kZTWwSU;dAkpPZmmUge&t1C$XL!Z1}tw7#Od1#ewd?R@?nsDrJYkr0>XyA3NQG zpdz#+T>5KV#p}84B=PN`8F!WAi|a0B5f1BvS6>RAx`k4V5kOm&r^_)N+Z(^PUZ8!Q zIbu-qJfr7vTveI(QTo{f~0W*@!bDYwLd4ZTQJ*bG-1S+Bfehu!+Bdb3E8m9ssO-(~L1FBoo25D7S>KtzW4 z9d50lLtIiH%~n+Zhm(*=EyTTXy`!WtOb;*xXi><)b*Qac6NK(or=Fr7yP0k~Aaxzao=61wT)^JlN);$Ax?K+ zFsEi`6H~Vcmn;TYk^h;M14tMj`ErlRS{$z(XJ~TZ4I$mnJ?1fLxD^YcdME4OjA`mq z+;Amsr+l9-aE;@8ds-()Gq)N#I`Wi+Qi@v!+qQ)7 zU71PX7gwPZxF95tq8#5octX2zT5Xin{#%-i;Vd9{vLTCf_c;AVU_EI-2y{d9TpxHi z_Jp>mar%rO3U-1%*E%d5&(ak;cPXt;){7Ij?07U3&9^+W0*5TFB}Tfgu4W2W_2;FLt_zO*l#~J={;{mZo`&0T`@19%MAGP-C~;3`&8E z!EpYJjAS`7GisIJLb`_)HZ3t(**gtdm-o?bQYhUm32xIp+dlvQ>iY6%s@gZ~BZbT& zV~9$FDf5siq!OXb^Hhoukq|15nMSD;A`&^Mh=YVsDf5^zHW-SODN5h9>+QGJx7PQa zKi;+8&auzg`+1)GzV7QDuE&;7zHPYwdmJgl%{sS@*O%%9S6&~Fjg5=vXLzEhtg2E| zSI3v9vA7a}@rAzL+YST$mdd|xF+S!%xxv6U!H*T+r4BdWVk@>zpdh<8m3r%Vl~Q{~ z)0G$JH)v`KBO#-^^DN_r-ORPIS;7oykG;Ocp<#C8$( zOtZ$T3!g7{2FdlCZ*<-B;#E*2HGox6me+w|7oL=-skcz_<+!i!vx$PH8i9gJ(fb>c z^os)9yRWGSXq;2^i!3UsA*J%!nB}UpOM8B6sFX>9*xh6h3$)uj;Ko z(N)Y8$}kX#8pWq?ZO@(DxwD7k$u8dR7rniFQFBwZ8EjV_tIOjcOhb#|yE9|&m;mHS z@y&81%kqyd72n>ZjJA~RxN~4@y}Bx0v-)?g(8WOSq)%VEOIXC>gPEr)tB8deeOtz< zVO^%}eSk|RzS6>UleoBm^y{Ftm&M{6E>wq;NWNvvX`w$k>NON;Hbk*Ce036O(T*D) zc81<#=DcS-vAu^oD^z~|`kC(MLy}@|2=a-z9WtQw| z#<92I&>de4&ws6c@Zr>lS*6x;3nK}K2fUY4w|kinU66={u$tf!+an&ngM{$I& zsd~~$-Tc9$pY>pzW%P+b*w`W9ey90F;R$?VlZ?#jFRCZ2snQxcmZLdT)+htN>2GE; z5OUb^-o5yZFO&!+Nel&b&N9%yh=i86@Bl?oeWpdn|Ku^zTpQWz>z0>kP$HAc_Di?( z86xB>wNZIO_Mb3+fY9-ajg2*U^BC~@-od->6in3Ul#Yqn8(kT+7KHv&^ru@XXX$9LLAwZ6aqYi5MXdV4P)oRn<)rEyheQBn7do)rnt<*7ARrX6G|EBX1x zV}EC}=$aZHJFDlqj=L#GB(HtASHQcuH6`RrThjN(-76RE-GqTzZY9|Ml zppS(r7~$c?1cCWVX_o>cL+jt2-3tS)E+4MWkG2al@kmmNNB)erQ!tgl?@c7jxsQ&U zH9mwNwJdQyR5pAeuWc2ShH_HU4Xz|7N1^UzcyV?~IyFgsDwcxlRaGCKepPO^PkG0V z?l(TfXsT#_S#D&}U53E5(#d@6&3kB1={mV;)vCe=4|0c&2;Ce{4e;!#IO<{-rG*Ej zYg*vLEH4^@&E#Tov{BB^q8`qD*C(&a!LEw6^+rJ}0L@BI{!-N=t1|{jd(Vt%Vl<#z z#23-#o8+1oYkj&YV_&@6IE{v`f3n|x>OO%CFi9zkS?yEmeZQ-Sa!pAlH6M zPnn03*#6KpLXxMq`@e}Joyo`$m9VbhqWQ9;rmj*YXjbqH+`3$8nrB}?hD)-LanPfu z(JeA?7Rps zU4bJF;eAPj8IDP35 z?^4goo2ov{5F%)CFXq+sk-c>3VBx7&ZDe@vFE1P<8cMDk6LqCfN`pnb4pB#pZ zR$o4TJZx{PM|X)ZyQ~^lIGuVtU;Dn;n@#)o)6F0HtdIblgP+ku4dj%_mymJ!C{EZi z)@3S>*4`rDv2Sb`ZC7?=K#Jk|^#GJ#nsB|9+&=ae}M9O^8uAgxG~>| zs@dCX1)f0p=P%l!p=$0U9W%rV7$zlAp#8aS;gGbN+FKgZ-n}m@sXuk@FCJG(y&=m- zYRNssL~MKXOz(owR_@wpbgrX7j6_Nm66%zyAt$ibwHq07^xw_S8p>l4kXg!ClJWS+ zOnN%Fla@m`j0umoLwp9pRnGHs#}|GSuOcCS(!EPjFGAs+!8%RWs-KGjI8Sxezm{6c z4(=vtrP)`qbG_vw%-vMgyp-D8cO=sO{fS2=t$tL=@6t`JMzHGm`Pz1;UYGNUGNoRI zwrQ|^rc)u!LhpunxZ+1g8;@Xo;1zI#uQy%To0U}W^-@7nN~(TQx~rxM8Zy_u&!zAx z`pU22ygc~vV=P$U(XM>)?5gc%J%<+x*)KO^m>0hyIGM_G*JKLf;^Kr2Fm$t%Ypws; zRr2n>mdcs+IWHLv`V>9?qc=$;I(4=54p|41miB=)s@;AObYOLu3U-MiXk9(EG&7m? zc#_OyVtlWYK~O>4I}pW;1PlNL2JLxT(${IPO(5&i$;mwDR?rfdkF()??b!1@rRC+T z$#NvH(O>^#DK9r;93lz4EyKMIZZlNVQEiao;M#kFmuS&)pf`JHBGhl(oQt(npkYtkHy3;W#?6Ip|%poK=dG8H=d{{6~)^E`{_6MlXY z0TNJ>a1tgMv2qzz6_v3B!Nd1KEr}fS+X7I#l{zQ}^8PHT3lKob9@}N1xG!>N7~NUEGp4&pU*^I}i8R`bLu> zE?FY4lW$i{bk1`7+7{+t(^VY09WA=M?9Ld7ed0aRkyC`zV3i+V>T$^GfTOrn+tmJx zDJeD^mVWzB2@QGA&wbVJ_J^9iaa$)uNFT{#eBtvCzl*KQJsmGB_C5AyS~_k*z0!By z%ONW+rvB0kSIY+r>b8lhQJG;v+TD~}1Tg~IhBBV8ujs*}``@g8f13yeJRbh8kd}_H z^XqpH8%p6JiG!4*X3v~u?5{1Z+rK=kX{&sKU%FCRFwZ>fT>g-zxws-m4~S+gMq?+w zB6cFhJl2gup^(m?>7KC>JIZHS`-A4j6W@a+d$wJ>b>MFBV@i!fvQ$z47Yp-DR2F&F z$*CV!-ajVQH8bsu(_1RpNzMiJBC3lIzAo3lPANSu!+1;e>Lag-w=%q|SH~>O`$ZJ) zH#b*YR`cb0SMIMcw(eyeAN!eIOg!nOrMx~q-OQAOtxqsbbB3Zox~Y6yb6U$jRO7uY zhVWf1{G9x2iA5+gx5uz7I~ys1+WXh#1}7%M#Vwq3i`o9(Ni6Op9(R(R9+dgbq8i}5 zzcR?V?qw&zWP&m}2S;UU`s3*nPwV9PTXS{Pf|e==hv#<=IK>x_`ywoS*sMn0)Ob}V zuXX+Ur^0;!lQoEgoEifLMhhlB$2Z(nODH?he-4T<+|pKb0ZK~oEaH4Enn=3%9T{M~ zoOYUS>Q#sUDhwAEE-P%8<8*oReG_fJ`2Rvq#{y$5XRkz%F=K1<{e<{9VlUj*ftWje z(VmFc1KwmzH^Nj)1FA-C6nPLF{It%3A~XNY_QYTQ>kzNqdF)yBB&5)Nb~8Z^2=S?| z+SwC9pNbE!`hB)KoDQlh+#3D)V3G4e4D$fly>-NrGEUsx4@zobVqpNmblnmY z4~aB9;w@6TFF;~xFhuS9%w@4JDKJ#2>cMl4P!kGrNgZ28UmXXp;xS9R$lbbr1Il## z3Ss~^2TjE55D+YlHJtj<+1;8qMM6Y0AfSHDCG>FZcS-uAE|QD!!laL_?_ zY`V#m`&s@IZ&o4Dtwn!~qnFgq^7Qqe83vq>+ZMm17!{ z407JFbzKno=Ab*J}ne+2NmITEj<%hE}t&8QoO&si5eH)IgUk z&-VWrP89qZ&}ZVGuuf%-)?N|Mg|9=}^M;}s^%0USIU;Rqn=&$_y8O53vN6XIBQs5< zi4R)mU$s++$uV)k4P0s?Km7dpK7yXnv-gsE75^aU=;z89F~PrrxH*^UKZ6jXa}tZr z=*{vWl;|k>JFZRFlnpfLEC-XDt^_en(L{aYnwV`rIpcnWIYj47JJTeLb0UGG&%jA{ zQ!S)KY6KHgGQ>VZgvnoU1&2vx_1={^8jeHpqnc|-aK1Kn4Lb=uuB$tb%lgNV;BBj6U_*UUnL*Jj*tfk$5MHN?3w?) zk+@1e*HGdnVvK+PM0W=N#6tX&;enGoj~$cn_4U1wnrhE8ZLB^#I7lk9O*GH9Hly0R zyKjTS8347gv8$=W3s+f7E34`kFYdL?UXxq7-Ql@k{YPdFR0vxs-xI^Haa~tAY=z6A zac6OU%3=4AaR`R*oXxW+sOjtL8~g-GF!s1Q24?2dPcNE;_(Sv+$fyQH_28#heA^O! zXlLhcbBm6?v4XoLM-2GPRSnmJ?%m?-1bx1_jRk%lL?`1R!EU+`2-SFumA)>w@knPb z#t)Yo5B=X4VdQQZ4IO2~aOJv(xYSBqDkw-**f{6rOX^oh?rnF=!GPbJ`kF3H#z$ZA z$eJBe(b4U=f)(gAp&qZV5Ru(qCeyrdK|9;I>B7Bha;}UYG5OG>&Qfc`LHssT^_!l5 zru9bW(2PjjbY;d8)i-$pb97FZeO}F`cd7}_rXV%S%R<-ECK}X0KiLPIt zUNZ|hTzU-JV=E{+H9>oEk84Me|8+TFOwPkY1RcL;V_{Lz+3;}MEBaX`11J2^-YS5? z81UMg;UA$09haQ``r}TSrIpMiVclfeUtWtV(9ax zrg}&+fpm+9I2Y*u?l(pI(y9^?Se`liB-j&TlkY!$Qp&ylVO*!_N_MBa$eNgz5>Fe_ z8T~9Y082X`48vlA5c?06?Vw+>{|TxEM{ zRfIZ`x!m~vLSCLYbn=KVL30+BHDP?~bptw#u0x28?-M?J`0$>6`|>6V5oN@<@a*4~ zK$gq6(dufQidIQJC|1=$wlf~8+s;_Wh0)COFN^npq>(g7vH{uSnW+I`=_d=Kq+b)h z=)*+zCKOL)pe*jRRDbGA?tyNVgH(UVqj1Q^+mcXI9HF0e4uZWH%5(ABwP=V! zPUHt;(MSGuuIje!fNJ*P*EeXk93`6v1^W2Nc=cDr zAhg0StEsQ2gM4940PB_a=b<0{$XXIjfwx>y4!bkZ-paD{R}YdPD8 zj~_vHOgw-6nrtZ%iG;58qa!rPQlAv$;1H1z|AHal_&5V2qpWIEWQNA4I4P+jOJ;HL zJl`KHOn>c2NJt>#xm~`@iO6(Su{8@?U%kD(VZ2sPysHT0>Rwj3>Wu6wVD1-R@UlOrlgi5^3R_? z*Mhzq*)k#Fp-4{ij{~YwSj8PXc2pj!|G6KeBod`$N-d~rjB410Nk#Akt> zapH5|V>TWs+ovxsZ*E08m!t(l^X9SlZ%3o(_zZ!(+`__^_nwlHlH?U+UD2I5XY7K4 zENpCSnbyvTSPAvG(9qDJ{1APf5C{dOq^C*xvFow3!22t#TemKv8GnidKN&)yw}UC# zx3%CmAhi$ML45mQj~KoL4;a>?Mi=#1+@*eF zYl!1P)`qj#je#laH*coLgw^PMnXL>(H`Z)6OT$LT$;Y53!d8JFujD?Iy}UmpB!q14 znwpwQXnJ(G7atcEU#bL_xTz7s|KrCGZ4a~b#j?Ad?wAxS{cQc^7wmux2r>H)0^V=o zZn+@^JP7CNZhZMjAU7Xh3@Ugl7RU3jzqOej;Xpzzuo@-?Cm6LlYA`}s0n5<2;D~jD z$NK&AJ6lC%B?lMR#`~YXe39g8ovnK3i67^~(uzHe z{YKR6DR~om9?^Bqw#XasCuG~+&zjHl*c-6?GcbHQ&vcv9v696cT-FMk6=#Ta=I77T z&l(z--hK45>jF?R!N^w&S6cn1yPqZUvf|jOzXV>QtgS8u_lxKZx7=tafJ`eCjaN5* z`SRuBjT?;8($esjBXGAtc8Z2EutDBGGUBq}TnkG|BCYcY-GbraVE`&|t|#%oZkf+j z;`2Irofwl<9-Wv-xGd;tN1S^Df%KV49<5p5g2F;}?Dh}7*fjFbZz5C*fz1&lY)+z{ zgIc?LF_b*%kugDV?J)Tr>Z&3V63kFqh6#l^Y}pa^&LEgNkzu-x2skGBL3Hs-}U_f!%UgIgL zdjpig9mk?!ZJ>oIaAvHk{iQEP8_=$aS($HLyr!$Q*j&Lc#Nf3$>>V^hZU-MdN<>!* ztawhL#B&nzv7DmXVQxH&}D^(BZ>ZJ*>3+Q5V63Py~LKN61!ELIMQK#(2+FSGbC{ZL8qhc4z#s z)BRXvKC#XyqONXM;AbI?7PB`tH}hCGj$N6oxr<~bFzbcnWO@Q~gi)s-22oghuSgZL_SvZ?ORSo|W;lhye)G6UtfwBFf1Lzw0}!Ldz>LM{R_ASD5vR82e5Hj|s+@h+=?)aj4kQ2nPhf zWeyyF0UYHNeMAA9ip!qfYs8zJoZ*1l08`aXO{_4Is4IztjYaH1xFswYpa#@ioirn@ zH}I?Kjm@Hn_Q1h|9Pq|j2V!uOaBS(20sl}xcyJ5Xp1phF(TeO7X}1$V^T~&Oy#v%l zVAul(4iMqZ$JZ&fcwTn~jvmTy!MzbM9X=aC1GMPFiQDzQU;O+=hE205%{x$EfRh39f`EZQ3u@}>L!+ZP-5>U#T)d%yUdg-v z8O#^qn~aQ%P++;DMUxG#A6ah*d$XXBmyxXPZF?_P$b4Vb9AYaNMF4w*Pb*=tF{+L6 zooXdqFAyfgc?j&nR+u$EH8^+%NY%C~R1l^f_?B381YR&Cu)MK|?qKSjPClpp)Zo`| zx?*nPvr{U$_RSl9#GdfTBz-!v5uhEI32Zs|hhxW%4Gs?}#IG=Vs^T>M^Q2e!S$U!6eK#WT9Zu6^Y%56^CP<=$us|!sZ-j7%Cwg zM|Iu|gum{a4X%-(=s3!bn0AKBY|<`TI8Tvk{nx`4x74Zw+K7OJ05O(e#Ou*-A%}G*?v%k zB9AsgftkbkN|Apv?fhYn4XK*-@3mcCU#}0cFV5fkiTQdW$Q5TPBrw)t%avlw1r=JV zW$G);()SUcxpxnriTw8&2|F4?u|~a>$WGo zkqF_vcVyPrayn!DPK8!-BxP1sVNs^jFi`^A(R+w%i2d^F^bEfL*!@A zbW5pJSvLl3KkNu1vwd9fBl8%@DAW4)%*0ol7`BV2{#aO8j}Aoq@AFr$?&n?0Nj2WW zg{vUGymwp>ClPICBj8}3H#P>JX*CJyfa$ihv8k=A%c}9eCU=K;?tGW!{;+Zi`EMg= zo;-Qt&q1%?h)N2IPC8wricYrUlRv-N#BMm^uL21^-Eri_2Va~JM2UQrgit$f|GjVE zkE;X;`S+DTh9RUlR3&mtT5E~QP`I*Nj~s_i8I0CHei0u`NG>Rl#=J1X{UV*lSDaug z6@@2_HuNqMYx}-Mihp)Yu|` z_uu=fSVL{E`}V)ZGEvXAP(yDt8TH(ui1}&&4*L818CY2A5EspMVMbkbqjXg~ z80DJkY8q(0D=hL>{hAY?p8UcHRX3Qo%xt6E=A*@G`;3gD%=7Z|EQLzz-zp>#)eU$( z=K`e1G)!D^7ZGlvF2XQH(WxWHMES4q6^T%cfFt~Q7R}3ASqHBB#UE|Yb^x{Z7sOB6(-QLXTux3-q%)AN6A>40%=vZq z?%fTDYh4-=iEOZk;)3Uil?6GgIc|XUj)NT2~-&1}%*FId4yeZFbuj?q<_@ z%IW*3W~e)refIJkk&pRZms@W+g#mofdKvad*=~trt$ueeUJe3{^vlF&>g!j+lzIFj+no(Y)F4 z#!9$w>8hV=5YyK|RZY0Za*nRt)7;Fq&Ak{NxdDEOfm9m!UCjKx<=NXhQN!>|FzLmd zo}0QTc5#Te#bgd{A$BERCZ0creT)PqZmO-V4dG}@Mc|27*X8IDd+m02ch9dsV4jc=$h~eI zGYMh$)&6f46>1gBixWqBA8c}!<)a2nNy)dj_d?<#Xl9fK?BSLqeXJFI*ss~-)}_&& zq7B5UhEpNL-+-l*j}K}Y-hxWgpO?wyq4DupL=i5yZP3F}<>foBN;}x+HJAcYPks4} zQ9s~Y;I(_6gzP|Ylz3gvEd$X4L;|aSeE;O3ASPI}XJeahn(YRCz>47+5s{IipmuPmu;XhZR&%yw?c>3dp%qZ_(uLY0c;)#121tRl zJ~*_`AVrY{6g0vcJ&ZE#{q{FI5*X#URD=nF~igD%UJ8qL)9CnNReY^DB)%g$}PVPa&(B{KrP%Ke^_%w#>lJ zm4|R(7Cxngv9q%q=Mneuc>6~_5;iG4JUo1En@uysD?*m$>f-t2zIGfm5&A4>|46Bs}PKVRb(mk!KTZLupd2on;l7*qaf}AP=`xt8v zWo2g*pctQ}Au;oAhm1|fdzamM&<0Q%cy>WV=lJ{Q9E3h3k}7m0Tky`_m9yOFvueQ# z!B04W*+xC%iF}?W5^bHFib_^d3}6k!PPGp&bY-hY{^6dWq{|*ff8#v$C@4eIXQF{=6oQ939sq;wb{73CB|V z;>Bvg9VZDzOm>24NxphDa&y}01Ku|8mPQ)RGqGeD6k!pMy`!!LJq|6Ex*by$;rJya z(mFvw#0uw7$0!2jMBlP?5J;@8Av5KLP_i$W%73&nLn?i{`Vou)8U%F2-#EfZ)V$cr z#RwAI347v02~S*IjSn3Qf5gskIuTH5#0KgQnm~utT%YA*uUoB4TLd-#J765wv*9uq zKBjo*+7@7@9pHg{;BUm)YrQ_<`ma-zEEak}W*q%C?XI6-$cvpBiQ-3RJXbtKkWQlm zRhq<>2F-xpzVTmy!NJLWcX3O2s50&yTd*d*cS4Z7NKa3HI=W!x`p@Qw>R`aK1KuEQ zZ~4Z&{mHC(?`;365f+1M+i8$PuSFcT-Ss&;Atws$#QOVI57~Knqd$K>hMbW$>a+SQ z0*T{9#J{-D>dwx!K0ZDKX^?GjeMP>xM~4O}9o`W3ghaUkePFPN)cp8(X8*uM2=yFHeWCJ3%_Pa(H6uWYz zBaZwv^!LEt!f^IxdZqjjx;W7)Va)HvJI0rj|0-Bo|XkLNp&%dvsfw14ZklDX&o;Pc6 z5nOX7lCt&YhJWw!-Sx9Dtn^B8E-IB82AT5rm8+y5&?)hYYWv~UmELUvi^Bgtu3(qt z)_H%l*uGH?{AGe3GHx9?4eFe6by!p&Lw`X+TI0{F^I|O3-CVgZ`+qRh`0~T!T}l9) zz}e?)r3xmD{~d#zMAHtlhch0PSKTx;G*GEPs26m7?I{|A~f;?n>C literal 0 HcmV?d00001 diff --git a/ros1_noetic_core/fanuc_msg_translator/CMakeLists.txt b/ros1_noetic_core/fanuc_msg_translator/CMakeLists.txt new file mode 100644 index 0000000..1e00414 --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator/CMakeLists.txt @@ -0,0 +1,205 @@ +cmake_minimum_required(VERSION 3.0.2) +project(fanuc_msg_translator) + +## Compile as C++11, supported in ROS Kinetic and newer +# add_compile_options(-std=c++11) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + rospy + fanuc_msgs +) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend tag for "message_generation" +## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependency has been pulled in +## but can be declared for certainty nonetheless: +## * add a exec_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# std_msgs # Or other packages containing msgs +# ) + +################################################ +## Declare ROS dynamic reconfigure parameters ## +################################################ + +## To declare and build dynamic reconfigure parameters within this +## package, follow these steps: +## * In the file package.xml: +## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" +## * In this file (CMakeLists.txt): +## * add "dynamic_reconfigure" to +## find_package(catkin REQUIRED COMPONENTS ...) +## * uncomment the "generate_dynamic_reconfigure_options" section below +## and list every .cfg file to be processed + +## Generate dynamic reconfigure parameters in the 'cfg' folder +# generate_dynamic_reconfigure_options( +# cfg/DynReconf1.cfg +# cfg/DynReconf2.cfg +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if your package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES fanuc_msg_translator +# CATKIN_DEPENDS rospy +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( +# include + ${catkin_INCLUDE_DIRS} +) + +## Declare a C++ library +# add_library(${PROJECT_NAME} +# src/${PROJECT_NAME}/fanuc_msg_translator.cpp +# ) + +## Add cmake target dependencies of the library +## as an example, code may need to be generated before libraries +## either from message generation or dynamic reconfigure +# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Declare a C++ executable +## With catkin_make all packages are built within a single CMake context +## The recommended prefix ensures that target names across packages don't collide +# add_executable(${PROJECT_NAME}_node src/fanuc_msg_translator_node.cpp) + +## Rename C++ executable without prefix +## The above recommended prefix causes long target names, the following renames the +## target back to the shorter version for ease of user use +## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" +# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") + +## Add cmake target dependencies of the executable +## same as for the library above +# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Specify libraries to link a library or executable target against +# target_link_libraries(${PROJECT_NAME}_node +# ${catkin_LIBRARIES} +# ) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# catkin_install_python(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html +# install(TARGETS ${PROJECT_NAME}_node +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark libraries for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html +# install(TARGETS ${PROJECT_NAME} +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_fanuc_msg_translator.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/ros1_noetic_core/fanuc_msg_translator/config/params_bridge.yaml b/ros1_noetic_core/fanuc_msg_translator/config/params_bridge.yaml new file mode 100644 index 0000000..37f2aad --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator/config/params_bridge.yaml @@ -0,0 +1,59 @@ +topics: + - + topic: /fanuc_1/joint_states + type: sensor_msgs/msg/JointState + queue_size: 10 + - + topic: /fanuc_1/bridge/follow_joint_trajectory/cancel + type: fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterCancel + queue_size: 10 + - + topic: /fanuc_1/bridge/follow_joint_trajectory/goal + type: trajectory_msgs/msg/JointTrajectory + queue_size: 10 + - + topic: /fanuc_1/bridge/follow_joint_trajectory/queue + type: fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterQueue + queue_size: 10 + - + topic: /fanuc_1/bridge/set_payload_num/goal + type: fanuc_msg_translator_msgs/msg/FanucPayloadNum + queue_size: 10 + - + topic: /fanuc_1/bridge/set_payload_num/state + type: fanuc_msg_translator_msgs/msg/FanucPayloadNum + queue_size: 10 + - + topic: /fanuc_1/bridge/robot_status + type: fanuc_msg_translator_msgs/msg/FanucRobotStatus + queue_size: 10 + - + topic: /fanuc_2/joint_states + type: sensor_msgs/msg/JointState + queue_size: 10 + - + topic: /fanuc_2/bridge/follow_joint_trajectory/cancel + type: fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterCancel + queue_size: 10 + - + topic: /fanuc_2/bridge/follow_joint_trajectory/goal + type: trajectory_msgs/msg/JointTrajectory + queue_size: 10 + - + topic: /fanuc_2/bridge/follow_joint_trajectory/queue + type: fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterQueue + queue_size: 10 + - + topic: /fanuc_2/bridge/set_payload_num/goal + type: fanuc_msg_translator_msgs/msg/FanucPayloadNum + queue_size: 10 + - + topic: /fanuc_2/bridge/set_payload_num/state + type: fanuc_msg_translator_msgs/msg/FanucPayloadNum + queue_size: 10 + - + topic: /fanuc_2/bridge/robot_status + type: fanuc_msg_translator_msgs/msg/FanucRobotStatus + queue_size: 10 + + diff --git a/ros1_noetic_core/fanuc_msg_translator/config/params_fanuc_1.yaml b/ros1_noetic_core/fanuc_msg_translator/config/params_fanuc_1.yaml new file mode 100644 index 0000000..d5b7f9b --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator/config/params_fanuc_1.yaml @@ -0,0 +1,3 @@ +robot_ip: "192.168.1.201" +robot_port: "502" + diff --git a/ros1_noetic_core/fanuc_msg_translator/config/params_fanuc_2.yaml b/ros1_noetic_core/fanuc_msg_translator/config/params_fanuc_2.yaml new file mode 100644 index 0000000..870f3c5 --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator/config/params_fanuc_2.yaml @@ -0,0 +1,3 @@ +robot_ip: "192.168.1.206" +robot_port: "502" + diff --git a/ros1_noetic_core/fanuc_msg_translator/launch/fanuc_1.launch b/ros1_noetic_core/fanuc_msg_translator/launch/fanuc_1.launch new file mode 100644 index 0000000..e7ba918 --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator/launch/fanuc_1.launch @@ -0,0 +1,5 @@ + + + + + diff --git a/ros1_noetic_core/fanuc_msg_translator/launch/fanuc_2.launch b/ros1_noetic_core/fanuc_msg_translator/launch/fanuc_2.launch new file mode 100644 index 0000000..3762f49 --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator/launch/fanuc_2.launch @@ -0,0 +1,5 @@ + + + + + diff --git a/ros1_noetic_core/fanuc_msg_translator/launch/fanuc_msg_translator_fanuc_1.launch b/ros1_noetic_core/fanuc_msg_translator/launch/fanuc_msg_translator_fanuc_1.launch new file mode 100644 index 0000000..41bc3f2 --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator/launch/fanuc_msg_translator_fanuc_1.launch @@ -0,0 +1,64 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros1_noetic_core/fanuc_msg_translator/launch/fanuc_msg_translator_fanuc_2.launch b/ros1_noetic_core/fanuc_msg_translator/launch/fanuc_msg_translator_fanuc_2.launch new file mode 100644 index 0000000..15c81f2 --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator/launch/fanuc_msg_translator_fanuc_2.launch @@ -0,0 +1,64 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros1_noetic_core/fanuc_msg_translator/launch/fanuc_pair.launch b/ros1_noetic_core/fanuc_msg_translator/launch/fanuc_pair.launch new file mode 100644 index 0000000..7ca9fa2 --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator/launch/fanuc_pair.launch @@ -0,0 +1,6 @@ + + + + + + diff --git a/ros1_noetic_core/fanuc_msg_translator/package.xml b/ros1_noetic_core/fanuc_msg_translator/package.xml new file mode 100644 index 0000000..aed2fa7 --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator/package.xml @@ -0,0 +1,68 @@ + + + fanuc_msg_translator + 0.0.0 + The fanuc_msg_translator package + + + + + fanuc1 + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + rospy + rospy + rospy + fanuc_msgs + industrial_msgs + actionlib + trajectory_msgs + control_msgs + sensor_msgs + std_msgs + + + + + + + diff --git a/ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_joint_states_converter_node.py b/ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_joint_states_converter_node.py new file mode 100644 index 0000000..21105a5 --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_joint_states_converter_node.py @@ -0,0 +1,38 @@ +#!/usr/bin/env python3 + +import rospy +from sensor_msgs.msg import JointState + +# Namespace of the node +ns = rospy.get_namespace() + +joint_states_publisher = rospy.Publisher(ns + 'bridge/joint_states', JointState, queue_size=10) + + +def joint_states_callback(msg): + """ + Callback function for the /joint_states topic. Publishes the received message to the /bridge/joint_states topic. + + :param msg: The received message from the /joint_states topic + :type msg: JointState + """ + global joint_states_publisher + + joint_states_publisher.publish(msg) + + +def main(): + # Initialize the node + rospy.init_node('fanuc_joint_states_converter_node') + + # Subscribe to the /robot_status topic + rospy.Subscriber(ns + 'joint_states', JointState, joint_states_callback) + + rospy.loginfo("[Joint States Converter] Node initialized!") + + # Spin the node + rospy.spin() + + +if __name__ == '__main__': + main() diff --git a/ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_payload_converter_node.py b/ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_payload_converter_node.py new file mode 100644 index 0000000..07ee831 --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_payload_converter_node.py @@ -0,0 +1,101 @@ +#!/usr/bin/env python3 + +import rospy + +from fanuc_msgs.srv import SetPayloadNum +from industrial_msgs.msg import RobotStatus +from fanuc_msg_translator_msgs.msg import FanucPayloadNum + +# Namespace of the node +ns = rospy.get_namespace() + +robot_status = RobotStatus() +payload_status = -1 + +payload_status_publisher = rospy.Publisher(ns + 'bridge/set_payload_num/state', FanucPayloadNum, queue_size=10) + + +def set_payload_callback(msg): + """ + Callback function for the /set_payload topic. Calls the /set_payload_num service with the received value if the + robot is in the correct state. + + :param msg: The received message from the /set_payload topic + :type msg: FanucPayloadNum + """ + global payload_status + + # Create a service client for /set_payload_num + rospy.wait_for_service(ns + 'set_payload_num') + try: + # Create a proxy to call the service + set_payload_num = rospy.ServiceProxy(ns + 'set_payload_num', SetPayloadNum) + + if robot_status.mode.val == 2 \ + and robot_status.e_stopped.val == 0 \ + and robot_status.drives_powered.val == 1 \ + and robot_status.motion_possible.val == 1 \ + and robot_status.in_motion.val == 0 \ + and robot_status.in_error.val == 0 \ + and robot_status.error_code == 0: + # Call the service with the received value from /set_payload topic + set_payload_num(msg.payload_num) + set_payload_num.wait_for_service() + payload_status = msg.payload_num + rospy.loginfo("[Payload Converter] SetPayloadNum service called with payload: " + str(payload_status)) + + else: + rospy.loginfo("[Payload Converter] Robot is not in the correct state to set payload") + + except rospy.ServiceException as e: + # Log the error if the service call failed + rospy.logerr("[Payload Converter] Service call failed: %s", str(e)) + + +def payload_status_publisher_callback(event): + """ + Callback function for the timer that publishes the payload status every 0.2 seconds. + """ + global payload_status + + # Create a new FanucRobotStatus message + payload_status_msg = FanucPayloadNum() + + # Set the values of the new message + payload_status_msg.header.stamp = rospy.Time.now() + payload_status_msg.payload_num = payload_status + + # Publish the new message + payload_status_publisher.publish(payload_status_msg) + + +def robot_status_callback(msg): + """ + Callback function for the /robot_status topic. Updates the robot_status variable with the received message. + """ + global robot_status + + # Update the robot_status variable + robot_status = msg + + +def main(): + # Initialize the node + rospy.init_node('fanuc_payload_converter_node') + + # Subscribe to the /set_payload topic + rospy.Subscriber(ns + 'bridge/set_payload_num/goal', FanucPayloadNum, set_payload_callback) + rospy.Subscriber(ns + 'robot_status', RobotStatus, robot_status_callback) + + # Create a timer to publish the payload status every 0.2 seconds + interval = rospy.Duration(0.2) + rospy.Timer(interval, payload_status_publisher_callback) + + rospy.loginfo("[Payload Converter] Node initialized!") + + # Spin the node + rospy.spin() + + +if __name__ == '__main__': + main() diff --git a/ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_read_single_io_converter_node.py b/ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_read_single_io_converter_node.py new file mode 100644 index 0000000..c0f58c7 --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_read_single_io_converter_node.py @@ -0,0 +1,51 @@ +#!/usr/bin/env python3 + +import rospy + +from fanuc_msgs.srv import ReadSingleIO +from industrial_msgs.msg import RobotStatus +from std_msgs.msg import Int16 +from fanuc_msg_translator_msgs.msg import FanucIOState, FanucReadSingleIO + +io_publisher = rospy.Publisher('/msg_translator/io_status', FanucIOState, queue_size=10) + + +def read_single_io_callback(msg): + # Create a service client for /set_payload_num + rospy.wait_for_service('/read_single_io') + try: + # Create a proxy to call the service + read_single_io = rospy.ServiceProxy('/read_single_io', ReadSingleIO) + + value = read_single_io(0, 101) + + rospy.loginfo("[Read Single IO Converter] Value:" + str(value)) + + fanuc_io_state = FanucIOState() + fanuc_io_state.header.stamp = rospy.Time.now() + fanuc_io_state.type = msg.type + fanuc_io_state.address = msg.address + fanuc_io_state.value = value + + io_publisher.publish(value) + + rospy.loginfo("[Read Single IO Converter] IO Value: " + str(value)) + + except rospy.ServiceException as e: + # Log the error if the service call failed + rospy.logerr("[Read Single IO Converter] Service call failed: %s", str(e)) + + +def main(): + # Initialize the node + rospy.init_node('fanuc_read_single_io_converter_node') + + # Subscribe to the /set_payload topic + rospy.Subscriber('/msg_translator/read_single_io', FanucReadSingleIO, read_single_io_callback) + + # Spin the node + rospy.spin() + + +if __name__ == '__main__': + main() diff --git a/ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_robot_status_converter_node.py b/ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_robot_status_converter_node.py new file mode 100644 index 0000000..e3405b0 --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_robot_status_converter_node.py @@ -0,0 +1,57 @@ +#!/usr/bin/env python3 + +import rospy +from industrial_msgs.msg import RobotStatus, RobotMode +from fanuc_msg_translator_msgs.msg import FanucRobotStatus + +# Namespace of the node +ns = rospy.get_namespace() + +def robot_status_callback(msg): + """ + Callback function for the /robot_status topic. This function is called every time a new message is published on + the topic. The function converts the message from the industrial_msgs/RobotStatus message type to the custom + fanuc_msg_translator_msgs/FanucRobotStatus message type and publishes the converted message on the + /msg_translator/robot_status topic. + + :param msg: The message published on the /robot_status topic + :type msg: industrial_msgs/RobotStatus + """ + # Create a publisher for the result + result_publisher = rospy.Publisher(ns + 'bridge/robot_status', FanucRobotStatus, queue_size=10) + + # Create a new FanucRobotStatus message + robot_status = FanucRobotStatus() + + # Set the values of the new message + robot_status.header.stamp = msg.header.stamp + if msg.mode.val == RobotMode.MANUAL: + robot_status.tp_enabled.val = 1 + elif msg.mode.val == RobotMode.AUTO: + robot_status.tp_enabled.val = 0 + elif msg.mode.val == RobotMode.UNKNOWN: + robot_status.tp_enabled.val = -1 + robot_status.e_stopped = msg.e_stopped + robot_status.drives_powered = msg.drives_powered + robot_status.motion_possible = msg.motion_possible + robot_status.in_motion = msg.in_motion + robot_status.in_error = msg.in_error + robot_status.error_code = msg.error_code + + # Publish the new message + result_publisher.publish(robot_status) +def main(): + # Initialize the node + rospy.init_node('fanuc_robot_status_converter_node') + + # Subscribe to the /robot_status topic + rospy.Subscriber(ns + 'robot_status', RobotStatus, robot_status_callback) + + rospy.loginfo("[Robot Status Converter] Node initialized!") + + # Spin the node + rospy.spin() + + +if __name__ == '__main__': + main() diff --git a/ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_trajectory_converter_node.py b/ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_trajectory_converter_node.py new file mode 100644 index 0000000..7df8778 --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_trajectory_converter_node.py @@ -0,0 +1,230 @@ +#!/usr/bin/env python3 + +import rospy +import actionlib +from trajectory_msgs.msg import JointTrajectory +from control_msgs.msg import FollowJointTrajectoryAction, FollowJointTrajectoryGoal +from fanuc_msg_translator_msgs.msg import FanucTrajectoryConverterQueue, FanucTrajectoryConverterQueueItem, \ + FanucTrajectoryConverterCancel + +# Namespace of the node +ns = rospy.get_namespace() + +# Queue for all trajectories +queue = [] + +# Queue for all finished trajectories +cemetery = [] + +# Conntection to the action server of the fanuc_interface_node +client = actionlib.SimpleActionClient(ns + 'arm_controller/follow_joint_trajectory', FollowJointTrajectoryAction) + +# Publisher for the queue (for ROS-2) +queue_publisher = rospy.Publisher(ns + 'bridge/follow_joint_trajectory/queue', FanucTrajectoryConverterQueue, + queue_size=10) + +# Marker for 500 ms delay in the queue handling, activated when a trajectory is canceled +canceled_trajectory = False + + +def goal_callback(trajectory): + """ + This function is called when a new trajectory is received. It adds the trajectory to the queue. + + :param trajectory: The received trajectory message + """ + global queue + rospy.loginfo("[Trajectory Converter] Trajectory received!") + trajectory_wrapper = TrajectoryWrapper(trajectory) + queue.append(trajectory_wrapper) + + +def cancel_callback(cancel): + """ + This function is called when a cancel command is received. It deletes the trajectory from the queue if it is not + sent to the action server yet. If it is sent to the action server, the goal is canceled and the trajectory is + moved to the cemetery. + + :param cancel: The received cancel message + """ + global client + global queue + global cemetery + global canceled_trajectory + + rospy.loginfo("[Trajectory Converter] Cancel command received!") + + for trajectory_wrapper in queue: + if trajectory_wrapper.get_trajectory().header.stamp == cancel.received_time_stamp: + if trajectory_wrapper.get_status() == 0: + trajectory_wrapper.set_status(100) + cemetery.append(queue.pop(queue.index(trajectory_wrapper))) + elif trajectory_wrapper.get_status() == 1: + client.cancel_all_goals() + canceled_trajectory = True + break + + +def done_callback(state, result): + """ + This function is called when the action server is done with the trajectory. It sets the status of the trajectory + in the queue to 100, moves it to the cemetery and sets the action status of the trajectory to the state of + the action server. + + :param state: The state of the action server + :param result: The result of the action server + """ + global queue + + rospy.loginfo("[Trajectory Converter] Action server done! State: " + str(state)) + + queue[0].set_action_status(state) + + +class TrajectoryWrapper: + """ + This class is used to wrap the trajectory message and add two variables to it: status and action_status. + + status: The status of the trajectory in the queue. + action_status: The status of the action server of the fanuc_interface_node. + """ + + def __init__(self, trajectory=None): + """ + The constructor of the TrajectoryWrapper class. + + :param trajectory: The trajectory message to be wrapped + """ + self.trajectory = trajectory + self.status = 0 + self.action_status = -1 + + def set_action_status(self, status): + """ + This function sets the action status of the trajectory. + + :param status: The action status to be set + """ + self.action_status = status + + def get_action_status(self): + """ + This function returns the action status of the trajectory. + + :return: The action status of the trajectory + """ + return self.action_status + + def set_status(self, status): + """ + This function sets the status of the trajectory. + + :param status: The status to be set + """ + self.status = status + + def get_status(self): + """ + This function returns the status of the trajectory. + + :return: The status of the trajectory + """ + return self.status + + def get_trajectory(self): + """ + This function returns the trajectory message. + + :return: The trajectory message + """ + return self.trajectory + + +def main(): + """ + This is the main function of the node. It initializes the node, subscribes to the topics and runs the queue handler. + + The queue hanlder is called every 0.1 seconds (while loop). It works like a state machine for the queue. + Trajectories can have the following states: + 0: Not started + 1: In progress + 2: Finished + 100: Finished and in the cemetery + 101 - 129: Finished and in the cemetery (timer) + 130: Finished and removed from the cemetery (not published to /msg_translator/follow_joint_trajectory/queue anymore) + + The action status of the trajectory is saved in the variable action_status. The action status is the status of the + action server of the fanuc_interface_node. The action status is -1 until the action server reaches a final state for + this goal. Then it changes to the resulting state of the action server. The action status can be found here: + http://docs.ros.org/en/api/actionlib_msgs/html/msg/GoalStatus.html + + This function also publishes the queue and the cemetery to the topic /msg_translator/follow_joint_trajectory/queue. + """ + + global client + global queue_publisher + global queue + global cemetery + global canceled_trajectory + + rospy.init_node('fanuc_trajectory_converter_node') + + rospy.Subscriber(ns + 'bridge/follow_joint_trajectory/goal', JointTrajectory, goal_callback, queue_size=10) + rospy.Subscriber(ns + 'bridge/follow_joint_trajectory/cancel', FanucTrajectoryConverterCancel, cancel_callback, + queue_size=10) + + client.wait_for_server() + + rospy.loginfo("[Trajectory Converter] Node initialized!") + + while not rospy.is_shutdown(): + if len(queue) > 0: + if queue[0].get_status() == 0 \ + and client.get_state() != actionlib.GoalStatus.ACTIVE \ + and client.get_state() != actionlib.GoalStatus.PENDING: + goal = FollowJointTrajectoryGoal() + goal.trajectory = queue[0].get_trajectory() + queue[0].set_status(1) + if canceled_trajectory: + rospy.sleep(0.5) + canceled_trajectory = False + client.send_goal(goal, done_cb=done_callback) + elif queue[0].get_status() == 1: + if 2 <= client.get_state() <= 8: + queue[0].set_status(2) + queue[0].set_action_status(client.get_state()) + elif queue[0].get_status() == 2: + queue[0].set_status(100) + cemetery.append(queue.pop(0)) + + if len(cemetery) > 0: + for trajectory_wrapper in cemetery: + if trajectory_wrapper.get_status() == 130: + cemetery.remove(trajectory_wrapper) + else: + trajectory_wrapper.set_status(trajectory_wrapper.get_status() + 1) + + msg = FanucTrajectoryConverterQueue() + msg.header.stamp = rospy.Time.now() + + for trajectory_wrapper in cemetery: + goal = FanucTrajectoryConverterQueueItem() + goal.received_time_stamp = trajectory_wrapper.get_trajectory().header.stamp + goal.status_in_queue = trajectory_wrapper.get_status() + goal.status_on_server = trajectory_wrapper.get_action_status() + msg.goals.append(goal) + + for trajectory_wrapper in queue: + goal = FanucTrajectoryConverterQueueItem() + goal.received_time_stamp = trajectory_wrapper.get_trajectory().header.stamp + goal.status_in_queue = trajectory_wrapper.get_status() + goal.status_on_server = trajectory_wrapper.get_action_status() + msg.goals.append(goal) + + queue_publisher.publish(msg) + + rospy.sleep(0.1) + + +if __name__ == '__main__': + main() diff --git a/ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_write_single_io_converter_node.py b/ros1_noetic_core/fanuc_msg_translator/scripts/fanuc_write_single_io_converter_node.py new file mode 100644 index 0000000..e69de29 diff --git a/ros1_noetic_core/fanuc_msg_translator_msgs/CMakeLists.txt b/ros1_noetic_core/fanuc_msg_translator_msgs/CMakeLists.txt new file mode 100644 index 0000000..abfa7db --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator_msgs/CMakeLists.txt @@ -0,0 +1,213 @@ +cmake_minimum_required(VERSION 3.0.2) +project(fanuc_msg_translator_msgs) + +## Compile as C++11, supported in ROS Kinetic and newer +# add_compile_options(-std=c++11) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + roscpp + rospy + std_msgs + message_generation +) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend tag for "message_generation" +## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependency has been pulled in +## but can be declared for certainty nonetheless: +## * add a exec_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +add_message_files( + FILES + FanucTrajectoryConverterQueue.msg + FanucTrajectoryConverterQueueItem.msg + FanucTrajectoryConverterCancel.msg + FanucRobotStatus.msg + FanucRobotStatusTriState.msg + FanucPayloadNum.msg + FanucIOState.msg + FanucReadSingleIO.msg +) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +generate_messages( + DEPENDENCIES + std_msgs # Or other packages containing msgs +) + +################################################ +## Declare ROS dynamic reconfigure parameters ## +################################################ + +## To declare and build dynamic reconfigure parameters within this +## package, follow these steps: +## * In the file package.xml: +## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" +## * In this file (CMakeLists.txt): +## * add "dynamic_reconfigure" to +## find_package(catkin REQUIRED COMPONENTS ...) +## * uncomment the "generate_dynamic_reconfigure_options" section below +## and list every .cfg file to be processed + +## Generate dynamic reconfigure parameters in the 'cfg' folder +# generate_dynamic_reconfigure_options( +# cfg/DynReconf1.cfg +# cfg/DynReconf2.cfg +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if your package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES fanuc_msg_translator_msgs + CATKIN_DEPENDS message_runtime +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( +# include + ${catkin_INCLUDE_DIRS} +) + +## Declare a C++ library +# add_library(${PROJECT_NAME} +# src/${PROJECT_NAME}/fanuc_msg_translator_msgs.cpp +# ) + +## Add cmake target dependencies of the library +## as an example, code may need to be generated before libraries +## either from message generation or dynamic reconfigure +# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Declare a C++ executable +## With catkin_make all packages are built within a single CMake context +## The recommended prefix ensures that target names across packages don't collide +# add_executable(${PROJECT_NAME}_node src/fanuc_msg_translator_msgs_node.cpp) + +## Rename C++ executable without prefix +## The above recommended prefix causes long target names, the following renames the +## target back to the shorter version for ease of user use +## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" +# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") + +## Add cmake target dependencies of the executable +## same as for the library above +# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Specify libraries to link a library or executable target against +# target_link_libraries(${PROJECT_NAME}_node +# ${catkin_LIBRARIES} +# ) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# catkin_install_python(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html +# install(TARGETS ${PROJECT_NAME}_node +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark libraries for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html +# install(TARGETS ${PROJECT_NAME} +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_fanuc_msg_translator_msgs.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucIOState.msg b/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucIOState.msg new file mode 100644 index 0000000..1f17dce --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucIOState.msg @@ -0,0 +1,15 @@ +Header header + +# type : the type of the I/O to controll +# address : 1-base index +# value : 0 or 1 (for digital) + +uint32 type +uint32 address +uint32 value + +uint32 TYPE_DI=0 +uint32 TYPE_DO=1 +uint32 TYPE_RI=2 +uint32 TYPE_RO=3 +uint32 TYPE_FLAG=4 \ No newline at end of file diff --git a/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucPayloadNum.msg b/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucPayloadNum.msg new file mode 100644 index 0000000..633426c --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucPayloadNum.msg @@ -0,0 +1,3 @@ +Header header + +int16 payload_num \ No newline at end of file diff --git a/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucReadSingleIO.msg b/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucReadSingleIO.msg new file mode 100644 index 0000000..7ebdfc5 --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucReadSingleIO.msg @@ -0,0 +1,12 @@ +Header header + +# type : the type of the I/O to control +# address : 1-base index +uint32 type +uint32 address + +uint32 TYPE_DI=0 +uint32 TYPE_DO=1 +uint32 TYPE_RI=2 +uint32 TYPE_RO=3 +uint32 TYPE_FLAG=4 \ No newline at end of file diff --git a/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucRobotStatus.msg b/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucRobotStatus.msg new file mode 100644 index 0000000..ad3a297 --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucRobotStatus.msg @@ -0,0 +1,32 @@ +# The RobotStatus message contains low level status information +# that is specific to an industrial robot controller + +# The header frame ID is not used +Header header + +# The robot mode captures the operating mode of the robot. When in +# manual, remote motion is not possible. +fanuc_msg_translator_msgs/FanucRobotStatusTriState tp_enabled + +# Estop status: True if robot is e-stopped. The drives are disabled +# and motion is not possible. The e-stop condition must be acknowledged +# and cleared before any motion can begin. +fanuc_msg_translator_msgs/FanucRobotStatusTriState e_stopped + +# Drive power status: True if drives are powered. Motion commands will +# automatically enable the drives if required. Drive power is not requred +# for possible motion +fanuc_msg_translator_msgs/FanucRobotStatusTriState drives_powered + +# Motion enabled: True if robot motion is possible. +fanuc_msg_translator_msgs/FanucRobotStatusTriState motion_possible + +# Motion status: True if robot is in motion, otherwise false +fanuc_msg_translator_msgs/FanucRobotStatusTriState in_motion + +# Error status: True if there is an error condition on the robot. Motion may +# or may not be affected (see motion_possible) +fanuc_msg_translator_msgs/FanucRobotStatusTriState in_error + +# Error code: Vendor specific error code (non zero indicates error) +int32 error_code \ No newline at end of file diff --git a/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucRobotStatusTriState.msg b/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucRobotStatusTriState.msg new file mode 100644 index 0000000..6992e4c --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucRobotStatusTriState.msg @@ -0,0 +1,23 @@ + +# The tri-state captures boolean values with the additional state of unknown + +int8 val + +# enumerated values + +# Unknown or unavailable +int8 UNKNOWN=-1 + +# High state +int8 TRUE=1 +int8 ON=1 +int8 ENABLED=1 +int8 HIGH=1 +int8 CLOSED=1 + +# Low state +int8 FALSE=0 +int8 OFF=0 +int8 DISABLED=0 +int8 LOW=0 +int8 OPEN=0 diff --git a/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterCancel.msg b/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterCancel.msg new file mode 100644 index 0000000..2b78cbd --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterCancel.msg @@ -0,0 +1,3 @@ +std_msgs/Header header + +time received_time_stamp diff --git a/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterQueue.msg b/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterQueue.msg new file mode 100644 index 0000000..ea2d7e5 --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterQueue.msg @@ -0,0 +1,3 @@ +std_msgs/Header header + +fanuc_msg_translator_msgs/FanucTrajectoryConverterQueueItem[] goals diff --git a/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterQueueItem.msg b/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterQueueItem.msg new file mode 100644 index 0000000..809875e --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterQueueItem.msg @@ -0,0 +1,7 @@ +time received_time_stamp + +int16 status_in_queue + +int16 status_on_server + + diff --git a/ros1_noetic_core/fanuc_msg_translator_msgs/package.xml b/ros1_noetic_core/fanuc_msg_translator_msgs/package.xml new file mode 100644 index 0000000..1cb5df1 --- /dev/null +++ b/ros1_noetic_core/fanuc_msg_translator_msgs/package.xml @@ -0,0 +1,63 @@ + + + fanuc_msg_translator_msgs + 0.0.0 + The fanuc_msg_translator_msgs package + + + + + fanuc1 + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + message_generation + + + + + + message_runtime + + + + + catkin + rospy + rospy + rospy + std_msgs + + + + + + + + diff --git a/ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/__init__.py b/ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/fanuc_control_panel_connector.py b/ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/fanuc_control_panel_connector.py new file mode 100644 index 0000000..40c3fee --- /dev/null +++ b/ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/fanuc_control_panel_connector.py @@ -0,0 +1,92 @@ +import rclpy +from fanuc_msg_translator_msgs.msg import FanucTrajectoryConverterQueue, FanucTrajectoryConverterQueueItem, \ + FanucTrajectoryConverterCancel +from rclpy.node import Node +from sensor_msgs.msg import JointState +from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint +from std_msgs.msg import Header, Int16 + + +class FanucControlPanelConnector(Node): + def __init__(self): + super().__init__("fanuc_control_panel_connector") + self.currentPosition = JointTrajectoryPoint() + self.trajectoryPublisher = self.create_publisher(JointTrajectory, + '/fanuc_1/bridge/follow_joint_trajectory/goal', 10) + self.trajectoryPublisher2 = self.create_publisher(JointTrajectory, '/fanuc_2/bridge/follow_joint_trajectory/goal', 10) + self.jointStateSubscription = self.create_subscription(JointState, '/fanuc_1/joint_states', + self.joint_states_callback, + 10) + self.goalSubscription = self.create_subscription(JointTrajectoryPoint, 'goal_point', self.goal_points_callback, + 10) + self.goalListSubscription = self.create_subscription(JointTrajectory, 'goal_point_list', + self.goal_points_list_callback, + 10) + self.cancelTrajectorySubscription = self.create_subscription(Int16, 'cancel_trajectory', + self.cancel_trajectory_callback, 10) + + self.queueSubscription = self.create_subscription(FanucTrajectoryConverterQueue, '/fanuc_1/bridge' + '/follow_joint_trajectory' + '/queue', + self.queue_callback, 10) + self.queue = FanucTrajectoryConverterQueue() + + self.cancelPublisher = self.create_publisher(FanucTrajectoryConverterCancel, '/fanuc_1/bridge/follow_joint_trajectory/cancel', 10) + + def send_trajectory(self, trajectory): + self.trajectoryPublisher.publish(trajectory) + self.trajectoryPublisher2.publish(trajectory) + self.get_logger().info('Published JointTrajectory message') + + def joint_states_callback(self, joint_states): + self.currentPosition.positions = joint_states.position + + def goal_points_callback(self, goal_points): + goal_points.time_from_start.sec = 1 + trajectory = JointTrajectory() + trajectory.header.frame_id = 'base_link' + trajectory.header.stamp = self.get_clock().now().to_msg() + trajectory.joint_names = ['J1', 'J2', 'J3', 'J4', 'J5', 'J6'] + trajectory.points.append(self.currentPosition) + trajectory.points.append(goal_points) + + self.send_trajectory(trajectory) + + def goal_points_list_callback(self, goal_point_list): + trajectory = JointTrajectory() + trajectory.header = Header() + trajectory.header.frame_id = 'base_link' + trajectory.joint_names = ['J1', 'J2', 'J3', 'J4', 'J5', 'J6'] + + trajectory.points = (goal_point_list.points) + trajectory.points.insert(0, self.currentPosition) + self.send_trajectory(trajectory) + + def cancel_trajectory_callback(self, cancel_trajectory): + try: + cancel = FanucTrajectoryConverterCancel() + + self.get_logger().info('Canceling trajectory with index {}'.format(cancel_trajectory.data)) + self.get_logger().info('Queue ' + str(self.queue.goals)) + queue_item = self.queue.goals[cancel_trajectory.data] + + cancel.received_time_stamp = queue_item.received_time_stamp + + self.cancelPublisher.publish(cancel) + except IndexError: + self.get_logger().info('IndexError: No item with index {} in queue'.format(cancel_trajectory.data)) + + def queue_callback(self, queue): + self.queue = queue + + +def main(args=None): + rclpy.init(args=args) + node = FanucControlPanelConnector() + rclpy.spin(node) + node.destroy_node() + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/fanuc_control_panel_gui.py b/ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/fanuc_control_panel_gui.py new file mode 100644 index 0000000..6c602b6 --- /dev/null +++ b/ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/fanuc_control_panel_gui.py @@ -0,0 +1,112 @@ +import rclpy +import math +from rclpy.node import Node +from std_msgs.msg import Int16 + +import tkinter as tk +from tkinter import messagebox +from fanuc_msg_translator_msgs.msg import FanucPayloadNum +from trajectory_msgs.msg import JointTrajectoryPoint + + +class FanucControlPanelGUI(Node): + + def __init__(self): + super().__init__('fanuc_control_panel_gui') + self.publisher_goal_point = self.create_publisher(JointTrajectoryPoint, 'goal_point', 10) + self.publisher_int = self.create_publisher(FanucPayloadNum, '/fanuc_1/bridge/set_payload_num/goal', 10) + self.publisher_cancel_trajectory = self.create_publisher(Int16, 'cancel_trajectory', 10) + + # Initialize the Tkinter GUI + self.root = tk.Tk() + self.root.title('ROS2 GUI') + + # First segment: 6 input fields and a button + self.segment1 = tk.Frame(self.root) + self.segment1.pack(pady=10) + + self.input_fields = [] + for i in range(6): + label = tk.Label(self.segment1, text=f'Joint {i+1}: ') + label.grid(row=i, column=0, padx=10, pady=5) + + input_field = tk.Entry(self.segment1) + input_field.grid(row=i, column=1, padx=10, pady=5) + self.input_fields.append(input_field) + + button_float = tk.Button(self.segment1, text='Send Joint Angles', command=self.send_goal_pose) + button_float.grid(row=6, column=0, columnspan=2, pady=5) + + # Second segment: 1 input field and a button + self.segment2 = tk.Frame(self.root) + self.segment2.pack(pady=10) + + label_cancel = tk.Label(self.segment2, text='Cancel Trajectory: ') + label_cancel.grid(row=0, column=0, padx=10, pady=5) + + self.input_field_cancel = tk.Entry(self.segment2) + self.input_field_cancel.grid(row=0, column=1, padx=10, pady=5) + + button_cancel = tk.Button(self.segment2, text='Cancel', command=self.send_cancel_trajectory) + button_cancel.grid(row=1, column=0, columnspan=2, pady=5) + + # Second segment: 1 input field and a button + self.segment3 = tk.Frame(self.root) + self.segment3.pack(pady=10) + + label_int = tk.Label(self.segment3, text='Payload Nr: ') + label_int.grid(row=0, column=0, padx=10, pady=5) + + self.input_field_int = tk.Entry(self.segment3) + self.input_field_int.grid(row=0, column=1, padx=10, pady=5) + + button_int = tk.Button(self.segment3, text='Send Payload Nr', command=self.send_payload_nr) + button_int.grid(row=1, column=0, columnspan=2, pady=5) + + # Start the ROS2 node + self.start() + + def send_goal_pose(self): + try: + values = [float(field.get())*(2*math.pi)/360 for field in self.input_fields] + msg = JointTrajectoryPoint() + msg.positions = values + self.publisher_goal_point.publish(msg) + self.get_logger().info(f'Goal position: {values}') + except ValueError: + messagebox.showerror('Error', 'Invalid float value') + + def send_payload_nr(self): + try: + value = int(self.input_field_int.get()) + fanuc_payload_num = FanucPayloadNum() + fanuc_payload_num.payload_num = value + self.publisher_int.publish(fanuc_payload_num) + self.get_logger().info(f'Payload set to Nr: {value}') + except ValueError: + messagebox.showerror('Error', 'Invalid integer value') + + def send_cancel_trajectory(self): + try: + value = int(self.input_field_cancel.get()) + msg = Int16() + msg.data = value + self.publisher_cancel_trajectory.publish(msg) + self.get_logger().info(f'Cancel trajectory: {value}') + except ValueError: + messagebox.showerror('Error', 'Invalid integer value') + + def start(self): + self.root.mainloop() + + +def main(args=None): + rclpy.init(args=args) + gui_node = FanucControlPanelGUI() + rclpy.spin(gui_node) + gui_node.destroy_node() + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/fanuc_control_panel_status_viewer.py b/ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/fanuc_control_panel_status_viewer.py new file mode 100644 index 0000000..9ce71c5 --- /dev/null +++ b/ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/fanuc_control_panel_status_viewer.py @@ -0,0 +1,97 @@ +import tkinter as tk +import rclpy +from rclpy.node import Node +from fanuc_msg_translator_msgs.msg import FanucRobotStatus, FanucRobotStatusTriState + + +class RobotStatusSubscriber(Node): + def __init__(self): + super().__init__('robot_status_subscriber') + self.subscription = self.create_subscription( + FanucRobotStatus, + '/fanuc_1/bridge/robot_status', + self.robot_status_callback, + 10 + ) + # Create the GUI window + self.window = tk.Tk() + self.window.title('Robot Status') + self.labels = [] + self.create_gui() + + + + + + + def robot_status_callback(self, msg): + self.get_logger().info("Values: " + str(msg)) + # Extract values from the FanucRobotStatus message + tp_enabled = msg.tp_enabled.val + e_stopped = msg.e_stopped.val + drives_powered = msg.drives_powered.val + motion_possible = msg.motion_possible.val + in_motion = msg.in_motion.val + in_error = msg.in_error.val + error_code = msg.error_code + + values = [tp_enabled, e_stopped, drives_powered, motion_possible, + in_motion, in_error, error_code] + + for label in self.labels: + label.config(text=str(values[self.labels.index(label)])) + if self.labels.index(label) < 5: + label.config(fg='green' if values[self.labels.index(label)] == 1 else 'red') + + self.window.update() + + + + + + + + + + def create_gui(self): + tk.Label(self.window, text='TP Enabled').grid(row=0, column=0, sticky='e') + tk.Label(self.window, text='E-Stopped').grid(row=1, column=0, sticky='e') + tk.Label(self.window, text='Drives Powered').grid(row=2, column=0, sticky='e') + tk.Label(self.window, text='Motion Possible').grid(row=3, column=0, sticky='e') + tk.Label(self.window, text='In Motion').grid(row=4, column=0, sticky='e') + tk.Label(self.window, text='In Error').grid(row=5, column=0, sticky='e') + tk.Label(self.window, text='Error Code').grid(row=6, column=0, sticky='e') + + self.labels.append(tk.Label(self.window, text='0')) + self.labels[0].grid(row=0, column=1, sticky='w') + self.labels.append(tk.Label(self.window, text='0')) + self.labels[1].grid(row=1, column=1, sticky='w') + self.labels.append(tk.Label(self.window, text='0')) + self.labels[2].grid(row=2, column=1, sticky='w') + self.labels.append(tk.Label(self.window, text='0')) + self.labels[3].grid(row=3, column=1, sticky='w') + self.labels.append(tk.Label(self.window, text='0')) + self.labels[4].grid(row=4, column=1, sticky='w') + self.labels.append(tk.Label(self.window, text='0')) + self.labels[5].grid(row=5, column=1, sticky='w') + self.labels.append(tk.Label(self.window, text='0')) + self.labels[6].grid(row=6, column=1, sticky='w') + + self.window.update() + + + + + + +def main(args=None): + rclpy.init(args=args) + subscriber = RobotStatusSubscriber() + rclpy.spin(subscriber) + subscriber.destroy_node() + rclpy.shutdown() + + +if __name__ == '__main__': + main() + diff --git a/ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/fanuc_control_panel_trajectory_queue.py b/ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/fanuc_control_panel_trajectory_queue.py new file mode 100644 index 0000000..2e98cea --- /dev/null +++ b/ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/fanuc_control_panel_trajectory_queue.py @@ -0,0 +1,64 @@ +import rclpy +from rclpy.node import Node +from fanuc_msg_translator_msgs.msg import FanucTrajectoryConverterQueue, FanucTrajectoryConverterQueueItem +import tkinter as tk +from tkinter import ttk + + +class FanucGUI(Node): + + def __init__(self): + super().__init__('fanuc_gui') + self.subscription = self.create_subscription( + FanucTrajectoryConverterQueue, + '/fanuc_1/bridge/follow_joint_trajectory/queue', + self.queue_callback, + 10 + ) + + + self.root = tk.Tk() + self.treeview = ttk.Treeview(self.root) + self.treeview['columns'] = ('Nr', 'time_stamp_s', 'time_stamp_ns', 'status_in_queue', 'status_on_server') + + self.treeview.column('#0', width=0, stretch=tk.NO) + self.treeview.column('Nr', anchor=tk.CENTER, width=50) + self.treeview.column('time_stamp_s', anchor=tk.CENTER, width=150) + self.treeview.column('time_stamp_ns', anchor=tk.CENTER, width=150) + self.treeview.column('status_in_queue', anchor=tk.CENTER, width=150) + self.treeview.column('status_on_server', anchor=tk.CENTER, width=150) + + self.treeview.heading('#0', text='', anchor=tk.CENTER) + self.treeview.heading('Nr', text='Nr', anchor=tk.CENTER) + self.treeview.heading('time_stamp_s', text='Time Stamp [s]', anchor=tk.CENTER) + self.treeview.heading('time_stamp_ns', text='Time Stamp [ns]', anchor=tk.CENTER) + self.treeview.heading('status_in_queue', text='Status in Queue', anchor=tk.CENTER) + self.treeview.heading('status_on_server', text='Status on Server', anchor=tk.CENTER) + + self.treeview.pack() + + def queue_callback(self, msg): + self.treeview.delete(*self.treeview.get_children()) # Clear the table + + for item in msg.goals: + nr = msg.goals.index(item) + time_stamp_s = item.received_time_stamp.sec + time_stamp_ns = item.received_time_stamp.nanosec + status_in_queue = item.status_in_queue + status_on_server = item.status_on_server + + self.treeview.insert('', tk.END, text='', values=(nr, time_stamp_s, time_stamp_ns, status_in_queue, status_on_server)) + self.root.update() # Update the GUI + + + +def main(args=None): + rclpy.init(args=args) + fanuc_gui = FanucGUI() + rclpy.spin(fanuc_gui) + fanuc_gui.destroy_node() + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/goal_point_generator.py b/ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/goal_point_generator.py new file mode 100644 index 0000000..893649a --- /dev/null +++ b/ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/goal_point_generator.py @@ -0,0 +1,45 @@ +import rclpy +from rclpy.node import Node +from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint +from std_msgs.msg import Header +import random + + +class RandomJointTrajectoryNode(Node): + + def __init__(self): + super().__init__('random_joint_trajectory_node') + self.publisher_ = self.create_publisher(JointTrajectoryPoint, '/goal_point', 10) + self.timer_ = self.create_timer(1.0, self.timer_callback) # Publish every 1 second + + def timer_callback(self): + joint_names = ['joint1', 'joint2', 'joint3', 'joint4', 'joint5', 'joint6'] + + trajectory = JointTrajectory() + trajectory.header = Header() + trajectory.header.stamp = self.get_clock().now().to_msg() + + trajectory.joint_names = joint_names + + point = JointTrajectoryPoint() + point.time_from_start.sec = 0 + point.time_from_start.nanosec = 0 + + # Generate random positions for each joint + point.positions = [random.uniform(-3.14, 3.14) for _ in range(len(joint_names))] + + trajectory.points = [point] + + self.publisher_.publish(point) + + +def main(args=None): + rclpy.init(args=args) + node = RandomJointTrajectoryNode() + rclpy.spin(node) + node.destroy_node() + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/my_first_node.py b/ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/my_first_node.py new file mode 100644 index 0000000..513dee2 --- /dev/null +++ b/ros2_basic_demo_gui/fanuc_control_panel/fanuc_control_panel/my_first_node.py @@ -0,0 +1,27 @@ +import rclpy +from rclpy.node import Node + + +class myNode(Node): # Class that inherits from node + def __init__(self): + super().__init__("First_Node") # Initialise the node and give it the name which will be visable in ROS2 + self.create_timer(1.0, self.timer_callback) + + def timer_callback(self): + self.get_logger().info("Hello") + + +def main(args=None): + # Initalise ROS2 communications + rclpy.init(args=args) + + # Start the node + node = myNode() + rclpy.spin(node) + + # Shutdown ROS2 communication + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/ros2_basic_demo_gui/fanuc_control_panel/launch/control_panel.launch.py b/ros2_basic_demo_gui/fanuc_control_panel/launch/control_panel.launch.py new file mode 100644 index 0000000..5dddbbd --- /dev/null +++ b/ros2_basic_demo_gui/fanuc_control_panel/launch/control_panel.launch.py @@ -0,0 +1,26 @@ +from launch import LaunchDescription +from launch_ros.actions import Node + +def generate_launch_description(): + return LaunchDescription([ + Node( + package='fanuc_control_panel', + executable='fanuc_control_panel_connector', + name='fanuc_control_panel_connector' + ), + Node( + package='fanuc_control_panel', + executable='fanuc_control_panel_gui', + name='fanuc_control_panel_gui' + ), + Node( + package='fanuc_control_panel', + executable='fanuc_control_panel_status_viewer', + name='fanuc_control_panel_status_viewer' + ), + Node( + package='fanuc_control_panel', + executable='fanuc_control_panel_trajectory_queue', + name='fanuc_control_panel_trajectory_queue' + ) + ]) \ No newline at end of file diff --git a/ros2_basic_demo_gui/fanuc_control_panel/package.xml b/ros2_basic_demo_gui/fanuc_control_panel/package.xml new file mode 100644 index 0000000..a8c0115 --- /dev/null +++ b/ros2_basic_demo_gui/fanuc_control_panel/package.xml @@ -0,0 +1,20 @@ + + + + fanuc_control_panel + 0.0.0 + TODO: Package description + christoph + TODO: License declaration + + ament_copyright + ament_flake8 + ament_pep257 + python3-pytest + + ros2launch + + + ament_python + + diff --git a/ros2_basic_demo_gui/fanuc_control_panel/resource/fanuc_control_panel b/ros2_basic_demo_gui/fanuc_control_panel/resource/fanuc_control_panel new file mode 100644 index 0000000..e69de29 diff --git a/ros2_basic_demo_gui/fanuc_control_panel/setup.cfg b/ros2_basic_demo_gui/fanuc_control_panel/setup.cfg new file mode 100644 index 0000000..b6561db --- /dev/null +++ b/ros2_basic_demo_gui/fanuc_control_panel/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/fanuc_control_panel +[install] +install_scripts=$base/lib/fanuc_control_panel diff --git a/ros2_basic_demo_gui/fanuc_control_panel/setup.py b/ros2_basic_demo_gui/fanuc_control_panel/setup.py new file mode 100644 index 0000000..3903231 --- /dev/null +++ b/ros2_basic_demo_gui/fanuc_control_panel/setup.py @@ -0,0 +1,32 @@ +from setuptools import setup +import os +from glob import glob + +package_name = 'fanuc_control_panel' + +setup( + name=package_name, + version='0.0.0', + packages=[package_name], + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + (os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*launch.[pxy][yma]*'))) + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='christoph', + maintainer_email='christoph.andres@stud.unileoben.ac.at', + description='TODO: Package description', + license='TODO: License declaration', + tests_require=['pytest'], + entry_points={ + 'console_scripts': [ + "fanuc_control_panel_connector = fanuc_control_panel.fanuc_control_panel_connector:main", + "fanuc_control_panel_gui = fanuc_control_panel.fanuc_control_panel_gui:main", + "fanuc_control_panel_status_viewer = fanuc_control_panel.fanuc_control_panel_status_viewer:main", + "fanuc_control_panel_trajectory_queue = fanuc_control_panel.fanuc_control_panel_trajectory_queue:main" + ], + }, +) diff --git a/ros2_basic_demo_gui/fanuc_control_panel/test/test_copyright.py b/ros2_basic_demo_gui/fanuc_control_panel/test/test_copyright.py new file mode 100644 index 0000000..97a3919 --- /dev/null +++ b/ros2_basic_demo_gui/fanuc_control_panel/test/test_copyright.py @@ -0,0 +1,25 @@ +# Copyright 2015 Open Source Robotics Foundation, Inc. +# +# 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. + +from ament_copyright.main import main +import pytest + + +# Remove the `skip` decorator once the source file(s) have a copyright header +@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.') +@pytest.mark.copyright +@pytest.mark.linter +def test_copyright(): + rc = main(argv=['.', 'test']) + assert rc == 0, 'Found errors' diff --git a/ros2_basic_demo_gui/fanuc_control_panel/test/test_flake8.py b/ros2_basic_demo_gui/fanuc_control_panel/test/test_flake8.py new file mode 100644 index 0000000..27ee107 --- /dev/null +++ b/ros2_basic_demo_gui/fanuc_control_panel/test/test_flake8.py @@ -0,0 +1,25 @@ +# Copyright 2017 Open Source Robotics Foundation, Inc. +# +# 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. + +from ament_flake8.main import main_with_errors +import pytest + + +@pytest.mark.flake8 +@pytest.mark.linter +def test_flake8(): + rc, errors = main_with_errors(argv=[]) + assert rc == 0, \ + 'Found %d code style errors / warnings:\n' % len(errors) + \ + '\n'.join(errors) diff --git a/ros2_basic_demo_gui/fanuc_control_panel/test/test_pep257.py b/ros2_basic_demo_gui/fanuc_control_panel/test/test_pep257.py new file mode 100644 index 0000000..b234a38 --- /dev/null +++ b/ros2_basic_demo_gui/fanuc_control_panel/test/test_pep257.py @@ -0,0 +1,23 @@ +# Copyright 2015 Open Source Robotics Foundation, Inc. +# +# 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. + +from ament_pep257.main import main +import pytest + + +@pytest.mark.linter +@pytest.mark.pep257 +def test_pep257(): + rc = main(argv=['.', 'test']) + assert rc == 0, 'Found code style errors / warnings' diff --git a/ros2_fanuc_web_connector/fanuc_web_connector/fanuc_web_connector/__init__.py b/ros2_fanuc_web_connector/fanuc_web_connector/fanuc_web_connector/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/ros2_fanuc_web_connector/fanuc_web_connector/fanuc_web_connector/replay_manager.py b/ros2_fanuc_web_connector/fanuc_web_connector/fanuc_web_connector/replay_manager.py new file mode 100644 index 0000000..565fcfe --- /dev/null +++ b/ros2_fanuc_web_connector/fanuc_web_connector/fanuc_web_connector/replay_manager.py @@ -0,0 +1,307 @@ +import time +import pymongo +from bson import ObjectId + +import rclpy +from builtin_interfaces.msg import Time +from rclpy.node import Node +from rosidl_runtime_py import convert +from sensor_msgs.msg import JointState +from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint +from fanuc_web_connector_msgs.msg import TrajectoryDB, TrajectoryDBItem, RecordTrajectory, ReplayTrajectory +import json + + +class ReplayManager(Node): + def __init__(self): + super().__init__('replay_manager') + + self.mongo_client = pymongo.MongoClient('localhost', 27017) + self.mongo_db = self.mongo_client['ros_web_service_demo'] + self.mongo_collection = self.mongo_db['recorded_trajectories'] + + self.fanuc_1_joint_states = JointState() + self.fanuc_2_joint_states = JointState() + + self.fanuc_1_record_name = None + self.fanuc_2_record_name = None + + self.fanuc_1_record = False + self.fanuc_2_record = False + + self.fanuc_1_trajectory = JointTrajectory() + self.fanuc_2_trajectory = JointTrajectory() + + self.db_trajectories = [] + + self.pair_trajectory = None + + self.fanuc_1_waiting_for_fanuc_2 = False + self.fanuc_2_waiting_for_fanuc_1 = False + + self.timer_pair_replay_trajectory = None + self.timer_pair_replay_trajectory_counter = 0 + + self.timer_db_publisher = self.create_timer(1.0, self.db_publisher_callback) + + self.publisher_fanuc_1_goal_trajectory = self.create_publisher(JointTrajectory, '/fanuc_1/goal_trajectory', 10) + self.publisher_fanuc_2_goal_trajectory = self.create_publisher(JointTrajectory, '/fanuc_2/goal_trajectory', 10) + + self.subscription_fanuc_1_joint_states = self.create_subscription(JointState, '/fanuc_1/joint_states', + self.fanuc_1_joint_states_callback, + 10) + self.subscription_fanuc_2_joint_states = self.create_subscription(JointState, '/fanuc_2/joint_states', + self.fanuc_2_joint_states_callback, + 10) + + self.publisher_trajectory_db = self.create_publisher(TrajectoryDB, '/trajectory_db', 10) + + self.subscription_record_trajectory = self.create_subscription(RecordTrajectory, '/record_trajectory', + self.record_trajectory_callback, + 10) + + self.subscription_replay_trajectory = self.create_subscription(ReplayTrajectory, '/replay_trajectory', + self.replay_trajectory_callback, + 10) + + + + + self.get_logger().info('Node initialized') + + def db_publisher_callback(self): + cursor = self.mongo_collection.find({}, {"_id": 1, "trajectory_name": 1}) + self.db_trajectories = [] + + for document in cursor: + item = TrajectoryDBItem() + item.trajectory_name = document["trajectory_name"] + item.trajectory_id = str(document["_id"]) + self.db_trajectories.append(item) + + trajectory_db = TrajectoryDB() + trajectory_db.header.stamp = self.get_clock().now().to_msg() + trajectory_db.trajectories = self.db_trajectories + self.publisher_trajectory_db.publish(trajectory_db) + + + + def record_trajectory_callback(self, record_trajectory): + self.get_logger().info('RecordTrajectory message received') + if self.fanuc_1_record_name is None and self.fanuc_2_record_name is None and record_trajectory.record: + if record_trajectory.robot_name == "fanuc_1": + self.fanuc_1_record_name = record_trajectory.trajectory_name + self.fanuc_1_record = True + self.fanuc_1_trajectory = JointTrajectory() + self.fanuc_1_trajectory.joint_names = ['J1', 'J2', 'J3', 'J4', 'J5', 'J6'] + + elif record_trajectory.robot_name == "fanuc_2": + self.fanuc_2_record_name = record_trajectory.trajectory_name + self.fanuc_2_record = True + self.fanuc_2_trajectory = JointTrajectory() + self.fanuc_2_trajectory.joint_names = ['J1', 'J2', 'J3', 'J4', 'J5', 'J6'] + + elif record_trajectory.record is False: + if record_trajectory.robot_name == "fanuc_1": + self.fanuc_1_record = False + elif record_trajectory.robot_name == "fanuc_2": + self.fanuc_2_record = False + + def pair_replay_trajectory_callback(self): + if self.timer_pair_replay_trajectory_counter < 150: + self.timer_pair_replay_trajectory_counter += 1 + if self.pair_trajectory is not None: + if not self.fanuc_1_waiting_for_fanuc_2 and not self.fanuc_2_waiting_for_fanuc_1: + time.sleep(0.4) + self.publisher_fanuc_1_goal_trajectory.publish(self.pair_trajectory) + self.publisher_fanuc_2_goal_trajectory.publish(self.pair_trajectory) + self.get_logger().info('Trajectory published for fanuc_1 and fanuc_2') + self.pair_trajectory = None + self.timer_pair_replay_trajectory_counter = 0 + self.timer_pair_replay_trajectory.cancel() + + else: + self.get_logger().info('Trajectory not published for fanuc_1 and fanuc_2') + self.pair_trajectory = None + self.fanuc_1_waiting_for_fanuc_2 = False + self.fanuc_2_waiting_for_fanuc_1 = False + self.timer_pair_replay_trajectory_counter = 0 + self.timer_pair_replay_trajectory.cancel() + + def replay_trajectory_callback(self, replay_trajectory): + if len(replay_trajectory.robot_names) == 1: + if replay_trajectory.robot_names[0] == "fanuc_1": + self.get_logger().info('ReplayTrajectory message received') + self.get_logger().info('Replaying trajectory for fanuc_1') + + trajectory = self.load_trajectory_from_db(replay_trajectory.trajectory_id) + if trajectory is not None: + self.publisher_fanuc_1_goal_trajectory.publish(trajectory) + self.get_logger().info('Trajectory published for fanuc_1') + else: + self.get_logger().info('Trajectory not found in DB') + elif replay_trajectory.robot_names[0] == "fanuc_2": + self.get_logger().info('ReplayTrajectory message received') + self.get_logger().info('Replaying trajectory for fanuc_2') + + trajectory = self.load_trajectory_from_db(replay_trajectory.trajectory_id) + if trajectory is not None: + self.publisher_fanuc_2_goal_trajectory.publish(trajectory) + self.get_logger().info('Trajectory published for fanuc_2') + else: + self.get_logger().info('Trajectory not found in DB') + else: + if (replay_trajectory.robot_names[0] == "fanuc_1" and replay_trajectory.robot_names[1] == "fanuc_2") or \ + (replay_trajectory.robot_names[0] == "fanuc_2" and replay_trajectory.robot_names[1] == "fanuc_1"): + self.get_logger().info('ReplayTrajectory message received for pair') + pair_trajectory = self.load_trajectory_from_db(replay_trajectory.trajectory_id) + if pair_trajectory is not None: + temp_trajectory = JointTrajectory() + temp_trajectory.joint_names = ['J1', 'J2', 'J3', 'J4', 'J5', 'J6'] + temp_trajectory.points.append(pair_trajectory.points[0]) + self.publisher_fanuc_1_goal_trajectory.publish(temp_trajectory) + self.publisher_fanuc_2_goal_trajectory.publish(temp_trajectory) + self.fanuc_1_waiting_for_fanuc_2 = True + self.fanuc_2_waiting_for_fanuc_1 = True + self.pair_trajectory = pair_trajectory + + self.timer_pair_replay_trajectory = self.create_timer(0.1, self.pair_replay_trajectory_callback) + + self.get_logger().info('Trajectory published for pair') + + + else: + self.get_logger().info('ReplayTrajectory message received') + self.get_logger().info('Robot names are not correct') + + def fanuc_1_joint_states_callback(self, joint_states): + self.get_logger().info('JointState message received') + self.fanuc_1_joint_states = joint_states + if self.fanuc_1_record_name is not None: + if self.fanuc_1_record: + joint_trajectory_point = JointTrajectoryPoint() + joint_trajectory_point.time_from_start.sec = joint_states.header.stamp.sec + joint_trajectory_point.time_from_start.nanosec = joint_states.header.stamp.nanosec + joint_trajectory_point.positions = joint_states.position + self.fanuc_1_trajectory.points.append(joint_trajectory_point) + else: + first_time_stamp = self.fanuc_1_trajectory.points[0].time_from_start + final_trajectory = JointTrajectory() + for point in self.fanuc_1_trajectory.points: + new_point = JointTrajectoryPoint() + new_point.positions = point.positions + + new_time_stamp = self.calculate_time_difference(first_time_stamp, point.time_from_start) + new_point.time_from_start.sec = new_time_stamp.sec + 1 + new_point.time_from_start.nanosec = new_time_stamp.nanosec + final_trajectory.points.append(new_point) + self.save_joint_trajectory(final_trajectory, (str(self.fanuc_1_record_name))) + self.fanuc_1_record_name = None + self.fanuc_1_trajectory = JointTrajectory() + elif self.pair_trajectory is not None: + self.get_logger().info('Publishing pair trajectory') + self.get_logger().info('Fanuc_1 waiting for Fanuc_2: ' + str(self.fanuc_1_waiting_for_fanuc_2)) + self.get_logger().info('Fanuc_2 waiting for Fanuc_1: ' + str(self.fanuc_2_waiting_for_fanuc_1)) + + if self.fanuc_2_waiting_for_fanuc_1 and self.confiuration_reached(joint_states, self.pair_trajectory.points[0]): + self.fanuc_2_waiting_for_fanuc_1 = False + + def fanuc_2_joint_states_callback(self, joint_states): + self.get_logger().info('JointState message received') + self.fanuc_2_joint_states = joint_states + if self.fanuc_2_record_name is not None: + if self.fanuc_2_record: + joint_trajectory_point = JointTrajectoryPoint() + joint_trajectory_point.time_from_start.sec = joint_states.header.stamp.sec + joint_trajectory_point.time_from_start.nanosec = joint_states.header.stamp.nanosec + joint_trajectory_point.positions = joint_states.position + self.fanuc_2_trajectory.points.append(joint_trajectory_point) + else: + first_time_stamp = self.fanuc_2_trajectory.points[0].time_from_start + final_trajectory = JointTrajectory() + for point in self.fanuc_2_trajectory.points: + new_point = JointTrajectoryPoint() + new_point.positions = point.positions + + new_time_stamp = self.calculate_time_difference(first_time_stamp, point.time_from_start) + new_point.time_from_start.sec = new_time_stamp.sec + 1 + new_point.time_from_start.nanosec = new_time_stamp.nanosec + final_trajectory.points.append(new_point) + self.save_joint_trajectory(final_trajectory, (str(self.fanuc_2_record_name))) + self.fanuc_2_record_name = None + self.fanuc_2_trajectory = JointTrajectory() + elif self.pair_trajectory is not None: + self.get_logger().info('Publishing pair trajectory') + + if self.fanuc_1_waiting_for_fanuc_2 and self.confiuration_reached(joint_states, self.pair_trajectory.points[0]): + self.fanuc_1_waiting_for_fanuc_2 = False + + def save_joint_trajectory(self, joint_trajectory, trajectory_name): + try: + serialized_states = [] + for state in joint_trajectory.points: + serialized_states.append(convert.message_to_ordereddict(state)) + + self.mongo_collection.insert_one({"trajectory_name": trajectory_name, "trajectory": serialized_states}) + + except Exception as e: + self.get_logger().error(f"Failed to save joint states to file: {str(e)}") + + def load_trajectory_from_db(self, trajectory_id): + try: + entry = self.mongo_collection.find_one({"_id": ObjectId(trajectory_id)}) + serialized_states = entry["trajectory"] + + trajectory = JointTrajectory() + trajectory.header.stamp = self.get_clock().now().to_msg() + trajectory.header.frame_id = "base_link" + trajectory.joint_names = ["J1", "J2", "J3", "J4", "J5", "J6"] + + for serialized_state in serialized_states: + state = JointTrajectoryPoint() + state.positions = serialized_state["positions"] + state.time_from_start.sec = serialized_state["time_from_start"]["sec"] + state.time_from_start.nanosec = serialized_state["time_from_start"]["nanosec"] + trajectory.points.append(state) + + return trajectory + + except Exception as e: + self.get_logger().error(f"Failed to load joint states from file: {str(e)}") + return None + + + + def calculate_time_difference(self, zero_time_stamp, current_time): + # Convert the given times into milliseconds + time1_ms = (zero_time_stamp.sec * 1000) + (zero_time_stamp.nanosec // 1000000) + time2_ms = (current_time.sec * 1000) + (current_time.nanosec // 1000000) + + # Calculate the time difference in milliseconds + time_diff_ms = time2_ms - time1_ms + + # Convert the time difference back to seconds and nanoseconds + diff_time = Time() + + diff_time.sec = time_diff_ms // 1000 + diff_time.nanosec = (time_diff_ms % 1000) * 1000000 + + return diff_time + + def confiuration_reached(self, joint_states, target_joint_states): + for i in range(len(joint_states.position)): + if abs(joint_states.position[i] - target_joint_states.positions[i]) > 0.1: + return False + return True + + +def main(args=None): + rclpy.init(args=args) + node = ReplayManager() + rclpy.spin(node) + node.destroy_node() + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/ros2_fanuc_web_connector/fanuc_web_connector/fanuc_web_connector/trajectory_composer.py b/ros2_fanuc_web_connector/fanuc_web_connector/fanuc_web_connector/trajectory_composer.py new file mode 100644 index 0000000..c61302d --- /dev/null +++ b/ros2_fanuc_web_connector/fanuc_web_connector/fanuc_web_connector/trajectory_composer.py @@ -0,0 +1,53 @@ +import rclpy + +from rclpy.node import Node +from sensor_msgs.msg import JointState +from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint + + +class TrajectoryComposer(Node): + def __init__(self): + super().__init__("trajectory_composer") + self.currentConfiguration = JointTrajectoryPoint() + self.jointStateSubscription = self.create_subscription(JointState, 'joint_states', + self.joint_states_callback, + 10) + self.goalSubscription = self.create_subscription(JointTrajectory, 'goal_trajectory', + self.goal_trajectory_callback, + 10) + self.trajectoryGoalPublisher = self.create_publisher(JointTrajectory, + 'bridge/follow_joint_trajectory/goal', 10) + + def joint_states_callback(self, joint_states): + self.get_logger().info('JointState message received') + self.currentConfiguration.positions = joint_states.position + + def goal_trajectory_callback(self, goal_trajectory): + trajectory = JointTrajectory() + trajectory.header.frame_id = 'base_link' + trajectory.header.stamp = self.get_clock().now().to_msg() + trajectory.joint_names = ['J1', 'J2', 'J3', 'J4', 'J5', 'J6'] + + if goal_trajectory.points[0].time_from_start.sec == 0 and goal_trajectory.points[ + 0].time_from_start.nanosec == 0: + self.get_logger().info('Wrong') + trajectory.points = goal_trajectory.points + else: + self.get_logger().info('Right') + trajectory.points = goal_trajectory.points + trajectory.points.insert(0, self.currentConfiguration) + + self.trajectoryGoalPublisher.publish(trajectory) + self.get_logger().info('Published JointTrajectory message') + + +def main(args=None): + rclpy.init(args=args) + node = TrajectoryComposer() + rclpy.spin(node) + node.destroy_node() + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/ros2_fanuc_web_connector/fanuc_web_connector/launch/web_connector.launch.py b/ros2_fanuc_web_connector/fanuc_web_connector/launch/web_connector.launch.py new file mode 100644 index 0000000..69d2d5d --- /dev/null +++ b/ros2_fanuc_web_connector/fanuc_web_connector/launch/web_connector.launch.py @@ -0,0 +1,28 @@ +from launch import LaunchDescription +from launch_ros.actions import Node + +def generate_launch_description(): + return LaunchDescription([ + Node( + package='fanuc_web_connector', + executable='replay_manager', + name='replay_manager' + ), + Node( + package='fanuc_web_connector', + executable='trajectory_composer', + name='trajectory_composer', + namespace='fanuc_1' + ), + Node( + package='fanuc_web_connector', + executable='trajectory_composer', + name='trajectory_composer', + namespace='fanuc_2' + ), + Node( + package='rosbridge_server', + executable='rosbridge_websocket', + name='rosbridge_websocket' + ) + ]) \ No newline at end of file diff --git a/ros2_fanuc_web_connector/fanuc_web_connector/package.xml b/ros2_fanuc_web_connector/fanuc_web_connector/package.xml new file mode 100644 index 0000000..94710ff --- /dev/null +++ b/ros2_fanuc_web_connector/fanuc_web_connector/package.xml @@ -0,0 +1,20 @@ + + + + fanuc_web_connector + 0.0.0 + TODO: Package description + christoph + TODO: License declaration + + rclpy + + ament_copyright + ament_flake8 + ament_pep257 + python3-pytest + + + ament_python + + diff --git a/ros2_fanuc_web_connector/fanuc_web_connector/resource/fanuc_web_connector b/ros2_fanuc_web_connector/fanuc_web_connector/resource/fanuc_web_connector new file mode 100644 index 0000000..e69de29 diff --git a/ros2_fanuc_web_connector/fanuc_web_connector/setup.cfg b/ros2_fanuc_web_connector/fanuc_web_connector/setup.cfg new file mode 100644 index 0000000..de7b925 --- /dev/null +++ b/ros2_fanuc_web_connector/fanuc_web_connector/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/fanuc_web_connector +[install] +install_scripts=$base/lib/fanuc_web_connector diff --git a/ros2_fanuc_web_connector/fanuc_web_connector/setup.py b/ros2_fanuc_web_connector/fanuc_web_connector/setup.py new file mode 100644 index 0000000..a422430 --- /dev/null +++ b/ros2_fanuc_web_connector/fanuc_web_connector/setup.py @@ -0,0 +1,31 @@ +import os +from glob import glob + +from setuptools import find_packages, setup + +package_name = 'fanuc_web_connector' + +setup( + name=package_name, + version='0.0.0', + packages=find_packages(exclude=['test']), + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + (os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*launch.[pxy][yma]*'))) + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='christoph', + maintainer_email='christoph.andres@stud.unileoben.ac.at', + description='TODO: Package description', + license='TODO: License declaration', + tests_require=['pytest'], + entry_points={ + 'console_scripts': [ + "trajectory_composer = fanuc_web_connector.trajectory_composer:main", + "replay_manager = fanuc_web_connector.replay_manager:main" + ], + }, +) diff --git a/ros2_fanuc_web_connector/fanuc_web_connector/test/test_copyright.py b/ros2_fanuc_web_connector/fanuc_web_connector/test/test_copyright.py new file mode 100644 index 0000000..97a3919 --- /dev/null +++ b/ros2_fanuc_web_connector/fanuc_web_connector/test/test_copyright.py @@ -0,0 +1,25 @@ +# Copyright 2015 Open Source Robotics Foundation, Inc. +# +# 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. + +from ament_copyright.main import main +import pytest + + +# Remove the `skip` decorator once the source file(s) have a copyright header +@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.') +@pytest.mark.copyright +@pytest.mark.linter +def test_copyright(): + rc = main(argv=['.', 'test']) + assert rc == 0, 'Found errors' diff --git a/ros2_fanuc_web_connector/fanuc_web_connector/test/test_flake8.py b/ros2_fanuc_web_connector/fanuc_web_connector/test/test_flake8.py new file mode 100644 index 0000000..27ee107 --- /dev/null +++ b/ros2_fanuc_web_connector/fanuc_web_connector/test/test_flake8.py @@ -0,0 +1,25 @@ +# Copyright 2017 Open Source Robotics Foundation, Inc. +# +# 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. + +from ament_flake8.main import main_with_errors +import pytest + + +@pytest.mark.flake8 +@pytest.mark.linter +def test_flake8(): + rc, errors = main_with_errors(argv=[]) + assert rc == 0, \ + 'Found %d code style errors / warnings:\n' % len(errors) + \ + '\n'.join(errors) diff --git a/ros2_fanuc_web_connector/fanuc_web_connector/test/test_pep257.py b/ros2_fanuc_web_connector/fanuc_web_connector/test/test_pep257.py new file mode 100644 index 0000000..b234a38 --- /dev/null +++ b/ros2_fanuc_web_connector/fanuc_web_connector/test/test_pep257.py @@ -0,0 +1,23 @@ +# Copyright 2015 Open Source Robotics Foundation, Inc. +# +# 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. + +from ament_pep257.main import main +import pytest + + +@pytest.mark.linter +@pytest.mark.pep257 +def test_pep257(): + rc = main(argv=['.', 'test']) + assert rc == 0, 'Found code style errors / warnings' diff --git a/ros2_foxy_core/fanuc_crx_description/CMakeLists.txt b/ros2_foxy_core/fanuc_crx_description/CMakeLists.txt new file mode 100644 index 0000000..164f74d --- /dev/null +++ b/ros2_foxy_core/fanuc_crx_description/CMakeLists.txt @@ -0,0 +1,7 @@ +cmake_minimum_required(VERSION 3.10.2) +project(fanuc_crx_description) +find_package(ament_cmake REQUIRED) + +ament_package() + +install(DIRECTORY meshes launch robots DESTINATION share/${PROJECT_NAME}) diff --git a/ros2_foxy_core/fanuc_crx_description/launch/fanuc_1.launch.py b/ros2_foxy_core/fanuc_crx_description/launch/fanuc_1.launch.py new file mode 100644 index 0000000..b78f736 --- /dev/null +++ b/ros2_foxy_core/fanuc_crx_description/launch/fanuc_1.launch.py @@ -0,0 +1,95 @@ +import os + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration, Command +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare + +namespace = 'fanuc_1' + + +def generate_launch_description(): + # Set the path to this package. + pkg_share = FindPackageShare(package='fanuc_crx_description').find('fanuc_crx_description') + + # Set the path to the URDF file + urdf_model_path = os.path.join(pkg_share, 'robots/crx10ia.xacro') + + position_x = LaunchConfiguration('x') + position_y = LaunchConfiguration('y') + position_z = LaunchConfiguration('z') + orientation_roll = LaunchConfiguration('roll') + orientation_pitch = LaunchConfiguration('pitch') + orientation_yaw = LaunchConfiguration('yaw') + + declare_x_position = DeclareLaunchArgument( + name='x', + default_value="0", + description='Robot position in x direction' + ) + + declare_y_position = DeclareLaunchArgument( + name='y', + default_value="0", + description='Robot position in y direction' + ) + + declare_z_position = DeclareLaunchArgument( + name='z', + default_value="0", + description='Robot position in z direction' + ) + + declare_roll_orientation = DeclareLaunchArgument( + name='roll', + default_value="0", + description='Robot orientation in roll' + ) + + declare_pitch_orientation = DeclareLaunchArgument( + name='pitch', + default_value="0", + description='Robot orientation in pitch' + ) + + declare_yaw_orientation = DeclareLaunchArgument( + name='yaw', + default_value="0", + description='Robot orientation in yaw' + ) + + start_robot_state_publisher_cmd = Node( + package='robot_state_publisher', + namespace=namespace, + executable='robot_state_publisher', + parameters=[{'frame_prefix': namespace + '/', + 'robot_description': Command(['xacro ', urdf_model_path])}], + arguments=[urdf_model_path] + ) + + start_static_transform_publisher = Node(package="tf2_ros", + namespace=namespace, + executable="static_transform_publisher", + name="static_transform_publisher", + arguments=[position_x, + position_y, + position_z, + orientation_roll, + orientation_pitch, + orientation_yaw, + "map", + namespace + "/base_link"]) + + ld = LaunchDescription() + + ld.add_action(declare_x_position) + ld.add_action(declare_y_position) + ld.add_action(declare_z_position) + ld.add_action(declare_roll_orientation) + ld.add_action(declare_pitch_orientation) + ld.add_action(declare_yaw_orientation) + ld.add_action(start_robot_state_publisher_cmd) + ld.add_action(start_static_transform_publisher) + + return ld diff --git a/ros2_foxy_core/fanuc_crx_description/launch/fanuc_2.launch.py b/ros2_foxy_core/fanuc_crx_description/launch/fanuc_2.launch.py new file mode 100644 index 0000000..7e5ffb7 --- /dev/null +++ b/ros2_foxy_core/fanuc_crx_description/launch/fanuc_2.launch.py @@ -0,0 +1,95 @@ +import os + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration, Command +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare + +namespace = 'fanuc_2' + + +def generate_launch_description(): + # Set the path to this package. + pkg_share = FindPackageShare(package='fanuc_crx_description').find('fanuc_crx_description') + + # Set the path to the URDF file + urdf_model_path = os.path.join(pkg_share, 'robots/crx10ia.xacro') + + position_x = LaunchConfiguration('x') + position_y = LaunchConfiguration('y') + position_z = LaunchConfiguration('z') + orientation_roll = LaunchConfiguration('roll') + orientation_pitch = LaunchConfiguration('pitch') + orientation_yaw = LaunchConfiguration('yaw') + + declare_x_position = DeclareLaunchArgument( + name='x', + default_value="0", + description='Robot position in x direction' + ) + + declare_y_position = DeclareLaunchArgument( + name='y', + default_value="0", + description='Robot position in y direction' + ) + + declare_z_position = DeclareLaunchArgument( + name='z', + default_value="0", + description='Robot position in z direction' + ) + + declare_roll_orientation = DeclareLaunchArgument( + name='roll', + default_value="0", + description='Robot orientation in roll' + ) + + declare_pitch_orientation = DeclareLaunchArgument( + name='pitch', + default_value="0", + description='Robot orientation in pitch' + ) + + declare_yaw_orientation = DeclareLaunchArgument( + name='yaw', + default_value="0", + description='Robot orientation in yaw' + ) + + start_robot_state_publisher_cmd = Node( + package='robot_state_publisher', + namespace=namespace, + executable='robot_state_publisher', + parameters=[{'frame_prefix': namespace + '/', + 'robot_description': Command(['xacro ', urdf_model_path])}], + arguments=[urdf_model_path] + ) + + start_static_transform_publisher = Node(package="tf2_ros", + namespace=namespace, + executable="static_transform_publisher", + name="static_transform_publisher", + arguments=[position_x, + position_y, + position_z, + orientation_roll, + orientation_pitch, + orientation_yaw, + "map", + namespace + "/base_link"]) + + ld = LaunchDescription() + + ld.add_action(declare_x_position) + ld.add_action(declare_y_position) + ld.add_action(declare_z_position) + ld.add_action(declare_roll_orientation) + ld.add_action(declare_pitch_orientation) + ld.add_action(declare_yaw_orientation) + ld.add_action(start_robot_state_publisher_cmd) + ld.add_action(start_static_transform_publisher) + + return ld diff --git a/ros2_foxy_core/fanuc_crx_description/meshes/collision/base.stl b/ros2_foxy_core/fanuc_crx_description/meshes/collision/base.stl new file mode 100644 index 0000000000000000000000000000000000000000..4947de029b4ade779a65166f85bf25711ea3bd07 GIT binary patch literal 8784 zcmbW63vgA{6^0i@Q0ORVu@MkKxd@1WLO~?S+1w+qG9aiF41x-R_!zXfCpS0F^v-15-n+iN z)_$$^@68?KM|YVyBXh>Qsq<${?=o#+moYQ49vD4!8vUQ29n7t3Q&k$x`O~#Txo*+C z9`U-d<+gM;^Mc%}x{-TzyCAY z64(<_(VV$z?L)7mzkRmYnsDWd_NLmkQ6VUIjlF&HcRh&2r(?HVbAbEj@2P6%5;gh8 z{pk`(hzMCZc5%Nu%f%+}5d$ApUSH5}$e-~M6WaI)i28nkrpjK6Rqm0WSw+)Y#XfHP zynWmF4>;C<=C;I+QMI~hzB+5=ThlhKOGBb#!4CV>hnMSl3y*JPuc}CTw{4qbJ+A($ z$o^?`9M3&bZOcdOXK!Am+p->am0lCCTfdy=Ygqq#OS)_zy@Cb#Tlkkz_O^+oWw>g% zHbhr_^KE2+TG>^6Ab}Bv$5E8|duzwZ1?tIyn#wbkDfYi_+`+LEo$hc`bl)?Tx_$Uu zbNiO-cX3;0A-%9Pvbz1+ZsG$8^oKOjA2)s($^I-YfiNT2K9DB5yeP{$fAhocxV{@L z<2^3kYxeDl9_;fZx6AD{z3z{;-@jLXPjv6?xz_%-vfY|C_f;Z+RwgPY3*0|Zf&2O-Gk3JM-pBGTpOZ~N-lFwkD2XWI%l&r;9UMo zPglkC2$429#*Ex#AJ^sVV|KM3En49$5cSO~EPXd^_GVc@B+v?Hgs9@8j!qdZc0X@Z zn1%#Ki2jJ4-&yBm-yKzZ?GJc8^t{_L@0bV0M|~Fk%KnG*#P>5*`oe`VB&5B!b(TFn z^}P^H)Vr*Pi3{HRCWo9Pm*EQE{8kcBn>`o=$XGvNsPpcGlzRukpHgSwV7Zxh+}RUmNkU=s%q~ zT8Vhqx;@TQhwfCpPrh!+FEv*Twr{R}LPj2pDI8Vg{TG~xY!gtiMti2}VdX=bhcoft(8Kzgc%D5PpP66OD`RcKFZwb@MQR zQDL-1-`CDm1J=E7RZPD!W)uL&PK5g^T&dm7)NS>5pGG9ZA%WErt0<4WQ?qVw)y+;I zuwSIT6ZOy4s~kB|CX%@9S5!{sr0G2!oDb(hJ|9S+l{p{WljJg^uN=@<+?RanH5K{` z=E~X4b7f-J1o}f2MPwA21By%&*e}w7%21**j85QK1C_z;ayzVjT6uL)NgYH2&!9QM znhtb{`WNdGB(UGGS}OK3gCfohCIciyWip2GVN`|^m4O8A3{+}FCA+$-o-O*QVZ4G* zy_RQp{^D`%W74su_VMSI>2}!1km4KFw()~hyMmULNT3g-iSoA&FZuq5I<5Mejk~31 zMH^2|;_ky*Le!s$(~S@~KS&d$EO@Q5LuHP7y{1zPePF#pnrI;t?U^{xfWSzQCaO8` zYUH7%!?kV~?^5YSh2!o+YQ=-2+`)bF(ynSf-@fb5D-*_n8lGrB6HAy#Z9t%vIUl+wqQif0r%)vEc9W{ot~fYI8HF}7!z9>5ZEu$d{-MeObzbb)gAsuk4ib?d~&sS+b5Z?a2!Yz8C~LnF43_Y&7k{5)lc;1ys_!IWjXGc)z_x=J327> zcE?I>g(^IJV;P#&IDuAp(<8e2^w9Ly=_i=TYCxbBMo4tS zohc<>T=25KN7dz|N`~Wc1TQSQ?VVun4o7rkVoJ#;jSy&sV+t~yD;W-bpj9|3li^&+ za7dsP-hGHZ{A|8E>(U3EDb`?p$JyOyG{=4et8jUZ@M0Gw<12E$M|m2~^)(#dOyY7g zF&d8Pa@%O1xM;iJ{^7#?gRO!)j#m9)rEl&yF5Gc6fmXQ3f_sz;_o%>!AE89$-!h1d z-gS?%-Zi>b6WA|~iLW}Q1zJ#$KT5en#!r5 za%uvtP}>D{P(dBk1X_hvpQ(ci>Yygj3L^|^l!6+S;3KRPO^s4eqcnk5VV!6yr-I6< z3A93$8B}Kl)mam0g|k3ps+xkTrU|p#xgEU2>Ne4PG(gGU*UKmQl{3Ky>foT(DyX%Z zFgskg(I3$_&t0eFZ}_-!%hXzJh5h2Z@vAIb%io9w1X`KX#XZTsGP>Ob-5!?{g_;3t zdoXgh#fnM3($@r9p)v?=6E55)G-0CRcDarIf|0v2ax+>@V856pf|0v2awO0S{c&bE zF+@$x>+D`QVS@E#-ZJ~Z3rpkA_I)FYKEl~&*r-&M`e+CDj;!JkfmY~`Xy8kO)Z*Tq z++90MLIhf&zu?utkyitbSKcr5{K$Xh|7ET)&l8!~4|f*7ejtHXSbd0Yn=soQ_Vo&D z(cx)+J-5AjUjKfH_XMtkA3dgPl-v8J21NbKrl$t3G5L(#Z+bR7fW$P?sQ`oZv|0m0L%JbaFzhg_5~KIyqrp zAoY46ot(f|d8CsQ#!Bx>q&1Q2aS3ZK@yE@Y>sylEG2kRjn9*v&j6=5pXt1x$jA|>S zlM{HaMLIblW8i4C4<_Wj{l}vUtk55kxf@t;H?T#QpjryApt*loaR1N*TA90u{+`I( zaV)qM>0i()tjG$zdsG5}Rv01C*+&PdiP@c0|AQq~P3AIt@}Z^np(_HFkq{y0tI?^- jdZdH;E2|77a2#PDFRY5HF&B4HRWv+App{V>X5{|^DM5vp literal 0 HcmV?d00001 diff --git a/ros2_foxy_core/fanuc_crx_description/meshes/collision/j1.stl b/ros2_foxy_core/fanuc_crx_description/meshes/collision/j1.stl new file mode 100644 index 0000000000000000000000000000000000000000..19ee82a275f3774a1a488683427500ff23503fb6 GIT binary patch literal 47884 zcmbWAb$Ap>7w!w!1b6oYhhRyjyD~kvTX1&^?vM=b79cnTclRXI)0x3#ad%y0kp&iK z;hyfKCvRmx?tPxSf9%eaeSdwbs=G_hIaS@PdHsStyZ7%txbx8N-3oRYRj@(#A-(E% z?!x{*|8XQ^Y-)k}ynNR$&X;EoIfpgwr%2_hy8k#^+`VkmRAox=cbEP#}7ee-iHR>^420ld)CCwU#Y?so-_- zN{m%07sO{gN~2A(wpw9xWD{OlZ6|A-YM-sxI5tNWaHkHnl{D#pl8zfdgR|ZQaj>H_hVK*fuMV1(E7bW znlZ*7ymc!3y! zz!Hk3T51c@RA(Bk=IbK@f!9Tvu~D!=mE^U3+M{J~4e8Y5_FCAKuL6Nj z2GWcTeE-fFG*H&`|I(c@+C+brupZcMj8*+wKrXwrnYwMlSpHx~L2KG>%iQ(qi(l0WKKx0yD+^$((YsDRS zMXNO7h1%iupMniknXTaKC_?q9zHGIe`mwj#@#SFtt3z_7U7HBk`XH-N+ny(EO1cga zu7b%dL^#&1mMdm|t&}p8NcJ6t6F4p2 zRv7kbUdv1Mpl6rEv+E(m>n8M-j19;+gny&^@qz9K+Mv7XDWOQuNj8u-$gx-M(Ce!F?|JZ>DAhHygO(!pi{9^gh>1JLxqAMJ8v&4JEbOnb&IV^&Xz4461ite~Gq!Zj zYiGKCTpL;bgL7e8=B}D+YFzIFy@c2^TnL}%^s_Y6YE1bi5O`g*XHEphY5Fho|Fo`B zS?CSS`o;Anam;@Sd{gla{=E(Cqr~3lcQ(Z9;vM`QL3N6I@2E~_@AswpU!y_XOy+ks z@I6O+zqeu5L%*)sZgJz_?`+_kiuME>FdLj)mvcna3A}Wwsq?})%g9Qs-G=5&wTgLF+NuP?~H9(60GeE`cth} zEG-WxH_M&7SA^?H)^au+sm=QzH*!vH(n1^Yd8L|prAVMXq#1j*K1d6lDXU{j`v^9$ zR7le}xVWv>dHyfCR=w|PpG{-jYc5n&X6D}Gs%W3;ZoB7)RbLytI5W=uC3RIr?~fVl zv9F%C>_QH{C+LSjpz2g)U$>IEnxfN;eJR&U+c`Wrzdgsxi8fG$_87}i@S^kOUp@Jv zZco&spwN?Pib75L$znVkCvHFjS=)YZ5jsKOF5 zc58Bg<``F+CmHr#MFLe~sUlAm)0A;R{F&bmfj|}7V=VG{Dc-eq0B;!VT z+?Xfa4YMdYa@dXE0k)n>o1aY-eU{1C+&N|V@=O+fWyKW>68Q#qRMJ_y8S@gPX$3i? z5ug7#8}ATMPatq!g0m0Cj&-^%zp2xcpITPi;q$hn@~-YwrA%OBg<4lJpOTuXRqOdu zOO;`xO4Gf1bbX3k^W$({Xyt*xoiR16V~4FWN;2xw66?3%Wkx+jqI{1_^1R^Qym*(D z4tnCO<`ai1w8vQbrw!#Pp6JLbtlDXC7|Moip32+Hls7_86-leOIoqagbWX+Cv~vg{5VzaL*xpX^QS@ zj#Mk;4G$L?HoBGa)%#t~oEqoajCH*^hS!fx={!95t9l~kV&#t_c9-5KN)whTrwU9m z=A}4_GWPW77~Y^%YG;M@-vt6yqW2@)?y)@L<2Ch&^hN#hYbEs^XH~s_MH^_FR@=2h zd6E&=)u`Y<1Oja!&6t`#jO!y?=EgrnVqAnW?0M16dhZ->TZ-%385?I11dY?LOEbI@ zjIEBd$rW-R@XyQEr*9I2VjGW=@Qi_Zi5)HQ6I4FPy9z61ZO0XUKXV8Mi)fH+KMU zJ$b*ZWFHod#MctxN~Wb>jeCwX^>9Cj^Q_;y%6(~c9@Ao}(&t_|t3C?j9bDIYzEbYn zdE@Vlxx01aeixd`cB(lNsG`}ck}!Mim!dbH7obYbww@CRRAKMRnBT{-yy%W`Qo{|2 zN(DX=EFohnx3uRwvV4{Iy?mq6%u6xnoLF<3Co1N=l*Xvi9r=>u-{kujd>u$&`yfp# z`q!;^sW++kk@O2g(s-v0m+i6?5*(Snh_QTJ8DXYL)959XH7x9k1~Gi{gvpG z$w)+7A_8uR1gg-tNFKM3q+)ei!ZJ>&tH@EqOGM4&as5bM$G4;?yhdxHR&2bQY zK-53Fb)TH>VKYWG!}Ae8s(FZbI&LHz7vVNXIL4Y+8LRdC@l-vtAi49iUH1l`RrRqC zeM_Rf1?PKf2kwVRlRBQ0eYY(#+UM`ZJ~k{n)`{*Q5qBSiNM{lexCTU;W*I~bz84~O z=_J~~^%>HPMgQono$#ulc9<#>SQ2qPIGu|&`b zA0@3h^`eWYFS)yYvU^+Rg2ozvdQ`XB&r^@;PFNds?H#O5x$lyfB_hxs(u@r~-9xLs z<)Yk*dN{N}?~2=eACWft63y&Os0VPHJtwZ{#5L#N*=jpS1Qk&I?~UgDCT?+k^k3w* zUQ~1sl*iwWet5g-l*n&s9hk-+OB&Di>S`LsXEUQ!1rwfU^A6WsjlVOP+Hio*Rk8DV#y z>K@@bxw#U}OG2mlYLmhu)U3~Cfj|{{bQt@qZ7J>c@kQ$WAW0xlg+3?7+WJ?~E+ze@ zKFL&p-~4Bad*hl*t`mLB+fXHXqjs(L(>|pBp&nZAClIK@XN<9ZGs&G-HQ5Uve&Q+?#t3Qyp2m=Wv(GFYA{#{nz2J6UxwTCgwR~{ zSq80oR5M=rUSEMgRr28(+<%sxYxo~%UF+EBJe+ngclV17JW@H_)w;|IrTy^Y3aZFU z;WE7xj1^f@JCLW}VX+{A zDzrzdyT5{+-PMuY=kX&oAmc-o#t{Q9S8(uZ^Eh5d>*A3I0YxfN0K^cAs1gfx3jP=j9#W^pkKcBuTn-guI z3hgl#lrOb5czrMrxst^>@2@=WEdG=KQ!3F9H)B#pE!{tjdAa4^RU}Y_&oN`KZ@+b} z_|%clEb>DjP$ia%e0>`D`rM|k565tPju~qc(m=~MJ}Yk$=N8G}TcvFYs#X~z%M-MwsQtmAruHc(W^IeaxS8rWO`#!!j-xAeb zAW-!#O@H^abDJ;!y$qGUF!K1v#(_AL@<%m-y#>Y%4jF{1$VMtQu>SVAKTz#$6YA?U4D%(wy4Mx=p5q`^briVkU7<9yA| z6}2HRwr+DEjZ2C-E@4Tqr5OwST9_Z}S%X)vUfhBNs_Vn&y!Z}<53#rr`K6Alp*1)?&ZJBatj zh{|w?%6JG=QG`ZGh>}s{hePDYL!e5$=LZL+mjB)!${+eIaL@>8HAm#tM=J+4X|P%e zsghs87NODLStWV*yD>cS;4pzemDpA*COhR9L(a)3$=BC0O;%-2hdPFT5AOlq8^%f$ zohau&SDAa!9dzcJWc6`OHtt$%o}bn{^`;v4|IW_2Ru&X){AMg>Zhg60uX&C&XGinJ z`zBZm_~dpw8&$XAx<-s<>@QPO-WpuXk*w$#fj|{TImlDAB$(^b*9LLXS0!tF^wo@1 z>k(Is2r#yGVhdh$?L>9HYD8Z>1gb=jSI(49xoC5jWzM<~9=UC(lIQTXAbnNzJo`{3 z_p=Pv#E}ig@({7L>3<1~e_&jMu{9@t$tT&y#fSA@=}5o4xBR&NQbqR^1tcwM!`g}wld(i>?zhtMYN<$|O7w-- zl}GUhCw9dIZV(CbGkE-$Xpd$YM6@6x?|PBI>mp5eaK~7lcGMNs^6xj5{5~{8jr03p zTt$q^tf*|~mv^p~(hhGMIQi>J<#X}_T=zPm9}d0sjI~>2=Ld%Ol8V<&8jS?1(DzO; zNIyI8IDUs1l#{ zw&c_ICZB#*s(H2vGnH|X$Bk?Xocmx2DdU&gD#ztA{~=I??Z((%@`Vo}UwAZmqtFJb zaOOm_KAMsBry1FyLZFXJsVraeaD*YhGJ_nag}Rej+~0_ z31O_DYi!z`)@_kC`rY)~IN92^qZHeE1SfxzV)~OXMvJ`!W3v|QklXCaCl6g5A`p1j z#P@u~z|C@@m&N6@1^NpFs=h^}QwBbD8NMvWwv9e42Rb69)L%p!SQ5Pdj5)JL$>*+a zm4aeK0##T-#%ez(FQ>?qL)N`&*DKAo{@mEWsz<7^BnumKv)&mu#rQj8l|mZJ$!DB1 z{BTHMyCKb3O|p?b-p0k953R{;%(w@5U6B}Yt0(`q|Ga#y&JVTn`Ps^y>mRJ~c`}}O zgcxa1R}bWoY1hf$r+pU)RAGFFu^|Ho@fk%{%9pMsb)pSaiP5FriwAP~^J@8JrZfV9 zDluZRtN#!_YRD>CkMNo?2tC4!Hq5`r#iM+DhVje&7yO4nl^C0N5H*6|&of>=Tf16} zsnTtr3L|EWjaWW{SNeOrye?f%2NI~l5*m3+9P*YFGj9oFI%3T!3yDJ(l7~PQ&b5q8 zCk~lT9s*TpkFg|o>ho{oa`BnTGdmV_9;IY{R8#St7NMXDBQ%UHKG%dl+n$;K%KI_~ z30!R<&DewWoRzPgpWIB1GJ)(_d8#qt>KL}KbHYhiWLvEDE2CA?XsNW?5 z@~=Dus&MYh*uS^N@>Q*lOG^uVS9`QwrjO2&{zk=*)ROK`!uwB8?Cr6<4iQQs0#!JQ zl6R0YAogX>81R@fAkc=Of@}!J4iIrXykbCL6Omw`!V)r8bj(=(KH{oWT2AJiHgvI4 zvT1*#XFwIckBp^yI+9P?QBQu|@P~>7s<2L!J4kJnr_XVzfbVyKKo#1f(I820K4$x6 z`JW0GE%j2&RBSUc8{R=&_lr@>=|s#V;zJ?=Rp{4<^D{K0s7y)n;-C%mgrGh0+@0>h zI}nj05rNl5Ixe=(AqAX|wRpN|nHW8sjJWE8N3QI`yD~gOpP-L_*MMmkmZZks!qof#PqkJDCN)Vx~ z7YU5lB5kylmL)z90BzuPsTDjiJtKQZgX|smx*g6f@%cVR{6o(*p?5`(m?mTh8PQjI z8|j}_0+A4-UFD&5)i@2ZcRWP=b&Y%nkiFv}u%$(Nlp&-+hEM_l5qFWM{z{|%DmuQu(%W6t z`$VC(LTsD*D~O+>6B z;&D-tK$TEJwsPQRXMUPlrlFZ7%_iMuRuD!;X@2ESm|4>7)!B|_uS00|iUiFK-R2q> zY4RF$TkdSVt&_aFgGk_YGiR#iUXkNvY z?;?TGKBO57FEhvafY4UbK#Kn;BHJ z#_>e>jg^-MD=!a$*#bx#D=!UJULFGbD5Q;*mj){@4}m2?nlV~CYp`~9n`>t*iD=^l zW%h@Cvq|SEv!7PN9s*SuS2b4K8mzWG1U@n1b49Cd4OZJ80##T-BUeo`bJfUW>Na!W zFs_2Fz}St*lg|DXi}8%KcD@|>!ZqA?l<9|anSMC($+}ISEMujbd~lv>U7PQqb?u~| z{_Yz`#~4vWRFN0YL(|hk#6=<&BqC6S@kolF&r3!%Z^b*)=!`Z{B}SK4Qaq{~<(_v; zM4$>=fw6U;@@q}4rTNZ8rNVZ@I#G;1p4gg*!0RH-*pkUk=LPbMo+p0^`9j@h4kW&* z;yXybaLx3EBY`CmZBP!RRx>^a5(!j^_q^Y>$IfIgSn`Oz>*+Mez@TS zv_nY`$eH~92yE72iF?kC-PUduk0^LukyyK6fYz-4e)&-0E73?`wh*m3-DZv_WAE4X z*Qz&m8iG+2=5v;%&elU`|k_Xs;OQCrfwz@cwMAvCevbvTI$Q5=u=rm0(0ZA zgp3_YmCLzqK?cY8e4#=;C~o9wX|Z+7-2ANWk8;J7$`>XOs6u-*syV|gAvLc#{O;TN z?a$A7sY2oIrDJN?KE50#pS&9G9zg9QX6bdW@W|rd`KIIbd67UBX74dJxZ?%sNc{mZ zBeof(vNn#tAE?6k7kP?OYEqftEHQ;1iA2pIX{`EP`);XWLz;YK?X$_bmw7wFgN(NF z*ud*zyp6Gvqe{xnD`s`5wC{kP5)XkYF|Jmx$}MU6hNgjwXNaXj6_${4)ovxxwiVc> zK3Uk7H=aG*J#FV+SLbz=ZJ6DL`Cg1=4gBbQ;=5KYb-trOpb9e&8Jkr6gL9f+e>Lyf zP6C0Md1#L@<>xDBhoFI~HKdC`;B}EEKisu+n)RY%4FWqIlvAP>xzOt|bRJ1Xk zh~-4|N<^SawBh$8oz{wCEb}O0f;MnoD$Yfd5OJ_sTvP@LoQopO*v3~qoG)h{35@J9 ziu+XD;?kcb-QSK`n%EODww3ZM&%P>V8BKYXNMLV(G(GLpYB^swY~#3-X^cSNb@2_R zeCis1sJ-k90-GEN6A0|P&>mv}4+}ecmCx+>5j|EQ@VZDdc6VtutxrrNUekUnX7ZcH z?u8ErDV+yzQZUC4^NSd3k~Ew4(x)-6o@ARqU?w2a^t3N7sQI+2#UExW??4-PUCd`9 zPm%kOv+%qAd`z{`F_X_7aan^GD|3pM7fMB$Dv&!^j)+1;SQ8Pb67%6296#*L>FCex zhYC8-2C6XAjdF3~iLgWjs>GUazBk3$_MhQ=d|hL&rOVuFi8e6vkY?da(mB=eP`*Ai z+(8)$v1TR*X8$40*sDJ?J6E<2A4>s0#%d;;;~I}we*qBs$uQ;LYnC}JhRAk zy~z?|jf3kCT)og~J(Oqpl=3X6()t4lEIZPS-Mp4udv~M_Pv3W+MS1MyF1mNN;d{lL zOT0I<3*vfm?J5!J5)r7v^$zVnr*+hFT1V+Sa?u8=#8Ryz;xG}p5)r7v64FdR_^CQ* z@fbd8Vs>ZlNl9Hf!)@VNK&UY0FRN>uZ>{7m# z>es!Y{NiVkKo#0Eb{1>q&SJ_>a+|w}DcdX|^H9jfrA#MH&va5K(+LS|D|~|)8(o%b zKPr{v11FDiP?W@N?x?|hL5gNTwjo7jG&3rL1gdafI>pa7aLtU$Ab~2JEi=}zv6Zj7 zRD$o^y)bajmL3#UYNs>^+@)Za7H01mPa=mWQ8AxHdagYAcbL6pJc%5hL=Qo2<=N?t zwDBZzcoIDXJy)I#F{EjIJ}()EC(%P-Nsy+U7DFrZTyrb&4H5p1^?5rfNfvcg+P{fV zaOaa4U9!*c=Nmeg=XE3YM3YEn!Y9SWq5M@&>oGoMD!qUl%Cf| z-Y5@&xnoE(R+{q2a!?*wy#LBW;B_&-jP`$=50|SI{9D#DozMp6t)V@}=0wVJ;ljze z?k_sDL*jkNrE$+GM}dJJE_Y`w+qvRQw=RI!$ zMdB(Jm%?Jk@@f0?2}Gw3_qW{37-?KLRr&W@PEA{(4Evy;enDCHGGyH=klF9aHWf2W zDYKtLX1|9(m6-iWy9YSz9`F#TqRf7eJ!6N03_BF8unWSYqLJE~u$zN+LCCNR!b6}6 zvu2H*7BcL#@DQjHOVy>hBn^(V^NBZ~JHF2!<3lkt%EjLui%$k-w=(vm_&H0f(qa5% z)EgBEREcv2A{_sVKo!n7jD0LJ>|?Q-J72IK*b2s885#Dyu#C=OIvq?Pkp3 zB$&f_2vngx#v-WS%}xF8CF*y_DOao?FLW{bSL}nues>1-?Y`8vUrt0|-;Ol-Ug?yA z_VK=O@_8#}91yeHFpHTyER^efKHjH~1gg-U5xbNBjgQ?Sfhx=|Gvb5t&-nNt5~vb0 z&nV6*n{iGgP=$43?AJy={;cwMHRUEhp8MHUWlPE1uAB$T={pYT&3fb3cYtEvGqqLz zN_^*&Z>o0%kw6vg)br#(GiF^K#FM71AqAK8;cW*^RdlaGo65$SSDsS?Fpre6mz0e= zyZ;q+%s=1ETpTmDO)H7G(@!unmrk=HVipls5)r71&w5egV%zcAJ7zT8xGv-r#i<~Z z$CDvsM%+CF=KD}=+fzb{r9P-#|Ay&o;V)bV{GEce^kGrE9C*(2JxdKinz-EEbhrF zHLok$>vZstdTxC`xqH%)0)Z;bRV81>!~N2-o)#%6I*co~F9#*PQq%hKNp&0g_b~sG z*5~;$$+yc@lDkvBj6S}a`K_2|iBCT5D>~dGbI;Ql|Z30)Z-Q z1v>pgz9Jnue#kO?j!2*i>tw{}Wj#h8LNR)}2Uf@n_OzSWR$t1#m9qHMm%}rQM5;bl zf~LxG8OGS^M&^KQW)7eYye{@#)KfpGDOZVq+L1sN_Tcm+-mT3~9LUcHj7$<(Y~n~| z(a&0nz4$@}SEiWV$e8csI{eXte0OoPlbx0$Pk zIX+@`0-fBVL3W#mKov$X>BOuPznmxH_kYk14!3#64rU8r76D_+;t73KgaoQEK1|+o ziXxlm`yhcTj7J;i`)HZt&-XzBRbr%?PV3S1(|QWfdJqXzVV#Vw^3ca7BJjFMGj@ma zGP=`BI2YBNR-2m=i!J_EP46xhD<@RAEcgi4K&VVD8#N0#)MpL2GBHfBf1R z2~=STjkAz6@A$KjC=b7~*B=F33 zw3nbyTywlGtv@}dVg8=L6Xwz0?+LuFxMMwm5$l2HETg>yed2oHb!oi==Ncq1q76Lb z8SN$L6WhS+;tJ{a1fB$q_I^*`b#dMHdjikBMti>}@VerPK7kS23eVF=dkOl)ZH3oG zzsBzg{K^B``#piz#oY?OC-BP-Xz%v~UYFiS&yJzr6ZjnqwD)@guS@+3oI#hsi1!1( z;DPoM^oj2WUYB|weN|-iuD>VZRYspE?zK!{#8ROOOPHWfTq>a?!s;%85pCe=4ogV+ ziJdp8o8Qc{49{)XXZkK!e|XM!5_4E+HQ|KSgomKDfhR9V%*B~O=SD@wpBsfXP$kB; zYdt9MOc%djjn+;sbMG6?+dUb^VpcKjqH~(N=#W4ame5$MInA{i610Nw>`O#@jEy|_ z!}6uFU%;6McHZ-S#-PvZL);5S)v$fp+#=|Y+k@OC2GtPOhV*TY>6E2XtZG2kha!Qi zBFq+Itk1CTmKH_MSU#S$^ZwHg@XLPLtzE2Qt`gF80%r9T(&#ofEFs550#*5{r4Jf$ zAh$J*zn{A1+i!khSxEsD8V$)l(YwcAq5{pr5`bL$1H6G!rz$d)^Sq%wPi8dBism9kHt-#ew z+o~dgDzwK~zU*b`+dF~$+S0;~J$ITZMXC=_!nUjtN`;YFTHUoS%Dt89{KAd00)Z-w z{L-F=Xn#4nPzbM@YYXj|Eof~Quv9thERiUpln`m6^LK+=$ZLLe<*)Xg69|m(it(tU ze(9u!YkKiq$*u|n#-Nhr{Iq54-iY`UHtrr!Qtx{rArLu`CjNKL7>yo`@*cOy=SES-t&unuVz7EoAL@I3`Cbfx?zt&%RsY|I;a$$#Mi{G@^w`=1{MK)Y! zNw9>Jop7&?JgMtQUgBg1qjiVvU8%4n`Gq@(@krWZ(qEQKv>U^xoyaEX_uM2JyQ+!ISPd`cD{-HC&>*o+krI*l*hKen{ z?ysKGgZ5#3h3kYsph|2jsX$X{alufYZoAl4sKOFb&+s~poZ)SMUa`wo`NEY9*5nj% z9b+p-V^PApqW?A{v5Zwa*i3r!IfU zUiDKjqKI)r+E>&oNY&QbdB`8<1OinQ!SbAWM={|Q%hi_^?L76Cy#j$M?C0rpvB^o~ z4|Dd(^=F0{@1W_GNAIZ^^P;$cY{m`rHZckG!y?UCvqqWZiWO4veZegZ8#!`LQa)d+ zWW(#?J5QrQ`oYqI*0IEa~y$yvWIo>aAQ>fk1mm zGd89`MgA`Qvs#;176`m9#`GuyqGm-N?E6WbRZt{Q6(Gd!diF2HKdxV-&MQx6(Lp^> zg)u!kpJ9(LA9gE3o#vJW0##Ti+KYUxF8`DynVRWK9=@s9d?P;iSC-N?B+wq68%0Ex zq{-BDi3n7QCjt$6QHl!2AJ1=mw_?1r{@noz(pbe3( z`Nw$2r>c46UP(g*0!xB4&8dT@si$f!l&8^`{^;FyCG<-P@l!GWdF5wXN4otJ<-krO z1Ol%s_6)Y7Q`BqJU*)9!DzOc-f27_H;gBw$d0n z5lAFZg(akw@YMa%o^s2ik~PEl_cC7Ao=3y1l?GS0VGI)Es*Guq>PX>-u1IPFk(giR zXHf9V8P-!R=;Ud57AV@+B88M|*bPeuTC4TEGCt_+;$qgjMQhk_C5-E6Iur2nc&WFu zq?FGl5~#vhG3CSE&MEaNv{;&6KqOEluC`N+3b(X=G)>Ay>vJp>s<4E#<8b>%Y16Zp z(%PY+d{CQ$*8D408Bt_xH?ggbEnFb=c<{G0ceY4iTOmz5Mi$rP=O!28?@Cm0tcx9_ zENj?UY5R7rf-ymi6;e$2Sq=WYU16U0XP`i!3fELL%a~q+f4f?k4_){u3T@!}4DC@y zW9L!Y@c6SV=rjtq`Na^7LDCr)o=9UHF*g1z3nWk_#vqU78L2J2I7V*ub-4b;5RVO1 z;f_k$IoW-*)*)@MTx918{W~Te0#z7qF}_No!BJOo}h{*;3F zvn&Sg8=*zk9WSriHA6qA$W43t=xZLU^{;t&qFGo%%0o^vO!MluP!6`X6bMvd{L47m zNQ0A&JT_2;_9%9DyS^4SJ{Nc8$n2mmhq<$Q*HUfHaOR=Sy%cTYwhc{Q5_2~>%@GwFL? zn*Kenw)8zOBv6Gp`?Nmys;eETn2*=J)AA4!*a}!eXKzW0L!`gD}>yo>WA~orDGP6 zKwmG?v`_fhM@#!Hb)&{Tvh(rhGX?EhHP3x@r0CxjJzg2;>qgrAyfH_|*g0ReE-2P9 z(cPhK4cp4&^MjVuoZ)`eIq@FFi-l%L5_=rIjrOG?fjb#-ETK~!M|YJfJP41zxJ)Ea zh4#qzx~`%0Zg^cHx~_?h3s{Z!LOpDKqnU0kyDCk?6eVL;_W!CpC3oJvIBrLebTC zi3F-dAM!sJvN^m;Tysceo+MC43FpbEXJjPctp zM~W+#{MWy>^GR1uX#vUlxyzA%7rm$G9j1tTGtE(9cG1HH-iQRM&^ydnfpJ?Lo0SSt zU*3rXs<2Mv#rYVnmZ@*&gHo@zq&jywc2Va@CEtx?x^Kzj_d$P8N>L-nnNrZv*vZxp0!GGJV|ZK)H0cCYNkk~ zOZnuw{|ff2?M?Yv?Lz2oMKN6{|voe9E9N|XcYLSL^-ageD3);Yz7F)OK14W4OF2$ z!>6z5KK;_<)2F$i+dRJ=OCl1D8e27eFWD~IONIoN3Tfkvcn!{o_t?OZS{%>mjCc*s zi1!evLVGm7T3JHN6K3TrZ?B6X553#;(BsZoYz68?zm(DT{1M2T&q*7N1gbDDLi5K> zrM0HXB!0~86Bu=}sk^OZpwhG39tBlmsYWQpwN9H9UhKgKfk2hGfAG!2(ps%^7T)#I zHGi~$B}9AlMFfYh7Q2q~z@LEvf!D=Wpna*qCAHjnId7e+Z4}x-71|@hT9H?FR^{O} z)x%_6F=Itk56?GQ#fV9acX^)Trayl-DOU^sv>CKGjr_ z0tYICy6;g?B}PmhJA8RPs(F%3vOf~25_i#cc~qL;{lmidWxFO2SVFW%J11)tCy$rH z*@6#&Xalc{tw8Vm=Fh)Y>xqVe>qZc&^^8CBZ-Bn_#mLJKiN+-thJ2CkL0#z78pcUlBD$er(!+AuD<^q9z zJK7_k{@GyXzwQxy^i3l+;i(6X$VgM~lfR5KC(6#Nd|GZ%+LR7@^D$C+70zrJ%?fK~ z3;OvjQmHiIC+($JovyevK(+JJzH0;m%Z@Z-d#10k{CsZb67O;ZP%5P9JQ*Sy6OlU+fhvsr(e8o#QPTVmG{0(^K9J@+L1x4qV}(c?F?tDN z^d16L6vqiN&my3F2Ca=Wnqo!!W-U8}Hc*AT9VrLt+yJT1Ts!yLmR%?ns_A~`cJy@oxf_cTB#P?OTjyc(M5`RmAYiHzO?fWIdcRefp03dG~K~ud8Gyy z?0g+hD-ftcdvxa6jBb)tW++cnaIrobSk2J@dr>jQ`liP}(!Je-d8YItA*wL?>a7H- z17qxb_Vnq|6OM+&>U(&n(jH!ntBP?>m%EKRg5Hl2qm~^)0#&#cq0E6x1Jv&Hek9qG zJrD_0iE9Ij0!XLhqX6V%x592GPm~lRe~djZSx2gSYJ_|{v$5OBL!b(yi?jnY|6%E2 z$q>2B*Ae>uC=Y=ujKmsyuq4=nH=?)MfH< z1}$eW#2UAb0s~VSBo+KqbZy1UfyB(LQfcRC9Mwyyp=Aqw=V%tJ?1U$;Es za6ewu?d2NKc;tWL=Xf`bJOHPj2hf1>04PrGGS3#ENWN#EpKim9_EUT?!*aDEMcn_T zh&vLZ3QP6Cc~otG;+1@1edqrW31!Eck0_qWdC@NwKS7xTiEWtA6-FA3vlE==*$GIX zN{m6$u3x9Q>lX=BiLKD*ZZGNU`WU&OGemD)>;Gz9Y6WXToo>9)q>SfMa;0G_BLm{F zGgKKjqKfdei%-m?n{LT!e<^Rbb@>lrUYAM>XF!bgODA6{nv(C8TMC4z!YA?g;aBqT z)GO7L#k%kxkL>cMwIEBNQ35BTF;vO;s zB{gYf=NUR=i(TW&WxX9B)&uKDUoxAt%`$JnG3l`u#!u%s95kzKD{GGHVpJDPNd4}M ztkT43ky0-&TD1UyDvZQZ&h}q5CGR`uq6)lh;@t4K5(ZTsHCmtY+o_ zj+|m_yUegjmRCP>%W`rf55Pm9O0mtqA`D`bp(!bKnfz8Hpbxr~6>w_DuR=3TDwH4#%N3;u4&WKF%5HFDsRSEZo zJoJ&{q>G!=$;oqt3O2B%(H_OmFHe(F=g1=WJ}TP4dyX`HtFe`hzZ+7Fw`{c~=F0N{ zO489ymG#r+Di})_BkrX$*m(Cd#rRu3F#rjSxFc6OXeXk8jf*wI@dY(IZJSo#!*3k(MmPUJIKuW$2guCyQ|$d*3$J- z-KbX-$3X&BnCnj8)SI79Qns#fl>S2`P=#?kIx*{NHtEKaIgU!FMFLe=LOMs-Kdn^% zdAjJWx9mK0XXl`e(j0f?{$dPLBz!JZl=e3Bb1Wgh3=*h9dvw-hgO1Ymh3jIXR*D3w z#E4?Y)8(Y%&re0Ir1&7(!04hFAI!3eOYIhPh^}~8B=EXO)5*hG8>=7pw2E%G&CUZm zuZ(^5XsSDsPU*$yq8RN9TeDSNIOI)q+PorxD%?H7*wT-4)i0$|I1aZJ2~?py@^b!t zHl~MreAJAx+V~iN217_jXkc z`ytxE=pxc|zUWq8NAHoHs)Z&ZFb0Vgnxcu77Qa)P}mn&DKa_Ltx z8^-ZOduM$wsQHL!`cWiMCAQUso^JKg#W4P3ODDkws>HVXhls~IF-;^;g(al=#af+x zwg>QjaeEqEF%9M_Q%;q$VT2FYA~ai?Urv2Bxhqe)`Gq{Ao{{9 z+*qZa{nmw-4-pAbl@K?itjSFy)Zx($c@n?u9Bt_L!z`f~1qgN*a;{j>if?L|^go0d z^Taw)Bb8}baY;9vdjwgaC zM*B8Zt)@*mQi0Fh^0^uksKWRct+p#x){b7U#Q$z7A4CFG82_ZREZWu4W@XLK-~81w zAS7g@+mgGsveav#g84oeU1V(j-P+oII$Naw_#}ZypbDdzG|RYDOBJA*_z+v=X`me0dDdp|?Yd_RNh)u`o4EjrH*BTeXAq?|haWBf1) zQI*ioQ;wHicBULUhM$*C3WRRM91UoXktb7yF?F2m{4it;Kh#4cP=ygQ+M%#H$hmdu zXg>Gh7NH)ZDxpsFrSY)G($Owqe9E3tmb4R-TYJ!0yM90_8%BZ9_fBW42cM)bhKBLU z&%y-)Rp{Sm>>GEal6-Lz+t%*cW9Ot^q48sJCH0?!cD~AMhCrYS?NOFq$-HX*V|M;@-w&`QTe$hU-u1qKu(zG^s zomE|V(#}_VtrQ4Ui808=sp>fLe6aJDo$UgFZ6%h9dIkx42CLbZ(EH&zaT9w9iXsyM zy^n`L6-GJeJj**Tq>)#K^7MPA>;0975LFn>Sa$1$)c5L8K5?r^=sl;o;|xp4Sh`$o z)EgAdNZBxNV9j*ZV>ePv_|u`E3dSk$ZqoZvy^iX;!_H@QE@MFgRbpFp%GpM}Nj6?L z5N)6e?J;)DaYHRXGz)({z7hBPE4?eG+H|GykBa(!PS0Kt{hc>Gw~W7}m8A0r3c6bVsxR!V)UV#A04(sa^Pz-)E)vd41$wcP{)RbmNyR!y${)#!BO1ho}-rrwZ~Yu0!jIeaobeizHJ2pRp{lWIra2^ zWq19hYPN{>0)Z;D$Jkg^RLqK~(336_ zi++@ie%;}!)FKgqD)jHup3!@iV@gF&lD-bJ3pQ3X*{7u_k=;6+P7OhOl=V`&YK;Bp zBaeGc@L9BZl;I={eTPeh;! zef_jzsqnz@D}17qvXf{7RoK#u)rx)K2%S7pVu=V;VF_u@&~U3-D&^nO>6XTBCzrWD z3ikpW4bS9KUQMzNZlmu8Y}{vu+I{~HX>|!YclobhvG2z9vU;tqZbKE))cb_&P={>Y zA?-~>pbDQ#I#c$jl@Do9f~OA571Mlhf5lO%x$<_(Tm}8GqPJH4Cy1Z3`0!8dc1I(D zDm<}*PIM?>*?Wa?_3CWP^rYUd;LWR) zM$U9L^p~MWhvw98U#lMi!uWG}xqG1FOJ!`hR@cW8Gq-_Gu5alpR~}!Tznh$2AW$Xdbp~F_CpUZ@%(Hw- zDG;bae*m3}bHOR)`_zmtoa-eJs1i#!^!XD>YfE3|Iz3arA6D}Y;;IN&WQ=Y2S~S%mpnR)u>bl%Vrb^RAC7zFZ}O3YAed7YUqgSRnfn`UUV%rx39dBsY z%Y;6&EsK_)kT+ynt^ARm*>I&NuGNxmdl=aLA3M)DY_33{3fqm&Lrx+&Lf_l@#V6AQ z0##^_zQHrmPo019jMQ#S7?0`lF82L_3D%6GtJ`qKfg?5LUrm+NhVxHKeZoWnM*yVB z4;M049p*YNh0^Y2w1J}!(sVxc__6BuBgdsqi3l8{kfwU{UQ#Wj@Ca$yG&^scExmu| zGTE&IXr6$10OFh>70+GORd<9mBoTosan5jchhMcBYd=})(mR4SP$l-e<9zNLM7=}= zs<4Fgea_Fd9P4LHkgm~8CU4qQv6d$}t%K-$fM^3}HS{fPYi&p1oC(s|Lw-#{i*tN;J zSGC#j`~kghHzWL%-S+LG`Y?B9d0KLjKo!n7=xp^mC)LOzUUH)*B7rK3JA39t6pt!k z)jA~g;oIBxa71<-;9j4rnc@>RSHT@M=X>Jf+ZMS)a|R?(g)*LP`-#ixR|>r9(f zO1-*SZ8+l)=M2h-_o^2W*{_KNsze{DobA5)?|?9_<(w(b?s-XNJA$EoGZo?2pU_?wuz@O^)lkH}_5}5XPkG)ljlV#kN-W`&2d|`pau|R8)M#C+c|UN@ zfO84Po@T!>hbT4{z#w-XEn5I%Wt6N$`?C7 zmX*aIfhx2|(btsI)R=7FB`r(QI literal 0 HcmV?d00001 diff --git a/ros2_foxy_core/fanuc_crx_description/meshes/collision/j2.stl b/ros2_foxy_core/fanuc_crx_description/meshes/collision/j2.stl new file mode 100644 index 0000000000000000000000000000000000000000..863dab58b84e8e3e145345307d11fc708c2bd5e0 GIT binary patch literal 48084 zcmbWAcYGDa*Z&8k_Yw%AD7{OG^z7XsHngQtug7l7%oh7>z zQ9%VPAiW7l?;z!Oc9Of_&*U-x{GQkIdU3z;yywi!?#|Af^O@OJt(z9@6)_-UaQC4R zJ&T6N6m1qUB&uomaQ6TCe+S=VZ20Oy{ELoTMADWWT07qa?`K!~*j3ME_SG3X)LSL{ z2s@T#_4O_Kg}3OMQTA8!=9!G`c(1xS`R#*X=ieBkw#C>3OIsIb8FL2F?~eAtznjYc z?fgCYzjvOx(kR$3mJgzTGiI+uRtZ+eiBCh3c1rjk(dS{DIj=(g17pr@)EHYX|I3=q zVnbtdne>tV;p~IEPENLV)@f%4Ow8N$#%|_oW z5-(R5(y6a3=qt| zj%{M>T9r8S=3h&Vw_7$T1X_K4lJ_HF;0V$a4}T9X1j&6uWklG8tJe2c8x zTi>%1j(4*|_}r9hoqR7aHl|`xF}y*z_Wa}+g}~m$UT5s)KXK-X9R;;tnkQ7mNIlT>32ulxsT6*LuF=NA44>ISaj0{Mi72acvjV>K)&N}Kc3-DGYq!Xo^`B^aZt&EDM7X0J-uaAGn>vP1eK#Yx%AGQzZkYsm zrB=52HVLn$dIf1@;Qo<;o;9z31i+^V{mCav-<9%2(NpAgpCY&u@g8Gr#r4uUpT0;N zNwphwFI~v=i|y@VR|9?J*|3ng^sG$u2Kw4=`b|CsgBl0YbMs!=Bc8*R=V_U(ScO2V zg$GvGUHx?@JLsiD{1wxdAO1GGS>wniEizXdZ|(~5c7HpIPpdlAJNC$AIZEJ&!Pxa! zjdw2giMjdZ4ux1>xt@2z)QNV;qKpd7So^JO#euWewDlhi<_~u6rm-Z!+E}@uuXxt` z@^|9A0=|(mj3lQ`{g)S{T20xqR%{^Rcq#&|S`Q78bZ8-`9UpanB=UEird=4?oi{3) z%bG@IO)gcym-FnKq&p8<+QXg~Q2a5rsCk%~?fob%d!1K$=aWON2}C^Ik<-T)hFL|j zcD5fc$>aNWQiSEyw#1EGvy+xl(j06s$BHPSm!aG#44Y}@i%=|8=X${lPwG`bT1S~HGJk7d;fg1#84XH z!bYkDS|yK0$s;&pN85#o0a3eyEBqE?23Ogcw6t}YeYI_ZGpdolWGi)~4!pisR9{&* zIPvxXg;3rGKr^*dvvPz$0*Mm zQF!94;5B2rDg@3M&>v&F+Ez8|T9LtLSJX0x^=)P~Y!P8EzC1vgmmtkpWTzr#=@T~+ z$NbbtA+T0hTgHCLU%|Yb?#DV!qjiPAa*<}N(5orpZPDS})aDt^8`J4gr)MkvJx<u}`OtF(=S?Rf)zc^g&~n>|JN< z!uf-IN15=Ba%-hp{qMa?J_`0Ue;ZL$TQuON;sfVxIPYR?ckMCe(leFx7WXP^%kIX@ z77m-A+1L49^6xuGGf`{N$BHX)=7N<8TGMx?LZFp8Gw2!~YaSXfMLSyist0|b)wPxJ z));!4J5O|GWY2#bZ65El)cAWq84=%Uk(@_8YPmiM-#BV7IK*foG7MA+w8EaIv3=xl zt$X=6?rpW&=)0s$h%;uaKYTaT`@u~4`|CmXLe;nPqM^gJa3UI{BG3wFI5d;VR@*c2 zK`igGbd}M4Nr2b!@p-1l%De>UD~wI3bYJ_UU>py)y~^+%*&}O`*zbNQTA@G2V$0sw z{`?ODt*}juEm&BSA1WEduYLTH@$dKJWvyx-%HYfRBwqerJW9^z==TH5nFlep@A5DD zlM=o8vNjVHg08u1h3{Rt{^0)g2i<+r%6a~1c2B>P*B|u1<=>O$bCJ?akz)yF}J1d8YTjHZeBtdK~Xta=bS0T#`0uz$CA8kDkdUp9xuar+?Ib zJ8>(HpZ=|ucB;@pg+PDUZ}hGuVs6IT+R^crLKI&*+3TUTQ@(&KK9!!gN9b19d*{gFdp~Dpuj9k{ zJ7as(W#Sj9RzEC=HjqH8`6E2Cq$`!HQ>{dWAl{2=)pPMmg+MEu)i5@x>oxrf`4|>E zM`SNlS(bHQY*Jc_y}(#ut)Dq7c!d~rGfKA`M9R7InI$=VxZ1+mGGlde^)vr1y+nL| zf298W*a)je(sR^vN*6noo51^w||!&X7%*AzS_#GS2#Oe$CkL)nj5pGO+oIlK*A0>*Hm1zA@uqXdLut3WZT%`T5tb&@w@{&4##MJCV+dz!J=W8-+OP6LeHXAfye;P`># z3S)Px#PR18%ji8~lR{vRVox)+CMJ%1s*Es3F599IXoddh`G^kY1%AD$b*o;9C(QAA zotgg37WsT{Cbpw~OR#D+&*KXSD=B{`9n4QNfX$(w@P9ka(OyJq3V~MRX9js!Y;J2; zu^nP|fhN39*aU6Ii4Qo<&%OTj0Qx}Ra-PUxp6K<@MQLs*uV%`8mwx->B{X~GFne_g zeB3Tq>snZ8TBjhGrT zYTW?4aQ{UX`eQ8jwQu#D|CALI6Z)G|UuEz*R@(z-SV*fr)_l26&wH%02*@!&Ab%gq?bWsjWO7;Q1uN6*Ml2elU6bG23ow8B1Qto5;_`pZcP+V*dT@bSe= z83WjOyP)q<@vr{U>W3o*l}G_b5NK`CEk-Xv z#GzCKTA@FBqPmvkp=G9OMQi%_%ljXCot69WNdZ25ity=TEcmD5+{zJe*w=mh^?}M> z=RMeRMt+5u`N8{MC&p1GO96TYY0hB6oWXMDBF@}^W&oCdo((@v6(~G>ASNG zHh<}}Nt<6}Xvncyv+aPTnSG6WPY-#ZFYwba%W!4@*JuXNpJo7aJ3f|koC*npl^Foe z3>dpJ@2#9IEh-zN5NL%n4p}P!wMz2W3fn<7O!C)|v0s;7HnR7NHD7mWqFsG3S^k%8 zbK2BJt2H|k*Y&BkFlDyXdg^&&%b-~EXv}7XK&yevA}WhPbL>Uj_NkUi?u3d==*vK=01hfAOpUK?2}9ctwgXoXjn-XEWI;BWe7 zHY@(VP5Z7xA8$yDF){*$u`D%yb$@d={WRwtgYBfWV#y08a* zpcVRKtVL8UKEF#<^Y;>&J^Fz1-j9tb_Od})d>A8BiA(pY^9C8JnM0~?(~!U!E7FX` zZwcb@yr%i6^(KYD*)q};Z=ctOcMHgF-ibeG%$q$;W&t*A8=r(NSBZbOH4<$mMr-$; zjN-csRF)CC1)~Ce`#TOy>eRBi{WLz%H{xEpB!6U*vCv*a#ovo(YX|3yR0xdLA|$}MevveO&d5|A-_oJ zm^_lG>-T~2R*b_kHm}AC&-G>tw5yd=0A$=XG7Eb-LR`A?QtJ`QKz%L&khp zGMLL24A6W>JM!)ua#$JdR`%4<1r#4hGv=B9N>sUBBym-6m_neH+Et-7wsr$ps3s?ONy$VTS& zv2C@nZ;SA8r5aj^*V^0LhvxI4l^Snff5~eujhU|zx_jqv`GIJ`(4k9fJt z7*p#QMII8Y^49%OjMmfqn*Q#Ox3|t%${6Tm6z{79TG1?%+UH*zJSe{2Xw)H=dxBOP zgR*eh@>k+{DCW|WBVGQCd!7=>L~tqst%~PpDoZLb^d-fw_D+9abnGyO&mFPU$ke~5 z{4YzNya`2u)||3d$u)i6FqiqTYiqvhv(84Z;^QUpQ&|+ zll95Om{bH>VceIoXUjFc_tjCnUWdiT9|5DJkE}(~`>3__J2~rs5l@QNF5lx>9TdxN zZC+taztU0?H|D%@u6Z&+cOll0u}k~n_{#E;TCVHWJ^i(bUMEY|uvbFWu@=p z`1rluw0fxsj1(Zv*wlpO`hgAG#i`}t=Hm*ZL!9iizHqvQE1^>tpUA(TF6CrVMia4- zh(A&hxPnBQh!?Z;?lkvlaK5qP1Ix|Qu|tTH^VC0fbS*QN2I%P<><~o?_BZRrh1G4= zD%!rgA;Cf)SX;Rg7O)bw{3~J1T4BCTwp>8Vll(2GTFKu|YpES>NwOUR+TjvZ_auMa zk!EcCi&>%vwcJN7e{$oLv^tr)tA$ob(|z^55Zx(~`s9~Dg{b@W`Xpx+)}vHai({| zUwwVCpB_OiUq~&V@T#JWp5LCxExebgUodT^7UDkiyOTk)OFUf%l2lp zehTj+*PndY^Q4_MAJlc$gD+2vqxZ<6h0z`-Lcc9tCKHLtcQ2H2=;*>(E%Z(IZrLEY zN_{Zzt>Oc%)LP9Y!dVH^`c@&(3Tw#NsWL(OWok$8p;_WVul2I-9UJ_i)LkX!reqrE zUxmP|gPLjR8#_nViq`20f#qTiNyCytOh`qb75bBRyYAfWkCX3qIRZG(2U;QhKO*J% za0$Hoke1Jf4$p^6V7Yk5$fs6^r`9FV3hzqBjP2L-2zt&(|6AR823-R0e5@h8)rfF> z#HJ#!T%;LWwRok+x!Vs`2r{oN>0H(s0T$@PmAf79F~;uETGJV?ZqI9@5HxbSV^^kT z31dAN1ETzS*CzaFx$NfbebW_U<;l_Buq@;3R|{Vx;VPUlYB6`(;q(Cd zKr3~9or&eny=Y<4XVGSAUIv~o-v44rUwq=3deOy0lcVK@z;#E!`=BCtqlrONW z`E<`F(Xi+Ng+Qxai@RF!SBBU{V;r5#@q01mvu^E-O)uN(Ilhgx+EwUbhxN+g!+aEG z%oy8QY_R#FRjBAPak4_771ofkmWzj&k2`hJ8rEN?H~(d<6+wBfnR{|5D;9M%@vv~5 zxxGy}?UcR2ljrs%s|698FK6*##!Stty&z&ut8!YkB$YrbRiF6iajbc1O@8C*W|crI zRjYQFh^s{WyHzF73Tw#N+9jjSXU7^F2Q${tv;Q1#b$c3Vmn)S`X$R7b-F`gU+;%hG zI9Z~cLZB7)G-F#yNQ!w?>%RZuAzvr8{oq8aL01 zN*Zpjd8#F$71E653m;+5Jlssoiz_LRKr3}^uyoH5v-rLxA|#@L;sdj<=#R0eS`p^O zoEJpIvJ(nHBZJg(rbO}N@8tY>>F5YkYkXc*d-0<}P^{0jLVt`=tvJ-m3oZ9Tei(G& z)K?t($|b1fGE3^HmDPN0<~@;oMMp!_Y}3o>E0@3#4)dzAcRBQ~OJF7z{ZWK|^l*N( zM{BXFN>#-NmWwoF)K?t(%JqR7QH+tw>%rlAxCB~Zn;84ubnX)jVKA#+8JW`f>0Zl0S)B3E-u*Zg@K{*+>tt)8^h6E-#U zI&sQR|IY5i7&}JmDLP2R9U`WuBG3x`(cCAj9{+esdQ8UyB zsa*oC)aPSDsaSsIgGa^;pVVx-1X`g##zJ0x!s~oAQ+r|tbL)x68*{9kz3+qkKFok) z=8tCK^~&+Ncg7pLI&+0UE6f5iHe+-np5x=E`e5AUo?;zMQcPp>fMPOynJM=ZA=(iQXzW0-%;LUL9_EX`dv5MPcf7+Iv-u_ zg0VNLtU_Sjk!CC`vIZ~p-d1CL;~<5=njlSD=a80sl6k_on3$VSn$*XeaaXuq^RwJa zO;jJXMpfqR28|Z99=%92<`k-;5NM^U6Na02^=mah5KFp;nHd*k@wUy?-TvyY*%oHs)wT0G zaaaGFi2bPuw89KOW9MR?>Id03#y(PFqYtz~f237g`@3E+OD`?HM-=}o=7QACcdSy- zhq?4A=KYZEb6VPm>F>0UWxt_MnLSr)aiG6KUcMxBdYydu5QedQubKD897U$+6g!V?hFI$XMPBMfs|KcO_oV-9RDG3da@7RNpGj zgAT=OLk84S2(&_fGST%Qmb%?3MnU-XD8A zSLYR5l#uVG+#B;LS+d71a>=p%Oy#_EUzH%@2oVoc5tvKE92;X-T36v62QLv(R$0Xd z)=;fg;hov|vg?b*g9i;20=y7q~7vz6|-dBLOgQ& z)etAQ{naPAeMqS7C>@iHHz&gE_*6#%%SBpd+)c>1TaeYa{5w?WO)d48&VEIDpKtDF zLRQ};&l`#5~^AZ#0B`$$hst-~Qn4lc6 z{K^5eA{~I`-)SRv@R-gHp6axNht~ZvD(kEPkia%koFP^-JErX5K?2J~nz8`*s+$c{ z)CowCQo*eu(o$<+hEXiT(HbCuHNn-3)H9e9QuGW+keS=jWESUWVw!d7=55`sY5pXI%FhJy@NFE|2VTz?^ZC{ z9F=XWmj3j2A!};Sl8O}6t)PmTv6C6M=wUksnTMvR1X`g|nr39iCVlbkL1v|^Lh*rC z=r38f>}RLedr31jSPq-ZNCu&)zgEsQphKr5^v#oMzimofbbRnIE~ z#`n=5W4*hrlQHCxFA69GmW$dS*>V9bPlDccbxW!$jCxl<@45t9kv~^cCa<7?E9eqv zg*qwO4&lVYQ`#ZRa(WjPR7lI~A>ewr1m0uRS4mEM-%+HI%7UW*a6McC%SD>8zQ0^E z%(k&+mNr|o`@LQt{5;Pbc_*T#4AondV>x-l*w`%Aj99%-A<#-~d9&%ajEVJP%_2)x zA83XCD8e%RmIsKsP%BsOrQW+#D-YDlCD00MC|mAB7Is%9k8&XKvZKRUyy{wOEV|jLgZ0v}t1=Zn|9|&fUtq^F1{uuk}%@`3d&XagH`$$LkDivmq?iICTs1_rgOy~m9x7l>9%iEy}fmS1x zU8eTylY$+cti4~ew?d#5>X~Q<=r5N9i&=VL%DV`KKr2+)&>pO6rZM-UKaXpFXkcvR9 z8WAon2{!D54BEvvas1Z0Zk7Lj)6)L?NuUqQRf(<>PJ3E4NN;YmJM!y;n@R21h6({b z)RZ~TqcfiyGRM)8MKoHfHzT4bDbJ9=*(B18jr??iUXo^(ZC_PXh>q<`%6aM1xp|ct zIb#KS?eG*QV$!;r3V}62nrd~SsJZ<8-H8in{gG}~khPX}36!H<0;s=2wHWOT`>D9u zleEseNb8IQ&BEpWA4m6$G-JiO1exjkE!O^-SChxTt||8kZ!ePHhiWraB+>OKqMN@p znXUaAUO^$y3KdX{ow;A!JTY~$HZZE5LSPNmcGwq-nDsX;(Q1rnq!4I@HB6q7IXOsY zW=5GqISX?#?x+^P*_q5*3V+rT2~;W|Ewh$V&){S&kw85I(lVI@N`FbP@}GPiikd4_Rxy@s z^(~_Y5fxJrXob2g+QBojoY?=}X#V@lCC2mMVbaH_`ssXVr7E4S60wtrA5sx$rS3(p zcXPQuY4>3Md4bu+^K!9XryU_7@A+_VCq{1RG!i1F5z#sofmWzaVk~IuJI~1Av0Thu zX58%4TKX7u@l_~ll~9pH`whN%=lPO|=cx#^LOl~>TK+NoN{#DU_0Oy56<#{(rUWZ? zaaJE{m{i@8LtG}plZr@qK2p;23+GU1T6wK_WPBZe-Pkj4jQM0r=YvPT4Y!|HTW&pX zxccCV%~5vrkfqLE8TXtS#-=^YF8G~}qQZ(1Ch3Th{5xupsF`){L1!=72Zt70v`YPQ zoye22R|W~ZcU4VMyJ0Pbe+Lf|XroO0GEX~Y#4bH7{@mQhe6C$LTjw8QSKj}nl`7-zY69qqTJo=FYuo{`s8~OT;C=$N zSZa=*e0aczOQ03{lW(?NT8MKV_nQUu_r};g#=pR2u|~M+K1z;iX6QUX?*1B$I(NPzDWLd z^hKnZaaCwig(O#AjtU70QcxZAE2xmB88WEbNTnmoa`rppTSoOUG^JLKrU(hNQhktC zP3qxNc1XKEFiL^`Z=fEP43)@s#dKMDH@$x{Y{ESB+v@|(a7+kfaeMky}GRvdQ6Qn@_wB#I|+4tsP~hq zNdcd)mb19?v(=wF3ED|*glNzQDLvBihWaYva+|0)DpVQwm!*!3R-THzX(Vi~^# za!1$as98s)?=0)PCf%P&sM1n*_xp(#sR*>fUZ5Q#qzVfsAK#NI41J&$3;i)RnKkA$ zN9Qmzcb%mWs0u@xcK1`+pfHusxuY<}(Fe70bOlKb=2z*F8qX!r3e|g*V+n3;9@oDR z+<2xBFWtu4_wfL`e%m}gREVh>uYyEuB%)C&qDhl3R{fs6?Z~n!&DhveZOyxT1I6g) z89C)uxKTbaO1_YxhvT771K=sjDK&37ex* za>7WU75XC|#~YeMejO)TmB_33z`A1}($1H-j%NCyU5wM4Gw{=8`&tLbgxhEI+)B$; zA7>kNF^BBRZOn^g3V~L5>J+VOf9_%iPO2|<&-+J@{%WYzzHEeD`dm)s3StdO#X6y< zx%GB)VIM!P5U8`m>rXqRzp82$+?rs_?pBk}?;UDIcWG~rKa|ghy}M&qT`Ob$_ICIK zC*%G{x|(L$fg`oAp9d)fTH$(EY9>s-W`cAQmS0Ulstz}MLU|+kJ6SV9x(xFp(q(u^ zmw^OkWsoMlPfRxRbBX~7%12S&NtWg0=&)SMQziK`Ta5i1FwDF+GDxd>YQ8=zJkAE$10ZaUgBarMtCfmW!dWNZi#n~$_i z6em>zt+0lS)vZ3ryjgl_qW8!)z1hSu)=Fx}gL`T_kY=n*<9;TupHn;j^pHZ}-KXyJ z3epCdg?^}_h5fAhKr6LYs~be}yMv~SZ#Qoh{l1^-{hST8vz-1{IaLGITZ~=k-h;pO zt`@PMeX9^?HEPThZ^KK&?OXO^ik{d0xI1s+NfaHfE)g4=Px214W9)Pf9wea^(sZuc zsBYZ*(f8sAog|0^TB#bZO`BTrhk5slE{Fb72#nUEKdHv$pvLw3)wrlBqUX_7K*^_; zJ5TLldTQzEbP2Sg=ilpp{u!IK;#1y)?)I92RrO_)i^{#oiymk5VWgR|eO`ZFm7>l> z)F9%IR0LX~%8JgJ__+ixM}+ohqv8XtFxyMnzI~bbdn4PLYffZT2#lU%4H;V1?@(`B8hs|y=!41{)c%lKWM6gO@WOEINWE$bfmWzzqPt{F6@Ih$0wdeR zS_*+ym`kTv_`+(u%*C$_Zv)i_T44=ozFVj{&v$-;)-gu`K5kM^d49>%4Y`%`OK6-2 z6;hw}v-Rman``!!VZ3aHbs^2)G`EX?6zI$9n-UTw+C z5+c=FAg$n%h)zWOor=Jk zAWb86^j$qK^vHvw=RW3D%IY<}pF~lf;?Ef)S$?0!_s8`2^m!jI5o>Qm^V5s};aA&5*&}xbDmfOFxYH;-pY-&ImZL#u{?R9YhB$H2 zUcVJk&XZBKQMpLtHG(u=&q?Ej1X`i?i_TReP0`P!DGDJ?k-n|5)JCyuxqYaUQr`yN zcqO?2;EKI{eOxAXVH zs~lDFlpiL0(h<=o6@fKDn$~Ld>g$Y%8#~e~KCp&J%iOjJxotWn+s&W53L#Y|L-}(P z^5-srR;baCIeHUv^e%x`G-q)A$(f7^Ga30`oVgFK2UMjK&6Z4;2E|2WWYalu5o@T{iuT<} zAI`ozB+v)abZ!*w<8<~~I&oekFnX%SMIRC2M2eia4-!}tr0JYH+9m5mQk_$vkibY9 z){r8Q6gzf^eiTba0;6?E%hM?ZoKETX71kYT$`z&GpobhBWY%7_&NKDuMLB-_@KaVF z>SSH;&hR zRIBoTMe00n33)2lk&M}VST2rsv^z88SN$Q4iMe`wr|)T;)9Z}w4?H=QaZn}ldw3`Ry8=qCRh`6}98KA3xV(gQs zyQ0!C&6p7{=b}l@n!}k>qm`;cx;5ag5W_X&$T*ciD^-y~Gh`EH$gU5xqS>;mXJL$H z;U>(&T>`CWMxNxHCzX6|6wUMn%=BFXt!UOS3FibV#%SdwoOP75@}haIB%IY2t@PZU z#$KQ|&X`@IK+2pN3ACbhiR+s()#RgN%32Kxyn^UYu5pBaje`W1tG0vY?ZQ8AM*^*A zK5zQx^P~~}_)PHl&`#R+7jgX1uakJY?5*taq`yj~#RA3FC%4LL3mT8t>OD~jRB5Rv ze+7PWKKR!^#%m3psRUY~KRTKF{`mt3R!`E7Je7p`U$sJ-B6m4?;;65uXmcN_1X`h{ zOt$<0wA}T9R%)$C<7I%xE6Is$Im$B}eVp;?f66n`su`eFa|yJsK0 zqg;PDcXi(B1)Y_bd%q$r3D18KXhpOKR+5qLPU(QxRxYPtQ)-O8S;i$Rj#2D_ztS zzr@8q4n-@Z>D-TQ(MA>`+NC1U3eWUnEap`u^GcyWbNscxMEJ1YR^0sYcA}Nr$-c_@ zwX?qg=cV-K96j9h?{}uywBkaMz}qZrhgYU5;)UGS}K0c`=t0? zNs3=m`C9%RhxF!jwQ;27r5;H>jbH8`G-3asOQ02MO&Fs+iYDw)bP2RV6^YzaEx+uL zvZq?M(AiUstwqJ2)H<8fQnb$W4tEK(!ZuOnr`W+8?7{ zDg;`oF=RSngTo0MUjLaKm^V=ORJVE1kC**9j~M>@PUlPxm%!`-(zG|@Mhu@*wUd$9 zv7Mf+;RNq~$}ZKqn9YZ@>f`ix!+1p254E4-=O_fWyv^6K-X>I1%`cq!ZqJS*`P^IK zTBmd)6#{jANYnF?cg5}+k`o#TbNF4TLGsyJT`G3VO^QR25~ zg+Qg7s?v*J{;#nh_JBwvts45ka#0&cJKUBA2_<`5?A*0 zGc(+YJ>dIlh`n*ZmlkT{RCU|6V*$pDf|hu)TP4s6YnZI^?v`nq=(k~bY9Fp*5B<@; z?T6WQFDV);lA@9Nq^@7Nh}yVRdboT!^p7?sh@8~BNT3y7n`D*Vn`7u9#s`v4N^{f`-XH_ zNT3zgkg=EK!#Op3XVc#eB+v?bfihThPPjvyqI1KMKr5`FBocv;O3BpiKw8#HuC`NZ zhMkZ49i7tUwsHT(pL`kIR6I}wWu!f|kp6B6zuiha_XUlJ1nm*85 z_sJN$&zO&#ovg0@PF1(fJmcYZiyh*@)6?H*3ro^)`JvV(WKaVzhqu#cfSR@`&|{9 zs@S6Q08BU!z$I{vgK9CxZq;dR*5_Y{38aTZA6RZG1sy52woR-rj+0_*!iX>{Ym+E@ zPKG=_RBx$@t?4`4n;RyU5Unz%=SZNHs)s8`J~mINFW#o|fmY~`)NNb4n%^X9;#}x$ z{nYKjR-17>?2tOSlv*Lp*!K_mnFmhh5n-ox>R+uHY85FIVGk$e8S02=o+x|TImL%Y zpY8q3*lYPjsU5o%0tGjpq0Aj%=3+A&fGgq%k-|ILZB7ako4_$TbK#Ke~6GXNA&ca z+gmJYm_6o)Tt2)rP`5^V$qv*rum6?K{B@_T5NL&}H^!%;`hj8s1}!=|t=!;$bQRwQ5K+*6o{i{NvAWi06NQDIR<>*85~k zoc-mM=SisdQZ-&(*S6!Q+T9QpZm0xWp_Z5SlC5gShwu7X)NFQ9@qwc=`Xi+i5pRe% zn~K0U1Jd+XThWZKKk%~%`%LwLH9?xrp%3iJ{iiz8-Qe|~-iXRG)R#&9F8AwqX~gmR zRlYPDxMvp8m?*Vsj;>c~Quzm@N!>%E4-!}|t|lpZP$Pmrt8-lI_03g1wBAs!6MMP7 zJ%5A)UO&q3y5S`Gr34oEoIlCa@;B$1H6EbrR?=Z34?x z_p2o{|F<2e(LjG``@nK>pI_Ppo@Rvp(k8H6+*g=3f!{7de`ym~uDatenfbqch2P3R ze`))`a&f<6+5~>51O25HLx_JQT9r^=`0 z1Ha&b{?hh=<>EQ}X%qPM5cHQef#s?v@Tb)d+!c-f()NMn;`dq8CUB=W`b(R@a`Ahx zX%qO(5A>Hdf#s@SicMzz?|p^e0zrRi`@nMXYrAO^_>B?tmo|ars^8&Fs~z|q3-p(^ z4=fkI@0~V*U)?}|X%kp3exW370>9>g{?aC}T+FwmP2iq$^p`e)`Bzcc0vjCk670-tEWo&F3TQwyYg#mpvNj!|bb?ugwshQJ;Nttmt%bSZc!6 z@{*4bzp9)xUO@%)IjyURmyt0FfmYaWjFo&;g%A34op{%%6#r>`GjC++A$DM^JU&`& zx#t|BGM99Hf0Xe!IPQmak<+8_EV$(b^qdPK}mMSL9Dx2{9a zy`<98hw)!N9Dn|D$)BqnB5m!99@^zbv1az|w>?-Z=ePg6hUkwJjijy3Od7B30XOu( z*lfFPfr*Z-=FTP1N>!ebu1|oj&n3`G-FH{D*b=<~^;NrL#q@P|Bcyil^Y|=2 z)GDH4kFi0dfpmybtJisuKn*0)bl&TX>mKL6vRhoykih#2X~qU`D&x6CM6sObJ(=cQ zlXrN`%xpfqYDm*p_?k?XJ_dbZDFj;K9YfdS<}*)YYDZ7HOV9`2mFSPoRkP~p4zZE$ zL?p0Wq!|l;w#{%_e(TUu&y#MArNXd&>#R~q?th|Cc}U-0ZW1p(BOm{qiPVumE4=V0lDUMifgJ651Gwva$8jN;K*_hGMu6CK=5=hh-Y?+iDJ zhy6z1?IXf}(k&8LF4A%o6)=j*E0{7;%iqpOjrW)wsRfMGE`je1>}mNn5b!o|3ADnI zNS*;9^EfGIK*&6fb7};tuJP;)nNbw}j3Q+YT>`C8t4jNdNbd@#Mz{p#htQwQrOKR_ zlS@S(ST1I>w$GH%CqoIiueQB+zQ_2-jQ;3Mj;C#T^ZJ{`+2JaI zR_Kqun{lfH9~jnKyqEovxLS0wH{+1O_Jy`NEvyOl0`=|(9r?q$ecE9u7D6`wFgZKm%3*pscSxp_x+^H_(B=8nEmR;QQa?6xZkD(CN_ zZjE-C-YaijIh)I@QUA3-0CU;?*unXJr@7qSL8fw_+T+Ubh&9fJSMY@e^1oesK zC{pfLdCx*CREUvkvQR&>R?3$)kU%R`i!tV$yzf7OpE9oU^d#rhebmOOS~cgSlbtE& zmmq;w>RCt*;Xfk<3A9qr()%)V6Vo{@^e&wiiUd7HmjAR+y2o6_9_=O%Z)A>6IV}_k zw8A#g2)DH>uVQH8KII3ae;eSvGd|o7{3VxjmW7)IP-FTXei_LBDxFWO^x;mu)%H=| z%cSM%Uni#zbzQ1r>*tuhJZIMO+Lu3luMlX3Iyt(6-w)*38!b+(m0$IN$}{vw=dd*C z!q3;rZD>6iKk4b~JvSoUPSkSyuv}F^_qn$lU);a4D02FS{?YLv-U8=(*oOlsGYY++ zw)}Z~Bro)-FoGAHQ3&*bG_BRX8O=9&YZ_Cv8v5Q7le{IUuab(=YzfqK>bE&&Y>4IW zq6--dc3B=I&_9TAyBX@`0}Hg6xs7lsT?JpGkQpcP(C`c{fPjJMxEDlrFr zTn2rhm0GLa-;LszgPR*`i#K$>QRVf2ISZ{+ed3)1qxpxeM;rCE$_jy2*wb_@XV=l( zep}xN91yG!Xodb5%h2?n#HlxaG^($NHH*J)fAIPj;r5|A%dJ77^$s=;4!1WnUvA;) zf}}|K$}m1CHr|-qLnY7(&+a4b;741GnR)9QhYqU*TA@E0sp~E>-fi5U*jkS>tGy_7 z@QeH1?HQ43t&pbkEWHbi{EOEmj;NoCfD;gN{F`;dz+zqPjrW|d1h;*3EV0<}lg8CK zv5F6+9ncH3r@F@b2l98$FE+OsYwrHwx>!4_yFF=!dg3C|$uXIkmjlGg1}Z_c4zzoY zUotU+h*hZw)bgRmFPWGX*30PpWt>tgY%Thu_2AV;ya2sxhu)hd+8i3{T|)2LT9258 z`C8QFFt*QVz{~t~MRd+~MIkV&i!|LO_sjDQf8{b~c;&m+>wi0=_D9wG(EFUj``jha z3KdC=y;vD$K6_eGB<;JUXHDpDg>?wGr@qMLL*R0zz`BTf3m z1>Xm^ zGyZ;NIQxX17%~zV{h(N%8{?pP$%`I|POL8nMbDAI2qgL=f?}_Y$j3N}y;7`C#$KK1 zAjU}5*egW`b%+kS1X^Ju8eY~ z#CMaN9(7{K7Aytm{>k1RVT0|J)w5d|JHaRg zow@vNdwy}s3NiMR^9q4h7~`Pm$B&(O_OIi_se0EH0%_~aZ@#G+j16auZV zhV*>IS2k{I%Y@Z^2+x}B#qJ=AWfVyj%fJ{1X$M>B!4vM66aNk#qY!ANMn9a<=kqSb z#3#p907?9L* znxN%$3A7@er5iz#%1jfKnJ$4=SVO6^G(l(S5;O~U+k`cgT22$RoGyXoBFz|`Ibgz> z1D5}k0*p+l(I`6Cz=U%RTmr2yqQh91!X3@_O`^nVia=5f(Ix0PxBL-W^haN)ARsMcORh2M*0`m2 zjqmS0&@SAr@~;|=!Zy)46KBGBv8TDkH0!QHpbs?~H7i>L&wMdZRNeoFUU{|y z+TT9N>BIiPnJmr1ef{}G?;0cK(gB6QYk)M(EVIo?JaXu&(IYI@%+P+9xpZ}RyMMeI z@xb^4W9v3%H_A=cja&2L6auYq<;~c~7rJZD--H=EXnjsTxZek^$yMSMU*O62`!|UV zDVA|Fe~G$rx4YXVqn2A}MbQuU#DCf$-FJ~^+&v?)jYlQW>cV>s>(23o+m%0aq90%6 z$?ADLj~mnGs|3~%{V^6jaEIq+@%Bd1jj_)6ChGdXH-Y7%KgO;fI;IWYchaajS0%7b zNXu_pc;K5Bt`961BO&yh$IsI0Pq=2>>#X{~cA!7X-PL$MIA2N>2it+=;dI_AMK-W%lU7oa+{@Q$Tz3g|E|SoOR5OV#US30-p=94Z)cZ4D~z4c z`s2Qj|K8^x@k8>P(BdgbA4R;Hh4MR|2cq^q`L1;dEEj3U5)W46?YqAa+w){F zYdq`YeQ#=U3HOw4#u~2Wb2 zck{Qxvy7l`A1DM`VGU{RT)4k^=A$dd%7lG-!q%Zy{X;$Npes3jC8i9uO7`w)Z@jPW zN}^pUZ~B>^w$CVjuy-p2jaQa`hdl0SqOV|l7HOVs9UzY1IH?e5MPs6S{x+S~^D4re zeltKs1)o+3w89$F-i!hf=F9_u;?BH3^rmNrSdXssum|SLrL+TS#{T}ghk4@8M`Cx& za|(f0YE&)f-acl%hD(ivRo^QFT47JqjI3vWb8M4|#$YQ^AuINNOGLx5Q><4PhTDaYJa%?9x~pGQLy#6HyoWi}vsxVe{9A=UE4u!c z|73n@$Cg&+_+0x%?WDgH0&9r==wym>5$1tvvxPXfMdUv*)zVH3vBNIBPQr50A7i3< zq**R>x_G*3t3sd^-N&xNgRzR`yYtV6&oG`BeyG>U(a(FLeYkz9bZ#H6km!Bop0LB% z@oZgrg15Z!&)qi)fmZ6utMaNa-Z}RRV-C%I&<9%Knu>Nvp9|xmz1|Z6lkO`7T447R|!lOstxHZMy&2 zfg39_3UOQ|(2C~m?y8TXoJU6{mfGIM=#~(t_&_UlRn+tC%>$A1dKe!qRtdDi8q$h> zMjf7g!6k8iO(wI$tG?d#Ph;(Di62@xTUO`P1`%WDUlNZ}5okptgV!GkqpS?&YulW= zB3{#2f*f!`?ZGr>z}XAV zQ7B)VtDTv>*k-Y!@)_}Cr>R!({lRwncj+x0CGdHqc*%>lW{D3si%K(90!KJ}=IL0@ zCvD9hq@dGBsRUY~Kl)bu!-i)2$V9Qb#ykD)u%=d)KxA RTrGaS{Fg$Y75ZcB{{hgN4NU+5 literal 0 HcmV?d00001 diff --git a/ros2_foxy_core/fanuc_crx_description/meshes/collision/j3.stl b/ros2_foxy_core/fanuc_crx_description/meshes/collision/j3.stl new file mode 100644 index 0000000000000000000000000000000000000000..5e49acfecdeb0e52471b13d0348b150052847c52 GIT binary patch literal 50484 zcmbTfXIKz-l5RL0zba}@e+JezKt&_(Nt0b%iEBy~Kd{_m2_Qr2;6ijEovQEA>r>5BYy*MHI%dcN2XS&x~bXb2^HdG(`RnwDd zT(@~*KQ6WB0Ypw9lyn4DxdmINh3Km*jE5u59XL(i_w66c=VM{Qu+g^Z1Z!%1h;IB| z8u#5A?Oj1f=Mes0zClHKw|^PS_~IkDp}NxA-|Bm_fvvTvr%!8xx-?g5JG_B74#c>0 z1XVfC0%NY3bIYzz&T0K>#DI-X>dwLyf||Y=pYFJB!FGF$J#TtNT9thuud;HF#qg^7 z0h3y_;X!NLawXKgd55Z53U9O;f8U?jK+S!rGyD!K{z>Y7w=MUG&SY!3oiJ2e`&LlL z9s6c|c-dJkSG<|}>qB{Hd0drLX}x76SA+a)HWm(QrVf2GJp~_^+MAF`(#m)4$V*N8 zE^pqmPxhbQK|LQ@N_~IW&l)pGQ71$;R?ELH%8lREpEiecxcb6aEp$#GpFgZJFYv4( zzjCmI+F*P%QDK@fzheW%)ZH_*O2zid-`eyBKj-W0!8?U*j@Kh!MOZ(SKcoyiHrn?0 z=~YI-HBUOyUv%A?pk>)62+__uP(L0Vq(5KwmC%f7m70q-SEg&3U7Y#a_&&Dd1{`)( zvArX`YujwxW!}(^?Ymox{ihPNvYm1e0^7heV5Ke(lfP| z{G*ig*JPVlf6w|Jb(RY{yIRLS;4O@EM2A2`OidTzmCjVtKgoWEPsc?Co$ z5I52hRONURF%~>~i5!sFO)Olz-Gbg~HXA$ohvQ9xkWEm>_4i_hcVZ)(v3x49;T<=k) zj~SkGuc@-D^H5QvP;p!T@c{m1`VDUhdxdPno1sn2c)2T!5}&`Gu&L|>R>7TUI}2&= z624-zeD2C{F}l?!lW|--fmLuH+la;u=6NzUD`m7i@!fC{TXC~LCa4OxW8S=bQk6UI z+5=@Y^ak$g{jz;i20Whx$8_`z#@}b?ijq`mGW^{yOE!7ViIZALl+k}U2=uI^ql>P~ z2j_^fe+I?^;THVY>C=+YlTjPE#|dg}*}SSc z>86t9vvD@vfQxo@6J4K|k3MtDddYh+~?uTSul?rh`|bSuilmdY^ra5foi$7LNShHzfO$Zj&zm18y4g*uY~gTO&==(E8Wz(cL&%A$Gzkh z?66m4W_wE`7-hU^Q;x6p-fJ6+l| z+hgoS);8kg-L=xU&e?g6&~San*%L~s-j&pLU1Ie$eU>Q8a(+}g`LwtF_MKD}&ei5Z zVdC}p+VZp)-(^fpZW68+-FrppwXK3$wN{kv3GS8S6+DB{v0){C*r!)>Z!6X`S4u`=E3LRypj!OWkLl)NM`<{xqUB7xfw{wca|b2badEczjL0 zx&Wi_5V#W;!zg^>))uz6W%b%a34yOaV_D#dst?2$c%m?YRrGGRz&mjnT#u3PPQ(OO z;rAnB&5Eqm3}T1co)B1t+r(J0$SBc$YPdGjGD$A;I6iGuoOdi4-FKKYNw2!uN<)|XM981tv zWDXz%R^b@{oZSn-;%G`et!Lk|{P|mWYJXN$^0|7e*d8U8<*z4ty==mXN z`_MN|%pKH8>*7^f%5!0&tsTDm=WfL3s_Oo!di=&CLG>G6f)PoMcB4hR!wK56LCJ)` za|28>cKpr=aS@){`%nLon!lK8d&`Xf{k5S9O>#I~lB zZS>E>F$$(3!t!OL_@Z{zjviO!R+h^{y!Iiz;I|_|A(lxyElt6P%!>i%f^C?NbQ-P?of1Uhxdu!p*{GKhs z;u+T8lT$C}DVFpA}KM!_t2+AUmhzHl&d$*?~IyAA34VMp+m5f!&=*IZ-#EE!Qma{Ewe~-(!1>SI@DwP#R zRP8`O9~l#Pyi>hBw-LiS9fW?c$l;Gt;{sv)XPHdm_?iN$DAPiX{#wR%4eXIZ8XX+7 z^P=SC)}PB+C2YQ4WQ>&EZj^UQSTt@>fJ5v>mGB%)vKOoHi@^(%1#ApdS!r;NJZNM75Z-nOB*nT*oSWZD0%scS%#Y z=BMB;!30*}JBG0fbF+!P6*BUKx?X(kL0K2wGO6X`14#^k&ZDlKePZ@hZaeuFb)7b_v!$4a=j> ztK>~u-lkMteQc||YCx@u@UEO0kxR7vw*>#zB`+ax%c+e@ZFWi7cE#{4YqQJANfXpJ zX9lY)l9mM-_p3c#V*GZ@==+CUl{U=m&)=0c+ah-@*Vk9)_ZpCH-tQJ{j|VW;#F^xxzTa_ z+uA4%6UH^Lzln_B_6QPV?e17i_g}u&ufIxH#T+dzAE(hgupt z#i~mloeV-YY>_*Mjg;C>@}O-YJmF?BTQq9?&p@?IgJ8H)Zo&2l)TuC7*C`jQdOMlm z@3-7OQ}bfbOmCjXD+$P^s0Pjwi<+>DjdJMbuot=)1W$6yHXoQJM2*|<6PP8 zF_wSoEa}9wCj5>lz>`krS3b3>r>5ksL)O)3I}Q|FE>-H>ioeK{ix5TH{TBi|}?I z>v69ipOgZvi>cR?zH0i|qWw%W_PBFCIgfW)-Xgz32z)*0)w~|>DyLer@D&4E^A<1? zo(d!3$X$_Y-yM6D7CoHR`%i|$8O5W%=k;9WAM^6@tgo980;{NpU);vq#));OT$3;U zlWOao4=n$w;P@qu`#}_^$aq`t9FmT}JsGAMGso_<+4xp{FR_7pQA{(YmiMys3LV1t z7oH{`TsPM088cYT_17u|dq};?*|?XDc;eBY5RY!Hw$Z(6k0mtBVj7;)3>&L%EtN++ z^|h(aW;~?e_~pT7`%?_tZ#JEP-eAjbVof>%dxB}kf_}GSAG8D8z-_`bL~Ap5)NXsj zOv0x;C6Fhk4%vly<49PWXaZhcKRHJ$u_A_d98`c1SS9LAw~ff62V@5#c*k5Vap(}P zx~-H)7s@WxYtdh=vEr?QTT9y^8a5SE|DG>T4Po4ET01@0=9fy(*s>(visP`1&A2TK z^Lr=$b>|Iv>%Yx(m!xcJQJ>N(9%azDXykWURGZ<%57)X$2&{^_(MlgzAfvh^Lut74 z_xjZkzPsaPeNuV8?NX3lsL~O|%e#S!J;9M;#+=U;5MkAW`Oo zJ03UvBzYBxmp5)2W{V*|iI}X!Oi6_E?wHro_;tXLtn#vNhvlF7`ts7}Q-a)fe^SCm zPE@gq&T&hOj+aJs$;Jm{YfA{MqVL_j5Z^T-^!p&b+ih4s+dL}r`y>)|#v>=juKI1% z=1+VhZ?|+N1XhJ+^h*iX?kRmM8!MyR%8oS6^UTPPo~1T$o2XZrZmf|?FOQe2Cq)q( zM$7Hz4W9+ZevaELiSd)=xm$+)4`E*s!1fp`1yQvXX;C$fB55j$u%*lWfT%wFH%1u$ z#{^o{PnRuZDF1`78gU;ZLkvX?;asKt_rEq!Jjw71-a2XY9|_%1896K{w)h7dpn`w3 zL`i__!!83f}z}fg)ZCw)aQE)(#^B0!3^8U<1X=6m0LmZQ$eLDEA); z+xdZv1S^fh{a4Ge3VZn9Hn1niL%4JP%LZ1V>+uHytI*YiGyY#TunOI~e;}}m#=?<} zG3lNt@Y!~UlPLFpdxhw9QEp^|Jheas88&`L&*6Sbv-jUN&~vAw=i|>Ux7{ViiU7LX z|3F|Bx_AG41#LFq`7l;9Y`=}W66OZ^#!C66MD66m(Y79E^_6_eX5Xpl-cgQB6&U+e zT`%=*QcAn|o)ShM<;Z|>^jC~^?K4f9^u3(4vT_`;k-k^6zqJ{AHfg9hTcoD;%WJ8; z@xXZfEPol)<=!EMtO=6UzRY5Pc>BaxyOCff1X|Nk$eJGW^^6pq2i*-!zO{%DxDO}x z*sqd zgup6%-WaPgr;P}`Q&f6)FgqW9zn8xHXldnjgOV!FVZbzFecjuNUJY|dsV}n;0;{lx zjE%n7NEBbW>riT~!i2ypvDhBuA&0dVL34|0xmM*Q1U@c4Z;aLG)KJVD>#J?l-3WnI z*dF9xHMnd!n7N_m-38)Tfx>EJ$969fL&ha&brG(|_2j3Pk~-1l*KIe=Wo&Qmdj7q&gIK8C-5;Z386I3AwrX!R1K}_rr=%;_labsnh;op*Ss0a*fma+c+f>VHpxrt zJ#4DJ_25=o_=hvEuD|53Rt@yfP-R3VX=dnNxA1dWpNq#d4M+HgHY=w#QiZ z39(|ughc^!tK}g!@Nw~ZgG{Hoqs6Z0yG;AuJs~!*3fqIc@ZY)TS+@xbdJmF30MwU2 z&uL_mA4tn27nnd#ZMr;w*SWfiCrWdz>YbOwM)M{y`bM8@id(TSR!ozu7Yn*-R_qDB z^Wp82d6ekZyqk9TWDp_H^+@@rz!W{O)rFwF``bc0P@W7S@NqE>HU@SUNn5y9vg`-T zkZD78Wqy7o;7%?b`;OZLxtvj5#GS~c$w{N%5(2Agk4(!#Tf6Q9c!lz01j<#>(VKx} zT##HGLg29|_K>lNLiNPbJWaLr@x^?ib{8jW>U5$R;u0Bc1+)Ts5|)cp}9@NqE> zJq~#F7QA}2+|W(yGPbvl86~jl>6TZvBV~RW3+-rLE4MtN=W*GmR3Fg=GD(l7Ws<_b zII^B-rc;SS1?6(`6ZvJvF5(Adq`ZQRls&JFW4Q&}b8#>Ys~NSOWzUCqp1>+c_7-E4w@;R| ztdq5bYoo!2yV~K)xRlNNC)w(8{x5?HWmYkE791*^dDe5zWNEsShxDs@oG| z(wk+qc*X@)MS;wX6~8^@Rj<{3NzDhY1%dU!yEmny6a0A~_a+2Zp_NfMBX9aWwmAE} zHeV0yE|h@W`hh`HmAO}j==izA&m+_>Wy&aCb*U}?(*-I`5iy{cr!A{=K|*UCXA3b_ z)yl;3##}y?4T={KfmPTZtOA^Hm6!JZEcf0O&Ig4oQT__ft^VCDM#VX0c;%0=yg(cS zqGLJ&tLW-tKF{mYkfQnct}D%m4XncX;*345a9wHz#IbY)R#6X6i=)!IsBApQyA9W8 z2PjK+Wm5mu<4HR(%~-Fs8>E^E*?HYZtqFlucnty8)k@!z8obKD?_F<42&|%BO@(pE zau{V~Dlo@VH83sbzlqBYG6JBZ45tS!!pLt=Zl6qu&jZr3=GM3zwE8?x%NEK%qZr&* zb!w*N++E(=n-KW8m}YEumRGj5)ETLsa%|?3wydDwHO>mo*u%L$P}2Z}QI)bN9f4Ii zzX)=pAa~Fp)PY_?cpTd!rc zZxaH0f@!#S8+?#XvUYsz1}E|MLt(Yh;FfCANq5^@)SfR$vk-grS}kR(+=ut>e%68s zBXhu>O=mpkzcYE@NH?5UN@LVj12(7 z6^Q2P2&|$luYANTJ!{{e*Lg{8V6Uh>Zy=rm(JUQ-kBey-mzY0E-6po-xmITp4R7?;M0M+F`FhFLp7X+B|OqbxjptxPpE!R!NOs zhjD%^6Cn&w>{pZ8^VqXo+B%>WpYbUtA@FfA4R`zd@6z_~O?b0A&LVk30k!tCV0A&U zKphj9c^19`ssUcxvhzq4tG4cv<|Rz1fRsZ2l!mnM`T1U_%H<@Ki}OM&+q z^XLx+2!YQorWuQZY+R!basXuGCYR>;ORh-r|GiwUg4V-&{P zXPaTV{$waG7`Vi8b7(#OvRz-bhTAWzaTe^^xW;e$dxfznnWk$8Auq%4n5!isHZA`m zv2%7S&Xm3H=VyCAHh+5%W;9-{P1?RXvAj}bZbIOET1-R6R*?uznKp`dXys?=`aUgJ zrPrzxR(xDaG<-Qj8xlE$w+~xMh`P#Fi}lO^HFo|JE6&n|%z;yBc`_~+mJ$N1aAq!J ze*t0i2KmzwScN@=`eCOo=Iils{6SKb_94<_i5wrJnj2=con3ooo^f{VS%Hj|saP#p zK0S)(wAQlBJ>S<7xi?CE0lCLmg|7_|9tF$;hsW?Cp`L`m=Lge_O2@h2IKvp~Ie{=LCtIZ>unM0ySi4KTX=*vEAD{T?II&TpMx&rT&AO_K z>$&QNSC0FtT1sW0pO5pq=njz#}#7p?se=HX(SCH7iD(oR+9&I!!PKn{Q z=eo!R=ZsZL=k2dvtuj_gpOfs!Lw0&?kxIG6@J8(l62f?MI#jqqx_xnrG((QzkJnNg z#(URZM~&?r~t=bvX(xFO^lsHn57?Tl(arB81Tn zdtNwt9)ai`^-gLrz8(MTS_Y1780X5Kp^j-1@!}}rMb_0&^b2gLEnF;}#uYV3hsP2E ztJYo1nPSAwCciW?xkh$MvPA9OU`kvQ!Ar$#w9Z|=RbfLWs5o<-W~)!Dwb`=z?RfL^ zo`VU2RVd;GHn_IfB2}GYp8R7dA+QR!4=N}9wo4vAV)*FO8Eo0(88Z%3cO^}>Ri)Uo z%4zQT%Ie#tl0f+WMG34j&aNZB{pE#WQthZ%-ae<(|Jbmrj4SBqagJUbCN%(JZ4OFc zm0`o~Ayl%yPLV45jpmy>&(`*u#;D#gL)CjOZBnQT=jl)Pi86oe9>-^Ooh)rBn^r}W zKd68$L;bfW3eI9@?1A@E^W+Jm`R97q2!XRdk%#bXN;8USpNfv=Ur#+F1kMq~G~|PI z_Oi|Hg0fDt^eueSmLohN>L(dx;JzK!qiU_S^o9|@ukNneDa$$A7^i}wE1AU zr~@f0!ere9$=; zLQqfe72LkztF*6fOI~hyPD0=-i0v_UYVa4S=8o1p@4s2Op_;hKM>V&;p->gJu>**P zK)ifP34^xx29$=U5RPsC&tbzLaKG#5IsZgBR1SN_vH#nK;|_OJkNlZ%R6gJeg+JMF zRIlP%+dmO_N1zP6a!lA+yxql)YyBy)2js8S9cHF}||NV);`vcndIsEh4b*S); zi+{3#cXhPyjQD384i(;4@lQ7J?u+(4z5Z;&p>pht^=HDqdzNwMJL=E>h7VD(RnW zIMz}f5w<_uu*czyvuls&{h4s6aIEi7UfCn5h7Csy`A>vHg?9`66XDoX6pwfRMA-Ku zGrV%_Q}!pqp~5raKN0rXwqe83i$)K>A%)clY(naPO2MOWTp0*8SWrLc3B*09AH)P!;mSa` znotdB%ncquH6SLiijMT1e$NfA!Q227ScN?_vPHIO+T0jkuX`SO;j@*M-AnKRvgs zSL!H!%2JCE#+~>(PEBT$jNR|o-Rzzz z1w0!gA7@r^Eg`KRw3NuMHGepe53IhQ5LkudGmH&6InMN{{XqU`{vkqOmEoa11_U+L z)e=nRr$hOMz$NmkH9MvCZTqX+M!vPR)~>>50p?K~>xz^W7v#TF-^<@7w9_~J^-@_o zqO6LegSh&Tv8>zcip1Cp^0)Jpz$#oH33&kCRYg+XGje1?5sqzO6^%e%tz1=Xt8qpi z5JL&9!X7eqsCaeZxn-R^=bAfjV3BpxqZf+xSFnn0;F?Irx;L#Vax6Y3pF2~G5ZDH$ z87teax_CBmk{l6No)GxBxCRq;%|7lf4)vNYU(Fpr2&|&JQ)<%-iJ)z_DjZLSHQ_m) zBKiDBxzcGDj&0y5H;q$2D^gMHN_a2NE}Nea__&y6?4fH~1?aC?%cUMpX?3DSyLTq5 z`nVbt)*yi}at+?4Bd`irpQi2a(*THlu)hzsfm=>j^$$Sp>uOj9m=CqDn83%SHKS`` z|HL&w{OUD_*uW}m56*74+)}Lvb>#DzM)4g17lPDivvRW06ctxwZrzkQXsOt!G+kiC zELS|PASqA%Wv_{pz$#pK2@$U*jVy%*w$y429m%(4aI#e>^u97d#c@#_jf7Rp?Sn0g zx+Q3by`u?%Rj7gsylUtdYvNZTwBr-w3_>xgAPgIZC-yofY!CJdo8DFO%r#k?nvD`D zkBrd9sE@I_nI~!!hEf6_7q>5s*xM#STRM;uSVh}mFnj(V1Xf`W8M`~@qGicYS8dzN z-W+8#s<`R`pEsze`f|o{{6tP|!}mUfz$zS1hPsJ)zbq4q1j#36wB>!fJj+#cQu%OV1FKLT84%NbA6t6*e>VRN=}ri&!e<(? z)wg(vaREW5v-MSe!$q~#wI5v=s^Xd!>>*=2|A`aB#^yDbXmQ`%apzP$_1KZ1+Ijc+ zCk8cqqU!qqB}jXN<;tmxZ8Q^WotHn57;v1|uo6%g5*QUa^6hfqJb zJ4P%mKQmy%Ue0bT^t=VG@6F9#eXG%j2R%nd) zvM)rN7vw=~;N#K?h1D}hi`eIZT1w%=#0FO3vjCOeH%ANgSX0yXRe}&$h0io(Y=w*# zXa2fmD)sCUA+QR!2{N#Kdy9yPVcNu7mn}zsj@4`Q_#TwC@l`9X9>J9zjJ^HZON^h} zR%?6d3L$Xa1fiMFqk&?5tEyVu=6!^~$EEr0iF*f$aY0i|#U|_~1Xkhfc=#&G+uovc z`wV91MwbYIRoFwwHMkNj@_L48d0OL)y_y``gI#V~U$IQwyTG(CqPIZ3u#Wn6lJ^WfPPJQ>qCr7&K)$Yo zz}d<;a|EjBLNrV6$>+>Nj}0Ki_QBVz;n|ldPT^xoMFbf$5CUIw>>e)P-6D?7C%1Xf`Wp@L_yt9&*!3vb$|wU`1sKedIOpKd)FuG76yaRhQ!mV$DG z=Vy7MHJlJel*=B0q*Wdba$b~5)yl*tE)Nsm3f5CH9nY<{niHpE74@oX>B*8;Kz2TP zU>ibU6>bw_`%EJ7(&|4M2a(Kv zobeC2&RNrTJv~{sht{=M+ODTRPe@igE5a+v@MeGvY-5-IWXQnA1kSp~+1T*)3)rp4 z*wwK*?AC(`titvfyHn_uZCA%5y*(|1FQ@I~s7{_{#WwJfV9%OdnMLC}*UW1cw-eRo z6w_bzk5^{4>7(Pi05k%G=RA6LNzwgU1+C8G5E0kiU(eH^ld?0sg^qW<#r0V5C4nZ1rcB(AKPHn3DCDl|KJDGH>!Zc)Z zeCML{8h5Q$PESH$74Cf?i}mb#X-lnkd{-kU(KmN#wMTqQwMb$K9cM%vYtW9I?WDQy zrF$dV@o)Dt5Q3_3WP4+w50X>qc06t{wP8FT_Q*E2$5^4yndQB;6`pHsSz#Ra_c}S8 z6Gx04t%k$j*A%}e#bi|YpbO;)VML(pS+g|nb$gFYa=}Wqc}nq8grF*iJ*Z>p@kR22 zT?E^1t0vGcg8B&9Iq(eZ9JqT)SCW|vF@UZ)pZS+jBb9zSejCs>t^fN{9c(lgup87A-qdoFOyg7i>q){Im@@y>%6CyRfnsT+iNiA`w zCCRge7(m9k($t)d_}?Csz{kZjWA)kf7R3^tq?E37S*bm6vK|)|XkD@- zRXGm3BjD_B#s)bB1)jec$-6F^XSwOL&~oM605w;_6D!X6#+lMEkE&3?^fBWw{-W+& zLZC=9p<%`3&`8q|=OO%L-}RQod8+cLCVkaXJ$@0DK|3;jZ#qvi*Y7Zh&uz1p5I9E| z=O;rI#DZ*E?-qmjiT8U5fmJjQ**qdq+thvt-&A=OA+Ug(Q+OCfAyH}AsGMrz=*t|nI%tiB! z!$_w6aP#+0aeVr^L_%PdaRnW@gWFn+Fs}}W7+mpbgup7C<gsZ|<=xjyL__M+mGkJhW%v zGj^$(lez8Aj(p76@0Lb=uLbp3)KYyJUyVGe_#T5V7Dm>W=Bx?hs$Uj?3H)Bc`Sef) zajLQOYF8MqnV%AdC-%1wreVymYp-qh?_L|AVq`|zcaW-g^w9B6;B@!zIY1cE^FHYa ztU7=)Va|T2&}>$!fv5X@6)_G^qJVep3wTi z_(Rns{{}Qhf9@5j}wWCu79M|T4ZtY>S~5u zR=)J{8teWAyOfa^C#X2%8%00hn#Z5&Z|OTYyCj}Q69TJnjyR0r>aDeu9X~g)Y}61! zU=_B>C)bkqVl&GwTAPlAe@IzbI*@9 z*lNBwAdbJcj3orldcZW)NBO-o51bdrJGTrW1kRtpH0%x&@xwf8T^tu@D-&XKZ%?sv zO01d`q6A@@v2{zvm?M_O@$m9(2!Va4z1npDCFaQofp4hQP zR-1;k@)DJ|#;V&#ZR1#lX;|lk`Nw9MfArc|l^g%^d&Z*T9lz0B1n%86(gSJduA2OP zW=dcc&Q5}TabU*M5oRoL@BN7lygxa%2VYVSye$>bOY@T(f(d~$d1y{iQJAqPFk{*9 zk`n@}usw*dv`v=Qt*pp<_L2yJea9I|P}6YJENvB@ylf?z5Lkshgs+kecxub6x!LTc zbm!L>TP{wW3?c|;@8B#OxUYaPvUl#JBe06zS3y25+Rn{!e46S?Y+x0>{_r*0da33S zb)q585G^ly$;9Ud5o*kUD+z&s%so zA+QR22r&SygwRq8^5vT|@qFXz>&opsYPP)|D*j3c{r<<=;&WRGh;?cNl-S)?Yl#vrH;qxe6iX1huuT#2zW+r{Yyvm_b(a5Z3ccC7)!4 z5LiXmYwI>GEK-M5mTQ!$PYA5S9x^tkV;vDQ@?`R^tYvt3%`lrM8D991-6`p=j`e`( zIN@Y+o@|uBD%>W>hg;u3nvk`poK$)QU-~U2$hSd?vczMGig)S8SsjdhUF#;b%iB%gSA`#AjP%P8vnM!Yb?`WAEn_5@SZ>(QX!P%)f<~)GI6*t~AQgi{t^I7&5eD zN^k)&U{hv|PijgCtiqWJuz$%HSFts2rTIqhCWOE$d{@HP1Wy$b*A~AuCot+2R^dzq z$bpJG} z6R&@QjbSZCNf9BJoRC2b_}ES_7x+y1n7N#e_ll$Ys!egPCw7QbIWg*!1rt~malW-) zwNVDu*|)R~S*%{w#GOqiWW}qf=o}%#Ehhwcb$ndxA?!@?Ru&q3r=f7K z8-&0rY!6}p=ln$JCwX|IzwZzNtFX6>?e!jJK34CtdGOzHqE5gdo@v`CMgEpZcI86z z9XMBWx}7l(bJNYIu2BN3(3}d0{mon~eo`CL>9AOl{pT3#xyzbT(K<=TDl~fm;`!Hp zrm&74Qi;QHV$o&T((e5t<>H$(uk3qa;k8@%TH412mS*KYu1Qy#y76l@LPd+D#!68iSGA1qNV3|8 zSIi(I?9CR*Yl;gWai%FD@H!q{iF?udveY})nXh?634B~kL(d8IoIN0)dSVY(?MAM& zU5Bogakk>MG+f&WUsyevw!hD&qqhiwRd_87zM=%HWJZK#6ReV98(2kG$(F-vpFva( z=|OB@74{ImQw?4jdEtA&tB_A=HKR-K`&zLL>>)14`X=;efZ=dRSjMIi(lUlAJa_C=XQgg@+=xw{o1@Nw}$3nj1$p9R>({6qoqBW_mUoaRl54XncF5Nh^;@Qa-lI6fVLRrFlB_b4TP zO#G6(U{76Q1FP^_G4xTwLwxL9&D7UlB?MOC^TyaRH-9mH%57=eCU1epgXD}-A|R!* zczZG2y!}g{sJlOSN#U?4TZEf!Ru(Zh9*iZTLG(hzj+uF9S zW20vU9-E!qL=cPa5%jHr_BNy^;gmy}XN=(-xV$5`01&Ze>R zBlyXSNtPC)ItKYfcU8w+Dxl-_FEnF?>(QP^n~vm*;LX?VBm`FB^)Kk13pX7u7Q=?$k@@CR4@=m3nHP(O1>*h#?~njn2<=NFv~vqgn7}H$ zD+0s->R8N+U&QfN?G`1kdF~~AcEzfF?)i&X?v;fXe7AA_(&e_j=^QIR!{?jL?$6?Q zQlzID6UOzht8klOg}02aHZuiceUldx8`wi^4>GVnO*a?MK9YCH(%v#WEQ7e#Ww846 z$7w5G`J-!hwLVTa`v7q^6D6<;@9)G|80U9u~mxd;#gohgA; z*h9!$dg7nlE8B2hrrAWx0Dj35vMEB1pMTMcSCsL3Bx47ZBQ~(gxHgWJ(b*sR2lUN3oTr$m4XnZ*!hLnOob)2TC+{V0TOt}i4LbX* zrJ8G9RUNP6(bYb$hZQA{{XO}hE4K)NRfawLIvzysrg}-03iRZ|hutLvR$+UP@e8YD z4PouBJ*<-D-<$Rw-a23CI+&WgVM?PAOEvcSHan7}HWiv{!Z)jMq?%jeE}34upv zbhI=S2xI53m+1(s!XCmtMUZ)I?6P^Qdjhe6J;CESSiu6q81LRsM_?89kTFm9`BIk7 z-S`&R+u1k7RSoIiLS5g!jEZ+4LT6fq)$mL!rR<^upTGM%A+QRsp26O@;UA<6HNyC& z4;eYOK~;E_?83cwl7JkqX)T=yVXS7@cfY_M!YCYioNdtKOnDZ=i$RaGD6Pj)@wyRS z(_!rVzx^yJ^Xo}|r=xjB$9z!5t3Y%er%q6BOYs}7Qr_|-2!T~-rU&QBm~-})ZF5dS zU=^Bw0^!J<9mH`nyTciEZXme_wJR<9Iqi5XWITog;o6-Y4eXvi+4-P=(IV< zoMID#@cuP8$_;C&Kp2tj^aNJn7&)wYRW5GpaWXgTL~P(b1KWeW?jy@;v-ZaEVWlsa zuvhrFG!~v^PkAl38L|^{uOS3h;j;j{2tLcAeV!G?JFH8Pd&RG`JlQrt-8J&5f+OiP zdVXR^l$I5~nBMciB0^vlj#)ESE3`&H-4Vn1zl~=R0;_Ob9OCVnmM1T7ID*&N-COPy zAS{{74N)hrJ#MQqwb$3;_&#G5KCeg~)Ha&W8Wl|ltio-Ax!Nz2SO>e%-1*Csf8*`+ zS~qtpBTiRQaRi!1oed%b5cks&XhcqE#<~U97FUm7lRB3uO>E%kFs7l80^$lpCo-fX zuqX8EL%V>u3`Dkc1Xf{tkQW|VQE1NDlIt+eO+l)@>Oi8B)R)#Sq1gmHQC^2?h<6!s zX#EQM^2bG+>9u+VDO2;CNOTZK4dII+TiOVw8qIC=h- za-wB*u6yTupqvY=OJ-h}X3V8|EwM0kx_l_LG$F7GM^OzisCB1^4&2!U029u3)4?~049->1m03QL5*Dm=S~sIy0Qk)uLJ-sWN@ajX&7 zCz-RV<=fTLah?pOVJ)>=9ud0pi#$Boix60aJ%n*$pttz={E8fV(2WpSg`=ua`Etce z1U&giUQnYTA+QR^WTE;ZCZ8qm^%*Ajp0UD@2U=&Ssmh&?2_$BTW0{Z-mw&6)s&$Gq z=L041EDZHHy0L@uKJ9DjJ*m<_O5hwwOhaAj=XRD;mWgui%MoI#BWHqSN@5yXey@~8 z%`{i)S|o-LxJ|SjEAo0++?wo=p06842z*>jL*y>(WZ=<5siyn?#)&?cT;)EuXDG8X zOx4pzZvXEq4=kzCUdx=q2c_)|28u!7)>yyX*rgmeKS9TlTN-;kUPV|cTrDj3>(-YL zScTSf;Ov(AaM&_zb+Fu}M=wHP6|H%fAQ=0sxb7WHM* zO_Z)nN~ovD4AF5WG0rfCDxo8nr0GDENT38(;fOb62z5Iu{dLZr_g_y5tfGhSQVGkJ#eBm$Vk9jWj8c|t%9otTyK4zCvXKxj<@6Tdy>+f#2u&9SnV~w@I`alt(MjsSbE%+s)IIkF#o!H7{(BvE1bX#dx=^rd%wM41S;tX4)H_4Vb9AUAf--+U)V_*L2&}?!Kj;lqe_=fpV$Qd|s%YX;U-xe| zT8Y?Ko3xyIHCzf1J1(3um7i3F5LkuV1beZT3K06ri>8IEDS=hkL#Xt&E|)xg>+#V| zN(f7SALV#PlUmuQ72NHPY;|MYZja(I)^Wm0DN95M|16ax1Xke~Anaw4VUl$1V_iPM z*PRepMPq%7>L*CQj)n00m8cD@!X7fVpkS!|YnAinL_$ODQl2SV((p@COt#Ttecs~o&bVdDw1WP+hgqBva}4LgwihwfsadLeJ_D9B6nlc5m<%oK~@;76&YS7!dj6j zQ&C&2FDWD&X*rJjF}4(hJF%9pHUQ#q4RWkW#spU3h#rg+Q>thM zf$&{hk=Vd0e5N7ecapc}q{Z<&&4&{LtLWK%H@c1a;@ZvTVlW%-vHmNU!^bF%GEY@; z)-2vT1HRSx*)KPiD#N9zukza5>X1UgMsp_*g&7*nZ^Z6prafW`h{y!X%* z%8px!YWl2M$G3j_1kW~Ej!lssb)*E&7Wuw$7eCN^jk4{qu^Y+s@MKfIBS)pN=FyxV zcMgjGvR+xfI#Il0J#r*G1Tcd>-PD!i8o%pl9IHThjTCzW1CZJeyRhL;<; zRteLnJ;<^cILTBp{;~ADIVJFMF%8)}&jy>DZz>}w-6{cZ# zA{YuI%=O}?y*h9v0 zh40f=Ub!c|9}vquVN5+QZA`7=s1c16&325b34zAZgl6n@J`c;gHan!F>qZd*9~Z}& zU~T*3WbML)OVZeEqj|uH@6xnF%M=gD*~VUBd+>#dTJ_9BSq5q0jW|NwOUz+0_V0f6 zi{8hK&DcN5{Qj?uQr^pyz{kZjd@Ze@N8p906Qx0eDS@94{M<0suEP&=(#HI9ci&j< zx9x%a{pkv2)r~}Qm*8sy^T90{wB~1BwfXsz@Li_N*UgaCInW|yQIL9i3cJr)1>QNsSR>%&>MrXgooi;x1Mh#x2v=r*mq1r zY^koV)*0TS-KDjG&3+WIz1y3KY(Y5ghu^^v3*TB*TLMI8zg#9v;J6s3;ZAJjtrds& zZkDaX34vpBn1;F{SSvF650~=`2!TDpalf?aph3J0?IdBZunOCQ{o(qb3%Eae7@tsK zmVCL*REzhH0qX6(PZb=+qfxbc-M<7@Uoni=37Sa=tTIMU_6Qqe@0zzsF4iWR?^_Tp zyL7s0850_zPU&|=!7(`+RSW-FH#r{=trt-O9~aZG(y;hSz}I_Gy!y~d#0G8?rs2KY zzjkuPTTy)9TuNY1@L7QUWQG+>J_N+TS(LykY>%QadS@v!GVrjjeGaFcVW9=s3}^9nc<0;^~{j$Ozlrsd4X+kGic2&}?wf;_TShsgcl*OC)gf*Jv+CT zSX5$d^111f7*$Wz!!sr-^SXxW=>0)5d0>Q`tFkzFxwyH|8WSP#ydOsp7|Yzfswh!1 zYjT+ce?njtwg=xVe&Q#tzde{7Te7-vpIBFaFO5}x28WQS0gfiXw}e(y7f#zUnm+aP zBLr5_7(n=j1Lngp7R_@mMht`z^3k*rvW{oMH0z~a>7(YH;brCgODKU=c;*c`MK{6& zch0ITH-lZqunnxj_TW2;U7WN*vWP}+6hB)4xhN=&M- zCa7|)Jxa%arx33&4Rf5g8Km~It9++)EFrLpo~tsq%%&EZJmjW{F@(S>>Q#wq)wMdu zXG;|d#fi6mjZDX8E>>>5qVW=ZreTG*^*~dO++I>G5hqeN1o3ifmMbmp(adEW7l*N^ zb?1S2WscOTH6`$I@!iANt5P-0LsEYwfA|u|m*+jCb$mZnc?ok4JXfc)?J=p7%y&Il z^4*V=z;h1Ne?WikX>Mgsu6y!O+pmy>h`|(d$A2k-kBcJ+P-{7Cnt9CB zvF2+Bxb_`7gByfmNvg0HVO?Dx!b8%gJ9m1rP#{Sg}3$LSDu?BC~cQdFHS(9QDX5 z8Z(d)IgG+xJ;j6kU**}~oyF+-q57s0dDJEi%jtNWh)0>Q6SP}Jk?T zN6T=x-)L+ONnLIp{xVJkt-i<;2gfT*GEXJd9C*wKUj&bfF|P=XH@|pA39P~+PS_Vm zOfr}AJYgF2AWkgLzvtiqm&HnRsLeoc0}@Y$HJ0$Y$;(0%Y1ckV;5RCLC-&@@O)HqQ zy>u>?66lH2F%3J{f4-W0JLafq(lbinJlr}eQtD9QFswHj*R^c|m_XoSp zGCwSx*&P2aPBeJAPFuKXs`4C0;rRSu4`FVQueNCWxRtr>?6Shc(n3EqV2q;G_a`eq z=Ioo9` z_=vyG98cbOsU{(?3Xjxa{o|UCIMOUMAg&@MunIj<(2fzsstN0;UWepswTKO@!ed7G zs;*njEqrwF=@1R3u_q+J|!ydm2%bEtA z-70->i4*-t?&0&htWjzmPSi0$`&x6-!@$E;k|metqX~gkc>Dl4EQd~*HebCaT^dCR ztiody*q{2s64S~V3#H65^$M%7hp=<~I)C%i$Dsj7zs2!q33~$fznr01*;EzXucS|e zx{1BD%ttea1)NVu;GPrR`S4Cm`BlW6ebo=s`rFh7R?(i*{okVIRoi};7N;Yy3VR5- zoO3MZACT)D-%<*knY*$W0)5oKU%$yXl7{;$xD)4E%)fwGyeg0oScQ8##;*PD)j|qV z8(2kqoVurcG!^=&!zW~71FNuykRi0!VwRvEY`#3({t>_X)SK+8gnLfxA!AuK`e>`b zM)%Kggupg14ZF(!Q%yYjHQ-?1Lbdq3L$&p*gT^WEv(#5{pNO6=xPk+>RTs|NR}dyw|x#?`+7#X(r|8;S8AyGt8 z93L}FUkbBGdkGEPbVy5|$|zMG=yjVp^E&+K~#*@%{hXGw06U|2g;Gnc=wUZw8hW(PbQdr8Up$ zvy{uMOl;8#7MwY*?eOM{hGzk;cH_QUN?;YfLdZPXz*J2^vRJPpF>tmx9>@6>!rAE$ zJIqNh{McBTRXLQk)gpAN72FNb4nRE-#@L-ub7fi}A+QQ}9I&faq-L#Oy{7K)U_xLO zj>mB|p=Rk!V=cdB)xnPBZ!vWpDyb>Wd|Dps|;kpaE=aVO8>(V>v$vOh7aMk9x0zapmdFs04U2-t%_s_ixoz-jW zCr2_{xBTF5WwMzj7X zo8t7Ai$imI1B8wfHmEX*%2!T~}Z^_q_l$TBwSjFAuannRkim7&)c#o{*J zg1w8nkGoA^8KYj_{Ue$XScUF6)Q_kl*nun_mmV2u4D44p9z5CaYn65%&E_Xyo@cr$ zO#wC4qHP0p2K>*5=PXZT$)nqyo`*0$FoEYIol&s^*>d1ws+6;iz`u)WaO#f&tFZU* zI(M`=c|J$!4=NW|bp{I_H=6mj%mo_K#HuLoO%|v;$U%AHdA-% zO>r}1j&q`UxTX{3nfPkM$T|Y6u%p5`=lw;gP#wbi!|37|ScT)k-qNIr?HsIs`u3j2 zY`tYu(hoXBb%ox7M}cO};zU-L7%q3tsR)5pcog7U#lcC8PY9IfjZuWaDjbjF{s3E0 BCnEp= literal 0 HcmV?d00001 diff --git a/ros2_foxy_core/fanuc_crx_description/meshes/collision/j4.stl b/ros2_foxy_core/fanuc_crx_description/meshes/collision/j4.stl new file mode 100644 index 0000000000000000000000000000000000000000..1341136996da22bd9320199f6ad16e979da86d18 GIT binary patch literal 24184 zcmbW9cUV-%_wdJp4LbrNQL&+-f)!ENJ9}?1HUw0_SP>f{ied>O2)5wY-ZhrkVv8k~ z7?rqp@9vUV5;ZXzOEhZiVq(+j6nJJ~a6c%SFx$saen=X1}QcIKQjvv!Y(@Jk$= zGI(^t*ujJR2BiCS89ZiaM8W{_|M_>d2qD$Sc&altW^1XAYHDn*mxGW=j%<%pc0%lV z`AfPwu0QW)?mOZL{Qo3}HM$yn?-N~FjrcNKyD`Pvga{c)DVQcCu2wCzTtv3!$eN_G zZ}QqlIwlOMZbt;X*QJk;y3utkKU}?~cIc6%?XL2f?E>v-Z#}k;F4b+`FE+1_qaEz? z5>gEP)NLSq{`>3@OHeGa`aYdV*}K}`jJB6f?5rSKx60X7-Qc;=&#g_bW7=8|ev(1^ z?yewzd^OH~q+Bn77(cSC%v!!+bxR;#tPVEq+j>j=&L>MC7(L-$S9)Z2e}N|C5fFQU z$O8h|D@b9Q5Yy&n7BjSbcbrJDHgVgJ;3N9??CSFPb_oSq z{?;;q1{}JfR^8Z0ny{~fa>&Qco;ziVoZF!VNKSGLm|ss$+YzZu2ySejc)@BWbO6b2?V1<)~DKjp1(k#3HiBRCSAX*gmviY8>S}XTPj0NXE+vTRwy79qU&?E zYugu@G-AtrHS6Y8fgr>sC0aG6eI~v6!#(v*@z(-@rEr@F`Q)Oz+Ub0@w)aWaLHNdD zv=(M}i2m%f1kc1%-S}qW%9S+nBKtJEo#?pIAJF8EV41r)e z_uecv0Bz98=3)nWv^JTVXyx07$k8#f!as&D0q>(BpW(o^vuBr2boSOHu!s;C4~5Tm zXa|g()1Sj=>YqD({(lj84Wc)}TmFl{Qbz*6G6`7c70!Yk^(2<+hy4Q+$JN$}r0vjj^a3!Mam-XX9Q>IDZ= z!T#PQuoN1PLI^B{Mze4NW}QBQ4$!ARJ0qDBLuJdNyLnQB?BVp4BgwXVbEe!ps<*

JU8@r5o9E{x_KinWGsU;;A2K6~m+YwQcfSVj z*ZsWW^z%Q~ydq7x8DuSaFM($4-X)Km+|C}H+=0y{Zi(VG$R=MuKiF2SM`zISa*0Kn zy}qs0e?XEzpw-yW=LQYpk#XTf~wqv&z;ai?1HqN)?*CwD*A`-=CQ z7;)5@6Kra$=1HyE4}XW?y^DLDka*7!(?XAH2U}UPY3#5u<_&X;$Zx(%(4!^8t0~Cy zfmM@Me0%Wao*pK$K_svx$R`5P?ezmwuMH;2LrWKQ;5K2JkoAcZ>E0@L)dO9&nf~{C zcV+r>U)$V0Ma?+M!2Xet#Ijj*K+qkvYZF-@uoQdKVy|G^g~;iYkeG|v^x}@^me{kA zVOR&28ZsnCADfDgF8UL4w{mytolwNur$sq>Zj8TDVe?AczQ4*U4bBBA0lv3wLxwz; zKN}vP?7W+1t9`R1w7hhFS9m#I2UK=Xq*RVEO)kq+)6xIjrh%Zea`_@v)(H=CX{~h^Uuxjgm(WI{;zPiM9 zJ~hRIK7Q^M)~{Vxfhf2JIZeo#Dleqe?G3Gd-FgcIelKnlApuurs|SvRYmq}RM%H_R`wfBLxCmBGSXMKUK?L4%DiKwAGl@SC^jHZPy#JNYBoF zJNx|DiCT{Q3vLcVj&Ar!4e0m8>R!3OKrksDS&DRE@+az?l4G>0_dd5WsmaA8$I(-J z?4pz_dnIJisyS-vx*pnKLBgz~c zPc81H9+{Rk$Px&q10rNyO0*E|Q5xFSg#8s-uJ3RVIe}GwzuqF%tJ&Ooed-8-z*0da zmdm>$FRKra#{#jt&nBr~PBZJlA}M;jYvkt+EQM(yqZbG)g`;I5qZbG)g?1dUYL{nA z8eIR7+DC4wp_S?wIj*KsZ}AXY`Qu)W{16W%H=v%qL~KnUzK;u{s}dV(_FAi~U5?jN zt|^(0dJEUskyo=LzXJ1FE!mgmoOZVk*#1l)uoUvBK*Y`OXla#Zk%Eh)=qn1UA2O?c zpgE?n(R4*JOT1z%(_)Bp^zpy-5}jaD&Soj|Yb*?zqd7PPAJbv}1TRl4qL_rG9LP0>N}(3td)y`%RqX_&6`x*gHxe z5Ad&w)4#gL09goQQ)O>e zli0hKe-p2Gmrs__*ywci(TR#PW>|hRoc8kfrtTvrNNnzoykAYZc4~*d>*pulmScS; z%j|O!*;x7NaSNG{B#0CLf;h1V#EI;i_Ve1w%Wu^eVnehFz^aizEX#Q-m6+_Wua8}8 z_sOMadO6rE@ee*LKejh_FrvY_H*)XOkD+%NF=X9Z>EaDpAdo(RCS({8eSo+M1d37x zDNH-tk?(AWKwv5MY{b4W-zvat5Aih9n*%*G)b9>F!|}`~q`Yec1%izYpJSLNWC)Dl zOc?X}yL{gv_`Jfjlc)zX1gLiiBc|3@7pI*qcbn`_H|D&xGJF5%<)vgis-*W7U$v~| zuJK@F4$@L_7(q;6DfT%ZO+sowU$ua~%7?zf1nxKXIoAhOXCUql^q@cq1b#2330W|3 zu;gCks=EJL8ucACT$USGGk<%hw~!Cue20*!kyE7F(a+S|pO1To;I-a_r}O0C*Wat- z+xCFDJKtxs(|c@6LOqEx#Y7pnbPM26y`U2|2xXlT_zYptX}{ia_A^isRwaXS4LT+SJ31V^s%l^uTQJ@s->JRyUZ5+qlbd? z0kl&yFB&$KCUx4NMou^-ee2#rIn}=r-MaCqkZp;1lxO!O+HS{4_0sg81p-T52ydy( zo_2-yPW}gUJQKwKU`MTw9_XA0!yJN z19bf6Ihf|g7q!|-UJwW@h4m5Ax^DxjR;C;uoRBYq23-e!}Qgn z-qMw^>4FX{B}U<%5yAAvlseWeZb91lUa#ef2gf*Sjd2s=Pc#!@uRWgDhz_$&w+^1y zOdzln>IG;=sk0*_)7(GQql445lz}tkM)T~_)$t$eE$0zA?gfaD>o1b7pRa6{M~)T< z9Jix24?5CUwxG>2ttQ`#Ewu%MYA6{CzcSx#S5=P__>RoR--tedm|vnBjd)nry1i0) zZGQjy$~d~z*3ItjKr^vGOg+;#ik6*H-s;u7vOowezg$;IoxIL=^>KO7(R@n;ec5WF z+Ut2$f#{2*aMVvo)F_!=^!2s|#n;i=T&|@AeX-Kkq_l?v>kxAT&(NWC%=G7K`8Fr4 zKcy(jmrdK)&A}_}I8VTBB4l6Jp>#v;6SYEVk-$=D1;d!PXqH5+M_;ItdQ{MXrLaCY zwcI&^{yC_Kwf`@BtouTmDZw9PI@;W8Cs>7PLN3)BP3xq+QfD4sE)ZA>=R1U~?wmwF z?J~?-+`LmDu#{-k2a{z>qixBO#|P=OQb?jL{+nny^+jKW#qB)b5i^#3;Uz5(m#0dZ zdE*5FOR=4S*DneAxUFpQnw2WOwTpx(<h4 zHBi`@HzBoiV=X6+PNd&%bkl3dnBXzINPBsYva}nOK|j4f1%kC4P89V@Gb1?dsm@OJCsxoQxT*#d#D|YM@TS|3s^xc4A~(I14L`aAjLKH!O^B z<$yTnER1l~VO*7v!duSkC9J3U>Ei#Bu(7j3M)1m1;e<=dRS7Gc;Po=5!&M_ItmQ5# zS0$`)9k}}CIvF)|Okyn4&SyJ&c1hvW@WQO(r{RotouwB>xTIXwPiDz~&qSE*|5iL* zb($S~b?_P~YX|r){iaIcgiFd*pDCPR-@O2i zOA7my2@r*U50#14Ic|ETDEj#zy#m1^Z(cPLJsct=CdCOXg=mOHYq6ZueH0yf@|6h_ zEK3PJ+*uj2J62}Twx7Bg)sLz`v;tyY0Rq1l(-4aSF$5}Ji=pC$zImtO#oI)PpJ7$f z$yX{S3R);y#o96VJp_L*rs1SPim_aQ{lmV|&5FD}>@2Qb2KSp#DG~@Qg?a(r^x)@I z%a+tJv|NkT0>N}(Pwn#azEJ&OSr=qqI`Q;QtWxCE2E8JP+u^DXmI9(F5K-?TxD>OH z*G>o-0P`voi0TCh+zVnmZk~#=WMmDeAKVqK65os4^bCj`AoBA?0=FFNBc$Ytj+XCE z`_gcz5VCKK+KayK_+HCCcV(%p?&I&Q;s^wmV(oC%`cS1vAg~mpU1!iEJ)eQV5K(q(qK>>oz5*&-VW@7rwM0)hlHmUAUQ}w%pIZ?CZ_^-Y6>c@(B zO+LPGpUm=v3b{k%aW!MXw~q(n7a(f9hv0Q;mhW&{sB-F+ZKIm0?*M#Ovhi@uD^_(b z33buMQ0Zi2%LzQ@crHN30@d>cKNg`^n;sSjYzcej781hh?Q4NJ^B#grVSUba6op#* zU8q&FZz9?@*LN>Gm)PfgjyZ2~uv;AV_Yi!S!L&fA|Di+Q;W+Iaj~_}Okv`pD&&o#X z^S&$OsN$<^?AaJiyWR^vMUEN;q{8YL)`QRur$$v-QYnLfTiEW~x*6X6QfTvT2cs zYI0Y%?dEFc{tCVUgDNcG6VIeBmOk?ElXCZ^3Iwi;Gaarvb;Q@@q>xFCrLWGW3j~(J z`Uv>|T5eS6bx&dXc4A`ml|W!A_RMRtgs>CE&%sMGZ_VDzbzmv>>}p3% zAZ7u2Wi&qvgFD-6GU=zkA60W_ z6w_y**0y1enW^8 zSW3Jh#O@S*HEn}sTH+ajz*5*kLT-%Dpy#!P>bSbi^me3MgG?_nGxb_Hzva!=Bfl?B z$W0)w05Rr01eX$Z#DP_v&qi9V?s%?S#dTmQY@xH|MmsD_%4oR_5pdfH-;FvjJClwg z$JA=~id!*pV|;`XvLw*{>Rt^yrky$(K66tC_{=%TzR7(f*>b91+sK}cTUwf^gY~XK zgkl0qAsSABbGv5I^iH=`)8?^y%ip5|q+EC11wwB*C$JRK0kxH;>(c4QGk4T;%M{&H z8)IO{Eyoo$;by-;U@11{#`uG8f0CR*z2_}b*Vkw+5LgQ9gQ|0S27R%7f%?CQX8L#- zV{XGzn1*xC>J?p@pqguJn4(3FjTs^2A4uwnvB;Wok9-GNN%zx|dPI`F2T152?s z@i|RM&xc)T`H%|M&yIM|BkSra`A^o_!au5@pc=A_@B4wLHnpPl;AS!J>@Ojf30?%;=IdeJ6HyHz=&IQYb-NV2lJbU(1#@l)BiPDs~!yb17d0yfu-*6ev;U1V3q&AUoVyM zITxBG5GUrAZa^nit#7?HH%!}G^r@VtU9?qe7~;TZA>wJq_pbuzSF`I{mz8WQ5V$Ij zX}Fg$whT30^S7?1-30=_*Sz7RTq`ce7C7@G2V@ieKJ@JuZ!BY9MhFC!V*3X_*&w9h zzNU1nM0aWBe)!th!as zDy5uwW4bdxSs>7^CfuwdL>szQ>UT5LG_*#lK;Uy6tdEdy>ju+HZX4AVUpLpv)U2U= z=r>vWvX75&Hww22X8W-&)W1WJn)AE2K;SbS@r-4h=8ys_*0Q=sC21w{^W^VqeqxLG zsFMSo92aQEQJ-s4-H0G-(bfq9A&iIXHa7HCzk8RZ5l@1wQ=W?i9&@ZuxKFLI9yLzy z_1MseMTFBV_q_C#x6h`3MA-!l!bCr2W~6W>u(UO+DtV z{V=eOvcKAT+krnTIWjEvXL{NU4w1~U9=PtU1p-<%=WSb5pV zyiPlFXMtdT*T^|_n&)kBtJuhEuQfd^5Nsy$ObFA2w7L^c_YXfTZQWHwW8ZMA3g%Rt zCZt(>JNk9@A<5@skzh2p9n;Rpa(?xyQqj?ORMuLfIw082cFuo7v&|4|!>-L@(buVW zObe=4)#DOQU@6>h&YaVzOb7&S6C+%G#j@1eFdoNXJPKNc$AkBXD-(v?S<>I@%#rnq z2d{*%HyJs#*+oF^ED((5RRd%d?1LzG)-&N1NC$r}qj^qE$mcNT^&xi-HF9T8U@12K zt~$diAlTi(2PqQ-tFRQd(3wq)g}mULwouP;cBQT}vtK*l){5;wHv#qAhDJ`V=bSt@ zWcpm07rJdI5NPh|*&U~a3X5L-Fj}ZrJdAS#y&k|TFV4Pd0DaZw%vOQGeZ`)QK7=*M zDiaNXs9bLsXmK?l17`G>OtDG+Q2;P>pHV;r)^Ce*Hof)4%AS-lzuh)OWq2OCUMM2 zNZ*7Qdamwz(+?BN2?UmE+p4B=tOWetXs;*KGIsO`q2+hJF}XVe1p-TnRt>q=g8txd zH5H%LQXsGtdp4pz&{1q>2(7Slx^(489c|X$+DiJd?((!f?s}ZSZ@MsoSEj)4E@?~4 zYO|ygHotcWE;aO29i`QV1Uc<`DTridPolI|sTIW z`jBorut$n);4TnYO7zs|cV2qM%c#TX_fUdL*N=2ueK4QxP_Q@{<>Jo z+dftx@O>y&VdMJXl&A3k1Hsg=yz$2Hb6D)hK~L)u;lsK30vI?W{%# z1Y388#}Ohx@Fg`jOV%ENQm9+XI|PptaXb&dW7*qU^4eM3lJ;u`b=&JNpS$)y^P?}~ z67YHnc^$FD|J=->Z6Q|c? zcrJ@GZzo~=!c8Es6!S{F+9LdlPWM+>hf50AOP0q?q-S>BQCoEVS|D()&UA1K3CWr{ zk=8$yuMUq}EfBZ{fN7@}y$CxR>}+~v;&iz(W~hg$s&QR z5_Q}=6+u7UHeBs|zN(-DzZX|5;QrP3ZD@Gdb+yOOO#}i zp0}Y}=5{y5j|dV7ykCjC!Ec|mptqN@E{XHg)wA2`q&zBxL33WO|H5o6@tsmttDAR$8w9!~CMmbv=6J^%=Ie8#5nf zV*k#=XioB~u-jfI1Oo51jNmlfp)Z?ESEM~ReO=lv5cs{XN(3vmO)cc^Z!dw4{l{YH z!xr03y|$O7*ebj`V|{RI@@y>qacg<$dfie2f!~Xx59d0c9egD0W>raIK7-jif6o-X z7S3BMwu4pAfv~)f;H_l@ucSLOmK#7^eUA<<#dPx;xwFbS4r+OHsz$?jw`eZ91PSlJ6%0)eIQ-VXO(e;Fp7 z>Fgsd3;skP(20_u4{ot`=pd~x{(s?+uaT06b zRR1*8OW3G!0!y*aUDXeC*FYe!6wccSNrCL{9AtMR)~yu?EX8PUp|j=7p|5^Vy`x7m z0RtDC;a@4xBQjniVJ&ynGFZK2H00;k;rx#EE+?=Q`<&;A&KT|roZCgi`5h*(l<0lf zDH)tvhQX<&Kwv3Ga|{1Hi8H18%+b%)@@{N2vz!y@pqLg2{p^ktSPIc_O2#}j^U}<} zvu`-TTK=Al6>2i9ub7v<_8x*)Sdb1l$3ukPa;^hO>6y1H+eTIi1ha}uVG9Y_ej|+T zTG3j1z0jYoxay}2`>e5?d%U88cQQ6hT=f!099-U7s<22TuoT`!;Y2YfhA!QF-}HE@ zyPyN_yI3C~^?}IQc;8fUnn>XHVjAkATVm<7Bh@7`s3d*vS63PE!yq{@pp?)Kyk8MA z>*qG~M8z4>=~lG`g0+KJ4MeNT4hy9}{pl`^KNp}~Ug4)q*xFdWkY34w{UGWE@YLJB z?@mXS_|}yApqxPTFWOr9V!X}VqR&k`rV07zVKTikBFgma;dgp<(Af3um|!Ew^8`YU zEK8y#)n4k^oj(Z#lj6P|dvND$XLkVDT>v(h9#!pVhTp3R>m1K~Cjl!q>=OL@BACEZ z>~o&UIOpyS$Z^0s=s6D7!KIjmt{jKW_RHXRS3>O->%da%b8(%sHO|h^**8XfrMH9Y zz!nOzk3e84_9lMvE5vZRRa^(NijNI@c8v#X2V3K?*54tx6w|>iH2TUJ!wCeogz4a; z`L9(hP80|%g)M|%vOf5bjvRYHIy$u!J^HqxQhEO*dD`S>GM?>pVtqv(oFU)8Ocbc; z9}A~f;|@zn*NePE82gey6B6nkN9jPbG~|9Ufxz!=`KYO~=TVA$I`Rg@aD7L%qrW8{ zlIC|1b>K*kJ-gz>fpBi{_o%~C-dFDuT#B`cTj=a7Bioixzv~eI-^0-ef>pZTb&lXW z1drRtzMbt+#!NI}9asv_G0@R)C|z1QUHYfVE-7$I3xzJ|DSvtCik=m5t8gz6 z;ts#(tXMim$||={Ah1_s?cg*a2}R@SH><};2k&1H2>f1gJf?fbQS(WY)Yi8+#a3Y{ zJem+$diA4IQx>aH_g`99f73|Wy}6gIwz-4@dmN_E6LDSUPd z{~F23E;M;ZpnCX>w?JSi9A(03_?>9lyY`~c1CKle0!v{F;eJWm7@B>5k?FwWa@ygs zEtHu*&Z0rppV+aK=&64OBKW}~(~bfJmcm|}kkm6tblTNo2Nx#%Y{fe8O2zsJ84bjS z7sU=PDL~-&Vj6xKRw|ATUoJ^^YZTX(b!etsa}1YXeR186E4O0pb!N#p>ffcYv}mWB zwgF~hr`bJa_e)poIKCERYX3iDX-V2tsyRa>uoTuu$fojf)D~uvwzViO=)h9gTByDL zFNyBH)mfSwvEPcVLNi>j5bm(7kEch9j+JV5I4=-Io|KwVC-6eE!9=7bjuF?E=AU=TeO3nT*q488LMj`v&XaQlh_N9?po{1p-T9 z3n6#jZKfGF*GO8wDzy3bx=Qn#N%G-qB^2yG@a_ZE^LZw^DSfe&(b`uauoRB%2$_E` zmhSg&C6)WYO(3xE!umkRU$OM_%>mMumm-1Ri#;lwE|rd>m%a;>hL0BsEQR&Koubj9 zv}wCR(nGDTc4LE|5;wSs+^%0G2OekECVoN#zjp>=O@~3!&H@CM!Z|LSF7=P4A7+=8 z$`>mw=)iLf>w|xT4v0>fWu>SBgz#Q8rwM5{HJT=*u9U{qd@Y@bZ>+@joFuQibzes7 zL&mX$b0!)woW64!QJ+3{`Mg3a%Ghg-I8h+56q{E@v}EkHMl7n&M682L;aMrfy8?lw z#PxBpeKKA9=9MXbm1e#DJXonSw~V}H*&l+(VHWZ=PskM@y1aa4s`t4_2vS1tMy`mZ zLCq^lBa=&MSO*?KVQfeu5OT|kQvCu1mcm{eX5!#DdUE}zQq+mZQu$v4m7@>R<=}vP zVFdBW5+YZLqeo}7llCSSqnN-_;+Xqajicj2!leh3ifQ$J4O05jvGSXzx9r&OiaSnS zAcnRHmo5|_u+;QXflAEC4Ea^VyWpt@?&(S0duB+(I^DBk9asv@N+3o9ap~g>i54KR z6t)mzQLi|fF)v&?kWox~U~8n*&7CCY9DQiVIk zvGh{y|4B=to(cq(!ukkV>m5gb93L(n$|y!Bo(WR2Eo0@I7jMaUY{c#tbTE?|0^$b5_il?v(9j z#vIVYaGp8maOND|?q$cVTJ_%ddGD`z@cWsn?&;~SuIkx~Y}weWdtBeR0i6cLb@l3; zuKC8U<+I?I_OrfFU^OvguL zrW2C=qnqJbwx$NVf8qCpDo8)ho-F@vTqdV_^fH82T&oBhfAlV6=ZVcjLVC@8C+BeV zGPJ)^91+6CxdM4jCB8gYF8-O%;^7#Vr~Hm@mKBtJ!knr3_Aq8`t;$=giC$QG`$&3V zh0dDzdzRO=`1Rjaa>#e*Z4UYOWHJMNg;bc{Jw2H{Jv&A6ZTVVCJ=9f;-SNWcwX3wT zTeo;EeX{;`dH5HHdtstk>Ku z*DGB9Qnt79)vjiKFc!Zq+S7{@g*nmPj({r1%nSVaq?p2-TsYC`w{EO#odR;(Z)fBj z&#PGOOFITDU2U1Q92pQd2CXPpE_vhF}Q*0{pUoBC)<51A)1f^Ra^|F#i51~2|cOk_ogxB zOueozQ1KXpBW825vmt-=dIsh55=5A{Wj*H+m7dzstHTP&D?0niYl?n<=3<0fp1F18 zYe!yI<|8x3q;0OrduGYIf^yr2&hp9|n1CY#kA?TcN65?nT`Kpj(u+Bgtg)Lpv<$!3 z_wj0HqsOUr@@m&(vcF&ZABfb~hn4QfJrGSujnyuOvHTs(*t0{L>74Zr9zWfRkDu@T z!`lGgsETj%8gfQfGejT0FN5B-dnat~3L$iqvte1ydWK{7mmmV#!*5hZpo^g|e}dZ+ zdLjaP1!+QZo>(WBayurc`nBh?!x59UwI=w^i@)nL5g}(?pUUm#6*bHs=8p)W(%*AT zCq(q51KzsQh*m?`s%J^6+Hi7u-YLzrKc*ixgp?hovUgG1+`B#19fqFj-=)KNPaj<$ zV6JvQlQx!mFrj+Z>!IrZKa)1~&|0P0=pE{(y)CrcX|okWn6QQF`!&yBrnjYs!|_6RxL&W!~m9Fs;pY0UO{{bTXH`;(%Y zN1a@n-*87|=R{v^d8wYoB_(G|r8=X*VZUY|)9W zUXxP}{_UX*2{=>38I_PawT-Ol#QRd&IlhL8)hlTi*gNAtpK_Ss%!z1HSW957`sbDZ z8Ms{TF)m#2U6eAo)&jZ8-DrwtBZqe&zm~ zswTKzym|t@Q#%hgb_EN<4 zKhL{sB3csmcx0*Z$da#cF+m08-hn-t(LqCmQ1SRd!34V z2jdUlx5NzAHA96lgO#>KAB4D#eJ7{ADP@@Rs<+bBQ~51lqZ$wQM})Pn zEbBR>2`N1|k9>LHWIE%!rWP!8Nqt?XI$B@hx=Tn0PVD#z0ab7fCgfm?^K^g0QCiQb1+pPVdxRHL z1MZd3=Ipts-i#Qo_R18|ZSvs+^QAq@LxRSRVx-f2W6hR@(jVOKq`{RMueG@*=Qhu~ zKUs=1VFIea*yT2=*Iw|aQY<~><5NsP6|_glpf)AbUI*qke>p#jUCr~{xMa`i^g=1v zD?!`#B0V^fROLqks$NbmrZ~;!D|UAgGmL$mpMH}I)8jmPg*KoH_B0`LIProLN9_ox z!tE%OkdHcTG?_m&O14BxVty^PJXV8!g^AD6Cc3vyc3M3s2@y~Q?eV?ArVg}AvIE_E zd?+HI3dVMXy+#kBL`eHF~d{BNa94Oqe6fzseP-iUxI5gCXcY0~E?k57)y31p{hUzM&lsL4ij z%44~2@YLrjj9wtkR~$}ca$>(70aegLLS7XOXFJqY(ueMEbBKWVg|QtW26GZyMBU}?5oPI@4|TPhmj;^7?i`m6 zV@4Qp5K=xSiKR9wCeKN(gb3&frajx8ql-`FX9G{wVq!M<*uqhp{e)O%A2<{3jd9nS ze-LqE8BWaQ#2`BY&LwajBjirYimdaL3(}5G!EEKD!kU(mP1$#~ga)4ne42zjD^QGm zzI9AGxHcRSPz57dJ}2gXPm6RoA{Cq7(b5iU#G=92w{MRF>d+jHjD9oncKkEiiJi%F zP&z)TH6q}BAx%g>qX(N-_(Iz2pvH(u9sNQrvGQ2@(EL?VoA|i;?9Se>2x;x#n1H zxSA_|?uiJff*ukw(zh4$Y#k|uZ#XK8_&m?coJPm_21Q(p=U=031C*cPyCTm7*6mR) zd6)AVM8JIlj`Z_RNMaPW;1(+I9p~!EsE8f1SQ8{Bdr1%SdcPj12u4$$?7ptF}Rw)%nfkDhk{c3&NJI9m8F~ha2v= zNa;_V_Zg2oi#EZ%EZpM~a<_XT-L&zXRP*T&L_n2KbR#wFagwn@p-4Uw$KTyc|7@BW z^7L$9!<4TR)a{!Sjdh}$nBYG1&$X@9XRnITS&v(AVypKNI{xoNQtafOh=4XAO-M&; z+WTvIgzl>jrB>Zj|iv|v@zI6yLhf7CoTnhu;AtI({5L6 zYQ=1vOv$GU>k`4Mx2SJtQP_bAb7Jhck3q=^loJ z>r<7kh3BdV7eygYpocv78vC31`Pc*W0qOk%Va-`0nvihbyQe&dvO3-lvha6;W1MBb zEUtY!cFdy{@}zi;aGK z?z2=gG*Pt_*Ss!b&9H6QaZ@_g&w*_p(#~+V>Ukx?_qMuyR$UX!$q9Sb+62E-dG(%@ z;Fg=^yWbiSP_-$0?jW&^n3&x1|594eq$-K5>drCB<0ZeT#d1Yk zYF@T17tC4qUX)v&&?bgnOCE{{F|PEyD9)Frz8qtIJ@EjIb?S`>I2(v-z4Av$$q*OW zm(L8lkA<78&t5bL3KQSCr)(b#9=!E=93^zh|7Q`tib+f($3>9?4P-z z+8v)4#sf!=ARCY-C9qxL_ihHOcA0^3TKVHZ%9w~U;?VJS7Mjy;=RRe zT5;1XBJW;P9;Wlt6qbtOxJxC}N5*_A+_4fOh?yyE%^PB}Q%FFS_B3_t@@{Y7Q(tGx7g5CkS65Zl^$$Uu|VmO$7w{sycnGAc+9|hujZ61QRf;hG`MO5HgzAaQKJp41XjT_ESwnqvr&>&RZKC7JL1zq z;x9iVpbFRSenmhPuHF5LfGT)KBTN4?ub>KMBY#am70z=0$}6aX8R%czfGSwC_%#7l zaGw7)0ab8bA>@zXWHzcz5&7V)dm*1rbk$6$FN|w$7DeY7;JiY}eoiEE;_^S3fT~Re z<21Jag|SV&(i;gWv3DfPHtC>r_}hJC1FG=cUXl~7CmxhGI6XiFRN*rd%Lk zlRn7cUJCHUlC8CR%lA}$_@2|cAGG9stb0I9Rz=T1f&Cz#TP!X24QHR;o;M2{sb**G zU{6;|j}9MKO)IR0SiExC;bPtC59RGx5a`NQUP!d`l}?Cu9E>}zhK)L%4!q?pzr*`# zWmAdmI=ciBPzBm#C021_ryT)R;#&8RpGXOPMH6n_PD?1$iN!y=rw+sxCOy=Z+qO;9DSb()ZdJWjlSvJ~xoH(dtN ztEI-Gw+VX%B1;QljaV&&UOf?avPQN1{RrbWM(|kl06F~wp|@7p(CIAV2=}V5)hpeG zy@xuDVrpaqdV*&-5Vs=&s-Qhy%~-oPtxQ6sHW8LG7a!ZHD1ga zk*;}kM(5V}j-^DP`AP8&QjU8g5dlten7}ClJ~KpZ+(_U49Vs=f*xwLTv7!3vc3I=x z`H?1=d&l|qzWcn`oa!0o^ab?|9fuLEe5(qoR~dg3%yNroE_zp-{URjzsTW&u_q5rk zD<+^yT^ZrOrMIV;8zp%%$7NxL z-s>V1&+fijfu3F{(=7JR`uxbxq(+>l)gq440)<)_F15-~dnFH0-AN5ghF%}Xcowbl z?E_uDL!vb!+93kA9QFtyr{6rGPnz;wSG8Ef@c!4;KKHw(dp4_$`YPz%4z=pR#_F4? z2HuWryT4M0^=s2sWbcRxkgW&v6(?k$ysT)h&SpdJ)`);A=piA?hU}-0qU)u3RqJb5 zUUq`IvXK4)Ap$ul{VwmcAIUf-+-BA^P^69^g8;4FPzHr_leEglh2Rp;NS zs&V+MbgweuydD2en@MSeH&u%bKm=5Q91tg7g!iPwJzQzNjzbUuRUlu&iH+y?)6z-J z=)=D8hV7oS)ynsCsc|bCncy>kG$D`USJ1HYm8eTlKSV$k^pKzNI&+J5>hQ^YD5?u0 z;PZ#}`1^790#!yXGhYwwjtF>P*l&bLo37CdM^2lw7l=ayR6%=uF7ba7JfLJIosrVR z@bBrh%GXUPYTTAc6RhdrH!32+PkQ(A9L+s59uZK5^P-;RoaM$lchh}~dm{p?zGuJq z^Y~lIEk|vRq({mmTE5`1X3~&XB5PzjnJK<}@y`141rb8q0;LH;_rGzfRIME3Kk+n?^-J{$Q~i3 zY}F-1!23d)pAoit^`}N<;E4h}v|Q_zEkZyw!xC9qeMc%m+h);T+=jJc@&lo(gl#=W zHh~JT@W_fN{r^+%>Vmg?24~5`7^Nm-FoW&zie3BVIizG(h1R$+~tcCOEBMZ4GgE& zo>5*rcGV_VsbI3NtJ=nK&EUP~I0+iQRo(%do`zvEuf7NiBA} z7itG=A3rbZ<1XjxQ-js`Ux1;y-xX!`jq;k$9XHEZ(q{&2WBP^%QplAc*63U{L_ihv zkdOyzVR@cQSGIr270U?-?;?tJ(ks&tD&j z);hP?ZBOMnpVvJ1BlecBV)m#F`!uv1Y*=@x+^d-A60F&kIp!&a8vQ`%Dx8y9eDf_WFgJh>{WlsBPz9^Y zgoNBE#jfRCNKJp#VmG#YQP;$DQfn_PZ}CcR2kZqx7Uf8xJvnQtpZfs1gyG?c{(U!k;D6CUyi=L3@Nu z*^@!XEMj!#n^tVi8dY5^#i??UI_T6r{vIbKF`b@2yMdNW?SKe)UuchzcV8)uJieQr zN{B`TREcZb>75C8-qMO21L)ePn1JIL+9M=7^%H%4s1fz{ZHsI`-yu!NjI&jxo~8}d zV?uuxR%W^qwqTw*@L3xTo^8OV6F!}*DkXEm#g2d~{6*E0^oC}`$K$lx_MXTFREbfk z$G$vUt2Q(j<3xxZ0aegLKEpjo3^}>&n|Z~%WTs`-Py(}+QSYsd)!61! zbVN-$ZTWCSKoz#}s%8iC(vQQbA03Jas1hF9&SkjzjWieiw+|gMA`uZ#1wG{X-P*2l zYJr<{%cah&W#Q9G=@qxsR$J<6@cTHhw)6RF+O)lrG4>5TKQ;yta0h|uMtn8cUu`5k zv}UbkHF!Q@o?7P5sh0IaUk&gqDu_dzIQSDnKb?SA0}H{`lvCnfx(#uyuZe=tX&z

)L*S@t!@LVpuMbYt@T>~Dy&;iU0Yf%<}3b%!cR_F zSid(wgnhQwdY+oEgSGwpvwr=v%ZpN$Awt;GRq*@-&n>m-#TLi4kX{@(f(WP*wC*7x zt9d0ZC$Gf$_Bd%CnX{{wci{`8dfO)*R{LO8j*yj{$i<1Rb_7)6nqFOAyYpXhKc&1wuMi>TT0Q3=u5CMde@?XFLYUb!qNU}q9X1=FqWA-$tHkrSM$6m=sB=oR;j9(6KR@vSzXEit@4#g1g*#FkVZBndmH+F0l~czarb(UKP$lU1 zF_K!V?O|gUAx`M=bt+B#%U>_sSVp2fp+EnuGj}Q0D%i~0FM zU_BiY&>m_BBA`mpw)I>@03u!x5rDl7T?Iy{nl;*c-A$)r-w6q*64(0Ml|}GcEj{%U zLRY~y@h?Dg>@v@+y-eCJjWmdP(7H=8!MZB0j2>Tb*4%gTO6jk&$%ud|_~jF?-OcSn zXEuuo**z->5wNZbYi#_yXj~6EJoB(QyJI3EpbA##2#I|XMX%qw8RG3W3=z;1_-z*7 zfAsG}uX*eYdAuHb1y#^PzDr#fOUrb3pb0C6A{)>X5XthHp>Cld8n-+f_W{_ge8l(JXq@SXkS3((=>9ae_YobA(5UTEA?TsO^ zktW!qu&4Q#NdAfR>8VUf{Wt^>P=&vVJMd{0t(AA7H0^1BM7&hGsB6p2G9KF29NFVF zVgGIPNQI+PNkc!wro^G@(~wEVo_U&~Uoe9eenP62+DIdgcb4AQ=#L1ff^Fi}B?k|- zCt*8%JiL~nM9?Qyxf`$Mx>z2a{ebg4KY`sc(7bV37ZzIop*(4Okg`46s5L)GEH!$) z1|@bcwlAs*{#BK>coE8O_bO({>G;VwN~x`Rj&ZUOdUZ*R5}oF|J9WA=sh|s+-?o{d z_{9xM;TIlS_T7Fam=Od!BtCY%OXiZIz1`TYK}`_>Rq%T}LiWACB28LVmHCEMLj=rU zLVG+~lB<}PZ|2_=J!@k4GNhgIXg9wGOI)IV;fU+!<=>{$%O&?v*B9*&0Z(<{NM?(3IxVt- z=VYX4L_n3e*6k5eYS9Z?xT6pK=VJ#%Ku_=~i}XtG>4On<=&fwn22?>0`T9{TpIkCv zJ{{^jz;JW^Qf2s!6{=50D-*2OiyVNhj&t;M9(hT~WEygJAR?d&R`~gRwS0w?D|#!f zait$3pbFdj%^}KM&~Gwz`#RXL%)O;hyZm1MDzW*?R!otDh<{zKzUU3y&hq?wtfN1YenFj(H{t11wBMxfFc5`puI&7 z#pL{}1KICQs~h6W-&aZ(Dy_ZVSi%HrEW$&*LPN+3PCQ!`$ky5sPz5VOgq*sOLq0tv zfMv9)iEKa>t`&K6;vOf`?FgvC9?HJ%a`OiDS%D2D4Xt{fRCcuw&<@utY=Sc!^pJmL zy53E8n=Z3k+kFuMRdAl?Yi%_qJ$+PznMYMY1XRJ5h>#Hxe@F#e)MPz_FacF~-rb=t zlib(TW>3onARADH+f*!H5xM-j*34^mPJ`3s<;o(*V6CH1F3Z>C`ud71TZVzf%yLK-5CK(iE#dVK9%U36v7Kg1 zs>R}B-mA;<^;1`c`&mx>>Sw{l-cYZe@ZJqB&SL%6(^iKu0adW}!hhG`cqw+~a|znM zP(8N)4$(Gd)KoVVu7GMqID1~H*;mS{G^4MaqYwdAF!xS~&x2*ONX-*cyIcd<%IHY- zT%GAg|2!=;SZ~2KmUi#gQ2+7Mq(VFTvyaU~)r8D2qcS2=gLM^Hq2b?Jwpl}G-I*)R z+J_0Kg7ygcvrR9$bygQ?t2q(bfHfUxkB~NggJ`FXe@oda3}s8FO--K>|J?ZaXj}B_ zl#nK5z$!o5_1g>S_L^aAcJ=41db6Fz;63d%sKPC8zrvmNoBdvTP3hv7vtDkOXoIP zaN-&#-qgSZRKf2f3AsG!xb*IU6H5zdjch;_h%&j2Yn(X3iOY5bRACQA_S~8ax8!}S zxp2$rXqW@C<$XZD-EzuXCt!v}?6&pO*!-*--_fglN6%{q$OhQ=TQVWGTn4BD{6Od` zu)F6OFF{yq6NrGG2zz?AC5y1uCJ+Ht&_k5Dv*h8dnF6D*@sqqC_ez{r=O@)gX2N0v z5_<0n8+x0vY>4kBR$oX&gy>zEjns2;S(!V2s-N-t_78-v!hI!9l3TMlmfVsx*JFg9 z!2Ar#Erke`PC%9TyPk8(%CPj|EzjUBhlKD%?*(WNWut!ZO204c=`0)kj6UUO^$`J8 z&>pW;FL0or>$%W(zQYYSa+Fg}Of980ejRIq83Y(*5;87ds`Gt&P{z)}Po98EwLIhMn5Bd3^Lo4X&HtQsBzX68Wu~F&= zHq%&qUW5r|5O5BlY3xc``RHn?qbnw04gk_T_nKn`4R+onT@S_tyl=X1gnA`vs?k*z zzoZksU@1K_;e=F0!UR;oFEt6N|9l0FN*x4Vo1FE2he5O9XoYuLpNgAgNFm#&M zSZ%xRH=}223lp>fJtU-a;2iqg^OV$R+dxD>6|~2H2_bwD?Hzwo`lMnTPzCMr8GPe9 zT5;$xX%I~?G`-bR_41o;JmuWn1bv4zk1{r|qZ@`ClfIfU0aY;b!ZThg*U;W{m)-qhK{Y`y)tDQP$MphO_SAoch&xykJcXaJRIfc=BiCr*<{8mr8yU%y@u3Cw~V|l`Bsd{MCRpP4z?sRKZLbpGz99O&ixO zjGfq691&0jvu*rr)Q~=D)wefddzY0!1XMu}`CO9Sy#E8=JI}sZ%J3wjhjJ~%sGY5m z%>;8mc0`W0Y3VZ>u_H%IAOfnOJwke1Eu5B`*`CFZ%7zH25^<2ed*Q!d(mK%mIjIZt zJNJ+-s!>tt=3~@$ekB@EShEt%ih+-&ZbKa{C4)wS*E`FP~@eP3hQ zZQIU3hx&d<>-(Pn^4HZSEEl)_q(MpT^MG<1Jn;>qGyeTYfe&c|IMLsZfU59}MM}dD z#kJv+%X8a{+h&*IbGWgQQ<}18UsfvvmwIY>qy03ff;9g{pfT&ExMM}x#(K>V0af@H zHoW%jm8QnlWY@}8K}5%^rG5 z1o!8l-}ubXw6%wv?YciJaiBILpz288$4YEo5AE=+GJLexcX5$3s#avde_{fv@EO>b z?VRQ0s{Dj$PE0@*_Rw*nr+nd7dFInA#L#l^9mO==P1}629Jl`cnJbXy)$j%`a=33r z7S7uN38;b|@?XcFG(BVst;>czDPxc}Pg5?WOIp8x94Ide-xVGw-k%!0G`#_fj`BtX zRKYim|3;&CG3i>fHq6&I44Q>rtNDuvHCDdc zg7?+_^~>qdSDU5l^|1}8g7*0LYVB6gJD)a4|EoHH1%D1z7tM_~hBb&pUO}3Fy*z9M zJv?@UG%^4aaNmz@IBi);UBgyNb)7K*a}JQ^aiY^O8a?}*6nJ(B@(Q*b<_36mXO{X0>Jn2$6#KxKh>+Qp9M~bpu5`h(mWY5V z9Qzc#?ZCdQkEbUpV*;vh3^yP(AN@0_DXS1v#4yv@K{@w(ur_W^P7{nWM4N1txNfy> znvaZ(WSK+rBLb?xyjERJkI z73>86TeR%b4ZK=aS!&=9@PJRc4b`)jJ8X^htjP7 zw;Oi48;qyf3sz$imwXLlVZcVKqNHvD>*@DW_K$ zwPx!GY6n=Oc&wG;cqZ-U#~3zf!8-~GsDiN_|G)N3TT{n7E|eXb>V<5;HsN+mA|CSi z(ydtY;kg;eW~=rQpe^bHUyN8PCf4siP;3Z2B;-ENx8K~?ntkh^6WM?&Z10JOyWDqf zeOA6fNtV(0pyKZmq{U|z)L=vgVia!s-A#A-%8bS=z|92_P=#&mEVop8lwO;aEy(LE zzy^#gu{~prM9Jq+FzeF15+Y#i3u*p~avz6C^=^?snHGTboN#(x=LPlW#4S&r5d8Ot>&mf8?dJdapJ^TPIRy%pbC$YPpgVbC*CNm zalqS7%=c-aw91wAB0*_TW1>=?j~?ybqX`aM>vjwq>J*yp9S?QmZy z6joZhFsKCjT|M4cRrAaJmRDjcj@Cj1jPBtt|M8eQxR@MwI)I&ZuYm|SN}xS{-lwX& zJU6mBbKV%p4lcZ+eBM}In_bu)c?D_yt3x~82xZ~IwEc-uI z5CK(i@59eJ*SjnIPYPn6$5clIRKZ>#WK_;al3Fl`t(=DmsKPCu)WuC6uKKee$2x{l zJs&8ICcA6*C;FOT)Q=)Cu{YdqYJswnGb5>#k^pyhb@w&nN zl#pQq>N10|tRap^^cgQhw15JRCRoSARkEZjDIv=^;bKQX72KEbFYo_YB?Wo3W@E49 zK{lWYyeoWncYOaU$)6J=?FguX9`aK!#j~?Ifj#Mz=aH;L&`b64lA&trr4=+-$HS3+ z*IfnKvS~Z$srE)hz+DQY`Cctsc2@a9585qPOGD_mH>$E}pxWVzp9w}zIFcEk=*lWg z+fKK%3q}M~0ed_yF&1@VFYcw%Rp;v=0;-@rzQfL5HZ4~eYgnNKvH?{%W*9bWcG|zi!&tHWn1CwSCVrBm z*-Z0?uhGnBZ8mnWri*eTMb`RlbI>3m+GNWuT}otTdWF9q9!`jWs>zW~%6(r+n?ETB zkH{KGkIeVhwqTb>6=1oJ5T%`Gu;$^FOM@y%^DiwXpGlj>03{?D-usDiyf$n!e~)AAJxXORam0aegLLUtc@V68gF zQ}=o;*@D%N)UO_VkF%K^xFR{@QQl#<}#R4K~|9@ug%s)5Ta8CD}HJ9E0oB#cq zb#%dq_N67|CDSJSuB5nq(eK-jESdhB5fh5o|M@xvxNhC2C2Aio@Vj3~=Q%l3s>;6a zQuXoPr`?GY4+M-ARxy^JkDt$Ndl|lCjBU)%@n@cE<$s^K%VDg%%6qaAzGD&#eB3(c59ICT+J zTZ%?ofmBXZDqD7n20d1#Lf~nrla0pD{`BjSe&3H;bL9gOamu3NnMNgJDoQ*OCBi;5 zG7ya?OB>?f(7K9yJr*^VMtTt?K8Y*EgHnmOLJ1Wwh^u-LNP%yn6ChNScqB?hRz)QY z(Tu&`vW++5aEV{Iey_7(?@5uV%QLUer}jZ~n9Y(05dZ0hBRuNmdXe*^h4CDtr1P@WW7<;hi5^qr3;k@G; zjd`~l&w)Q?#Lmnq6O|K@SVL^I(wq~`W2m{(Lm-d`SRuAMbJ!Zjl;)ghE)Y}_8(lJH ziPx;yBoUFQB!utrwe!uMyhZB)7GmQKA8547O|(LlL9~n@ zC>7<$7|~o*QScz@0p}ZSi5~Dd(cD7VRN5aP6(Z117%6xzS{5UP*h*-QegW;_bCe2w zfze12$iq<4jx!kQ?mJL-^8v|NP4bcMe-4HP?cppPOYlsqDAX%{5A=>S(G6^b%83a2 zTc%tqPqCLDO2^No`1X9tt6yq7I9Ao<~T*;ek%kpY#M**THIcZ1Zpv~H@@J$9tfUkby*&r?~ z%H>^$&P{v+e{DofQUF-b2pT_ClO-T@WC$wdbD>lCEKjKqftrU@$_f~}a1zdLft>n8 zcUE&Ed}Him+f7YmI9XZ3dyfj(NXXfQ5N|T4{Af(I~y96z&C{#Dm zr_gIk637i&YqcIA^%dKTdAFv%v+uS)it4k!<6*Z&(;fn0sv1S#`%DQ>oAx(n-K%jM zVO2F+6Nh&!;`ar#bGnj=elT-1^vEqR}P(=&)AUZ_whHTA90S2 z+nlfvKt&}q{o~n#6ZyM~YMtf7@2rE+=UV8|S^0d#e>(BO>_;%Y8mW#KZ2|42H!TU- zkXIajbaocMYh;?}IQ8fe*l5+Gys$@M55zZ~t0xX=w?OtN>^Rspp?msBWe~z^7>(dH zf)0DFPkOE9fgM!#SBl1pfYkxJ0iK0BX4aYJk;wvUNjPy}cjkb2yADEl5P7&N-qeJn zeC`pSOCHkCf%G#)e+LzMapU%W?$s{~sV=^fQMG1F5IL73-hpoLWpIN(_Ry(12(%Ms zt}RugXLI@JK~4RIHyw!}w50_45TUWPhU*;w=FxO{fyl}og3a1seEMcdg+6a z{`di{>mXDtLDteJNrj+Pc8sab3-=uGx!$&gB%xIJdAND&%?o!a3xQO0H!x_%;t=KG z%kV%1Zh7IJ5TcPXHNr@uPjVYZg!_lhuOS{N5$=aXC&>AR5OkX~{2D?iZQ)#Pg-h_j z$pujgffEiqH^f6(SMV?sazhA1r8neDNQHA2@=>-@5;nxc++PR}Ds)2##Y6bRpc_Ic ze+bQ$-7cYrq0&+TKeb0C$R3p>n^%A}3%i}!sno9KkzGw9tU5@0t=c~vvVXYY{(%!8 zWD>|ur*O4@ma~ho#!XtS`fWZ5MMpo#*u?EN7PK8>X(QA8lS6;SUu*JKf+8qCTdGg<()>xqW4O1dtHpy#MbV6XOd6&7o7F4_2)n7dOm`nRKn*NF<_aJyni{#YX$D- zNubI>q%%elR1e!CNLe3(ZjCm-R0tXw6fNoN<3VGLq8mVv8)%A7jiB1vK2N0wrJ}jQ z*xVDvJl3w-D{nqlY{KBFKzgbsY4!v?S%L@uv7(gsTQT3eb>J!+Vbu>(SJ+KUi+M)J zP2R*C7TO4i5;fz(xs+dG?h@x{S&_eoZT4oZ*a=aBzqlrSdu}s317mwCPdmGojrX4) zm2Dv~mdq4JH?PCjo_4C+PVh?#UrJCOvdhT*%$|L>%vk8PS^R+i^D^!Y?sY~>rK$nm zA=6)F;QRM(EcYI*DEIIFYEB(QC>5Q98RNC3{Afw5ii^!YfyokIxw>=0ji>Irrq?=v zc)alOj^9QRU{Os4zA^Wu&D%}n1vg*jRJ^`VbOYQmu}+~6XiqeK@V@@VeCYZ@=hM0G z*$C-#)h%ha!<`fNP1rj{kD@$iPc(h-A|Ni`G|DOcYmW$m-V_oE8FsZP3+6asSA$r> zyKoUpnujGJgUC{Sdk7%wCLJx6sWcOfY zU5{8-^8iU?r?#?7dC(&sln9H8-d|y@+JB@+uc;^2uE(e<$~c0xJy5%$yqN;DzR>}i zIG=v%y-sBduj>#+P%7Oe!ph*>f|UVYC;KdNXXb7d{?L}T{DHNk?~3`(kSGGEOwSNi zLV5P8r5Byeo%-`pW#@p0?v^g?40iwcZ)GkYw!b@1+&0caknZf#UIH`2sy2Mcw7$IW zyiFE@QrY}eAM{8c48qPyD=JRP@nM(3`l7I=qhruz3b@9d;E z!J97m3s&^E33ZnN|9?ZHM;3TLw0+Qj*BP0h2wJab9YdetOYWT%L4Ql5{3LyS2zrA+ z(Ww!%)>3q81g+W>of<*=2SukwQ2W@GT4L(jic(R2NFV1%*b9|+&1kg||8-z;MsVNS z&qNNwZ)x(L5`1pzJR&~ol2tKiz`WH_1f|klLhxuYc2UQ)Zqq`9D|jH>?j`whhf`AZ zB2r0<fa&v-!18^>at`bJ@3JSTQl9Xr7x4#wp|GcGXT9P8k#d=Nc+HS*rU)+;eP% zyz5c3A>k)BFWjNXou!h>R0+E>sC!Y-r!1*t4&vMnI#D#*s<`^;-gEDcy^8jHbpBQs zs$A$n`D-ZXWNy+CasQ*gyngC)rz@feN~P;D5XJc&pH8{{=!%1#5b@2q1o8k$?1|ji z4G~AD$9whrets_tVOf{fV?_M(T&z>(@b^3A_MTM%k?5|>IV5=Kstsr}0U%<}J>|U) zZl9WMAt)6*>pdC-5&ffr^bf3Xfzm_QN9ZN0!XW~BR3+(A5&`FGDtHFFsoPIPtUgq< z@spY@n9f) z4sh_Ame7_8qU2Q)B@#hphi9GhaFXy~CGj94LVswTY&{@KR+A`^h={h(ou#D(kGF?B zdHuRE&x^{i?#JugldrE6njTLn5l+z!Ai};Y*sJ}jK^{>cgy?2ITfSI$ygd)B7-b6s@y$`)NDT06%Q9%Uh?d%L&#X%84 zM6qB21w;f95ta5|D<@}oBmcE^QxTZUYDne$Z)IRE+gASv z0(05^_&*SsYg>=;oo@e;_ay zX~Z+?zxPL~R!%M&>DzkTF8@Dj#g*qiPt9e~X4bOE$Uknkr1g`uOw-CsvomLi+lFh; za(6tsELi#6uEgO7pHoS(tAn53`@KGY3y~%6Y2Ez$W8Q?qs}c}#D`{yEQ|^F4AXcxqwwFVWtp6O9R>NPP>8GoPFM4wRZAU9R#z>1Ts$j`k!51rXtB6*G3boT` z>gADL1`a-qxhjnv8T1-o&E#?sIg3=+LmJkV2S4uTSos3A%c;`9p_{Zg&_ z$(^?!I9l-t;a=pL4|z0w;BTI5wJLn_9sf#>5i-rE1rB4b?o;+3sgilA$>k!tttssP z*=ULk6?-X!HZjOIIyv^(YJ=F-Yt50<)mPXuPLF9F`en;>x%|XChY<1cQ^OD69vDF& zT8QS$ius>>HCcA+y(fgSP(zd?#LA9I-uI`+%R|%JALLOOt?d^V_9wQf5UI!2?Xii6 z!bxdpCqBSRP6eVpMWJ z*(}c`uVndeLzu#?%=+`Vy7K7))qT}fGlPYgyP>yyvEEjU4b-wqo z9wwKqhsot4xUF8U_m_W%+RC;`z;bO{1uWOr+?MfJypnH(%j(?^``jRGpBn_Cg%}y> zLB9g^Aj-meVA(?0QKEU2V2T|jraU`(OnGG6cNCGMo@u5tJsi6xmmRw%my59TLzkxc zVdsHC*!f`)cC_0vdeJ<;bb7qL{BWKdgq`Om7osDxwqUmYdJ@fAl!f)cvW2jgK_4N@ zfGOw=Sc_q`nnf1w>Xzwx1z9-EWi6b^OpGH<3y@OU9 zOu>3kOS4yNB&DuuI+0d2OyL~--#qf|YG=#fwRUjBx_TR}wU}a8OOp#F2~mL7^Dpb= z(On;|=SHqw&kX`4k=?ERv|jc7F@Nkszr@U1>z9~$XFUL`)wPJ1;U|!nfhkxI?n!P5 zu2ZTf<9|q=jFSSMjP-DmBeul)SN?-{az=e0lVUw2qm?5`ymNcHX4}_v?99Vtuc+4i zZ;SE5_>1MbWw1xql4?GYYL0TT=586*Thi^Qb+P8yy4VUrSl>q%q;ZA4hU3cZLFp#7zcD}JFG1n)# zNVC}|8_K+C#(Rt?IN(Kf=6GhsDVVEWxjibj+F64pua6MfEdq0487|^Zw_5T-Y>F59 zR~e5z|F*jEResVUC9&L`7u1U%w>IBosR{8DAv{80O1d6P)$&S>jfSYL5LLJD@%GfH zD`N?9Xj+`QUt^`o^+KAaDyR3dk()C|LG}E!ZMKX@39*|H@r1yXJAeF^xMA}v291(< zT($D%?|4FTTYdd^I@O@^P9tk|rGbf$esaisH+sBX;=)l|4Vt`+3gtqR)3%az2$8sK zaq^nF+e`}Ps(GpJjTdf|cSS~chA}|-0;Uc!2|2y3Fr{@1rM(p3~lAk>iHge^K zX-CF&J!s2FCPW)Ta6K?(+{JB29{>4uqakW5#Ai<|^Q#O`G-ceH<{xQ%eV>uFuxq)X z_G-2SDT$5WFBF{FzuwloY~8Q?LpiERNo5r2S3U?-B-dN(1_hnu8iT0NsY5Wi`~r)3 zx6W7oc|z1C1j@oPP?8Y!B4y~fhh+qyNx|@wJH#qgQg73g=M&izsNFNj7{;m2dxD#WmwB#zOBWuW&A`4RXfG!{=i((2; z=j&>6xd^t2_r!P~?3Iyg?Ug}T3wMOan-H@IktfY~QwFA3`*?&$B5Er{Te8%ve%~DC zwz8Jf%6e$ESB_#^B}BwhPp&gS4uA7NDBSRZhbd@-8yw!KhP^o>vGm)Dkk5bLO@_NH z@HP?xbD`x-xU*9InC`ws?0vS09QOLR-abNLF0{Lem1e8lcjHu~j6bt~=(YT#rQAjc zw3cW^2k-eVF)-k>5dvo|<T@k3`yP1&#Lo zT^9I<2!Xk94%+!)5z}c#je7Gyn8z;W!r4_kGy4ugM9P@cZj8+K?$OZdXP0}Jg7a?S z{nhHzwc`?H;R%HNw(StvI?GD$1wvphoOe0*FIGzz->``82Rg}nJ+65#69RMLyqnl_ zvRd*-RTU|tQ>(LH`6)f*0z%kURID$~yDtuYmUwdQGK;8Dcbr$$A1YrY1m?ndcO$88 z;`JWSSwze9PlN_E94ntC1m?ndceUDtsqZe_Xp;}d1vck5!0#Wk0y`OtQF?Md1u?oB3e-E_G>s+bAMni zoOiZAETR_mU~zw_UQ7tgh4aq#xka?6QBr0~4^t1!h4b$8gA(eUn=>q;2aUuBJ+ArO zR(AB6wz8wr%pyB>k3`z)yU1wwd46CnoOgD9ScIKX;WdQ7TsXV#6<=rOV5E$1F`&}Wr>=`95v{>sE8+|c^xp3a$u9)J9g!qCG=?Q_kFgEQX>JRQE zm;LmocagM01kP04Qw#BN_V2w@eFn&eREBML#Wlp4iaTT>zREJ)`?LNy`5l#kvlDm4 zxQ`a%1w#Boh?Z0areGN;Nr+9QTZLk>Pm?7Hfhjn*apx^WYeLi{L={3{E*mF%^^f4 zLSTw5&!AmOVm&h>~`WFr^j#xCM}>cP)POxE1zh(N1` z@i|^V&A8IvQW?=Ce;@)aCq@nFbcrm((x3kHGg2AW8kp8a%ZV{SiXoHr$=q_Sf0Wt^ zttH0&FjAOm;e57mn1W@XBq6qv6@BIVkHg%9n1UA7i7kqoUOJh#es-BBp@QsoX{P#R z&jPZ_DT!4N%v4?GEKv2UA4@z%-&bZYP`j!fqg_$|d&PB`?&;*#Mfsz!` zb%Tk){d0@e?$aj|(;pchG|93=U0d}jY4uE#-1^q#vU11);UESznh|8Ywb0Zl!|J4< z`t5}(f9{V6QT||I{eDnGHoX0Thq;y=ogEarJkKC{oShkbG;D!7TZn7E_d!nm>&S}o zVuO1grl4GuB*dMBbh`PnN9BqJMJ49KdSHtP@kakNdSTB(vgh?;5^IQU8cj}lq*u9}VH%98ImTD|>Pv*4|Y zlU2hLN>$ZOf=NY&t8PbnlUBE$udH=)RrycT4R*Dv_gQ7VYjZu>qWHy7$v%UE z3sas@yw+mmwp*UQ!I~~D)Z_6psf?+utLjJE*OlMIU5K7XDLz*j^+WfdSf$qL@Xh(k zMLbq0Ru69zBTs#Q#6g^|+&PHZ(oS7jyTm~Y(Jw=7{m_6{3ZB?AvO3LQHKrzG49n*QJ3e?SmCp zJF4>ysUB3|02DIh?eVH2b*KNt3}BR6r$<0uT~Y^uz5YX_vMQr%vC(LU9fFm zXLYX5l7Ar{-Cjjs*;H2+JNa7(b79ThGW;*9>V)fY^8MWzJ!}&kB`%_T={UV*`vq_N z?JRQ9zQw`vCe2lujJeg{Q&t48WazGR_*!D&4^{-PO=_>sZ2p@p!^A~pb+t}^cE)F{mK+__uU)P)qI!A#d8KRK@$X&4Z)#Og;$|BaZ2Ud3V5U_;%b~5*%j<6w z;?2Aj^`mh&y`}r}N=(U}>DeGYM+^0I&$J557NT=ZdA+F7uimS1g(Q}aWw?mhD@*9F z4`r5Z?mZ$=cWec+>j7D7YugXkuBPvFO)u*`pU!Ek{gvhi$GUb_oyjt|h=J+K=!ri) z@RmN7Ph!f750?fbTl7^=Ub&u#Webt>S}DD4avGWSpS%tt`^m*Y$1a0Z+HO}95iP`D zPgT{8bvpS}qYM%?!Fq&y%nzEp-c0q$R+KEmx>IfS$i5f6-`XGW7T=j1e7~)UO4z5= zk&2UpHbt7Lr^#NCZ4Agp8v7{3@(Bg>uEurckjD>rn1XUqk`V7yucf=K$VKt?Zydyp zTyuh6No`cNvc(mmg_u63ix$0;y$SJwhnm#wJvn&rLK9W$bOTlYrbfuzqFxx zbgI!*UtjdOclE?&2Z5R(T8LqD`{<9VJm<|wA9yHhd$!@h$mAw!@-MxeRuCd@)sU{# zy|_G|ewtVJ{lP(*3yoBAjdjub`Q-~u$9kB8WuPP> zHlNO~pWX9>JpOb)M=Q*QXzKGVZS>BB-17Y0>(NtvW83lU?#v_8gGs*?BaN6*x4&gO zeKb=}`Phk!9_E@+Vq7pbrHb<3S*%>drp_&Ot+NH>gqMywmik_%VZld*>Z!UZ^A)1W zCU$S5OJ>L|Jukh7DOes_A|a|CYpIi~6p#()9COO(HEeJ&sijh5i_B739@Tt`)Y)Gu zCEqL%=V2erdv9>?{@0CEFIp23EkwINdg%;hZh0+}&xbGtH9<*2gnk&J(>!;~+xq6f z(4vjAf*%U!F|9c0rDeez^>>qfTB`8OQ;1fC*uUnO_sEukA0(05#7tKn!kC$VA! zY1QlFmi~`abChfAbcD-5_Jt5$q^T*$aUjt1=}EaDA9U<#IDTir+^n|Q02 z?p^YhpMiSN_LSLw*d8=YmqZ#d@3vGy1sX9z-00Rur_YdEH*J{S!(4VG8pNP7(>}=A$9ZW#>e|a}et%L^qmIQ>qluPtH9S!d%!sF5)>_ zqbB_Lz)zty%C1ELulh|tS{h7h);HKhYm{BPg2*1{r!mEKgCW^;t}QvEYm`Yz_%xmzZQx}#Pu;!tco{YTyJ{Xb+TM=LA?B?&Pp;`{jQ z`(O>R9&Q;II+O19M>?l)>a3Gmec_kB@K$u?40zRl`Pa!o!rM)P_B)h9NkW{> z8q)bMq|?`uzxC`I9`G7&y#XT^%M+r~(h551m0Y^f^*bJ>pzbJ%PO7Qqb*Sb8spgmq zYwjX4e%?Y49h*Z}|7BQobq;uS-uC9uVEy*S!CQKevTJYyvOu&0XAqr7Fro`0N6KOw)DOd(d65{;CX8N_pkLU}Xr$&7S)4KPQpA4FmZXSFP zHzB$cwrv$3*=_6QwA-d#BJZkA3TlNTMu=&&+s@U#uIAk~BJ6HE;N3Q&iJd^Z?GbHa z^ry7j#$0y49Pn=2Mf9QF_T9NP^^dgM#$0y49Pn=2MeuI>(H1efFzvQ67q**=u#pMP zkqJCq!ZBte7C|JI;nQxrcee(5>BHT&X{~$$*P!^tAW7$IV`7Wn^@JdC! zGxNP@jEq+LltdfL3OJHR(ZPVCgFz%Zn0PV$h$U|by)0uPJ>+chXspl3wehlmBZ4SNi0Tx- z+A}^uw|E%8GAHgfeid;1%0?jVdd^YKvfa~Zj&foO)&tv(EHyu;rTzk9Cga*UPlXZJyKKfR39Y?F(cc3 zZ`Px<-d@fxQ7-0sJnI|;-ZS;yMc}GDvIx#-V~zT z)CXxMX7OWBdh=ZnQAnRzHPOR@u*Z3-!-F>{QdVc%lYqA*B!q5+rtzr&qlnh zR()Ehms3wy*2CV-$kEzVS*R7Fg$Szs>K!d!S?~QQuTu}|!BpL`MTB^Ec@}wYYMgF2 zpV%V6jlkCBSOBl->`Mr7Zf_$pjbF#FY@M?YSmCxxR>zd=PZ0mV7IP!OE)$5~ffy&4c`(5pd$a6QF>LaI?gfIo! z*eHq4?zZNUFZFApAOB>6hnmoerg&xJRgKmyv$91zfVg=@N1^Xo~;-yT9a>t%BI?wbULzoNE$Xpkq;A~G`NGYe2ucz}ch2yU5kFY0$ zl4$IHks!~UE3b=<%IhFF;>?}~doqZov!XP$IAX4i@nU7U!nO3_{8K}i3+v$`Hq}ays}B~{oe#Jy3p^|2vk&$HB0fXQ zX^mu>vIX_u=SF#$i=*@GH?Ys(BIwGcsSEt}jl<+1t6)}sv#+63A71MtKEo%c zm3;k9c718ib_c;HGVC|7&)}d%)&13EgZ_DSjtLh$K0%7gLiQH2NQ6kUrJ9`GK9|nc z{TC0}n0)faYdZT3e45C9L&RsOe8048+c~3tt9wp~2=WmWujA||AXLwovqctxUYoujyXMl_E0xsk=^sO+1thJ237zDdL{IexpE?6EPI z{OZup9;VoSHfOZ1R(boClt-?mlgnr4m6!{)auN4$7nO~2-t#seDI!r{Y%3SB?A>az zTF1Py>qKHr0wWgNidJT`dPY{~VjsuK%)N5TyV=ii3?Mbd&LYKg5G4sQxloK86aTa~(|hD2sOT9j*>V*< zeMK}y&&i6uRhc;98&j>Q;xl1d{S|uw>;c%7Q$;+0v60nTCe!MSDah->b`xUv*aRtK zE67?RzlR9a5Ye;_KBzBWe!GmkKkZTo^~GF>rkZz5kOj(CkdxOI^02npJ}8OUZE0)C zO;5(kcc+ZxeQjzhVt?2*%Ji%d*7uR@`&b{xw3YQdSKPx~ z^ZxgvE`^2bcY1)cbW)(d@cM-MsXObV!s3(sV{MISM`t8Ot&}yn4@-k|W7v8>H zBYCOtI}UnFsB$gW7XrCky7eeAx*SZcfX zF*aBTH9wPF|1#a+neo8GT(mMPUSoN6b`fQ7|Kok7E6Jxu=Zx-(j9j}bGHV8+g=kRy zSMS~8mE~;ON6|{DqO2f9VA&LbjOmaVLxDL9j+6-E2C(~Lxht^v3eQ>SCwVnFoYJJ&vb}^l)Qzs9-RO`tE?8#W4 z!Fg-!LMD4EGd08uJzH!G&2c&Q1k(+4meE!4)XGf2FXLl#Oi^f$v zMGewX)BvLq7&UNX0DCDiv6dne2PiUuu_cU5U?hZ2`=+FmZ8vArttswR$rF?Kwy5#pr_ zEp)}2+4SwUGdw(3!SfauF{ySZ-T&ez{@J{Tql^?2PvV#l^`eRUxMyBPiHq~{3jv_JUns5a~!NwDs#ZkMa%&_4aZYDOtLHT=cZhaB-0PVO!Vu zD->_9SVO1WPa~h|lujbsh$D_s7Lq+(H0&*kc*WM%9}mCi<#{A)^n};&-jI2Q%&OF} zD|zhN5oee{sEHlZ#v@NXkCJ>I#dCvK9rhqG7ozEujLukk5u;k_cymhMzH z&mcRt%PM2*RFKG_X3C%9=T(pFHjkn3-2`G&4tuECYtY<;B5!In}PQ! zQty9gzW;%DGw}S>wbXq7V=mno;WF@M2;O6HZ>8|f7rL7v`ECZ@W5N3|wjOrY+M3I1 zR0ih4`#5;(hSqax-B`N8bB@Zun>u)}$o7XV!`_>ab*T)zSA_SK?Cl7P2xydiPPd)- zMiu75y_)MM+L7q-eH`5V;vFo!X%)FQk*Vcc?|rHV-p<0?V0M1kyOw;HtS;Rp<8g(# zaCYI12qE~sTIP3;hF8&jHB7;Ihxgco_=fJpbdx6-|BpYCmA z3eG#c&n?78x*Prq-3{MB2+W1^4)2T$v4ifPC(-@${e-|=IPcuO+COy1y&2tc=X>|H#uG=1ja0I-r2EhwOT`?{RMjW z<1isG7tT9;4}`2J&8WBOZIQPKfw^#Y;j0Mz&Rt76jovTeS5+_t=bihmiG4TfKi){e zT!^MSarAP_kM!0Hzr%trwBS1|?yRjGc?C+x5CY$gL4JuFH7I)0yy;|K(!tq@^A2CX z5#l1ey@N05U@k;cxWv8)#IN<>J3jbYk2`CR(W^t%>D3{A*$8JR&O3aKNQe{kdeT?) zvJt=5gD)6iE<_7a*S^riTH($F=biiB()*-UC3*#l-`>GoIPdUvC_1C3nzy2trWk=Q zO<^uX(`pcDUGvfuzH^1IS-G>e2=(ARdXbY|l=i=hwZTdbpo^}i5!=LdKCv^Ss!z_|?nUkJQigLi=_ zvR&~;Y!yO0)u&SkWuaE6E!`RY$FId&Rqov>gtGAVk&F1F;rv>x)pxx*g)kS^!$ojK zxQwcVz&7Dr(K~T2;`YpG+*W$b! zS8qMs<;gaB!J2#$W3PA%MqPY5*!GMH^4;MZ(oOnh3O~QLjb2nCpXoum+h;~Q=0bF& z9((Ig(CgAp^0@RU0!InPdWCp>bX@J2DHHUMO~-kdf@PqjNEwBu4APUjeePlDoQv+= znL9r&V*8q133uvD(3K}o^iVFAhb}uUS90reO7uP_=CXA%Wz${#s~N&qeriMS?(Z2P8#jB~ z)I7Ro;97!rts{uHve7%HcVkU|MDJ%~F1%k&dz@l##s4|4pnSJOD~TzrN%THAe@7*m zGQ{vJH9}>B>86b6opVIseQp46us)vR? zH>)L7c!& zX5sV=a>~xXEL1&)PYP~V_?R9wU8Jt(pB${Xe5h#LI`uy77mDb-^B1a6@1$UF9oDMM zj<>v7tuOdhXLpd8f;?1|L^s@amiIp|Ho!0c&seACh{p1S_-$v6OHQm=0_p?jsYb!v{9Aa_)VMJspv%PPF%Ut7`3X|MQznRr#wd3>p^X*8RC^QutCMVrO=5Dlr$;T2bvy&0WMJ3+Hty~GPeX|_XQ7giSNg&@$DA{ zuYP(W(M9CTbIiLge(<`VY$a*_DQbH&2eD3$ByqKJCb=)m41eDG*8Cz+>b(-I6QYHv zRx7<+*LbY|%7k`KTVZ)9iG0?tw|GIpKfG?$+c-Ult$=8n=U$m`jjcmvyOLoKYe*wR z(MU0)1krSttp0c2$R11l$&I>8Ym)?QSMqtio;~P2GUaJ!lwkWHnm9$XJNaEk z(94k8ugv~QP>A=>t>HBEpxmVC-=R)(5ut2 zhnjJ9e(=KC^y;6RJyfv{3xb<-GAOrZSCSXEJ~5J$AmgH!@>ewdR9aLHC$q zN_S|hHrJXR{JN!>qapp4#e!#K++Uf!lrj4}l!clgnoa?_l5e&5FMssd^zzeEZPn?w zW(Skg6?g6{AzO%;vf1Nh@uHXfb0yMAOu_O{k`PC0Op>o%&gTt!si?Ournx#u_rvF2 zucvma<|_X5lweJRc&APjRjWCUZl#TPc~IQ#|;b8tnBS*C`5%Z zBjxoIEB)W6l=n~;YJzC`WuVXN$eB%x>kS9icr{BkRqwwwEGYACZ|80ovbShgG%{X} z+gDU?d3%+IDOes#qCS6ZqCC8!pWpR|tcS65tkaKQv`~45^$9ZO;XP-bO?~Bc^{cOj z9}1x?M33LwLS^0BCn#2&5fc~Jk*}t$q06zM!68enJS#Ky=N4t<{)K-GdjtV}$BdTPBpLp%W|I;5W9IH*GXQbc1HCRloPT z2f@#bSXs7>Y?d~^e)>|u!zc?i>GxqfH7Q5uAni=%>GyrDfs8+1T32dRJcP0k-8Q+M zT3o1e@a6(WJbtRSoN=v&K0bR(Xyu-EDnqHxLCY0O4C6j}iwbX7k?*sOc(s4mr2Ec0 zott`C9!jE`cktx5H7n^f)wacB>8ShAFWaj(&UFkH6yrPYoj$HBPn@i#oBvkA(F)N| zf7V`YIo~n(x-26`=Z%#)9>nMtLsmQYyik+OpR`x)E_Dnl(eJVd@$$7eSuuM}-QZJ^ zfU;1N#4kFiexG*;yjF~;HMF)Y*fvIweW^qUWg)sKA>s)!p(7(!2estvKDBhlq061S zWQcy}^A74mx*xZlei?(fQ4MR#g73u9iw;8))?DbQmYr@NETS5sTvw}ELt^BMO>67- z%2WxVEJUCrA;$HpCEq(*OaFFcnRD+BZ@8f(Ar^M6EJwwJ^x`6i6K22AS$*2NT~NEi z5`}VCeA`j2Iom#{YkDwmmFlu=r@Feuk1CXSxudFZqJ8jnm8A{>B@v5tdyM>&?hjTd zxGID<3-M+kN)qD8uu}5qmksr*!r4MC?{`za)s^n;f^H>vv~Mn5 zNgnzrq<6&+4^7?LSzS==f}Ay$I0%#^M8m-~<>HRD^_aO^ox7H(AxfebNt@-7=X6^= z|CvyTte7H;U@RHRE&E+J)%TB8z7&b@>jtPtLZ}J(q>6k~i z>XO&0aJ(**EuBOJ`JRgWIOBgJpPu5>8^87{t@QLu_tQ$uWm*1)d+Z`|uj!~qkIk$f z+<(MF-Jh?uNHuxksbF=JD~YepU!>k2JSdRauhQ=BuS~7|HiO#ey1lYFWuWdZ;_2K+ zz2>i1)+6s1ckXkdR;aBIJ>MCldmZoQXWY`tLrrkEjk|E7^_|v!!KsDyi5j(>C{9ZG z#cK2`gMtj=*MHTc?6LLUZ&QlsEt%pStq|eH02Vas?`7>?OutmTzEcLq7Vy3*d6qw> z(b;q4(djyrk=Q1vyIV%4EPZsxg|GW7lJ+`r21H|v(B9zh&0Yq2Ddd7E;q(XA!_{iq zoGpI(@0#luLunkX5aIU6utRbB>!zi3qy7s$)CBt+M-R=xi+_3dI@i+e`lgr8h=beG zIHu_rJ$GdF`=ozHXa4AbhjLL97cr#cIluhxz4e(aeH;YNZJe9LB)^4iUX zEQ2E#G^BXR%}+vu?vB+nf1Tx_Ttv8*;rm1R{FQN&bmh3B4g#$Y+A$%H$>K8K**bdA zmuozE`)Wu@thNZE3^VuDaw}f)h7K#VU?Rh6vYND!Gn+=dNih{luWM zhtO9;4bcxG_Rc>sa#!|P{qb9C9nTWwqIX6<^~+V|k?ZyJvt1txp>K!?*Rz~(x4itj zMSVT}k?r-+uSE?}68)xLpIUNxP)mPBo<91{C>K3hipeyKk;6yV){SqJ2%#U12$V!` zd1tFB6X~t6(hD*r;2r=qL`f89I9f|i>Qzf8BrkKcLQfyxxDcXt%i8kSfie31{8d7@ zgFsDi_aemox8h`prZsi<*M>M+AsTl`^iFDgtbFg=7~SX5mCim2HNm$!=pNqXIn0t#1o?uWTBc>^uk{^C*Y0_(YTuwV%3~jx#jT~ogBZ*+1KLDIo#vY zZhKrvHX2n)?@T{AgtAZ*7xBZl4P>T8rFDV(MMAjyMKtc!>F!dGI60|$b)C}gsgT}kugIm z=|7HyJdC8^>p&RYq0_!s+sJcOa_O8KvUw;AHE|J1AM}?otA6sooBwtQ<1mQEsF4s= zzKxeh6N~DcQ{4C!-dDs}7QI#cR6m(7(`SCR(LFqrg_^jC*hi+z*9UJ4g*LZKz}Oqc z7BTuI#Gwpzqo1PKl9Q)KG}{d7eDC^lLwJ0XLG0H#IS;O252#<0+YY$koGDs-N|+4AjI$yu3@v z7mJpW>o=_pVHB8l5~)#c)KG|jHdK~5GaU6>#wry_LqbXC!p^f^;r4rZtB2A z>a|&e1OBFa^yjDRlbhlXpK0;aVNAjO2TGzFZdvQ=y-!pyzg4}p;cS)Z{kBFHmJ$8t zGYk4Hh*Q`62_yUI3hAfDqn8@>4OtVEM0ZT4dpcXXO8Wa-%MYO}M7xM4+x`xhFF4I; z^;zLzs>GD0Mk_2M`pvO^It8dV#@o4Jf<8A{)I%>U>ie)(D2Z;2ymT}CO4VsP*U0n- zQ5K?I#AlzDm(P!^udB6tx9(|*>CvCj3VjA#sp&0?s*lQ>MOy0N$I`|l0(~Du3-L+M z+_KYwcBbZtz73LN5M6i7((|v*=2l1y?D%vbuk6kM3h83md-6@sqYKv8?An+ zhq+KI7eVbLsl7~Fp}x^??sFIMpyo6=ZOZSVxr2%xq%ozae@zdfJ$J1rjY3JIF~pn> zOo@JT87PT(04*lSOLC&m2-GC{&Ao=@(RtLBit^9Zo=iS5{}9bTMRUPug_g4pSX4Tj zc%p)&nJc*rOo@K8Rw#*1ms$*vb>Fz;5g-Y5kACwk!tyBJ=J{_LEPY zy5_atIwBrx7_A2*+(`HrwH2z(b$`Gr<(Xg#4D1_DZ-J#e4;2@1pCHtibBLG(w0*c5T{64 zP7(LNVon(`JObhrsZ>r;h&V;sa*9%O*_tb6Q@IG@6#2v{@-3%`-mhG&ET@QjO)(S9 zwv{Q5R-A9H_{1slET<^-x5#V{nirF7-x##v6orXXq%Eh2XO3bv9qPvSfH*}e zl~WW?oFZ*GMX9-nQxp)VNLfx1Ac#}s6Q{_xoFblsig|s+jY+K&mPaqjRnDY|Q{-7r z5zj&MDiiTG`;(g)GWm8Olw6Iv*nnXNpnRpN0FJC)C$Zmv-Kb=>M=XhT2W?&nHI%d zh&EQ#V|FGpGpXH~6=vFM=W$ znVFb^uVqQz`mh-sboQ!oyk^|EhvpsV@0{|S%0>o zY(beT7qOyjL7AP&RupqtPO7Q7i(m`N>`b#x2ZN6eS747L?hUY(??) zPJGo9(L%5VWp*Z8QG23fW)9YgEht%1Yem_DGCPy4DCS}d%Ir+GqAr3hD6=!!irSMZ zGY7FwD2eXfkp*RTCR`bI%_tDJGWM(F@GR;1KnVH1OG~7pKX1ettR;FflCNnd!O)wXtDU#Z~ zzsKxMW@h56u-FGENeE(PYG!9LGt>IcigzjY98WPb(=CHonLe{KnVCtfOvUjYW@ch8 zM3e6m-s~|ulbM;Q6{77~p^7jwiIwRyJCm82#L6`LGG=BHE7LF;nVIR9L99%l*_q7D zL|K>%(LxX_(_?lfGc$>msW`^R%uIZ%7T?vQ-*zf`$zygVGcz#-%R@;*5G&JXb|y13 z?OsOlKGUA#DQ0H6S`jNV#OzFFW}+<2g=is&l_{B>$;?dD9nto5QAL=U#LD!Toyp8h zVr81WI5RVem1)?S%*=GlAXcWw>`Z26qAbjXXyPF^EiRdz$;?b*Wh#y~Gcyxk@5Ofx ziLte>sAP5~Gcz#-%R@;*5G&JTb|y13v2?7H-E*o)q=;CV9Q1ao z#c`nihM7sMOv&s_W@cg;h$dF1;?s=?Gm}`ElG&Ne%tTEPO{`4CCnynSCb2Rlvoo2Q ziLy`=Vr43hR7IGX#LAS+&SYjL%0e`;G8LZ$MVOh1MPuZ=xv?^BmtFk(IH~U;BbwNn zicg!Eu_**`EG2U-nP-WzP!r-O_@teAmWV(}bjI>hth|*oM*i~T4hKP8NX6^{=0oE9vO+9g z5-S%JkCFP|ju7U;m!Mq)u`(sIGntubPZ5nJLrsX4sW>(sVP+C5Q!+b~nVDDyB2W^Y zA`g#~%+6$HrahN6Rt>d6NkR}SQ!+b~nVH1ORLl%vW+uwD(MW5liIpjtoyp8hdwyzc zEh117?QzP~k<89yW+t&R6?0dZnTan1<9okC5GzwMJCm82n1bb@Bs$H=IbAY4lbM;s z%2XWbWM-y~y_&V%o@Sc0omk$}`blPIGBXopq3$k%SecU9nas>YggqHGYdF4iOx&n% z;w7^)nVE^X?CERtO~}+Yw}l{9ret;|Gc!?lVr43h#WFLKSeb_57-41-D^oH%lbM-V z2I}r2h?Oasoyp8heAgMZLP>P4c7)zqB6cP-Gf@*83pakLJ^wU*Dc!Yvb&zCsCNndM zm8qE9#mr39#6=J*Q!+b~nVE>NXQ{^j#FwXuIk1x6>?d|6Gcz%lJ+F1su+Ov&s_W@e&Rh(Jkn zkEMGt$?QyKW?~A)7Elts378{~WOgPqGqH5k9VH1ttW1yDnas?@T!_XNp;P2-wIs7M znVE^Li1l!_B37nkb|y13Q7$4-k`Tnol+4a#W+o!A&vEonyrgq2$?QyKX5tvd*@a`8 z;)&^>k<89yW+uu-O`Z26 zqFh9vB)TOOH%T%(lbM-_Kqus2GBXpcC9Vc&UCAasGg2};lbM+)7d3Ga z#LAS+&SYjLBG9(uDnW6d-|I+bXEHMrR~%eLarL3Q8Hf5xW@j=p6Xl{NE`nH@lG&Ne z%)~VnH9<*qH^ZwfnVreZOkB57E^0`>WVWWIWOgPqGjT;m1WFQuSecU9nas>Y{{uBd zNz~^ZYs+}LnUZ_n))4wQ=+B|wMX}d4N-{f>nVIOlpe8PYSecU9nas>Y?+!IYNmTRf zv69)D%*;d&66KYS%}7cv=GF~l+4a#W+v{J5siCw{$=ax^qWp`l9`z(3pK%L0^LNKUR*Le zlbM+)3(**JplI#bM<9gMQh1NF~YaOlD?c>;+>>7^|UIHml^4%+6$H zCdxuhTm-Q)J!WSzGZW)5h{mW9?I072N@iy=GZW)i_{$y`%c3`Z26VkFhxD>6PcMpcC%R%QaTGntu*WuPW5f>@cF*_q7D z#3(RExluzQh?VIvJCm82C=0d1_%$)fe`xD7JCm82SO%go%1!SfCwJ7$&SYjLM$GX< z05zml?S=Iovoo2QiLrZ>>uN=;OrP1A%*@0x5P_12t-gDVW_BhsGx2l*&sb1HA&8af zF*}o)ndm!5Jyt&3wtOaYLPP((DL#SOnas?@6x@HHq*RWVVF+2KlaYmGM86}@c7*_pu1G+Lq0fGf2S#LAS+&ID$rL7?x0Xo_V- z*oMq*6PEpD5Ll1scO>3UtW3%5OlD?c3YLMA=r`Qf-|?883Czq$Js|##_LzQ~!m?ORTcN(uZ|-v! zL9EO$voo2QX<4_X9%#=GM!0b%&O~=cBOGB<2Bt*6xeSyf1hFzbW@l0dCZQ(LZ|*fL zPY7aVYG!996Eo8?l#NzsIbC~Y`P4=$Oo@K8Rw#+spKo09nVrew3U!Zu^DM&h=v{*g z(>1d*nVE@p3GJ0-e;aM-2G5|On%S9L25J)hX8VDX=(p%r4cE-hWM(GHiXylkE`nH@ zKC?5KnTa)w)`JmlJ&2XboNdX>Ozf#>e=x%B4`O9XW@j=p6X!FIc6VG6D^oH%lWUIl z1LtG(o6Dn!*PsEC*_n($JBXGj`W->*NJd;P2?{69YNgBbMNq=JPZ6L z^Tx^g-wsyuhb&aR^BhY&S7(TNmVQ~4f0ry@^J%JRV}2zhg|sRifBJC#Oq2Xu6(&eb zS&@Fa`nt#hRrh>KB1)n@FY~t7`QTIf=A@b4x%EBNu6J10@x))(4_5z_B;Evl<4Q!Q z;RBPrYhPB>=V!*q?|bwlPRV?u70N|4{ZdosaOjg8ll_zjxP42jM(N~jadUN(RSKEJ?Y_viR-F2|r z$P#jCgDrkN(yDTimTJx9$wn*G5YcpYmwT8uEZ?2*r=-=P^sUwC^OKBLs3D?hFzp&E z8;!UT&O2?UmoGyz^=HXpMl00N9f^0!#>yYl?hMx;t?Er~t}4|XX0$>L5ly3H#T;*M z{dD2|q*aGWE!CXPTt-SFYKUlx$vibedKI7X>QP%|?ATJZ-rUD%g&Ml6a|c;NUMp7B z`;*4iJ(L$s>Q^*S~ z?&<9zt+<_78`cUnM6?hssrNciF9u{8cuaBIvsS1f+F&~Qq2Al>)sUM=D;`ta_N*0Z zh-mUG`zM8b>O~$`Jf^tkSS!>J(R6!&M*096@%g9+dH(S@Wvx&{TqT6~okn`rau^VEZE z*V+EDR;VGa!9qMm7W5mkq?Ji4w(D&FSS!>J(Zoo(*wk-Hmh=m1E4J%wJy|Q%5YhB% z1g$n-(5kbNY&)+oyjHMQs3H0f^nw7bHaDJ3^0Javyaw`G!CIk)h^Aj_rqyOXtvYPm zd8Oo)hP6Ts5l!c6vuf+Jy8NN+R7Up!3st##<4qY@9%@S#?%BEirXv#$@~U=d&;oVo z>v5(GEDzE2yJYtU`-`{D2;bg0!6}1RW?rFrb>_94S8mppZVyZ^tlRcW^!+xC9mJHX z3)Dw>r>oV)k0m0SUZ$8jUf-M&o3P>VvC+d^$UH=jANf@4E9-C05AfGiujSMO(Z~=a4(IpMAWQ<1KMJF^b#DWiH=poyo7dyO>U(-v`88$oO>; zTi+-XPJFkMzI!99L>~tkxVTprB9ygSc<@iR{SOZGb`U5R(X{8J-s4{69z<#t|EYcJ!_QY9FL55=>~i~j5zWEEUrsp4 zYc0+-%!O!LYiXYUwxj%^b~Mj%RHG({rn|3XOV(Ihf;I!o!#PiWBH62ZWUqc8PX_H0 zmWOCMgCv_6kWG9*mKtpz&RRs%lN{u^9w58R77pzzYKYcOh-qZo|0LVa9x~c+)DY41 zG6k(40j(d|$Wr4vff^#3B9P>{X38_nWA7E$BGeF92D$-C>tHWh2jfXAT<=grL{mKJ z`bGaFt+lPl1Hd&EHAFO>(I=)0|3m9Jdl|THqlUPO3h^=d40p*(W)B&C1Jn@F)K^+lJ`QS#9)}RU$-nAGUh+RQuF#J{4G}FwKl0%e z`EYfptW$zVzXVefqS^C8((r5;0){3-3{~R?$H1V%UqpGA?n7nY@ z1E7Y8rn>;td(Fv%JwRIFJ_9vGub(V6dB^WQUe$Y%w8Fg%YKUk$ai`uJLB04sSq9uM zp@xX2-yfureu6yMBcv7X$xuVwA<@}3dBflaGTRa$kHkZniL0yRW5oir3# zAI{dTw9e7Cfy8(cdQPY<-6k*cdH9v@JNsKcncyHWGSxNBY}NAI9P97iT5~X5_>=A7 zq`On)?KyK*+TUj>tx^&nX+B%^Qgc;KFD21Mtgd_~yzZrhaLtdV%DA5M)#)FT)Q8Wf zBqBOb;kl~BmPm9*h{ov$`o*4J74HAu1joxjKN=+oQSOWU`iCcn`?ZoAOZ1A+Tgr8D zzUokHhMHgXL-N~yy`5V>m$JYwzPqub6_$aLgxLS{yMC{}?fj8z2Rb!JO$KzDuiE6D zsVcsDjLMjH;zj?P-Rb=s*GEW98GC20Ixc3b?2zB?rEwBd zum`bkgjljHogdZ<{OR4tIHLp+Tpz9%*NN_!OzG&SJo}uV@8w|_cIQEMq)o>f4Hr? zxKcVj{@4(I=r`>p_A`zvcO+i#ALqCJ=K1jcqLZCbGUm;BYW3PAGgHw!7vhJnYxudo z+8zF(;ADw&4G~x#y`}ePa`>CP`@*xom@08TBigOUM^BUve|hRoc-faO0^7%J-S-N< z=zVi;v-kYU0rGD09JTY;xkmTBgXXAwOXjNIGaXAjHEy2DICQr9tr7S6iIY3M!=LW- zETFp~l)7ffr*<*<)iTslGSHmNF>%_J2shZou3p-4e*zP!DT*P|n3;tV9{efet*yVYO`-EdX zZtHI7`h?&5rOevj)-L)h80OwCS|7AZ#FXun$$Pc!SK;H+=?tJyj zXkMe<$$iEXzwGh8Y}85OJ!-rm{ra4l>Q03PYFrkcn5nMJ zUZ8eWJC<0LzPrp>pz2rW8MWkza{lqm2mG;Vo|afT>W(9ZBEoe`d42YK@h1*Uamqln z+vf-J9X|Z~`6~XF+Ebj7h&_nf(&{|2lfH>EZNIS{D>mLJVPh*`d34(MeX_Ur%X40-b!{cyoyR&MntrVy?Ow0Sub+AMn|5;A3U7U*B)V_# z`Ps0pmeFh4d5TjHy!DM}dQYZLWuq_qtz#2W zcdQdd&%b>TU*zX9Ud|0u9J`C{gJ|OK?%M4a|GSi*;r`Q(w}kzHXg-;b{!5axYE4rM z@A3(+yXU~&OEfqCf0D%W>{UaaQX53XTk;o% zDuO-8Ip@=7CS?&8ZyGi$27-{ek=C|EReIB}q&{gc}3E zGO$fBe&I$~{*8#XC`N~{4O8$DMT~4>tGft{U}H;T-xx$v z1eYW+7oxFm+%m8gv8}KT-7>IEFzWa}*Bnz2foYbc>z099;m!*+bP?DlI7)Dgxd^m4Xo>#kGEft=a4us1vJtv;(d~wR zg*C($efZ5foqq7Z|7llG!-qqC5&iI+5hqX9@Ol=RVh}h=5dH9*5sMycDBoOC+90r} z5dH9*5vA`=H@TO6QR6UDOOLKH z|1K|L=Q&r2Q#HJ9MWz@8_8Oueely|*weHuudKv`w6rvw~GvXcU!4^fg8$R5_o=QnX z^uzCeBQWJ5T8M|=yh}x`uyjN}{AL8!9BYW^hu@6A)_vHb*wXmT2-}0E=Gaq+e)!D@ z99OJWWVOWp$8Sd9*kyeqwmqUr6#Y;VBXE9jn?%-EArSrWn-Mq%AGSMj5CHw~n-R=S zyr1V@0`n8?d1k=83~M<9_5iF^GT%ZlH<37s3CvH#6dM-}m;r&3gkWwWaTI;#C)%?{ zl65@Mo`#xldrC^*%*qtOI4w5Oz2E9NHN?|sAP(^q?*X|zHO5lv^QbizvzmNh&exDrc3K7!GxF zGjyk8m@>w5*sRqj5HY^DfvZ#$-okSusOKF8Z9ek z=uSx;E3r+4jiMI&M0cKPSusOKL(Kyxys%M><%HMGMJy{f?%HQY2Z7io!bVY(eWGQ> z4BaWIV{j+eFwX#$uo7&ND3&X2@vtmN?;sjUwBF8Z9ek=uSx;E3r+4jbbRLukJk4vSNme#vU0?cwwWMk#Eq=^eq!+$mk#t+eFwX zTKhzI)@WHVLw8E*Scz>SY!sE)C%W@Y%ZeE?8dj`0;f0N&wNG>_I?IX~GCByvHW4<8 zO6(KeS*m5l4BaWIV5Y!hLl7|N(7wuxAm*)%vkMx&L$HW4<8q1Y#K8tz=hj?Qic zU}J)H0&Ejuqo~9_krD39%ZSY#qv7ur7J9JM%ZQa8kE!kq$|6`79qkGhda%?B#Y&Gu zxxFQ;8}1{-LJyXD8L`sik)9RIokg0fL9x(-rCvs?^ccbMGCH-=Q(~pZU@Lwu6jtXA`zQ7###+HwgPdCANdC zlFn#mh?8pA4Z?mz`#x^%jE28g^t-T8w5+&)Wrp0_ z;T9eGcGxH?nIUr@&I}n1Rv15EqiF3Dd7NN|jK=ML*e1e8F(b2A9*dYEj|@12#5f2W z#Zc@MdAwtWjK&%SV=ZhHL$OcfF_jrI8frJN*n*9s9XWa2W`;b927%Zn!bUM8Gi06{ zFhfQ|4GQxT*eGViK9T1i%#hLW=zzHoY!u66_R4b{X2>%RoS48i5jKjk*eCKliWxE* zH|H>igN-0?bt8S<BCnU2 zA){esk-uFNi+v)m$(SLpkZ_M4>p|EkYOzn`bssZiG<+MvHW4<8TI>^fZOIH79Ry;V z2pdIPR=j>?hP;}@?Ha6|VWX&JhRkbZX2@vtiCCY*Mp27>BCo@lA*12n2eyf@QMC4n zyw+!iyz&kLu}y@HVl4KFyq~}f84Yc6>}9}4(b^~So&_^xGcVl4KFJianRMx(W3-v>5|vDhc_7|skC4a))8Cc;KBBld~BpTu)UW(yAj zuuX)GVn*x}8NoYKVw;H5IDG%I<0ZCGY!hJzWyC&_(PEp3y>XX@*e1e8F%Jk>qo~9_k!M~!BNN+1 zoIRVoeWKVV!bVYveIm!jX>d#!2Vt8C8^uuU6PY`s#WoRVt0r%sD7J~PQ4GaCk>5Cb z4nbDmiDH`w`yZ3HPZZlk z*eHf#pU7{x205l65Zgr9D28I6$gPAC&Yr>M2`vRSeXvms#XgZkiESb*pN!Zi`UtU2 zgpFb-_KDnHIh5EY!fwXo?Gwc|5jKjU*eCKEUKMdnm?y$E5jKjU*e7zl9E$T71Y(;A z8^uuU6S=H7ADlnb2W%5zqZo>PBG)t5hhMs4n+O|4CH9G2&s_h0OBCBg*eHf#pU9!a zHW8;y_ABD=25U~SP2Aox6#GQ}))>JtVI2kAMA#^1#6FR~XGZ(^5Zgr9C}zYykr7-z ze(8#R7wo)3vGH=Y5k|BbxCXgqG2+0!3wB+z}6Yxvy7N%!KO+R^G7I zg4I?m7F!$_GvV6A9d}r3!D=fb7F%3vjOO-+)($IKSj)y@DJxd8utm&&MX-{EC8H5b zS!cs$@|Lnc!_SQ^4+%!suivto1*h@~Mc4r8%4WCSy0G`t(b(hwGhu~-|5r6DZYj943TJ{TPY zVrdAA!%(aZojs-P&pA&#K0>({mWHr648_`zL-7pBM~I~%EDk%1wV|`}wBrZoiDSYY z#ldffL#90*pSs^!9>Q6b+Og#Pf6b4kELdb7Xe0e@N&H?|r>coRY|u~f8%~4M4uU7% z-x0pPqo;;#B5V|6 zu}|chVkXQm2*frKHi{d>K9SoGGh{SIHP|M?MllroL~f&8gNzodiR34>5VGF{uT0&k zzWx6swEUggk=ZxA?st|0e}mvX3*J=`dj{CB{SAW8%y|vyEC>Du!EYGhuWMaSa%A0R z2N=muYG-NR@Xn^B4I7;TA`bvUY6^Ct z_6^Tid0v{2JP%3j`YeLW?VrnvYl=(ZpL5O#u5&ICmxVkz#bv@}G885IOm*0=3aOf1eb2%+fFS3Z5oA`1o1cai8d6Y3(tb!b|rD;d$_z!V!rQaTOD!c+R!Lv!e;-o1`7bJOpO~NvF-aQE!qk3)g>uiAXo4=pBna7E!7ht(x9CLo z)y}Cg>q~W!Wk(IGWVfp(yDQjb$+%l|sg5(|hACQhSFo0LJ1nxhf?XE7!-83Hs_BgR zXNs2H6|C3Y4vXxrV3)=2uy9<=1hYYd^`YBO#GSYpcj7j?+=8g*$OE?!?9JPMpDxgxz7`P?!fB+>x@Yd+gAUGcoSO z#qLgA`UYzpgY`4&9DdxePm{!C@5IHp6BoNXaVZmym(xQG*9<7dow(55iA&3bbIYXw zB~0wDV3)=2uy9<=gzL%PiHotz(%IdKOY4@=T$}bzTn4)=p}P~8wjXA~Ee7@sRql+# z26xA!7u&nY25VSbKC%mf6|mi5!8+O`yI;6Xe(3tL-RHKAFa5~wMx}4C8)1@NF4?C^ zVzPIUGuUOZJ1iWp?0sWZZ}-1tPaHcVc3(UQo|(`)+}*ND*m}?mxr>~>!A^lmcI!AM zczb*1lxjr~OdlxyzUF6u^MNV_hY4`~J;2&iNJXS5NgmeN||w&WvZ zw@ZE-VaJQxl63}Q(YQzLWYyFjPv4QFsrw3 zgdI+?EJKdTdht*=DGQw!4}(($Yi)-8b|WK#XvND38TJRn%Iql_b7v-ULWUK-J0+77GMtpzQ!;+TUlhk=y?7{`l!eZVN6L!1b4=EY zM~IU$drHP}@i)({(t7a-aZ+Ya$@mS|Ajf3Ac!W49v!`TI{z)rg1b>g#i${o)GJ8tK zq4-^tg zD9)et;t}Gc%$|~QS#dr%f0)VOgbXKT_LPk4nd`$ZT{$7cNm=N;c%*HV+m+uE<%A3; zWf|wiBW)#eLWUKk{Z{1bO}-oJ#UsQ?S;l$sNWV2kaC+8@M+PTl_LPjjXZ}+Ce8>qI zPRi^l86&uS{L+;bH(4v{UN)vHFB zWNnBwj=}9y*ZUMOIkD_Ff|8!|;-2G7vU*{3A-u4{+R|XvYY}3Vi`@zP%nU6em&fH4 z^W~g#iTG(SU#$BL_AqQ3oIfAIe6c%ZODCAfr=6PRfeQM4l4_mtl&)gOA`A&SmH$gpn|l+)61Vt9!{uvOnh|xXz_yrG)=n z|2~4tgb`eZK7z{x`+Ej^N;VBHLyO4eaXIm%la9jjT_>aSUs_3u;84;crBsuA{C&>3 zOc=psnCFwQk`^Mllz6#Sa!LCLE)&iHN9= zEdrtCC#RS%BRGHgu=zi8a+fS^?c83u9jAz#q``6VSIgy=BJhw?TpwJ|T(drcdjS5< z`TO@*+njS|Qh1gW4#mODOYTN4vto4NSr9+s-s|A>MsA^RXLR9N5ZB`F>)q}~F4ryR zyznfDWXEgPyDdw(+!>AC1lP9KnWDMlBb1;IOBg__FuaLK4vi0RJ=ep5i(y*?TT znH8tb=)$w?$#Bj&hm0;f3xZ3xP@=*lDQSKdgsZ`1uP?1BMi-t1!R<=oO?JE_RI=k$ zcoqb=UE!PTSuwisEC~KSq)d`MD@GTd1;IOBTnCIUJPSf@>aIjH22hg z&mgyPaVs};iXrKk!Lu;j1xRDEiXky>itJ3u4QP88X@`hQzp)YwtAh_`wVrjV~RR(YTeH zaf%@Zme7_J?Eh1SxEEkxm+V-{ZCu>Swf7BR!Eaz~ZCT-tLCTQPRxu>Ttz3Jjfk!fC z$Y`q=qH!xXc8VbeR^yfx?Eh1SxEEkx!|hnfZCu>Sjh$kMfn~a7#S9s36+>d&%C&bI zcpPMgjJAp)8n<$j8@UD+_Lddw|5Jvz7hquT?pVofT-?fy-HluWD}KugcMMX7jJAp) zF>d81H*(XNH#20kRSeO%m1}S0N;ye<@(l{Rgdy$)82QbAgK`@ew{o>p3^5X)+|?I$ z2}4F(#gG`ca_yZ4p6~LUfzehmB*v{=?G!_dl)bQGhEh&aUU^n>8yB~7wNnf+Que}1 zYBFKSXsZ}fhFiJGP49H(%?ufB6+<$(m8+d%h>>NE+{(3O#q(&MUo+Y&hA7<1)lM? zR-TpI#>K7N*eQk>>HmZkGi0qK}Y!$heQJoMK2i$ARXD!Hr_`Q(ztjQ=FhL>-Yf3EDyJBd=8!}A^DDXWi<`e0rx=o!F7KXmNn6Dbg`2;j zQw&M#mTQe`(<+82-2BZr#gMdJaVzl=avK-7ax+dbB;C#AT{XYX|$(N-}e#I0Q0mvEoK-!^~qRxw23R&MMRL(*Q2(_^$%3{kk1 z8#~32wD04umeE!*B*d-U*eQmj;|DY3-p(q9DBQ}mK5MuS=bn?%Rxw23R<3r6A?Y~5 zy)&b&Vn_zJa;-lZ9*cMc;E};9hJ?74tDRykMYdvwo`>qH!xXc8VeC zN{CkwjJAp)8n<#|rx=p1mzW`=tv{Ivg5L(;V+ujm+U6+>d&%C+h$ynf|XBd;d08;V{5w{oq|8eSvw%9PPoF+}55 zZs-(4(sekmei>~QLt@;@4V_|0x>LXmdF5>tLt@;@RZcM^-Hl*|jJAp)8n<$lQw&M> zEO@7Y(N-~}47YMarx=pXWOz4%cPXr5NQ_&#$|;7VvkczxV6;^XiE%4eImM84e@ABB z$*u~ctzt+9w{n$J3`x&~d4A>3GDa;a4xf9fIJ51cY2taG8|;W{G!W0}Fe5n}aPN7>(V*Q?4!Rx8U^nj0Qe}tsxj41ot(4IUf7V`|;jS zdW-L91G|5Fn}cm87;Sw=hq%#^alWI`N^;injPu0j_11TEh#MUl=Q}#hIiKYF2)W6D z8y&Ip9c{!$Np1sjDR6q&_xb3V7`~%p=R4Yn9n@imyqM)YG1~f$j^R5xcD|$2(#4Il zG(Fr`OJlOWqcgal5j)?}X+FgEE-3{@Ti?+N_cKE0J32kv=9wj<(fcge7#~#it@x}y z{X82M=FWKvf=@f%TH5N1!{Y5N=XiE9Tt1ApzN16j&#-qhxW#dOFggfkeRrrn;uTy@ znb$y7tA4FnvuTPs@T-@zzwan9eY(yxkH7wEwtMBpru?(h&7K=y!)oH#ClA$?KKUcw zGNhs6H#2WrVm4HnVlF6pBg-*i_q_38`p2b#ZnC7l;!uokQ?%H$S~%5|-}e^MxV+SA`to41E+YS$vC!OKdAeRE8Vf}gEI8{AtnCVxqEaV*W z{sp7u&gkNJSeFmu+1&=qo$9n#WA2f`ahZwSZ^WOZX zFE?$^IX2?i632wy+Wnj9W%EMy(GS;d;J6s=BO2G5tGhq&OGa4n+>p~qo)>=G39KHy zb%x&9X==PZ0Fx zt+76_-@iNZ?EcHa{mhnY&o+aOTO8f|&Y9-A4+fZy$1VY@eaD=xd$l-HPuQ|w5hG69 z-N!WgaFCgG*P@8g@P6@hKfU$5L+tGVMsPlo=L$9EBaH`sJWoGZ{f~G>-F-#;hST7f zf}s71|HVW8Gej>64(QBpzPxO(d3bIgbN-uGMah~fpT_P7Tk7J|I_OjHTl5$sM&M*2 z`*wd5_FfXL-7&z7d-qJU$maZ<=}q;#-$Gq7b!A6>GwZ;!&4?HJnf>N3jyNXRQ-5@X z?sE3&dT;NqI&mmwK`Fn++!@Vj0!EP|ON&r+hC9!`;O3RTB1o9bs? zxoQLNM%=vVaxS6C@e_vBOqb?2$aUtLwU^6;&lcidlW);Ah&ez^LB>~oJ6 zn{Le~n1^23p5?T$L;nf9EL6zF*KGPF!@2#UOR*VPb)=a&twjGPj1sg9mz4v^9d@Ox?ifZ!k&GDB9uFCKm&Uu2C znhk>56)sihz1pGlnu}Y9TvI#_`m8QSzdj%R`4Vc^6i{cTogIm{1eI(C$#20T(RJHDSy=+$B)n4fyzN^^0 z(Q>L;zU-~6Kg-CD`#t=w)$X|a#TjpY#i1CDeYnHM#r;CLZrzVqV360`T- zsb-@7V)!|M-Tmtf8L z+~?tg-7Dy7OFJk|oza|L5VY+*S^evwc5(gt7KO~6TRxWvJkX4s6ECe-UAKR~hnI6^ z;?G5QKDRe~>HgjEuj}GOU!_CMwxd(>SbJKLujJ zw%&1@Yk!SzTXv4()R{ZS1WWRo+ry6+9-=qzY^^wTM*C@uJ8zo0zwhXH@~{>mBUU|C zY}A`$&4P-b{An~8x%l(2>X2so+K&%cFE=YO-;bJL`rYx7$DQ+py^Os|ZThx?)~~!2 za=grhW5Stm=~VUjo?Kk5&QakV+ltM1JI9-D8$QhPn870vYVe}RGefFn^jY=kmY!fFeT=tF%!%sUw?$sz4z=^>VU70(Zk<~y)+oXF$F<~%~REyjdSDL z73+jNMlma98wBTFeL}o+Ru}z5^ZM$GN{h|iQzn`gtv|@_ZoSyNb?7AXQt|uQnz<75 z(W#S6^R4oopE3C;)$*KXde8wMgp+m_o0lq0G@p0ck!2=6qROVp>X;jIal@IXggja@ zLyjp3+HJl(j_+!(PmdcaX2N|5_Y$xjTv%T9d#jw$jGT<6?+p!#;fWHoN#HSz9M$9Zj+!d4uUy<+@4u7{pGR%-;f~~=QBh;dUH^en+-r%v~Ss(X& zK`^>})qO3yz+j*CMv8mIc_uZeG8+eTk? z!f}d6WJcHfe38k0f37+AKL=oa{$`~Q!cLoq>Z5lK4SDXorp*GQ`}Z~9tUK0Yi1qo; zmBJp2#_G*ep9(oHX2NLfY(M#PJbPdpJ!M*X_4@q_%xm@gn%Vo;jrLZ*!VJlsVX8K& z8~v-Y`3BhRmJOR~64O zhy32t+_$I*`DnYTMg06lv-Ah!_GNgT@kRUb=FSUym~uA^^%!C&^_3gqCQ~Qr|6JNQ zx+Atuba=0et+gd z)4joIW>fnaK+GB2Oz*DULD$)s3Hi;uI%CXlriZC^(&&iO#`)k~O?8#M9rVa9okNay zP>tc{=5uN%;^`}f>1Wq8D`LK!TiyeLQta|t`pHL6*H<;3k>NBLJ@xLv zrqxA#%kfUtM@zSvCQO;2b*J? z^)aRUu8J6aK>f4L4Nvqlr(Y+C4_Y4VR{D-T?RD4Jg3cTlGvU=eENl9<)@{bM)6-TRm*Kb=U4*^G+Sps1F+kE-FszNf z$+XcG#$B7a?W+N%=aw_gjJ8W6M!)c8fAa`X51lKBT935XJ5O$(Pr%Yem%f62CM2| z@+*FKoxddFnBY~Vbw*!3@C03QOljxW`t&mkZa>?!YqB`vczIVO2pXN$Q6Jj;B;D(i zDAVMXGfj5)0JFXM5)Z*K!SDG+ZT0yNwbo5)-I%G{wx4<6sk33px;SEn98(Z%eD`Gi z?D+cn#-plcF4@+{oc{YD)AfNx5y$KAQ*U@Nqt`TOrXMSskl7XWGjr}c+Z@z#v4`N8 z;1h5_JALw~R(k5f`!c7m=wsHj9c+r9SrjotjtPn(y04zxvxdHEY$hYUn0(*TlX1Mf z%Z(HFHr;gPpO4cEXWp4v|5P8-`sl&t=O-6=2#yJNh9qJLjPy^^J4heJ z3^^vOakiYVuV46Sd|dU1GHWjAVOn+{Z%RiFjX2(9H!9y#-?{V*-MD{sUDT*bDE+MT zI?~rNf@4C@(6EE9IlP(v^5;z0pk5DiR@r#-)6$_)3*Ft!I%a|y^z6{6Ys1q_-DfW} z`*)C@y7S@=dcki^^)1~pA;01DI40Ox9yCv1wf2Eb&-!O~=3TX9Urfe!8P{c8l(8LW z6LUxC{^z|B-~8x6j}>$G5uGL!>E|D*t;@FE=pkhMma$OA@CT3XY3|49d9ocjUwXet zcPOf@x88nZ$f0UY>S=zeGuPC4^3RCA_m0=M-1}5m`i{ylci#7F+M};2-+X~tvh`Tx zKZ4GjqhH%%u9p0`-sykchHY+uC9;&`jzmZskr4``3iG?&$pC2{S+;tUpT&l_5(itPq&_7q~6LuU@ z)k}l9`-s!-IYEy(WMe$(_qwWmi;-r)izTM?v9GhtirM1y^`$}ad5=t071s3*nF*hB z$_csbtjZ}lMuRy==?1Us@RgQrl$>kJE}fihPr)wQ=Ef!FfZ&^~&+5BNkI{{`tccfD zEb>?}f@8u?(cokCqMql+tLk>~(hyq@*+&$656)i@R6DSSuJ=hfwSWJHic@Fqei{R= zz9+6&d6>E`_hiVS7|kUT1P46OM$i6bO}r~O&Z`g3htI0~ho|YeSF8(HX3BZ27~$8) z_8txN_zmq|WpLptq>HdgQw|humB8XyEtleaBAH z{RiFrh3AqoxKr-fr1W!}iiOnk)WPtMc}&KVw;pK@R+kEzUr8Nwjtjp`3E!Pu^l&Am$cQvv90x* zcOLd;OB^rHIN-n*FLPaWB41JBi%APnK6P?uef2kMI`fK-(Y%_(&fT7ty3V$C`mF`)yfr5?;q@-mfhRZ9!!OC`N6XL7 za9qrUSH-YZDsG@Z{-CQq{P$xry!vG{ue?!%C!M7CKexT!-0y2|ea=jHZvc0f=GE1e zhM$5}%iS4{i<$5a0_@199ju$JKT~%c*CxX|1&rohiXdn_x|!}iXKd&d>+lS~cXjn2C>QedDKbZqxbt!>b<5@U9A@dDjT*!E9~a{DUHW(53$V zmCV3p&MUKU-pj%mRq>7Z`-?~Ds#DGlIWA`6BkmdXK&I`%^K@oSzs|h(#(Rsr`vtvJ zU0rWDpo5-MW2?7w$E!0`9REUZegBLD6{o>y z-sOfTgx?3K$KI}}pICZu$UEk|^Un;$wgS7URm*k$>9=`$`LgHDqN0mUg(vRJ%JaOL z=a{R%yED7z_*>KGJfg$VEp+h%MHX@1fs;+G%}-iHf^N6*<}@bkGngAUbZIqDzq9L( zjKrJRP_vD&Z%-|$%osaQ_d9!086)I5N$>9I*Qd`xa7Xsh(wp9!sTY5BUd(Se4UQ=Y zw(J{NS~~eOecHgImApyL&-vtsPlWP0|MZ@2y6oY49)jcbZMHwSx=PvbCL{Gj2fiKh z8$KE3v~kh^RvW>p6IgL5K3DY-^?n^#`oxsebh&em_D)~J%^jSzx+1)%ca+uI}aFablD!P?z)fbu%X)dm&W^! zoZ%t3g)WcnCgeVsySf&R_jmd^fzeGG9I!V{{(zMWu4_iXY}E z<}2ugJI9nq99HWnJ#~C9?|hKc_$y-NsWWxk!$*bOs=59Jk$eUDG}_~fx*A^;e>vQa z1(CG;JVL(OpYhf5*U4x>B;R8mk-Oxc_=2w{X?b(UTm4MSWp~@JcH-32%?Tf_%HI9v zN|QY25&x}uSXkO^jzuKB0i!ReaeEq*kKi}VP|!(CdBkOo6{pT27$qF1QcN)^2{kNuC*v`PJ$R z8=yYaK`5(`ZmtT?+|79SFZ487*K^!4*hH%amt=a zdd7%*V$);c27bfbIZv>^YBpI<-EWPxnq(%0=d`3FVH*T4jqqKh;o`DyTpD-|f&yCp z<7c_-Y-(ejhfJpN7qojVYfG=|$zM<+$8e8wIZ} zSj%lp5NQvWlTg@gN}0&>{>#>_WweK|eIj}T8}FafOJcIDa!AM82>WT=L+Rz8?>l?7 z?L}=m4pDfMpc7VJ8a5%xkLwd%K5Q@Q<*85~fCw`n?vYW(g<@8P5^>SnzXVZuBk3_Z zc}@{74Mr4dli3O)tq+tgGw~T>yo!>t@)60K1TCSG=OpKhc;3wVPEL20M8f37BRWML zH(zC+8}8~B9sApKyz^N-Z;B4=WyYMhpA7}HNzh459s=#kPXp*EK_@YJ2;|%%(s+|l z^8a9E{@<)Pjnl{Vj_z3TlkKnkoF{R)oSP))NuK`7Dp`LBBAFq{Gtc2{8aZHX&XZD< zP|WIY%gW|F=|u&>{T1?I{yra=6-P3o7X;>?5v}whSttHA9~_F&$X_J($$v#8Ido~H ztI4E9{)$NWx}2viCduDl5lQMc=T)Xea)+1m^jAbO+jasOxtnN^aygi2b5JXb!j zfAq~c-~LU`xegG@NGON?|ELel;Uk*EM>2>1Yd%oAwx%Rrw5v!~^zxk4&0i6`65@42 z(klP&2+mV7*G>^Rd2%_lUyeL;xh3CYijW73NcuiOUqNxbr$)PIV|$&P$V2j- zgViuwKFMrZ5DDAAMW96U2u?34bq|q~xRO@QOyoIX=pihtp=ySgjH#c6O% zk`HE8KnV9FUU^Q+Eswz3Ii|I<{qEdK*gm^8uKj}Z2&{xdTA$lD9Eus{5m?b%1ixV> z@|?7Mi^wIcI9?7V&&hWKo7B-2^@c73b>(MPcDj9XWAjI!b!b=6)Ev>+m`I*CXYXG& z(wwDkw$DMZ_1r`B@Zx^DYRhV6{ASC@%gnmk;!78OL%)De{>5--L^wt+^mvI^#iqSYL0;{!P)f}w&4YT5yP;%oJh7W#wiN0?6 zi>2Qm)js>eZTZxHD6JKJ(egpdWcx4sM_o^N)H1{u-7gnzeR;Zm@!<1I`OQtuF3KLc zRZ4ermSe(6+|-Z5VOuZM!&l7f%<&#{V6ABR+y^XzW5Uk%4;56OUITTuRsAwX{90jJ z^jJsnQ~~DYdPE0>cQ{t14;-TwkLsyAwOG)ZL)ED=H5z>LwKkNGcq3@5@T-3;8C1#$ zRvl&)-yrC6XG?Woe^_lTuTaWw27Nw1`s#^AHVuv`2r}KfsiI@+>wa4rmmc@c?NQaN zs7K&jeea6smzo1D0^T;FM2{y3R=hS;)tUZtd`H_OIy2(!a#VMt%Fg`>f>Y z=;aSad*3_E<_UH(?Wd|A!e#NaJ8tdFq52*FMAY`gcYxTO^%2iLG*_M5a%)+yH&1Sa zm2h-tt8>;#yz*S(rfpbhZO)!`%=+l=Uzb`m?5Ug0QMr!~jc*@Oxs2a%dVWj}5ekCe zIE0<+xR~%Pezq$kAO8!Ng_I8)%H_j`@(~+QgAZQvbGWKdgOTLI)gYeJoZIKLbi>C` zx~@#@8)oH7-Nux!^Q!kYQBvpp#?_h)|MPYrtU|x-6E@}}x_u&&7=+VE~TW@>g zaBWr|QOa*P4Ne<(0nRyD*EzU>{`{H)$~ay=E8>`7{kb)xyFJrPubI+adWO_j6rYST z8mGwR+iLmkx#o}!oCfR9aZI>Bh|(Q?L{>K}l&;OWD_uNq&dR7MsC-YIq|pg!@EcBp z(++|c-plB_9&e_vnbonB`En?ql}kfWJ|d|>(PosMjab=doC)XCP*)%g7ngnG(y(Zk zw%rNIm+r~WG*kaV>GB&_x)#kbrKPKyA?N&tS#f%4D^c&DmGH`hR}-$z-JZ-<$DgIA zcde#&9e?0@M({d;R{)s%ptYa((ZT9xw03^OX>d$wYgY@=+BtRR?jx$9?bbcGf!c+( z%LpzvMyKscHA1^`t;Cinf3-fs2KA2zS=hUhVMrR%e zd35G6F`d2Ixew11c<$rR8DxI-Bj#7rF;C>V56`c79t8Wu{5;W~tNAmp!aR}Zc0o`n zKZmn(QJyFAT-2X4x;b3@0OoK!OXXR(%ZICTH4@M?=!lWwGTtlW66WjyCqBZp#iI&$g?XuG`n<@LF1yDkkk4(em^Me+Ka zdusPZIfQ&8u=i17ogljd$^I^Xwfr?pcxzKsD%J^tSmbsfITZIRc?9e-Lb1yb1n<@+ zyLHZ9!|iwt-2QRtQCBZ1JG%S4#FE3lx$cD}W>T-=(S@)`;h2J;>&YE91UFt9zIFHv z#i5){NhDr8e8l|9C2dBo{Vd!Gixdv!Y)T^W_2DD7!`^2^lacCv*!%DsXUP+hS4X=8 z4ZpQb2bDIRahht)f(SgxWaA`cK^dKNk`xD|r_=9+4%EYJx z{6R38GhP&OBQ2n+ouF z@x_=4Q87GTaQ?6ZihQ&Jt7E{5Loq8K;ViaP2`skc4eViTnefQTZ7iRUxa&-{?3_`y zbQ6TLtg&c)(6y%PrYTXE?_Nee?(TKthKeocshLCX%=`sARWJo|7*vpN4$3 zVx`C59fy+VBv06lf`4E5`HjWLulVrBtWHuSe9FEcO6$bylgQorvi;rKY_8pCE@luxaBwE7o+8bTf z;sxYG{QGXd{DoM2{BkH!1BPGOsOeo>vOYrm`@+v}srdMH8sw4q_~krtOz`Rm|Gx0^ z8;Xx#r*j^Ok6+FcqoK_K|GsVZdomOszx;;N7@eEf3iTndba&wlv# z9X_m*79YQyL#LY&iS{z1gFyWI!q0CgK7P5}nIY#X2*kfH{QPznAHUp|m?5JvBZGh6 z36DJ-;a z&~P7e)a7NO&?&U*A+w=G#8AsX(`axc50#7~3kgJZ%N1r7HNglM=!%e}1Ci*uA{xI-^G zdSUtIETcuk9U8_i4bgCimU}EZ?oOG|zH$14mLbOkooZ;fAOH4YT6ElZ92cj-G2xaeG~A)(9#2|&k(YBub1wm({m^iSmV3PS+lh+b@E66U zfIHRDaIaCjq81%@j+eP}Oz`Lc4foZb-x%*5Kh|T#Uof{y>@GvY{m^x%#Qj!XqWBHh zpwCJ)+!tT7e>`vSRIimVg1<+Mi`U;0*1dEj_RLYrX$ILE ztT-Q>Khy^_+@a+jSC}x?8$Y-{{L&Q-cWAk5(Q)T`=KA+rqG-57%RLqy zcMc^Q?ohP0-wJ;>L0~o9x3`Q%$DO}5MsQ4MyU=i-e&jP{3*Mfi_d*@ZXI}P96!)6@tSRCOI(9ov+!Bd_r1*avnqyXcE2?7%x&jB&Y!wP z5Bv93rcsD7K2 zPdz@KR&I>qxR?pI9-MRjE8I}EWBu@zr!Q3;7o+|0<3Br_hfmimEnU~{Qg2k_(STz@ zOFZ+L_?y`~!d|cSRbMVxWVSs$KYHxMEm;o5;|e^bU%5JNG0udQKRM4Ead>p*nBX1% zmz8nHM>mHfFF#K)6ONbDgSY8!r-z%b8PK`f=2_ks#ku8Dz^bUlGjYoYcZ7pp?(3Bm zGjV?JZ9Ty^ZiPLar>{RF+lv5{x0oQ<^=d8M zct9n!VcAiMzJdLUmS3>Vgv0 z1zxN13fuV_jq*ATzg9a`e^}{%;b|`)pZI%?#A^VrAbDj8RT8L2Ed1n;ur|~q_zkD$ ze3;spQuPSc6zUP2I)`F3ZnFMdL$_~NPPMI?Dpc6GIOohT2o5{9p1$pi8fx*K<-NAc zEzw7;nc824xt^KwT@O;ChzD)ENL2B3SZuyMY<6_r@2@1@bfdgShig9kDxCJp72#zK z1}5HgBk}0qyy@CdjD|<+GiJu`kN+jS|FN^Y(sdqNEqcLw2He)9qdI-n8S%rr8!HaQdGZnGzJFzSWJ&d~tjScx zsWaMdyVu-&d%XOv_rjlM;S`HnAEW*6qv6B%$Cvln6}DK=-|I!Wy>d+Ob^d7M@U3Gn z2pj)*nwN8qm(zoK-O|HV_NyIbs~erJIEUP~`}x>+{*rij&p-{?+}F!FGvQVl1jRQz z9$wSrk#Ns-L%h;uCS05Fg>=+N^;@g$WhZ{~YT|#_whZTg7vKD=S*{y+bf~c?go1Xd zsAoI1y+~9;omQXiC3v=s)(+)tC}@|8dN#k|v5#XyUjhZC-y1#{ih8zF!b7|-Wt~=^ zeRiI?Ekm3GLZt}`+M%dtJGDK_isNN8&d;F)b?ez>8POSaihhe-eRGh}oSh;sI`#pi{h=;;*w zEGuTnXzVjUN$`m4s;Lb#=Z8)S&$42M&JVp~CCb@Q&<;gC+o|nYR!$GlJ~JBUoX{WK z@698^C&0=n`dL=YkkRlt0M*6Qn~n`dJ=-baSys%@`5AGnL^&G@+M%dtJGDK_gc&j# z=U-5dta^TqRoN{oX2|Fu5asN(6Ze*hdbU%-v#gk*(@JryL^&G@+GV1i?bP-xD`v>( zy#C;*F8h~>dbU&av#gxvpnYaEZhAw_^VB_`#iE|=l<+JoX6QWWI98&Z4F&DECRjPO zJ#>ejJ=-baSys%@sogkMqMQu{Z7u5A zPHoS!Vup-{#yS*SFZry8RnK;cewGz8WHj`=pb}ee{l!|;vz@-LWyK7ghbG5Ll(V6r ztwlZC>GN4u%#hLW&j7XC$M?>*+Oj)3j5Zi)EGuTn=pYc~Y$#}JQO_1dW+>>|G&ntG zi{1yy*(YDWFqTp6^X-=ysPx)2I6X$Al|VWBtKUY&qMprZ@V<|~b{6GqC}?X@&t?R# z$r+t$FKf|WX1-2?$(E?|P3B5hl(V6rtwlYX--vQHG=&lBr7Xt;@83|)hJv;h^=u9$ z%Gpr4!ucR(tWeH|o>Y`q&lcruC}?X@&*pqET9mV)Miu4Nvqd=@3ffxKv-u6@oMXZa z8Oqs%Zd_6(>e)P-;2jp84dRP}ayAsSV^PoMP&`lc5u%(81?@6X&*nJ}&)axD7X+f5 z4F&BoQO{-s$IIwc|Gcx*AjieCFpdcdt5D8{f_9mxXLGz9ic2I2L^&G@+FI1JxpaBY zl1m!CMWCGB|L_a6sAqHCGMZ}>`G9hEFSHU-&*pZ;t;9!&ayAsSV^PoM?|{E9zs^ND z8w%R7jJ5o&aVSP(Z2;x$Bk-MzdN#LeX2NLf+@UXd!}TTHXK;G_&BLP{`m68IUx|7) z_e-1}qp@FtK5-cOL{ZP?zK_3JMnks`{qC`!_pm)2_pi*5dpl@5p>LmyzFlU>+=nwm zMuQc`j~N(0L_M3w31-M>_(Fnm_8~R@S0=Mp9*dYEj||w^#yB_+-yWxXlcC6b%AV&VCtl2ALuA+<+M}8rD0Qm&_Qy zw@lQtdH%r+84dqenEUJ=k;};JmFGCjkY^n5DGTLnC}@YGp3U24&)U)lF!3-H41frZ>6Z72z!HVa# z%#hJo*FrfP3fgw|%5!IC$TL~^%fP(-f0(z6dN$9`c~;D5j0RB7J_BomGR(qx4ZsW; z4bLr5&VCB(kEc;qyv|^TJnM(8GnBJ8ge{e*XY*Qy88SKuL^-=J)={FK&Fdv*$Y`7b zV6FBL)@q`j&1*7d$SWkMJ7PUp`S`X<)U$cr#|#;by$mR4kHMN#)U$bQ$qX3{`*tX2 zhlh^0WyR}PX2`2a?6+g>3dN%JTFhfQMfhcFckG%|0&*nV~X2@uGLco5>W!Ntf^=uxu znIZ2|V1|Z0nVlErLQ&7=QJ)zy8m%4sKDS}tXEFMAo>?$MMngLj%GpmIv!YDYvw1&> zXHLvk&giG8Mi1W{{tr5F9Iw;nh(saJdFYDr%5t-zkT+`jwD15Z=&*z-hR+LvP6ph1I8<)#0gT^7haY{XrXdH4(d5y!ZXO75p zgvKFP_=!`nAl~G=qRCGqOXP>TqfzBu+oWI6M)K3|W zoz%R}sLeSeI3LM#-s5}6yuzv~fx;@k;WRj=yo&3(>VJf*pyJAJocGp9lwy;SI-iEq zQB;p?+0}*-&Yx){nyk*BX_Qx^b^5hR^lSNz^Tis8el5q8*RMUT#gR(%YdI9N@)1tI z)|M6XO`c`H-A9NH@BCH!$_{}JFVB#ikKagCe3SWHzFj$WVCxHs-z3kH2FDZxPC?Ro zHex2pvy>>OhdYYUEM7h@)L%fenCH08Uvwmj#~t$i(4+h}=#-Q-PM~xACV3WC91~__ zd6i1*3yHZW&yrhC4>9ERowevYJ1^gnC_?i}k5@0yaLemj3afybB+ul_-NuxvPHRz} z=C~4sO&BIeK-YTwdu=6kMZ}+t=(@| zPKVdFMD9QMdrY1sy;LLDBDf!1pI1AIq&|}8Ji@8C+IGcbD)*?#a~@F}emUzeK0zH0 zznpC4?fh~^qi{`znl|Z=&i&rr}MuVi5{f$%V|S7f1OcYN#KpVUrzNe_~lGe zmwIM~&R=IV89I@;sRuQvQ>qoI_n`*mypTqsAH``nm8dAMAN79T>!}j2ryPp&;UoU| zs7iRt4`Wn?1J{Slm(iRybQ<9GboFDAS_`kITpye#jw$aUcKrbz)O>h|b)H}&(Y|sX zVk7cf8|C$*N^8ARc4u&jTKVhci7(bj6uFp*^A_t67r;Yot*geX2jL+$X${gcn4$CP zYGcBUDyTtSJgG?C2Q?_?4>xKE{V0ytsYFG2{V3;uR~-!hyBv!1;UgN2x*@(`+$6PS zX4AyeZ6vB4jOMgq{h9Z_tImM`UH(2ePtIqqjVTBgLk;S^+8xx1P=n&QoZsR|)S#S7 zRFv0`Iv(DQ``7KD&V+YkMmX=rktk;|8vaC}Q8mA$gE|`;RUDV|ZXAhj3daQN&m+Ex zkG*%eTG6#E<2(;XqWZ<57>!dI_(Pt%>3p>V{*W2r{2@ojLSrWB8S-Q8-5ce{zSY4xi+GCU;i*f4!zNGjTr2BT=&AQ3C#b;lF*;#x`mh{I@d` z=f6E7rKTvaA9Zc7)_TsQcIvrTk4rqI+jyCY^X2Xk&VRdVaM$QW2g@Ry|Mp0fta!Z2 z`?|k!SR3^-eBC>r_L1mEInVWx=sfvp9N(v%{^Wwz>TPILal9Og(NG40ulo*FTdBL@ z>)!dak3Uv*j=Iy)C#i}nyCxp^ zZ5kYk(U@8G>Z0fV+E~3_?V(Q2|9>PpSUk&QhC#3r8VY~ZX|0N(q2ROiU^VD zJo#x1*pbog55jHPUXv2F0-FYhVl+HDKttj1Wwq237dG19v=SoG!Q%NYGsHYGuQ#Dy zhu(zKm9Ra7Q;)Fym7hlcuHE$951_@;{q98B!KT5X7>zy=dK1s}_%WP#-@x@wSHkvD z$!tmbC}xN|CQyUA;B;82_=A2E6L z8M@{1)m4ohRYPXQXigh96rkp@=$zr<^2rC5I@OLyl(TrI$9ckyTqvJBr|PN;p?tz| zIpvc`bg-NvN|e`+DuUwFzaOcsN})K#Z=CXp9m6>$+|{2xLSJ3>df5Mlb3K4SH|hbM4}(%RAM60dGgb^sC2Ae-hOnr zvUEkF;9}$AP>jZ|8gykUm)4ByLsur5dCRB}+t>N7>hC0KH#T(+#b~UGpxQHZ zz>atuRC{>Uz}%hwkDKrA4~3)YzpM#Ag~E|jGKxe$%IOtFqV43TF+J#`Kl)eS_>k5I zDvpaoF&fH?P&gX1p}jsC3P&Ai-N$IBd=%w%utW`NNze1cJD>)|tehH@wV-s`PS)}; zuLf2BlX6C6~7GS zERL7UhuPw^56W3hwyX$6Ig8&gf=dK?sd<$#{WDa?I1OgPr4EIPV^4?b+r9B22mcXr zyo~0$fz3o-Wh@*Il`*bor!r<&UOua#&~Uq_dPDslG~75YX2LBLcT8>>t1sDHDc;%o zsgToPG`Hg*IN^p+_q=U;xDtwN{6#Sd!LH$gWes-#Z377$6d1Km*~E4 zyp}otr1^=mob7QK&Amhr^nl*oQ=6-+CeXX%9>?k3*>x265-44$2~J)6Kv@=Qf*cn! z;l2_(sZ%ED$@+$H>I;p%G#Jf2DlBXA+JI^sv;nzqXI9J>XY|l&ylUa6VHR4AJhJe3 z<)=~f8g+}U)(@yZx;82W)7Y}HF_8iqp&4C6e&%$_?$qcb}&g-Qr zb98BEo)7X&)=y*f?oRrWbuCo;E06Nh;82W4-wwUhVGp%d?V*>-Ggh9FGeh`igtqLb zC%00EeUmCR+5J|Yk^5;hpU_VK+`F}^_v~?A8XStzxFHR-DXd!5dC->S**&jVm?7?Y zL5KIQJ?+(pTZ2SD%Ch2>5U-FhXBgXB-*aj^wFeqioCY)T5m!K&>t@qNeL6N(=d!CG zUKR2BDhNJ;W^tGPp}MEp14Yb)SB<=egO{7fPtu2P@1TzAl1Wsp?7EMc_=w8TES`2~ zTQwP)#mt0Pkh~U!9RT#5OB$V_DnZ|wneYmm*Sqj|QqoK}7@kqr?wgUQTG=%+Gw~5c z(09IOVO#ag*^hY$UTyQb9X%Yhu&1sVrk;ZqHZ$Sf2;NP=Wv5%}>LboPMFq?6OjNDx zegZS`5gBMQsY+D_VyDwUfyAYZS8(z z<9U0>sv%pJd3$|~@b?oBf3>o{txu>jonG`1yl2U~pF!|Rr4Pckn}@2}JBNCEuN*J$ zU%~=nNV&4NZy%}dYxHKw@iM~Sd;RRmpW_(=+o-A2$}8UaWhNXGtkt)*SBF+_pj5fy zL_f;zM{~Tq*Nbz`$Jd2lzu8Mo?)it858ln@J#tvkoxdi&ZEYL1@Pt$c%dS#56z{{s zcj%0vszJ>i;g%UAL*6mx^V+o~#irDZj6P{8yXPOCyCr=2z|QK5;sX^k;ZXhSm6#`f z8yQtmqLF)9&&%WYKT~RBn`68^eGbLGI)dPb`$nim2X6>#)Vv|&c$pQSE(bxAmT!l* z4y~i^+S5dFyo_G;6jXcP92+gDD1KOGJzTyls@O=?cqmfr9fZ;E{#I<(bs86KsPZWg zP2*fRzFZBp<;3oa->?@KjtL$eHceH*=3F@Xnj^zIwiTQ2c8-s_ZTK+DO#FOITGvI@ zT(+Ou+7x#>DRoA0Ot2Ptd1dC;A$`<}jWyNF%}UJoqb5ZC?)WHMf&9rZL+mqLFju*Cdy{lsW$lMk}&vxXT4!I#x0ss;;h3Y$FFC1m@8m-ZB!>Mu=R#ICUE2QAh8k5pG2YWMOIbKJT~(Lt@=&-!UB zZ*g2a?C|Pp#`-?$Q}Rv3p%@(mk8HX;K4@)wwd(1Hir?^EOO6TW9}CN?e$Q1_HBM=& zI9}$?Y=dCu0~6JweW!-A>&y%}6xR)x2Pl!L9+eM9QQr}C1nQ*DYAHa3{tFfJ1 zspoqHiql|*TsPQ(+%#F$xiJ?unt4jd^~~*<8A9{E!xNb?2W8aq+RZ%gN!*V8G=|)F zl)AE06ZOrjySy|w6r*w0ym_ixy>V_>yJ8*hJ7*goW{4Hbm7j+@hBQ;}?L6G`0>$6F zpT-6F2E#cAt9jc#_R`=`jD{+E=~VUDo?KY9&QT%vGR%s?XTf&%g*uo zMDCrre++_qo{ZEJ4{Qpnepp^{AH__3#JKaOsfYTG4yO)l;jv;g_u61}>f*TGPl1}d zq_5}GiAORX;eue(4bO(7e>_aRyP&-{8gM8cyU@4K9;%kN-WY!U?JeGj!=ZS5#0qlc zoOoHi>Z<+wJ-qw1e9QR7g(YV1y;GwpcfO6jWY=?h!)qkyP>1g-HgB|? z3XPVxfGBD`RXsXOXQr3CK4gn6w(;T{z!(k2T@jaEcevX6dspwiGxrSKV+28)=ROY~ z>|Q}tTiQV}6AtC~3~hT)R!=?DF06mwBCk(mhJHRC(c{%8ZK7~qtJ^|;!}0okiJtv^ z_(SIk>YG_@yk3;i%r*#q`f67E&S^)e?|jqZEZ%tH3-tl^7cHhPCNn?esYTK@%hHU#XZNF9yKoe8wB57xN-DMb8C>Zq5c`c{xbLm@LB6} zX2tcF6w=7$ndQ`tqlcIqM^ChG*xuZ?i06E84mszXzcf73$tmW`Ip_SP2s{X@LT=gb z2j|Zs5WoE7yqm>rvnw%u^ZKyA$vN8_vqiM9z47581%ypN(qL%Zkg;M{t?&H^`;n zBe=zJd;RB}bNk^u{cS#SQdZ20x&P&ha@2B)<7I~bT)NDi>;IqYoLe~O$?tvsbJ0H28I%4L$4KmZe-DjPBX?GS?pqq9+(lc&(+)Ifp7dBaDZ*7Od`G+&~Lj zQcuQ=Kc|-;4J6c$$ob%7F0}~BVKNpmy6`NBLs7afJ$9Z&a1AoL@GOW&P=mc{KV&UT z3pKSl%jm-MpAr0~fR_9f#x9=~r_SiYvy9H1bIu{73(tb!(k+xImoz^M!quS7IoA}U z3(tb!b|tLxeIiz5X}`5ta!1;P zE<6jO@RQT8EXU2>Cg)9fJ@y+aG7xFa;c{XJmfTck7vK|QUX#E99o`pn#+Vsl*^D&e(7>4{B2p; zG`NLxC`S8f2qI}eTt5GtbIu{Rb}o@Ljhy71%ZEMUOAC=wNkhAboM!IauKu~KxMgr| znIWf>)0{fz$!7~pE|1G;ZoAxKxE=dx{5iMfo*C3cLU7tXg86bj{7Nm+4`)Q ziTloNyzcuiq~T!c_+j5LL)U}<4TAZ)ap^B;pB3kp>%)DUg*0+`T-ulXC0^Gm{|3Q1 zsAO)pD6|N&j=sIfq2c*to{+CVOCnJ}8mEk#&XTt2Ks!X=U-Y#Q7$_*>y}^AVgnYk@FZAK}+jL6MIc zrih&6oJ*0J{Bv1xZ^=E*Klh1l?rcjJEyEy9`;0m_h^^2Pg_>oBuhSrI`$qnjf6GfZ zr!F86T7Gg`;*t2|UlPBhBhP}soVtLJ|HMyDb6m`j)6R#L;DTT#oE~y6tJJ?qgPBMg zm?8f^Sh4PkTZLH!qf=HwOh&adbv{QslgWs@nl3T0&P0qR8nIV^( zp9aV4)`m9Te@=tjl3UTG2+aB&tNC}n+^E6xUqhiX2PK+kp$J^h{IRlR?Zl_rE9zMNv@jqE`&XfOHTv z?>Xc^Ks3omZxJlPfLsEIC?OO-R0I+%fHdj7NKp_G@AsZfjwrndgbRuh3m_;qP$?q+ zT65-1)-mCE{yb0Mz}_>n%j`1q&YJz|iB~?h)00>JXREa5IwB!sloUE9swFy4DgDo% z&s*yoUpUozu02#4IwB?m{P|}zv#o41|4YZ}`Re9o^3_)?<}}bA>iFo0kX!d>H0$_i z+f^&O+WfcOOJdK^m8vVaPoX{6TB;X9d?_zvgPoySY-vmdS*R?Fvn5o*Ns z-Tc=}C)|4D#iUT_J_?|CX>Dz-N*V3-!)G((b)Jwuh3|b<%lE`+)#Cj=+FKn3?O$Jp zpQ$cmp}$N=p-F>UyX%_}XLTr-8}PvC->>X@u{}2m-}SAQ?-Gkp14Z|{H(vIK_uW2@GIR~<4EB5e zr_GwRCNA-o%SfT^^*yRe_kYFqE6yhS7yZD;Xx6rCpR~1o3ia=)-%tD0r_lY?_uYxC z;rp?D_bL2jvGLJbN)3PX-W#kv_RRJ^g9~R(bxB90FGJg_z19BpDO9@h)zd^LIef_c@f8#55_fh>(y;6D6DwClnz1M13!&__L zL4l9(k=Z=~t*WF|@-Dj5jFLhep5P;GE$P0$ebyVH zTaVp;e6i_6UoZ-vbE~D)-FHjTwraGaU`ra7c&m(B&vx$xen-XEsFrl{lsZ~fcddeS z`oE2@%ILmZ3iLd8Jx34u+eFuopzb&=N}(kkHEVU>Z67dJ(JGa$)ZKU2YyP_(tHt%4 zr8)}z`2a7o0oW3))qRt?Kj%8PO5J_86dUb4E`NRUHa3H*uiZE0`RQXb3rzJJHXA&j z?HAb5u7te0Z&GykYkmV8zVv1#|Dw`pS3-*Jo3%Qdv!x(^${|HpLW=I2wK{vSrC=Y} z7uM=Z^qaMGL{d@;E$P0Mn%^l&t3rmhgmtPDfZkkRdpkJjo&x~0$= z>`Ex3`(~|fHd_j=4XzRXm+qEctK$FfzR3v@bl4TB@hs6@RH?h~mZH;ip_s=Kr|xz; z*@J~*l(o8ju#>0My;j+;`Yzqp`G3mb8fhuK=Zk2&Qg`2rQfNsxqO8?@v#&8$)~c>0 ztfkc5cS|8XUz`ny@n1OVZL4%XoEPFLV|4Ml>ca0Of$M~ z%INNlZL55JFppQaK8!+Zx#nAIV||z=b|s|lzRA}$-zj{37)4h?itd{fuK7;k>%%Cz z5>j;Eq|gybNhn6Or2AHCe#f5Jlc6nPovwxa?)SVa(cZF7HwyfY-N#0^DFZ`geZ*sCTisztFV4cNXM5(*)mZFt3 z+EL8I8nKz;D&;rJ`!^Y-(2`Cb`F7OND&Azee(>ZpzFjSH?7mwHzbzSsj)|X^M%{fc zN}(kkHEVU>Z4dl@wMfsEy8CV^+JClVwYZ+MTt}flAK=CNPB*$XH*8f$(Q^0OQrGjC zTcz&4TMDd?61#&@U`<3sO7~3}SX~xH(vB5Y?GU?zQFJBb)qS%TR)NK9v=q26Wd3EX zu0+3C3z~278Z8C+Qx0o&CHl=;(0q&0XernS_Jy^&68&bazP2lcmUQ1r&2L+^U8_br z8QK!o(bn3|(Di(@DlQMkl(R0^!lN_WgQ)n{^)ikr0Bj$(Ty~}?ashG zG2^q_uWU@TRyUhQApfx6gd6slGPpxfJNP|rx3!xmHaye5g#hcF>x^2*T0i{!1``ka z@YVKR@3YpGpSk*)#ZYv6Eh$E(eYD#A?vtz*WK@fn0SdONaf${M_U)~*?`YL1SC+Q@ zuXm;9PanCklkpn;Pzv;EUe~9$zvpu9l91QJ_WqW37tw9IdLl zRw;E`xBcg6)-gc~gIdS1PtnaS$I2yi&TK|6kz3X6oEQUfySLZ`Vy5A4qqbkn1@8|Z-)x^H={|Ch=N7v7ZIFZ>h z*5Zntarkd9?@@p>;*hPqT(MZW_U$t4yD!6gYtpeM=5;%R>OxSM3?D_K@Nu*6*PcNg zcb!3<*}e>&18P6;*6!>GmpIdw@N0DosE#voM=VK8Hog3~c z?Bk;I;k9hmII`>uYrXaib|<~G%KGFojM_S2onSw7Zk4(_6Qfn5EnR=r>YS@CgbaMd z`C%;q1fH1xbQE;kXz`Llf}KnN-$Op#>&23-eM@UAG$uYPyJTud~9|0l=(-BeRB`) zQ=l&q>0~87ANK8|Yir(Gh1&dMdm?qzYWZy1x9UP$xBaKBsF*38bJc}Dg|D23ql*!3 zpo#Xan%}4J-N#zuv(~lBygTI7r*IioYmE!0G|!H2wOvQLPoZo3u3INJQ{L9@SIQ|U zMmbhGx2}CAPjw+E@G+WuGxfmM&5vj8Z4^4QeG1<*td`E8&P|^}R}oJeo*^8c*IrRd z;oqhiyuW?tcUNEenxosW1nZ;0`mk@E&1lsqd+z#bwXi-KtPlIf7&cfR_8k=XFbev@ ztOT=GVSU&))<=c)u^5WZYGkW?4y+bNy~6rf42A9t+z;7)QtK|!Z>eXVk#QLFH zvefh`)v{Z(Yg;v@FGF_#)fip#uT9~jTiM+F=gu(N(#5K^dDb~!tX_c%F~Xt^s#mH# z{Z?`I*k-nbv&Xf^Z_Xb3$nQP{b~lTTW{FaB_Bawjffn&k?9^6*`KYkY?OQdbt=s-{ zH0zmx*{rb6jl$<+F)~y~eV(nB>U3X5Pvaigy23g)3f0g)g=!*C8?Gw$R<*KE!Ly?q zU7j|acT(`QVT)s|oGg$p6-#*9aE$oP(}t^RQ406(Sc%KCZ=N>nV^EB?LM)Peq0hVR zxz+L!Sx6DB(lw!H?f>8U@VPO*s`<{|{?*rZ*WE=lzfYleHNX2b?5&@J_T8sY9p!u{ z?C+#do$gbp_NneJqKQssCr<2^7`Fy{iOEo{?90&IQneDA6T9ncQ(#1SlQ9`e9TcNn zgRZ+3d&_f{ec`w2SWw_&H0v48bCx6FquW2v!N0XqRjYNa=ql*TP#xtti}^4as?&W6 z)lnZGqwrO0-+c<7+pbpJ&MsMdYJX}N65jH8`)1Ew$6lMF@zHH~>iFo!j@oaP z>MM6Qo>@M+VVCqNbVpV_);;*ODX1ac?xWOw3cur6OSm?=JrSeM+iUy(g=93VhU+ck z|4-Zf+%>+c$0CBKTKgMa*Q(g5IeVN%j$5C?^~XwFuk73PZ7~$8;krI_-SlOsw)4Kg zk?AV_`p>3=yVsWAU|8aTHXK z`!c*AR?FLN-`*%JKL+9M*z-sCI_bK$O_1(E5Up;sG6uu6u zmX3msbe}@UM@RRy$Er6baz-t7eLz@$efXYeJ$Jpb?|!RP6S-HBial4YG>XxdZZzwS zRjn|!+xjx}Oy$YUvGdWT*Jv@VQr*>&USxEmReHPgdA5G|sxAGTV~?lr;JvUAK%8l zk#A|2kJPuGad~m^Ne7m?8z}V?`;S%!k8ER{Qu<)^uKL_Z_A6If_s&8~l#g>w zR=#qQ%UFJ^iwFChn~S5qa$xBz%48_@p-b;mJ+#^+m$5dow{G@oRqnmiorRVt->;oK zQt>axEv5NuPb-$)|Ds|?$Z&l%8A`qNxRHu~IqE4*0{@L6XF15w66MQ2P-ZLRTi}24 zI@5~xLxyU*QnL?~*~(ZRc^%?hu5>w^NXPI)OIaVzB(c)U53^4^@;DQ-+-QLZ04t4sqI?Q<171P zN{>KGR)v=Af)%B+rqnwBh|`27{uvriZSR!`U)4}VIzijlg|_blO;qhuYSrVEu7IYW z06FVJhL$K_U1=$84*pw1&hn6t8K1@%ryft)6}E zglgZtR+y-okN1Svx}^9<+M%BINPk5s1@BqBr?z*W?|yaP@_@NJ*0-E_PocF`-h%T- zs^5L@#OmB9xbMDc=Dy{5CyvwyoOExYB`a((QeF7IIn_aXuh45D;;$YXD;_)Mn&EPP zKd@98N}>KT#64cPf4Tfy9~vC=y8DVl9vZ2pt~sZ=@b}A1y!fjl)x6nrt6BKo{4Z0h z=k}djeFF0E7TwXe6mLFkgTa>nJh0RfT150bvbTL1>p#6yx$V#HDn`F~Z?XSlQ>t6O zbW%0Ih${6T--i?D=X0y8t>O?3^X}r_SMDvembR)-ar>j!7UMtszT&&TIIvV1 z`b(v@5P9ylTdN$m+FIqC{(fh%>$IuW65l_FS zbp1VrmMDd`7VlzKA*3xmCSVc`2QF!T#k@|9)_=^osZOW>6_q-%`5z6T{-w3$Gro^2@#qT}7(X zK&)@EZ@G81W4-Cp_x09?@>O}jj83?;_{^_H>i@g)z*70@IoMz4^;O%J$8Ps>z0o~) z7FwcbqOM@X)~-ITyy~E}%O%der})BUCsnuYKec)sdiBR6PO9$y{S@0vs8gKX_H#|5fKy|9W7=_L58AHK+Q)<|DqBeCf#52M_=6Eye24D=kqwp)X^% z<@T!Ia^LiF<|+3U|9bj_>SGsAwY@~CAIA>5!-XThm+X1>w0ixsr?Ork*h{oTPcoHXhdF*T?Edo|#@QJ?EZ6M^X9qDgM3x>Vu7LzNNSU zbFOo%dZqGk>)W{=90I+%_4W7lW>6_q-%@(rmTMMs?z*nH|FOOdT}7(Xh!OtYZN+1E z>|DMAEz$L%d{rLa0Db6$;yoXnTg<~=qI~st3SG@9?YZ8XWiHn)@4D;GLQ8ns@YLb$ zURN;gS5sz}*KDK(ADE!E z^v?Lyw?``eZ7IgBxl1{G&x++K-+6F?mMCB4loD&d7gTFq{on+>C$bf!B46c{(uJGs zT8u|uR(|@S33}_h6t>w-%Tz|8)G4vo?ESvzxt6Fr<%BH%o2*x_JL#zMnc4SG`1olD zSKn~HT1#((DSfG0I)Cb&)5`Z;Tu-=l>S(pppSQ7=Xf0jAcmwn^OXq2S->ckX)(aD~ zWEa?GOFcftsFhPn%Z{#Bzj<&}x#A^HPEfvDOIw@LUf@qT%R&ZQ#F`vY@~0er>*E6xSygcM2*ZO6!RggLreqViNj5$BJQ znb0-xcJM;GkNQ4xN>=JYwVB4`=xZjFJ7u&owRLv$j|RCu&x`qO$PPE zCD&;VzUNH80gSyguKwVq*A~x0hL$K_k9&4&;?fzn*R#>{mmuTD$?G(0zvV33Ka~1_ z9hPVw`pbnbW8D+}GW_$&Hx+liZDy$@%GcvaUB*Kzol^oGPFebdVH$O*lzue>SJciC}%>(X>Yo2-s@Mp z(qt(0hT}J!cg2fWyNoSP`tjHux7|`a3>jLYd^J)Y?>m2K=5W2W4k(xWzq^ZS)`s(T z-1Zuiq0~!^U;D}xK7Oss*!83zPj~_{?uQI5QNA8+>irmgY35*W$XEyc`17%AU%AuO z*P0BahP;Uj`?25SCl5}+Sj}(y5hcnO;}#eS;BnU9sQ4tt>P5&vKPE~)f*RvCap8Py zd%|A^OP_L6aeF%-QKEbqiH#^R@5kLMol<-NbADDk9}{Ihf*SK*E!3;EUmjOn4c(m& z-PIE1>+zQ^Uzu8Lhc)<2yFQ{s`KlF`(wtws zR6L6{IKN#Vm8_4TR{ILxC{Uzrw=F*l3N2B45GyS>rSxgEY9rqnRJv04`*9U|J_|j6 z88Wm)`C_HTh@^DGOXG?OzB6cVm0CwVrH3(t-Ky0R<%^XTGmBUFpe297&Tu!hL}yK@ z`+Bt#H1TL?;(^c-Em6Lzp())2ZU4RR461!f-CrNuV@0it74>h(&=TdVD-Hd?s=d>9 z23ZA?$FUz*zmW?MIX-U)}jq z`aE{glQCA@;dED1z8E*zckjba%~gA5J0DS^e02v$KX4j!JA>}d$`|u5=f}x7aXt>+ zJshi6OO&skL@B-N<#F}3(A@{IYW0*+YUr_?gI~wV$yNJsyFQ{s`Ra*^I~-2u?Xd>` z02z8(DqlUdVHKe^&U8D^^%k!8c8wiQiDx;^^n&NP-qn?wdllDYYti#8$C+;Dxt1tj z?zvoTt#^=TInMNg=Q;N(?g+F8l$v`k*JLY$XF1OF0nc+SQNAAWZ*glWaaX{ZUhq8U zp35D9GL)KU2iIgPgJ(I;^a0OvEm6MsrIAP*m%+0fXL`Z&oM#7j1jwkUJOjBSP=-?TET6E)W0$uwc$VW#ALDthCCb<3&1>g_ zXF1OFAPeIm&vKmUcAo1gqtvd)E`zHUXL`Z&TuYR%o~SAD zEaz>X=eeGiO0DNE-b6ZR?M$CL{q69zH}s&<-wt1ULmwZ1yX)To;A^kxbEm&uOO%4~ zuk`A*yC{6^nLc;=+qIU;gRi}z=dk_l4!-tGpF92SS^{5tLq8&ayHifc*Z869YWm#i zZ`Tr~U_>B&rfsX>YtQt#)87tXdqZC({q69zH}r1vw>$XS8+udQ-|paRujzBAzg z{JQj6IIiGxr@viGw1vtEzXJSrQl`(H{&p=<3T-WJuX~Nv^tqeAUE*GK+>{#e49`r@ z^tsdDuA``Y`xNlC*Yvs5->!43dZqG^*Ase0pF92STA~!HZ?LxSx~`_ro&I)}p{q!B z8abWr*g4bZPJg?u59O=!Qi89&rq7-JcIB&nI9<(nh^|~a)8|fqyOyX0p({A08Ec(C z99y+0=S?1;)jnIQ-eBH=Gp;tj=pEnr=Da1Ixyrubr=D?A{l8OoEBD&%Z}pNNSfZJH z(}h-|R*_m^DNTLwxcc+Iomx&<{dHMOl&^Ba8@b<@IQaJiMY+tD&`-)b$$^hH7T|Qg=&V*GdML}3sZXA1Iy*7w%eop&Punz zvpu=#`k}h3Rx!NiYYgiL(ev-2=USqCl~YQ8{MY^U@#y(m(Q~b()Y@7^?>w+v$yR+4 ztTX{Xp;tBa>SpMbt|DDss>dlY z)(0^^nejf1^}#Rr4dZvR2grZ&7Y_;0ChO)%C6F+UdXqa{kgSRX_cxW&R)AH@7* z#`|b3mB&~gMD{f8oq@4Fi22Ek_t6r@`XG*>;hjM_VHZWL4`P05#`|cAQfPEMB7_j@ zgP5Ppcpt|4AXcJbyboi25M9&o&cIk7L~}Iloq@4Fi211*@1rG(GVIG>tPf&-GUI(1 z>w{R5hIa;~W~>ilPn!15z*rx|{A9-aXf173pMtSIi211*@1rslg{v(@#4lof5c886 z@55LhM7uPM_fdOLEj`!bNO&N{sbE%ui;#kB*}9?Ncz;2Qfc2<9&2)Rj*VYVm}b; zgP5PpcpoiM3e`7w)e!50n4g;QJ}N_3k?J&hj#wYW{A9-a==xB;Di4{%5bJ}OAB*=< zz8+;^D^*uB;$9K!gP5PpcpokCUwh4Kper~fo=>jI%JY!t7r#^D zeu#TR!8-#_P40gzQOip$J$Qt1U%_XXS=3f>vCmQrhL+g9P;ka=g&@zH%(M?Ka@%{zn6vyP9BTS~6G zL*5y5o>h1In&^5}@XnyCNLQEYaZ13KWa3PSF;VMIZBE2CG>r0S@1nq$)Wn%E>R#)tHHGyq?ci8CR_ zL`#$};(Z#%O|&wAFR6($Vbnb$?IUlDQX|&AVVrntZ3ADDi8CR_L`#$}Vl*1YX|ytc zFR6($Vbr}NeXSo#jac`F@$Rh*;7c-bCXO+Q66K3NG>lzpWdL7Ne+yCfjxh z8piFnGJr3si8G-LEm6Lhi-r*+tqkBxhQyf=V}eNgK$a>s=At3~pp^l9NkN>+L5PUg z66Fh>Y8W@u$^gD(&_&%V21}`-Qw?zxtqkBx3gS!{5w9i67bjf9IGt7o@FfLtCd8O1 zwo9pTJ~q(hZmd8-oC&pEOK{c(-c>o_wuDv@XF`mLN>^%?2aL%NzdRt$gxanp%2!7O zaeWitRS;)FjEVMEsde1oZ^sN0XF_e)66LEin-cIPHE|}ynCPr2wa$M^z?am-nNZuc zMEL>>5*iBcIkcTP6JktM`;=PsI3?gqYT`^BV-oA5$5+tO=s8v`aVCy2iPfombv@!m zFzgJ(nGj>rD-piBW59yM?n9gjF($ejD7Ee@xB*~?BhG{v6D?7`y7S@I_vn6^I1^$_ zbXQYq-5(LNedgsgaVEr=Xo>RG9XuuAOEPgLTv56^E4A+Pc7BvNKMFrTh|X%bIz2Y7 z;kx4*r0e%e{(P+RDKBQQ-U- z`1ui;JCrZ?D(Z48gZM<8AGMz!QKEdg=Tb{s8N?^z{22QA5qXuAFZW#Paw~)QM4TVl z&yOfkz8>S}GKf#a`BD4%5jh!@FV7C@aw~)QM4TU4Fp5^9e9;GDEnNoji8w!MKR+t2 zBzoeNFZw{NrOO~b5$A`=&=Tc~xgciLWe}f;^P~3jgBeInhEiiLD(Z6E58@MXeq=vC zqD1*Zr-*%Z8N?@YRdGc*Qp;p0U+5IEuP%f5M4TVl&yOfkzG@-irjONx^TRNTj?^+4 z$`?9Jq;5A>puqWIw1#byYL#c_#}Ma7?dM1IL;326*!fZ8 z{K$TO#3(9X9XC5a1~@-zKR;qVl&@p(Y((t*C~$scKR-enl&{XeogW3x57TxnQNE5P zbQ#1a;{3>deuP#lwd%2*9|g{jS}=+>Q$4;dCemdPpNR7#3r5lAL;31@wDY6D`7!kK zBi6a2bB!C|}*d?ffWleiVLw#ICQ@y3d=>vLH^;eU=STNA9z1t_M!heU@?~ zgU_-cPLUWzo)_fDJp*2qpnz8-@<9M=Id{i`I7RnaMlEQlgHSrez| zKFg4yIb^hj=CjPiDZ0{9RuMhp8g;IqucDZ0-xWGDrEi_u#1S=PiUy3aD^0G`4aH>Eb8Wlfx- z`z&MJm2aN{KFc9-ite)v{ZYMAdFHbm5~t`s%V>#Gz_%FsWmtLbak1} zvLH^;eU`C4l&{J&pJhRuA~A}}SM4ZW&E~T#h*NZ*Wvp|xsdNP!x~3+&hPWcNSk$rr z>Za+?JchK$L|PD6q_x!A1_GlY3WNSKLkVSKiyT)JCCXPhr36e-Cbo#UBDD?BiiQ{< z^6kq2nj;g`D1Qma z7vhS5aA`UOkJeJJQA)rRWnzAaE7B5Rewq&Rqnr%$lLhk=UMH;uoKCdXuuCPeMZ^`M zMGdhx98vIZI_#2ajA54w!7had0wd5614L@&1Wnvx_nO!u;)+zSFc%FGHl$E$Lv0m; z+6umEt1Bl%ZI#3p5m%(`Rf>MAfGNtv77;Z_q{ zL|l<-xc0o?4`PH7x0F3@sY2XR<8ezB;+E_;Nbc+0d)u2nF~W#jsy%KgN)TBQ6o`z7 z?4&6XBaFDE+T)g@7BR`4JYs|qx8%P;5+jVbrP||`q6D!R72=lcH%OIdaZ3f_mTHe% z3K>d)n2^Y_idX|+IT5!s^th!8aZ8QIEmeqHvfm&PcTyp4$$x_+Mi_BRLyudE5@sW1 zh9FvDeHp|EBW|hixTOklOZFS2@+C$XaZCOiBr(E>TPi$mDP$12+_kDtL5wismIfZT z6f!h_rnb=HmP*7e6&|-#A#SPhxFzOyvDMAh!MtlUi*1YjI+s5Ez#KwRD2ekuu-VCtHuOkJ^OhcD@S|Y?+0*2HL=1(54gQ# z=eAp3w$2gJ+z_SI#_s}Gl!+B~ToElgn-8T%+;c-LQ+opduBawfnCJm5QND=GjyE(? z0UtqkCbYGQ>QR}>}67ZK+1euE(tGO@yrD{2@sMj6T% zap(=PWvvY0ifUqo9aj`3$`=v;@eV;sz!ha;g&kMaFt&>_lrQ4x8)D>I8Ne0Q#0opE zC`y#CW=1qzQ6^T{aYYSd#wbJi0vFIcyYe+xwlaV#s)-eLTv3!LUzg|jDBy}RvBHik zY6k0Gb0uXcUzg`t0N{#hVuc-7#C}+b^7V0Z8Nd}~Vuc-7#C}Yaei*fno67)tpe9z> zaYdXDD^b2a|5dBIKqzElg&kMK`7jyE*XO@##|pTjnpk1S6;ZFOMESZNyA0rpGO@yr zE23Ui?1%DoJ$4zu71cx!IIf5*$4Zp1dO}hHLLn0??6@MX50jyM``!=WiZZdnjw=f9 zhx%j?=MbC>S5y-#?6{)v!zf>sXSkwFtgz#Xq94i^(GW2rhAXOx6?R+^cNrT+<*Vb? zu3BP+9aj|dp?nby5i@JJqMBG?#}#pxF&WBN=ihKenOI@R6@^|YUqo4ih8nJ@CRW&S zMcidftCeqmeE?UKi4}HSQLGQ;i`b7?X@)DRi4}G{4tJRjj}z3o9t~HNi4}HSQLJ<2 z>+)>JFkDehtgz#X;!PCgtNRM#cd=@T6?R-v>{rUy$IWE`S5y-#Ed7|r)v0`a+~&1w zkgJwhVaFB4zN>tF{%r?0Tv1J|u;Yqi*H^wi|4l0cxS~v~u;Ys2{7}BG$1Vf7qMBG? z;)L~-QNFInE`zI+PO95@ohyMT{`dbkF+{CCb+k`7VPPVV>!p_k-C8OosC1 z&dRZCWe_9GGu`ukM2YfsM83-)Mi^M(%$>pGv`vQc`SI5orelS~)ty(QnzB;p(_hSgGaP4_NLK~D? zwFjA1p^3l>XV3c)nxTAELoM&e5LjW`8C3g}Z-0FdBg`}1^L~VeD_>n{miJ=}SYg{4 zbQLLIU5}RcV*sqMty(QnzPvSeJ4RyOj|spE+s>f7fl}+fk`gh(Jkvez$HZ<2P`=M2YfM?-#rVIGuT>d)|+D z-BJ1KxodejGqJ*+m$M=A&+~FN#3u6h^ZpHhzII}TJufG3`nG4#JKs?NBis;;*zR!j zwG%7sc{!sNeeIn*`r3(jY=1weubo(7&&wGl^tHo}X#RGUmzbBcCRW( z+KCnRyqqCJDd=nOT5EYZ2gC|{Ue1^U9XF-6yqpEG!k(8i#$EaLDd=k_R@n1$hW@Bt zsXWWeIV4ut^KyokCEAm%P0d`FcOBCEjyup<#Y9vBHk| z3GaZ`QtFtGLDOP>IPS(*d#j^hn4e6nuw#Dk3-4rW6)-IgFhBO~)?~%|ykUMavBHk| z3Ezv>Qffo+WMYLK^Amh^6ny?&22etoSYgNfgeO(!*=3ma7`i4CD@>d)P&Dj^m8kA| z3;p&A%ugm(*fBrh5mvs+$uK{eSYgNfupcHv`Klhbts+*~F+br8^Hy1JU51TxtdGJm zKjC%K@zHTJ%nx;U;Fuq3qRqMLZeJ6D`JrCbj`@kzsq0Sl*xm)mzzP@sEHBKQH#jsu2p>sVuTrY=kEf93}oYv7t^(c_AWpMR@iXD#0WFu%-;nFdr&RC zl!y@qR@iXDTB5e0%CmO?YG8#8C#)qzN_V56oa|kI%(y#$7a*)urO?*ey8tz?!iE#p z9_p+qwY>|FffcU(U4R&O<=dwqMwoGT{w_f1kLs1mvv&b9u);%s7a(R(DOBI=U4R-` z;eo#k5HfTX^|hTCVPJ&|e-|Luhw@c<_AWpTtgyx0DPPBY*sZU>&WRBQR=DtY0b-qd z^p@?lx`HE@MfThxVOx5R1KUw~Zt-MmPiJC;ffdf4TZ9=ltVAs@we%tTO@3K<*S@5w@3l3aQ56H zAzk^Z9$Rh^W;`*Ru#S)V;ds00Mm=)xWX~-!kLNghuH&QQ7I|^9=N1XAR^9DuBJZKp zE6*(wt5esV>M`=3BdVWRVSkG*tUHfYv=(}-qJ7(2bOo`({uUk4lD6Zh)d;)^@tl6k zAjXSWVSkG*N|dih8@dc)ynyvG0&hZmt@nc%FJgs>^U@OK>oJ!ugBUMjg^BZWw4}*UYGS(5s@< zoC}U!D}xv>VugwG(h}wC5ymcq7%yUliF|Riq{&cf>J)XLl|hUbvBE^9Xo>RG6AlrL zz<3cW>~GP~GOETuI!olv?NC z-lD6C6{fcLN`$ZDd3~&i@gi2(-=b@{k|;x|Rgdj0x|&#F!3mo-C|_M^_7+_xR#duD~ z2djx#VSkIR;Y#9IDYfp8_7+`1tgydD7yGXARZpS4MOP3j%oU}(v+~t_9{m8O0SJZK z-+T!z(Y?fx3wCNpw7SJ|YAxO295>+=5U=&(QN4-T45TD_1z7Pdr z6k1D9>J~Rae1^aI5`JUHO&B#JLOV`@o9N;!iJLIJ(prv!Flu}Ah4>G{W{?kS+C93( zf7o|_-vus%_>V4Ll=u&m!4c@Fe!{2;~8B{IN*$gC77t2X(hK-MEyK0QR`9hRX?QgyiOJo$< z^L{_J{=uyLk+Tl22mkesfo9o!$BiS+`>#K-x_tQZR%>jFtf$C3`oxdv-<|c7-SgnY z<@3gGePsgu_VBY?MpCWy>0eK2R{Q?()jMG)AmaD_-Sdk_ET5;m^Q8$|;^S6vCsIx+ zedG2b&;RE5yyW!{_b3!4q||sndCq?MrqdrS_WSxO1A5`%HMb10nsM{q2_wx?znEM7 z5PeGN@ma^@_5Oa};Ey}Lcc2+tmHICHhBFbIuKy7!w*2xj`D?$tXRyZ&s}Ho~cTbKq zCm{>%&rwS`rSxu$?h{`>xPJ6wtM+6lg^qMeYc-gU2M?-`8uyNYmgwB{Wz0Ex^L+VU zo0PjxTVlXp-r&EttiWzf*yuiZ&gAB=czf$zHXoNRu}VH^w~_L;OCO$~wcO^YxE}iy zZ#;g#{N1x2Ex!Jv)do7ED(@}FOl{^u_MxUF*I&6`{>ED#Esi{Ym4TM%94IGPsW)$) z4_srD@&gNV(cFyN>DjoC*7ECNgLpeacH)y#b^9Bu4jB_{NLSZ(b$;-zP@O z*S)&yn3iatlv7HRU;20P_zQcN`A0ibMr87YjH;8d0qol6e|WyhL$u-CbBh^Y|6IAk zPj(w~%hYB~YdwZsYrp-$g-&q*D82`Z1()qOb{c#yw>*87mAJpesNIgXZ^V9p;%rdt z{L!7qv_$zTC;S@z-uZ*io_zeEv2@e583l4cG`VROSI=YBGC4^=hhtEy?5T3^D(cR4~%Zp&6->E zK33a;;sQ{tzT?iEbNWlHL~AKEehmi&wdBvY?lz_+(2}OpCFPXTnlJskuAzxn++lhZ zGL%9!KcziD@faxPL3g!8HM}q5f6yvw;&(3Ek$M$*gmrFoL=g4z-uXjn$>jI$#5s?d z(ppN5UuD*qKi~{L4J}d4P>t!&$9B+mj_yIwcGYmzd|hdH9T=tMxR`qW_k&%I}$CHnTV%EnH;`;2mbjPA=*(E;FmGWeu4WAk&`yMxJ6Y9?^n1jl@IxCNozR<%XW!A z#T1P0-XEV{AF%A(2RfoE@7R%%>Sf42#I)qk2OLp8ddl?rlKSlfEzvnpPWa{L)IG}0 zw^=Tqd*Z)%hl}x8;bN9yUjuUq+F1~(;v5USxsoEHrM^d~VwLXSg{Kl<6-nc|Yhl#Vx6Sv*H`0x@t zjA~9Es)>>@_J?LeI5?y=K2it(;PN86!IzBYf18BV$^NqsiX$ zzU#O1jYWK*b;NDCDbEo4XKqAEEcqC8d|k7 z=3Mz|Ep2T|oITDWXHa{t{peG0KAysSd>b>UBdX)0^90WwYCj9Ak6;FM*0h%DTS}aZ zi!dkOAMP-w`lDLXr#J?^J`24+7W1Lnr&_7208x_|*>M=*`!OH7CbX8WP27F3V!3j; zYPnN#h0+@3isj1Xs@1u{O$NKdHrO4m#Ll24I-ANVCECrfpG(@#d=&(igPpasn_;_| z?M%BFmWJETw3}f+m$aQ}H^c5Q+gWS%WzcSh{an&^))Jls-0NvOE2orbH}gcG?W`2q z52Z%rGVEs9&n0bV+Rd<;%y!n-p=me6#`3e4b~EhflD0G7Ux7txxrvmTb~7w7x1DJ> z!+tJlJ8KE;W>~{!J1eJ@Xg9-tE@?Y!iBjlDV?JOv!+tJlJ8Ox~jdDtfb~Ef}vz=)- z!@e}z8PPlOPBm|4ytA~nGwo*B&t^MoE&Ntj@ixP~q)$P+8TNBY+gV3c<^%?mlEw}*v}TkHZI@xrVo^dKQntwYw;%JQf>yMsVJ+b;r zTWKw&PHCkr9xXNo#dG(aF{UNjC*_1VvX}1}eBkn9$|LqYe{3VHgG(gX?dDVz<*z8`F}X zVPARoq>*Z+_q?=~&J#|Y`wy<4oj{Z@g9NnYPom#08Yw**9 z>toULHPH`kul7U7Fr`~xyl1ch=HtNcpWho@)fk;8yr|=PbIBd}g@Z<8!N@?Ko0>cJ&vx`s8f9e1S|iUwHB6t!{yB_5STgs>5Hn8SCS$ z$v+>gx7jh}=a1WAs3nJ7cVe~foh`L;N@?5Q{JJ>u#(m4(7F^SlamxI;)wbtMtu|iz zM?HDC>HlFteL5`F`t-l{=3Hg00NdlcH)3tB_9L|FxVg*ZM;_a=eE<1h7~c22_@%xT=flc;h&jSPkGZ3GR`q4fIDElywb{!Sn@v0_ zD~0k^%}?nUXKhg5aa>W}KXJ`cOH?bB6Yx>nZ!$Riw)=}WANiTAqo}o1$FTb>d0uhr z``%yPvGKa4mZ(-LC&Zqgzd`*4wCexRD&?!K(tQP|!QER7cH8fX;<;1y&03=Jlv7I6 zmpHF@7OlD+ty1aQD%E`G)v+rU*Z=OR!QA_f%vz#rMLDJPr@w7lzV(1j%QvUlL#_4K zQ@>Wd@uiR2{NH)aN!9YVO{p$iom%qOyH_v2^11EH3FkdErX|W(IU!2#_KnMTp0s(n z?7>I%Wb{^-$isd2@n09egSMXxZC4qp?J5tsslK>uzHGZa%PXG#{7^Mc^;mT*r4Q~u zt^O2rcOG92%$dq~f=_rprOxAUZh_8mPR(zEStw-V*6oZ8WaU%#eLU-@b+AN8hf6}`du z?V#rG20rIjLT@mAyfT~i-D(MZqc#1aKF?O7e3cV^qlYHKH(Jv#s(iJUYo)h}zkT30 zkea`LXo>5w$x}|PCgS&rn!inGOSFYLB3QMU4|s)#^a$&S>PYL%roc*o-XN^7bAs!uU-&JpElcTKOq_|`MW)c2-7xw+SmRQuvS`iR{{ zj{(KZ+ospMfkI1^LR*X1pg?iJkEho+EPqC?A4g6dss4zQ|8d;Nl@m}9JK&e4m7f|s zf7FA!_Uqrx4m;gG3UK!j=lfjsnwqFd9Q+7 zv3d&CC!5kcL9x=k3yMu9pFXBOUFCcBV5GVU7RCP7^W_emQ67B9g5vxyoH3>)%2zq1 z^rIU#EBF7%rseYEj~>&OXbWi(@tkU{qQgM(8&JHwVD^}ns3%=HA?_766m2QmQA(k| zAt*IGEa>_F+_j*10sYXnYoD}*$Y_oEI1%&l;bYGq)A7;Xs`jL`6y|*U2d3A1Z+J#e zOLPYN6z_(%ue|4S`IX0x7*icpE$Qpk-(K0JSnEx*%Pl{*)9~&8wNG{2j+5-3pdPQj zkL>HOys13?&pVed9NMRt4o&1=-ZItuh4>OsoCJ#X58G*|B`QN@BR>OblWG%Cuth8- zU-gSACuC?sAAXF!eDHJQL7FYW%a%cGWo5_P&--3#pCN zL~XD3qp$7HZF@|)#PpvHmU(KQAuUGURB3ZAyWL22%Sv;q!(emfG*Z1||GCu>W^+Eg z!7=61AO88^H?QtC)Dl{&yi1c>IUz^<8)ud4A2qW+-k?ID>qs^)EkZW5qJ8Nn+3Dz)e&c2NK*Z$w&A6qY9)LR{ul|uRU_uZ|3wPCs6b(aiBh@GU`ie+}JzX_xQy)}ZQce?HtBl^N-z_jdP2 zHT0Of9o@9CQSR}|^mu8B-t?6dvcurlcEmJf#xpRMftW|eGcc9`_mqb542)&K{ikW; z85qlen1;-F27UKaYiSD+TZ>o*#582aGiZtX_Z$AkqMQ()h+hE^(~ud@pcLA6rA~>l z42WsSjAvjh0}*;endd z)mPO%9ce`4!WKO2qCN5@-=96EEzuVG{h{G+o+;6?gN2uA-Dyj-g|zIjt2V85N6QWt zUZ!=YB}$>PfgXTm2MaILy3-O`cG!m-T6f9`UQSpNu<$aiJ8cy$JDdm&tvgzFI4PRe zx}#+W3op~Uqh*J)u%UIQYadI_fFWPJ_LcX{+f>>3sAlE{7)W3r##^!4YGsaXRO!3&@x8IAT~{_rP$~ z@2_8M`1Wh6A8o(kJl?O=C)4-hO!(xXj)XJE=_ZQ)DUcb;19R=kS{V3QE^)0D4%KK+6 zOliS~jwrABPFcKd$z^M8yVg?bn2!PHLrc{ArJPdw)rEVN?;H1W@zz5(D%4M<{;QRq zKeO8NuWQ@Q8Nb~Ns-EnmOND)}~ym6quKq4L_XTJ^a{>NyxI<*V|v ze?XtL{V2!K4;@jRoBn+G8Z2JG8dP1<5!I1~Mc=NE!Esn0s!O^)`r7WgTT^#+rRoaS zwE}E7qIVG6XK{Uc_UWC$ZEBxEj}WrBJ}uF`OF5VmigJ>h)0gjN4@Lfq3-9j&0#Y)w9l1ON;}Mc za&YDON9WJI@0^|tJxi1mV(u=PS-)wAS@}zEIBlrs2W@j$Ee-8+m6y`Wznorw{K;8) zXs5&c|>2 z?V-+;j&6TGZhY^iWwpU(`I|?K4prk+GgM=6FG2Ji;!-UpRkdB$hesj$uQH5BMOnTfF127xs@C#&NaO2~jxK}osEA9om{j-g8DFjC5ynozcvQrtT1={zxF6Q2l@ns4 z&?>~G7K}+%zFJFL8&SnIXHa{t{peFL9+mUKm{c869Uu2hS__f69`UG%OU)9KYCY6i zstZ8Hw=u$*F{!FQswI62#-k!GH8UnvwNJHDR{?TaU_~J=)nZb0O=vA$Y50Y=**w1v zF>yPeHhWA_ZTKZ7(0TAJ3YH9UYMJqBj8#LNTEn;r#;PHjtzo1EBia=ChWpj6`(?(& zF&<8Fa9T^LTM9-yG15s(5VO`W{)2IA$|)s8wq-`RF}h7_A+oJu^a!Kd6yXRQrX@;&$hL+NDs6NdBHJ<}+!)=aC5UWm7-_@kHbwA3OXknYjBsOgo0cewQaK^_ z&O^KBNr-T}1JP|tp)%l;Yq-C+w(}97$cS+J-xH1)(-Qoy8hBUbgp3a82jkTktESSm zRXQTT6=8H4uf|w4Ezvp9QBMi6iJ38qj8D{gRvlCA!JPq`_*2BIZSadDdl*HnrPO#O z=5-GYXs^*WfSopxw=Y^kil|~d2ybirog2B3?mn;JU6Hn$BC24gRlF;b8g|-5-s$)a z`~0eN3fgP5akNDFDyNiSrwwVZ(N?=@^(WWjEt0%wNlFU?F^2j06p9AZ zJ^}LsTaYqnt7(ajf^xEc)LlQ&-oW!IUX2#&!k)uUt9j?;eOKGAwUpZCW7y4ymY{{v zTjhj%$+(wm+H17c6sf1!KG(Wr^-l$_c-p!}g%PMq7>c zcsI|=SLLMyJFTX@M$1b}blj9vO0d(4jzV=wH3OUkEekuXq@6=sO_6iz3#Wy;u;;XC zX|K^%(-P&YoDky$o0j$(Z8a^?--=Wo-ol1W%dw)ZrhHYN_7AZius7Kc+G;wYIye3K zps$2$khYrYl8&g3w5^XJ*9UDi)g@gYeQl?Yq0?Pmsk(x7t-un#-4IoV&G3j6^Zfen zALggjI|_1n1D64OhG8?bL~k|932(jtIRJb{;du?>6+YrJ5GUMtUV{p;$W7!mD1px~ zYzA=|h-4HbYAsgJ+&?<&>D$paed{uo+6B{ZMMlYfu88QF~s4 zc+n5o`FN3!xD3RlcfT6|mjQgn(DNF^i;hHfAfn&$VH1~u=;bEz8kE3i3_Y(wl;HHK z5J%m3UW4Fdc@0Y7GYZdZ5G6{XBW-yNO5igJ&ub8KK+FttU-LH|qDX+xu#B5{u@JZn z;4`x4HHcR{9Vcp|>oF|$OH)e3WdNU%J+DE$O5!L}yEFDFh|2&zqxQT8F`~qQ054%# z(}~MK+;$Ur4NBlMYR_vBB{~N>Ha6K( zT3&+^_>98y8ic;8_UTC58q6K45t6)|hjACWIQYg&EMo4+~K5|yW%fDNB|ME=4_)9PPcbk-12?+xQ?8Tqc%Di0ZZKYVmv z@2-CgR#^YCq29chwVrYGjGI1ho9~K+cq&pu+?g})hgI(joWG!Y_-O1wOGw&d6lr$YPZ#5-_^YY za}(4p1#Gq2ZM7)DoL8{b8n@Mgli6w|Y_*}=YEcVgRl!zk+*XTy-fXoJwp!t~T9haS zM!kZq)`YEA!d5HXR*MphZUtMdaa%2RC9~B^*lLB_YEhzRMqdVOwGy^k>9$%>s0_V7 zqy$^7gsoP(twyZ2-7NIn)wA7fwGy^k;kH`zLtCXMoY`t6Y_*}=YB5&2Q|sKAtyaQT ztKC)$ZP3#It01(;Y_$@$T6SBF*&$5hw3bpM3lyTY=Do5@y%iz>J(jQGz1`!w>|4Dp zi2iKj6Z4-C73Ps(R!coBeF~2w%Nrx2QA<>Ya)OLD&eABf#AC-yUf(D493s!wdDHBC z5F*b!+RSRHPo__C3nn?+U)>6KG3i#VI^FX-2J!HU>%B+RP7oK$HrgItaw`b-ZaDRKl zQDsZC7ATpU&MDA`%sde8Z*Mp!q|jRE19SHY1%GXDe|wam*A3^I)EJH6Wd8QdJP_`0 zk6IW_X8SX~m<#43bQ$osXXb%m4hYOeLwzD&t)+KgL{ou+c_5erLQC|vteni>o|y;2 z{p}%LYiXa%-=4cH9y%u4k3I$b?KU6oZ;x@;@xdI$Jej{eGY^FO+hcCE7Un2)!Tjx} ziSBO?jZ-b@Q^4O|Fb{34+3e4YLG7kiEK^CYP5((Ezw(_axxpIgpE_WjZ?wKY23zPbiD1Nx_7}!U2|3m8>es^CvHf3 z-yuE~Hje)$3>&9}jZ?Ud6D7E@hCIConT=Dz#wpy!sbJ$YZsP>C$}=0MgpD(F8z=6G z#0bO2Y23yMPG;kjuyKZN<3x$x6Z>}`*f=F@oZ4-ixV;i13>(LO6IOX<mH)BR%>KWBvQSca)T~-w>;oX{A&R0S^_}w9Ml6m}Y zP#|iqAA$0ez#;!GUg*w>B?8-S^RFn zoMaxq8*{5O*q;x?@7Byo=JC6sud2s7(w6(P2L3gB?$3Dh!TtDlM)~g|_HDU8nbk3S z?oZ}uYOWNF)R?B}+a0(!>nKLsJQ~mp5{&+-#S&6<-;kh)uRmATC$D2K?W4vjh ze3cV0KW!e!Ol-K8fMOyd(M+D_hjba9Uo?BR(0BzyYbmv5r(_P(?Aa-Uum2WeGKh5t zR@h|_L(kFm+@Ji-)N1)JSoZCCC!K;gec<)8=l+a0MzoevTkcP0h|Qk+lbK+Rum93y z-=3+`We|r9JaYEjpCLmj^yXx_KMUj?$e#O?xoVBC-jMn-mq-H1jlj6$qti_=u;q0zeJpV>2dmTZ__#NYYC9WnaE;ds^Q;j1ic&< zcHictcZGOo_a`>=rqBba7NpvrxR-!}9zypg249s2F2TuA*qOL$Vye-ihMq^tP&-rQ zr38OsO;3*d6B|L{hQCCqQ-VLSrZ?67iDB`oJa`I&llc=1qJG_<7<{!Byi^UnVQj7W z6HDT%iK(W=NbeR)bT`nuc1rLkmc&&PQ>`V+S2>wKu_UgVm};d^+gYj2pO}fOCZ<}w z5$el8OXGJuysmQTv`kzzG1Xdvo;LK$u}{j${E4|kFRT7&Eu}VpVkWNI{fWUBGuhB% zOBu?^{E3;kYGSIj?XXtjcSmil`4fu{>8)d;W2IgS^K57O!yQu{o)pzr)fhwf=MLSk z?bUv$=0{d}^GxW;0xO8IgZ7Iu_A15>`tMPmx!$}VTB0{gJ30ezS$OW~c+nHKK)jGhoF&i2$Q_-LJ9_B3ql1DtOYWYYJG$XM9J!-2@Rmc* z9UUdG)8c(jVmxUd&`z}6(HVHl+H*%oE#fyjzBykpyKD6+h_j@<=DDL|L{%PfmOMiu zcXS5cvhdu|QKEC8b7Q%qGw_yXtEqJ5tMV*&bOzqC@Z8Zcw>pFU`5?}c_L}F84t-Va z(~-99d%4TLr=9}60rc+-^gebO{2MuylHIbVtBR7@h{?uB2I@|B{eF`F%fnY8? zH&yJ;x|a~S%=wAjR2c~7!gEtaiBjmkV!5d@5X^<=riy+Lxy(87+*HBIa#Lj>n1{5A zbjKlbnY!hEH_m~ zZmR6Lse(f9C`xU)sWLFnwdbaayNLEyTWGndGBD3W&rKEMqrKI6vfNY|nCHTCQ^nls z4E8CIn<^tWRq45@LaS9v`g(OCu+E6t&K^V02=#{hx%#jAUNw*3%^pJ^o(YfNHENIR zweN^M&mKe17;`I8zUsxZ7<$IHXU5R4xyOgcBZl56JZ9Iv`yMZ1oe?9PiFZ~C^}}eN zEQX$O`q^XX=XJg}k5D%m$|a}sm*<Kw~AP2#L#Dtp=S;uE1_SZyQ}xTYQ#DtE{{3$hTdfm zZ-5y3>@oCFqI{K;#n5NO&>P-aOLS*Yc@{%Yyg~LD`e?65$6HIZf7TCT0kX%?S6zGc z*S`LIIF2QI3_bBG9p9K69qGWBWRIZ_kFc(fzP3C5!*o|ys;+HaD=E?M%D0z1-z#sE zHs^kuw0k>$8KB>?js2j96Mp2{^Swq1@@F>mbg~vbpVR@~OD)T0hOfHze6I~##uBZi z)RvJn^L;1J_ZocZ`=-y8GU)B@I9b-y44?bZ^Swqb`g!TGB?Wg2?k8=l_zM91`a{q6 z+C2NpqgSy+Ybmv5Z_WI*!SlTa-@o7&hfV(d=v9=#UmrS7K{4=ruTi2DE@L98En8^j zYi6GBmHn_1@2zEu@D_U32xPit&j+6Gl|8f)RxTM2gv?jbUp_6>gtDEJnZ=X<3#Sc&p=y>c1!gYzvc&-WU9wN~H8;qP61 z^Um|V#xJgF6=@4wP2_uYp6``MSo3_Zv2wia4M(@X2KoC6-&pf}udxP|!bicV?Y*Lm+y?d=z21=3 zK6k&CQ{eY`M)n)JMoaWgt(@Q&-S(J_e0@XD*ViClU*q}u8ro}~udktf5c&Et^7RdW z)8^}o666PKkgw0Ek&i4mS-!rEe0_!I>x&ZR0-&Yh`T9bhmai`(Utj6@ z`a*`TD3xdV`ZDtM6`rpzWT>{QJj>UYk*_a%zP`{nz3-@wS-!rEe0{a&>x(t0y4#-* z_ePmVSnmnCR z?htwJxI1F*_@=PGiPQkIWVk!6<-d};&ytuszA5Z)A~9~sN<7xYkYPmcb)4)?Bu1oI zMmgo>5h)E%OQp6qk!rpv>~A79d`I>I_;K;>PQ!O=8Sg{P9r4z!51E)dzA5Z)A~k%a zmk~R}+;!B%+!4p!;_isK`U*qCl^`Z9>QHdA=!3+@01^&FE7Q zbH_J@{Y|78QI$u`9dHefyCdd~ZwmXHNKvA5pmSqyB4xfQOx&GHSH3FG-bAYTrm(+> z6mzSyrn6~pA{Bg7*xy77tyb+Ly0IH+dmAt#7mLM(>*=iLxknhAR@&QunX%#iHX!4W z?WEUQ9{uYSjHhO7xW5g^-%^dje`&IBj~#Xj#Dp`d*s^$NE#=#%U=9|>hWp!qA;V*~ zjju<1yA0<1U~IU=gw|`PT>*p+200a9I}=8?{!A) zzwp|(y$x6(7fbfH0r`8am3TzFQG2wp%U})`#)kXbfQ(Q!3azF4N=nSZ!q{+s8<6q; z#>;<+HEREL(ObnFEXc)@{cS*^1dKv!X`k$EKt}dkCLJ9U?MI)2^TF6~e;bg|{3b)k z$A3TfRxt+)a6k5xF)prWc9&)kN{x%@v^o>Hbq))*dEQ}5Jw*eWOZxpJP z{`;`YU=9}KVzIbzT@zYMSDL*I$S79J{H3RX``FFvtaD>;1D3?U`rCj+bC`6UXXRvX zpJlv#mi_Is*spXaq8F8Cdc1v>k+J+JKTvw|67{Oz+i`;>xcLqx1Q;*e-VW{B~(&!U8AL&Q59;!y7o_V!u93^D%p zS?tt$TJ~k&?XwbZpJjjhEGSe4f63roG2T8a@%CBvx6h(PHKX4u{`P_QIqYo?<)xaa z)Ifj&pU9jt{`Oh)T>H@AZ&+tspKT7W=sp*@ezn9;Z zGcz-%41M8RqI}hZV0k$+bIN$`&t}}auIX}rvW4@ch4Wf(l=;DtQ^s?D28H?-v`?)J z=9KZ=pW*k>QJ@dLlO6rA9H#1fQ_qC=&su1?KQn!bp8GS}uC1Ti*4tFesJcL@!X&MJ=;ojhf`a`@>yo)l=0l3oM)p@zADc$ zd1mI6@!X&EM%hlSw~H(!E6Wq8b;QxNM6%(KNOs+U8(AN~6kvCfQ9^fzCaL&RF8e3g^E`I3Qow)jNl zrFS@`wl`l&V4f{LQE$b1Z}W%??+3BYj8XJAUl?a;B_88v-^wW>0S#HK`lGd!I-)cJ&S;HyMzg;&8YRRIGD8S`$iymk^6)#(9~KmNXEggeqj4is8ANOX7iXwV zduO!7JEPg(84WGb`Our1y)#*Kz>#o-@pndR{m$qx|ITP52S>$SX8fJe zTE8{Lbi5zcV__zcbpjkS_Vf z-x(e1cSeW#cSai?-20GU{GHKSzcV__zcbqKptX}<{GHLBerI%;e`mC@YQ_)RSp1#Q zO20EY%)c|*_#kb!J0HJZXX9$)z0a=?SZDTdr$^>b?r`^(ldn7DvZ;^meEj4~ZrNgT z?X@qOy5YHl$*E`bktTz~$`Ma@t zMe$$@=}uj6;N&~M-pf3epSn`D{}Z!@S8Q`<&4^6&m%nh}nt43*wR6VqIdNgV z!@Fk>*+RN&Z98-FiNiL`JQhsr*Ehd;ui>^U-dQsa68+ByW=>8YZj^a!d+rYP*KRqx z-bFmvLb~_-v3X(cfHrb{7w} zkgjDg&&1=2?MH`S6rb(hbZ5;KfN0BLo{7hE($fpl*Vf{}7Si=xSa*rX?3MQ#E;qej zA1XPxvJmaLu~tX}({rd4EQ8&fN>qwkg{{;!*E& ze*KO0Hm=?v9&909+pujp@mNcCd*LllRyT+T*IJ_O0k-AD<3b_+EyUMk?QG$Ghm`a! zfV^q>bvLeNYgFV;H2LYPElK_=Np5Rr3+YlLx=~Kvw4JoOf_P9`qN%qKZkMIMOcuYR zteq{S%bC@Al&s`lS;>yF63!aYoc|EsBugL45^e2lAzfOiV!Nz;ds(|Ziq=Oo?Kp&Q zivI6q@!QMV*+RPXv=FuseS6ie;z2JWn*JEV7p14q$l?!@9Bd(7MvM^tS9-En*`pW@ zh-O>~A!xpL(Y)K**+ROEeEM#C-NDGw@~X`|=ZKa>Gd_lJxa@XB_WKj@U<>Iof`{;k zyy-G|)$7HB(V1w*`Jf-zdb&D%w~dGM5C2uoUD2#(j-Qd1fXF&u9C z>zXZRzk9*tkH0g0@}h$;n@UQ$@#I72k8FL>59_b~cJ`1hMEr5B1(W~1MTzZOUi90s z6+SU*xY2s|*S@u(?1Z^vefyp#PVTq!^vRbT;@E!d^XrX0dHuEZfe+0dvgPAzojCcQ z%O<*A9&^|KdHwS*%orZL?XT<4eg34$&ulbpa+jkon@TkI5BlChKG%dB^YqouRXZ2#!|wgPvnzdq@eXH=;v$<2JX}3s0Xh zJhcC-npz~?F5>>zuRr#9eQkZ>?`ID=x3nwrQ@on}+p#aqnl)T*T6YGCpuH(yGXL8n zZ@BVD^^?*SdC-e!)3WxLZ&rQl%XixFh?^URw{palwuCeuw_5W-sz%#f836 z+;i*UUoN}8{vX8>w!Chy>62T0^u)2`U%=2d$P$6mC3b@}$cu8)4h^vRb#e0+>0M6;en)t}$qefY0qcB*Er zc7M%Y990+b?|=QU9xijm$T5l~5>jtOhw#j_J%-~e?_8arSVAq5ZWnRwI~LZr-LT@= ze8m#ZE$xc@LRjU&S;L>~JT~^zExR*F1no@~TjAn*k9Vw6|6IBv4|)-8+IzUIhF^Qz zjrEJyzrW)jq)UDwJay~w^@nahuD)m5>>=rTCGd)1Po+1j+Hl>~hDYr1j^TS0OW49{ zDtfSPvpRpH;bB`nSC78zp3Z8(HHtZMMW4&gsek{6&Fh6fm_6jW#I|M~9EjyRlyOKkup8Lb}YP>t>4kE~>w^!7BAn#N)X)oH4oSKUR;@5`Em{ww z-WO#aBQKsgJoe{bs8@Q?JvCcMm#09w7w4N-)dybi#MpPQo<01{TfQ~<#04SpAbPp8 zzc+c~7cQMhQS{$?>@__9+%@aTa8Jz^((RrV{p#C4u1`Jw)UkubW9~EGot*OEB@>=C zqWAi#?qhj=&CFxw3i}S{AGrV6`y>ZjNVj`#@TyD3>SOj9UpQYpPG8~T$pbf8Gx8vM zpDCA4e&iLGT#)3rUOfJC;Qk|XUbwqv3+Z-G8n(N5tiEaQ@sC_69%~+P$>jOJy!Zmk zL3HLfns_`ZU48A`HLKUOa>N$W<;jNXmZYl>9e?V`f>w@E^B~=E`+G=abPhuc~jk@QIN*?R-QYq?_lzpX3mQK^ z>1Kb-JnXd(2w|^fOZMQ1&Yl*Z^^0tZ3?JX>xvHngK<-47pZ3&}{47asuVoAAQX|T8 zO1sa`yRmX)ptM9&Zy~HDul>>mPmFv|GsqUw&7Kx#RwpL1k`rVljtrbNqB;K|+$T#s zQkM8>@n8$-W>3pJ92w4*wU5gZX?;Y~jzd^hUc2Hx;~zOrJlI0I^fc`(<+aPs*?;8y zl7n7EH2pCId+ly}k1w>>vW0XRF+#XbJU%mL|1n1fMgyWVzlr1@_S!WR;ZAJjh%Kbc z$QQyB($#5-qOWS@h-ay!oAs7?RPx$qFMML`Q|)}j7Shf0KWR@>zFl*EhE{{`xAPHs zkZzv;$t1@V+3q~8IQCk$kS~-Qu_#YexpIGDK%P&OA1g51y)((_YIK(&dV( zZ;=%lel+8`+L3{)CDB}Wb>FKz)@!=gbL{~7ZncCypSKq~4)TjSeMhgT;OOAUpq)h@ zJBtRbwY+bhNmp9SE3fJHTDFj`D^skM6nC|jS6n`!oT3&fg zx7V_Tboqs&ehWfT!E3tLbFJll&zyM>t+jmAHjsE|EwAjkUeDP=x~|W$w3i&x ziHFwmF|X+rHV{c1xXf3b3raLltj|jVJ=z6c)`iIu?+H1PKmMx^q9l0{8iV9xS z9T~jWg?}`3xt|X~YkA#xE#CF{Za_*QXf3b3rh7dnchco(L(p1Ydri03vW0Z1kr1?& z*Iv^d87M8$)OrY7%g4N?dp&0h>2hXO@hdCwn(oNJStFX(6N1+AF|X-f&)Gt{w9pW= zme-C9Ue9TLMAHjG&|1FGYr5BSwvaA8O*;UsvyKd2&*?=((;q|7TKMhxAJ ztNnu4bVmk81ER$b@k(p?h`rY9Ia^4VkxwUailScAy`D3w5iPwT?rJR`@tW@SoGqlw z2(D9Ptp;Axy`D2V6Rr8j`k}SF@|te1Wee$YB~m_7yL_+djtpF7h?X5=9n@N0c}=(1 zvW0ZHqN?6UyL_+djtpEaiRP-UN)F}ul<(^~*T-8&oaZ}dhiQH1`nV(4X}I!y%J)^y z^|6Hr=lPUT=sV`?D^un9l<(^~*T-Ju*S$%{c|PU)dd~H+#d$vEF#68*k&=FuM0q~t z`zq)9*g}N!e9EQdQ8~}2d|%JGKHkv6n{=G#QzoaM&JCRBQ@*cqu8%Fw^C{O9>2`TI z&!>D}&$&M5`IJZM``m!&?tL=O^C{ogbFPoQII1qfc|PU)D(Cvh!+Abs+2W`;Lfz4* zJfHG?J?Hv(vrWzj_q{IVOmRQ$0G#JjzAxtb*pjo(kq7xH!=gN&@_jMa#}%JV7T*K@9qS|r^r!g)UB`zq)9IJdMb z@(aOvKIQv*&h@c{2-;f+&hshXS2@>59`qvGv~qpQ^C{ogbFPp6LAvCpiWKGfl<%vY z>myyhpVOOlAF}d%%J=o0>thSw)#<@H=iF`Mp3fnD2FV-Ib^h4*xrfgnmBsCQc9UJ{ z{IT*mq|YGPLWIsA`#$MNu|(&OJ)cAR43fRbuY1eC&L4X|hx8dFTXg=|_t}ciAW10% zoj+DShx8dFTZqv4W8Y^yX;eCY?D-thXOO%-p11Dn{ITy7rW8wb{#f}O(r1ut(fMQF zXJDq=<)QP(p3fnD2C4JMzR$NDONj2?b+7Zsp3fnD2FYF=RTrW2$I9oBK7%9=oj>+{ z`sYz`gu3_R%2j(lhx8dFZ{6qnV0XpQ`D5jCNS{Hng)15PX(zMCyvpa0K7(WnM@UK` z==`zgb4Z^-vV{naR$tf5x}fqoq|YEJA@xSI>Htok(epW^&mgHq((NL2{#f}O(r1vI zTiO-*Nsd{wdOnBr86;bXpuL5l^T*2PkUoPX4|)-8T2*0R-lOMpNS{H{KS-DS^bOXG zZ|gp%%`2ZllCDmE`lZH)-mE?KDI52E4(T&Uw&--J`85xEunz#|y!?A^QbHz>O;aWJ=#8s|`%T+;<2hq7MC-ZRij%wm6 zSMRWebaTZ`=HXg6)x`B&A(X3vA`hZ-T~6lVS~ykjRH%oGEu@<(ZZZ$o!l@>%hkCfk zgLHFUPUhiSI92aduHIn_>E?=?%)_;Cs)_5l9xhh}MIJ=wx}40zwQ#D5t6UGq7ShcX zH<^cP;ZzgXbA?c@3W_|4&UHDNhil$x5-R|Q2LL~~CR zf@|Sa6W4P+99y`DBPHE#tXeqL#Kn3zawnSnLU1jdYT|mfcD9f%HKL5Lw5yu9%Jp!R zmT2lN1lPi;Ca&jtIJS^3XI5V|%1TrdSGgXJvqm)MU*Fxy5>*oyt(`5To9ou1)Czwdwyjz?)x=eB>NL^ICE^`ml4wd<+5;&6=;rM|5+?cub3^juS&*NY)%sDnraG@5O$+HtBYj(G;-U4U=bGxge)R20e%m5l>8)>DPCT@JRIaJc z>qpZrww!p_(p^)X*N>)!bQS0Oj`fL$){mZR zs`L8MwB^4#w&lb_>qq74&%Ay#EuNQ=Qk3zCFo2NLM!1w=E|gT0d&nRJ)#&KXDs`L8MXpwZOx43>(uBp!JM>8L!E9-1#Hm)BduBp!JM`I17%lVJ%N6$6Ywsy9V zuB@}M(71k7-j&&-XnjP}j^p~#b4_(#KN|laU0G-2X>t9iTvMIbkH$Mmm;M;nkDhC) z^ZL>FIqAwen}`wDkIFUGdHraj4Cyki#Py@+n(DlMH1UdbWt~mri|a?_n(DlMG|`fD z86V^N(Q{38UO$?+OS*isi0en?nrhcmGdhzl<9y6z43*2Mb1tL#jdi^{O)8hs&$*1| zy+kvpT59DoVm-C}%zj~CBSLRWlgefElh?YITDgom=Q0|){%TGYnejK>{iT~KL-P&e zuBBEkqt3aErbX{(lgefEb1tKy6muE1av5Vem(jEkq4&f|U_r1v=E{Eb>H=>X;eC68F5W@K4a;-7S%Uh>NKP8 z>Sf=6sT_IV)w0bQ%ZO{L^BGIiqWpf}^}MFr<)Jf{+BMbrjHT~d-F(KU9^u1j2H za{WYJ)m%%h`m0{9zjB30Y$4rT8IgIomRj{!u`)APZ}crK>E`;0%)_#tm~6I)0(S4LzWuBBG}Rh8?n zT<;TkkZ!J@$UIz2ttyLNuD^2SQEVaIYgT?_byYiN9aQ{n*HWwgs^=;TwvcYFjL1A(ORY+d%Jo;@pZD16s=tanh|cvBnTKnsRe#mX^;fRg zC~~+yEz-@E5t)Z;sa45Q<@zhvkrg=_bgrMsJX}ky`m0{9zjDP!Y$4rT8IgIomRj{! zRj$8sJzSZO2A%6CG7r~MtNyB&>#tm~5nD(%S4LzWuBBG}RjjAZ)fE`;0%)_p>Y$){uyO-ix;s#5(` zFV|nW8Z&YyUGj_dSC#6oqSvy8bg7Y8e^sgeDn#s&se^urBt7bk(H`nDv znPUA_rTVKF88~aC+qEm#Qmg)|%Jo-`Wsq*JFUmYzOYO*z>#zLV15sC`+w~9EQmg)| z%Jo-`g_ABlE!JPTGP9TKuNp5RUHW6JzjD=N^jfx%uJ|<(Bi3Jyss1WP21Wy-8CUch zZmDXr%Jo-Gydquct%-cG{;F2}RWH|Hxym!@igXztLvSs%>aVI?f7QfY($)Mo5j@sk z)vCYh<@zgEd6xNT(3<~dmC$`MT5(i=6}^@%q|22k)?d}CzlxE8s|?Yy<7TzfubHa` zQuSBSYuQ4&Tv22FRjvA~7#X-)63ultejn9yO?Cc0$~%ArrMR6suk@!B6vL~ z+L6^hnRs|DcTKg|bGDGKXVtMj@$g#inrg4-UdtU3%!6pJ5cbK$!yfCJ>im6F(?Yto zPOpWDhu3n~ROj!b`i==1^Kk&QF;tht%aw;mgrrPVd z*FZ-E^B`TX<&%Hgto=T!=bCD-=WHR}%rAab5WlpjTvP4!+-v#H@7lb4AJx#!{PH&q zUdvrmoxhK=9I=ITv)(cfujQ_(_IjS>n1CD+o%NP^crABLb^boe^ATG}H_!iMnh&q# zuBp!7M|nOX57N!^KbhvkYq@Kxy`Hm$bh9029$w2`Q=Pw$vRzHWt|HxR$C-!Ma@SOQ zJ!cE)a!0N&krWkNQ=Pw$vVTM#M0a=kUdvrmoxhK2cKUob$etD{#qXnfuBp!7M>X#Q zq)UGB`>4t_)%IGpkZ$(0%)@KBYpNX?C@s;{di*}Ba!qyqKFSdwYLRrkODi)QzmMv< zrrME#vqrj{|M-1W<(lgJeNCMS&T~lqZWee#tV#M#GdakKT}JTueN@ji)%p9VChC)J zp8tO0;kDc~)%p9VW@RB=u0-+ssGe)89T~XFkZ!i)%)@KBYpV12QOycTy4fH5ju`R# zsGe)89T~VpS0sir#CQ*$Il zxR%@%XcUAokw!6k7(uj`p({^T%T*Ho$t$cCp6qSsxHE{)Xw+iyAv87uBCRC&7gi1BlG1tcy zSCkhmba}XzS~b;mzB{4eL4>lB&1mD@36*N9$MW3?%^Xm>M8~@mda9|e^W6!J-buHM za4og-efjQ$#(rp5wEQ?@p*xQyuH6X+QKL+H|}-p{JVa zD&L*Z_y_5dU%We^QcZQNrzTy#pYzQ--ks2MzAxXM(D*qs1@z!}r&H~k>U^hD-xZP% zE0*~DQRg1<3^M0;vt9Z8(KXfiPABJgV+#>Jf7D4w_FA7mx~4kc>D18m`D5Yd^G8>P zrdZU^hD!^7u~u4MM8IKp_RQ_nTk`A(<4tBHN8$M?bR zisSP~*Hq^_otigDu4LpF?{unMQ=RX0YDVHy*rJ6l51&7}raIs0)bJp}=Z|Hy@lL18 zHP!h}r)CbQU83WiPL*q_^PNtO-buHM@cE-_s`H&rjs4KB$S>aMG~$}-e5X@0gGBiJ zvDjO@(`n2#)%i}Rh6lZ95o_1^qid@3olcE^kS_VfJDqCRROdUL8t=>}Kha9Me(v)} z*Hq^_of<#Sr%Q3gp$F@xTh&slraIQckrsL6`l9TEuBCQOT)tn_RY8$1(YY=sM<3Tx zyCyE*FY0=q*h0FwPAc4Mhij=_6PNE7b-hn)A>CYYlXvA#=*HV}2PqvV5u3O7ITubemI9CYes-Vb&=v+doT*HXJC4)t)62kGXzoXo?u)UJth^$uG|H`ftn9?P_ls7lsgCt<)c9HdKsjQ5LHs;Tbf`$b(z8hMazt|QEHxR$znp}=TBx{NEq_lwr5 zsg7R{u!VFP`BaOeT58o)SNVQX*C$3fh-Q3@_lwr5sqVQRjxD6il_B0QTC1iy*26J6 z6U{g;IhwzL?^SEw4Y=RsKDgnfT>lrRI(Zj+gHVl&|e?IXGT^UBxfPx(HTZ~I$vYWJ!C z{f|bw)N~gy9DT{~m|KsCw1{TZj)+0Rb?u7pxU{h@f_mqdfwZwiz3`ykSx3Zq>LRFj zfAMJz=Y4xKPhEs1KVq$qN6A;%XW>W)bK*1C#4h6WZ}cW_dU)%Yp|f^xsWy#>wdS8S z{?TR1TTzSY`Ufiv=__r2&!F_~TfQS*_Tq`z(h*NR@QsNwo3j?4Gf`xUh(W>)hO{N} zH>&yp|MYiU2!DDADwg9x7hIdAD1^of)6i;H_ywx8JIvoB`|-D@#R z%!~%Ux3+o5;hviB3Efd0{;z%evyMJH&bjCRpmpw_Y96$OE@Iw`KieRP=H9o9=wyNa zwxGYvhjxhkK77dh{;Y?O$r<4mGbkrNvE?gIJ~q5&UgF;11Y`(i;uRI?S-HyqKyhg>AC1lShno(ug!1n<(wQ8)5V+`){VBGb$ z&h{$PWekppLBhpRP1?#A?IoLPZhLHa2sQBcQO*8}`yfV)E`kw&h^1QzTkMY|emGK> zxYF>@L-N|vi)hdNe{Fr*60C#~M|1AmLi^SN<4TvuBGI6!VPI`TgBW;Jj7vUEDqc%U z4MGotAy+TPtED3tGZ=jsmAX7ctJ#IK7voA7!C1nG!?@B#FlI1k#Te5?FamHt$A}RT zgM{n)`3h^E)DPipah~TQN_2TJ8kp{awGJQgoG%s`3>$bp7QA8W{{46D9;4dBw|}gO zAEXp{sJH(Ho%`Xkexi3VN~FH&-)JR{;jx$LuJ*w3@j1^^eC{IBihNjXNzZ%7=j@wH zKrs5`Gp`tN^4Zk?4}vk6v8y|(yk!;Im(_WR(I+ApKjgJd^jUgj;QoXAUHW_yAdPL{8?Br3A^Q9h_Y84V^k-&hxqnF1 z^>0Mbx9xWyd;BZWYZvqL3>yr&(i2UqYklyKCM)7m{{L&HH#f*EdZ87x!h!`YX z*K2d+j0k#g7eRk!FM4yLUU*~)qo>kq>CIgPeUQFQf9xW(%V=(X%03wVLvI`*4`j!)j7h&)nMtiOB>~` zkF%-qq`!ejMT=uRr-c@P|2r7cerPeYw=RPA!}|b;?jjhSX;)eDC0HW8$g?Th@miJLFi%7x$9mQ(){w?VwNcS{u>OnQ=0Jj z?X}6q((YAy!|&at-issj{m`W5XUymj_Qvzl5cCi4t&858{sWJSyD+}DEw&?5?_}+? zS6biFZI|yEjJrfPqcR)+%2@MNJgsl(c18Qi?^IFKOXorRv451Tiv6Z!Te_p7{bcNRECgS=;m&;M_BCGTo}ZIL$CNRp27Is<)N79tW#{E#pGDB1O$5#O&ja-pq0?BXfa&`Th{%+ z7n)exwVsR_*lW2fsa~DLSV-Ltgb`ue=**5t&hZEAlrnv4s{xbnYDgGwA%TWsbWM zO&eF>cw^$k|C`h+#%)NK;Jwx zLf?xMpBp(08j>#gaW~LKc%3Nur2LK(<=}nT4Psy(9&fP*_M-K45!OlJL0h7YH3&V# z9I|(laU|RU(B8TTt}?W%B}Sitd1T*?TIAl>dMi<>%Y#wI@<^^2yBJrx2+l37gmcqH z&}+HAc4xN5q+CYPF7phW&9=WKr{3vNoTn~=-pO7>cM)l((yB)7=IGkm?jYd?LwYB* zORYCNgo-ohyR;&$yu!uj#iD424TiKn+VRqDmlj9KsgY(>dWbtR?^5GPG&=u!a(t#n zx(HevV;3#7i=f|84tjGJ!HAqkHR)KAMwRy0U4-@q&cj3t&-t17Y~Pn2<8wp|5^fOV zNbw2wBD%|i64EkgFS{A)E!kCN#ag4`RU8BeTVhe zuYYdjn|tk_^9;#G?Sr-s+wRjpKWXCXM`z?w&HU;C_3(~!tILI8FUH-|4w^pk&JFt+ zVX2QEy{WoF2=-#serUyq##_YazIs6QfOvdQ2=?OJ)@ROGVZ0sHDHt6-<`Q7Vl z_M)_(e`d>xRrcF3BP{tUGY{xZ6N0@c?Xt^1GTtIS`Q$RahsC2O1bb21%Rl(;@pe=v z+`N15QpxchA=r!3(iZeBaz>me1Y1a#ltS1~qxzjjwSy4s#j$g=mODwlr4Z~z{ZJ#S zXq0w;E*=*P!CssLYCVKnGx&E&e)xB;ui0zmu`}Xq+V42Cx^qBQvazh>0$B<5LuqL} zA#5N^TqsMtQV8~1iSSd7okZs%-7- zMQOV$&OMTRx$B=BvmA^WT*)loYOg##d+onYKcM>39p}~yg)7kaVEGRC%_*&) z4@O6Cs)s_bm!&NT%hw{_C&@1qkE?}XFH2kYT9&UJl_j4dIW7@`y^^#kq9!dImPd7p zto@qhzE~e8yJGC4w6^JKm(R~$d$_FqZyWT6zm{FG7p1jLAGpOSt)CA@XC5$IC^ zTHADs*i+X23-PeEvlpecO}C@^iLCuP$zf|}FG`y%|FAr&Swh?>#E2psTS%9bLO4aE z`in+&P4=k5onz-{leJHkb3m5;8(~tJj^WKwwX3Xy* z*h1}+QV1uX_zBSs;b&8B>8zZLyREUDVIjdgbxtkY~E_=P|6ALER z`sVz|TVEW`e&cYPSI!u&{HL22(o@;%H)n4-@z8rt$p~xq(#MY+-uCRx3+aRGRgFI~ z-Xg@Kx3zezEd)K4y-vUEz2ohu-Ztygy@w>no=@GpkUq#>T`O5xh-ZYj|F1W9ERl9a zO4^HRR8uvoUrKV)WiO7_a))qvmYic}FKR@0c}u(Ni^tcWzj-0`!(P<7?kd&{zI~0e z>gj*Ec_HV3y*RU~eoDHkek;l8QS?E}ch*m~$}_m4B;WCsGkV*JhovpMJNB}CAHHzI z?wt3YmK>J0>>%08^0kOJN%HN*;{*RpR#Fh`W%=4sy*1fxRcX#GZ5b7N(ejh7R#@Y# zYB^auTj(pKq)!?&s!F4};?GIDg*$tBZpvuWoL~0%kx_DvoxP}$5I!L7ZY&-@(5R>% z_M+CK*Y=)#&so*3PbW((qhc@4tZq+A5pLkOyC>H9Lfn6T{cAh*((_@HetzMmuf!Ph zl9f+WjIL4?9lUSNTk6!Z_oQ3ci&3IM1S8l&O_NeHs`$=Hy6nZ#>K$8qhI6#1zE^84 zdyxm{Upr*&8E(_QeTsG&e>nK~iLH;=I?BOboToH{<*n%Ew{J1A-t8Mj1bcCwbO(g? z3{Q#2$26*a7d|>(5bQ-?3E}hFGn^qgo)F^Jtv)hdM#WzA$GFzkFVA~w>V#ULd?Ebd z^aJWI>)pWX`S7V@CboL}HgTTWi}EGOkI=ip_l5Z4rJGFrdN=s#bE zcY}XOa!b3z==_LaFU!~NGA#Q`^=|N6@vyWHfA!>uU@yzpBDRv`4~oZmLRi{@U@yzp zj!LE-(%BOvaEb$^);)Swy+7f$F zz9f0EcG@d@Q9j*~B9FR7JZ{#g=o9Qk`ShKX;?;SQW5pbOiXX5S?Kp&ebJqDo+Lur# zjO~nex@{q6wjWkzo3z-Av9gO`3u6f>bw@?I?8VV0?JDO!biUp1X?g?hr7ZbjliG>( zQjUFZJR75&d+i;W5qeL~wMs&_$Oz}!JuxY zpE44$y3M0f4k9C*Ygf*_c4mUTEK{p#YQed7<=lJDx4W0##p8G>t=}-T^B+yK>0G;V z?lIraUX<4F1={&%gm;ye-1&C)qO?Y6=RY;^aIRfB_o4Ic>_urkD((C;!nt0bwrf4kwJYadd-uv-l$I76 zf^+Sb+}6%sl$Kr)f^+T4xyO7vdr?|?n(pP49LhXbws!WiOvR4s-4fcfOsy{H$DMj4MX8k-@ok<=o@GoxOOr z=~1=O$GLV(?tD9YS*BLn!=MG{+O@A9I^WJnO=+E1ZavDmcIDh-zMZ`&t+T|f*E-j3 z$(?U!FG_1f8yTEySI#|JJ9|-DkE)G6&b2G&9<80dEK@t@hr#llYgf*_=X|?+6`vs8 zE+yyMm2>Yo-_BkfJ4dU1Ns@fvd^>wlKh#JFiX}tk++)6-y*LNddI-+7E9X9RzMZ`+ zQ;A)iS;bpfiE{3hcYV|krR`debM4BxSI)Py7p0|zhTvSgrhH&)XD>=iFVH)Vcqr!{ z^X=?KY3XTtyOSKsxyMzFy}Hsax&u(oedv6OCB`e-aTmcB`Z*(<5$&kRooMni!siptw|i9DiH{~- z9oBj7%F!aoqr2j?l$>i<&b{Y+dsind5AT|_r_a2dYj-}}`F8psd-)Ajd-{xUuHCXY z-%cN7FF$KfKQ+ncT)Xr7&bQMC*~|R&E}aq1wJVQ2biSQF*zI)~?9I7$<=ltPw_Ebo zep(wNCB+hrN;&tKZzo;$;%HN@y-3cnvllg@Y8UZP&b{Y+JN3g})Vj_;lxtVcz2|&8 z=b+n*wjfDTUx%yK?R^-%h&h z#nI~b?jSkG&R*1rc75WZocqxEcIt<{sPzz>YxhZ+^X;62ZZAeu=ctvd?m16w$@L~b zn)2$cekh;3Rr_7#s$-to*_z!>lc#tnS3Pu|+6cYL zPxYwSi}LB$3M7Ye)kEj0Ju1D)M?|+*YsWgN)?U=-!rqHoa%FEuouQ=`C|?N9Q7cy+ z^VH4;D|-_W>_z!PaE{v6?mV?K&dT0I1bb0F-8L;A%2n6ig&U#l%~X$yy(nJ@&QU8@ z9e2ncm9jSx(e1VOq;dkiG_%f8D_0$PSlYH_?@46~dgez;dMD7Rl&g;QC8Wz<9Bo%} zj-9=zkr14tR<1hcsi`0KqSixjj#|0u%6V$eLAMuY);VhLshzF0Y?-0v?cbUd?7eT?KyXzn)b?GluuPi;-Or1%u~}R*o*S%S7IcGa@9TOsp)s!Ui4;< zNI9(9`75t#WuC1CKDV|IWl*Nb`70yZmR46?9SSi})+-~Z-R>&dQZk|)73q>6N9$4P zjIc`CD9-I+@ZiG`$BfV!Vb7<19&a1r*sI;uxIYnWX=7rSk`e8wNSFLLTAvv>mys;7 zD{Zk#?j=I-nSss@;<}BB_29E==t2hh!UyU zi+hO>d}iP}NS_;cRAn{j_M#4bW}vf!+UEvcOKi13`9koSfzA%%xq)-)CBm^6<4|`GTA^6Nd zX9w}^j&soMMX&XlfzA$kJ~y!B?R!S61?UfGNCh2S#- zogKt;1NsDeQ9f0eN)DYJ41I1uzw7pD?N}MF6ZaXeGGo>H=#zg|zv}GMCw{luo_*(v zQw7zW_^kId)iccLr%dYK_Z_d_b@lwQpPqBTkas<#Dy{T|3ek!@XKpcEX6480FP`$V z`u$%#Vd87|?hxsc-^x3GdEy(V?wNU9y!Hk45xZ|#-yVf|zEa;J9{eVs{D=)tvt5x#9f1}GLHr4zqCH;jBD!a#e=upkRL~D&j^FjmG>Wh zO1c_-_Pp4^BMtzAZBkBYwR5bx{u9o_j^1Wj;AC+`<>L=G8FLO?QH_y9tyw%lF?>)S# zG#``V!5c`(k7(V2edZRu_sgzskR0!L&FRBpyX4pVaDTj=^BdQ`pt?nNb+dTzJ|glX zTE7~)V4vRe(^sv>#UoW?CZ8a`DZBo7*xK$x`;J%Z%0GTC9;s%t{T8|0Q$%zKH;czV zr>|OFoaK1yeRHE-k)QHPT8)YiJ}VymtLKl{2lQR zGD~uNK|CA*imu4de%|sJD3*Lpa@ao{Kgvy)%O3k`HC?aq|fo-E0!Me-wBIRMSz zZkoYs#e*|Ne$;eYIj71>4%Q6P8px065a!Af=gShks?p-ej~1hyjI8~?W$nw!YiZTw zM|AQ*dz7t&oRdz+>M|AYT>OAepJmo?XFOFo`=mW}{LSLDZ?tX2cX zlHDc8Dbf{p+vG>IeiKPCaYfC?&!j6yvNGr7=Xh1_vz4`L<@|!?N}_0xsW3v;>cfpY2qc{-Ls$0yng?(xx=?iu2ny| z_MHpai|b&j#ha56e-h$=iM8sd-+O2NdLXrsE-C4Es$YFs{o%vs3{PD1&V`(3&c_GW z*>_@vg_wTboiTr6vzvF!h@lWS3$exf?_9_h(j_I;i@y4@ z>O&gUerw&ikX}SstW|wU2(AE()XFQycbsHb8BzaQ2=-#!?aJ|}c-$zvIzW@YV`UX;na|GDGbjQEdl z&FsBNh!;|ZBZw#44|vR##4+%tGK|N5=@ z8F8X)_XCH|=^Y{-Y$09p3*kHRj|Zfy>pqY?s_4r8QRv!lT3yYT*RCTTCulw>hwZqG zo#^D}@~GZi@nDPnuJ9uzMd}oNs%NBKMjXeF@;>0W($2?Iig3GWJ~lQ2y&M_JYgzaJKP5WV^#^Cn)r{xO-yW!lNi*W1ML+GVhXbm?jO zeNOF`R@EDecb5CDdDO(rt&fg8hW=*X0=J}b&NA5bOzDRFH&!6$3dD8wvaA;C4_hC4RUq8LEa}G$6ooL4G*GU*#D~W zR#$)3PXA%e$3e;(u!VH#n>rm^VeK=lpMfA_6Z#&-3`IdTPc}6)I z=g8PXy7XXG{OYafU9zh&@wnjFL&nRT6TR*=j|^Mey<0iU<@9#L%^w-F;SXMeB$MTS%AD zRlj#9+g)34UcZzawySS^VB5%pXxs5M=T7VTV0^n{3+XZjCm;N)&L*xC5BtZgk8c%u z5N&^Kd5r7rP8pWrv66!=r0cj+V!nRwPH&K3lpN+^KQBCpc3f$7^>4+*A8J0HkPotj zbh$Ew@DjzuA7A*D`Zwb7#5%iA6kQSR_}I?*Zi?-@%C1h79Bd(7u0;CXaJ@lZBfE0G z-Ep_fInj>u#X|LEnAWJXbT+ZK{G2VM%k@h6#QnzWGvy!O7Z0x=#deA2dZoK8w5t8; zs^n2@;R;7eA&hHO&uUcvBgx5~Xz~l;Wm?rfw#SCGPXX9My3|MrTT8oZNxOd*4@yfk z^`?xMX7HbyL2H*Sq|2EN;W=5!ak7%D#e=g(H0M8r8M4Gz%MyPp9&909TBvfbvi9R; z?IG%_wQ8bi$6b$N3+d9+62d2nUe)MDMAIL2$AluoiP@vrLb{9?vRy@=10=_x=7Bd} zq8V58-Gn0CpEMuNg|mfp8TqtEDT;nu^RcOTFsc#F_^7P2BK6(!D6a-=AziOT#S2od zZ!_7IbC!(GL^IB-qERc(rt&E7`q)CcT!})sSF4)xqV-|o!BvK6u2*SQ^J$;+iEJTV zuBdvO5RVtMd-cl6)skrQYuEFkbaiPy?PCk+a%Z437_FQ~X!p8emZQ935pBJ-`;rSZ z=Lc$Mc}<>=(n7l2;e_yj=6q}ImVT@V$K4C*dj8w})f;8IKi1CjDe+(n>2jwg?aFq) zuU+5jS`D}hBieS{-HRTUcb04+UG6v=AB;Oo?k0)0Kejw(Dwe!0?=0Cux{fPlHyFa% ziY2op$8nku?uv?&GjnHVET8^*&)B{hd&vA?9hYbu14(>BfmbPJU1ZS5R1JiBZJXzod1a> zAUJmF>VICg^~C*~rnkO^fgW@dG^}BnmDiZKapK5GcZrCB5wus4XvR)-mj`>%qv*k1 z1ogvMLXC70A?zMcc>V6oS))d}2ues@Q6pUhC8S3!qLBtP7;>g4)6(VODkDM@*S+K8 zaXv_?VW5XJA7%II5q_xJy;w$r?jk55<)C~GVqhMeDb5FFY7lzpN>1BdM7{)yJoMO% zm+QH;TjWdKGpMtt_H4f6n)FV!h!z^qptF0WmC$;c?t182J8f5ujpZ+nDC4zu%k$Dl z#TFtwPvxDV%Y)L|cFV5c*52+*EI`7g87#f1U9~q_Pkr_8z>-rZ;I7yH@YFfIRad^OGNwzbMYN-xG8)2fUU;GU-IX(YMo_y%x6ekr z^^Udbo!>k+A_Qu5LUj9V#N3rO8jhX(j)+*qI~#OM$%v#?|5p_-SOJJ`pTR?O5&s&C zTNItv637t|9&d@~!Z+yl*@&#Gh~Rt>-98(U=Ob3+wtC;GM|AtVD5Bd^X3)LLv%gm1 zsK}k@_SuL$gHaAjNOb#bM4rKjXf^7Q6kYMzh(%{Gt-@1AiEf|4BVtWA#q)$9x?Rs{ zi5_o?=V>Gb-BL0STDx_U;^34~qT6R9=uxfSr;HNaJ}1d7z5g5;-ZtTCs;_@7A=1tw z@k{m=N1M7wM5}jd)Xy!YwtLocw%4w9myT%l-qr46h(Y4SHEL1qE;6bHA!IXytwxt3 zhdK{b!Q9SZtI_`p(d|`y;{QS{I)i0Cx|07(yVsTV2Kf{1!VkNA%l@m@{8hZIV}}Da zkH7ln`t5_hwMBeRHQNs;i?f>EQg71^nZM4(UqK*RH>zkC?&^dS^fvLw^|tAsal#Ri z2l+kyi)sD4=H8$0%eYEA{nPZe{R{EnuYQpq(K=&MhUIv@(a+E>e2w*H_FsSAlRb}} z{H|Vg+x`xJKQ{9?AXjquZJWQ4M}9=>+*xl$yC^f^+VfLCw_ksFRxk1(zaQN`v%l`L zugE<1*PGW?%6>Rg#9!VcKcb@z4%StMyl7E;7f8&n) zhz{X?@z_}BAKQwDTaMUwn^D^?`E9ah;+=eOoBhVC1N4@9b(W+2(iiy=tuMHgVfkO3 z<2)=LmhiUegUEyYEXS88w$695+$~*QtSpY}cdeiD%VL(J@FQB^0%*=p)*JmNH6Na- z@&7t4@*qFY$6ZGsk$KG3oNtsX8u{y&#eaM~@*qFk)eiqY zCG$96w)+ibKYRws->D@(qN5KsHQV-_!h`(mAM2d^)y%_~dzHoUob&gb$d729{3w>} zDLKBW`EUd%x*|XOdCS8!+lNRF^Wg79kss0eK1wms^RbC^nD{Qu zhbx!)YhvU_v~FisY#)9r7bOW*~>pD8q85 zbj6j0{Jeg&wmYUZ>c#R8#}ckfOo0PEs`J6Asne0>}QYSOpzZotzDn28IvMbkxGa{28BWlcx##4Qt_A%;{AJHNFMXTD;@(=HpxU!HRR|ZwFYE|1q z{_!oz!PSfWh}Mn0TGejT%6V0mqwGb=k1L$KRy<~Db>2oixC)aW(IGr6U0srQ0G6=q zMLm+jk1KTupVZ3vUhQ7z<@qQ(Nb)0ExBF?%-=hC9RzEv|D;! zJh&_3?uFt6h)y1Lmv)w(b9+wVL4Mo; zCPdl2a+gYeM2GN2#gf^1XXyw~bVYvL$!bTYSh9`exJ`0!w@rRThww_p#Q)9bgN|fn z&dHBEa^2XXnCKe%qs4=74dh3(PJR^IFVA-6h+J%m{P<>}Tbi|UzD9QSCHWxVe#npL z5QbW#-YfsOQ}e-HXz5 zcp%?8^oZ&cS5VFN1FF(vFY?RMp`Pq}7$6Cv0_x}+4s zi&P`Lx@K@FIT)iDOa6T4yhaQ9x<<8}*I9DaK(ZHQn*Xw+8cplY0U>S?Vy=0hg>*?N z*4Fk^*Nayo>m3+va*sRWF?ei_h*l9tgnku{cdmh{Ph4^$b*!0 zuYu&aO;xP-<{2zIVUNA+SS`~7znGiv@p1+B+f=`Mqx^%tD3eF{)Sg>sgz80msu!(x zm#)}Cx}=n%sH<^*ldYt@19;B&S?Q~hu5F<_hp?S2QQtK5R#`+2&&{p#Pl*Vk^*$)X z210yJqhgC~sqpjs7mY++4Xvvc#lwD3^ke@hz3exIpT5f`Aa}+@qT|;C{$iweyR=JbIjSxX+ledte=7vFNbPbq zRUss6zf(L`Rn0c7k5D@Fr)ZPy29$`bwM z%fGWFmKe^s!bp@>10$Zuk{1M{D5JLa?V7<;G^!iLgR2Zz18cYJ?ev9$R?e^Ko%0~A z&M#VNTFm>nl9aPaTL|F|svI~_J7mAtE_irGMEKm9=xf)V(SQBejC||ZD%t_`^mccq zc(8?ZIsf|3OVw?zt##gKjk~w*&wG4}c*hpef7)of{u_Syxy<8#w3AW2Xz$0`0kDO1 zX>TEXMY|<^aTwoNw%B)v{=*9niadxu^5k9npO|w}=JAAfWJl?(=y|;fvxRhNp&_iK zUEiDa=JkN&xZ&yD`ak>n{K$joTmQ0O|4Tpqa^_)c_uHK-&)7n`jAQPvd$yF5ac%AY z9Po+$x*t9@@*w&HuQ>!f?$i!>H_72jC$^9-eMN69+J)~dIh-|k%a;yrco04HM+4~U zaqaZ4)O>tEJlI0I^i937sAl_mRo1u?@XVJD8eI{+VCFo``JQ@X*;97qI|tZ8y7XY( zhpe}vef0+E`M7V3W1BfAdevFS!*;)`H?JA;kAr2qY$07n46QhNySqUCak+Tx|6lVP z+a-E%&RAK76SIhD2yZ#vOpd(%D?H8w>lzBX*IlowM6C-&(N(<>S z+Nn}jbN;yASbmk~W6j6D9(j)TP%C29#48@YqNDgOM?B|6C(T*!cBO&}lG4VXjM_)YHLb_ZTLinI! z;!~Orzj--c6|Mu0Q3g=(E5m`9owIhN7>rhLb~*{ zgeYE1FCv=$sNY0VWH>12WY|Kwj2O!GDf(4@PIA8RtVd zRIA!+OQr^9C_d>Mizuk*&BHMk9c4Yp#hApJaotkb|mF*s`UEe#iU6uD& zqHV|By{LDVu7F?*>2k-Je9*T*&B^{z-fM}rKejv^OLmYP=D`-y<<2>T3l&Rz3)ETS z!Cf)Yjw`LMZdc9rO_~q;2U|#&Zvgs@T-9v*7N}qN%nR@OL_0pVbAFpvwdb|7bS|7N zq{}y%_$|Qj!?LT{l7nw4L_5wG3k_kmRyBVO=v9p^q|5axgrl@Z-LBp1%kuhBY?o-R zS7`?I@4(eNoM%OV{xb*c5Z^4uHkjRi-(Ef6(-x2p(OGj|Lw5zUs?YLay)sB}QMGtQKTXIUvSVH+0M-&Me zMa`p?FJlIaYL`67JN8#^|E2jTw7B9}zM{9(H~pLDyzDHkw_iLp5w*K?1Xuk{>plDL z_|cytqKj_13_3e9Rc|$KFGRQfEe9>!y*|0>X4x`YbQeM2=KOcjEhf!inGb4oi8DCx zsHhWa*LGEO*m5v}I^j-+I_x5-6Yk--XY3-VQAPvmu#2Eh7_X?qE`kzL4$9X>aJ(E9 zN83e^JH3{(xj3S{u~1jkVHd#&KtHGdcM;SgbwwR21F4$rUar~ha;LqPXID4=Lp9sK z$~D{6BGK)$5qI9cRz0(+*>3%r==Rx&BUH2fqg=Dyjg~FCwP_=gl_w3*Cx~vJjbK$V zwYVrctqevyDmgy(=DG4FRq}LJmNo{rl#F;EZJ{v(RG2OII zBm~hVR(37X<4tQu8c9L7l+1(HZk?nxW6CJe?XwZ|s5WLy86~=XPLf-C|2b06$#b3% zY0eYBw3G2@+rJd4+ZJlKrPTBvBpz+AR->l7Gz5G3xoCGWgy{Q^Yt*9JU4+LV0y=9{ zSG$YxNPx~7)z$9O5v|@ms^Sw%kvz)5UPhPsSRxO};u-Az7Jw+k9l%Xj9yR&YjoU0? zpQv2OWa(uzpY`?A5)tIVoBc^CD=N#;_Tn#89C*eq-BC#f{|!377;@-Ow^y&V<46`m zBtS-#yY7v6-3MP45k%+C@jup8_xB%kzd+oPna3&z-JADwEhcHV^h$b5h%O}}cw0T^ z;QDVI+sM@Rx8z+3snJ%4T?8fMFNW~L@OMo9FUhGZ-fwSASSlfTm8KkvyZW_eE z2-4yR$-9f7EDDXp2}X`*(|-&e@n!194yaX zmuUH21Y628(SAO5{j=%=5B;?0gg{*_>b1#sjksu~8N;JMC3)$Nry%pAUO^?^wXJ7k#?sZ(e3l1h;B~=!qeQpQ zY0uD=Jo&+tQKH*t@DMl7M?w(YdK71{owYQo6hHW!MrG=Q$b*RX*}drV?%yKVQl5*h z9O3*tbN#cbgY$eaUUhA^*s&2mTxmw{?Vo#N)Gqyw==Rx&c0?i2JBeyD$mw*mOPHC9m$kYqTA;*gJt%Tds(0YiU#k-BL=U@|^h3R&UQq*3epb*N#))^lulD(B6@Cy{n68b&}*L zvqqU3#K5C!y|e3s9BqTpgGWUhEz!X9+{)KQkbA42?re4uU0TI5%!9l$X0Z6ES_C!H z<-w7V?$QySwW3k$t;CYlRKBqe%(sP$bYDoz5@ETiqSo+0zq`M3fB0U$n{(iJPw_FB8 z{jSqQ8M}OAq8IsJH(HL(a4H<2{z=*}Uzai_f{oTP(wK zP_*C?E*U{9Nm@u2Lv$KX`gbto+)_VFlswA8@p5h`UzZ1^HQgflVsZ>Psv<45(3P*{ z;+WXl53Q2+*7o;&kUK|3eoIGC3zV-x49tU;$oW`Qj&|j2dpXwHj!Rr=ZQ48dZ|-Kp0_muR;rqV46Dg66YV1HVbMqbhN5$|%w8b6!6NX}+l|BZw}~nMb2t zYLWVBpN-%Qa;AuGpVO$)Tu4_MUGWb~Tb|vk8?PFKKx`?`MEhC$>7Mu1>aIC&W7Oid zYdbbV`{|x{mkH5EGNRjOBhp{8cxf>-~E=7)F)r=*cbMMH&L%>B5#WIrQMbiz3K|+vLi{LzU5nU}3%@H=3 zsH@gWNVlu2-|O7&PMt{^xyk|C_D_BAIK5TR9xcxwxnhUWpRX~!f8vo3O!c$scfYk; z@6$g!w>tRZg>|=O%f4#H^d8ls{jBfq{_&^k;uWU%eknwu>y`_K`}KDnoThA~d+pla zd5vW=j}e_e`qaduVz2U?Mnc4P(^ji@-Src_8^ojZN_3Bkbp5=;)I%b_gcgsw@KCi$ z)2lqYR~I2&4U4W;eC+tB6VolvM*R7vc~OUn$0w(+H+<9cZ|eP9qw2P_{0cgab|;-C zzDGA&N$`PNJ~VafsL}GA=%#P5((`Zs;a^Y=VdYB}3e~odZb2s=`)gFoJ^!ZRNGSDpNh;jub_^{A|$(yKhXR~O+CB}-2;`1e1Y9_e~+{A`4^ zTb}hRN}9plcKyV#mae)jEx&?Jay%%zx_pJ{!&~y47aq1Tk3IF;HIBBCqnG7~)?RuQ zMCwI^=A)PAL-Mp1UY?Dx7kHi$`ab!`oS&Ur@263*rSM3jBBejb2XB1g1SP+gS3854H;pbP{DEj%5{G*J@ks%?hBiU6%&^wFI8&RGc9=*bYQN|i|v@@bS zH*)lf97~FDX;hrSG^#kVA!lmg&3p8BUFWE1iBEoH=l-?J?3b-FBL?=7GHd4kj@Rwq zf6X)g(q{H3(JhDMRc-v(Xr0gZU)bf4sGk#lcXa=l$1dsUDvgRdF^|veHZ}IT|H;oZ z&yj~lS{C4a}g}ZkcCF zyOgnIXkmIEmy66@&7*eB@gYv2Wd(W)@e)Y_e8>&zD`j1YJ z(yo5;KBGjCQV8d4vE}fU%fGfd`b9n?OqS^AO!SI>+^YYbji!y7lD_6xZ$W+X8E>s_ z6%V$ME^R@(m+!7U{PID!RU3;3S7)OC^Sj&kzx;-SGmp2ucUpbYF`udK6c4tLE~Bfy zUE1-b!-pPyOK-M#6pOPQM4$7S-TF7oI3e@+!S?r!&3o=E)i1<@Eu_o1qVH=TIk|rH z&;8zL)K$A@Ao>lXpXjgr-qSJ<&)`94oE_z03+Z+}*ofl}n$epn9wm}l4x;~59}FIo z+ut{GisZOMa>U(ww= zJHE8{;>X^Sb(MBSmV@ZI7axl`|K55Fs(oZvcZ&yGNSD5;JITMhcJC9itB*+z?yrdc z>xuJWyJKsdS-trOGe@i|wvaCUQC}f#v1M;9`Nw+VQ6hllAbPhG(>IvOKi>M@Gpld^ zVCLAQc(8?Z>HpCOd;falYwP5L?fVDO=6BH{4^K@zYU%3JXS}s8a+DU*WmMAd4@y_( z9&}s1c9x^OjgqeQ_M3aZl6h2`^Y0wt-IW*x|mBtDn>NYU05b((SInPs?`i{&Ro0y?B)PTI{OOwH;5X{-ob0aJ=&0 zSI#)Q{<(Otg>)C+$;bzXyNCyO$VA&8TOR*ZEV)E-+$HoY=LyAF6}b~le!3k-k{=<-*A)-8kS;Y6 z!jIC*8NHU$5>35@@IKAp6Pm#};=z_K-F9XbcV#8_%SvvM9Go?xIsYO2Tb6j2EOAHi z=(euApZrJdz=c|J-@mu|bm3E_z~rd6kEw{%aQ zkMbT)x}N`bFZ!ZCoLv2nc4U3==(e zCLi?f)sdRJNuuqKEf1~EwS2JWRgEoOy6w(c`x333-o4tcxGN^wai!JOh+^U^w6nCX zx-BhTz5#^re#OM=^X`?qd!ij5%glywx?=lAva3VIgDs@XH<=KwQ*1v%c4ayEmO`}S ze6djd)|S?&arwuG#Dgtey6t-9%;uT(%~#DFF%Q0N5zX}~o!uRh&xF7FqW6tIch6Rn zDP}nDuy^O#*_IIgODA#T`E2{<@Q3l&UbkWFMRa*ih-4?G7s6MM+;XBIh%V0wv7F91 z3y+`o7EF{;5nY}WVvf#Ik8aMk{j2P0>_nI6#Sz_>gigI$O8R{@jEdZeF3(Aa5_sVE ze@jjYi7w9xLG4nDM3?7;@ab!r!NkkwXR}9%F3)9DX+$1XLii-kbDQRz&r3tlG7f{4 z6iRtMVxHPMIrhu*b1!SOAkuT$ zH8}1XvHcCtk00=l&Exa7D{nYap4*9-MSlB6W+gO|`w!bF#!GYFEI)kQ(LKm#!;D9HWcg zsKa(l=0Q2Ew_@Q$H;91|9B)@z%9k+_LGH9fj&?~rk`_5Cjy57h-+xJ0MOxBb43Pkf z$iewAqIf~1tyoz8EMbWslr}w=^&_pC3B#6zPQB7|vYrKJf3sfg)SE~4nsrcb?vyV^ z9*)%1G;LZr%QHsnbv`_=+FyugPMA0Gl9N9gV>^4%deT^)xb(crJobKM(}{cM|93>N z7yVHu4QGs2|1BP~gn0MbPmUJ^d(l@y*yZeRRx3#kk7|d@w;3;^VlR4{zAQd-li{t` z992Dj+Uup|RzK7Nt|?AiLkTi)HfSco!H)+l>Xz9ji^4{hChP>AA1Mz9y<)6J1% z&sNuo$NfSSUo(QeC|?M7ow-TxX~}W5d0?l{UR)FP{*e)5LUdc&wU(5052QwQmqvA& z5Twgq9Bq<(UY49=XD@0bgw>?oYsBMW@t}U#i(1$1-d$lvGn{;F) zZ;_SkD=VQjPz#h#?@_YERb+{u6oR(IUX-u3cH1uPmAxpR?#7iz%@mK13qhY?FUqG| z<>j^OOO8E-px?0x;B#6_H#?S+`^M0g1x%2{ccIVvv}+wgrzMA_F@c9lD}VaSaM5SM#Wy;mEl%d z`=75lsvgQp9IeYvpIV@NA&kn}AGqb+!%Kv)g_rjM_M&`^pAYTlWtAyjTV$eq`h7-O z`%paoXdc*~vlr#l@9)UkACVmPb6a>B6?>&QPcy6ED-z-{A9Q9`+xYqLw?c62>_v?zCnN1%D<1a=K`pWuwXU3{X7F#4;|D@;4!XVCnN|Ii z{NsJH68j*nfm)z^A)F>l?8y@M6N0wHUX-u3cJrXUvKQqG;Szb&=Hjup5cCQ5qI|ju zT3-7q$>CLve#c(4W8G)D&zZHywzl4iC^^^jZe&=0r|I$u#YVk(Q9s>YjG{zvyj#k#LO2E&mQg(k;0w%it<;B^f*S>T9#Ov;3eFRE^7C<=MTuh&xpSd4XzcpA(PL%RF{|(FZ5~H7KA zTg}b7vJcM5Ja$n<<2}0LN2WDkukxHmLWJd5RkgMEWF9Tu%g4_@eSRay-%dLw^Z2o9 zAboF*d00QCS9vaSv~g<4vbVSHgqRHJnf5=2Nv1VI!gdJ*gm5ou!?qrzCAMCss&plLKZUbN?^ zQ_vrqA}}Io3@J^5tS}hb`)qHz2*m*@LZhreshAMGs3h`v*89Et{jGBjdEqQr>v{jL z^{#!sXMa1;X5(HM>}dI3t8(mBBjPXO);=?FYdMqpjL325zCrurkqx)D?9C_`k>fzz zrfPp^LhKdYu)QL!w}q;9|1(+T8qM6Yu5uhYrb_I8!;0KTje1p{A2|-hR9ACX$+!<< zccoRigT2oG#iuXsPJ8RKBt5TlWy*Qi!BfT&&7GR#uxiR+_hUTCBAa0qGaFWQ%U1O8 z+~=;|{^4bZdL_mUFe;|jJ5J0kv-ZZ**R0?2@q4B^w%dVQbRD^Ct>crA-Pu>&`230O zgKs}ph)GfYjV!b?YqWM+-2d^;trPAa*FL#@`i6rW9S44O?H)Sl$Nqgs)@jMJpS^dT z7H)Jb>^Z%?<VT5|q}N=(pD zCA5SUGg@Ws>4zhobw!^>1hvyATDw6k(({T*<(axS2n}Kn=6%OG&x)aiBZBdvC3{xl zE*;(zc`{Jns3UuZYbow+v4e^3h(+MUryllNol(1LcR-{iUX@Xx?u`ziVt-`T7|{_O z7Wx09RrF(r4sdJZ#(L|A>ThJ_d7ULE^@R7i^WQYPTTggXmQQD*pLpNb*Y7!SSC^#U zOVv~4BYKMLC+?hK+_>k1h4iSNRKH6)*qwWTZgdg5-jNM_1@5WV%@&#Yg(>iDGNH+ri7u%7ChN5&b-<(}8C1B*FuM$7>} z4R;^RTM^Med*$NwYcK!uq{F%Urq~H)I&p?_$Ngx;r^SFcAsuANNTIZ!$!`=D}0j6{{=65PC}aunx{p?zo%93Y+g!K0elC z6}KY$LG;$GH*HtW9~A554%OAu&Ie{Fm;FjCJuz#(sJgmHI(WY#`sA_mwySpkCWg>q zv3JaYKH<2teQTvwc-T=pyN59zo|OeeE< zyw~%S3DMT~+n-!N)zzOAtB1sHQ=gi2 zoTHroS}Z;DcR543V~?6C=P!$SX5K6BqC`9YZ@cEINyn3_-Rs3}GYg3`l*^u|Uq4mt z{#6XRkMvm89hYd=@r#E)fjuaO(9%48&QR{|&iO4d0bRSiArtNWSUUc!v*fGt!>kw1 zQ0~|VPwOoCqx`s1IhPEOp~ai%_hP*QMfe<$vsnak8pH1+A%3gr1hJL=uCiZhhUh_v=| zMfaGZ+qr7Ey%5c~wRWL0ct#n#Q93v?%H>~iE>e{|tSWIOGHXOL|9bC(D)H~C#1Bfx zI8$<2p?d$Ws{QlRu4VNR&0XN0raq`0b-8qKhH|;n0`WQRTE~jJh-mJ|)?U)d@T~l} zLOM7z%B>TlwRP|lyAGZPMDtu}ZLSmUf6B*x=@@59E>FJJ{w<#6x0MfnV}z#~(L5i6 zTYHD<>Y($16Pa>(g6lWE)eXL&x-wssr!&!G|M;ak&SC8jbDcRe%B@b+nmgx~cC9-O zyA09nSL)8vakDz7yV^KYa@kR%a~@T9cIRZbB-;9_pMOtX?YM3L?rNN&T;2@yJ0^gE_?LIKwUU>_nT-Wh<7tNa`XDF99&e($|rrRrTlSF$zmX5QY|Jw3L z^5Ywd6=z1db#vAeUY#XBp8Vjgm}s9X6_Ncq6JM` zd!l_lW@cM^L}&YLswE-=o|+kZmdx)M(BB3e@g+;IW8Sy1L~fuZ$!u{J+s>&i1s)T=GBS~*b!mx z{T)Gcj&~!*8GC#GBsazp1$&-Wr5~0>bdCeD({snl2%>XbIx@PJ<$NT9=#2W9L1v2R z9H&)|YqD#Y+Ze|xzu__S@AZY?OpGI2quM8<^Z90$TWGP;(P)xHy*k?zsm@h;Yg3DG$Y9okVF#5luPF^04%EwL=3 zbDSB>?1ksK4~WijAQ)ZCaz3oXtBB61>zjJWU}i0?N_0v}t2&c)X%?$1Q5|}E*}`e&6pCvwXQ-+>4~ z|7^}xW6mogx!gMP1h5W|v--?=)wA_I-WtJGw9rgbJzL)c;S82`+D>aHtGee|akk1# znvzRNM6gQo49>Xe6Vo2=fZ!_ok#%K1#9S!EBJ_;0a(u*A=&N=iCc_ph#)J`N3^!g# zkMExJurkPqY!DhOR-DOwXV1-~+?BzNj_NW;AJ6zW(u3!dqVS_;4s8&O;b;}TWvp0l zBZBra=k#xbSfuBfHQH`TnVStl14oy(m*->k6ebW^yUZplzt&p^Pc>RX|3(CDx3}rj zE~^%STdXLHIj8PX2Wyno{{QolQKa0_!n7# zsq7RamSS-NrizQ^fj~T3DA9Vy*u`2bAL-A^DnK^f6$%=i{5nRQZ zZq2+}@oSgnEg2#9QU6XpSFvKmNtGYs*Dlj4v5z`pT*dRzyjt;V=fSNVW0g^$f32BU zD}L?F+}g~ubHG*fPw&bQyVRbWbC=a%1Xs~NeN#_5#IIeNTbn0YA~Firm;ULuo#co3 zwJUS(a_6K~wTeB_2=QxI=GHpr)tw!MxCc>^_`9-7{Mw~Ccht^Rv{uYacuo(wiV@M% zCFu~qc4lrZqy22`6t@yQbb8DG{aTPObUak1GOEXOEd7eIu0{zoF6IF@g*DlSi zWi4?P{i|ws?Xq6EivH>C_|hSMZRgfWSFf9pcx{%&j#dPX?~y z2`*-){7BDjRh~ZMDs~_9YQ?Wz1-CZ3zW0YaKvq8e(=Ydm`6+(w(%jnYkVbG7{pzgjEBPUQ?cDo3`$SrmQLs;WcIhv7LWo~G zw~le9`UfTHeKNA@fUNR9r*^KQwSAv=&&{o+hg`*o=x=1wA%5-B+*-zms~Gjx%&Qf@ zc4clYb1<%AX3eX0SMwgU=Xncb6zHG+zN<4oKE{^hEUquvyqV8@RA1k5h*`Ebm@RMj{wRlkJDk$XFkjA_{6YHP z9i0C6@&0clV_#<)^pEG>@x%AtYKYjlmsxCxgTY_rxf}1&5rqnUAw=I<20e-pZ|}a< zumm|!5@QQQ2Yp!Gn}*arIrKVpidi1cnJly9_#vC;%9PF#68TjkA7ir{j?-UFNHauE zNHZhC_P0$dQ@5-p!(`X=zpwVpWMZuL^TB$T2laTnGYJ}&AO}ifto)5|J)u%NzHVfI zhU}=jikMuZxL(O&E3Y-GzK*S!3?cBdCa-J%GkyBK{R8T3g6SR z4e%1;w1cjnE#kfVT7qn_{-?w~M-3TkuzG~n{)e}i-lvR$5cgwsL-|;FH}bWDX3QnH zufaXmTg;hVO+kD%eNHNuCssb6|5_rNv79RpXa~F35zg@?l#z(-X5QkI^6Y4WbS=fm z^6o?X8nR9I5^J|s*Q+&g^7(dqzI>;@mdG)?>N)=QW`Zm>=O@kcT>sqXbuLsBcj5}_ zmV32*e3KI7fmX~^XJ)vMZ4L&^cq2sHu4!eGJ6qUbF`k2C(G$rf_x~6vCo;S z@QM4pMVD=rbY#a`h-NI$$`j_h-@QcHmsNGt9s33)G4{~+FJ5y=VX=R4HNEq!zCI-q z6J(u3%oG*B(r4Gu1UYkVCey2!H|cg9diM|6@sHU<#7!zBu5QsaEa^Y?MtZH%0iPsF zV(jLzf}&xrG9vbNCLL?VPTi7@IQI12Z-`Q<54b5yHSxy1kdC#mbybdHF{MSD+0LSC z9Y-B?|J&udPuHvo@^EaH-|Q%qt-siiCy8fC4c0bYdf+qtal8y@;$S*jzp&BPgJrg7 zHf{JTd-~srC%%*A)1M6%Tc7XXXG4yg5s@5LG`&_X2Nlg&;g3DVku`ZN)~1 zTYT5<{TlWG%0)iL&RjUd|G83AwEtODnNir!*#C^>`*7O)Wk>_jeQQl+p5xrckE8lP9|gyP%LpQC?dY-Q8tVoB}CJX^IiZPy`Y zwC^%-VaUw2mpP}W!^j(J0zAwS~fuoYK9vi|%vj3Bsr#P!k-XjLoRtQ>;xX%xjf>ri@+WKyJp~?1&bFJ@Xn$dFC~vzBpc0#OmhF z#XmJ4bN5PViibl@P(#K(PXAob^K4yxrB^-M9xlUj^v>9uw7=T-cAtq5v4p7A=7UeR z8hd?)jq@@g!Y1iMqoT%7lk1abaNIt={<$-Cbw}@d%KCwtAUExnUQXTXLmY9$fh#id z5h7#9$yidq`}MpCvHUkXP!rUU_S6l>??3aORwxU1ddSV#p3$%NwIYt`|8iLD7PdXL zB4x+p(LOb~!L)XCa>|T$(|vl~_a@74CtuiK^ITnhUBmR&%|I+(=&m0wD}462aZ`&3 zuax;KTKc?wYaqn^rV|f7a;c}k`%pK1Pi^OjFb?o3<=V-o+7W|keC7T=2_riCY&d2^ zEWKA~e7eO3>#DV&5-uNe9cBX;PPb0UjAAl(DI@sebaeVmA4zyfF)GxbnpOH8g5(0Hc z%T+s~GtF*L^i*B_Ag`yRCfFY;N4LOv2Yg7YII^5djCKpFy~u2gpQ-umukB@0IXb_d zpFR?okya?n_P5;={f6*$-dBU{*hmN*Keb+Dwk-LN10^xmB3G3D_WF7Ai=^2GENPrr z*s^(bDdV}04NYI>6t(z&t7)uTx*?5{wWlNW!}WS=AF8ca5Eq8zx3rG<<}>I-LldIO zCw>UlXSY759ccF=897iZzTClb+i=w9j|yJIQJWCL|D3kJ_lsmKK@OC}*x{sTy;eB~ z^W?G)2GrM9D@%lrvFa1g-$u#P!Q;gIxu?xj=A5?Kkl5EHH@xp#sx0Tp?&Gz@VLA_-0vF_=6A3NXwBCr;s?PpvC zG2SNEUSj`yTZ7W+9Ck?xg4t@>*=>K@N2Tp=J0D{;*F}q?3kw<6(tniOZejuBh0y{(c*S&JMZNV zk?F0A{b9F!xFNrB{Bbw=b|fzml%1}6m{1a9n;MT63s3GgtSr@$qrPYdN@6Uu({uje)+t{5WpjaY zTjq2&ev68fIj;ZCF?Y{1o+amLe#p6nKz5fb&c*@Jks7i#L~<<-*6z0apvkcX<1s;G-HpG@%W%P88Wk~ zY4HgcB?AGdx(_I<=nv z^?fYIzQtY(b1q<9^lq6f!)$%tc5(;NV`~<1OKZrnWauLoH9Yz1f(-q58Pq`R_sx6n7$c`O#^BbG=UoKBM z*(`tI`jF?C)KQF`wTxp)YFa*{L-XZwjOlmFPmX-ebBydL+{dUK>uO zF}9`cGv4Xd6TVHFlzEP`7JHVl@T^vY-e z7NS)|hvMW#59H<79(yU{3Oy%!RK^ayf5ttIJ>iZeO$rBkBJ{3|-MiRPEcq0}jYa*jnw{m31(XJxuE~eFaZfS$Vm5K&L;0lLmidlL*=6)Za@*mY3 z3G4&3L*%5yM#U&$m4BOb1cA{B(}92uBId zO~yR84iuNij^U9#R&kuq=vP#&t~I>DqwnVuvtB;uBG>ir7&lL~LKYmb;7`z|kY4pGQ85cs01gYh2}G)G8*> z>!YVu5z+o3BCf|C{@kN3NAH6zihPXiceu~X?eG_kPiv}YfO(Fq4`aNgZHK(r;M>)) zF78s7I=UJ^`mdB@(u$kTl`LS~9Z7y=aXIoOK7>dj#N^Abb|GTkH5cRf_?2>eQ&$tB zX(!VnT0FbB*f4iw{st%u{h;dM5{Tnz$YMihmqYup1bre(`qvH%X=OVl*tN1nWiiT$ z8qyAcIIRC6u*8nGpFiy9l7B6KO^6G{_wPY=)C$pzZA-bsuQ~S>UpKroTn^7?Jm9`U zvYq8jE4sKCV?QjHwKkM9IhdS{JI}3@8!i>6)?GS2SnQdd%Jt{o2CRjAYU`Fw%fZ_= z3>V>LXK?4g@)@6xUM`!wD{sPCi$0&RKeOHEx4Lu}vr~p~qSGy9p1k z;R*+?04Rx~YH7jZ?fTQ)Fkz(ub;nxj%GqZBTRyFCXW`j&u%Z?E67(^Q~Z1y+;u>ZNLUr=jqHdxwl=OhPXzt{0{%@EtYbD2*@L+X}jaVc@Of-qiM>=XEBf?RqslSy`|=JWDH0^O_H zZbmC~i8YjN6)h%v&sPvE(*>X8z6sLrP!3nUu{X+EwEP%f>y#+Z zls-xhRSH z{4_IExfCtRmxxvDK&@27r5^(fdq}G+EmW}IO z8GU21&lSc_kFI z)9U#SmLfE+&JVYZE60=s^ES6=;jn#|HA88*gS{9D;Moo}IMP&Ux zz-${OoJI-Cr9QCOJ`jLCpM9ubdG(?n}b~UAhZ-O+LvzXLd%h9P-^k+Y7 zi)8~RX;=&MJye9l@@VbL)^JhOvy_5BO|WMf^AFCU-@EQ1j=p}VpW18Y{7vr@0A??M@Gp{tarukCJzDbaqIWys%uzJJW z=F?J*rTU8rIle2oILL>R7+amQuzB{%F{1XB1_}pig7cB~iB;E_mly9W2DoO^QPz0< z6yNBOC_9|}Db<_m%X`+ElSXtFE@QLmSPQc^R73~gu?ExYG2&6LD%#}tHGM8VN|1Ue zGa*{l>RS7pJb*ZA#${IWOAvvQ=(ev_0d5@=DN61wpe=M=?$dm2g1odblL>2~&u45} z+%Eond~-~ zEN)6!NR-`#wbV80XVI^`&CMoaK;xqtYJv!qL_3+v%XluoFmX0D!Cd@LM`Q6L@$#=g zN0U+uyae4^8jWJ@Iu~)`Qi6sE%%8w)2s#M|))14sR~H3F&sDNTkOL(#7Ap_)n?Zxb zp(l%zac_XN6hFqEKWihp+{-W4q;9i$pN#Ac)C$pzo%+&W9B-D&zwLgmSdM%siLuoA z_jnWXiS@2!G9x>#)QD!x<5gwxb8{WBx7B3Da?BjTR-p6w#eKZ(s8I3b)EzVKMUYRm zBa-J5S9aAG0S9kuC<{4oEKp3b#du!+Y`8c#rl_WjALwV4L}#4g>-gdGZN-c5zm>6T zfebMm$24|(l;v6OM+nc(?i$V<hW`3L|mzOB_|a#gm4X}s9LV&TJ~yTB5-fK8COe` zt0MBV0R7yt{Gx+to3aBy4%|zSFX??)>mE2rwD4G*jQa$Xi#v|=Gmd6IkPPa{IX!TM_vX zO?#iE!TK{g(LbRRJ)PVw5bMe44?3}Cv@~OMqSx#vdOEpV?2#hmLv0y5`8Zf#WI4&3 z9IcD9_z!=fPI7L^a!L55y*@lq^P6C7N@kuEGZgkvF8L(23?D2 zUG80M$g^T$eJsH~N51s9s1A|Tbh)-jDsrgvgJQ_~5sHgmYm&Jx%0inE{jVLi7;-|< ztGlok%2g2*t<`PO+N?!gw_`2z26n{1*|?O$qT8auwtuz~dsc|;Z+qT>9bs!XTfP5( z1mu@wJ4m-Dkuw}hu^qT!|drSX9P+o?=|Ae;c8{}VM2R_a%L;eX zfT=E)h=4eGt&}Z?h4M@E!&Lhb{l^kJ$A6LS3=Pw>Mf9yy+xQztm&4AMfTZbi|E}65 zT9wtQpi)b{pkfG0N)egGBve@%W5Y1Q(vZEX2uN)%| zwBu4sS4))h5?Otin=&f@G{J72`oXmD2cIkd$VbO zjH#ke`06EcFRQGt39M{vme<#W*@l>f$XKE!ir2kXUN2VPQ()F)ys?YVt4Z~Y4c|2~ zmH5(E6mW7gR(J9xt%7FxbFX}r^&;6l1(u*(ltgc^UX>E9x@Xb(rh*Cwwj1&>w*BQJ zE&7|YzV&$xff=8e2|9J&1^s00D#nQ1Hm!DO%e2OiE9oy?YY8kF{B1-^%XSTnFP}Fu zp(I+PYE(4exm#7=G}s`peX!k75@X-DX4AfvuBNw-Y^ZRcRw#*bQoBCZ#%(UFhhM2I zFwYV-IX7`Z%Ej{17=GE-=jX0<)pLxWuU#@;=k+fhOj&Wajd8%PMkdT|#C%A`3ao0N z7w+&>)8}LrSb}^giLuCcS@jcX`Se)F@&ehh7NRM$KX|CVZ0i7R^tVa2`H|s~TW$E7 zQaWIQv9F<#sgGk`i`$l!#*14_WJhw^Fuh54cP;y;x%~dV4=F#YMj1;qZKPy;VwNUj z&TO=vP0lnQpWR16V3wwuFZyIyD}D5W&)W8@TNDIph1$|QZ#_oOd@!q*wSY;n136Gz zI^E^#spsy#Ok2Os!ckxB4;4}G{y06QoVVGr^algB3HcHWWVdCsA!XKF@X*w?GyBU>+fGrs537kruRT zrV9EHC-My7$#ACP45s|6n32NwRFwJ8?^8H>HT1ja^XVkK{knF@GqZTyU5HJO@>rg? z9wW{7DDUxEZc9>w8Pfk-ZPVm`@>@RVpCJ!Duw_#j<_*-B-5Xb2?kD7aJpe zk9jDy)OB!P{0;43Oet}yS0&;0BEKbN>>PRagu8+W`a8EJ_oEr|>_!{MfwniaZ8J*= z*YTAEvZGciBI5Eu{ngXiymQk991+N;uIJ4xH?_&(4a6wNT#8or9_F^(*f>Y#{mb37 zKQWJG_F&4C?PSYt8@Kr{t-!1L;;%V51(rNG>SRef6ep!mRTJ_tHuU{KeahNIe!J>u zjwOh|b)NQZmG5g6+O-g^W~A{AOY&OA99|+@E_O3T#W-8u%vd6a&2lp#n#NVn5WQ;5 zc7DjomtzScaA&~Sgf-8!njVL_mf25W4^qyI1#%!Qzj7d_yiU`eG=9bpJ!)#pbjm2f z5rdK#n>pmMcHjL7PyVcOP%e(eo|%b!^twjA(X5jL#N`&NZMVo7ryo3jpiPY38k|G> zUE{K|D>Utt+m+ z)e4sg5boJmD;#*H!jmP9_Sqr&lH2?F7>CjvWub;DBH(?9-pIWH>~((L1BBWbEpKTiPFPrNoX>l?3`%^ogog&Y1`5+Vvqk zbL2*ja&g3{eI7shqIS)cMI>+aQG7erQv2iZtA6IhX5++%pV>LyfMTRbjWc-Gu4s-* z8Y`ynDZ#PC(f#el6Vq475tJ>2k{B!Kxi`7u-T}h5z$Kog@W+i~cg4vM1FM-3@mmij z_BU_*G(xbqGdb46XbXBG#x76mWQRdupTZ)fGiwG>i^$L5FzB%xDUGlr4CNXD21%V|tbaAIya`M*NCX~e3=s&WU zo8|eN$IR#>zDB>@Sp9BfdKNtP8qO}-S@wIAeC)xQxGT@^K2QLT;IX) zqBXtt{@zy%zO;-VI{B~Vn9Yy5yo}{I>S8!u`zKE}cULlgkpm@BzUcX%-Z74u#lpaD z0%f5lDk5ZWHbY$2qQa+jON9e-IkBY~dtRcyA?&rMsNbWeVmW5VW0of6^_AG~eXX!b z99~yJUq?~}oS8Zs8J zp_?IzET3^VkJ5u^Ikq(IcZ>HoM*qf0*t4fvW*}YPGG_I9}kq z@`RJy)Ww01E%ZYbNJEFY7 z!q-PCM%{f^}4OOGm6u`57_AxO;XZ6OAj2eO&34vRf(-jyFE~X^X?fOsZp!J%7s3 zZA_GcNb3D2k)&+5+$&tM9D!Z%XWGj zJLK^-Avf(yQr;#tet+6fdvBD$T64FQO!;o9YaCeocf^kJ%``)Bci!z%xTx%UI>p0! zGre`muUPCJ2W_HEr;9!%jy0iVVSEJ00B5@Y9U<)%d6fqZP|hD;2>CjZYrY zCI|nvew@sUckZi*j02tT+J9;)z@^`(ap!NzlX6!5nE*Y(9_Nh^UTS{4a?Y@(dz3(S zM5~AxYZgPO(?tGmq&m;B-PAQIIR0<%uQ8MOloq1|mY`=)`#kL7mn8AC7tgkBw1Pn2 zj%c!D)?IJyKYxX*KKd&aG0SJTVZUn+KL}Ioz_!Aj0b_MXcjeV*cjLnzhS_Fq#)!jOh^EtBi&@^ICgk9E*NhW5 zGO(7~x=SjyYv@e#;}FdcoOd`sRK!sSqq*tkZ-x(+aRR+1`b6|A^fjxB&9oPx-8mzF zg+2;BgX-JU&b?0F<~o6=t{f$>1QDuMud3foJ`iH%qYkKR6s}9S+R-cQ=jVC;j^hnK zUk?zto4}UFkxx<1?fr!3gZ<{!HLh{o?;v{lsLaMnrkTc6lWo@CPD$W?2fCYcUK}p4 z1m)sPW9-}ZGUEN5N!ottCA{V)`}Anh!PxzDBNN_W;_U!s#DAzJ7Cl(1LGZl1=#>^8r9X4eiw zkImUNSADG5dcCJ;=u^d5xT3EKYvBl`o6(3}hC#->nsxeEfwfQ*6;WeBD}H9`XRY(G z&I$+K%HVwqMIc9X;5FVm=m~|}2`oWA)RwZ_>h($2(z)w(EJ z;fYlCMKUqeC`d6LR1h%$Ozx5cfokMT9@r z9^QDO9Ujt1LEz0F-s91C2m9a9%DCUuTnDvK?rV_)xhY=qeuDP1R}r)C;89}C>Q5;T z-%c zhN{&D+I*tLelkTq^!fDdg#JDCY(Z7LS9bo$kpmGZi8vgB^?FNldr$aw(RPB&;J}j? zN}}wx<`=YE-!2w`6)9@@-OKLUIY}^^HoDGmq?T@d+E^FJmr)p8> zS}S80Z>@10(>`&w(5|<;WB&8$Xyr74<5ktlZ`nBQaY$xeehN_LIm$&o#xC7XHBY>k zO{+I(tg>&%nTlxox^c(s<_Q%X^jd|wDw#FtsnMg-9evZl_fdUG z)8n0a)1_JUA(3qr-;THM=;!Ink+B;L>xcd@mnpCAme5nHTK)C%GB3RMtX8Lpzp_Rl z2d>ogB6mw|-sj3*^Pya01g>PL39h1yWnbAqXsgz1&Mk{8>p5mn;o8pFMaLQ3>qbg) z;G&Vrz8&SNh|KYAMELh==En1!m3;|v;0}i}2lRbB>Ry7OsNZ1aG=Xwy4rau%=xe%Z z=e0@{@rt8}7sXyI_DCAeRNM_xTkSco9r`csgSBv;tBB4i=d~*r{P@k2>5-z0(=YBB zk(=^G%U;lIvA*>b>!Y}s#r`cMtc4K-y64PsLHk6prTP?G!de(xP!SX((}z)vtR}_C z(5sm!xD`3pd|Woi$}12l45;P z6zfB|SPQjfOmn=THKa(Y%fC^zjOY;Vqmi3V+iTBj|J?NB{V8UNeSmF++=R$>QL}%c z31uM%W-U-o5#0&fztDuWFlMbHn#s}0yBGHr$Gbk#@NOF;ccTJbEHTX@Wu+9`ccTXU zV@xvgKDyhXXBeUQ#TdSq?1*Oz|dFvJ? zL@FV$B;FxhHcD(HS1pXATE8UO@{k#OPql6TvDW+R!(@$X&1JQS*#8g2JF0E_kF_Q= z3X$VQYnjD2=Kq4gT30Rv%7q2}<>+hkenV8>6}|U0$^S(EvDUh29ptIzEo67`yHSJfQx}~=quGv}?+p7Gil)br# z;|8IAua$7dQ-1iq>^H>WAX9xi!Y0dJ3wu!I$Xv~lH+C2(Mm9RkFBIr3V_temzxMyi z-CEyMYCD#vbJ!)(j%@HszSP)TJe{^jbJ*8OIxX^+VgG5;<(Q{D*O$IELfpU5ZcBIa z3q6{P5%n{P4JQKR>;)!yX5u1=e5!r#TKkDNZwiUn=`+mpYX?ZTs77)?j>QuB5Y1R- zw-fyIqk`(=J(Tu%`=B2Wf}wUPH?=Sk$lu|U4vIk#}wI$dj4sD+s57bs6&36P6# z&XdT8XvP+wsce3mEr~C69xSRp4v~{)_{)oqF%tQ3gwjh3zhrIxGbws)$}ar+50$I$ zddovMmdfHGBjlWKjby8{aS~@5-9a|1tgX*HKm?H0#cHJ^=;cS|*v;YZ@+f_@|9&aqA8{VfZL z<6TN${Y>?9Jkh0zf@ttzgp54qDKG~QES3HnF1&*xnnqpj{)MKtMGS3wN&3X=yvHJ3i?VL3$b+r zwKjJ%iH(EX3-qE`>)@cF(&ee2JkfbRX?0>Ey)_8?%p*FqS3GrPeYpHOx`kX48Y@*q z^R++CJr@@gGiSC`MmyFzU>qVRmTfI_pR@V-ue~m6o4%X9V+sZfESWwyRIc0VFAMjK zkvMNCgRbpC^OleEwUdp)m063mytjqOWljNdyRdOgZ|Y9|h6LZIF!H*+%LY^gJZrKRu)2>xYmozOvaPe@w7tde@xo`i32afUg+0sI2kOC+;h%YL>OmYC*n`;r zj4gV$SPS1=PV`$^PvAVjQHkT2?guS>_3hQpahHNkIL<+wA1b2fgsaJ2$TNH<&!Bn$ zTxEWF4DyLxYbVE$_sRDC2v@z#uQd_961`;Idq`_Grkj{HY_ob9QB(BO1AB*GH?tQCbaF(`tZTAA1dZld&qa;zVwl zt_`OZ2UivxOE|_T@0C`y#lTRO7v4Frf z!9KX*5h(9n>Pb6h+Zy$5TBHbBmRH1t=v%TN)yh+_|N z+$9byK?HKstF2obIip*jUDYcqcHlk;+mNCkdrTs7;wzr7_J?8ptYw1^w^%Vq;c3kb~+qhYa z>d%Wb6j>uSYS>mWr-sRQX?`-2`k+_vNcnPeV;M2VHb2hmj(XQ+O~kfwo3t~1N6Cby>hZ(vTeyD2aYIV-tND zrg330a?55jvMcC^{_>CHVRFP++p1RRorl=`cWp7=@+?_|`^z$Z!==y6t@0B^DGXji z<*=Zg5+yPAYE7gFeB#F!yZ!WL3){#X3x>+vOV&%&1U)KaA>RjyszWV2bnj$u3$P;s zB{9~&en&BASx)iCm&)E7cl%4XoWrH}Bx)-_H;HT`dH!KC|D5$?M^lG}!u?K7Vac-6 ztH(=!dEo9ad29H3i8i4m`Udu^QNro$^yKe@qWGUd?c|6*LSj`1KOe&HJ~LGx%V+=E*9uqjW_f z_Wh_VT3;z;*m<+9EZ1m=jM}(LqD?4?e7muOI6I)Oc50o2`1?Vi>@uR4Y`1oiL``tL zqA$Lu4iG>59vEttKEsh65h#hinw_t=h^ujukGn8|XKBz*{&9A&w4Pig5k0<5Px-;C zw;Vjlwnjy6Gl_&l<-~$gYYl6P_mr6y^^x6Q#!0jZB~hfvt(|$#;Ocs(OJ2&#iL0fY zH%K;H86Zncx1Ca-c$5}*s>Yj7ZEq}YgoaAj0c~Z6aWN7#QSET2Gr_ltF?>SJoFd^{ zsEnXkWs!0*a$HbP+4E;_dCa&-K~w%!s}>^C;wm1L_26g+B2bboQq)T1Uz<(zIXs3IxTv~7-O(nL#8}IEXL*OfJ=)Gjos>Su_CYk= z*Dl(~zphEs@;>M!uokut?r`Y0&qN#HxIV9#vA=-Q=V-ZV$IzAiMfq>ldFOA(INE^- zwa?47Z7JFnjn$R)g1{N6`o)0-1deLd9c`k0Vy(tvS#%i@@7h+G zgQy9PO7d{-A)?F5gS`LtV#@qLggOTwnk$A>At1a-$b&)D*vgT(H|(OTE; z3pjcivlMqgu(tSg$wRza8=}~OD<|#@=nis)x9HupqKIzoqpatsJMJIoyB`5k>~(h*rE?}~ zxay{tD5!pQAqaEi9^js4uRLIiT#}P1<@n2{ZI$DK1{7o75o;oX{wqgAFW`&~ri{+hmRSmg%)z*^E>(RB^kQFq+K z(>q8uho6dVEPQ)9>A3SoG@cU}8)MVE%P$PZ9q1iiYfn#xoWDX0dfua@K7fMUT`R%K048cy6QLoQx&*tLv}>t8JDu|y9VhU z)@BJh3viqHrORJ*1U*m#L%yPrr+Ljh4>$8q3Pl8uCG5{x>dB=T3+N{gDVzQSeV zLjzh{VN!%#^rMN4uDDQ^zcxw^8qrif8ECutDHZg=kX&`BDBgS>N8QnK718t7X)R!} zzZiMqGDqDJ-SP8Cd16XaSuerHQSYxN`lF3E`Iyy@ImX-3CX_^9Q2tp(6du%2j4D=w zZ$CalwhCz>H{Y8tpZSlFi}$sV`|8I2W=HUdIXpR~qo^_QIY)NX9ns{k>Q>NtMhKCX zR$lBVFjAhY+EhC4UnmjXbbYuyd9a1dpMJw%Wtc@9Gr5p>?&~3{{v9SujcOq`CB{m; zb-+6W`li!IrW+iyi%nf?C^uNhhmsgub*ze*Q?tH!;?_>Fe09n&xvZ7H?D}e+JkxcU zoE+*eTX(bVsbd~p;fFi=2)B2c1nP^{s)z^LCd2o(l||q=uGoR-w|j@mR4;$|WQUET zeFw9)Xa7NNJ=8@(lz%@&E;`&=dR>qC?UroKjd|Ma`EU5>x9ydC9K4lLE&n7gYs1Fu z;Mq!a6et&O%!5X+9#6uB=?;Au~W$jp%ea?SL4QeQSiCJzXZFS5t{)>akn zKIgpyN{S9E$_lg)+XvB<{ki>zA)7J>)kjj*RT6JE9ruvsLoFPn@~a9}$XHi2nR%sBB)Ttt>UfW=H58 zvlg@^O1o7$NI2XbB**j#kQ<_7B;MVjO^iL5WY!j0qO@*hR0Q54BAULlP2=`xP$3ce zJdWdO3(rof9kb@-5nZmw^MapzmGdB;om4ygyh`(R#u?_Rrm@PI6VFs=AAQUFPBraC z*ca_q-mU_5$6AP{2;|YlT4w(=?E>$noYn9ojFRYEVcJCAVB;tA%K0Od)#PbKPqTZQ#9Bbhi!&YZZo@lBC#kSJwZ5*N8*Wx(F zR-l{eIsS%zmivZxE>VhBSPRi~cJBFpGs1@3Tqmtf?E^jDyZzv;*b)Lp? zgyWn?o9HWolft!bHL~(6T}CQ5?&w!kt)f4^O&T1d^TPc?l^KP#5KX_YmUxW2JuEJ2 zy{#!wE7Tpm1ie`QR9nQ&sV-_98^F=ypl?T;$hVUh{fE40H}azBIdR2Nz3A)EO6Ijc ziVOL=nd0G4cNNj};4a?(fe?c~=M$(E>W(V|eJ|rh4N)Pso(LaPOR)o299*^OTw64^ zKKA@eKJig4WgW!b0IrGjD`O3sBqvmDD%#I2rL1bGyNYPNYCpfcv7IpexW-Wv)E(D$ z`r`Y!ieg)+L1g_{h2uT}cT1`rr4uXbZ;lriN6j~ty$@=FHZeA=ewdcuud~>9{*AIP zL4>;Z@tob8-!Tsq$9`;7v_jo+uSGXlS}{@HyQvs=Fo%M`Jsj=^DLP0y%WDS@@J#1D zIPNBKPp$4O_btw&KM<|O+J4Ox%dr;jgXz~czui6fJ@+`#@=H-=XNk3NugzEy?j$A| z14J{Qa0BX&wQxUAyVqV}qNiIt|J&h?cb!Uca_Vr4(IwLhnKkbU+3!=Q^uK3)StjG- zCma9rIZLbB&Z@)2$7P%Of^dItEa|g9PWCNnHNLu|Nt8slnPFj~T-|u?wbkEy$g$b- zZ6jA{Hk5^X#7dOJ*zf^vV#H)0vAlX^!{lC`^68W4bPkLGU|fUV8~E22 zdAHXW8}ffWP-1wX%w_DGj=MivzDg<6X@)mwUF3G$&Nno$EAi}mx%h|AT# zd858~YQ$49-5XpVB-Uh2;%CQQFrc;A&xoe4S-JEOPFsKQfc1yHumt%~67^t&L0ETH z6*c^t8ju|=M>MU2HyVqm8fAo&OP}OZRYK&KyB+1MQIjNkYSlAbz0yP6t^a{{?f=A# zC8!BXq8HNdeZ)y`H&L(Kj)Pc&E3&$(84nvpm|rE4-K$6vmf)I!lIWWpolN3QSOw9s z)5avMg?6Zj6$`tI34Px3eC;b~Xb1X4w28hoxxbgFll2A9JL#YqYoW(c5iQMLVo;76 zBBI_@FN{Z{<*HT}BdUnqDO`NpSbc&V6Vtc9^@6=8^R6Yi6I#ID#c z$yf_pK}9S%7bLzHzso1)d6tYVit|Hl-F@VJ@{TSj7X1^~5N9Wja2)ycQjdI9VA0kh zTi@qi4kPo)M>Xc9dj@PPRjbBTp`KI|aS)ERi zlslMunUC%^K%^9_>y0Hh3LY^|Z@5He?p8yhB*rYw_i1|?3=u;QFZZGni=AW2*+Uj% z`^9o@MR(~MRLEMj&>Z>aAB~73@}Giw2Xia&WB5{=9ag&?SnKsSPiso=@iI174?<`W z1@-3CUIU$Gcwq@yZnb+}hShp^rS>beANrWVPo9q{d?PMwclXV+t;Th^qT{liOBqM_6 ziq(FvifDSTR=AR$c+e=W`nZ@8K{LtmTb-V}2 z+Y3k1DA{gpsNXG6Q$#&om4qeaudHxCn88PO^vR}Qxz|}Nx;Wj7d`X6d*dNG8UvJ&n zPA|Rc1--voso}WVmUD!4cKenx>)`paPS`N(s7?N|?p51ckQUBe^*XP<@vWmuD2UL| z2&;F|rgCYXg%Z*9)$GxI^)>Gv@#|rZNytII#A?qFsxfD@HPfcX@>G4>o$%b{z4Qs+ zUh`Fk8fGl<7o)ANd7H><4dWzAVr-?>LwD@?nP-aIWyV^lm5K;H*-4)vK)bMXKX0K+vbNACPys?CKuU7kR870yCs8a*9l6!MBd3htOjEp{zKIqE{MveNOY$|2 z9TETUij($LJnxby8?+xluM`Sx8r45h9$GVyIBfqqeu@?~%1rUblJ7~iHrdfA$@Z(d zEqVWQks^~zJ#SoDaK)+KeX-A@l8N$EqfW#T*ggyYkvvZ98k*C9B~gb$efBp@lnH*l zep{oKpZdK#`(oQBS@2t z6Qo2*baxlN)o}J`l*r}O#DJPihPFccD9$jU3SSUJ-&%Sw(i=Gv57+Z)`e3N%RGpf|t#kUyKtj^A?yD$&7Lj)thhW zTz!S?KC+_Cj+9?^)Sdgz{NM_G`NB8AOuDDoTNG;{nz2e9vS^>F&-V?s;3r{GFtTYSm}kba3_P3(g*u^ z`)H?8ZLyDV9PKy@D8Ic(y!NSim~b3g+>Dx_T$DsBPNpfzwmDde<{-*Kw2By!*h34x zGg{2@zedT}zuE*_8f{|CtNk=>`t!je@mU1NcE?(Xw*6W`HuJaI(PE%+fo&va^ev7U z91D!SEE3N@kmU|!IeGxHJY!#qbA^62)F({O;}Xv|ov3a=e??J)3?GG_kAA(bKx@5g zctP=W^>}aewdgs~gHs;Bx?p|4Kd1OEe$asXHe74b&(n>&N4yq2Doku%u_p<4thoQg z-lUUPU^!7Eo3ALCXPr0h&vAc^J95U>o+vKb8k>ucrLKEpbO6sgv_@q_6BrwnZMfKS zbscZ$IY^%w7p=AFwZN7emBEg>Pn^@nI+ikJ-RYeMjrRQ!dhQd$ z4f?5pw*0FMc0^ZN*v9%->`=LAu?>-TLWn-(`Jenyw?ejDwG4Jd4~uMLElByIOJ>^; z&b1orM=2}paq+gcJj;w7J)#|C8*3rT*nA#sL+l$LtuLMKZO-#zLX(Gz|2teTsM zId#Ab&oYRnJSnR^gO=`Cwhz}gUGC2_7Z0-KMrE+0?mug{wXO{xBCqGOWiB`H>aP!* za*{8h-^fLFM6W2{*1BXHy;Ce_Lj)gds|O6qBSHt9HzPZukLPJ?y?K9#9Mr&uaK6_- z-$hwrb+_g);|>|oA72JoLtTc-I<0JoQWlf$RqrETx9)~5r^ss0N=HppJI;=jdN~(o zk>zNDhU|zyN%YcUpSOOyc102Qm(Y+M(Uikv{gvN-Kd!dU(mcelln`59c*YqS_wXo* zvXJgM>IFBri_wq1YVLyqt!d^y@=eN4iJDLbl-2(Jhh95PE25wJ<{<{wIAF`a%3wzX zN}?}1cvsX@!yAem-vVvmyVDwzaNr^_qGC$_f*d6^3VWvYPp_St&}%2u9c@BM6eH6eMNfKBwUu5}p@rB!h^Ad1edqoaz1qq`uePujqOsM} zUn1#!=q1tzdWnQRg_f&!+>DOZ4v+3Bwx2$t*ntR?M0sSz-x|Uiwh@y9^DAQ)TLH%y zebsRZ#eC@1R&9EV0r?`Aznc}Yyfs!bfvx1|(wOK9kWWVa$QFrvgG}_r^ zP0*{YtJ~ak^!jKM`bWCw+*wC|Ii{Z2|9Z9=R~FO+y*7QPh+@dTp5;aD9j%o00}&{R zq6WvM-pxIqC^>Y4veu&RxF%AhXtzl(pZz5-y5)g}t1#Mx>lI_w-h1fFp4Jv&tDhw! zJFc9#GoZ|YH!bz@{}d9XmaI1;JEC#_K)>}nq=!Da)O&ufa&`?@eMI9Pg_bayij-CsnHj$TXxj5h2<1Sri`$?kILBH zAsY8{v~uPR)t5X;;d!qg@N(Hd<(&c95smw6#=?4p>yA$b@{LC%M|MQx9-g9VFGuOg z=Vl}?8xzHG=Z$DQC(v)vZ8PbK^b)BJy+lHG)E!SUbo0Y|>2-ZiaclAv<@|wYJnv9U zzh8g7)xc+lGp{ZvXB^ZWPh|9U7-I)LS8!eJ7`@uUlMw2T=Qg^jZq-5`Lobo;(@P{g zDWWE-9kmLz&~2}sqUf~~vLgZ|(F-?^(z@+M)d_l0h3tsNGcIG-Dz!80qgPw)>D3mV zmnm1xYX6=Ho>=LOvySV{-xm{+Q)bz+^fK-|Fp|Ej#1QMPw*hid7F+J%R_3I;jZWc3 zbuU|%UdCw~YgHIG*xGPJfIQL5hB$C-fY$e`qalCA(aMP)YgODDYTa_AjdZ0KW7LCr zYw)OsYqX#lgB3fl)~&w>Sx*;gBM1B05FOs{Z;Tt^+EnWNBZ_hzSE`WQ|}#2`Vyko4F(AfSALY#fUks0%i=T zm=GhFbB-&_z0B1$=bXcuS6y>XfAz@Be9imc^Bnff+3v5Zy1Tl%y83oCwiZtvcIO+c zM;{DRYS-sHhP}L`=D3!NH7^vzP!lpf1D zk9@7p$tP<2T84D$!>+y^p#L4wOewZMUcojYCAxj)Sxsy7!k;A?gJhH)&xf`w9HtLg z+*rA<&*8oM?|yY)hak2s(t{y)lwCv|Sbfg$t&KZtuqvE2SvOEm$Q7m>KOC!{V*UZJLKpmo8;~lx-cw3en^Sd+5;6d|DFbR_IgzrTZ`vWgAb3?*UhT0c(mYO zt6%E6PYwIof=xbhQ$~5QwIU*K`KE^T?dq`$^Sp$1Ao|{u5&FU9^_9_6Igg~}pXK3F zW;V8Hpn%AqV}yRbZhfWOiup=h*J1ki+zphpBRqT3-mKYJ$20%Pzn!niu$EWb;d-ql z^%S?njEKm{6xn5G0hZ%=ZHBbM^dWlt=tjzq-g6bPuUx8oYIO?MWj+t`$ar?wXwWEq z|B8Cb!+r}CvE?(1cUPBh?Z-Y$TrFb@u@<7~M6vKN+3l~6Z1Uy@GPVQJADPwC9-D~&=JtVlE(snUN%-dQ}>k-_Hl`g*Bh^Lk>mW#aC<%%v)xS-zS>ERu!$w)WW#o>v5KVU!Juk>RQ|Mj5neAodj_9nzM(W=?)>9fc z3)=*_(V1nXvZMa^gQ(a}=bl#4g z+q<&qe;<)opA`|`z7N-X?F>~4))moo68EpW)|kGas~5G;fV(Z+JBjV+Rox|}Wnv5~ z?-RjqzBu-SxOWoU;e9?YJGVESoqM{0-+XcGIdM;g?IT;#w>K-c;-WnAV_yr(jL22o`zK$+z zdA%^^rOcC2Dy)TQNs5UtVaf5wX!fOLHyNcuG-@Tii8Q^acFemmE1Z3b5j7m=Jhq9V zQGXlRvhXMJr90mQZO1m@+@urt{afY7gBvl=2@*r@C_BzzN&3?JH}x;~zO3qZRYs{0 zjaGtQ+jJ|fWjkSJBd5MMqQybmj%}iEipVCql1+T}tTsbCh%1h06GM(B=hG7+I zvfFw)84>6+p!dP0>LDMQG1FN6#VEn|K}oPp^fvjJ^Oo!>m*wV>edG1}#g zqf^Zje={NiB|$WK`VT!co{5cTv!bk3x;@`3(iQh=Yy0gs@@!VuD4P{(A7!)B?U`If zgbVQ)mY(emOAvv)DX&57A6kFP_V$^wy`dyn3)^SQ-KN=dw_$6s7LF6$?vHt9uxCjl z%i_=_)JjpWJV(c_>9%Su1POv=%inQ}Bzoh|2Y$dB?h z>h|o`^a{q_gK`k%fgDA7AW?SYhiJNg-Y8XGMp+%}Q&vaHTdCV~?jk?R@TfbpW~ZF; zF&?F?jw>juBV|_9?RkVLlcR3W_e&Wbb!T?#)h&mp_0n@RQl3QJp4}MHl&?{DX1Dgs zpGzA-c_0T;&KJ}r)I>y6ETiHvwG8EGY)&~EDNmwq&(e(iC|{%Q%!mDSc5iJ8<$>Hm zc_2~ykRPHcLcd^#YM~sB+bBmPnN?8N*!x$GMu#pTKg!prJ9BR57`RNWNqHcb{>lUCm>5a}=SkJ=ndGq+?!qa)dtrmTofTy-*45^j zhaHljUn(NnSMMoznCs0V-_#UlE!Gmf@Qw@Wu>PB_$_44v9ZS$}$N5j$tdg5Do^84` zWt&E8fVD)M7|^gCD_%G=TYNPe&mHZsCAdEm5xuw2`wTnMp9L3 z5iw`LGIa%6hL^FsRnY>7Yn0tPqsVrp>}o@@K4U1KzG!7|B}23n)MvefmhndSME>mDsK@var0n>(3ZwR+R?-(j>1;9l>eYYvBlrJd)3bYmW24kH!8Q8}j|`a-~vE zvvPIW)Q~GtNlHUkvl7(hGgJB}DHX>BQd~6OTc$;xzar<2&%}Z*WD0p+Fj@KYbAV6_ z(d4%uo3G~i6v>t}>@DLr?fC6EQljzh9HZUYKFheVZE_0ILJ8gW$A*~uCMhdY+K^Od zUFvIvs7MPXc@@?wBrG*aS=puwAwtu#X!oy%v3?#C zRiuUJ@w+>OTysfQwlCm_65|V~vz4*zc%cIpyorG5XEl3-+^UkSw0p)8RafTFUT-MF zV)o?LkQPd!<@}rN%bKhV$kmGw)8jX)m)CV-i~Afcsy5P_6hr*5A$igl=qcp z?{`EXCHmH&lxN->R&i}lv(Fr)d!>1+v}UC3 zGi=&k_4#%AK|~i;IiQ<*zgCYluA?T>QA8jmx+T=D7Np^Qm*ZedmbnuQlh?k z)0uV4^GUAKCh-7ShBUj4Lb@~`)0~!}xkn+^JAWA4vwu`7&7w5>d`1LPqP@YsDss+- zW7*q|B@f{J2$T>h(a!57zOyVqK?}&h(Jp8hV-%dGPk>lWOuOy zZ+0Lh%DMcOu_&_bxyiO;pP=kWi9F=9;cR&N`hm3&E%pf6U76e6S7djw7qK0pRMGqD zu|DO!SVXlM!AKVoNXfQ-Fus0lp!EZ_0VP37^rh_h0`e@fyE@rj)HtMz<4^Cz4bI9A z=4j4(xkU@}0})7x-ealSkQJi!V|u7X#hHT=qE?cJ{CI~^A-g*)+jk4jPNa)-g);oH z&GPtjo!G$q`vqHq2&5!Qrd2tZb$uCjmDUfmGAJR=U}|}j8wPH7H<8^%ONMmOuFx&) zMYoNq>w2>xhSMtAC`2G7YI*rUnXexPT0hVtql8F_zC+%3DwW&aUSxNX7TR50B`DAK zrW2MARr<3{H&qqwIig8ISk(q)s;JhW^`kVcA1D=~Nh(-5r?r@8;db{c*Pi`J=XIBhZ+zmPta$GAQ$!vgF1JvhT*=MyL^c)tc0`=0Uwq?_ElEm+0k(Uo zwL7U@8u(h~t{=^?q+)~O8#lQnDNj24E3KOS%L=H=mG&-tZ?MQcRt+^zSL5?UGAzM1 zAtlQ7;=bN!2#;icw@eY*foqhw;*6@?Njd)dCKY(E^T+cQUn#Y`|cBs@291m)TL$7dbD60yc+1Yy+rNUao+c67hSLD9l!bk8v zjUblb?oO0y#y>Hv@#M3H(5)3yHV&JV*6R=Y_GW3Qa(nrdv_BdzQ8IrDR&b@JufnSN zvsaa}Ft;_|)D3>uwdTdeIW-4#FqZV3Jv||*x^UbThDp{1x{5QXb2;_%odVBew7_AYFN6fGB2(ga` z(iN>w_+fv^XFidtLG}8$2BCo`{`()Jo9HCwsh|SVSZq15iLoB?!?RG&$nZv*ZnO|$~P|Uk$VEY zgi%L9et%24mO0-%W&DN)#ACyh@~mj)U^eDjOBGv){ex&iJUuPf$yR|q@+`~RdQV8p zo3dERQ6^YHelw=^OKXrXL3z90OgwU5jAX8V#L2TmqGjwKq^et7DUtY~dm zwMLJ%^`(|8m)iwUo>V74x9$VernFnEM0o@gk9GUk84tAnOMcOyAG3yiUB7zEa^;@U zUqSS>ofox+qn0V}t_BdoGi9CSPK&?f@eTWN9?Z@I(Nj;A+i>m6GUdVrzH&B9N>DvW zsx~AQNfKgjIiiUNbMgp#bXq+`eKn+1Sw<}kv5yC$sU0ECcDP-P)bdkbB~f4DoWL1{ zXgbxu8?SbtG2gr9Z?0F&u2;y9#v{Zz9tl&*YepLLURPTR)(80^n#TO>LdzD?-J!$( zl2PN3AL$iy>Q#YbfogBk-OzmpRMc0T+lVI1FyB|Z`?{vOZfbzgyV!EHN|F@ayo~m- z^%hI7*JgUB+G($FJjA{VAKO!{xxKm?Gj6!Ba^iZ9<4+s?+fC%?+&9&$ZM$-W!<#_8 z5)osYmtoIIsy-wYad*rQM2ME5=DS{U@q1U*SFv3LZAX40;>vtq_JI0o4fPe4;Os)) zl>K{bPdOmHyTCkuz# zfI5cSLuV7`7h0~9Ce9=)iW-NO6VVi5A#E>2+TNWk9BMW4L#-qa;7+{iPcv!&Sy7xh z$Pdvr3#VnHSsO>Q7Bvp};q0Q*~IH)6VZ|(S{#ojmUYH!WD`e|O+;&nXw(JTZ6_tjg~=v{kyL1r5iM$d zPFfA}P+u*hzM>X7)+p3h)MH7i@#wU?lKN^H^%eDxV`V{ph^BXCXjKcQG4D(kjz-F{ z)*?S#eP}0qH(u^fV?K?nD6Wvm57G28DXq@^NOv2Ng+q-)ez=O#2$Bb|o^&^stSIU$ z@E4M{-HmPnA0p#=~T^{N2`aj^HKsS~!9tqIb6# zrtYtAe52L3@SHAj$H$xQ%{Zlq`CXiOUL8^v<8s3_B)%5%tg?a!w~u3V#FJ{in2 z^9zxwWktDUctsUUkRMW#q$67*nEYd@eCqpBfd|hV`g&w*Wr{vQ5p!m8gpm-Z34ygR z*QkhS`@Rm_6#7`EKLNpW@4Q$rMJao(sd5~$lS&dtd?Q3VLSQY-)*~VkLvyo|A3WHh z_Z}J|cqXo6BNCN9c`GTHX^dWjBE*CD9{f+kT9~^_M7-)WSg!KSm(ibw*|!jZl;|Yx z-&|_##{Mj&k-x@sI<*?LL}{6;oPznC#0*VY2vL|2w+MkHoL`f~B&Em65;nA*675(n zzEv+)F2%Z6E~OQu9G?}s#VOlsnT33xm_v%1YFH<@NZ1m$$n%LKJ!IT}BwJ%=;fADuxG!ZU1| zv3uAw3zi@cky0v2b+~bu>`GE0cWgQKh$LmAzB)&}OMgNJOdJm!Ct3$-1Y6PwE}=2U zk>cZT&m)VvKwl1!UY#RN?DqfYl|2U?>X;q<-Rlr z-~8h%%v!94bCdd$=D9anhMhFeaXzChL5o4(c#-vaPu8a;Ss%1AXyMTEQDmEJVlJ|Y z^rxcjLrX2%U01U0HNq;&4O{=GrM72aN2^U)hiLscuhlpD{aK%Di6cK4|83VR5s}H0 z?S7dhQ2R)KXqRx*#PPTpTx9oSs{NDxumpP-DbYRQMF;#ikI(dny@QCPkY5WiS9W@;JNzyUzIgWPx8LOIpOj@9;R+IVNA9q8t>|3H+ zuh%i>%2d^Ay}wxZ8eGRr`QaAt-~Ev2OIZW8ALFX&4a-i}yUhtQpZIf$QZ>s3>tCJS z&G|nrP)hCa)F*H9B*YZ=(f;&plt%uQ&~lVelxpp*DtpdT?Lx!@>BcS^rh7f;qKDS< zHP0V9TVEMaL+=|`mUv`q*DT;NA@UPqb-O#(_h07fe~t|??>}5d`P_V}E_(-?v3+Dq zMo$eaLbcCu6v#U$e5$hLa6SF`D{nKlkM5XM&$o+f2yYAOC|VrsX^LN6$`e37oc5mn zupLMj+eGKirK|e8l2o?|f&Gqc65FvoAUH4^A?^|aW&eDC)AAQ%k)We`&lFQXEh^T)P-MC zaox?w5#aBlRHC#`3a$$HKnQM6kS_8Q5f9&W^8ZA&`FP-{AwrbO`%{e8Pxen;Qp?}K zYqk2Pr}bI>Y}6;XB4Z!kFve)%)=rj7M>`pjN16CV`k1xftc4pCHc#ucRKKk+uqO4- zNtA99!krMsk99I)2}*^ONJ|JYC#{p^Bq6Yb|89QTRliiBm>K!e$!M2h+QV6G)Y$WF zWJI)oIbWAv7uP3l_cRymus}bVqnJLd2DevJ2@$=mjcVN2Mn-MtzZV@3(4RgkYeqEP zf*?erU2W7%yV}TDg8YyY#q^cz+PVBqG&y^`iY52sC+dSAHPi2Isbp?aZJO>js*Yao zyf;bp{C+3xcHW(;SCO4EmK1ZFrGE*lrH?yWE`v>6_}Hu&>OWP#TzDd*m8ny4qW)%X zn4bAsB{TA)Z_jVLXqAUI)t--EqGAb3h?MC2M3O4M`%ZOK;hl0uN$h=vXv%r^(5w}r zcMcooc`8W7=@$Bf?vu^+HKT-d+IO$KmO0c_I}+;3aBk=F57b|}Ow@w{gUp7J{q=MG zdg#Gts!?BUB*b6!U9|@$SB51hJ5r)==>IOSm8eIV-V~7suT^*8B>nNTAT#olq%6&| zXeVbC*DRfi2~wdY+LHF(I^plx`qVXyq` zH1R7QO6_=8cVTLan*+4NZ}!Pp@@2e-_4>5MdiBp4J(=I*)}(&>9-w{y6u^)!|NYZt ziC#A_)Qptq22a+3^6o_c zyT!|tv&Uk+@uNC|uO&%!-^a=BIjU;4vQ%YAm;e5BX1;DNp_q{p`MVdc$ZM8#(t>wS zlySZDeq3B>GisVXaFD^=eCm6X$EMl(>1kXO=eXx#e)BxEtcyGtBKYrjOJjA*gkUqG zC8_kXSMs2Wvi6R$W+5$<5Gj#Vu`lJSBf4sBw=c9{33>xB=eAbb4jQU=j1M5G;&N1B z`+8>8f49|zxyp*-6?LEB(q=@{_i%DC=F_aURxov)iX|vJQle}N&xW$0r#h%@4t0>R zg#Y%aS5kM&R>~Y0H(z->r;Kh*^dhNT-1@S-M~er8QBA!rY{O2PprUu1S zG+-@6i(V#2#6?$3eKxA1K`e3ZqmdGQCqq(gT9L(4d1)3Sa>w4qUZzx|DzaSqyT3C>4J`g>Ig zcC=z%trdMckk9cLA1kZLz5KM;0e&pwN@ibc#g#Kxk&|k0_VU_ksXW7#9(@K}cO~gt>nvK4 zkHxeXuZuDCKhXCPy`?PVEnTeZs`WMhr+;Pl;n3G2AC5fagEGLRzFuO@c~jlXC1?&N4IZt9%MtR0lQmPywOy>c%xi5c!CHu>xM=U8TDvOC<-b<# z6J9>ScL9(Rd9U<}QdW9J$#Cp(?a0o3^}o_uDx5pMgCxES&}w8et^b!o?Ce61U@R## zI##dgQ`&|`O7to_@!+osj)?Ua5ZDWdCWK2LZTjX5^4sd?_=|;(S7I7vouQkj=eO|? z5kCfcXvVzF*pnAK49fl7dfA;bZME?20rBmcgjrRz1a|`~wCtkr;*`3vqrNAis||fC z+MpLM9Ao=UcX&s7Xw~VJvAUB!r(g-v#eS2ddNr4;o}-4cJLOuW;7b(v3c~2~iPkTz z7N_$t?%ASVJ3EMV)YaO%OJ~>L(oH5l9#{*}bSourxjJn4PW+#uom{4h#(#^=W&{NP>Euf3g2cR-j3HQBq?gLEC>BDhAmmVT6iBP z#%ebGe7V%#CX=(})K@a^t1Hx3)LKUg(#6*?=u5yoTV&o>BdM>j7NSvF+Xyl~g5flR zG*XTiB=N-v8d=3T<_Wj6u+X#ZnMpgCLj9xI^$Ketn!NCV9*k?^-=v9Hf_;UQ=xy?m z%~)jmjG~#N*ykW=xMH7CG}9cfa8lHOUVM8`Gb)y56xPCbEJVaa%Ko&DwB6&EwmVu* z+OF8O9eLX<1LKyVI9Udyh5aTX$oepDeGZfLAuFTU?G?VELH5e=#wo3wE`8Won&S@y2#-Vwf~KI2B8xTbM(Bd`VIQCj3ywtPBk~^EpW|&-_6r ze?3me8j8B?G zvw%7mE%*-7+UQ5}y^_hwoAB=nO86^Ud!F)Z-EO@ELbHX)KyE;dLB$tR+%I-qA62h zrY)9Lg<@FAsdo<`kB`UIw2AYRluVUe%!sD%eSFSZN^Oj0E#BwmWA2d3y-j9otb3Bu zty&gywL&gdYtba-{LjoZ=4;EJwfGQ1ev#XNCCCFQNm8L$SzR49hV@=Clk2Y4zRJ)@ zS$7{@mcG7vS)IDu?WvDy*LGgZUV?N*O1(b0sx?+bvB`;3$?J0>@)ay$tsl2sNqvxm zYl)+MlGJj+XA8?0&DPc(YQS39auLBtefZ;O*0qtvf+L0FEF#`}Ur8OlDw<{ectSv+ zULl%dud%Xh?<;Bt%x5o?y{~ZoQ`EWZXl)o-xW{DS&}N`FDOw-0aLjJuL~H5X-Jw0U z`MZq!yI08HMSG5R9xbZPPh>M_{dhy`2d;y-eu%5V0$K;T*T>gET*Gl4#1+owEivvb z$W?y+H!Yh0f9P(Xxg!ieXJhv%d4HaQJu9O>|)ySXPiqHQ;_lgwa`+Fh;Xk+*5>^%b(6;et|eBxUZG7yTS?zj)4pI;)2`}=>YW4x z(#2JRPTU`bvcY>-sS`tTF)TqI$eX@=GHSS3%Q>6ro1z{)SisqEIp*dmxmEGG%CIrsruTg-o5!?Xr1ZV*Yuf5v z*1W3ET*ddx8QX73>eQzd8-K?t?mw4$UHQ8*8*RomQ4Y5${nI%3raPuAR2nQj)7R2@1hb(`0>A+Xk@A3@61Lu1kr z#hbsCPqnMhHWR`#sJb$!)F2xIYpraPRXK5cW;!A~SCU*ax+9xUh_vEAOvM|;+7MW) z>4^l>mF9`*h~3Q%tl)(za4sAxfIZ zDfznZvmvk+_J|~{N-n{Chy5*=B1E~szDlhNxfIR=YhjPj4l;jc_9c5B=0=Er7dBMZ z%&KKWU@hzsI;l=ND);d#$BGi-%FEJ9`wG9?5LgR)gz}M(+Ho@ zHU!qXxplTl3YlZ;LpsO#F@hER+FkBjJFkqIfqEsb=Vb^{j1c_@fwge&BqD|!k6=wU zoReE-;DJ5^dIRKJ5h9cjH3)$vsEH^oz55#3gcTiMkQE^W)zaWFdNt^y(3lfq5h20}fhDNzC@q~w zNt@*dLk6(oguq(p2Vt~@-ua1?P8-v(C|q~fyMdGO!i4VNfwuX78x>p+lv;I~Ltv*-q! z@8c|S(iQpL*rUiBmXemV_hxF*Nha^q$+j7V5^^5uoLS1$0DcDP`>C)z;bKRYeep-3 z9lX{<_xZ}Www0-tm&x3BuF~>6KOc;0<0A)-uftwX_GDs-ldj0mB{9D|%Ox8tk*$p& z6-O5?GD-P(nV+9}nf9wu%D9m==yxOQIb)SHZ$`(1|A8o3aH_JsfWHmlM6YR)N6y+U zJA2x?wM{BJt?-81cXoTt$%*~UTjEnKM)P2ZQiabuOcsG6XZc6iB7*$)t*+yLMF*<| zl2n-=xUo~=d5qg@v=%%7=66gyZr%GkockBETyE~4p64wC8$Nfo@NkBsu7R3eYw)bh#H@*~u8 z>|Ja*_6U6^Lz-B9L~dgmX(DO~j-WUm{-o`(r0qvY+fl2}=If(;iC$;ZeAG&MX@h3e z$lrU*e`T0ah(JoT{h)asN%Ne~D4gdwYsER3NY>{pS)Vh6Kr4f`M6?VG$tE@+o57p|W(UZpk4lh!C+%ekg{ne1zn zxEj3YYwe|uEIi?(Z9RAT2F|rsTsf~Sh>_cP4`Zo`m23#7kK^b1M}4M!R1repP6%s>x@)1mnh)*O_|6M=TUbk+A5CaK zScLY2UWC9M9o7=(-~rlmW}-c30Yc!e5o?K-A%ym|0kp4OPy1TbCG0os5n2an?|ho} z&U`0~`h&HwM@SQCe;!Wz^R0wH{lQw;Bb0xaVgRiv2Ecdps7qK2dxWx6Qk-EJ#Tj_i z0QCoJVUN&@QxwY>O0kRsgh2hlTB6-;nkz~5OYbY{AFF-;O8sWF@B67obZ6AStNB~? ze0pC||5zbv;HX7CqB|oK)K?mhWo#j-sDE^bOgL&$kLb?mN6>qt);zthsDE^bemH7T zkLb<_OOHOSw8_+0i--sH54}_Eh_E^`tqNn>3N;ofUR0j()=)k)*3hN7Vr|2lEkv=A9Ly29AEi9--5|{F${k>2r|g zoeq%+N55f@NYakv5?WoFgWNLEywf52;pjK)5lL$P(O1h(bI_9zH1BkXusHgSG{(^* zbl0-EK`TsiFg=Q+LlnnRi}Xsj$Id8vemjRYKYewk^;Ng8$TVvmXqvUUJ%VKOcU8N; zi&7zi{9xVbA&)=uQyoC-`5{_4u@>?Z5mB4&tL@VLcI+$UN9(-q^z=s&VgMod>WsC> z1JLb$yNDnUK(%`S$b&op-M*V3&p>zXSZI%<+V?nEg5!^r=#AVnbJTj|GaM$Vuon3Y zx_ysBzJ%4e^GYHF-+A%98kV3|A|<*@mL#hsX$P6US99nt?bWRI{UGfut-_vDg*~UE z1m_C!Bmb(ryL!$)J3G?Kwy$-}DDqyc_MI^KE7o4;qm>h3e7Aj9J!JX)$aDGZ>aHwf zExYd{A{r{?)cJ1$*_isi!mQ=Ba_^X~G^^@IbiJ%8O=c@oj`7_@z}`caS!+GmkcmzH z1F@^(RHa67+m0U5X(qMr=Gv@3#WIinjcMDsNJgcU_Ex6=4+J0)*^ya3M{cu z8Iz?VNp)(hc=cGq~eI$lvnM2@v>&};ox++%-hTAoCjT4_>?|8 z8U-az1V{HUEK{0w;X9Vtq7BsQo`0~Mi#Hg>5-+Ro!DUM2(2^N=oQ#pxY{SN|GsdH~ zb7y-kj)wDE;9W-AtlmraEU{1UJd%7y$MI)*_E_H$`zM_M+S4KFF_fxA8Xg2wU9e5+M?r=P{lk1eQ>w$X1I-ijWe$srSH5 zYfq7)_+ODCM>~4-i?t#6nGRC2#g?>d>9HlGMZ0(%Vp$GKbc(z(M0@eYY-~n-g)KxL z*d|HpPUA7;cBHXem(w!#JN6a!Aw``@OBiX1od`v*jMl*>v<~uG&XwM|4vOnz!+nP=!RtKOiwR9^2&ezyWwm<%;(G47UsiikgnknF zSLhX?k0K(L{1=Z5{VUO1T2FqWJ+h5{B6@wI4@Z%0)gIYKFBN@J(X*sDwQ7%3qwkFV zF8aZ=cP3ANEP49JspUA=aMq$nE=hEXtbIFQh4Ro*)Bx-iqS2q1q&Bo;`Hglg=`jGu zo&#%%Qf;AKQ9;@j{YE@+_k*>>mh+ugrX0Uck#UEGwZz`NNxQp<^iyQq#bGUR1gp>v zvMB8!-AO9kDPk>AOH|sWM$s-ciuSc=GqB&py;>LA2}jaSc;BxWfMYLgvuom`+E&8GH=*LDvpv}Nq*dr97r>Ma(iW=}30NM#YYoVAiPPW$!s692E4X=gw&)2i|OEXB(d`?H+Vq%6OY>1CQ!pn|fpApiZp5cX3! zj&Ppc0b-m;%Ncv+|KG_w9YM7v8v=GIaEkc`*@nq-eYdT^a7mv&9>_unPS!`cM9?p^SGX1FPqqu#LZ6oOH!;Czf zEfo9eKgNTE;{U|n#ZzQwFJzR;NlR>pvlspsVrrcFuw#xiPU#&$US-5EU>rOk+N z_PaAe|6dWdmOJ$azlXveAs)2;+5b7eRU^8Ny&C`R+}-^zgnb9e5zbZne*(`Kv0K?2;6Nuy^o9tXP@A{A1P%- zpj0rLj$JVyIdKG?ed1*WJ%;xEF9hf=pfe(zed1-s-gQcw5#j6;F(&ih5l)R0;|%{D z;T&5pD{9GqM__~nNASNRFrI{3;zXzg|CEnj+GsSTL<(p0cm~<*c1b0V-yqYj5`2x? z^v8ZVI5o+bgWlo6l5O+LE7f{058<`MbIu~!RQYxbt6|ovNQSlWlwCwD8?;{b{HMI^ zT515pv&}CH+>}8Ntu{%Jw0P3iY-lPs}^36C}(X2N!LW&rQq&`bXRxIsQo>b zsK2L6h1^jpq-2|eYDoGV#C;9TF5Nx{MINI`s=FlB&|mYz!5yU%cSU3w)YD`cLdY^8 zEv$vSC24+}?sCs-b&SWFj%LRvt~ZsaQ#T}ta>(GE7iXVC7~I~=>bZ2e4S_m_T1hvH?^aXY(xoCER^Z{#7#vxO=|_gCS<+ih?XW^S z9NLGyPWGxzceO3`?r~~4^_3O+$}yTa{*v@&fs4E(ZkJqTMx^k~o%k&Vda^6~hsrBP zZjeWf?$6^44j&io2ig@ngUq|c=(qHM{C!a*KmTxiFUZlb);cIrmYdIQWMA)m@~agi z8TGCSde>nGEwf6QUhG|KGU?ne%^#54Sm6F1k1~`wZfkPbt|&ZtCYI&+IVLhOpN{Nkqh}z#{UH+isSoE>V=BqU=T<)15vp z)Qmc&+_(^u>0({eKM(3qJ67D=V@&d&YpmQVnqjT4RdSnp9f~#u45?#Q3;qn*U8;{M zaXClK`Dc&ucCop}#)QBUq>Gd!>GI%sWBYk0jJ*nrJg}$#u3yyT-*Azs*$>{k$?sMh z`yYL0Olc9tumq(Nd9orIgFVG9Wlrmc$BP_D`e!JVkXz1 zQ1gJPd)Nhk4^uZ2=do*pf2|oSKNuSRElL$uC|6L|DjueRRBLJTU0T)(9;OjC#PGku zEoIKkGsG+x5qUcmN?TzqYPwN7)I2`HoYv(~Dbqq*J0=^qras|r*;3?%Cz-x z9rHiWex|)1*V~jknd_BuyrAk^>qqK*Z;=N|vemFNt?sj$rhP8FcUQd5q?SMa^}yAK zQ4C9v2TDt~g!*o=^xVD0m`qY3cWj4Ntt2OUaS!(x+6WB)drMf9gH z?bMzwdF8S3BN>(;Kcpl{4f=l4*Ee{D(4R1x4cU%0c1sgk`)z8oI4hb z+|qeep7+MPce=crHR;{633N6XupPjOty8d}N z!y-Z;-8`lWwp!c^7ZF8@EV1nPyHjwaIfi=~4j$fq8?4+0bN}H+%oN-2xFD|WUkBec zTr2Zf_6+YK_$8?Ab%(l|IQlEiVAA#{MdhA8>(!a??$7wwytHSACFq+JvE_rRgjWQU?UHXc5~W;3EG z4`j=(a%tZg#(JKk8J3`bB}z4Eb(&o7nZa`JL4Vh|&-a^cnY zEvI`A5Zd9NP~KL{b)#$+5s$a-l)oR{W2k?5Aj1;;W*c{Ulp&UQlqVk7hzIrw@<0jc zHsFh*@_Op4@zhrmi~;tQ*z&Y;ODwUj9fHG1OHdnd%u#zNAKCK=bn`o zkq6L-JOK0!&;t+==d3x5S85+IxRaNG9t(OIB4TjnbH=)!XHufclR+;GJsA-(u={L7 z-b7b<#wyXjqP}wYzFTUQF#R?!$rM1V59JWrG25_av#We+WfVjI6Kf&brX?285{D;D zV-EX%JZYfy!*VBm{U9v?|J+$iM87(cXer%rlHq)a==>YS@`kkMbV=WH;@%Q#VZTYz2-?>!p`9@2 zf%{jig)^AG#i70P3PKzu1lbJ7{tUHG?A=DRKX*-+3U}C8OYGf1iUGK!?}Tv|kF~_! zjiorlru5#$NCDQuv7uYo*;KV`%U=;lj9H-fg5yMM)S&h1Zxn&dNfAgK5A10%CPVQ= z^;>#85o=*ji;<$66kGb49_zz66~>kjP1$rQ;#EC8;)T&OjChH*og#O#J#vTh8Anr$ z^(9YfD;G(R!(lBPO)&yVF*2FAqbbG6F#d@#OGMN6yA(<7o*wbSs4PZOQ5Pg>6vcPX zr^l}_HjVLJ)CIcxx~?O8dFzrqz05q7uY>l}1>Aq&zJ&IiD@L)GRs7^53(E@#^!jmq zq_3k1vC7v^_FYt7#S&Z-k+&p0xfR29UN~SFbKyX$SmNBJAV11sN<8*d^^?aWmRFH3 zwnL;eX!AKa;Y2MKeKwEAGaeZFYztYpA=r%TF78Dosd!a-&oWycc6n=d0fDZ|b#3(5U! zhZuupVc(A{wIp>7=zbtm69d~YpbAH%*%9bJpf|wJqbP0}Vqn$BR?)Bo`5`5GYH?VI zTq&17yB=Fj;DP&o^id><4Gxi865;_Numq(Nc`RvUmHj`JW49C^fd`Hn@}r&C?g0lz z`5RcL>0&$355hJ{(urnywDNJD?CQ(he9TRDEx|YpdNmXmB}7j`JR<~_pdW;kBq_&~ zIMtg*FfGFfqOXPgD3eY<5AB$5Vb*9#ZVgM2uGo&l5hJwRj~dC9RvP%Mb$sc7@hgmL z(F=Kmc=NcCoUqEEVhQ?JNJ*0ZB}C5$jpPl<1{G_ecP1i|h7HxOZEGWMI@U{&3fqAZ zJ&N2-4%eFdyqC|mU#4OSwnOBx`FxC)uh$jBnTRW?86|;uiK9m($>+~{T7wF=Wy_zB zR2((rhZ55FyYX>qiGh{bo-Mu_&NUoCaXg|%dNAo~KGrv9K@Ig4HJo@jtP;iaDT`p= zwe4iD%RN=JA7U-11-DJwarfv|xvcaa9j|52q{C&m|K?KJvjhD?@OJ@^5(*K#NA0Jf zh_)dldNYI3t39^8n!Oew9BYX<9vs7^;;;Q7ciwWlBqHx2^<4KpAVelYAYG2O+b%AZ zeQwfAW?kKDHmBMN=~CHOHBQ%Fi}SOif3>63|KD;rWq0<14Ka@1m0`RsNDHMxX@BwX zCB!~Li1Iq;<9{NccR@!{68zR+=Jol;s8SuuZVHcKZ;H>|Siao?E04F|KQVn{LGNNZ z|GjY61XC&ctv2IvpS`;#7!N(`o4S6eh}a%A*%U_T)&uL9h3JlS@nLCse&LgbE9=KH ztc5WL5fS!fk367(hb6J-K=!j!7NukR1=iIeCUXy?i_)DW$^Tb~ITw?aHa^94_OUie zHE-kZ@`!oArJnm|w7>&pM>JWV?a6Y%KEbJ;xrPcndL1zR3T4j7(vC zhTeVspvdKF%rWe#JBDEi_OvKfy;1k%szH-1ujQVCR7V%YD2IA3upV6>Amj$1mQy}} zse1z~UPW6otc7>DF)~FbSeF~JD=wKWIX@L=wSD81g1r}59~ATzZuEw7Qlj_IpXOrcl4@B}`?eAgc$*y2loPP$U^de|uR8s}VmVj%Vx>j51=jxF zUgpB`0_CrW1=f&)-eztRR}E!NT=Q6(Rb47$EkxrDdAj-HKbplKSQOEJMycOO)EbFR;G3S6ImLin(7U=`-d1{OD2B5`1E#5lgV;NQv@a<%!fj z)O}^~`Ews{xo+>>N3|04ffbACUT-~l@9NIpB_0~*QJZ)WE!{2^qVZ;jBo%EMrPZIC z$5P`;UV#VR><|%?nzz=5e_Up9UzU^im2Mwr(j~oEx>n-70P@IIhiF-+$(Afty!m)I zYT?}j5pm#KAMHr)>Xy#2r@59mc;MXwyh%WD>e}SVbenFu`E-elCD?MLMDHS>s;I?z zCR&U%KTs;taQ#^Nti>A4Uf$m%l>g}Cii9hi&C27=utWgerv@%$otJ>XHJitfXfR7(X?Y72YM|FLK#m=R!)fgY58GJ^ao`?LM&sLmlmQe1zVdRvGoB zUxv4~#<$<2KJ@z2Qnvm8Mjne}9w1tLIqQgP7VXr|Y=(W!hzGpkh3`!uB}p<}o}`Y? zxh5q`@JNR90N=O3ccmyYQ6xb<5bqv5C2g31z*jI3O>v)5zpK@!Rgkdd|N<@@>vt1r+j5JL18^on@ z__g>N6uvz|FKrxYDqsD5UaH5oKLiB68HH%dj=%Pk+~aB2)PB~^d;}dH>wb6*3SUH# zr0Ne+_&$6c8wh_F5 zJL9WO_~sLxV7X>x=Ng~2Eb?h5AW(Kh(@EUH0c>n!4tZYkCO)GaeiXh}gfG-k>~-e= zHaqVmOWk~X1q8lbglKv*tPkBl+T*8|pPq#w4}8Z4Uss}-Oyi!cJ*%i1%3qMN1m8qL zO7uR?{eEoos;8FDR}Rk--!8(JkLc|hpJ>W*bJen= za8Ch2)<>~>ONf@F4OydD*1m@=*$cno-jc(IL%R4%5Z%E#5W|)|{3msO^#a_s+s>MK zrhP=?8$*&5L5PK2pQY}fUO;$#2;V3|N@Nr7R$_N|`KmYKYYA_L#e_{%;`{jMeWRwz+XF)w8!J!&>;RkoY=R@qyJ?gWwu!y)*s-0$(yiv?NX5 zRfN3`&!iT*(@;R5h9jC@+BnbH>(2&t#@W&gxo_JsSxLxTRWGVnHlwt3o4iCRwyj?u zHU2hZWX~15J;&B+BgZJNHHzp-C3*gVq`DHyE5VLih9Ue zpZ?y5XI>cf{EM9V_gZRD>-G#wkO$f^(%qsEAdOK4_#L0Yj zz*?{z>kWIX^V;(f{PS!@HrqA9@*vH~umpGU z*e1$CyUB+YvqW2%D-#eX6{5*|-I0fxXWq4J+ZrxN<<})z+5di<^?knpGfF5)cUHD% z`rZQSw+BCk6$kgxL-WNcZ>r?hPnN1g?RfZSOZFnDfSPlGtFYTfNft#-Q&L*JvMw)G zl@NV%HfL_`Uo5u<RbvSwg&D%4NfY{Pw zx>B;Szkai|j~UUDG$g(et9mF%Jz1)tfIzw^E%`pFE!c&xl$m==W`-;B!PYaB*$LJ4 zUWdHR$dCNQt*x1B*=FjGF)jk)bly1S*dSm1b60OOq9v(BTzfVuq^5eT#~0!Cx*a>? zlq!8H>i;(OHaF@Lr;NH;MR%*i^D}HN*nxeH_f^%$pM^0uKa5lAZ7!#mnBi?kGC-ry5D5pyNR{hvutfEs1+Ohkg)`LWbhg0 zcVM0){nWilA7$i@{U#!s&TGfI-ZQA#|NJIn3q4xLDXwL!>gDQsXLzM@$b_~mu9#Wf zU+t%iwXk=QADz)RXv0=~XR7wnh2cn{j){ophns4%N*L~letbI6TC=d6>f3DD1;n#Lar*QTx%Kg+`G}@d%USKTI(mR(exJf#`any&GY@oe#%&aQ5B>lNk3PY)0AoNQYX2Zg$PUB z#tAw*x!)S{*3bOVeVo3lMydXGbI@XWB?TVqreLPLRKO{hN_``#1UY#kSS? zpVD8|EN$AUFFUmr5TUh3=u^Ju(!Xx&P$)v6YDCd!~PO?!u@*;(gVi5wpJPu zXhyUoEim3xFSlB5i8VzCJZSB6M5aDz1NB#*&spP&alhn9wwG#B$ahO@#V!m>kO#I; zl3wS%tR5_S)biNBmk{x?rViG<7o=J56|Z4NN|cS{@jW$Vor`7QLR<9QAxYTG5&G1v zJFQ(;1)7r^4AYM(`>f+1@@%?O&)!hmevY@O(Gd(wkO#Jja+v{o(xNnE>fcL811fg?R?*IW`CH#qjJY+ zy+@ht)+c=f%rBOY)eDu`X1$)uwcUSiPObE=OP1#etr(V|R3eXENp-Z_-GkNnMN6{c zGbig+M^x31J*;dV^5pjy{6WAVzAo!W+jHNmg8&YNQp92#QJK7 z6YHw4m--8DlV>VBUS|`_=!HM}njhAgsLyEZqyI65Tb~D;YiQZ0w^f&at;nzh>EbKr zbYmn(Iju|yf3^HXS>Sm6kzV?ZT%9%Q7 z3t#xEjf#Acv1H-%I6c$pGWwh?w(}1MZ?cIe+G*JmL)Aw0zX&|?6^qlO>ig=3-)(EH zgCD(q`n|c<v!=nZx}E`AJVb9et9o% z$6b|dyJAxFHT^1M3AP+5QIvCT8?C%&OZD!D9|8iULNuKfU2mdwx>H*neK{Yi-g=tu zn&?kXU`6il=yq>O|$VQX_d|v+ePE#nBw$eb&#ovxR?Zq9uk! zZS5Me);LQK96&dN0D=67$K(^ni(irr_qIk0Jn-FLq$Ek}=eik{jVn?spNe6~9c34J zv^qc2xUfNs)WF{B1+C>Lxz)%fY>AHoa77#&1PbnCZz zCZk*Dy_TNWqZvx_{-5D=XMB!6kWSpO*CpwaHK+XZW6#uV%c2<4Ws6sZq@_;OJ9P*( zi#+Bgt~buEF*EqJ7e#X*%9+$?PDp{-f9Maohnf*hd01+N8OxO0W(Zv>B6_{a7xHm+ zq&|;E?bG_!A*XH()+-F=BiNn392j~<3GPZ?4j>Qwa^Oe)ZfuxKKRqgjBMx|GGqzvh zYP_^BhG7ZvKuUCLt4FNy#;68{P5ojRa>sUvh`&qckc%9jnwoP*6vGx`zln&5ITeHb zd!_6@`ZI>1>{0)&+{IS6cNR49$QclK}A87P{Ho*20J*jIb-)@cXxN!H{1WK&o#e~wOH${wdcBH z@2NZHp6hL8grNI3qBP!^d z^VgnpITa^(e3mcGKkGA|7wD?>cL*k$~B}nN|X>N6{3Y6BgW+IbjvjjD3~PO z(2ZlF?WA>DtufR1i{Edz-p`t*5>Z~J%&AEfpNKJ^|7XULrSkjS(zIpdYnP2)r7H=oMfs7cxW_;e%Ub&`G1>`x==2c=F1$Xvx{UPj%$C>(_Hp{`0$&_!9Be@VyByPXFTUQq`{e?ra`Iu@!zz z8FA6YC9nN-$3`Q+CsFK6qk0}Lq7uN}eM0Q=|V{#5vD)qPr@W zW4FitBItoaUxs+Qf1@>GX878iRtPW8s?V-O(Qk;pEFs}vKcmPScNxp4bvOkQX zKN|gTLi4}*MIr-xf+cP2YQva!JBt2q^!1{5SVT-bYEbt&PHb@>m7*slUM8pJRDHtWe=!w|%y&glauH0`r zUuV4mBQe+tBSMODrq5`4wQmi!hV(UHga;!(a+EC8UBshWc`(PIodlmCLjHo44u2se zsT%XW+gXar;JcE2;e%T5AUm!zQ^$s)a!aKK>bl#>d|~ZIQl6b0QJg-sE4h4-w_J9e)vw4&pz$0R?~vL z>uRf-9cP#!fSChwK1225T{O%2gG@^b6x8quBIN9Z8-5>Nzxv-dXm?+(J_B~f(Xp;5OL>S$tFF|v`2!R!-AQh^0~W%i6&-MuSwo2ks*W` zDVQOIJ_q4RebJAdS-sycLu9>RJ`85P$T=(`C-t{fdQK|#23%!OLPcr!bq5N-)(v%)+woaem&-_5VVK<}_mXsxd3Hr)p82PpBAAngnP>9)Au<8A zl_C@HqsRorOgZcs*kgWYO=?*pYcf-0P2xB}y0TO;A_sD}$bpCWyQOp)#S6U?W?97rMI-@MM>`H57|PjnIai8x#0 zEGkP?@_{9tF7jT>h`d+KD#g54c~yI}XDgX}qm^G3k@1Tev6%5I#>d}yq_|n`SxwSJ zWJfO%+0mH4i`mhlC;rW?7CV4fHA$A|^S$pyjxgpPV~()s?SHeT#ck#fR5IazId?dR zV=I|Qv1Ut&B69A+Ma~_r6DT{P#my(_-$dPZMX|k;B%SWZ`9mJH!8?-;YyOv|hwB7N zA|tBxtVnCz38ptKlh~P=cKNlMXYpDaf{ZzhZ1bBxhoV>RyAtwgIBgZm5ypvUe7L z-CpO>;f#pg9j!qh9XxCrx42LK)Bclr<847kTbthbQQaoD3(ZaPtE^so$-lR4 z3@=+$M?@FzL0xCfV!??A3ARGnWyH*dHgw$P4s1_$Fh%Z&M&81=bk&!1skPW-XO$>f z^oaIYJ0ibGfjFKld_W>hNtq`p!N3&84{caXu5&gzUJ{d%}=*+cd;|B3H!s98v zM~(~07*bVxXVZittb)GaK&y-)yiwm^qpU}4Yg;yJ_jX464wCf1 zR)|&Zz*IJLlj*?7F%*5e=<7vFVyAE0Rh#wJmd$bgNY;4G3aG55 zaKGxoMxWGQ@PE4dY-Mb*>Da5nCXqoJs8f)xKiPdZXklt+#|wep@1 ziRaF0Y})9QfZZR``OCZ@WAjqY1NQHp!YgbEG8Rc`8gP5X6rNB-?4eJKz0>w|$?}49;@vg@voBBKO~Zs#AiIp%_$G|G zR!brU17j#gtuR)EloaJ$tT?0JyCrR0eFhV|RQhL^igZyz;Uio8nMFSgpyQtY-n|C= z*}XoBC>&6^bT;27W(hKF5RPUwU0cL;Jvoe(W5_Kqm29o-&6jq7JJ)G(^_FRGQu=1ax*K(wd_ zuzv_s&ZH5)E<>g7ffAxlisEvriqlar_x`t1VQ_R@kPT|~%z*Z8i7_OIi6@-;Tc9}ze{ zaHI);V&gRC-LbKueo~w?&XF#T6>+L@Zd1*ojwP8ix++Dwh>*wmTV;&4bGHrI7;w`c zXCIUVDT!Oz+q7eoU$!uXxg-S&R+LvRpPBEJsjO>oxU_yCLSCbGH8N-~ zZ7#A5m!cF`NL+DnEfLX-78_0eF&|7z4P&JB9O>ekC{BhgUCJH~%4M}edr5l+M9Ay; zT`zIxOXCt+k7aHYcM~WfuI-9)zEnd~$2)~tZic*vL%O(s5Sf`j-C5-M1I&*6Lvi=YZUEjB8ZXssADDM+7HidgeamK{e_2Gk_oj(td7+IXOLeT7X4qvoX4=1GjAVJC zBxom!Su}Pdd3j?BE7Yx@WDlYwXibW0B+D#m^B-5)k%?qp$Xl=_eDnNw(k2u=1&Bt!hOiAb4W#b|6)`lff0&>*0@3I@ z5jop4qDVJUv+wlJk&=f6C6Qy>r~K;C<+G=daj8xeX`v+O0}>I%!$axzzH7+U0}4TJ z6#9LTlE}HM*^4~1>p(W187_IFP!jZ=iQ8yr*P@O`OVGVJmK1$fC<%Jl#Mve5Alhta zWm;@dEJJS{dLz-pCZew`RkCW#baHsuFp9KL67(~Q`%+66p=A&G(7Rt>5afYq^hSz2 z8FAXF@c~N1r~lqr{`G%~{gw7-e}xi?4D3y>4I^tUCM6d~OI}XQVR-7WSnGT@n;#Gv zP@)3=Z9;21k(1F$=CQScjbZz{l5UT(x!YM?^OIwTn^GF)l8D@)QdZc-A(v>s zv}|5e0&EHi#ai1084ojPkTLVXhQCYb~t{L)@hv0E0oc{ zpp#<7E~)Ft(Z@ri3_9H1%RI_t9%Zd+htf9PZt4E^zZL}U?qwdX7Qfhlo9*b~^ed2*b3({aTj*?4~A}Ew~(k|L!`L` zTgfx^vDf9a!zbF%mBnWn!lq0Nn7?E)w|uV}u_vOvt0*fMdTB$;dC|dM6nf0B_l$Y?3)Qwrtl=z9D` zptiVk7P-!g>d?4=g4)hND``)SJdlz&aac2&u3xZ@7{huR#COjB(-UzIhkHBy9OOUL zb<-TyaNI0{2$UW7s3N-bPZD)YyzXzkG0A{WkOxu{nVH1{XxEPw=`HI;OpJ;AKcg1+ zZSrpEMEPFy?$cGoZrdgafwCi7@OWK~7UfOp+|iHnkQUBY$Xf)?-zL!m`xoaq%zoyF zbg`AJM`~z2`f5i3t=DEnvL>*V{5=F0rDTq`78K?y*=pEI{Qf(d#W;6f#3qQ|o-BGh zj%V!cGUD5hky@F#9;`-=FTwc($F`90@2sRKckM=L^GJ1)VdWWINBMuVh&JVSFgR{j+lptgNaJ%*EzGm}6n~|KV<8+%rVyLI3bT zexIsy?dO41e*e6F^QQjyV9hahu+l(jhQnThXtC3Ol+BhNxJ%rQM(Xb>;Lp24eu4-6 zk4L8^b+n}$!dbW1jVbm9>`RCiw)4|dtbuoJ`b2yW@fHLAd_m+V-c`VV?<(x#U~TKm zv1C=1$prfk@?0tw9 z{fhqAuTsK2Xsf;T>D#>x8TJP3B{)k6PpVZdTDDdYZ7^rE37=r!MM@%*JkFXVRv$yF zcD&*Lf28_5R&YP3D2L>CT2JsIrx6?y@~bw#VNK~%%UsBsKwEV{1B}u&lcCwYKR%G zlbGRf20(r|f)(Y&yKFXK+g-BucqGMH2KgcS|IKjs#SC{y%y2l9AwQgnej~>H^S@aX zXG`RVXyLzFQirw>Gn|i@;RN@;>j(0~8CCT52ic^$m_@gUSrlh|^23!uQT9DOMeM~aYWc1X#nlV>AzD;o>pz>Mh+a}^(L=po{aqmujl4y* z1+hBM6g|--=0xm$h?e{AgUaW8EJUT-dwSJgv2I5d%H*>~1RAj?Vvi9uuMA#{*m8+m#WKN0N7R z|DPV%3g51bxO(c`PW@fo6)0?lZ&yZmwp4vrh}J>6=I{meR)2O#GU8y2x@)CC7zF}b z;rEac!!2WJ{Msn;;cP=P)|A0*=DG6b&m4`HuV(N`Ij%e|z{z+cH-mq)aN|xyKlSVS zqZ;+PQH`8EZKT*Ls7oeKf8xqXyp!>kcP4+^z>T*MzeRR*rL+EB+dS~Q^f-zBx}M2X zGu`;o1i2NW73G~nRqe;ULhM_$5Q?Xw5uH$EGB4s%m)nifd6SB-d=#GHMoQx5d8ry-MhibZX{@rIKT(Pca``Af^v{2|fLRM&o1T??+2 z&MrJ_Ow)2QdCjY(xJ4sZsn!Rc5)+ZQ!6MmhN(M8DC^9}len?3~;*O}at?NlPb!|b4 z@=oiK!Si>N;tM{y7!$6i^HcAN@EwnIskZjdA^8cPSh2#bDawoJCG|3Rm%2rHNZGmq zF=(6Y2Rind!=w4lfx(I+km6Ldn2iMG} z4|^D~`U#$V6L~U+?6f|!CbD(KiF76o`5`4m`Jk>RL8t7s)mIu&loz$F>o$?!I(^C9 zzq+T8s#o4@(ooC}OFQ~gd~&JwM6L`uZypuzX+%n*iePaU|5LoQ=AIZ%QA2EnXhoUQ zV<{`L=qj7*6e($r=&jKcc`1wY=3z;?RA*Y-Xs>sTVy#1rQgs;AcH*9i+`7*>bMZtS zQ97zWDPixSh4=EJ$ovgWPY~XKJ$|2dJVcGF+)uK;;c1wW^0Pv z5$))k%u`qGHE;Q#Ba*LdVs5_I*si`26uBdMSg&M0sLEdR<1ad5czQ)mZP|zYIM!6E zS%c_F>B-zWagW*RH{!?cpQb@YJhV*fh7`G@>?NX;__;pY%rlDX)kqp|oyKZRE~zDW zG^5BJ(J8Bw_=Klh%^_uV#Po;P*@Y_yS;3q(6uBe1@TDYvrTbR1tF?|;+Nrd5^J*A# zt|e-1K@}iG&sE0pqepVhc9nI+_emRB$Sr$qd0+$D`Jd6e>wz3|`<(hll%#6vSYB%X zR&$AlI-*nRTDE#bEsa(7rq~L#l@WEypJ!2z6>W))N>N@!BX9ApT76*_EqActQ7tLT zi|8Loqd5=A5kWg$D!XbWwQZ#coByN@4V^xkZ`!`ae15N75e84Siu+z3TWa^liYm&& zAC6CuA5s!0y?ei93vO1_3XXP?-qn*9qdD`>HCu@~^hYL);x}jHnpJzfl8(dC0^0a5 z&zNO=V~X;kw&f>};%{q<@8P5)a;Fy6>X%u=zKsZx^gwjasiU}YQ;xZpr;a$^vxN4c zhkNNGH$Q{w$&&Kg{ueX`kPSO!KN|e*K^_k6vMFvsij_5D>ar|1wHuL)FI^w=_ z3GH}AZ+7NJ7{v-bh(5h8j_LrR*>6@KYb%}lY>3bd%i9)`4|SSt!^NFgOrku;;X z*0*dMmJo85d|WY%hZQ<&ZgE9a?*u*WPLAP;{mkYImvkQIl~&q;ttvaxw=6~Oh(Jn; zqILAt;+xlD3$N9uiwnf?ndkD&rOWsj5xsWMFuu9yS##reI*-KrrL;1;E!fEkVH9g= zp-xCiQ98F7sk!FQ%v<&(Mbe`UAI9m|Gv=3h4UGTzMDu0Ko|?y1)_EMO;BEJg=q11-%zbwn{_6ml@o1IZ5VeF zZ?}7KA0wjodWrfd=UKRdzoo%A|6W`aO9-Tf@-;RschSaeoKJ(`g_TA`h+ZEH(SK>h8@fB)I4t^N>X-g9KW&Al0PY;^SJP8h*seG4w8K(+<@E>fs{ln zmG#w*PjDqe-~LN{cg6AL(@OGYQ|cKJ{bWcyU$?0Y_kW@9OWaI8+JNpprZvyJDORUL zosg2Elo(fEn^~b6b$+&)%`Q5g-``b(I}h|Qq9orE;`y6_R(yB|ok#j&Kka#Q8yeAd zm85yx)scLrTN(Z?%iAa;vX}JHwk>@?Dy%7QKzWe|@)nhD+x69whj$?>DjX)=4Dp=V zTk%0Q^^AzNXgQu2saTWyEzx)37Y;Yk9Mg*D9d22JB4TjFc;3uZlaD^@VZ=IRic)Tc zzve%vtEpZ}U8!CMR>D9^B0IWtE3L##OG9iy8;W$X=9$c6uhTXbX48~j-dtEq`jFRj$=A_lCU~@Q_GTG<+t4D{N=ce8PfF%3k{x-=OKwIPQKNqq zExuC_-Km8$loxp*Z$&w@s*|=e_XEis)`|oVP2m@!oOpImcO#+?C8Y9M%j@#3Q*{f{ zcSU<`?vO@?`O`~E_4=?%9#Rr>qB?{)*fyc`w6zv8aRR@-t1f>*>KY&4p2(f-y|`tB zi}7urN&M$XPo5s5`x!15yw6VT>Q4J+HD$;hWtS0AqUKqUT9Gc@-h$+9Nab0B-S}ux zjT_OUo=xHh=6mwk?`$`Mycc#=y>LylR9Ow^*lFh;US$=L z>fE8`NJ(g({FW>{)r30doM$MzPe>ZC(8ikwH*_}k*ptSu#(HtBtIp%$z8R*D^^<7K zssg5MA?Z9n(Tg|8ayFtQvK}9Ame<}Erqp}XI&yhiIxo}Ro9FFtHV$i%&OMuY^PUzi z5?WL?8W5&g^r}goTb7in)?sZsM2nM1mhH5Q^_1B7b*#2W{Fc zJF?xrkkofkCwvQvQt@Cd?Ql&$8s{=x(gP9lH(%Ga3X89vK)YDlFq8z}0`@Vns-;^*#?;_HO!m3O-x#I_Pz*mew)9 z5lz@Sp5eNLXk2$iox6KISS@iH*RG{A?m1Bs)JeRnMN!(&?@fvA88bodh(JohvwdTr_QK*YnLKQP zAMPd*jk{%0p=o$iEoQtzw+H7l+@Is_6)A~YVJCdF7grmaEUt(f1;Cm>NpOFyC{J?x zYcC2HAj{4iBFG&PNJ-oUQ72C86+4+Un>j?XiV%&~i^wD|)LAR^BaigCyN98@ggT*R zA?g&pt)WFuJZFO05P{0i_z{}@5;REj3VfPK#LwNZ*jBS zJrS1}Rhj+z7AE;iP!jYYi1^@gXKmQefo%9-AIX=22-#n<_)MUdv1|dGSiAy7j|a+* z{uyyn&#|5My(wcc&Q~Q*5$c4LgnhoQxOS^T4K~&?T=ICKBC9z7u;d*?+0h#*R?fH9+UdckSe8>giatb?9X+1H z!!p`N^EzHo`**vYqz9tWtEwnDp(Qknr(UeX;V{XQin3#Mb5Zf+c2R9b%Z2Q0zvhy+ z7G+28u&Ao?wxBk3!gaQ?BauA9C_8$f#VqRni5(QDq>tsfQ}i37?C9kd{VLj0yT3%# zJ-;FQ+p*$5`rbvIqF+DRjHFfU*^gF|_Z(%H5u-zHGwYd;S={UIG{%atr$z*j9>vpzIi- zQIy9HJJ{|r@7U7Tt)&hF*Q90o$+F)n; zFuk%C7~YCvEDdGH$e)Oej;gHv{5G1E*=UraeJDG|ZiS7LxSka)ai0CU-cgDuqU;#K z6erwXmo|C4F0RFn>L5ieQFe@yDoTx@iKJ7Uowla%&=alv6xWAfqx5WgOddOdj zBICUx7*Q5poac+!;;i$mfNf_f!i%!Yh~QDr{U5z5s0Ci@EXAEsc8rWG%9SE}$cx>U zTHiEr-T-3p7)8eDyQ0k7P+cprV+yMn(pZYPqaK(aASxj|Ysv~dyvo{q>?uX{QFhEC z5YeSq*(C7Odv@h`xRg17vSX%#$W=S-Mfs`=>}3&aiuna7J7zI+KwL??B)u8 zDK7)-{bG)W=vTd~vG*}%HgR=-Da!(7ml1`Z?j-G94l%!lky0iH%8t1v!k@T4n2vw9 zn8my)C1t%}?uV?$sk8Q4-KpX1@}fW~dj};!okRsQn*ydz7lYX9%862*3?k(0osh>? zbo9%MrZr)0DQ454?3gVi^7LOP(%w^C40$s=31%K)E*9qgi2RZhcG}&73d=6iRMG=; ziZEwNQTp`1=2!pgTz}hlNm8a0%8r>;in6F^9lA2jl2qSGDduuvCKyU9{64kf>7KM^ zWb9XKf~{uG&fq0Wx$$w29F3@x(4(eZ~D)TgIW%JIUxAkODz@*-L8e7d;jN$hvG ztukFM@ei4o5HIDCVXMcsnf%KSH{Lg0N3?HdLFdqeB&A=FqzAToG%JJ0oO9#zJLrh- zL&e=ri{Fr64cifXvcGc%Us1!Ir&>B0D~`(G+8j4NyH zpq`QRSk5mJZj-^+CV22qtDKC8uCpnfKWOE}KSb(Y&Lo39ZPY_#4eXd{Ks^xM#W9_q zb`}U{9Z~+8s-;`IkV;9_C7&hw5M`-sE1YC*9}V=~g5nfgp$}1(>UsIXLPTmM<~5@C6(b5M5K&K<7I8U`RXdV9z>k!vzZk{&wXev`7F^REF&`4 zl%~yG!e~(OUnYD~>}VRVdE86f{O)8#-eOfd=;v>9DuE_FZb|S7YK!`bGt~(nSa@e2 zn&V?Zu@$~ie22nUh(d%sYU`gE#F95XAcG5Zm83%1ah4Ew zZ7~n6%y43;x4#j^83$)-)JdGYFVUMS&F>MHG8WRDh^qn4k0MviP>c?}^NG|u=_Soq z*a}x7MY+c!OtG7mknz`Jq&X2=$*Y>TV=ZldnrB|)z+g!aY$dOpbIWcdZ(V)pwzqcL zzBS3b+}#E|zp9HAB}31x$SMvwNET1)NZ0Pp6Ss~1hrlr?#|F_XiAp_f0g1m z=#@uGiZU>zqG8K!U#b-I*2J6R+nzSyFYH~6*b05i;_l3stJqRcSNgWKtA-xhYH#BC zH~)G(akxHz{6|Sq4jAo;TGW?@Ww}d!YDCM3Ce}uFuTcOEy<0=#fu2;EAN|%z^9#!- zjTY==b^$T`<3LyLm*i-~R_K!z9+ribw5_XaQ}+p<89qTTCsGoXLP}FDXN3jr)%`NV zR_ITZ5l^Rf*Pe9WO|;@`B~L1P?qo#Mm(kket6f>kyaaN6!wB9grY1id;9x`_8Ty$- z?dX_9jUN1Ny7$ORLLgoA8j6fxmZT*#dhh?Xdocq(K_19kWLf0fXj6w-YHKf5r0yTb z^6Ag2@*1~l8PRKm9t&}hmHB8%p)c7y5%NO>`j!wavJE@DU?D53YCcxACGQ7%4Um$U z6VKRc7rU3zT0ANz@j%%zlS^1EHQQYwr6ca z$)ZQ8WIeiV>`M2&OkoGdT_YWyrSeLf?fAhmwT)=wV8*|=rPBRAdHU2|8)xr85rNvG z^{Oa!&)21;mKV@MBZ^CQE!u`iNt{w5f-}Ma46nO^9=Hpd>PnE{(>R9mav>BPTI@@9u&s}_7WLU zKCHbqxi)8B-%m>Zb{rEpRzw|PkwI4?%-Jx1+x9%1qi~kMc|}pG|2V}Oe{-Z?>}pA| zJDgE*4i=|tUb~TXUJdB2bPp+81XmeceH5k2iXQ&!$_%1mUk{SH%aeJr7$1I&|G!nH zXMzvEf8hW99(un4Pa3HIKIl~3Fm&Z$`eKnuS~=xaCYk?-Ua;GpOq?1;!z&*lbDO2{ ztQ>DXRM;}eug0uoe&BioKBK?RW8>#FN|zZ&Y!4SOApi1s=n@<9Ia z=Bbl)tH{6iNwU_bHVuw)r0dIO@aqW<{O1G*BcktQrt_~o-T9pi-5$(bGmE?__m~u$ z(ScSxmdax-t8tenwTy_KGccVWQ0wq=DGma$r@R~8ewVP_V|=7hi#-w1Vi&%@m|@6? zy(F^U5GwA9<58jZyw=`YM&ws%bSgjHp*rtathV6sveIJ1tkOqV_L%|Fe1&}%(ZXvm zDW0u+eu=DH-JQO5i{%a1)Z(^Q4o2ixKQ)QpSYM4-xlv2-2-{vpt8jDz8|c}LVjsmG zj%Y=(5S51))U8ZQ|5J~eFUIg4;*QLCKSv|-``Rsz@0wYgPpPE8E5APdwbpCOkc0aU z671E;57CN}adr!H9n^x}a#84))}wfzd-ZsYYT}M<;P>8l1YeLkLR;0x zme#qu(1hav`5{`wYqwjl^Y#Pi{4NKG-e3RpQRG+HHG!Lx>+y2u^nSH**F3iLR4+RD z({_eE9Qh$yQO4IBOy{f{K^E_uNw7CyFTvSPQDP5ur~jJQl7?${5`2Pv7bz*q)x%}! zo~BJ`?{AZ(5rqiZ{^&5fIeqMFOJ{^%Fkmb68pw#cR&Mm*M1Q(-*%^O)g0>otN0D>a zy(g`D=OLLp-I^c|^tK>BannX9BO!KCw0CA#hO+_E#T~iGhjX$O^%6@CnX?$XodOYTDA-YnsqvF#!yN$Q8v%5 zGW8X63CHd z7vFr#EMi;oG07Bb6s|?c57A;S>3@>EYEYY2=;ugry+gD-mt;O&LrxrTLEAJaNO4U? zwA^=ZFn7{FJBkLCK0W?? zGxeVyj{FcUJlmHlG>8`Gsbj^tYMsZ8DK7lttU5;QyV%EsRaDHh?KG^ zMBGEm`g(}gy96I>h2LC8Y#?Disz9t12yBI4P)1}r4%zN05W58eTj3X!5tloa_pK*d zZxtwPgW<9r7{gYdZ z=pzl&)#wB-9=|}}y*dqTO9zd0B2BDH>3(YU&;8ek?!G)-J>1osFZ{jNUiM}U3ov!0 zFQ#5(R$C^j%PxEJ31h`w*!3r=8yk7@ZS!3uoy4ie*wWkb+Ifj1k2vjSJmr+Ax-GWm(+2Bz z-q)S(O6T@*qvN|QU??x5ckx8^S)Mg_nWrOcOZKMw({GWeX|@EpBRZ$}Xmz1YC0^!) zj&Lg;LT~=MlxJR8P15|#%S83?(n@^tH!maJ4JsnM!-8qSOQlWScGRTUN*kG|7Wb*l zm)Lp#A4I?@N4mPDHN9H@9Yc9h+sJ|OYIcehAJ9!d^D}p?A1(j29A&1x44-`66t9kJ zY{geC^fn?Tk$*Lz2kn#bh8UafHKB&s3ek#^;x>Su>6=2@nwJpN1JOUv$E$^>34SMa zss350(pz^U^W2-&5wY$6v_j=B~b!gg)O{Ua3fpq`LX!X*xujZE}8W_v9jaGdvzL^`< zZeYY)V?`G0{l+xAZDG^Ye0PdZkRMVKHLx$n)4V$!Nt=tOO(-vF%i^Nd$M$c{|J>1~ zDzGqyJm;xMKQgKufRAG}3Or|HrC@Bs~!A&^20Z!rz*! zxa$b3j&UjBO}^l7+j$&8c@d4g zMP$^qBaMAn(X{tWF^cjcdXV2R^^@Nf^QgcR%b2T!BbO05r?CyFz% z!h3Gfk7m5EW2=XqCCDAoK}Vw19Pfi>_t!e2;lLp3Q>h}W`k)#`?ucGJD_R{``k;AT zAs>Nw5o}GrRxZdAx3r`^l835Ukyp(7EqsiKz8@Z~&bfQQ>}{_?Q>VM>C-qt z?kM|#@ZstNG(AZML~3eny0Gat zR&k*eBz7KE-7``^vCV!x;3$CaD(mUDp~_0qOWv`S3j4^ zH7EDd5v}eOrQR=!X)T*O(Q-8t)g7yI%vNGXMoDBn=EYgk?Cgtd=G#UTxg!E8iJF=3 zEa`WzxvYNQ5Q^LpUBfd`&2`K%JH689-N0kT>9#y~X4|Ztbkq3hmhmc`o?{OCr-2bE zDT-=3PtJ_6()uj(q2;5-s_M~Pb6nf{MwG<6OrmB67*t^|!-qq3KS+fr;*{peWrQ@I@T_WvIu_lGz$@u`yL zG&7Li9W-7&J!Y3VzEeFT%3daUtXgQV`@GfC_oYpuF>p!BXn{l=tGA)Z9T7-L?Av{AksJ2=*z@!-dVcG8wP5&8^Fbjm zqHkAEQTwHt%q{2W`zwonR&-#cNH(HXOBy~rMZH)r&m1w;+lV?LC6V!4vuR$LrnZ__ zP)kXV9eK&>&{$^vm?ln>*PN*K&ADt|UQw?Iq#T~kDrP!q^IW_sKDnw)QfEB5Zcg0q zVU+clKcywngrz$FXaq%hu@$1lE<7q4?z%3W*C=4E5rX742R zgWCi11se||N^&4~qFVXqb@SHEI*;?2lk#F4S!yoFA}Df41X2=p4el=?11ztwaw{Y0 z>{XN0m9MXv?;Y|mBKlUvG`0H8`{sXZ={&6bZRrYex~(=3q|LUcsnf>ZGaE{H7*Qvr zB<8CJ*O`6s!dmDNe>!zbhU&Ph6o2R8YD7r}M@>@ayFM@p*SPSR5IPi}GqLA+kD6RNdeq^tr7qbWV+ftMlwUrTLthXAvSZrc8PlifTA$piOQ@wuF zf!}62k5eu%gK$jOL0AzFCox7*T* zIX3Kkn-GdmM6TLjen?4V{N~%6;!_%#;xdyca!1(_Eh=-jx6?*<-f8HyCPdGU{;MIP z@r{TR>)x?i;?ag=f_+~-%lq$J#8&v$MF#f9DzsyGN0#)^D1CF(3EzUKXW2R@?^JG6 zrWQ$*^gx9C&0U_>(%MGln>x7|r7wtjU>_5Hh8iQZx9q8Zv8Z_jWyijYqd@ooF4)mV zMN`=7g+$T=dm@fB!Q)z(f9UOX?E0u^X?&pUI39&Xf3uR7wIhQSE~`?M1ZBrDFDfB; z^wxS+tj!h%-yn#sp?_NYn^A*Z2 zBN}AAV;|m~VFP@cO6v#8j=IPTc7E#g@(u9miVr3zT*;C<*GMD9u8X_tWrc_;HZW30(; zlsKa}sJ*l!L)mfXB=SXPo@VtdY_zpyyeRI~P$%5g2%pUKN_28`e^%s!gil?(au$M zllIi86H*d9T3gYYD~1}Hn)BEq+{uCZZw*}7U+PXk5k2dxR*^^3a)0!z_%^IEgBPO`0rlA!e>GK97~ zAm1nEv(r;UB|8ccvaL4%+iFsVh4cMFUpSo0CCIl@t9VIUj`y%e@UI?CFrMsJM2MkU&-%-vZH@SRCR1$l%`BAtz{LcP0=HS zI-&1G^pct-=mcwbmM^MiA$RoRpqEPIM$M^6i@9d8qrxYH+!2kwERiSE*PgyRbAT1? z<3Z5_g=qAb2|Xfe)A98_u?nLrOL`z0eRATA;`b8Nc4Kw++`FCRheO%XYbfr{^sPq6 z{u9S8?I)724`oN+qL>-hdQy+sE7^T<1`D~P?C8G~C&TIzdYv6*{+T5xdL0psK2k+l z_)ke%yj)rK_M_=1Z}xx|(t zca$Cd$-?*AKAbk}IGck2%VY5dq;fXflBIQta66M~t8!AJG_f5LRlO zHT{)+-c&29l@w_}*)c96d;sF4`rc84P2K0!q{tm*$LNXJ!?lj0hL)A`+&f;AA|{B& z2#ttsmrSI)+uZQKKe`FQm=MNTWIf{4nzXm$2GgD^K~m%gWyi>t$lom#L95iv^bd(D zNs&9sj`1&XBlN%#^m3&ahF*S?3C5rhjWIUi>zkTDBP+Hc)vn*o!#EeBF^(rjZ2>>} zx%Pv+k(=d+qNQ`Zx?@~f-q*IC5u=NW^08+}TCDqY!|>@vDRM{IWyG<)(R9ZC?qo)- z(FD088l$8l;$CkUooKz8^glP=gpo=_V@vdTVLMv4PZ@f)dvO!SqoN=^h3L1Bv~y&G3N#)L7l|CGFzQ!;<$QrZnsQ=+!2A4gdgridy?QWirOwT zn=qRO(U>hHvZD{2V~xKA(Yy7(Fw8u{TrAA}5m`vQ4V|CoNM2VhE$M+dMVK=sA|@|O z(#^4f^y#u41i7Q^m{}!!03AO2H@TfeQ_DQqhf*OLv$sS9Yx_6m=hu{Gl{liG$o-oM zCh~>VKQ$UrCs8lsWfMBFaaq#)dsQjNYf~TLTWnd6UypD$8a*=9rMBL@M3nBcEFb%p zBo-BS$_yx?pGE$gM~1EX>`7Pm2YPWg;h7ZKBAce<727+CR$S0SKa2b~R}EX0sGqJb zuHwa$Yv~BjJ*BnS6=C$_lRGASvgl%(T6(t^zw^w==rJZuO|9h3ul_!ZTv1okF%!xf z=83nvxS}UtAMIpB&5@GGdb#OIle&f(=)#5+Wj|GBvU+rw2mjL3$@pbmrg|;MokwKp zJVqG@6T4E6$gV{q3INQTJ=X~WtQlSuXHu@t$Z?1&bAAFFTd{eWv^OR!3jJEAWN&!lZ@ zQJ>-WJwKg_cGm_!dqciQ6(g}Z8S19$ZoGA%lQDHvhI((F8?P;DGBjwHp?(N-=MSuO zJysR!u0?%%LrzD^h*MKC)JFksJoCAugciH-jOw(;&N$O;QC$^%tmr+J_1H1@vVZ*c zj>M;Gf?k>8uZI@Bs%=5nEv&!?!M?$cuVvFPohrKhBLN_-(PrptK@C(W;=?qO(KxtxT+*bSmZ zO^)#+wN2fskmDo6Bm~YSh!!V!qKas7tF1MUC_DXBqx$FcGWw9w534AfzBJaN8$D;& zUn>#nEiD^1!!%@dOd)Tos`$uC3U&-r?-dd!jC?mEx`d^vksg3Q~ zh+-@Bi^>S+Vx8&pKFe5Yxpoax>3KgZo{=#&&rM1>$qP?UC`uflZC@SO4cc4vP zS!mtvmyx_`=$S&^;_T85jhvoeTf6kbMdE>eQRF9fmR<&O>8QK5?_+%lf!<+6i(9AT zR61zu6;}S!H-eI&=CV``!;)yNr!x)Ht~K!!=eg8B^%>CnfnE_sDKM`GT{CM9TeoqW zUZ3GF0^cb5gA`>#WIVMDv17#|10+uo@<2*rjq<8X3wTwet_e@{>KE#t>KAA`V@|rF z6b%)&vpDE={ft>cpa%ib0^uD)zs!v%jhA(n5a>HWw1_Bn9!p<8-D${nn`%O-@ckfK zQC9bz%%*p%N1HEo(yNiEf2xt7&55?C$g-GF(X=4hm+qt9l9eh>YN>xJtRN+k2XHv` z|0C==;JYZA_R&EQr1vT!HT0g`k&6mQM~Z*~(m{GBfh1A{sR9P1N|PcTMJc)4l_R zH-^)*nGEIU43aF11hH;g;X(#u!f4d^Jz+jr+A@ale*(G^nqP z{{7pH`oVV_8M!NJ@{YTy?zl5Q+(a`|?uOSj8yVYizxMH&g#jC6evHPO9DnT9d*JSC zXWV_o{Zmuj)n|UViD;(WakskmHVWZ>ZBN{<q2qeOXPxA2SyR0^ z!2ED`(M-9kpZrBOV<7I=PR0FN9$V(eXq>H0%xEPZ-=UYn-B;W{HPzb*%n!F6&6GC> zCgfdgO~d`#TDV`!+Q9r6jUD$53HG;{FY1SJ_Z2r*P4%J!^TYi}Gv)1sR5>e%T_<(> zacm8P^@sT}8nasO1NLUzmhFz)vbf`Fs&^)sA8u5dDQ`fWzqrb-fR`z@R84K*j;pEO zvS2iBRGKO8O#GS@W|zQi*<9K7$QL$D^}+_Daih{qdCTILPdX>&#@*K(-rd)bhBF#B zD$SJlGQKLE$r_9MwUfO2wIScmK8n$rHnXi`Z^Etk?6?)rC5&Ki=ib$~7{OGWlL@XrroI1yi2Cd`W5cZ(f$RtOF4u%#AfEV|=#;mp zvFFThfxHi|)fkPJzd95WFQ;W6jF;y%>0z2!4m{h*0gp@~6l zU|*XOeP~+4qVFUwhqgDy3p7EkW`EA;<6Fb*Rd`RP1KyKi%VBho_m&5%?1cS|umRAlhMI;WbAstzK{20(&9ZC_5h3y_SJZJpV;4Y`&YaU!(N8RfX4=>^j0U>r*mG^ zH_d7*Z+eG38S`T_&MoCxY^}lTFf;Kw40}uF$KDPvg?yFKI{DoWeKcO6VUNuG7!ALR z*`OL;hxq`n!?4$9e(be1EmPb`Jquo->A0$sycHjsS(qQAvA5l=xA8e%hj|~b!|?3I z{CM`k`S#0ub%7UX&i1S-@9KwUNan|Atb{Q;%hzEV;B^?Dg_$4EqR3O@b=b{#{h}OR zpy8RG`7s*rcp=JIgeYU2_c~0-Q!_t~1~l!ht!Z=zFVGzDUZ4p@EXkS`%H z73)M-~9zg_NDfm*oQt&iYO8l8JPPoE|F+%mzRc&sGk zf95+qdZe$1SN4<2tX$xJzuxao(niPo`!&m+BuO&)$3p~4lIFRH(|aB!aZMh*LTE%) zI#w z8htG3i^dDx@1;F1Bn5e2Y87U@xU!;%OFzzjA5iT94bG=PJ3{^D@l#z z-zBkxs!eWBYhO>>q5sjeqDc2)aq;cR`L0xLD(p#O2^o!>NXA`#e5PnS*W)&#{m)XX z|1ff0+MUD_G8!kgGDTSrA=T?qlkNHQ=DAYc$@)VQOUSx_`vwWA?9Py?!uFaXcFa6i zs+(!{C$WT##yYBhdHeGW(e}CMp`z*#X%l}K-~F*Ki6vw-c4Z2*wa-ARJh9d6$KQYK zO4Xs%FG(yR>ooSAFJ%>fHK{1h|9IUlJ^y1@s!e~LPGSiIXl-ISUHtGuwB2l0QE~YF zk6o#9k3F5l5;9uTX7rqDuZ2|7;+0gNp1hf)zNLf#+te0Mts_=7ujnF_RL!5im88C< zgp9^6!0WBVvh3L;BA%(#w?y~o;Ylm~7~KT=CplE^lxcDTMv`}{&yQ5@~4ee}An`XuAyRLRVb(YSY4UKf{BN87*6 zDr%@6oj)~oGE2p1#Bk3=S=S-e(x}P0(x2{OsgqekHRi4l)?S7tc7rCC+g{U9`qTPS znq-zRfYu5QD36<&(e}aUp@!1F;ZxEkvxJPsE3`eb=-)%C9$`atWos{uyC1R-DWS3t zZ~hoLeTV)cq+0f2aYNbK+q)iy>_bY(?ZfF$Sna#8+B}cj7|K#p&3hEG4=EwH55M($ zZJd4+QVq?S6v0v{|Ka*X@|CdKZ6D~-9fyhSnVksuB51oe53*0>n(%9zuT?T;+zJ!- zJB-xX4|1D=i1O9?7zrgu*>65vp+8RW{NUOv7ed}gwu#Yr)v-<=BdOphyTVT^0zBA@ za!q(C1Uxnr8D-acv_j{)Si&IUcKu4m^qXN~U+0m55#*LL8aFM*j@OUAHbQK!7`Bu9 zisuYQYud*tem9_rEFq69&T>LaZbD0bno-ltZ_W%jK&B; z+tk*`?536PCWC@v+tPfG4BqjL`uvYO{Y;{z}da zN?Pf)@tb-nzCB(^C1(Kj?RrsvCX!y;n?F8-RIYFLV?!C~v4o69o&kOJDZJ>I*+m0$ zEla`@;%wB#tRfPg`qAO*f%#n3>&{U$KWf_ff^F^Xkm_b!HCv6Kj1!eqQbI=Kog(N} z)N|4H=a|oxHpsX{je(2?)CkIX9eH3l-`U^LE)A};w0Qq4kK zqIAiPSSj9RG<*qcus6JDZp1#ya%2q05-M$%F_EU-h7IO}R8tXODa(;@B1_04AH@*GY7jBnmnv~uNjF-OJXEyA{AA=T zdE?Bs-}3f_M!S)Wq*9TLLaTPjngYG+Mj4VyMHvdM`byS>UqqNO&>g|cg*GBi^u}C{ zv(gfYR^uVRae8OyAmjMe4Lig0eWr5>YX;X8l#01Cn)wA=&MjoL{8nv3zMXnkje+b% zM$2#2Z-Eiid88PvM%Eh-)+<%7)I^1lTA~p08?O$L?kd@(wli8u<#|!I57j@?QW>pU z?s+)2bG9|ML9R*DX8k^1-&}aOh>O@6@yZ_yoq5x<>Eo(iNP52NBH2F?f91cBG-jr& z3lSa8rGl2+M|`yt@zt!3BlT<>7CKnC=(S(Fki_WKZM>TLx7C2C*`T*kLyNXMA6%o) zE$1Ot^nD!AtDu%N+uqlBZhu4j-q$Mwn#laPCcHa{xcwJ+>QNPj=**pE&v4h(l8Cvl zW`b1pXY9}`Vm4@xxSi`_^ybU+-5!~EF+C6q>)q9FV0JeBxLxXxv;#)}d1k)bBXcXH z17bI3wVxqXp;spBTo+5yqm-+O5xc*TJnnv!$}aECoCep$=mU-Cxl(OfBCWPFX6G;b zs84Bwv}ZNU@ms(isTKzx_4t(~^ga8Y|qHJ$5XNn-w)>yH1(-Ty#$M`eYBl%wznQsw#Mj~As@R^eQ-^BxUSu%+C?FihCf^v zOQOCf)jkQtPc!O>>WC91g6m?m`u_gsQ$XA>MvB8(qun_~S*NsTMyu};*`?KXKwo8r zRHsH)v$-yoMD^RyISvq)&{u;Y)j?z?xGqMkep_nq24VpED&hHPd#9h7kbNb62BTHK zt=hX6h`%;Yvl?t1E?QL?Z*yG%Ns#@N7JOiTA`tU_f6i)_BSze~`id>HXR1W$)vYim ziEG09aL~jEjCo7MaLk>l7_DiApoyz7<~RMkk8FqZWQdNL3$Jdk*%|p~4WG z>r(b{Xs8wPJ`L;c2Vy8Oq$KPgv7$#laU}AIJrKijU5sY`h#0PQFXQZ)X!{1@ zL^a<@-_B_Ec9?4sS!TT*ZD(J&!R8Y7^IQ}5SRhqJNVOAEF?U8YKb-4B%jcox4}ST^ z;ubQR+k{)c=-or`i9-;Db6qTn@=D$ub=J?9j7JpCbupU92Dv_8OPWAScnlcL-_D+s(dyfqKUTvheg&U66j=kVizQM0=Eb|m&{w@7 zRqo^0b*_uis^7eMu)FWu#pr6fl1k2Zj8^^T&9#+%4|f9@7OsmWQ99+=93o4uizNvnx||=c&qnl`Ro@w*JcEo<8O^>+^Z&%V>l`%?$~BJaX*q{0 zUGSm|58@%XM18vvl0Tz*8Tx-iNGip{jr9H#!BpJSEN!42@l3_N@ZSigVn6>3A|BDb z+gD7b(C&=R%8{<@dBDS6(b_fQQCZ3hl1X zyp})9Lt`q{4tFK=p9rQ>y+FGAFFcq^^)A`RzaW_Ezvt{;-(Z27py~r}si)4&uh-A1fmPGZst7BR?R;gi4D;gaUEpc6p_IS(<_A~N6W+Z0*4lK6h!_M-5`m~k#t9B!OP?v?9eNz}-C_TjHm4VmBNx)|-x zSGKpt$%~ouLHcO@Dk3s}Ua~0)cO~)XMB7{AY{KlEq0(@p1R@!(izNw+zcw8az|AHV zjp~S&xGqNfbGz-W2fsm-u?AA5LB8Fe!);ozxRUtsgYB&cmzAhtr@9j3`b1Tij9ApS ztd}(uzwX#+yj?%t2*duOj>S|gdl2ETYh519ozd#si1A>DVwE}!_E8k^71zaRrIlW^)EAn#31fZ@F`OE6 z89_2y>9iM-MSHQ2u^F)s*Ts@33-)qkafq){H>+rDKzzk@FNxzT&zV&At-vupkeY zVShti=HVE@9?p;LkW-PT6a1)84@1<)RO}yv2tPZh%j_VRDBndHHrs3YKWN7`wBrQY z!SXUcmKJBWk>%WizPcQ~GlKhs(cBB6b*+wdt;!C%+*vB+$Gk}Y3dX!7G%+6eM6Qb^ zVO_vk9O%`r(Ds4QD;_mQv&P8Z$0={`%n+@gf$nl$ED7thcY3EZq=Khbk-jbMfYGe^ zcoi7uGLW-0iXdmn8qSiibs;Xnx^^-w%7&eDT`URPKX#YkOA0|M1HOdoVl?|0>{?taciJ<13NRtp=<2EV%t*+H(0(aIjZi0pOP zAWohcZz3X7+Abq6Mk{;tqP`o*+>JjIt=~i*j_YDc*xTVvKtz_K5m|nK$dc<~H2W^> zJKr0tk3{rpA_J*BgN#xc&AtnFMyC%n+F#yK_ciR@DM_T~WRL3a$_aT!=h>Y&X zhtcvIdyvA*8t@*Z(hNCss_~G1P<~5<=M$gaiIY5J1i)zdEfHQ8hxSr+WfKx1za^FY z_IK#8I+HVwzh8@0gQjtbLQC6L-x7`cAG9Z|B$2kJs1!o-^E|`Tdv~%O(heA{+TmI4 z(|dOkq4w?+TJ@D@QM`Z7`Xj%kBywdD96{dgQzIpLFoJ6eo&(?#HRck{HF@U%?sZsE z_YBSfFn87~t|_2bZlo_|mo4OanO|^clzWl;N9mZ?S3H7BGvr7yn#U%v!>i8wxcb9r z9{=DjvZ`0=s6r^MR5~5psaCQ}J7Bbu%F}kz5_J;LwKYbomU|ZU*)Z>v#cAxg^LVJ< zm6ob{*RxvxB%rYkCjtFaAxZK?qkq;UNuG}OPrc#4(xUwHaK@nuVLO@1KWmcYp7Qq2 z6#9s44JsLH5s|%th|E8$BIFrJ{{)Pn^VB}S-Zmq4HqP~NI~c(=;jEf>+EACL z4Y`C{&NZP;-U)02C$QBC(whJKVOvOoiHtfx%M5*wK##T&h-g- z8rMIo3L()vuY}GH>NtU|&YlZNr96Z5 zL_tImoWQowyB%=mPW6dA1E(aRljKS6T@Y;xPGA>lUeS2<=yhB5i9Bb=QZZW7Dtjle z^o+!KPDe*)XU z32b!|P|!(0AtmJYg-&4WIDzfv$fP7{c2*K{`!uaL@`=+Bkrg`ojm18ZB~-q|yUk&| z5oV-YjWtfXaq1+X>j#xLkPPs=+NnC=@SE5!V+?uLZ_n* zoQ_uKMcr{`2^k$a9c|!rv^p=EB(;GhWHfRB@QG{T6Hh}ES>t$|)x7IP8R?+yU7_t^ z(00~p)+I)VPDdL!9j(sRCea-%S3*W>nAUWWHhZ*w30BM2$r7?PV?5w@f53Y1#QBo!Rdyza;&u z`lfTpuCEN8j`sYncRJej;VdDeaV{KvwFsH*kvLPNT1dB2+}TI@U@y|ohSSmY;6*bW zxgMBnRlRg(+eL>?M;kaDtOPmJIO#0<*!xv_yif^tSyBPe5u(CKI$r=!)a6gMJc z36-{ck)?k++Q8{(yvyORHy$nmJJcEolLw98ic~^$xT9%N}utE1v%8nxL$|T81m_3|Ad%hij zc>K@RT`o~$Lw7CRnn3UV@elzjvO&4qr+5buJPRvLbS?Nl5lp4N>0WA*7wNN90V>j~ z|6eMpeX32aR{ob%>Xxai8LHptKIgMi#RsT(&GBD6&?NV^lUo;$V6YtzpTvnrPpa;S z96DjU7N6h@yI6Adf&HbNJ8=o}Y@8*(AL4sRj#<{Uv88ZM@i7n+jDkDTPbjmUOP+u# zRjZ;_jdwvsHEEj5BUQmVL#>wsJS3vUv?38jfsi$AxI8mrq{~C@IVa_6T08HVq16I) zq27u~54Qc%rIf>HpU0D`bt12gccoHw`Rzbf@@c6gk0(ac?M-qH`{HTY6^{UKPf6T= z$BU1i)0~?5C!&u^IXhqI?c8fz*ZnRx>3!!+&(!WW0l-Uao$1usKOtEnt{r&Um=r5} zxRf()Lws`2Co}&A(IHnFC!*u~rli{Y$-AbRqn7(!C2peGVe`XC`S(E{j3_?w{m4h3 z&2$m?dsEfqHNeBgi>IhU{P6e53LWIZEx%^eb}nq`=!(N+Zjx998)%^LZCYtZJe&Buw z5iAMI{@+q@UEEjyEfv>=Z|C1eGbk0?GuO+b=_2AiT)bc&?0uMDkO%u(d_xO8zsvm= z;sHMKf;|B9<9-YBVA+}9Gdv{B<-zs(Qn_B#M|&QXnBdG0dwp0F%_X5W5diIwHm9f< z{R|ICm!z{5_(`fNSTRaRPxZWNe+>`RwlmeR( zQ~L-_BDlo=j*wJ7+U1S4K{}U*HoNR&i@7t8AY#>u!6M_9x%%%9Z@35*fADBB+Km7V zL^5^!NG7CLK*(`+^%cBL)D#hlWDG-5i5QJf~hzb3B&IuefZ@Z zA5r-9HZ87NAi9Zbcu=vT+nnc1^U^bw85 zK4-kMt&ONuHO68pp7kf5#Z#A!d;5sI&($>AHLM~kf(KLaJh(NYzd3h(EgzBR_4Y>Y zgK5P~Aef40(IjV*S+vWeWN*xuj2vvFuCdf!2n18{oDn->w%MZCC?BzOEv;g42bhUFjavIlbyH~=^aTGM6_SuN__HR zdhyRw2-dzAZ$&%3@>F)w*bN0@0ube+>)K3JW%)p7f0sy?Du@_fp|W_8SVi=B3c>oC zXf}5)M8D(n7y^W5RT1rhV5-kwF`U~i2fI{3#Hr0`MVphYU8xws8vf0wLeAOS<9r_9 z1JMbHwBW&16RW0mejYu=r3xYz-dSefEZkqzcnZNbarTR^liz-Orq5#n5O;xi9tfuT z?)3QNE!G^DDu`HH?2z?cvuJS<Q8}y~(krjwpK->X>OSoRH3H!B; z*6Q}kzM=x8V(UDZBa^wH>10>-esS9)ufH+NZ%11oEFfe%xP6>*59pn>;1guskjL~kI#Up4n#5V;1aHvYtpp88&osm=T{VYC4xM_%|}Db zqa`BTdcR!S*xWd!yU*h;5OF|c0D?=nUakqRK&5JH3_X}y)C7Wk###LG$z74kt#?}Y zk>=R*)qNf%ffxitQ6RX4>*boT|8cm#acR$DTegF}%*hLL%-reUbNxrhwNuRul^^=P zWE>DTfv64ymvFsY6K+ldab@>nJKs}0zD+;ZJn&+iTQBp&EB{4ejRPBwSw)7%SX>wT z#K26gg*S{ghQE8*8nLFXjR?t&Ii*))9$XVLcM+q+>Rx&5j~`YEM3(GP&!wL06duvn zZ+Y_b(c;JZzgfM;1pV&HL35leFHLr-f{0RPj5yOduibXaJ&Wt*n2KX9yvzCP7||{M zg0-(kjKw7!KX6T&W)B=K9+mpTYPjvb#oRe&WPW&IV?>ORYE^c7W754q?}EzhHyO!t zAL6$lfJg&G10cBH84>K=u^97v|Dq+VyR0#I?-jZm1KrK@l zTbP|+0)ppMp3ixn$M1h20$7L$Kt>rn({q%;(FfXrxFiqalE*-B{J|C#)b>vhEj_8e z)cyp~5^Egm5=T+^9V|p-`4Ew{0D`GlmpD?x&0<7-tq}Fy0)nYnmpB^4JE@2)dm^$d z4FprME^)+(6GDhy+ar2ij(C@;SeH1e)ilG8kk13bRIE!JIpfzn5QQH>6y5^}rea;< z=p4UqfJpy!MEc#(4yIyV;uV0V{fyPb*H}$_03J-my2PstywZ#nOJ1y4WZceFtV_I- z!7qkjRdfTZqT-0#nTmCZS4)~!4J)s`Sb1H7R7}OX#2!`CzHTwts8V#9ey4nl#W@+y z0i~Wl$=sjxIMR#T-}tqi@h~=>(XIldqFgcOLg!BDXAYlL+w>3#ku{7qd8!)yfnX}m zCobO_VHS++<0F1*l*xEEuB~B)#aK+m*~nWjr8U18KG8>f_VH(W!_xzeSnyyf&bMCt zWMX8dpJw@petj-Pym)4e(Etdh;%u#UFzxEh+vfO)zI`rOC4krn1XFRY7d(?`AhVblhRk{T_Jn74G>Jld032xlQJF{K_N%5 zAP`K&S!ay7lQQPe5+Su@4iHSmS;y#pvz>(b(Y}_Po7c}Ma%ZvrNt2c~N=#M4x>Ws# zY3AwUw<5i@+SzJv89xlXqgUNs%4Vvi6Q`IhGo>~qRS+?!Zfm2~s?^5*C+!0W*1kTg zV$7untGH;q!!ka?2pjscQQ%?`o2iQT8f+e`AK_935o_{SF)nEpjlx&o2_RTszZlfq zJpNTzpT~^ad5oS`BjdZT^Vv)_aY&^3%dY+|RS>ZyReED$>y}1DzMcUDYxsv(3Ys}< zPw;u{uX#`}ez}M7?c2F*rW(C5y*WPhWS1(4INoWc-s6ux#)?UO0tmK=l|Lm#zPfCd z&*SZ^t@Y1$jxaK8&u%l-wu+M@XU$4*se%ac@!5z}u_KHZ>-7yF*oq2_PaT;rcAn2e zrcv|s8)J+<{({X^PvUm2QdB|2ds$oCTT-M7*&3uuR#E|xtk9YUsVpT`poDBYXtnEV z9<zorLRtOT50$6dzVYN-k_bw)XpP@LreC0S`xBnXo;h=1S9CA zj5)MKC@tXkaynU#q<( zj>BrJcvc(o8L(PMSuHHeNwGm#t&mo`7goz9TyN0(e0X7?n3pd>Z}Mg(=}SUhrqefb zoI+XSUH<{k;H3Bxcpp&|-e(EC50`MgT$85F-7?bnd+!VS>wlSYRpjP$<$8d9*QB9y z&9W`~`~GUgg@Hz7{sg^&CsoM9K`K*86-1mF5@WQD;`D4Y} z+doFE8W1B9p_a4X^;b(i;*V3K#idTWBfcvBAdqk8>^Y=zQrdx*3)ONiVSbR%ky&nc z&q71Xg=~3!w44z<9*o9sP7a9?ZPD@_XgSNv^#&1WxglG=8ZGBO;TQ#oP_JtmT5hP8 zbHDp5I<;>Q8dd4rciEy?k8%DAb}naweXw)3D7JI9 zE=_}Px0P>aJ7@31Hjj7u;1i{%P7hDb-iLi6dm`y|Q~WObME1Mvk8zs=vw`xv?2&mk z;8_B{y^J|Zc~PDxc#h(^3$III=9E71Tl5vrUOaR1jH+qyaE9`5Jg4$}&hxyc!Cx8D zUsZ#@;+dYK430kVdtR_}>3teQ+d2MVI}d82gJ>xN(b8SS)U4I4OB_Yv*U}J?-S=Z^ zrea;T|#8p6OmX zoU(IBJb1oxcaaV3B3u40a%g{$cSC~+>>?Z3Mb`aYWGR*9?;^Y3^5hXq=%%Uxi|}`mL;b^O=7;z5Rtz?8nciADB}pC4IF6)|?cxwq(e zmnw*`R=sH?97-cj?#yf#?H^}O|E;zo>*BmPXCv|ZA4fYFjix`byPf{i;*!CYJ~X>l zOXZ@uCcJ+Y*}<50_OV@RUy#Swk7Lc3me+ZPA96DB)s2DsDv8DQbJ(J7OY@z>@48f+ zzvPT3ZV&VbH{N-!oG8%hjKw9)gKNV1_Pv>m?(t4t_`uYcMz04b9-f*2hHhq6l zc3(dG*j*>`?+SBVD$c5M9u~iAS$)5L>8;*k_gnidE@2*A6MpaR>^^cQHxxuICIOnUQH|0tg&8r=_pa~?_Cy` z1b9$QxD_9jE%Ew~h+uCeTg+n^wo1np_xN#kSkszpI$}-gJVtchx!2;1FjFxa=W8ox zO&oP;wD_$>5t~bXd5SY-d?UGoEPUzI&PUZ$tP|$YAl|#`^MrDu9s`l zwCx`oV&nOj#jm&bT3nL0Y@Bmvspq>m_l~!B8nzLQ5;BO<6S4&I?M%gJO*_$37h_J9 z65s!t*XEK8Mc#An6|3R4i8J@OW!kBuSW)(_9dY}R#Z(QO%yhPg-*x>i=l3;j`St#y zO6}G5hXpiBZ+c;YQzUkm~0$fnUo!rwnyUq{@v?mk)M&b4y> z;2DQ^7ZG1&9c0vtT4Jx=`N(1_p09$4RlkfDpOoHZ{Z{gU#ZrNvBclPy&tI|nr^0ff z9Z4(CTL#*}CEO0K2`|2{A8kzQf7FV(ecxj4JnM7&H0_mFhlnemB-l$^pSHLcx!z!3 zWxm{6+AcHFZLaC|k0q&0dW?C;Lk5zWVdWVay-w zoq7IXpO3qJb=K(xZ}t3!aTSp%+B3)@qL}rh5&-=WvXcran8IgwO!sA4+(pWMVD4Q zIDf_bQV3uj)$q396X3G45*}#yq!FNC~74r)siULu))*QVH5SW)t zH7{}Qoq1zzfW3($*qcaI=7B_nW-{JG@MAkSTMrxjX|&Ps&D{|ub~BiVAGbyLaiWY- zeFS(IiiaQRxg{(W*W~gLiU)J|V^Nm}OY6?HhMJwZPq^M-%hj0gKwt4lv5v7WxU-s} zW;ND6&T_L(<4h4OO3pY5;K4S*w!*gQ&L6s*KL!B7_ROA$J%;Psb?Ms|1HnFu{UdwS z6fZg-2=>VA&x2kRKGDwZdr_VNcxK?4$n{sY@>e{o@odR69P(F~Yo+&*F$2%Y95bMI zL$QSG8HDl-94B!6!10P}wW7IiwH*6!OvP~!P68q#s|kzh45>I)WBUkd;toH{`A2j2 zu1qK|%9_u%qG^oa68~GRyh1g}5%lkDfQ2nG0DSS1N!y4-x9&AFr2^ov74xtC5L_Gqmw$9tgbo7dFA5QxKrXv6{-pQU0=Q- zmef39r%q?Ue- z_8)26*<3HLCb=g3-bD3!qS=7b;?3fdqTyptg z@+$mtpxY*{2_9~0PF>5>TRa@PTedt>wVV;bRcfoSCi=e3(V~uhGn`9!Wy&>S?L0n9 z;`F~qiIe}lWpllpjpUjTxxRcr|7cJjac=v$M6Qc-y1{jA%#TO(^*Nf0t@jVeNx*^rR|Ieu7txTMi^aQC@%^;9~sUiy!z#uFoH+28@X=3 zEt{9&xo zZu$xLHAF5^{K&(BM*75d;E@eH#()R6gLyD-ylCD0ZR6@PO`Jks@fdJl1zSD=k~jm}{u8vFZIHE{tpKZ{H687`u=5MB zbM^*o=im|YN_Z;_-sd-XpEK}2?BUq^pdBG^huZ`2qK)81qu@o^JF^!>Uxj==_6^{v z+xwoH=MVPO?7`)%rvAhmK6g`&t=~WH_k&q6rQwO(Z$&Nt8*eaoZf&ryQZPXt{-`~} zFNI$6V5xjvij)%iTJkSaaSM5zeSVIoyD40P?eO`zRNST%dMOo4!V>yD@-I@cyuKtZ z6{ABu;{BF~ypNA|rQ-I55cr5UxV22>OXZ@22p(I%wf~P)Jhsg586IeZ{NwhOj9%PP zQxTFJ1MWkQ*86v;cb|!OxJ^NX&)t>Xr*irIE01_7)l)qh@{j+`gX{IWsXv_uAexf=hVS=#P_I6V6QFCepU=XX_sfe@o43ZoRx><(hCxZ-rr0 zXkEs5{rB237L_rBTNmdwf@{vOMJ0_Xhf5kg+Z@%ogsqlq(zJfNkLd^RwJ_?`*rOsc zmj@#_YlPcQy$GKgR?g@=4|Vv;u5!nSH)ZtR*<#Y z>c1J$MxNF2Dk5_coM8*DYlrm9p)3~_nd!0+3@)9!Q^rZsARtWYVjNnzV)IZ$l zNFHUB`o6QxRJ>k(3eo$py#al-zvYB*=7GKnWru?+;lCr>+V7;aT+YI(<)NG|qumj- z)d+H3?46l6_Hh=K6jPxkU7#h<20076JQxvNZI_G8B?hL9pq%Ml1V%8FZx141A41wk z4D5q>z&=9z6v5SYL*or0Z7>Qp$R+H%xF$_Y^Qj>+rr1ZQ9h?tfey(Q_HQ*VV!ZWb< zVIIL1{no?%#Zg%8WY20tvjMC&wA&Lzz+VaFuee0<^J7uz?R*cn13b2a$3*bpmNO5Q z(De*LdWL-P4BYSB@?c-V28Fc2d9Xp&5*|Swf7b@>-=T?VVS}vIoC6B#725~fAlnDq z4Q?+-w$-J!=LHY;A8hB~K~@V*G?XT?hhtyDzRT4TLuyGw^c8z&_M+&kkaxw-4?MLT z^XV85oxcG?`mcb+InV zZ_by75b=IC%GEe|O3$aVtLWp>UU@9eHnZy_W2ZE_oFSM&s{eK{sO7-sj{`LMB!XE=kwWGm?)w1OW8o%-^ z0u6J=Bc7?i1F_sS=U;h*5KILL9f|nYcBCMP3ccVW{|l>d#2!K@^#4Yv)-t-_%F$xO;;MDi6@3Z6tCS)MOBm#B$B%K_k#~Jod*aV? zoqS7fBp1<&wqDq%X&=mQ*jVSmd<+^Kw#?zkday z3|<2|IOcZZ(IpvtsrI;aF;$TF!y4_x!Xl}xsPGJe<^6Wx6em-LCQgnfOU#b%#yUpf zIA=_$>EJQ^c3%-TwPxLy_9O>-ms`$g+>iPqzc{#bzx7k$MuPSArFE}3+m?Rj*r(q% zSCy{qtj8Or!v?kikAq=vh}vm?uG?hO3jqX6GP(a?r_a$TPM^pLKzvaMx1)1*NId_0 zHNhp!gL!LO$GHdWVQ}f@NnkY-y`*9~itbvC!}s!B%wk;`-$G5)L_adc0)5+3I*wmFg#*%Iyk( zN4rJa>@;un4u3VNe*nRfFj~_-O)6@4&NtVxOOF;@*HhNzdQ{K4epy~rKhblI)$)NW zRcN+kL|npikux`*aDFdP5K_f0ZLLr3U1R6Qx1$A@d{Q(i^5ljeoHZ|FuBCZb({2to z!tBjw1CcNWF4- zNT1lbPjfTV&&!>*>w21ZM~^W}lpX7AHm9QeyjI;Pe(23`{5ODL30rKtoIv-*NdmZbvh2ZC@spB%J=Od3H!8(GpnYGcLpDk zG0N)49gW)yrzYlW@xbPip8IE*Z>+B7oGZS@S?PMsH%naImV7Di zUevYN#N7L`=W%58;du81-c*I=qU|bC|zG#sqjlm^n zAC2{>au$!`nh@P@>t{qCEAeH6N0!d@8hCqG);nZm&M2-4w;;Cnlj9NJ`C$;@q4zkl z9gNnr8vS(R{P6^Qi%VXaC@=?9o$>@8JGii23wBzCp-Q_WKLRo|5 z^}hEwvKJVQyJY998Mo%S$4n#l_*VpcGBjg~WV&!6X$MrQ|D)bZ& z)Pg^I+$bD~Wcls!fK>JiO+Bf&1pGkdMd2*1+gEnoT%T>d?6usHRI;^Qlw85=Q>Jrxr?Q!`@ zt#ox)knV=KLtkAgsjorA<4eWei0s(wuSvZMA-r#I%o*+4pdcIc5U?WHoy$YoHZ02h zmiFk{xv1HsrEBNh4%oSefSog1)8I>l@+DjXs}1qvnlx?T^$u=3y1>34%Al3&Pchj_dG%0)F#_+|Cg)N6y&QfA^yO zOZ8siC3AKYydF@xBQPB@68zA2LI(%3R5X<_gcOsZ#OZp%1?ER47_Ob zYKy6qMR~p3IO_-zGxj%Ymo@}iFD=y@HC|`(+ECL9t{!RhnLX8N`(kgq)rEOxSlV^T zKi%79@;LKo;&sZehZ+l~WwAy+{3sAvX1hAgyfXG>=a=5gO|D7PZtomvq^)ww%JJHp z0UnHSUY}+rtt#Mbe{~Ub?ZWht#;$kU+Y<)-Vzo=0XI=^WB>C3^j>%LKJ+f0)r{oE# z!&0hfNHhqNN$&S!XC+VnSeQ&D+tIhYlic=`RY0UJGQ@bV(-J#2-Oe3MCG~i~_0-P5 zS3fj^hKxF z(;_;)Zj|4X!;T%0Pwf2WRkK2xInKQTZ<^c=wtxHr@n@}#-@lq}cdv6R(7TMjR@5|q zjrhPB{*{S#ZEh`7NpzijW1LgvW!7NMu2+o)r;CdUl?PZ{BG-eb z-|y!XAN9Pu=2UIM&EidEjcQSa?Rs141lqwXNcKdydB3}ukrfhd?%!m#qaA{J!++F~l{gTp@m zz?nT@OJooc{pO!~Sl2A}mi(Oqo|^q`>kR87r~I|U`D}h6wBzRI7xiDNyl#Kmp(Ac? zrIc{X+2_MPcBD6~qnGWQjcN*}Vsz2BS4O5wv&Jb?Aq{xk=#|9HX*?-mM{$VPK zex>n3r}jb{Ex!t>q(nbMGHxyRLJ;v>yFc}rX!V{hS!^zmv(K&xbDXqo+D6J=_`T8` z=lbLJ;L$7fSiN{yb-Qc-A%QuH^Dy_P{$1~0ddJDPI6K-=>-tA}_s8kQ&m9{F`iiO2 z54&8i;x`+dwXNlPYF5jcdc%E=@ zJGUu_sI_)X_{x~(c8dkkf+gX0@GOdZ^f!Bir=8u*c2-9VE~z!sPRh{VaejL8g2^@E z_15VhhTqtoRlGg0Re%R08lTykG&#>k$H;OG?PxM-YPdeAl~@84x0b0SdR_iyPQwjL zfOzRvkMM6G(ScdbY;GY_NohBki=00HWC7wyi!tGcH${u@PdBxhO6L7i^;_h$e=&1p z5E1oBYy0A?*7p1bLj~sz>l9g-++%p6Gcvq@$!*fKI{U}k1$sRv`c`TpxP%eA{zynZ z9r>9vdZPv{nYJg^?l!s!ev9Qf!L4N~iS8JK)7ewEp&h5Ju6D*c!^GJmwQVWYm_Oz^ zJBl@kCV=cwa{0^E|e9Yk0~Nr*+*>dAEuJ%ZJozC zg}W98LQ3@!Bq|8WxP?q5+aa7-XG>Svy9uL9r2FVGR7=hrKeLd zy04RVdoQ%(eXXg;o$Zl*tov%4Tgy}uUG;1`r?35nM68Y!qwbdwF~!S>JnzO)&^{Lbr>oXA2Iol%)*L#oKOJ;dP;w%bRpjkLM7OeN8eY8Q7F zuA2hHv{qfjdkL59-GzRzxJ2$KWt*4F$(?7syB}5Ok6O;{+%n(387*IhR-EQu(Vz`x z5b;ap7%}M8LE-m)f5m3md3DFTi`X$KgWoWDet~s%oaORR{gZ$0BBzmcDyizNUrcM( zB4^%=eMu{B{0ym1JQpjfzx1^=Wz!OiTgy}uy{N~Iq}_j>2I94U#)#5m&smjM4iB`0 zsiaivUimC3`SMRdj8BRar!Q2t!WUks%O#AEt5>zJiW4apK&{0onRid6@XBX}o=POnO%nl^rk@+YRQys9~Z&-AwkFE$`VZJ5vR% zwjJ!_57@?a*a&+7*7jgK4#0~(ga<7RPs-khy)%0voPliJLv)d-#t6cTeh&{i9-fqaID5EY%i}Q*F2x*p3UeXL&NC;^ zsMxh!-c;zPQ;A2@=ex6kn!T8cXFHq&sMSOqYP85s*C35x*_n#xV8lL{2Pa?-9ErJ* z=Ou1!5K#`X&&P;+9wYwYnV#b-jwNt*?d|d+!YL;D9{Dyf*D@8yE7*5_t*qENe4pK< zbP2(-GgUBJnu@q29b%I6h)p>1;wU57j&z7#Ga_s7ab72rbXmh77;AR&Ky|=TV4t4j|Fn= zfi(z6^eh#(2^sC-W9_2vNIL0WU!9H z`oqTBBOTTtT*Bukc%7hWe{L8P-V*E0$yj&t3QMjzOJ~6uoaWggc@2kqsRm9Sd5^ZJ}u`gqf6?o54E_e`Q`$3}sb zFjGl%N>1iBasU~xwYK{p55O&CD$c6o_gIkkkvX48t+DK85Yjf;QZBrw8qx9x9#%@)dRTr+yp~or7eYfnwRYO?cS|xxPr` z`Kln_$C)k84sz~H(?0sAx{>EmZZWvww>HbpRGgo~Nse_@jrUgVv$HSED_C}>3T6ij zAP@I3a&R&i$C*aXiv?R=54qP-$h)>e{*^Pdoa_PS(WmGE?ZvVC`ox2O5 z_BnWGgZD)=EqnG+#&b_H*=1YQ3+w_gRd81(74|=7KiaWlBKAOdhlh7Cf-V1P;us@5 zTNeA!fUV((okM4pSSoH4=JPypM%gvXt?x6QPGrQ>Ql+$9BEAN7WuO?rvNIa_D@gUp zz^&mOAQ>Zg2aC~|4L^JFaS<6W`vB*^`P3-S2w?(_#1ZCE5-55TTP! z678OJ3ht6uITdFV|6qDz-pkkAzEV8i%&^F82Y#(@ri%g(Q}Xk8%v_saT<_l6deW@1 zA#zo94m?h9F0HH?b@93G&gF**&XdS6d3wj?=bhdu*hCjS%dN7e-!5Y?74M}75&I7p z7w@LYWc3Sk_nkv^d3%uFzBBXIv_84LzDg*z-tQ}~f4CP`yt%-+{3O9yaYLTJx+i*y z=oWdc{+mwd|HQoStcUCs!%9Tm_-wY58dQ^V<$CJOMB0)4#1B;>tj>EaovHW~0iUJ7 zedjr&#p#>1tzqel>CBzSz}p%1_POzPLa~wJNaY5J2RFp{Cm_5M=EpT5tM+|uk?Yr$ z*3i>ofzt`x(_c-GcG{tRXD63N%fBwCi~UJoSzV5mF}TFruMM51a(mr7_0q3W2l4Z? z)z1Sje7D5vL&T!G%@njlq|5#n00CDto9 zq62-!E$5mL=_7)P%Dp;qaNni@9&8iAzWS?AZ_!~vU3*UX!~kN(x(}Qa4@Nmzs=OFA zW7BN3yn$0!D~!H6y`-ned7`|%x7;3`sn)cb=2HFLq2yDDoionaY5(qF=|#F5U622r zyau}T&s;r<^_9fNsPw0_#r zReGNg50-@axfW#{f<^rRi-Ia1Am#S&S-(Dv@9P09X zJGY6?&me!*c(frJero+XC7;ed{EO~$fo|Zu*)X@X$58t;t#js)#?(w}t@rx&mmV%u z!U))hi}viJcf;;RmVWu|6+M5{xrAlsny~Vk9%r2SZdPK#EO%CO>yoF!SVC?Sc9H*x zGmc%dcdo4Yb6}1-IDe7ZXH~A`rm3{3L75ks<_FW0A5F{%t4;e)oIFz$f8){g07CW~ z&P2H zR$=-(hJCDs-6ir=KuaQW%{H%QE9)GsQ#|VLs?*JL>uNe#mX!pL!OlSA=KL&nrAnU! z5G)C!5sOZJ%ea$Mvk(3CK!Id}m#=$1fM9-%#(B}=C5$h2 zN7z@})su5=$cO(hZj|}pS_fy&mI_e=D)lovz0%FO@vS`T{Cq?etc1Gj*&3|e4 zG}mK?BuRVn_cDK$Ti~8O&pEYda-PTYoZq%e9#yjxvkP3SVC`ItzM>L7H7i@B+Jqh6 zG8gT&h-4OfkxVEeMmz7d*$0Xtn(Y)Q}@YA8(6BPLq;Vh-ks}I{alXuu%or@s<)0M=2;VC za0&AWO0{(TIeYH@2y1D0_rS`Fqs%PN-%EaV(+ubSbR9gJq&sbwPIbbnJ{z+%m3&mT zv{Rw=`_6!~wF7afrWGzT&pz?_nZybehDvP@^;LeWSqY4t5t>8@@QXhEsX-SZ821=}VIKJ}-9FC}rQx+QQ(HyJOoqrREKCN))ad zSWV(>^%=FqlxZ*6OEy*rtXO!B^F;6GBz5TK>^>m9=-Da7#j=t0?A7b)8C=qO=LqLm z%eS4WnZsmEO{=00^kyQ>CokFy7rqeSF&1YFuAgn@wAolTidO)L+lSW^$6xMbFK%Ac z;1WiddnP(RKB@2g@TFXNl}KzQ7Cj8J$4jMs5i(X|wAOgKGvw=<&em0OuB~|K zEwQ2Udv?9jXLK&9^vj3N`>iWGHL^UtD*AH4a8WgDW;=i8elliodB|vz`K_Hh$Em6p zbb7omV}?Q5;zZ;`D>2W$)iRQC5i+0f^{expsdpbFU#^}fs>zB4PRCdGB##r>fVfv@ zv>5edtrhj28@+}Q%r76%71BIRHfqXfY1BUKbFSWQrMgj6=Mv_@ym14xTAXOm^aX3w ziyuZHrgBuqgC$vWb)nPs_}t`gHfI8l{J+PEp}Q;W*nG>)mq4mLZcc{Lh##HoEiV`I zB1^=gLV6<^iv~-0kCwALt*^(4gAG32c`3&i;mn=U%nv@XWt?c7DIxLamLEp2>`WDG zd6m^MqILH5R+}xQbRH@0H|}XotDe+P{PSC8`}NpOI%@`_dHgl4Z|*kY?u6&X&m@+uIMiUz$sRR0 zfAlUp&pusv)6T=M24@_mVl>WWOsZ=)td!H59v>5!2YD{x*#~z4vW8aT)IF91jCx}?zbA>*1jJ{(e zA~KHKI3f!o7WB<;{5flpwcpzUQ^@D#KPf5-$&2c%iwo;CB#&`BE!kd`lF43ZB|+9C*{+5ea2M5_2A}T5`2=ox zuy@nt#ook?^@$xmjR|BXm|w6R$c4L7`8UJR?|U5YmYI~w%Y}PVsT?`-yN1l~c0zua zb26Ow3Fb18-!)DmzdIE9UCsz`9)=~vY4s+$@h)=VGms1Cj2GwLSS#^%^o(`vF4p#-eIQ$F$ZYLAWTQBT$l0i1@7_R!{3YysA|hnYO>%?`9-(Lux9F~p5Q`Rl zX^m;xKM-Z`oDs~{o(dZ+5@I%4H%8?P>LdEB$YW=0Wd$+}2(%u^%RCv1%Q2;}-W6VEw)jJcySg?Qy3x$vL-TpwrqITz0S+>Doy z8Lv6WctIONdk{~x7O{k~j~{YgwA=exPTuq2u?fyN*ei0iUG5bH?Lca~s@K(ge-8=y zM4|GDydS|5!ag9CvJdPP3AtC42YW>W2Jh!_HSD(`8*~HWwvK zZOPPf()QZ_RK&#JCx`xCLgH_OTK*$fKhml;wG4A#icsHynq0&qP+xuuk#=}CWYwmc zv5oPf1J>sX?Mf9-QiZrPzh`)8|G~piJeZ%y;}Rr#BBjEuUulPht9NkUmQdgSj(7|N zN<#HA`dP$7P+!46g$H+X@Q-Qqjxptb)wj%rD}J6-H$naPQwT{RDQ`~yFo4#yUwWmk zA=_{P|8OkIaZqqQ2rlstKrN+W*;&G%R6Un1`|>2Hv!x62;P{I9A!{%o^H=+TDEJhD zV>piOf-OgD9o1Snda_s7Zu!*hC-wKpcxBI2Lqq+t2=|TB|M)>ww_Mn`3H@weee99Uj!k48%`B{9j?$9vfv5#P_N^Ed8S(7!;!@ z0W2t>?VW_X-Uk(^MlniI12(}|V|W!TX?R#gR0JeQERhh2u?R>?#2TSjEbX^&7zqeI zLa-VTf)*qyB1ph0K7Ov&@N$TXM(e3=7c@{ z2cKwaY%lT#=7*hXf-7OR0_NSTBeA`!!(Q9eB9CptmS!8K`XTWlvk%(`UXrw4!XAS; zY)m9l4m&Lbg7xJcT6gcYrm8g38;H-d5WFYH`(-#8z4ynk^((eJ=j|+8skf(nA1Qzg zA2QgYJRUBhs>g~u?*O79ODnFUxW2-8R4m_?1M1^IIX+6&onvV+ubJD=0wrs$%*rd? zY&N&f*zc}&-zY2(=Y#)OSz2)p&z8pX!Qr`$t3W*-D7Ft<*X{Y%Da%ZppAfBRcZlZ_ z7cqF`X9=0xWkq27FqP|x((_zsBvH#f-+f?B$ulP&7-pERKXC!$92#6nh+3FU$#di%e?RdJ@z!zjF)MRPLVsUu{=6P62gwmR4Ndan*+# zn#P41mjO`*1ba2_4zp~W1=#R<;uH|=_;75qrT=SPS)oRZBcSR~eT?G`kaCOI3A5Q&l$xS3cEn~t~WZz{@cx!S=GBN?wHCZya66OjS zd#~N*hb05}ISau%^gK2=U)!{=;TWhpK@QKzJh!`AiSHf-qAL*a*QE8=MeT2uT)48q zlV`W=$4b3ZTT#>sMD}{l)uj7e_3+93@J-fz!y6C**r0Vwux9uF6> zdi0QV&)JIn+{i_gO&SpC1^x#hhy9hU>mp=|6Q4Q^1bZLb&9zn8*4^v2fqE!V{M;GV zOnz8?gHdKN`MT@MsX=cm1FX`Bsz{08G!D}i7i<++48;WzIeo){Sf87)9?JhLad z2=Nk`d4>R$rF;4*J9`XH>OD7Ti_H_+8@RWwj6KI5E4%<1lFe`n?`!aLZv1lZ_^L=8 z8f^rE$C+n1=A_hSj7JCv$@*B6EDh6r!jtN0=eF(wb$_7PUs)?xMp>kHV(=AVZ+mCV zaP;h-N6?Cl%{c)#SY1$y$@95rT&~! zpmVY__~a2ItpY`{49IU5Or6GQia6jIiH>$}3&N;oXlzd;EX;O!IoSc5Sh| zM21rvQiZJ4!el4CX6z&*gAw+-)Srx2>iU6w{rP*Vz3a-}#|X+F*&(RiVJl(z?$+nC z@@D!YPR&ip2&6MYYIPUUt-iLnJ-ooX|GkUvvW%=ffXv>2>NBu!T(s&9t+)=C91&w; zG;}zrO5AJ|y7npCb5qF$TBQ*dEgCA-^U$8SShu@amv#pv%a>fi>>32Mvv9)OxQKE2 zh-8eKsh5omqJpKV+J={SSHMe3;U(N6wYhwxR%cF_+R+E;i^!0kie@5%sqA<07`(YW zyUY`BpAT>67S4B=lTwH%&qkDtx5T-~;B|>(Ua5ZANiE0iOrjMdn6LdVv0`QhZ&olf za0|;|PPmC}UzK<2p4a^Lyt6Wwq_yJrwE3NM>}lb4%6i;PnXQ#YOJ2fgoD;@xTFk5a z)Box@=>+J#TS;Kcfw?q2tCN=Ix-%Mgo;~+ae9Pqd`q7+gwg(Yq zWbnx#J~4z_#acg&A2~Qxw|$ZyWdv)&X#9@JksISn9;w!|mM&~zUPEi{!QIiaS83)h ziFxxK)x_x={Ry+H^}+S!66ZT@3nTaj37o0c#s0omp49~#S2S}ApEzSqN=^P|RP6Nk z3-r&U55<@-pZQ`=K+HJlhk8Awzf5>y-J~54=F2Delc`TU}BJ|_)IL`?7wQFKC`roE}ZszGq>=mU*?3T z;V)L}BbYCrIL58n11k01E7tps z6Cy3#!ZMgs>Spe9=2mVzJ#o&Na~77-7KjVe^*@a}{bSpPMY*>uk2S>U8vMq{;nn$i z@$xUCJhp5%wzN`1=3b?*|Lqaoee=aA`x1|{>sNb+f8@_xU!gy)8yVx6V6S99#(Vl- zjf(w(`1lF&!BNZc!EuB4maqmM#+}Z2mHAPg4Zt@Y+t4aKk14e_6!!4ZuiiX5#&Z-? zq35z{2Q$MjxSR1Y+!)%aVE+i7YnckxO|KHTU-av0@A%NZ{CWXkYuWga6PkQd;gY@J_+NAd>1o9p~ox=s0Wx!WvZ9^4! zVt_z4rfo)MTLRr>Mm1FUui5KQ$pC+C^DEmD*e6XDM3l+9Ozxv??qgemF_5_{pyH@a z^-BKc-x;ah!Cn%KM>3_AkP5vZxP^T;)h>UVF((95aeVv_f}+TcJBtZq1pjT8AR;RSB(*1C$IvTZXt#}T%nZVrn{=Tx~6rTrbT;1#zgiD>mM0W)G@edv&i_U zreO~D|M_=6FJt<{skJ7riI!=yAJ-V`rf+>0ZYGxXvj4QWvo2#CW(yy0d)1Du_3A9# zT)*GT&RA@zKX$iR8!e+ek8Aj3*vIC2?er1msA3k?kCqrK!_Mt)Oo%arKq_C4Hu|eH zk!H@xp8r8)zF5EdU_z|(IIba;wk1@L8Wm|?;QvMJ^6~t60U>+{fmBZ%QF^bYk!JO7 z|3z$^ccx~hbU%pz4-N}A6Gr^E z=Qktf)tXKS8%c#!E8}|T<7YX{ji3ID*vqT#l{6pOeU5AYrP>zhFxTbs{?AxV%D8OL zAwuLJgf;GNDx5)eKFVkL!zPUqvQ{-+dgz_?wL=`{jf&sfT^;K%&1&C&$FFmk;oSP| zv2(I*Y2p6zpS*L$wAjviHj?CX!S7UKIyua_#s7=$vn4G*JkwX!Z|^5>W@)8YDG+Y9 zJnLmge(x)H)>kDtOh;`Cy?5I#?Y>u(+}5F&2;b96KlRmNrZ>Ip$Pdws1#RfbPaK!x z7%MG8ng{E)IuWK`%FB-YdLC`5*KQkbX1ijIbWnJ49`ci2t~+toR=s?4{k|8?b8#;_ z@VNVE1BPdoBMG-HLgJ=DIen`vv;G@K{&4b|)3jx>u`^t2t;sn;$A!Jnltg5uL)Wi!vi3`0X=M`obQOW~mVBIq*X?W4-2NkW>Gc zL2ihvzze?XtA8CEVa8qav?CgMGd3u=sQ7JHoSYRkTUa{k)}@4VJ@n0!9HuR!w|!2n zD80@qhxyT^`I{y+clN(IL|&>Eq-Z<7D~M+7Y*1zKB)Gjy-jjyoTZ`{JO32umxz(Jt z=e3YSzxZ;b!gU2lfw8JtF4(SZYbC#Z_Tor|YZuN9V?`30Yr8Lm$|_SIDJvYVkEk(> zHJI5(o432S4C=Q^Sw(RTMm=V%(9h3pw-W}*x^F_1l^RzDe7hKHR&S?&UcX;t$<9F< zQsKIS^TgQWn>Jao?4E;X7nfJ`YD-K{{leo&GorPpz4en=eQL%?^Wqgtul`J|Df50R zDnj2?;`n6I(O5lxZ-n`rG)C2u9GjcV1%DM0&vYM-RJAh3=~1^M%yYC-SI8cx2b_;E zuimnF{5&UzT(a^f*=G7p4K=a5U!2}>T7-G|g{S@cr&#?{r3mwwul3fh$Xi6d_wbVe zGao4k=YK8m3HBUYV(eUp3BqHcLk6ri1isI;Nv|escbMz5dfPL! z>8Y>U;V}DqSo_DPFGWS7=O7st9;hJ#We><6tsgcVX0a#MoR2xVR@8ePBTMDUFYpQS zz?K*bPq-@vFR3Fl-A^xZT|!Bw&X3Y3A8?q>@>x=?_2?*miY*|W?*pav=D7FQIV?&) zf7W4U@bk8}d)PxSa?xQXmaq_2AFL35Nfl*zSytgOxm}dr@vy@jTZq;~Kr=S;d^a(u zOHEmMbvda%0e;FVnt5<%@!Nr7a?=V;s@%KjKX&~eXvUi6S}6{0tteOQE-SHzic|`Z zM&9eh_|wty%)kx;#|Otv9o@l;(uvR)33B`KXboo#sZhrli>NfmX@4CpALlhSe4kOn zQS%wg(Ydo+vVN7g@%u>)*9?4v@ttQZZgF#YWMvUiJk&>7uW8C>F)kTjqq{4j(_bakXcK&JWBU;I!54{vi2KPSP?P%u=s_tC(YYX{T!JLX+g8M7( zsEh^Xsw}FuZ7;hfrBSR5oHbnSXx*LJ+?nOp5E)ZCNO{lIed&iC%-HPKMTPg)IC*pa zY=PQ`@1u&IJwJmy@+pHX*{_1KtKmGOgp9Qg%OXDaxGsMCHA1oBa3{l2pdDvfkl3F8 zhVA{D!5l3w+&K}=*oXrww3jm;iMAixaJ25w3d6Z!?D^J*+N^~$ZDYx@L<=|!?|TE-wYhBROE*m!&u*M;XL%>Yv;1vw=}ebksqQNyAV~J7q4iS?~~5j(Aq|R zsG*E~S<{pEx-Lbj7o`MR^vDm!qQ!LON^x}mznn}kR*ED43a22BCsXKy2i!xB%f^J zLhw|9BZ}z8pIhh`$H$s|8~e~6wc|+y@42h1xRv?1z$c5-2J5Fi;?32yeC*f~W4WR_ z^0wDYYL)MPRkY;itik%!u?c3_YH$011ugZ33lhxNf!02FF@6aDW7lZg-Y$(4L|9T& z{ZWqr=GXV$c0@B4)nSWPt>PMOcLRr_?L(J_=m#SPnAa|O*$rE$zIb%JId8mW0qprH zKfga`o>usnO+la}h-U2XC(T5j8V9wcxG3eV#dgc>?5WQ<-P=5z(c;ngQIJe58>3y! zo=4d~@I6-%lkPVY9cv!c4iXQ1f(U$r8G9f7O7rNqUK?GmB}Yk+3g1WageUdk52s|% z7N6U$VQ-O2ox$O2hVsm7mpjLF_7OPGI3FtFOPS34a=|2VnluqL4mAdKjIm8^x{Hoc zyM=H0DCPY?8wFcpEJLAseE&O}xE@)Y$1Uoww=Y9p>UB?h(r^9s(PtvelD9qWncu|g zH~xt*7d^A=_H^l|X!BaN7mahp@;jH}^^<;)=FrC~RnYBzy8TInS@D&HSdlnILs1Pu`4bF1{5n#_uT5T#ROm;khy_KP@lBUz zi4P?*a_nv4)A4$)>*3~+oL=@lA=L9s5oY@Q);sv|oT=4_$R~GsRp%%#_Etsw9(>>V z=gV3$?as=IRETb|te+lKI>P*|fW;&3*iJDsv9=sGI*)=la4b&mSR=w5n9u7!KIe%= zt@+9JvqiSd@3pv#G5XUH4l~amUiRtZWAyNC4)fP@|LsR&h0HvDV;Q-wVrGuqQFcT# zwr^ZMZIanV>aAaBC<&r7r;E`){OK@95O2m#O-cD?yC3E%T95aYbcVc_Pod8V*F*ZqSE)$BMp0qRETD5{(~*ryq#nrUpb)k z9MLBh_ttyta+pEyt+C1)z2Die<1cbhk8%oP@|9?P>~V*A@a2Df=Ne5KiPqBx%9-0r zYDk6tC;C1V#p&3RFRQ*+%>Q;ztK-pIKhxe}{#nY~p7Ct7-hU4DyqLE#3XHuyRE(Fb zUR_=(xK=}XvA2jO`yuOMt!kk-`RcikA{C+sl#kX&3y1lK%dgF}ce!X66)OkV^A`U! z?WLDH;V`4Jd)v`>#y&B2r*?a8TP;NJi^JM^TeN&ce>u$Cr7bHXsoFBJ;6_JT zfBFT{abi!s>@|vb6!x~GkBi&nABX_YrItY zf#~U(d+EF1I83j~R?nLrpDNCDuPH}dC?SVs>#3K1NzsUs-gflpaTFMon?GMA-i1xp#*FEuXV~d5YXy7TW2g4g6K*@q0(82d_Tz1S8^1ZA zqelRY}kZIk+)htIqjic;uEw>a1_YOn082;>?|YO>@KB@F3OJ5Qp77u zecotJ9$BbV4}nxTJ~$$b9sJUh-$-062G1I=Ar#81#(B(RmA9j^72geo5pVrBkGADO_16fI_pXL}2JXAqC&s#* ze0lKBk^yqVq-jdz4lMw6KR>ghxt3;qFF7*wH)W4P*;T}}mOk8TSY>(c-V;SClpS|! z#+LfF;e)@<7Jp=VtKqJXwifn@&L*A>7k?!6lIQj>RqPUsEuxJ=`^WNW8mrb?9<2OX zu`*D0716m`KE5O_zijm;BS)!FcC^k&Dq9PlbJ%hbckPpgmLA%>*eAxexA2zZ!>Y;U zasMcBQM9Si)~0^+*=@VEy`G%-&&jwFUe7M zq(YyXv63HxWcn&G+WxP(IZA^4z=#E7*W;Fp217ly19rrl{$s4Mvb781dxmxud28h3*jto6WA83{+EejnPC8v=Z2G$;T2hxJ?brzi zNA4)Q8u4n{JUw5yAg31pC4?h)M0-CB(bxVmz}$Dy;&Hl9CH{+Ty0gZ}IvlwpdO@-F z`l?w2%xZsHh)rD@@nKu1iCU*U_|64g^pXF>n?(nE*%6(#VS7D#(*QG$vPei1_vGTO zzpmD7Gc=CeQFe@LG3L49C%(Gi3!CFw4UXIqU1nQLea+ScbFC`^8MY~qmsymqw6CT9KQqBRrdu|3$ce^$puR{9UyzB{?$BOON*-XYIq79bw0%!YJ>8WAvul8b zINrMhUri^LJJ}ZvxufiAl=FYjJMkG+ruol!k(MKOL|;u8tmm1ZVEU}JctmXo;kQ2* z6=$BOa_<9FzbEswxc9!KdLV6%S)eq01+z~xhpHB@iH&Z;BvCdhW^M*sWhycHL8d80(-c+|Q7+@~V^j}1mokMxm48=uY3+X@1 zH(0-uE8bkA`Pfl*jFB>yKFa`Juv(;e=_Yu;|BZv-J0>g z1I~$rQ#VBGGoAI`<9nK&()!p@5{y988GWrDyyK%&;`Q~y0=XjsTVl-FCYn!fdr$;S z_SVk*)KY&*^7fAOu_Jm+aHxKETu-x*m(`CY7rXJV{%gfn=MJs#FQNLwAw4N>=wolv zBvh{-(bMc+#>bves;$1aNQ_y(orQSyTPRQ8ewp~E=Wz|6AU|x0@~_VC&_2%flD}@O zr+BF-yBa;OIkXZ#)HH{z_vMj5Zxm%mG-H?YhVk^RUy3x5lbz^|q9llBY)ILj{878* z;&Ji>4H4*>jvCli&(b8yoJQ{>#gLcw;DfGC69pcu((noLz?Mj_M0fu5&SbH{f0Kg1 z(M2?4SMN3DvF$R;)lVl2lov-q<&n9^InBA)M;01XOX8SdJOI&*E#Ldjd9MB$k=d@E z-C@)K(PT5s?#PD+EfRk$|4W&3)O?(O#>y^@;$M#cAr@`fmGuhIxUMkv#2&^gln)W>{jMq}SlB0g=NbEI zwC0iTHj5Dt?kVdoN`fm9V-J?ZaE~2hM8na;HRO&6b=|$4c_@$DR!M9!O4@McL^Q7R zbYgPg7ryP&SZA{-6$S1rxH@A?Bvni^zItMkShw_phWnkqtC?Q#_XM-`25&p=sEn- zXtbOdt6#ViPt=~-_M}b2u^)&=>x{8&`x^5K>oswvGNld@a&gr3T=Nr z#p*-Z(aL0OXgiH(x|?)xZT|8cxufi8$uc%Dt};)`m`zJtwiZYG6VYfb)2U2`CcNA4 z3&pvxOp1k!vZFmuR(Q>y`PRc;Vo0ev*j}EER6H+~9X&nEV+qnW7P4u6+Y^*ieUu%&NyauV)p*661;o7G zr4+vwy?FF-8LPJ7nU?R$1ZVAn4#i7F*;RyhOWjtst-tMj?5~O^jIyJz&e&gV4~fD* z=hu$q?WN>1pzIhApuF%arEUCBtlWHRv(|S>WaXPLCYkwHPt^v7O65$yX!&>o@^l+8$nuQLTm__rsbL1 zCBQ;#JK||aDxTdhz~XTCW(Qq3yV z--XDzI1?d$$-Y$!B!qPdDC^E=E<{g{%yy)5|9-VKBO!)m-zor+Z1sGxmeE2aTfMcY z+`qr`n45Nku;yb9Nku$dh!h?!ghfRXx_*D}N10*^h1HL#)N|^G3z5=~R4N(;*YEFR zRkX=S5lo2ZSGrqc8^#g^cXdiu>(Q%wQmF4$=lo0@{a9G1Xzg0)3Ym7sG(#ho?WVC zA|Bat-q+5}Smr{USmR?yD%4O~sr7T(Q{r*Ju}|xsbjO8QM0b9W3N@6mXA|FRX^F@9 zCnL1ojXiZssuwm-J5r&BGS+)xWNc9vV(#m#cBDcLWvuz}Y&;zyEZx;& z%DE6rVl&&3%Kh8YP!~c1!my-@x|+d4xMtI$a{sn8l=4OQW|C=$M?sQ`c(@QLJX{Ei z3N@5+aVEYO*$EL#J*R%S5Gnm|AuK&c4Q0$%KPN1yrqSrqSh)}>W933vdW;%MzS`NP z;sMP^Cz?T;k7TPKDf8h%SbB^aN^5&ieUX89TqP}`Id>sa=G=v_^cXdiEP&%V=hFYjJ|fHLJg&}yTMs`3qm+M zzSUm0^wKRJS1M<>BNb{W#Y@ik@s@;G_-d0@ZABFqqUK>QJ5r&BTG_bOcr`*a&GVBs ze{(|@qS}LOcBDcLrLkI8O*SD!O+s|{YHL_h^)WNsQO8hw=!U`>KUtCx21!LcT!<7N zsXB(*!&s@oS*6wUgVb~ChYOL?k5nB)?V-3&rSqZ{Au7`7(pb3=DPxtYW2ilh6|6o= zbR)#aj}@%>NVfWsG9RfrhT22XkBIHgf`ph!T0(Q~LZr-js*d5xN2g1pF4&INPb>dt zc68}gm23me>=Sdl^vdFA=@@DcW08#(YrzfD%A%gZJkp2`un;ry1sYrWtxAxGP*Za2eEg@PH zqRz1Xh9y-Z%VI|zL+xR#MX^BnfDk50MLb-H6dtKMhT6ke_tz!lDMCb12SL`pwW zbquwK)~l|c#Ct;Qq0yzWav@U2Dpki&dl*~QXt6jzh*+9InvZ0wA1U*Zs$-}<6nhOuX6NtotFCeMB+o`n~CK zZrau64c)2b4!GgeU-#ko1V;h;$5_TbW%w%Iz_~HJp4AWC-H#Fnf6^@;Rk!)tCl|=) z`dvD6F5iPKZJx?7g z>Upxe=PH7FF5ErGcB$tsv^D=UA};jzv8pk$zvvX<@4VMykfkN5RIK`N7uEdk|3!@Y zvz*$*Es#AUJ6pb|8aY~9U8t%v~`JA=O$Q<>*ip~qOEAI!z+YR@* z!LtEPjm)RrCk_9!sUkb}TPUK8G7196jbdbmJK{}wmSbzn+IfeInw?81nurooq}cco zL*94EUv5d~5GyOCZCcmN7*aakOiyPBsQHYgSzB2a zSbb7t4J^o!3VW_1y2M1uZ2K3AyIW^#?@tVLjc(oyo_1Wj$lEsDXSZa%=IJ8e?%pgK z7CoS>aO9sG?z2J_5&f*CTu}G2(61a-5NSKNHyEAD4W&~#L|aj{AbI~<8hLJqsURpO zW4O=15KZfDW1FmV=B4?0bEQ{SYSbm3M@8^7k6VahXHHx5 z;aVB2`M{HLHTpp_$URbK5T76qY>6>@o-W)ygNVQg3!)kO<4H@tw%%ni?dnktsW7&r zBEohD@%;DF$hzB14XLoVDq^K>2oOx2%9~Mv$*jtPgQ=Fk%8D6scS8;k~c8*Vwhbq;}(+zq2x#6O!mXuq*Pt4>* zsu6oz8^Kw>Q>lmzt^N_O|6MH(HgCt>JS;C2sn%BxGDeLboxq&cIU-GKjQ(WyXslPCJ?e_1#=~SlmZE<&0sLZ{8fKb}a_Aq&J@+21m(PU*5 zN)jKp^pzVo{$j%?$PZg03%Pj%arb6(`Qe&}bjOf(AJ1Taw5d(eVjvor)0kejpNxKDUjmlPK#}9Cy$id$XiMH1P}gAr#%ZH~U4 z+|rWbq$Q*cI>bv-B_!?9f9Tc8*0;6iH0K$<&v`19mhEAHd(Krva+aLjNxGZnyY8m) zAl=p7x=Y%w|IqeuS%*){U-|!u`=EsMuINABL3(Ss_14DITZ>QVeN6S8+-NJhLnpjP zgZb~j<(BWhzqP4U^w#R`x0Y50{l{8Ds}HwUp9{45;1gO`bnwDbTcS5=Y&0L?I4&-J zUwu-kX!X(Et55m;!}SPfjCskmUj5cLmd{wTO_bQ&%O9VF*hlHX|MW6{x}M37{3vSB zHJZ=Sj*F}BN;|RL;`@f{p(4hm;n)(bq7D1-OBWZ2#i8A`L2pLtSLtNEog<4KcVu-R z%)L2|*I74L*w^K?e9qK<1g9CLx85CPuJX%b$Cjve!qG1L=G{BuQ($|=WGgNcELS%wJl?Gw zqJK-{Fo)&#wByMJovS(fa^Jk^#Kv;#G^E08Ocjw~eII^f{32)j;Qa~$b8FR{)b}I1 z^L*8Wv(D@*nszTv-#4_YIbo)k9W!tdO*X?92d`6Nm6O+eq#!W&7}1Qi3<~A_(q(r( z>diRv;B&g_g|c)uUoZ5rs~Ol8%7yXZgh|f#`ClrxgpdceL>7QEltnz;in}+RT zhPujQPl*ov-t$D~inSRzW^Z6_KDI>Bs2c70Y5QU4+iMwlf_E4F@`X<3{(U}nv<5K4 zgR#8xoAcn^*PWegz8s$*KWvGzsruI9TMLJaY{6wYaz`peQ(nfaj{M7zmd=Q@={d@d zJ;# zS5^G;;UydD2k*8wlltedXZg^;<)0e^bI=>LU26Q*XTy2@OBn@$ql=@!*f`$+Ug6F& z=c9flmH9v(Xl0Vs_tK&D7(2rm`e6_!f7um*u>9pY2UgZwxw?~C^9ga8A8rJo94qrHgBX^8`AV0bpRyCJ4y-gMIvHM^JvE}dX^;*^LZk9Qg$F88+ zlwpr;Pv0#Qu|4CIm?g%RE-ZM$?}S8|gLYW`IM*SacCPS3(d%KH60^j1&kcIPt57`X zt_zWFe<^KG{3P-3;eH&SV7thVv43ZW*shdcB7*Jl9I4ja_o>_UeUw>XOCFbvV(nK} zgq5*?Q>Dc8-jhV7BmI=98lk0I_R|Aj$RARj%oE~lU2ci^LOd*c$K6(ztRHq&B_4%{ z2cqc)&#=c%Yph~utndj&xv(WV!Afg7V^ijwwB(RmmuSupx#xV~^E9sb%y%uJIT!9Z z$H)yvbVwHt{m{f=FCC(1itgeQDB8G+2<$Ofi4=9p(&JFppSzn?NlUOL zIzNxgAZni&Cb}8}6a9I`9`!);kKy&7-4`X}7%o5Rcg=i`1x+u`A6KpiXhd`z`I z^7`~i&I}Pw4WD4U*b>!e*wII>2wCdv|74%S!*5)FqeRaLa}!k)Kz?-JU{#E)diW3L z*NaICV*a-NM*YJPX4QW@?TB_+OVVvEA$N?hk?mu+DWmJS5@T7&v@jdR78i%8} zkKw*6p(4Dx#meSOvWvxG%QbwmXjOlsP~J#0fhsQ`Z#u7?-d8pq^wk-jZi9wY*bfyk zBuAv|wm~=(rrcCU7v~&DnodkMhsv-C>7DDRe$#NyQLk|RY3D4~PrggBMR9z{7B$?q zDA}mS59>AEx1O?InRm|TAxD*%CCZLy+M}BHkw+TO7g;{^w5)K$ZG~f$f~;^?)X+Mu zaoO$ia*ExKPf$W^i81mfip_v~2JULOi!wHNWM$_=|0N$ zpw)RcOyoW^fTO*G76;lWt{sPONZE1F=ESoi)lU42V#wB7lAYEP^sq37O!JW%Tc#6} zZ#}tAZ`3n-qtFMWH!9V;QxWt=arYaA{wrxls>e$6pX%>2M%vEZ+KwJJ`n8Cridp2* zTk*slHQFM@7 z(ZQ?~VZqo7Mp#q?MeejaDUmyj4q+4rqg0F;O&e&dZZ(%BC=Q3QC5%QSjiph zWAU-J$Al>Klg)`w5V2+K4ZdD;BU(?5wOt}abXl7dpCBS)yiaAb2_T$q1U^9owIqM= zAgP>|RE0?@e1Zs)_Rx=hP|uxK&udc8@d+YmL=L&*m!wy{W1Uu%^8rOUG5(2Eh-QqU zoKAO?6Qid{MKkEirn91-E-evmEx`yaQmHXyigF5floOvI0;9u>Q3O(05y-R@fyBr* z>27M&S&bo61X8*qkQi6T=sCR~uAG_gZ&akLBi#{5dhb%B{Yd5hof=P+Cn=uzmg0$c zqJXCWcsjrsog(uiDW}MI&Vg|a^wk;rb!=^3lTLVR&PiXK=$938#t<%1uv{K`lDO!E%&iVdRW%+6DNwMfb0gmU6)UL~Zurf!~6W&*+ z8_IquCqH;jj%U!gi_%?yUeCm?lne+wy~jKNJneVoGsrb5`3#sLfL@WhJ5#QKE6c*l zHNboZ%(B4T2J#0-_Sf8*1DIuju?2PKJY9B+$Vs^$vnlrj_ifzI|I-i3FNq*T=9dkX zJQ<`?`;mrnSQZf?Eg|s44K+jU$C0vIv?xN1BdIXc1*z12bWObAJWJU-9*4hYY`Jr8 ztd+qX55WFWrS!&&MG$50-17)lvcix`&66okIYm}h*h|VO!rURGQuQi<@|Io`qB`X* zVSW-)p;nUrLAg;@#@0*9jlvu#q(WPpA}o}D^^_13DgO%dtdL5zMITd+mzA+Kh7h>Z zqn&{E3R(J;M|PhO4@oM_1VbwItsO(TYSw({)N{->Ln_n-ii=V{oHbTgX>>884XIEU z7<<@wv37(I9W#G@ePa$?RVQla)xRTat?tx1T>lrM^Tp-83fA7d#ewE-bc5W;QU zS$h%c7-|pQeLd^P%M!w$q{7Tqq(bd+_1u+PYxNwnW04BAhvK`H&udnOX$cx#%)mt| z)E>s#R2!vP^HGLo5VL%d3bltZpB~$7#R)Nnv;^~wkqR}2vHmB=I&)BVbc>X%dv~V2 zMdj8p)E>G8LHX2-5cesc8uO-+3blu-a#7BBPu&ty<;S|F8b$pjzImYPHFwxg^p zc%*Xw{%$Q1A~jDRy#}{dT2$`e->s#QbQi$7J+O+TawAfBxXy2D*v78)hv+f)8B2C159!P~+N!3U$mv#ow9TWF$Co5aPy5VF|x%C(|l;Z6V z-Z|}rSVi|(@V*LCska9*n?a%>AqLW28N3sNRO$_d>y1YWi$}R@-8H;-gH))Yj8&jJ zKNgQRbms@}_8^sd(_$*!E3$6alv=UY=Jp4y`$I^D8cKH>;O>&!Ysg8rkC4j!`}>U% zLZsf0!rTbAR;Jt-apgIDzcI3k?qFH-QHP{*BT{&zQlW-2_7mOnvTi$tP|v9!u1t=U zez*`RH%45)t-By}$E5K{*X^@Ube9ZogP|UyhB8*v4082j63rmqI72GbP{yJkyt7&J zF_p9gZ?z#6YAEGwUoLI4ZicO(+fI0M4yjNp>Gr^f@PoG-CCY3`k8Rcyx9*}=TK{)v z+|WwBxwO+l_<8vo^v4v z9PDI6D%469F?7;B7s71$k3UkOR;q}AUQeC3sONOqX*g23e_Od&Dq?7JxJUCOXb#l6>`j8$LmP*b;r6tNakzGN7(=XoWT!Qeo^}J^vWAB363WtmD6B7Q?` z?cL#j6&`p#q@Mh|Zr)55X!O`NJXdZ$t87E#*Q@Q#i}5+^XBKod?*Ffo=|h<{80)9| z=fTb7sXdQu$MWaqNQLdHh$-EgNxi_owsyC2Ddz@w`ii_M`Y|y~hJGAnEBW?cD;FpA zWEA<~7}B}(%2@ekZC(GMrCXKrLF~DTh^R0`zI$HB*`-7qE8d=Z&V?h5GfStIq$PI~ zFFJ#kOtqoL;hd|8bf15bPo|U-4SP;@qV}OK;aflzFsWM4#)ALa+R|9jnCR~Lz>E|c z-PFt>swvyN8PD3}v28ZZAU>h7(%mzNEs+g3F^pIKG|IM?Mi;4Qq*Jr0XxvgWxu|Z` z%2>W-SzZ5fG`cj3x?6XV3ePDhaV(G9l>LwLS_>o^|E`h0sVt2HoyY!}t<q}#_=Ge=cdw7wl52(I zEog-+ODh~of;?2jp7KL@1zN9W(RziwMcHxGDb}|NDJHDy>>b>!}tJ)jTrX zm6;Ju)q#v3)vP`(=^;l_g{JCMp$QRGb;xj6w!$-3SA{0|m?|`_rwUC-h0$RZaeTyM zQJSg_J)^2aC@=PwD)$&azDnXKqRZFs&xmu+DHaFvBAV*^81Bkul*y5yr~G*FjM)3r zekV$WXsRb<{HRCv=C@G!zmR3(236%k1l1`r+*QCZ%I&J@B(0iGm#C%_QsM0?6|tc~ zn4FtFL|iU*)v9ciDlhhSL7HIWif6nzo4&L{zH{Dqd8PLhap6QBtAbgoyom0ZBiMMK zJKmf{wdoj3d$F%98MjKbZIeTh3emBdgN@OJ4dUlpQ_z$ zW)vwAZ*HcVZjAMjzsTz6$2yDDs3?#-%1*U@4ENVu$jbP6sC@pUtSFVgf(^MNnkoVr z?&^Y6YjSUld=@fVMEQ--kUOHO0+I2fCSc6j*0S@1&EnPJdm7$XLo`)6GTik6>6mql=$7MG?mI7(L-M~Gx|}D#<{Kf0loeK@lg!Vb+0K7pRt+J;T^kc+ zS9{)Ja3?urR6b{uzUes1iwJCqu{j0W$q~~6MfOSQIC4ic)hsf8RN4GAxrxmFWQ(}A z*j1e}^>!Zi99yE>XVH~qj&E7D7L{x9)sI7rw?hV)GpJT6NC0;m zmN;M5s<)KN9TC_P<+oREC_j1B6h&X;wW@3y?i!zn4lL2$cr|l?>E)_=nr(k$`EuO` z;YU@V@Ma<248)eGQsLiEMcGMBHNPUERt+J;T{{*f`QP#oBO86~Xcv9$h_SG31!ZDT zZkt}WF-Pu*z?P_%MdsS_<-2U+T69G&8n-w0ZyaDYrkbmWrkX{@k1DiVGdGbLZ!8pD zLNZy^TT^djVxO=jik`0z5=m6qs3cW3qAEa!yZSFmLKSI^A75&^!0w9eqPFeSlL)Kc zQYv>uU`wRC9ZSoxKDV6Xe&be6C&OI>7tvI+$oNr5n5sa@TT}&V2UUT>lTqvww&bd8 zq!mi3Y(y1|4EL9MP!g&TZ2b5dRKAwFvvNxHB&w2RxW6TYk|3I*Y73r;98{sH4pnHP zN=%0Pdqq^C$#7RXMl@sQW?lBA>c+>Zx-n8A8c%y&b)%%aZWK~sj-QGc{8M9jiE1vN zrJBq51jh||Q}q1eXmL5Et~1Juqkz0!wWBq6?Pwem9BD*TrH~InJR{Yo-b3}Naonjs zwc-8(EutCoZx_{lepTwRGs}zyIK{qQuPNB*b?1DYIVmc zMs?A$2M$uS9nq+jR9mFP4DAk8n+~ID)A$}>pKwH|NX6F%3u>uDY3jY5R_))t9PCu z!Z(<1VV`I$i*{Zl{AXrTR#B7$*A>Q=)eDquHym-!+wG^UaEMS>(T``U$YFV(*{aH# z%5H$N=Ul2^u_eaP38LN^&;XrQ+73!1lM`S^u!SP z%vMZPtCC*XaS);IYNfYyk~!W?@;}}+ow7Tl?6`|k4rIR$a(eGTZNsC_8t&WJC*0xa zYvx&-%Q~@JL}CTiX29G1Xg^SnSDP@oGQ6+2JmgOexufhV;_lhL^1!|)&e=6KXlN%O z8toveXx(R!Jiw;cJzR01(ho$VtwlMh1)Iy*8r#LyVXqYX3j2Z9Ae|4cjFba>=8A6J zHz+n7%8oW8eTVmHe|dXVFL7~6EyYem+0ibguRHD9#)?^wdI+@c5skhGV~a0#lV7MF@)oLxjNT9WgXmvT4&;trGG??CugZ8^ z6=G9;9F$!}FpuuiD--1cv@W9fQHVxQkFlH-xw}qhwxg(aGc;W`RX6@f z)s4}A#d{3sAyaLtykXLVDkytU1!d%pva5)SLo3N-s?ywssx%{aM5C`xx3L7Mh6g$@c^pW+a^-(cB~VQ;tQ=WHKpG9z#RJCS)z@udmQG`>Xwh=UBV_C zjxQ_2r+>35L8nFykg9uBFC&h=sFkg(g~(N6uc&ajfn0Z$ZumoF0;%#2>S=8M+hMjV zVjZjmyq~m07e=7qMq?Te-98YVjrNo^o#jZ(5vg z)Q5aghgqI(+K^5Cz+0{_Sznf`F-Jprv9~JXb3jRvrp8d|xvP&2r9yPQ9ledFyB+42 zHx`fmwdUL8w?z5B#eq<b7@5B-2;smj3HypIk25I7xG!_mK+`-&*eQo-M8)e6QRX z89BY5F?M6PIoIZ8SEUM%&L&&GE-#=CVQL z3UQ$8XAN&0ZF9sM{$3I0)jVEywdXzF`^vC8Ipn5EIXU(asSr(HYYzKGh%EKxnyI-s zaz}Klb^VN^73rI-^i@py{@@(Css6HqT)N#Kf7hE)+}|1Z{;XhQd9 z=l2d)krNi()rP%@GjgnnFbj|*P5t7GJu_)O=w=x9i9Gtk0rK;T8RBUFJREOPWqTWM z?7tdehCcVSt5U5yo+Pf1yD6>@Y{QW|QX!hL0gp>+udjU;r@nUNC>5g9-s@+ayc=O& zc6}rFM*W}p&u<=4z3>dY#h-CTyPFZFPLkMj#u?tHBFv0*U#)+!I3syMgjt6E&sgOT ze*E;}vtrkqQXHQkKWvHi+T;GR$k8y-tFIr&yJU-Q#2e}IMVgD~E52$!Hk_R%PP|DJ zjj196%8OKprafxx1g*n`4kF8lSfw9`e(CII)bourN73BSJ^H=P_|n$F;(Dkz7pvop z>zU~ZeXTcF#yDf>?FjSF8|o;K$CBKP|NAIdj1E*03tq<>p@7ZRC=4p5>7=r61NX!Cr#X7hjS{KY56`chMBWCHzV z>>tH<3pC_i=Va6DX9{qX9jOpaHDyb+;N{a92eUoMX?;H`HC}@LIkrUA#rCe!I?g!e zzj;VMWpq(?l$NTh^c^YAcjjDfl;WAHmU$N+0Nsd&gV>s%R!xB=L z?_Y4gJem3I(VAABDv>%PD!Eqbt*^laByd81Hv z6*2SuEK&dC7hybVsYr#g$CK4Zj!eYrTUQMhVjpJ+bLAJn>zuPM8(&&zSO z#5GuzYQOD{ZTg&g(l?-#vL+%GqUlC1GsT{}h2@uil@+N_c3kJFrtGGs(tF=5(corA zj(Y~~yVxi4alFpk9*zu`e;m83;eLk}0Pd)aRc-sq`E^oTS?PWjWsgGHRm7{8>131c zeo_z1p-6?Y<4#Tfpm%GzCgUtIWZOp#cYVD3jD4cYcpv*{Pp9;iIZusK>=Lxw&_{>$Q@-@5tT3HmtVaLO0Np(I7)?Rw9XiNv#5pKQeuTTUgM*NmLA%> z*eCL~k1W$Z<%y$O#Y~{=Xj7w&N;!8^r-*5RedPnMNDaB8>?-1Y%|bG%5XGYQ3q>kK zqqR(4YQdKB^|(Dk>-9iEpcRhZ3w?QU{vhfguWo@7+69>Nf3?x4&9IrXfKacIwV>(GZh5-QRtD;spZCrTGN@8 zg*C}*#Zq^M=JEG=`{R)Gp%#YgWAEkD4ruc)L2)hyZND#r+rIIPvgSlNHe0f zryXOxl*tkON@VM|UK>-cB_A-gm63H`q{2Hx!Q-=~m#+W6x zL^(w#2g{hHm2Ba6I%)U>BZU~HB5z`F2dN*`wSV7yRuC9ZL^NaaWrU2H-&HhydrVyW z*v!~6IKn(#!OM6hO}L7*gvCjX;MW_hV#k~noUNcKG1(x}}w z+{|{x%Z}}0RD`h&ZMtinqIL`4@~$s6rN&E8ugFU=;@3IMaQY4&#jmzpar$OID~eBw zqI}LDPu^GVY^+Lhn2y@sc9loka+zh%0!gA5Nrg`kfzr|~?6`Qj-6xy45Ij|hMj;iB zA$^HvQXko1D%}G(w_U^WK`NYCx-n8bzpT4#p7!rKn-ZbN8B`H}J!z)psc}$CBHcwD zMeReaq%Une3gW}c#%LF_=TQ)-?Pvj#RAEK6$y?&&l=-to!nq#C=1C6ImeCsbZpN5S z4s&kt@4r{aI!u$k8&6*#o}Yma|CB+F=~sc@J`-gu>=9{}3h}fTeAn0bIyS(kp&5_FxDRc3jef0-Nb+lHkMXo4KSWcFlyBj(-G$fAv3qW5Apvw9Vlm(1KUB4-9(y?k@yKKcFSi+kCTAEHUG*7lT_u1V4TX(@3tODm&FfpD`W zoe3j9)G>;YMHQD#E81n)=Cii&J*|vWUma$8)60(h5KT4DeoHHV9px)!xS#aUI~!|< z(AVDS3l+!@HJ`DIYj=rszESdj)q06(v7L=tqSprGoBy zYu);T{P2AwkABx=XO6=CW&4721!^DiLo`{hU3VV*tHdud-_Jpsh1f|=AIcKQf&R55j=t*??a7tcOQ;bwD$=~bRjnjntzdQAUx_Vb<-$2RQay1{w66vCHcPX`}F_vX; zXKmYoVsg_8O__6x%DtYe>wG|4ht_LUHCb&;MTt-5)QU3dta6wiX*MmiTYDILd3=Ia z?oK6H@pn2?1uBd{qpd}!WW&~Ig^%`?qxxo5RyedQ(c+|-OvepcEvk0AtxAZ3Kz?Z3 z(J5KfMD4?vFxmIoQN`**9_s2^aQFl*Yu*q(sOn3B@kESS_Prfr1c!y22_vjgPj>qA z=RUZ2lFjcsmAyg5V$RQtY1xos+x z1m9pf|IjOIGPu3$us4mO?P&Yp3Qiu&(Q39Eb6ZIBi?3plp(TU61m$x2UT{wOt(A0s z@>1+8v`cU&qNu@u=Hm08p)%WyM;cP0m4Uk*^9YQSQ03 z)WAV9)9Vlosc;X+U7Iv<^v;7Ge!s|qor5%_Qun1FmI3{L?_}p}vNEpaohwvp0(Tj- zeH|~(I^P&29aPp?$8RuF{Fs_`kwN@2`Q?kFRgfYXz3xEEdBn4<>dXjWuR{c z#imAnIJ1o1Vi9ua=GV?iJ8mgnDq5_Fru!coSBRwtABjgV+9z-iW3hCp?QbFzmXhG$KM-chS1XcZKe;tPIi`Cf=~ct{%*B9YlVJX6(qE z41D(gGRV-l3d%~2D<{6eG*$scwX?h8WbNqLE_>H)z=Na!zm9DA%Fu!pN}yH7G#XSyCp@8ES^wf!GpdQ+*jE&SfqlE9}xFK0!qBZXXWS4<>YGi^rn8gT=82g=P0MnnbEz z(>#)&)|+IuDsw$hMKsDbOY}Y2Q;vN-OL%P`oSbRvM6<~1zXK5+n9(D-VT(!TV}FZ> zZ{{=N(Z{^9>!hFL^e2Op_ph30j#&J6Ao4&oMYcbk6oY-jXvW{V z5s3V}3l2_>*fG(3w)Jn~Q7$H{ygSrWrVS}B5pjF};^Y^FCYtT9+z4FNeo}IY9uv(E zeq}LBhCm zzkirudiA(TJeoIrB7FTi%0hv|m44)DxHx%V#ffH<$2S61#PUuBW%1UT<77m`^_6417EKcyc}e31+n4ZIbF|TUl9jXj+-+ zjfd36>`4A=!vr(O)0=_V?!9ZrlPlMpU_Q@pAL@Couj-i(bm8p!*(3(9q|UJ8$4uS*;DNu$l!%1;B| z4z6WPdN$I$`{iHaQL$(<>DkOz7Q0_s;FED_1B{TTBg_(wUInT=b_YeswV`XolCCQi z9*8KFwU$x$#Yi*x4~xg^!x1v;!DS+#${K-GO|k_Tf8HBm-U@mZs3KN}hsdpSGRn{0 znRx!Bt&un^(M+EIArR4b9@jJ8z8qox-Sidl_?ok~oY-)tFk;7uGOyYitNJCHW#)be zL>`DHzqWq3?C5n@)T;l?i9D)ZYiqO`muN0q^da!9EzD?>_7}5{{6ah;Z*`ZuJD=0BOg1!7B#m6_E~w(S)rX4(1(q{_UchjHucAoEtnZ-LY6bux;b z9cs24^ND!q9{psuU2(!UDN^7QY!_RiYCTcC<=1Wp#o)a+ocQG0lpe+rufe8Awr_zG zCMFmgN5-2gj;E!4aLu~`GOBcQalVu;P!dEJoRMJIhQ^zhk6DP$MdM}cv$^7n{+AP< zV7s^{(icN650XLW%L!4Xtk^Is!I(23-pogBAsY8!x`kbRusqFp7K@sBcj{8yoz4o45~b?e(5b+&mAkgt4~ti zC~Oz`(P_qxE^<|q=b~fI(gNQc)OJKuCg7%Ux%BZSG5hgSfo~_SSL({}Zd(gk{(y(P zd$f+SmLNa%9V|boovh@2Qp~-1NLk?~yvkyPydG%&tFdN{7P(I z@j=rW>8r1z4z zTOyDDBkQZwg3mbSQCakrv{0;Pf#xNvbV?q0gd=~>*} z-MP3sytBQ(_WR_%=dbhmB+twwnM@|h>;%_&x=ZbqS$t~JLgZXKN#cQM^akjRY;RFf z$B{+c&*Leu1nHu`LXqV8-txf7twsH-F&upy^h=NueOFXChp_nN5xxawj|_cA^v>v8 zGV?ipI8!H4DAQby{vi5S=sD3lysOXfCW#)RLfcxBzl(H{ANkZD7VsL8;Ud@bRUG|V zz%tv>qpd(-TbPU$}PFVC8>%eeQ^vc9Z zKk7O7xflN8b)WnKeRb@g65U&-1n;38z(>Q=|6E=X)>oyp%UwE3p8oQH_>>F2ar)6B zcWg4^ui*9k)~s9gzUxB-mY`I~o1#VXPvXn`X7DM)2MDZ%Ete7ZN}0ve4O{r&>Ujlv zmS;CzNm;cdMj!s@zRmvnc*^H5F?w(=!xz0fyQC<^d-FQCOk!o%1t~wX#p#9O?$}Vn zQS&Jx-i`eB)xAvvdpD7MYNU&l=)65Tw@BD_oxj=cBkezshm45-;vx>Tn!sb*(;vfqO2L6 zZcV1?g)%<2p?y@8tY3me;_ql)u!4)gT4*_CMCOYou|3xV{<38TX*>`yY}JpH&2y*e zo5LQ_c=)wxCT8!5;QPID39NYnesd zi1u|J6j6G+-EVA%zIi#D)S9Zlef8XiE1aU-KT%(}o-H8q?ue4sD6EBO`YMID65W=V zc*k6s1eRb=qd%`Ghq`wcy>r%A2hX`Id9NS6+B=tY8>a^i{%-4drIGWHbD}=5`$y`l zI;@viG)Uv_VVyXZpua1703W^Ei4=GWsfonT4yVHGMXkvoI1A7{M3Ce4bW0a^g@om7n-c$MV$O+CbiG%dd z`!d^^=Md+nYV?Kthzxf0&ghMi0b@k=f=9FxpXzb+4SzZ&I$u}^>g!@%>_|ybevgb0 z1N-^&vWrSdz9^z)#IUZzM45txO_6^u^DIe~M9Uaxy$5p~!8&EIY*AkdPbg_Gxb;VgMXmlu(I>#!!$8ike< zEhbrLRuY(j?%VxJ#*qs8?M2M;(KSjczZ8eE4=Z6hP{ZrOBsRE zbD_~qgHH}&>Stpu|K7u~q}jzN=h!LXdO)EZcBDjS8Ls2RI#Wy2ORq{Q)}kCj=~>w* zBT#xaGb1}?7O`eyC<`eZ!m%Xh`ytMe89M71r{=aJC5phdbQhU6l~=a}-cqp^=I)}5 zKXtcE3psyCvygxcuUd*`zwCCd1ICs6dt)?Qsc$yLf=hB?R( zP5BuH3>7^d-Ze#RS|nv+L#bpQFCRvV`>*aCyiogj0QN5SmE7{h3yX<`O=hdrX4YdD z-O4#T6=|urXji~~Z(2F$@xNN?r#cs~pM6-!d1-N&e&T%r+6iCln_c8Hm1f@t=VDm0 z)RfOzF*#JPSkc{%lxR0WQ3>A16Vw7bYBHpYwN83ebLP6&QXlgqKk?Xn$VXK04pJS9 zE3tuD0-T=;wbtiX$#2hl!0fD%t&JY_CZGM*m^#kzr>*qBg$APLj~Zgjj*V)U%%vHY zAYG(HV;*D@+5MNRo39j)`EI!~@_ zr88%KJMyDcjsYg|e(G{{_l<%K>E>x|b)Kl*MsIrgzdXV=RTLQu_ErDH`!J-1Jg^TH z#S}V+TTP!;XZ0|)rRtuPDm7c^<3D=XecSC$xpE{}uk+Ny{>uAc%Ak9}dhu&UzVHJh zI3IgwgWC3WM}{Q{B@dR z@t^<8PCS2-L(GTV0+1><-oEj&Ucc?)GsJyEeqCdpZO$EI}T~n{KLS zW*2oj7GpO>K8AERtjXsrmc2g-W*Jbb4z)3I!OO{*m$vUY@3%_<^r|YC-%H|EWd{OOS^wmA5mI$JF|wh87NHNY{1T?vx7ETIdZvd)Sc@ef8Tai|V{u zg~dPiV_VAKH|N_Oq*uA@X)p8Zq4{~6Abmggr0b-?<~9|B^yJicEnSs0rX%e)soot2 zGc3s)YB8^#8>H8M=4nSt<7r1Ub(PEYq}WPt z)fOJz7}i>Izp5i=nIQf8ZBKiF7ZZigj3C|RrO{WfGknyJw=c;acegXFg(Fz`*9ynd z6+!xfdj?`doLvjMwoJX6dlGd&!gTQDfFkX7s5`v|GpvQOqqLN{<<~WB*r-bE zaM=Kcl03Nj#1V2JNH1`~(~i99ZoBGCHR(e|*2`IgEf~Ge5_KV155DJNe}1gJrRLrs z{pd7L`{gFnER%)@>q-x!9lIVTs2k>$WJR|6F)Zs^<4O1(hu<2)Lw zmM@p6#`o^auom_LN=sS(rx#{bCx2F>H727srShDAyi}h!tP~A1j-Hwzfhfwk__3gL>b+cCp z%Q@+j<*aXr{xFw^edO^smW>lb^t07G?1-k7^FStc_}4A9{ALrw66A-J$cm1?q^>`b zi`75jC-Im){-DM60gd@pT5%p-uoOAdLO=7ju^L#T538SxFIJnlcV>Q5_E`q2E%ZjO zAtGZI3I?!nolcdJx6}xCGrzx#MGGuSh+Su+0B>P z8ESalhlQ+1$(uY+-Xx;QCf0RhldI%n)yI2Dh~Z;BtgSkQ>F+(;^ptgK2q;CncyW^AM9PZuUgJKtkzp_MlI1TjG=YLd57~+QSy0wHrdGTem*0w z=V*7)9xF=s_t&&2TBBak8il?Ou2HylkzX=1k-x0_MV($MSn_w#%Rujg?hU4A7qR5S zt#;&-b}Z<_p>IciiNzu`mt5-Va%C9ii^f-cH#MwTIY~7R{?( zarI_cGPjS-IizD7ebS+PcBDjK*Bq=P+P5#Px|FCc?QwADB_o2%RTC*WywvT}d>HOh za2Hl?WF2R|53O|HMTUi2)T4svA5%uX-Zenl45Q}aBp zox!f27}0~_ZVPu|_CEJhzSauSpM@K%^R=-DdCog_wQqqw(u_j%p>{l_<=_^&^@f2c z5^<0#QyZ%J-}RPwEG&2^CHIULdhl@%yNtM3cP%fqwt;%I!T{EA-~5z1JXjC0c}n{M zoWY8c9I}?rJl;f&eA%C2NtJSYQW{!Y=tDkv*pU)_OZF$4hi3~^her)zxJ$u3hm832 zEQm)BXrU&Q9>H*bhUlbrgHqau1nZw@Per#Gb4u_5_7L?>;3&ynA-X|e^^|&lg7hD$ zugi~*xUW6v5Tbf~h+us_u5kR>5u{JKFMHl-?Z{FG-`AGR2~(F}j*xiVj&e(>a5qSQ zam3SJu|bBEUYCM&^|T??{6Y7%9Gybd#g8KxmLOfUu5>fH+M?y@5vINLN(F}Jf zSZhX+`{pi(gY+U-3`E`?in^qHi28eUgye1HWFiNaPq`d*w%5I-#sW~-Rf0w$C8diS3y7z7))f78O+DBon z3Yilv!M}p_QpF4&*Y|B!+m>mh7Ucb;eH7M;EwjgBp}8`W=8B^H;Z8N*U7NaKbuY<7 z#`U~sb8e|Jw1r;tx`F7r!>MjAY*Wu}@5PW7)M)+Mf*djENdw8z0(`&;I>Zm1Qe=l3@dWe(?Oevc}vzSEj9 zENRUPTEEN-(|6EXf}Rt_^@I{J8PeSZ;Sb>6Y2E^BZyuX?;|C27Zk zwSxNCtgXo7h$fGNzG^JVScYq^>edzI818GZ7QT2*U$Ux0b>Y?3qAnrou(cx@+HmvH@% z5o7AFG#x!2rgmI7T3Xd`jlva`-qd500#+YxscsG(!*G4YT6k(mar*HVZAWydy0_XG z$uGh6Tt>VZdS7cZFjU?CD1xD9fgXqKGfbOag2%jSq3#VG#n3B4Pe%4j*r6c4=5e6< zpy3FHo)@Cg*P>{{=h566)l^MdH$?I*5sm&F-G8vP+<$Qswefq|v&1_O^fGBzH0U5- z?`Btblv2JkQ<6tXA65gQ2&L9y0pZgn0Clw+r=GQz~_0=+Pq@eRw)& zxSdHf>RDSIqP3FtABe_%0%-~Daf)QBrJe~1WVkcIdpvoMQ=1nROPiHdiNx{TJ7>TWT;Y%s-Nbc&p&Iwj4d~vP?tZOl_t|*X zBfnkq;!YszNB7Rl=-wG?p;R*B%YdOQjP9LB)4enDz!!DoH+bmAoxzQJ`ddqM*KAF@ z)kjK{7w2IlyGS?HXX&O|ss*no(G7O`>q@DS0}LVu(n}~>z?v5If|OFD6WA+?PAEyy z2}p~g6VhKeLUd}Z0b50}2G1$h09%Of70En?Sh}A%B>mqSN#94U`)`!Rl$nRL_I_vi!qdH_7)XrEKuUB!Sm&}& z^xA%`WZq+ZrCT4%y_s?P&cNF?L|}vm-TZ81d+Q|jW6yIP*WNy4m;6Uek}Q zcb9o!ObJHsk?!WG?vs;vY|JeqP@1wIU$zhkfp+yON`hwUTCCMhY;S>S4eAhu~0LPX4-#6xw*x*uiZNGVzSAI z3hP}hJ_X|SSp{y{T(>5gD^irr$F)Wj>-Mq3_LU(XKGauu#+s#CC2LBCDf$8JrEOWu zV%8Crrt0C!KZMvjY~EgPLX`Lq;(J6>Yy5zTdiBbmY`SfzQIEg;fe^DwXZP_X z#C>W9@;JA%t94D#7(MC!Putm#ZLAlojMtw}{6>gZ0dxIE5W+#dTO?wTwc^PU`tL#+ z?06r68be=N3>{m?pAc7x2hzopW<0G|ln1A>?|VVIYtD0wJb|MY)6W>)l!eUS+T=XOQ5z&} zhnc1*FWBCFnb-GYU0jZF99z^9)E@d$FH6b&;neaZnzcQ>FIZ~nG5Y-2`!?(a(){!| zDMe{zZ{lkrshs~A!42O2)-L0t^xeU4ZKyF6RUGtaZ+SvgCN06SMJ+*HP?TKW!}r!A z#2ey)a}CE|9`pCxcc$uY9pZswi#JWE3v_0=rPIC=#G^hTumtbx@II1mOlr6De?}wt zheA0`DW_JNi@oM(#U9BY5gR zx{I-u)Q9O&nsjEFso>sX#G?hZ9JLxFC2{-}rTCmUpFV{6Kywha8e>vr#7mE(KD!7p zn{*dTFv1X{bSb*6(JY@~gg9zgQP66PD#p1&u~E%;`TknfkLB_@#&KmqD~gn8A9XyB zk6{_EQSYK8GYkH0Ip7kfpGml5tGjHp<=4nK{Y$j*?W^%Kv_0iN49Wklfbw^d(~p@29qf z%`;f5w40_Ey=6psuS*QxTbU5~Xw1(>fcZIMPVywCysYPsfdWhtnJ!MOGA7ebil96Yn%^U%LSDh$0@SiAWc< zl6H{0Ciw&qLjO-+VeFV3-IlylnRzj1Z`OWNXtSOl3sF zOp34J!#yPg`Ua?pvR*kJx%(MXWg`UIS6rQCE!jDC*B(DY+#v*7OVkoss+g;H_ZWJ0 zlMq;fceHXGS*3N2_EaZ?LgRr}4LtxH8`=*#mhLs|?m4o%Xftq}abzjV;_msq<%mZO z;(=1(Jur?Y`P5Tx?Ym1nCJ_%D1GFVbiL}JyOsa*uLM_MD5_=S9u%f*0Ie(wA8nh&- zuupKsk$D8%%CK(*Nwvo97)Or7s<> zy^iU_+GnYw9*NNS_+#PLG4)65fjfWOa6E9F==%?SG&@o0tTrgDq2&9}cN5mM3>zOj zMp_@P8>aW&V0O>yCUhBEh;8P$r)0* z*3}xXjnVsl{%J!5`l$3WDfQLG!x>E_53iQIR~$j4q$tyB4rZ6%_0+C7wn|bVUF1ji z&Ve1+kRk23*QuA16?N7wW*ymis?Od1v0Yf|VIBWxs=jvqGg{AUJ!{M+_kLnJexR_x z612N$k4Y2r1h7x>f2q3;7nKkpbv&%cvPSDJlb_iTO>a9Tc3~U3ztV*NYe_2f?iUUy zYrU8}MgKhe1xdC0ac5?|5z609y2r5u+aXI8n$U?|eshjrUOAJ84)eDL?u^n)bbo6@ zH1ebDd#`#jecPd_ZJ&6FP~m~@~!*=YxO+(#}d7Anm#M( zkxfPvIUmfdhi38zjtrt`t=!h-YohgTZclB9KuVO!^M{??$-~qYor?+_DfL5c>#M(_ z^%Aw7+K>`O=~c9`>f@~H?Jo4i1^9!AmJu6#%xv+g>ilNy(gNk(eBhd;%aIs8ca{e> z>=DXI-sZB}d0=LBluHwV+_A4@ zM6ugNSi>c>`u|m3LSVlknsNvonxuBwa-27-+D&X*ooHS_-%;zsCV1mwr!tK*YYxZyuMGg3 zjy`<98lEEf_M~BlDbV|t4bh4+w@Q@SXU%C|s%}?-C5XWGDaxMn57eGf z-u(6Ct^zd!+aXJJ^M(&w&A0OPeTzz#0p|yfKb_irwzDUhnCc8KD$v&Ati}0Ad$p+U zY~i*i2k-9wM_LEbs-d-`eEMGovp()80>1UyEO{BYF5!BWnw5*CW#vLYf%0luduRjo zEAvzHcv=6K$BVLZv9zpQSc`IiSUd88y5;{vP_8hRmMe_1gQU|!Uj%tmPT9EDyE9YX z0k=DS1fE$L|I^N?-}T?%zbigoAG_H&vowB{2$78tSc2!fNQq8A0^8Mg`9B{2MWpdS zG@VTBJ+0NRUQ#6Z)K5J#};V@VdF4W34a8LLJ9v z#_La$<=kYnH>k2pE4_HIIGAk%$E;bcdS2r92LG#z;<u6l0Be~e`!&_c74$|Ce&>IzcDzQ zvcW%Se!OnmbJHgCxcKovz@+s<#M;?14@4j(MOiQ=Dd26&5b^BSI*ug?7emd5|8E3Q zT3TznW)GN9r?hD6TVK*d>?@>1ipviq$CFg6Nh)k1N+t7Hhtk6PY zdU+|Y9t>;*ReI>ViZimyR-OWmh6D8^kq>Ht%-zX>G!_jKVe~O96 z2USTE(YAY8b6I9JiPyK(G*%q%LN!!3%J5h2_-c+ku-4=K_smYp33xU&C!qB~4YmA- z0b<62M2@wV+;O$^35wV6skdx0;(Xy9s@ucDB67a3KuK_g`xaQ&(vj|4_U$yJYU2^9 zmR;CaJny|i;(@jDUi7#0E)=hKr>x0z({S~+dhm~j=sdKlz*@)y*DK0vP~why!fDEI~watwEN)hvW1)Qw$%j)s#=_ z_?r1encWqol@oofr(=g&Ob6q1_o)Wr^{HKIhH5=T#$$6h(#2Yxo(-|gCJBGdG7#~M zUUul6N2p)RNIo2TGPefKu?%k&r#~KQ_=!*c98vS->mrJ`o6C_d*1F&|$C9%{oSu8U zfw*DvWLv&v6aD@!EP0mbYvt^**%Ej?R`*_Hczt~$AFG~z?ZmT-u^j1Qt&q)$7PoJ) zdU&{j_|ox-T6tw#(amEz$69N1Z?=@V8>>%Ueb*)Ed!e;sm@d^q$Iw=8g4 z#&(F+mpTm3a{h6JDRo0d)pe649$4#?*=dRF7OOWsZXj%hDzmq(74c$dPJwjMFMXe) zTSm2{mY+8e=Z?BCy+7-8;jj4YQ@=U-ZMfelUH+9NIUq)7y^P)6{=%N@!ngWj@B987>0+&R7hYQa zSY!0{0}VvuH8vLP_mE#&{Dvc4+}$l$PkY0S)ASF*IHC8fT7vbO&&1H?T{+UlTHRXx zv0U3eO}}!)K)h|)jLoQjncq5hha+9w(VZ)k+gfc)wBFp^$Zhy?R7H0DoS%qp9LSL_ z)|%kRYJFC6nm*Fg$e*}!SS5C#f{%!u-Iimmaldm}r|yc@`xSX=lM%%}hOoK*r+M73 zQ(Q0aVJ+Ymt#6w4%!X+6eHEq0+YqKKKFw=yIwkSIcF2g38@1S=;?;!pN+St@{90%7 zuy*%|);rEH&PyU^wPbZl9_0ti9^>eR93im3a?B((!; z{pjam&6_(~|GdILm_N2=Rm-RFfm?Nsbn)~fV+A_V=`~d^?rz+l7qQl5U!GPFuLher z(#2YvU5Z)v44A49Dr_Lc`SxtX=l#5A*(8p1@w{YN*Rt05LsRsEe;H>o2`*-qbflCh zQ@1Whx>zg3Qr4PuVv6pz$Utn{-;K>0wUvL3rCiuR3whvPgkqiNc4wK(ujT!RCQ7F` ztOT>(FCC>1KJw0nl*m#KY{rh9%P#`ms!BW%@oIvvwe4#<5Bg!`v&?M{V(OaQ!ncZv zW3BI5nRR-_DBX18olQo(n$({?$REQyW}G4Iqwwsl$LcWamg^Jr%9XzokBDO(S?00t z_{qi&vSjE42r?yu$EI~<-66M%B9>K;xt;COws%T`uOy8wqE$jt4nfTg| zy;#V3LYX@n(#77zUZ>UI>PP90(WvFzqJFD1b6>oKJon%XpF7i{9vKAA2eY>2v;9Z3yU9_BN z`4q(x(VngBn9S>S*)LfitcBK_i- z>@L>ARf68sJ5Yx$`&>nI+;8GY7gsV|;mD_+(vnSXbCe%0a!gu3uokX%wA=nso%Q}) zQ~df>mm^(V&vB)u*pH^6tcTYL-e>a}j;k=zMShAhQZL71$^?k487&-r1N2_d`=IY8 zlAE%D;s#&3?WVMzV=eS>=qsVxUMx#7n<#Ll1xLE*g`pQkS?rtI*dg;1p8M)6$@jrp z=&8{QVD1Ijj(&|r`5_%R(nW6)y+Im5pL*<2!*~4Ph@X-Vhqch-RFr)mv$Gs)gGAX2 zy*biFKN`JS^2pxSVCRZ`5X zrLKBk%{sP&INUah<9-Qubhsm%%DU;`pUFvM#9^&+_IUMQY4jXsKl<9WlC-p!; zeoI7V`zm)j#KYiRYc?a-@rA3%Jv#-9+#mHSV*Z|3IDR-Q^$OU*TZ-`ZYRo_g9nKSi6} z2z`>iwM9yb;ySCT_&h;qqq-GhMRUfP-@k98SNlgsASH^FEznfVD1Di}$}Pn9Oj~Hq zxT(GV@uR1`WXT!k>#y4A3GY4aNJ&vnW}eKSolZ`E)oT!Wzg?d!?j14psH4z4nXhMKl|=2cN% z?4P|ZQ_Qw;-StW*jJ{gq3=re^uX+bxRF>L-=r;SOnLT5=>sK!th>d~Wc%ji1wGTr^ zOH!fik>97A|N5)DF0LDh)3K_EDcD9W>r;v$EtI78lpyoB4B>i=W*}BHddn@BmzwU@ z=*o~5qEm{tGPlnku20ns#HwxIwBGY(YR^ZGXV-qsG4ET|UH?P*p%7iBd?#~wxp3N_ z8;DH#GmG1mR;n*PHf2Z)B^mJaBI}y3xBh9Hfmj!^f+t+dpuTxOm?14hzpZ|govF~9 z&Jzv9Z>NuTeE%iwar+4p!nN*0*1_Cce@fqjpO1LUsyFMcKT7>JJo2c&*16C%EhKOP z!&;XXzF-eq_tqo+Kg7Jj-uzO<9cq&<{TXsc*%RAlthaefZ++krJ`STh~(&TYNm#)_$|p zyf=p$Qi-%aLAtV3_4}_kt*d>&lu%#-Lt2PHN@N-SnHO;W$`x&De5zC;t$(uT_`0X& zm)^P;NrIFVWx|jH0eiysY1y91Jg6NaZ9J%b>68>DF4Ix9ct@LhCncO+v$t{-$``KB zB8@{ysHesMwB&ZJ&T2>oyU89u+UVVMx`;qZ6h~HKr75WNN-cMv3G8NYCr8<`;re~j z(e~MUIdb@g>ot#h+E0&qEB>b?vo86V_9tJ`PLW<=3Gzcqiqd?T7n}Jums)sl17i+4 z(&jTt(sNUggDc_s%+xv9+B-=d{w|j(Tkt?hDnuY9%BnJcqv`0}om$pX6O1|NNSlM$ z4q2*{TTR&Ve}V({dKG14aU5xu8tIaiaQx3+jmY^^ec!J}^1*YR49nn1voeT4N_6{r z>5VBQI7G|wWV~Uo9BEb*B}7Ve;^jJ)J;|Swt08Wx=o0PdOsmWST5*srSyadWR-FA~ z$FXN_f3#6`?`T*;Ym_5xjY3Kkd;X{{J6HU;wzgCi=Gi9JaqdGKoxSk1lNEKOttH5h z?pUt%Wp{@?)}j-1!?vgQ)s_y^9MitE(TCHjhLq@yk#*hGQeSQ)--;Z~w)LCk=tnC~ z;>dUxx7adXYRe{X;FO|8mmFNB=dUBaKzK9cJH019VwBY*rBGXT$q%6CD%BK z2dz<#v^5I((SERbaTe-3Px~F)P-;2yK;D!w>qcMJdDLSqVwx_E2eur0L{YW`c2kWt z>JzO|IJQVvmTKM305&URn7_MHMbbn>ASJqK$TyyO(^|Wk)>_n29DiA=Ut7PK-Y3k| z-qRX|^8o3hR?>=Nf2ZDgHp_H2e^+VNA_6HX%HtU-yZNNG8d0Yd!}*L7;#^Ub`nUW| zn@e2NylKTjTY`2F?Fzk#l(bS^AO77`@Xlb#CZZ%VB41!;_OU-b^qbO@p|wN_(XJ@U z#DRMQ8f3VtO`1A^p*>&w#I0Uuvh79wKifWN(FxP2ge+?7$>XFI2PKhLg9=5w)e-g` zYPrt+8LmYrAzE!Z>-#z{Ioji@wmD8-KTs-MA1O+&$5!p($FA4Hi7M{UxsR@kY{FCqIrC>45Y z6#G#DR4LPs|m&wM#Wq?NvH0ltkWtgf|;2HcZaMvkr4paX)~P z$h#tkeH`0Ty@ly`#d7MQ4r3fkhqThe2YcA#-_3ArG`G}$mrmVz!8&;Oa~U?(H$k0q zst$90JuEW$x7I&=cef)NEfGZr?PIKcrgm!K^(BnHN?+;GG9V?gS3@guk-SYkwXMIz z<3BSvT|;T*EMHT-dN*11)%r*Xoacz9bLve@gqClomfTgsK(MrSppN0lD#{fX7vXks zl^T_?sf56}f@pdr#y(E$^=@J6TOqY~&1t=hba9;M44}mb5iuzv@A)f=(-@dx4AOVM zxGSbR`pLb;sU4xbt2v2diRt}7^S9Zp^dIEOBBfLWOGDr|6T*>(K(B^ge$U#G#hqBp zKjb`PNR_S`!@N~T9W_k%po_s5 zmA)kPyd-PJUM$AZh|idCNG)+;pd(>sE4|)h%9;$GrR=@l{}ayaq7nZTBO}oNL^Per z zTqMspwr}B7$AJN@DDQddc}co2ifB4Xoz{lkytR-I-gcj3|Df)A#QHdzG!4_;Pa8Yo zGw*t_Sv3;*m2B~9gA0C+vJJxYJ$F6r*l%+02IMcxHr4LVz0`W_O+C9~cJ(lQ?JG|^ z_5z~mOIF{8>V_JfwdwoEu*#Ri9DnkL=^k{Rgl$4JW$W?juO44GNt>1sA@wfuLrQe# zHLEsj>pFy&salC4cWe`)DHdnmAQn?TkLgZ9+7?8rp0KyI;8pfB1rq zrC@i5QXyJVj^~eHM;rIx+X`LRuoj|mrYVYBr5dbTb$8L!{f5-?^JRP;=F(w$IAt+k zy0V6&KyJ$S>@f5ysX`6bu%^4%>M0{o6A?{cjFh&qg|ABr+cZ~66S1d5E>v;kE*7Sr zIcM+~?&Z#MtbEU1@>Y~I5l7AQa&^bPd|~=S+D%e6-8p9U!?R+%T!RQn6HznTruaK1 zzX{cSUmJ+u$pzV(UrogN+P}1^E`=Pv*F*I)be6HZeL;tEKU5!2S^Z?GmV9wx6)T2_ zKcD-k$Q^4Tnk@AZhw9(2uqddI4g+^Y@2FG6;eI+)SILgi?Na00ri>}g`3^RkeRy2o zkz0i7ZZxA1{q|l7N8qYZeefFtVI8?y?Y?cW_@`nE&ExI~@n9k4)~0!mlDw^z&Ea=6 zRPUa8lB&0#t(w~n6Sj;l9BW}O$Os-2rFI?~F1(KIR#9F=BX311Im26x{8~~pS!`h_ zFQPvlIxR9x2-U50eogU-&-0i(cnBBm$FN!7%R4Ie3)TOomLq!cv-4s}NT|M??6IOW zd2`kj_HnFOJgb0;+!yUVF1oD@)nA_Xv@g06DYDKA)$3g~5c8X@HSr0pg>_9fhTIX| zFKME9KPgnd|G+?OneAihQ!=-xu{4Y!cSNr%9!2l%h3aEd^XdOSFsn}GF4g#M-*IgD z+$*9;@lgHN2TuwH`k(AKo=z5d>V@iSseP1dGPYs8FT=ce=*MvkOAei%Dq80Z)hE%) zfRt!Qf2f1WZ$}34r%?xn+!2lZ=yvJYVbi|xjm6V1MHsda(by(M$$4K~#eFr)8f+=Q7HU91L7)f_gcAT4JMZa+M zQNOIhyNrz?ca$AxFl9V>=*k`*H;YdT_NzFH5RF!X?xSKdv4p41#0+}R6fF)~XPm+G z5{=VOjeD1gKV30evOXxgyw?6K>&_CMo#Ix{It;m^>}XL*svCjq>f#*Y=Jf$8N`+{& z+KLi(wHaIFnpsTRy@aFeh{lzHG9lzB&6=<6&($UYtW0tZt8rRab6b8pW=6!EhqQhq zlw_Cxn#0%3pf?l%fw`#=O}AtY5B9QDCH`e#6A2+@MwGHsmZI#GAGXZbdKNTG*$}4} zDU>Q<`E2fXWIN2iR4-uz1S znSV6tIq$~ieEe!L`l{YncRSXS^KxEvDy(Op$=agC4pPQN%%zBw=o`g=JnSk-_3~3F zL%JxH%)@2eD|Pti658}R-Poj(B2}tQ|9IGuE@on+7xF4!R&Tn@3Yf9Cx0It1GcF<} zMLG5{NgeyRgsEN8fedS5zD5}_t@v7X*3pcnw^fHqQelo)%*06fWDX5i>wXz`@X*`{ zDMzDHdtz#v{toxF%RGwxNK%KARE3KSlz5<2$WKuYis7njorcNNXGO3vuQR05E%}hv z3E+Xb8x>`1rq1fBo2!#YoF2`v7UqPM5r@u~S7Xj+Fiq<{PRav`Ssf+bO6lJpO}Trx zn@0Z{&#)Heg!~WU&~TooN4a{g^CAqXQVdNr`e)SZ45|N(HeqH&%2ar{ATQK1o5}ar zIEJ+_x$KJe@oo`Q-(C|W1ZH(aH2Lkl7jjXkgtjc(a7il6t&N!xDGOAIar|KB z70EGq<#u3>Mnu#5A4$Xc!(X!l>c>Seq(z#M+Hynlu}3Jj_V6yA^3KEbc=8|#f%zIG zw9@$RSG;(mlgU%Iq|WnHy2d=mT9|!NQ3gaF|QNKRQpG>?M-6dh@PoeMu_J9Emw0=>?Z- zr9?!$A0OprmU2zvn+DiE8uM+X#LxcYxE@?j$~B33AZ3ILy{g-5%^aR#x*x+@v~s5Q zn~_CQMr`YtWSSQ0ZfbjIf@H7IGSE)goOZ@RJC@)Tre*_bn+koIAmx-LU&IV22!M!E z|1y1T)ZA3%kBk_+C(vB!8D+{QKN``BGNj8p)B6P@4j%HEz_1odC1*K5Q;!?~IQwM9XDW`v=lzAA@ zs0)fRIE-npx>q!{niwhVwz1`MJNlitq-{>@8jxeb1gWoZ#XI_@{V?OT{Yjt>jaq9YhN!+mh97Zu244 zs%Z!2(Wx!G^MR`Yt`dq8Q_#XUvwO+5ps`YxW?Y@+wRTMY>1vUfOUZl7jFfyh^p?n>#&M~@XfS;|j6rX(8?=FO9{TBU64xSODsr|uJsm55@5>sRNs zS9KBdYd==6Y|3K3>j>5VP)yo*mr3mC=urJ8opRAGoc-@Cqgt5c>ZIGB2HaZz=ts9xeyns%>{7!n>WyJFK>v->^R^r~b-GxaHy<-rvOd@g*oTzut#LK6 zw_j~>&RyjX{A-zq`-JIEdglWrdD*;_`RMadJ^YZtBlAcPQKhh-_bHG9vAeHDEIhJWMR}2jj2IPnmS4)9Ra`H|*!DTz=A@)h{Rf?YBKq3L zI_AHt(z_6;uR9Lyl9iv_RGP0JI7V7I(TXA^in@0V5Qh_8MA3h4^8&B@%x%ks>CY%K z3-7#WM{oY$-9#?$&VrqN#-IOF*EkV2r`=7UByu~(}M_(f76OzM~Bbm+o2M3V>)j19;esuXvl8CoG9zSc3eJlA=6a zRZKjKy2$@r@n*;!+k|M!hPW|^IkmPSZpj%~tTppzo{f;BQCoA^;=>@`toJ6hv=KfPb8DJqlTmG*d|JAkYSQGC@z?<^co}0T9gE}lA^pTCGaX|3yb(^ zDnsswkY{ay**EyZvu#9!pj9f)B1EH=pqsdFM|hjWaN#r&@XG0qs=ez0l93??CMIjBT&HvulO`K6~sc7}lCL)@i zcYa@;n+lH;8NMt^#+3!_E}~O!$;4B-C9~2k8Qq4Z-^ATb_qs7?`eRx*K zfn>T3OOMURm=am4NJ1Rh*oXh>pOlOxh`^YA`eMD?5V3n%BYyQ!tcoQlJ5r)=Gs;&I zn}+7*nKIQgZbsAPMT8tDGyY*C5qPKwuY5`V762prkrJJeO$+4laj%l|t{fxza9B%@ z-kE%B5?|aTuNF2^{uTheKJ*6Z3+Zl?`0u0&+Q3nx7)pY4kssX~d~PV(p03IZq!eP< zSJ+zYh1AFakrp|Cy@*CyY`yu*iY;^-UW9JLkvpPM$5LmD4iEi9cDnz3mr{3y|8+5Bbh;H?9PTXGrhD<3AI34Pg}Y)IF?;8j2OXl%q--k=<2lj%@!}qFx^7)IK`8V?0krw*xh^7;-fg_Sfzv&@L{COm; zA1IaF^8Q1+2ehA>QGBo2LAtd>Es>?#d8er9SLczU?zUJJwGVq2wTI$l#%@>3)ax(K zcB`(g?LE$M`*N5*IG?9|Wq4`FL^}8JUq)KFt%jo!-RdXpFtoki=RU0YpV|D&gL&$w zJVPBd3bxYo_4lyf35a#He;1}7D3lsUmLB^>Ik1NvSMxM&AW2{~NLO$es|e^HZe3gQf96escVkfhprzT{J&Wn(nflrSU+1h*p#qKMRVg z4dXN?y%R^=&1rpw{4hd{qIXVC<~Jtz3w1+jMzWjJ`U?3Wnj(b0_Yo^!%;x29%~Pot z&1qwR{4j2fR_7ka`S`#VB3t9D#+aMa#vJ(}n%=<*+0Ngv{kQYOEBgRZ7`j%gxJIh%8~l(L|=|2qn>3)+EREqRuMYK42mSYLtS|cU$UPElm$fTR$WM4zC(k%|w zBJD|!Hl=TVTGwW=Pm7C$>6?u)Pq$E?FO} zCF}0vp~rawtp)`eUNzQ_beo8C8|@19)#pCq#jn{s`0+d=_B=gK7i|fm6=mnv$$VM7 zznH$Fv}D_nA6h$lLDP|k_A^P9-BW*Q6tB=+ht#&G6qOs!apcMyK z7F+=kO<#;0nXIPJYS4LOX=D9JUu%&cu0G`T{VvE78pmnPqnj~YA(0=VNw0bySNGFu z(2&LhwHo>1DoU|9-}|uV|IFqG@61ziP9Q%-(>Yv=?doxJe=%iFbrm%n`Jp#JJNlkg zv;sa6qV=PZlHEmZm%XKYPpWDj<03@eZbQ`>3Dw!g*`fLuiciB@=m#lEx!R?Yn}rP) zJA$^WSmK?lyjD9ZR3Ag%3?n7_%Jh?mX;xH(P`?e8JpGd=nHVuARDVpdm58R-PhIMm zb~KL=>@Fg3&p?r9_9~{v)be2uMoK);Qpcl4q2k=#l~T(Qfs`nJ$r^vn);mJvEr*Gh$4^P@Cm!WKrlO9bRg=g3 zs#<^lkG1{87eb)Tz*!{E+WIwu{GJn{NuFbp_lo+8ycOl|Ar<$3Bt%g{AT6{w$eW_{ zw(ENvP&?-5N^M8F*N0<(Z6Z&mgk^suA);Mn1ooBOyI*%dG2Vg@*NF#m#~#IAptJDF z-u~~`^b?oz%REr8P(rez0UV2lKbj(?$0Lw4&z1keap2sy?&a5+-9ZbC&mmCn5BX|vQ{^S_Z@Mc|2C6^Q2vO(MLJheuZLr9axN}Bon`DI7 z!cFR%p@YSX*aaHaLNsPup%ePg1Js175u)j|6&jXgymY{_+W%i3NQut+TnDN>8bpYD zOa$F4mAP=C8qgIYu7gEox-m!6IqpN(q4yVm2DexY*=~ zn&{n63|P2A!xGG2gS_cX|IB%{^48vBf&VfMYoSy!Vp}&?HnB@f5nMJ-Q*%DEOi!Wg z#*`@=a~5HaBzjloOa>PJpuKo|dya&_3`B^g3{A>AwQK&a;zs@j5(4`N(Td{U?x|XG zaCb4j#aa!yuc_c}4M>bll@O(+?>W14WT&402FG0#)b*rToWuh5-YlylR-o4Jpxg!qxhTCG-~L zwc&jY9?mo#gm9+iB#(_7>D(AKOka7-$Xb_lrLS0b;wZh|yV7WfGp!wnzB!|p^KkCb zx@*oqluNH$g-&8$+3)=G+5;MvoHccIhEc}70ph0(DbY98?Vs|kL%NH;Yu6a#k&-s% z)Vt2K-d%eI zrgs;oX8vtxdrI28!&;xF97{0=#OnP@-zOeNGoI#S5B3oWvzKdFGB)?Fl+_1f^%p{xMQ7T}3w0eRnr~aFVXb8w6H`upjn#Aa`Y+T||?o z|9t=-?H3_FO3s|2#~zZ!%lMk~~F6r}Wqr zr@z{I+lG|ri;+wN`Ak!U*xO{0X3OH5(kM7y|0m#^y&H^((pQG zSD61~pRPCkX5_}*|DlM%7KO+k!R&%pTV1`q`1j{16jb zn9AIqAch@ZsbLB7z;#|xvbYR3mD)E!lq;C1ZHd0a)~o+|06k*ds_9Mt{a-nz!okB` zrt23v8@X}4OAa>W)+UHmhgQ>@K>w5EubGF<{$BqgOpzna$yNXTPqAum2ANbsO;iL!W<9IWLcsn-14@^tPbyCbcykRQFM z^L&tIwA_taj8c7_B4H=;8RI+{+J+o{7luW^f~C+Xr?2n z#&kXC$zz+$?SVovmRlno*9l`6wf@ zo%kzxe6>j7^>CSnB`6j40-dm2SQ5~Xq&oFJ6_Gx3(0fIVp}V`j3ryG7PY_!s%{F+X zBXFK0n!b>}aX;CWEJLNXQ#5>O0p~f+f6Cpq`Gt1o_IQyycz|Jj(p!tY@OO?x$0>Rj zpk(U10No}fXj{)s5bL6+Xjp>$kP@8;Z@Q9vm81$QF;%iYSPRkg%JHJI>_VtjWcT?? zTVJidb#lyJ$H}0OlsxrT9bw!&_8#F9ogKAp~ zU!S5^-u%;slqh>r!Sc+bs6~wVHA_PeDPxOrR-XaU`lm@hZAghSe=RP{wvkj<>ii|~ zK&g-t?I7<^KFbk}M8M0n5)bswy7wz#U3r!GrF^G$WFy3ILioH|t6|Chhb67IPf<>4 z@xvzb2+UTJb;!^_Shg?MuokvMMtGg~VtgaN1 z@}evoQ{E~(zfPABm@^g8bWYu_D9cr`i71>rKtf;!R76t@8b< z<};n8oPO-8&fUWv_n8XykNM zjT+X%@yA}E445WAmTgjXv9S9(4JAPdG50ThM_8* zyELqY?T`_fi&$C2p0c9n%jFvO;*)U}>zwXUdP3so|6~|w^I`=uP%C>5fq9U1G1(=-R&cdj>Plrzm)$o=HRE%zRvhpQTn5w zMppU5Q|pR6xvPpYjtv@?jQ>#HX^)?x53cson6>GY=r-e8QE_m6W8rF>tYNJ+$=RJ< zGfvZa*C+o$T*_NQJl)zr^q93y+TGEtb*9<#*V#%rzf6zTQ(}xa?}yASC9eEs7X^oH z(y)Z)yfe)*;69PQ9=Piz+6`|c_WhH(ex&a+Z#^vOyz&3|dh58VmhXN17#P?Iil|^< zfRYBBGXwjG9oT_|VvDWV2)20b?(V)eoIS9&-Q8Zh^IBm4)pK7(nd zX@BNmmUV%`KBF)f&53k0)`?j6`5OwuG8`t$fGMaumPDTZp~j;1v%I3b!vVuGq?d~) z9(WRBGHLC@MERiwMP!(x4O7ToX?9zSCDC^+y&H+*ra~fU@=BZE&E{H@iKF%9i&L#- z>eSJ;limH$JJqmu>1g_<_pJtE+s49TbkWTc;=%J^?c=|(`tADftY?OWYA0^Q>Z{5a zD^8a7jl|(n1%%g!S2j%97hPK`7ZaVeh{OQNWL%`h=^X+bgfY!+i3OmBDWO}QSl zeu(e1e!Ts)8l;a=93^s}zby1cE!)0>c%HptB3e$gA81#o9%Y00>`7kYc+=&Qmw_uM zdN|bQ7prmmJV);yS07vx$!D1V(z5=>D4}JIvf)Vz?wxQ?Wis7uyj!hyyN~GdWUdWQ zw(w*M&$3LW;>rir(X*o{-(sN+&-d_54o~su+so^_h$)rsr~@75*zhzHPb2aClD?69 zz9)Zp_^A5g;c6S6x8mt3uA;O*ANGWeoz_`wpEcix=fbmy@`MavlqIa&`LVv=wD_iNyFmJwCd(IBlrXp z^@b->t%xq&Aw-*WGETqo-q=UI-cvwWa@Q7LJqD^cMseh0Nn{z4j<6-Zo74-AZ3Rll zI=y!H)1nTK(_NyCJ*UbFSpHd1Sg>;q1xiP>(=-i> za#yq^r{eUj8NXT)UH`S8R_Dq%Ju==vWYf!vDrc*UzD+u*u|fXY3fjwFTJ+6|D;e5+ zid2V{5Thu*kA1|%^mhtp5w}Hr6F}K*$ZV7@Ctaha#eY>i?flwZo z6g{23s1YBE3Y3oM&9P;*imfK-`MMg2T6Zf5Q~%9Vh6E`xpoj zT2b5>P*rSvSw}@L1JRG7%4*BHkv})oK-B2lLUevHN$q{>y^7LN_vq2?+T67h^!?in zPyayu#^SEHrDp1-t0*1O4;w1&|T}FFhRe& z*FfxjT3NWH1c-Cbi>T=DAo_X4=`2Qc`o(sOGw185X_w z5xweH5#KHyH%?g6J!JG)u_Tjeqt6KO-cnFqG9n|(y~ABQ*m;6}YuRTjYU1YQrUk91 zK0ji}SXipBsPX1+b(?RD1*IbbOQI96&n<+hZ)PYj$FAS?r0OS=iI6P85L_RKv*kNz$;Td9jI$AGe0=(X{BtyQU3 z)MVUBcdbg(33}ujLq_VOp5jfr>1yJb84RT(0!yOXncG{7L0Se;{B~Y;sw1^k>;!%6 zjL%j?pB+_J>+*cO{?~kCHQ0Wts`yyRSG@7hl8E~c+#z8}^pfW)ZxOe}C&5;~I9IGEInPT-m%CvkQaeCvMpRCnlxmGPWPM`hEIFnf)c2b>lcC0#a zTm+Br9IVxE8K*lu_+&**9xrLJ^(i<)8YS4Gh$fG0-8S2u6~3137e;f; zg)NHxM84?O8lp&CNm08(W@(h5?pP;^TDET>3M}2M`o90hupWqzM~P=(1);P&Xl~}p zrFtM5M={;k{Rb3YJ%gK-dt`FAyVt! zRMk6;8A?Y4mP98L&b`Do&jM<*vx$=RK{Q$kT5H?171@rKVzyo>4DAxu31_g$)H^9q zOh~LG9yRv2q3uIW(5}#(xbmIEanCpE;@45{)bCP%&O@r$*IyY(YDSXtdho zCte;Q9^Y?h@rn0lxK3c5uq3h!m;FTXcK)J6-7_{^i%=7^^Ymu_q84KPpseE2!YnFE zM+BBcob7&n#M}uR)LlhONUJlVaTTT8PW6ThwbgT5$xwe4*KMp5u5i@4e|w45i>rw) z_3}uoGp@DhOVCT{rxa1{Ungoi{g>RrZIkckWEurq{+mRQ(y`s2#z(dR|v`g~HPD8f`Wks7WI zb?#L~qw8g*T@j*j-$pO7b)K9!V4$nWcD9bdy%Xw=dqZlgWEWv>YZd1Uc98b9s0r4I zd^l?dHNrDOTp4{$Md^r;_qEMeG-2O1go%^u9Ho6NqH!NhC&G_g@eLm1)q*8oskn3B zdLvXD*(6qXJC|z3T`|39+5KO(yMLj?S84>m^(9zyFBYeJXG)R0mnq&{3v-Rr;~yHH z%+U3@_{(LbY)`*8lh#`FePl$*BhGBF{*PKMth40%;7X0MiJ6&svHIz6A91#lhvfU< zs?RTnXdArZ^qZdzt&&HV6LX^i#hR&BhTaQ$7OR&jn$0&(|44opF*6_EWG=Q8wUwWh zFJGc)?@q+(C7PvJmHJj~$embyXwwv{tW}NR`mCI1Wf4BZkE3+Vg=n(7ZDZ6j1zL*! zi#{=wj_92wYG^s1$Lg2s7`|xcGVWs9Vyjqs@{0ve8WCORX$`Hz(^$P#bpvr*%g?LM zauW%f125)KQ;VG%t8=GRsU9A$t=f`RvAWma2IA7w{5&|?O)Nd&z)@dp1sPG;%ffnh z?;y(be8Ny)M5An)QF}+J=AbCCZ08Jy`XYMs)WwjIUwA z6JbPmJXT9fo)N3(&T1h3*<$5Inidd`>Bfjpi%@NTbgVwZIn^3?H&hF28>>GYk!pQ7 zs-_k||37rNfq3dVnssT^Po#Vu#85iwE+cx`TBz;(hKkCoGcc5n=qvqdX_Lmq>c@wq z?O1*k7ljtp7Bh;+CgMpmoajLM#*`A> z_`fkXRF?{^Y?y*`9!sJV$b9Enj=SAOt?`R(XfsfE8L@rCIopB}qr~yBLpHQa8R>+6 z+ZYc%!?!G88P)^Q zI4a4@@Gj3+{_8Kgl#i7VINEXE5Dy@}l*qcKhB(v3+k(<@?Bd)cOPvy@#ysjR#?Y7F zP&%S<1{2FWq#9drsDt>K=?Ozk5RF!XZr7~N&v);46W#YZaI{OPJC;QA+`GJ}7R$t* zS4S);9d$?RN-r)h+osMP(OkrO{3BU7M57I+$Y@k!%fJ2>;s36pWJOVTwDT03=;p*T zWZ$WVj|`O7THpG?TAoaCdb{tRtZ0L2RqIhn%=xQ|s2x&XT0c;CTy5}u6 zTyT-rDAXO-L^{8!y*Vh)llN+oLb3;dy5qV_cf)hNV9h$#QwwgP?|^`Bfc3yNk@n7G z?yC=Nn_2Cb&G@jDWwoW*1Lvz18 zMjw*$*^0Svhh#EU_a7$AnVr+*4sm#Kno9tY(bAr>?IXE-(eXW%M}d%^I&f zqQ#A^>f8k(5(4)Lh^CtsKQ^;FRg+Y&((MG@_18|$7^4qd@WqPd%3j|_WhX1vURQT? z3zs54qxW&`){!xK-Xg|X=%12^71p>T-&`O}Ex+fEigpkYvWzLC4<_#OIj3$o(?il~ zas@vv%gizQgZZ+CbW-GgL9LooRlf%|m%MO9U>nj)x1(E#Mg4lJHTQj&_Ji0~GUE2$ z5yJOcgk{4OAL(QQdlUPgUYd%zuf`{CW?5e~lg|2ZjNzyx&Rx~NnA4p7Y=%puguu~` z-ZI_J9Jq!}DpFb8+2SE`HRIa!)noKpUyO5He=W4{7`^}C|Mth*ow?ZEv7^Mt5iQJ* zdNS?%@-h0}i@y-h2=TSXFT@{otKhxNdrD8ya*>&(ys>KG?y>r!6{%K4%d(eQ4zpY{ zn~E1f7g)k+MT;6At5@8YVny`&W}#XWpIAL?i{Y1K%DJ5NSrj62_9(z#f3av`mt*y> zUp`q8owG;{E%(w`efT!R7rpoWjisK8k8tW*g?HZRt5q|_>CfkWvLd?v4W_+*AFE%x zXZY=F+h0)YpBbB2J-i2hlix#Iax+#h>5^h~pW~~|c8}9vlP$rProD65Dr%GYej;S8 zH%~2APJ6G$>YFR4SWzCLXQ*P=pW_2pV+rLUnr<)aTN9r>q}TU8d#BBF`-nq%ID@G_4rNXB zNsSSc+cY;DBiue-Q68enTPhdEtqU^?Khq=?$0%AKv`QvZ{i`+ktZ7BW^Sw1Bdxhf_ zOQQQYmu9dPN85=Whb}N2qliF{gTCnLUxi;e*54H5G&GuH3R(k{O|Jsa%F5qs8*P8Pw&JKe%0SsB)4muFUNmc8by#7>*@^OScG2x+vJ9n5d5VB2cgf2@d5ESyucNBLmAi@k{o6`5 z5#^zkpfltV;i7-lPwKdrK`L4@v^a>Sw_Y5Q)!p%RL`AZqXf4sIp|vBQfh_gk6~fhH zWU0|2qdY{@7mh|$Q76yv6BjpmOCu5Gq1C1@thT+NuJRq1ID=Lk97`w<(e%aJyKgM3 zJ$=N@=2fJzi=z)$AM(PTmb1}wLd4pr0vzWWjy_xy>Ey2VVdgchsTgLtAlVW`tiF*LhFGqw)rr#utL$IjOB~B`O!8#p+Wskt z&fy#{?{lCV>&NNM0n8=0C?a+zkKI@8_g#I=CHER4c4TQ(wHzVbNe1SU#}XpqoQhTD zgg8j|=rNZ(!V&R#T=A;I2(g~t9Kc-iyhB8X6?67!)VkU79+P|q*%}~1?|7iPFUj~o zTKzZI9~*^;vrqQz^&`YbLg0FiJ%~M<7O%B@{2i~QeV<~FpHpm8v2z0GbXfTlKd(_j zVJ9gj97Qo<+Knpq_&Mf6G{x?Ma`Ju@cWzH{XWH>9_V_uXDH5yv;Q>%=n=ho;_9TjJ zQ&d;6N7*S3oPN_rW;6!7Shxp8+}$bSjwvV)OQO>chtsSHMR*5MgctS2R-m1Q@`nLY zY*|I#tjtFzHMzWA?FJrGT?TjdXvBjeT@+?Ar? zbtxK-wME@2KCIZe6m*+>Qa4`eau;^%&;cVRoGu-8r#+SOhgmb=#$fvH>l)kgzb6@S z=XB|arWmAR=Ni#nOB%D>YaXT z2hkK)RqPxc8j1CW^X%czZSRBpjaX{Bbkx1&Xm`b6Y;8+pY^`YChnJ|iL3P^bZp3TT zr6am?A9v*uF}7Z(F}8BfYQgnRS%ve$Z1ke%AL)o5+R$Aw7+V+97+dWx`|-{cMSf8A zjC7X_(Ys5yD+XgLFpaTQ$+rdX89zgP8v52?o+)4?CR=nOf+lkW`m5HZd>jhL`v z=kFnUcNob|XEff3sK9Uf1PU>@qKY>Qu})YLy%e%%H_Jtl(Z?w@jToe2XOf~OFCTj< zJ<^$(bB2Cldm@U9mK|LMN=F2iM5ndBPJG1)Z;>zIviiP{my(0{l-G$*iD-&>Dt|bs zu_w#%aEc<&USHQ>W~Se-#5!R~^a4%i$>w1c8O=nIQHp>nc3v=QLg!4%A8u`tz2h0H z7$92bDQ7TD)1@Nn)Xg5u7#DDI58C`PN;Z+6IttB+fWtrSbmMX^*m*;4H6X!80Mdn}cr z0LmYBbng{S)E^YDJx=jjiYO>{b~NfP*Ico7V4Wx?e34?p6tz(7>}b>w(Zo+orgL42 zJD;GqGwO~AEGdmo%?&>FE8?`HNiU3-nnBg-eS0?Xwc=W!GK7gQHYRdExUMzjjEeZyx3S(vOb7L zD?xsHL=QIp{5f?*%T5CA64nW4FuiVEyCUD+tEyP)U01TAs0rE?VxG0H!1Fnk5XUxO zR8cx2WGi|$e@UKj=Bql=)kRtj5RF!wSQe#o^NM{psRLcD2D2u8oxnPwMWtBklgd0t zYJgb!x`?!@p(beODQf9kgJ;iBNTigFHyA?c>m4HGRc*glW8UHWE!Dh9msV#)<0?w= z+I}tg*k_Z}fj8c(xNc*eaD}7zc~M{9u}l?l(e;E4rQ=#l%rm&Le)4)4Uos-EcwZue zP2cpq)GMP3%@Z)oD z2Z%8XOBzhTbYBg1N8gUV0QRmq-@PY?C{k#+!P!pt$PkSlpvg4rO)nnqyH|ZZy*NYZ zh(<4yz9u+-FfY=un0lk|K!XXG?$;t3Jz2W{(IbeTAXf1~Viluw)E#|olPP>-L*AkG zPgUQtQu2@yjUG9D<#=#izJJjKHE={Oj?z(g^!n+$eXG3rjtxEuNyNZLUmel7voM*6 zBg_qsa2MhT;~od^dEtJCzUI-=owp?B@>yaoqjc0=Mi4ui%_4U6cw$GRbVTF6jac3b zB2@q13~by3(z%~vXJF%=iq?Smw>F=cno3!^)fBQY?e0?g8b0q{sPdy} ztX?^dWzlF+FTs3|skxW>B;p!{9)OH+TAE8#>C;Sv{5{WLS)_Xah(_6T$0RCjf0?PH z#mk%54VFc^2Y~2)Lux5WV`KHM^NbkFbKkuDT%jhSQlZ1rt$0N5oKjo4MjVaQ*#_d# z06%f|A8+x#YyfLHIaK*hvDDRmsn**8HI?!d(~0p-waQx6J91O~*{qXrDQsaV9djX? zc>4SHTR!NcM9S+!7L<h zXDn?X5;GJR*}s+$Pm(?`l#X>;^V6z)UKy(o*l9$Uih30i9h@tOzH{F&Oex@4Lpecw zFV|ryQY+9~dSRW^LK!=WzLhR9)EDI;+GKj@*o%$m*H3)eAIDH%L|?yEL;3e&tp2{Q zp;gu0^i`|Snqu|g92R^#0beP=l4zb6E+oPeAFI#&y!fHkR%PJ6SbgE}6l<^CA&M*A zul-Rl#hREHqFl}vr@wbHWGpza#-{FSByySya+Hp`%ZQ%=YgoyZ9mLUr2`q7KsPg$- zte!n0#fs>Ga}-5$iqqY58#0vg<+$ZL7eD4Lx8S=ESSKurUYgpLUo_5NLfx04AxGVR z*5%5fqH+2WVi-30!IgObI9+>VMEf=znqZsstfc4`S(Br5)Lllri{HUc^r%JiBMTqa z-l`O!a`RFQ648OTgO%huar(z)dESF#3fe9#$zTYXgS-!JS5FP-C!Khq?lNN7 z&vUHOp5kIfd`0QRYuU;W#YQZPgtMQlh^D)*U%dH~F216{_%zmJ`imFX3W%l`lxYO6 zUlJfPmaWS$1?@Sm48##Gyq9JCT3XDjDN|jU0e+iO{~ctW%!ZZOf*g@&#-T?PS^^>rkb#jbz)|bJkLd{2O_W} z+Icm~qc*$nQ>}EhjZ_b81ss+1p5?}i>WGvn>f15xB?OLkoHr)Z@GS1U%c>gU^p7JJ zoNK5Fj$>MJZjWca9ovc7lWsDUjtDG?VvxD~)d#Lj9P3?%qb7((D?wixZ~ahRaVn2^ z-N{!%p!GpJM*eO=cV6UksPKM}&4RWMH9@;V5v=F2toNn9V#>H745cFiOQL%dd;QdG zhr5cXB_|kaf@rkbG)n%?BN9t`iH<=Zr1b-J$CBv%5*JrK<82*b{+!K*($Ti#YDZcf z_h-kZj}W7-ce9{$MB|!BZ$NZgpe}P5ApUuoRayrTjq5JG%Nf~3bZMGJG!N{|a1B56 zDpXn9B39o^uRGu>O1Jy}F2o&9HV~of|FNNT)E!R{=%vD_IhN4=BZX41h>Fq?jXny! z89hQrG2J&QL?lU_#ilU*4o!5uCWG|e!QEK7e+$glp6jxP% z378%cB9`8m`|J^M2Wt^`5X(XY%1+}Ba(}8vXW|Z`CYX!j!|C-)V*>IK!~|?bOhBwH z=E7DtnMRe%!zBAu6D>&l4jKQ^m&mL85c?0J%d5ET$hiA6uD~LI8g_r{ry;tl!GL(n?Pu`M4 zGAlf_j(BkTvk|XV>^w4*hiIDT?JlrYRmLUuB<29c{uMhv4dvmeq`Mi>Raj19CrsV! zZSdg~J0A|^A)0PM9D8HS=H(;a5!Zks)ry^ShiH^d-fPk2>M`OP%<5f$Q#4$$^ZF1? zyaVMA=PqBJ!|EvF8jL3cuVS@-@GME!S=zDh$Gy(wt9X`b8+=#CWFb5-X@4Z|G{K>(>zQR zuTg+M6dNp6!)-0(UHk zrk7is?yJ6Ds%`k7NC|x**#>93vzUGPsrt|Lc?qaH%0Sul-K8b>RsD==Yu`B1 zV7DpuQ!eZe91FCM+Lue+LG$ApafD^*@@nwM&b#+pqkbSBa_y}i0(FcuUx~h(;?xF)zpE>ehuJqI=H*(nv%!S|U1= z$@|t8R?J82j;tctU2Gq;cC>Q#s=_S95za;&VYII}x6z^!PoHdi`025UoyfMM4M$so zXnGeXPcl169N`n^J{t_W^i>Vzp`ACGR?-@Ef_TU;X^q0Q2<0J~zD(LcW&4RE91+!) z;d+PiaJ`~^?dWj6-1C$A;B%1VC!#z=(-#q{muDYnJ$Kbs8jQwtF9YS_x@$5$uAsBM z#6ylJ9y0m{xP~LzWLj}Nm-!2^CL@=mafH)X1C)pUgUPgd)F$(1;vw()lEy<$_w-R7 zqG>a6W=>T*H_8~{cIFwDE7zmYs^a?${?!KJUtx;eqJK)FJWV_WdF_e$3`LIP{#uY46fR5=2^N2fIWykOWdfM zokZ5@H`IWgR<-kinZZS#$LskW9$KpuA0FJI#8kcEmq*sodUUX2nyPO)@rX_b!*{e3 zL3N+18+)}>F<0q#1A}#ksd~!C{~{D~AyM*tU2$khHFdjhT(IgrRd1I0u_Oa!((Oj5}Z}lNc=q-RQ^gMRe2~`kG`;(=@tUP& z!@;6tu1S(sh$gL)?DeA?RZlzdnoAvQxuahiJ(#WuYDhhp^rr{w9;w2|Y$__Q`0Qa= z7NV*Dlk8)fUYhb9&RF(n5!hQddNBQsctleVCfUaVt%KR3dB%2OYO87GjroyY7HXnS z8l5!fXS{ykv@t)H4G-WaMpYJ%9+y|KEJO!%ic9)gWU5~Jyn*O=sx|YC9x9$Uej>fV zkLUr1CMJEYI8}dl-9XfuR-Ahm)73!-Dhn(NH96*ZLj3fds@MN%e4(O9gNy9eTrLt{ zW)@f$q7zG>6Ax-m)n7Xr-%+QM4Yl!8_S_M6@**+wN z39Uwcfn`YuD2dqW&Ic2ZevB4Zrj9bSO8-g-eis5uBE;xd>d}cg#mo%8l2+7K+}>-8 zTQv(lP;jdLPZOgDJNlOpOF}a7&l8;lrl1YR`jLkmxLJ*^6ebSde6LdbaC=W-E=1EC z*xMX!7V>2Jye=yt(AMJjP3Z2@hqpH8TEoPy*|j9wj+Rl_5(CQ z+eNqHFI8YMrV(Pd*JT@)g__{^P00G3a^|Iu)DbD$i>O!@qR|G^2}_MmymiOBYE)kj z6>Tk|(axv&49xB`U|FaMu0+I6I8~B=DqKZ$o3N5$S%}8<%48~kFPzsV-zOvaKDaI+ z8rMXViF^i&;WG>-p8?B4P0*L1NJG!rtkHNEQFEMyV_AsCwLQ)EVM*lsWFy}Py$SSv zaBZiPiH+B6Ey!nZC7*%HP4|7UTv@B+eGApXRr82}$3i6;h`^HQOn>bGwbF0j2eqO) zrTdKNsnMIuzQa|+X9yynf%+ibPsDQ3*D{$L-2#M{zl&)0tT)siS<%|j zS1JqnviZeMt6Du7ftCp8Kiz^j;lt8pfR95mM7j)+O?MP0mgcuVu25Is@D)-nK;vvC zFQdRnKI7&_Tb#42YI-;dkzoRnKNL&%wu) z=D9R$t%pjnmgB03ibpGnyO&jwwbo?4?TSa%jy1bgzF&Q^-a?Qqkq}CqNtR4KV#KJz zt<09u+r{FVll6!JkF2c&x>cSKI9b0tO-54>E^y|lyo8AOltFke?w|C4zAZXYeP~5_ zay_bd7|Tws9U>Z-ms%E9YM-Pno2>6!_0Wp)5KS*G9_zt(E<2}YVi^)@cbJ@%Tz!f@ zDe{38J1@;B-cY_A8(Lo}Ve&Tb%46J%9Aa_v4G?1D^mw? z|JXc6{Tyr`S11qBCe!o<&LWh??q?diG~&2@exN+G!Q_{;AFJM{v8yUeEi_)aeSV-k z32pkQmr~uwR}pQGR1!GvP@Zf>2REB!bEG*q{Y`T-&O4NcXj*IAOtRhS9wP?Qti=?R zhb5Uzl}M`&WEuR(GN5#{28gB;FRJ+^s(D_TwOB)xhZ@rRyVSaGsCC1rb+Hvu9-`^a zPsnk#!q4`?Q=iAMr%)cYH0@Z9^$>NIpHq8_3<=U`fK>+3^tQ;m9qRF7HH4$hQJNnp z4@V4|)hDs_VM zlE*|PvvZ81$Q68dAri@jNGp`ICM7g8$81+>8`hoJ$ zqEd|INDuC@{+v2<^-&(8DH`5xEPGC4_h!ga3yrw+br9v@%0Mpy(W=I2>^`Eg zE3ICzh9jEZvWT2yc|>#Yq)Q7k&K#77D;&L3q?KZ&$TIXK%YgF^9} zE78sSm9!dU%rr%xw)cUwa?1616V`X{c|s)7O9+^PEs7=47uifvRjyI|;5m|LwQX;q9OahMBjt>gZti|N0(0TWkP&olK!3*YU;i3^ztxPt zht=0ZjNi>`%u|Nhsw>8C^ST)N_t&3a2u%5v`d0h(e@3ofCH)5cmVvp9vW;B7Wc@FM zoNHMc;$ZD<9>2={f61T|{`6dcPX6Br%mo^1{~Lk1pcVcP1m=R){l5@@`ar8Zt4{e} zExPRgKwvJCK{Zb6!T*gIgSkjU%9+;B{}%#sQ7fb&ej)!y501fH)Y88YY1;iSgq+K$ z@mp>6R(0e5?hoqo^jv_ZG5jAHW9*|HbAg7+|3+XgXsiDNfw`ci|1ZR!UV~i5csBn0 zzel@0Wtjrw>OY8V*GBRzPestK$|Y5*Ii;q}I~pN>=1N_$l>Wbsp7GylNfd*gG?GvI z86V{R(nH0RV2=f9xmGmalq{FD?s^QLTsJTwYH1D&mOH5buX4j?x+G#rv`bwb#oec~ zgfrb$Nvp?+bJJuD7^o$0h>lPD9THPeBdrQY@+;9L&GY&^RWXJ7hH|A@pER5Gr+&LK z1@H+!-UiXXg8CyZm(i1muubomCL`%deUh>HVr4$?x+&;$-avsV+ds3kTxNa5Z!2e? zE3Y>;jJlJAys#kc8nb@$yj^y;Rd5z zV_p)1#+hBli%KQc+P}5J6qq0Xv3579uSZkOqp9XFql|Tf%KcRjY7x@EjsB~xoPt)X zMm@Sj@qsv!}TRv{tvD7 zRu^0e@%kFQ=t%Y|~@mlkaUb>%S zIR(-5g}ecs#OFR zYZWr*o>!4$3Th?GIPdsW{W`dxrQYt&9Bh=~M{9;{+s!5!*AC_t z9o|()a4+AKV=io;o43kpUDrA4dA%kOBJ=y7>WyKW&6(D>rbJ$WHy*@6hYU!F|}oI$11LFQ?VR82@Qr#ktX)Lj3QhXwCaCRyv1n2&obHO-rq3 z_(Si!hFfa<^sy|f74v&9W%z2#lo7YS^6%X~XanCbReBG97`!m(qZZx9Xe+W7IPkn$C-cXhZH$pfQh$xtQzu=N+8wj$ZHG*zm*qT^Es2i$KRJz& zSnldOw(@L6i(~N!2~o6a2BpSqKL)(W~i588PaNQ}i*OqZ=N;ui5ifGfoXc^Da>mCbrNI*9oP1bS@ObbIn_3 z$(G`1!4z8C6}z7xmo(0M1n=E%h}q>!4Z|-U`cdO`1(j* zyE{AB*}J5KK-~wIo2Rrq8LICpXN>K0PlxdN5!o%B-6t?iK^Z7J&G+GvzkMInoqV6P zRxo@YxgL#^2l5-6gAZmNw1i>bqCC`)-YGiPkY_qrF=60~!W>69_6_zXoxPsV$6rT| zOeor;2}hfOqY}rl$rMlXyfn@8A4dmqw68eNasHDP4W5^H`?pO*+m1F-wxY#o{m4M; zM=e@EaP7nOgJdMzZ9d)L$s8c6S1Ffpn&u#`$fUbww~tiwwBNt#^Vm63Gw`LJtv(nP_&HpoVXjsJtyvW=?&8$`tm8s7(x3%+&kmG7RD9HpuHMj{d=#5 z`+nS?!`LMR?Y#K>-#afnnZPpum>-0oT@f$!dsl>~DtP(z~(cCK>$TaIwwNjqyzx7^ajOFk4IVtfRO3mO;UiOr~o83=_{? zH(SDYHIQnKx%MQ^)+{e;=o1S+BpJKf4iO{X&NR=xJw>Vq=E9jqEF|j?5#?3DT>EG| z!(6!EkrAbb4;CMN+OhIcX0|9kUaMW1>5;B(lJ4Ex&ekGx*3q|Y&ZtlC|yR){ViG*z3KCrH2Wy&xeLm+31;Bwa8!uD+LH3hum6Lz8KOh!XG2%bD+qhOAa< ztoHs+fWG5LsDd(l%TCocc!cOXZhDc7#;2l$GItAGo!6CNO23q`TB)Ewy;sp@3YJ7( z-=IFie{)@SCTxjRbIg_Re4KV{pO4-nXBCq1@=X^}@4AoW`R6+fQ*dXBb)r}0$8{AS zCLLx|7B^sd7mU)_BtL!KfG|mu6Ai{{vo=@P+xfL58J9kE7meHXXMr2GNi|3Gs&+A2 zT>i>>u`Zkt5#>6HB7PGs+rE5Yn1VZO)R6qEqz>ZI*;`C2)rDyTx@(g)Prc0LJ_^b> z9x+DS5?@u{n4vSt$osyN=z2V!y$umkJrLcqTTd;nvxn|DstqA}4{j;m`~PLRSUfw& z6x@H}xqTl?tC&%`Ou zZ?@N3&-2pvME*ruH9Q$6oGWGLTgG=_n36GLW9`=ZvieK&cm?ZZGDW{`DF)5j!0I-< zF3SMKv)oO!uH8%Ot1}HG84iQ$ipsNhTM~1)a7@A7HnsxY7zt3sv$xK?WWn)ldwf-` znc}7|nKx5Gtun^7)G}_asQa9pMKTh->WU#x4ztX6-ZRXF=w%D4Yp1-5>T9};BSa^^ zAn{M0JC>A=o*Yx~%mFo|vy5Q@A}Pg#kBS?|`hN7*SoV^7T=zK&%9t~SYrYf9>T}wx zBpLnw<)Yoot8CxIj2v?zI_8J3mQ!=q>)$bUUduN7h>#~)SWe#njwyKhff~}AnYn$% zrnwb)+yq&xBQ>gPds>#!w;oudbjVUkt3ITZ-pgqd$*5biyy!C7k6&y%iD62#pR*SK z%|#z_ZmEJA(mJRFh@&l^v37+WIi?^&aVx5wb110ScA8Eyx-2UrmNm-Ber65kn1bgT z=y%aO!ZY23d$2d#vphud$gmZ#B$~C|3yIjNA-w$d`Rq!k@5y(UI_tx1YZcV$U^_Rh zbSpPKoBIyZYSKA3ar96I9`0C}V=hGB=xfr>WY4Q-{$%V@Ck@Rno^^I-SAR6%n1ZJ* zSSLEmIQmuX$HMrNEX!GwL&uZnzbT~qxNT8T#*|{&v}aFT^|Id&kc{SMGmAle8u5HH z;~A#(n)W)mxKlBGeHEc#NyGzq<0x(v%gy(OyKyWRbM3I5O5S@Zr#^k4aVE2M-e+}g zQZ;sQR~wEg=q+QN$XW6~uC9n{%bT8A!`cKbNVa}2pwGLsL((L0>CNPM`CN2w4~=Ae zu6|$r`NEk8wy4Na6GU%Vuqb)JFh_mupyh-p+RCQR%HNLFZrM%J3Ui?kPv0?dKB4Y( zpfxbI3&&h|IwT{`usQ0Ek6rjZ^G5cdNWs&Ui=(WAmVlDF2)reAhnO^Ak@I;hHs-t6W60UT5C@cqMj4xJVbV44!urmTbIO{vlahum&Zm29-Agjw z)hnr1|5%>S^b6vs3FeyoVoFl~saf@15o-vsWP3){TMTD!a}43A32G=KvS+=S*yKk) zKE-Pb!*Wrp(ZyE>z9~{zFFWoW$p~+BC{ZocpKm_AnPJMh3s?D!G5Pe@Z}$GD9z*Xu zN?cIhlTT}E;V1(UOM2hrd3t5lCoeSW;purW@#M(i>@Sa@9QDOq@*X$1(W%7lbbE43 zxuG0$;R&RSC|Y-p#kFTYek)}&a~O3q_*1LGdb`tSm76|?f?L?~=@nY_hnz8UOhLqt{zrqO_GZ<)yBPIQ92Z&U?u%yb>*Nzi)C#qwbB0b{>}{ne9-U_k zOZ>Za$TIGvn|w|yiNYE(FD}2{X25PqL-MJ!)nS*1mgD0J1=5@Me{@Gg;}wa;>f<$A^q2>EM)lfJC-DW%f= zl_5_Oob~As4a<-x+hR7B5U2lxz&at?WE$wOnk}}v^QHs+Im)=ljMiWLPfhzGAK(veZ;m zUmSRtWc)Sw0vp=Jg%2rKi6f%)?p-10J`~j7j@+iO?t4N~*5=S(4lz#MA}?-dX9K&i zabtRL)E9H%i4J{tX_}2)o7SGy3h2f$7oOb8h($}@vw$Ye`2@Ea3^hUBz1O@BIh3!M zzAaRcR)MDwir%q5#z_c9iOYx$p#IfzMn(lW*5_s zowX^0#}`&M94VpCTE3fPw5;mP|GJume~okDh!|8pm(r+jQ9X9xO2xq;k223Ezg{ZX z@OLvd&dft^hOwlp^!;`KN#&K73Ft!*WrR0NqWQ*v(DP@o78B_xe72sv#%xu(;dK@*uTzG0o z-#+VAfgcjSeBy}-EYlG`CBt7O^`X^fD=6drH!tP>uu^)@T!!~ry^%MM{8pKZPrVrC zLfvJ=p1xK1fT54sRW&7HEUg=#OvB zA+5YkwRz)9$JqO&sS=|0`Uc9KyJd8*j1!gBdm1UL$Cl9j%NViL>J_T;g1y~XBXcE5 zE6jzl5Zc%BMtt8*M_%M{7v_<%tI|BLr@l9}zk)K_UTCj$S?Hy&Z)@xzBZf5LyQ*a8 zlP1<+mIR)rtM$}Qxos3l; zT=v!zDi|@AF{Rt_T|YF-&syIZreKT(&-ZB`RlgOlmS43rx|v0a%3wXPBsz_n(u?=% zv6~gMRA!g1PEkxT7QI0E(h6$z?de!$XK z6z_Do0n2l6xr9J@&hhcen>vAd;sGa;QU739?vuLDQugOHspgnVj$qx*GME>>8OvG+ z<&o;qD<)nUHaVEQS0Ckh&e_VC4Yl<}Co_|bS33sr>xJ^MO*h9%h@h9Vl<-+K^+#c; zA#HojR>t;%0${AA1ca{0dtsxEdnbS{@48IJ+`Tb~5wxY0%K;02dZvti?#*0l*Enb1GB^h^W z&R232Y@lm3MM(Lj^Odz*>*)(B?IszAL!x=VPA--f=CKS@FoK1VCOW5HJ(!Oj{?1%4 za=H}r!kS}A6z$70ir1`o#A43=)`FT~ZEcqqD<%84)ZhQxl(d@UF_I^^23UH$s=yF& z`_W=0yi`lQPmV?*9X~Htrd@8K&o5V(5H{NgexP*@%hA16qy`$}`_ zi&P7ii<;00z4GUT{#5cP-Zd$k+2>mph6p;XSL|o{RVW_m{IRv}@xb6Mojf>-S58U^ zin)=Mp(dCMqkwcZ{QD?=@3M9vbAFS-TS|{@A_8ND^p=IgXg>LD#=v&vepoOUY9%8E z{20akGv7bZ;r>qx=EB;_h=}k}yu#D02_=*AOIl%zV*Tii6l$w)m9v_!=g-PeE6jy$ zNOv=+t!#zg2Q|2sm7yl6p^Uiqb{L=L9g=WjKs$z-;MkQ%Vhit){N>R=OX|V$Qh#7B z9B=flTECHeNzq8lg2<8#M+RylBkJ}a%&+#EXucRaQ<@)W4REedY&+*L{*N`;^0a3w zY3yPyv=}B+@_}LeoqHix<4HM&vj{bj5yxlr;VB=knk!d7AVrbUa-tohFPZHe#G?lm zU{RIEGSmcfq17e^ME=1%{&Xic$dfU&QK*TGIQu!0Pn}fNviIx*hMM52Ca+P&Hb?P; zY8abdV7X*>F&C~x^d@<+zI%c+E|-+f3)B7rKYRI ztU>=1eLIt>Q1KQ#`|&Mobm`j+HNjlyanko7=QrmMa%A8$21hdVInnErwHozLHNMXI zk)=U$C61b)-;Vw~eWzh@Eq*fT1mjIp8ES&LaA!ep{O;lW_8}LZFmM7xuNZZg5iK^A z<&AGYTb3O^+wTOeItj;cZ`j`v%KE!e8?Z;zER^Zdtk7KxB!u^M= z)vou>yhtNAcCL0EiTi>3Ox*R+xGLqrzs&l^{w`BM+DBn7+*uM+*42gI3}$>m*i42y zI@Dc8)UTPHM_2S@^OBl!)CBkBxI-om2WKeJ3vKdFFh{h5zGGNjm+&TzG;+ zyruI8SoDVud|ccUdg&`aOaad`b(!# zh{n@4I*02zja@p|m3LUMk>R-*Y9b?oJC|k^_YY&UuMOgOZiq7QOwMGwTE7;1wY?ng zmmyH92cq#TlUOevoaJvB#T#~6$1nv?Zt-lNl@aAsZ@Eu9FX3_S5PnU)^j zZ0Ra&d7eQvGkbSkGF2RiD62%XaDj?c?;`3mz`5kLyFxEKb5%M zYXm#uJe1>kG_tqw#GAg;kn|w2b7@chx|Kz$2j;?4bz*FtxsmwBxj&CzAfM2qR;VpS zMmy(LyN?{m_B#)e&f8Hdj3?0E;7)OM{N3_gv<{LG7-_(m1@-y)?5fk8K72_hInsc+ zFfKyhN=a&B{ry?mbmc|xBVmpMzAmzMz2Ot zT+=Q50EV&qS*hr^}U>IsK7?9H)oiFJ?hVU$N_;guXk&g{AQnEdWi zoD&fk$E7bjoXadSP)xYP^mvAGVAN2qN6@oe;#T20?0wEg((M6^nWH>ng_UpL zBGO$MWFDbBvT*ZSiYT`YY)*!o3{wyxbBen8H52DHX5q0{6q$tt93QzJ$%Vp2T*P6^ zoMIUzZWMC7kS9f7qWQa%=n)#vj-O6qs0rpmz8Ag3wz{JjBp$MN6MY%7zmQEO*CUAD zk~v;tpXCKhVaPB;ZXC*^ccV^r7av#jXFqyxm$+((K>i(l3A0moF`nz}TqZw;OgYq0 zu7_ml?A0ka>vm=-rP7eT3Gy4x7Arsl@9;1TqgzrZdDgTrztLGv#z; z$S_0=<$4Tq?Jw4ipJXY%e1mlR3|X2ekK$3L!Q%AGT&!&8IEgih2;`2MOjm{u7LN;! zVoM(7X2{t@KBQa^v1_O}x4)#tHmtA2*+!-;GHA(XI5SK%Td={hqf;Y^VT!qsHB09V z2ZoDs`P|sTof#OiV^Kr79(__q3N7fCxtLm1x}!+vWt#mA5#`Yff8R!m=pA>>Ps$aQ zn6ikV^Rje?F>z9Dqr|EwlP!;LKC>X-7`eQ1J?I2dJiVYDaG(=NItA2>yBWr<1e77O zis=MWOraCVj&uTv2-F18w1fOHN>ri~$kucMi3rpX(G*L4F_?Q^?XJd7D5b8szgQ_; zw5#qM@>kNQmh+VCFZ$~DUkt1$09Uz2Ch_!^k6f74@qMcXHrhEb+0%zqBm~wl6RGPdcBkO9&T&KJG zgji090776cyw@%x+;TP*X9=PFl9AR{zw43K|3*Csk@nlTmz<`RnDkpKOd)w`XhSQ~ zHoc^@nhTu}>wdLWdJ6Up-fy6LMgR5|qY2TQ5SR<^AIk{pK{1RFMh{{xL{o33$u>q0 zv0e)F7Y=(jsPzNmEjSviJ?ChH4)sqP`Q5HA&}#SZmG+ygPrxvdA-0FgcFZ?p3YLo{ zQB;PF77m_|Y&R1eEuOg-X#u&rrj>;wU%m_CF?zJ9b7Pk+W81OP4QZ5tB@tt5^k{BJ zP>S;ZvGvtqRW0B9+eEQN<=TZ;Q4teS&)x&)U?(O97>FVmAc_HkMOfI4c@?`Ai@ito zw!2$UY{hP`@muGh_w$aw?;q!R&hyN?Yptm@Gb?8Q=7Dop%qx0RGMaVRo~T}~pHIeG z`0j&#0 zV_^P02G!UM^TzCvwtgEiYL+?m#werZhd3I+E>HWjar-i~P5I+wEI|p8k|gbU8_tf_ z?y9Y7;H06>K*WVLsGTt9mHlN z&(~&$&Csv}=^`aMS!T3m4U0_CHl4Q@bV`cbuoD{i6tPa_n#AZ@xu3_*Bl$ z`nTLBbFs7ijHfL|6C$KRP1d<=qPk{~NkE|PLNsOSoyfs<#Jia8kLW3631QAp{|(j6 zVLpA0Xy?hqqwRod%+BSodV(>I+_4s-CCTAnc2-@_rj^^(onr~+7$GHEgF99$YPTf$ z`_)h(+X-`*mMXhEE8X@r^bQM2DwprKl)yGqP3h$a@}oSv`OC`QM*l@KbgYGF$}C>H zQfWP{fmY-6P>v;-D}|IO2C_mPC3jVeCjS^MNY(#ztmnI#zQ%xei}Wpy*EVFV?`1eV zT}D!6&woeF?>HqTbCfM>i)LEZiy)Y_B_bBAU8%MDB^7bkf42kk%1BxpCF_eGH0BlZ zXn9B~Q&4@4jNgK zChHX!$|dtVsSRK6rXAQaz&fvNCDwOJuuU{$^#9GP@+Wfe-!luk62u)b4*QlYex)bfTiU+`;1VF|4X{r8GON^}<8P?P)K-I_A|g~_^V|J#uf zL915(->Tg>t2O`9a=PXmVbcu%?aqj%HLw3qGm!S-3BR-t?ysbM^xs;Iw37Zmef1-w zHE&GXCooI<{Ktc|kN#WxAe!Pb)&=p3q(z&N7R3_eC!R9$uQt@ypNH_vZIZ3J{lAmm zaLY`6Skd9eGHF#RX=?p{x}A0de)!jJfF-2o|2rEZCEJd}fA2VWPCx|h4Eq1}D7RAq z+}!w{mVPHa1xu>7ovzRQlC`VR4yXU#;po-V6`|a^4_>2v5D{1ldE53V{(FzYb|4xh zl%#`O4R!L@A-uasvWESGtrbV`asF7%m-eVo+M}=p5jZxs9fvpgwd3IY!7&#{kaisY zd&j{!ifEjbw*7-!_m8!-f8Y$qTH^Yk-GJx$wHx3{#TASz&8Dd}|6iIKH4bVb)DmQ; zCJmSCm)=Efi5gDSSEP64yub7=B2e#Q7A?IIPrCiL7R5aSb-Rcl4X6CpaMarWc1YYa za4#X1*ryirCVf?a^cD5VfBQD>gLt!$ByB@Y){C@HC}|%&8{i&JV`H}7$gKASimjd1 zntl4Eeeh&~weapkFFMdkrpYf|g6ADP$%qJ=?Xq>Y_n_I1rzM)Z=HK^0S_S6cT7tf> zw%U+?>k>TOVJ$>U60LLAg4X#nTIYCTrFCxpz0PSp!s(UnAIy6HXifJIJPG586;GVD z+XTz`>o$SsbGl8Kf8W*dd`&*#lF{6oPWtERq>uLu%tgnWg(T6roj3S(ZpS+g-Z@0X zN4j}g@6I{tYaUpFJn%+lyF1$u*1I#_;xOM`)C_d5<;#hO^ok|W6Xyx<^vUD4X1AH z%`>kyFfTh1Z;ZJ$nGi#h{&GtuM2$aMj;j`Xfxh5UBVWT*LVPN-O~d^IcR1Xy=vGui zaSxjn!Yh^(`wAt*exoy7*;)^?6{00+z?aay;e?o7PHZ`j4fX>0Yn@6r znl(Fw|12twIchuX1xZR?(QaQh;!(KbHVs>ddoA_|zG&n1CcqlV(OyH35M=<%zQtR zrS9L8V2pTU&6VjJJ8JI^LbUh;for8{@^($3b@OA=NkV+c(YxVWLOh`n#C71f*Spd0 z)rDh2-q)#D_SPfBm-5>*oTE6~#W63?Z+C;8gzzG%aCL6W9&RprXQE+Durs5ClGLsM-WGr^wq>&4XnLemk`+R@u&LgTcsG| zV~m^m4@C9>wiWe`RuqG&V*n2=I@-&*Qjd(v>I$wI#E^lZ9*hEcB10kb%QUX|DH z-bg%#5f2{yhJ}rmt!e0#_%VI7EF_#WJDcdE&8xdKYQo`3lcnq<4Lqx*a4$ zG2(%zRMc?ddACPcpM3#@ctY9-YvC;nH3mh{4Ly{+h7hxf2hI#!=QtNAiuGrDgWZH^ zNC=z_lbcl1S2#^I3Z~BeV?5j|RBUM7)k+cqXTvV%lc}eb8OGP^d;UOVcC52+10li) zf#Zy`M3gE%YFxwXgc$ut@8Zc4Pn?t=^`YV3MTEFWJh0#KB#YxDNge7=NM1pRjfBA7 z#j(Mg1)ajzXC^Ntgh2>g&p2vGiL#fYChgfyhz^9n7Sde$?`DekL^@L+9_qH25LPXU zV}N=WDM?bqjD7X3BiNV_s9$l_iip7j_as|&dlDhA7fJU2ESq9qdG2@oKlgLIi{Q+c zqU=W1rA^{LgA2wxjE}c6-+mVl1@-XCG=f z5ixygl5KrVCj`z6oL6GYi*Cqa8$qk4#uB`%;T?`*Yx8_;VAZ0Ye<1Kai1$Q#z4d&d zvbWk)n+10J$>v-0rBYWaUwS?pcpP1Zq5!?Lzx z03mSK$6Bc8=@r3)a~kX?L{)3c!Lo^xpoHWlQ^WYI<+GLiCmzaE_Q&X>ezd2TnXjAM zo}H*4DBarjAHB5KeK6>Q0s4)#pVeqH|OUw{4R9XA_~8{QptJ$G%}e|-0c z@^RL5;USrM*}VLjGSWo}krMgnPqpR^uRF5CE+1v2g=i5GTHcj+UDuFR$!VvcBp4fo z5lQp~$$bv|{M~l!Xo0u#i&c&F3q_o5vd4K<)o&(NvHi!lY-mMIcjwcdxU#LU_sK}N zuWuWDz&;lnVr*fi`!%U<`!7lNr@HgBr>?BcyL~d2AU~ueNek_|@ek+i*)-3MCM>}= zAwSYShs*JGxtg<{v#-i1FQSnjec$=5J5OCvi-iR}ma$JTdJFkUQnMum_@m(++2_vo z3ic01>0xXfy@x!e80RnAv(e`9@?h5-`r{hqZGFf z#C4f6(nWqqiQalC`dBNQ)Q|N$@jymeh!zo+KI^q3e}}NN2R`t`pec@j88>0Ar2;KlgdQV-fN9 zgpR3ew$VEpq`@iLu!o2C%zG?zd#K7-f)T$+iN1-H=%Y4$7tZFnPNoFt|IsRTNs<#j zmax&q_fp7u{`HGmqEjS0_WY%cCCCFQk!Q5wv6KP*#;^}>0u-c+FRUOXiVL^&RPQ|; z!)EvCCLqopWgah2XGw(--xLq$JyQ-I7QrrTsVlsAg0&D$FMq9fRVL0F$vS)uP#$^> z_4L=W#sDMj#rXEHWdTZ!fuq>*cuC-~FZ)4{PiwNILQ0hNd!@IU+a;Q{Ya1dXcSMLh z@`O%TdKCy|+uk=9q{8<^P(q4yS{SP&J_=)(UzS#8FWul-vq34_s9}BsqUp3WHc4rF zIfVIkIU)}kXm}>S&q83H2BOJ-KB2#IsBSoWoLNc8n?Qa@iQZhEcU4(-FMzf5%d0G# z_QZ4c%&e7)?{gqO@|eVZQQG{)C*rCB>i^V~6&Y%Ryk z7vyJsXFEGvSF8tHz4nKU89azUN@TN~^jYZ=?#n8#%O>!+-o(j#wxyGeA5x;1(g&4i z&KsMtJab3c-?1nD9rikY}xpC#R_&m#KQ zkx>$?g=l)wVPF;Z;w@t*iWXJA_HAeGe5saAcFgla3F!qI`f}th`mqP6WGq1*NJ)}z zlyA-opDf2Fwmv7%d)Lu?@RO^J2j<{m<{Q0bVeiJOC)Z)araq9d1f@bsk|cL*!}8@V z!J@JkQu1n{X1iBerzOnoLw@w4gQ*u=67oaY^zey{2+X3y+(qgupU$jTn|!QT`D{W~ zBl18>bRYB>#7dY>DG?bN0uRg|MSk?+N$L7*>RZw@FweYCQ0jN zhp{j1<|yBTp2-DbCz}0!o$fJn7IRc3sX*Wu_PB9#B`o}@fWS8Z5KVa#0fB73=Xs^G z-vv3pDbl<-(bG19NEh2g@8V?ovKDtfEBUr($XJ5?GicCAbJ}dhMv1IAgcx}1vvO{m zh`?INn>-CIquA!#h2;Rpd-9n4appC@ZY-Gfjk(s=c0{qahgO@4xQGb!c_CVow!e*J zhSLN2*2)`llijiApt7B9@*-W#oTeS8^BC4Rv!!w);Gw+X>tyr&fDSeU*212aq(OWX z3wsx!ES&aK#u6M&q(onkJUfcz`Wc|y@O>yFU95%D((e2wlJTGS)m2V6t+9ju#r0v! z)1BkYCqDN4H6FM2N3x@5?yD^`p2}~xPc(Oa8)z#*?;=v7zS=XEeLh%IJ01N%;IZNS zWOI(={cLEYBuO8;MzNwEFHN;7+_T2-(n%#NMi@s^lq%&xf3~4qx@PpfB%^P$;g0d< zi+re!NBi92=81Dh{Ax%4vLUR2{d(^F++H@dTp?Q`(QtukelWMrdI^Od}#Y_g->mv)22CYE-- zI=8I2D|i0d+Z>q@ZL1Y=+1p(D;RM@%(Q07-u0NaMlCI4heO5+V$O9>nFZGF;HQHI3 z_jJ4^BP~RWh?%Li+0P|zd~3gtGD?De3eme%ae6N1bkT>GDSJ^am{!wl_cPWe`vy}r zbL$>)w*TnapjREQnpl7P8a!gyF&XJ1KmU~WW=GeFHZ*qPWx!8w(K77c&k23o1u;oaJzT#^4Q+aiuC$H1_n~by&Eh3ZxN0igCLEPopLm4GO zPXl@&C`WN%tWw-@1kZKMQTgn!-7{h9bersp%MJBBuwjPnzv!FTnjEWiTswl_inddb zZj)ozJU9K!YB^G(Nb06(cCqlf`TRJaYaft%bm2dMFdY-Yf;)x zDrp)pI*Tq^?$Dw~UxYr^hh}C3KfKPOU^+E$|*$?-p#AvE-CXqttbcvUngR(mp$!wV3l`d9?CKMlS%? zLNs|AF3!{1*9zm!?mUyR#HHuZ)UkWB<}OmAm%r>@sfo`cX||t}QFd%CN=xt7uAiw6 ziyF&KNzD|jg`PigJSNu}t4)3}k{4ih3QB_B3{k3a=VG+JUSa&hXcwjSvxljz7iX;^ z^i3g}zKbkv)b<}7#&7I;ETi855lD$%<#Nx@XP)W8H#}`EV~KO4XQ{;pXYoTy^xo3u z%UaCbf!z4(u*_RLOAQUqs)fD@5#bb-pZl%q!dta%B_mx#i-^4wUTF1Pd-L&SD=OoT zRMk&Atg!Le4`JKpdP+R+UpzKJAGNk|Y<_*3U;v+X+kyl#!>$NkyucENk-MYt~cWf0;UThWjsr$Mxm}z4gt(Hr}L54h-at`(4mF zKenCW{)@WBo*uF*O0T$L*e}HRMjb5ANyrORB>+BYDT?_f_+*yE2xb zR|X^Y=*;jTf|rV36Pg~vkf681DoNcX|>5q!sxLfXyL z$1=7SYayCqSWXY*J3}vMtM@;aac1C{m8Z+Jtq(d1`s`W@n^nxcR@g%df`4?s7d0$?ja)ylOK|E#R>5RrhDaKU0_PlJ@OTy_D zPs@0cB}>sR3)7ZY;+yl+Z5!h3@MeK$c#0%{(2qs+OVivZJ1KbQz!)aHEz#?gbNaJo zXVbL79bO2xJG|qFh~0EcJw&(EQ*=wkyCvRI#d~c+IEj9P4yE5MU@rI2zR+@?b zj$-Aj4^Wb8UYF5Eg7yo%-BUEKzaPuf?~CH=zfZ9HpsfdOCz5pccs(|UemAbal+oUX zmLjy5(U%v!J}U=hUskY3Ug1R`w4{nw&ZR&4DfwoOU`s766toqiH5+ZcbS|lOEG39+ z`tQi5k2ZF+>7%Wm>~LxET1?0YcHm@A;WZNUv7l#z_Na(Qnsl!p+qyhmMt=?ZjnLmh zFJSJh!2LdXvD}uoGWxdA$A-QsvP@iV$s1NI&0b%*E~76EJ(!|j?dKD$$LZLDuW4J3wR$p7 z?dDTjf8t!vCKXDUH_k$DZo2>CA*%tr(t>p5&eZWjJ6_yqp*w$XY^!x}hD9If^&9bd zVPk%yPAzsMbBT&2NEi7@l51K?em1E!^YdP&_9}HXb&Gv(+Y$`;KC72096Eu(k3V)Im6M8sw1#=O3RE31(pBFyFf)|-Ud?8X*EQ{>r*f3<#5 ze(Yzd5J9SKEpDd1{$%r0Sejm3pBkIxNwHA&^8J0<*C#{R^#jXPEGf{rRjO}-ldVnI zK8mL%9({<%w?B9+c>Eys``*88twnyM+v{}Grd}Sy`ril z*>G{zf3i&EX{7AP5y4_+FH^C^t@~8Z7U@-NQXwTtnm%)#5;rWAE$S5_AWk*v>v?v6 zR?87hAxQPsDPNw4uRA7r+a;K{W|q+2&6>c$n7-|W)Od^gSJ1+pL|`i_ZLG+Vv@t?A^f1l9FucXL_yzBZ{A z-3&H=tk&1oj?47_W%aE8^hKTUXy%)Gv`Lx!lLQ1xa?2^m?056`9(BtS&F&R`Z`w#a zumpJ^Z%NAAE1DIm`rfpmh1gdP{|+)Ajr6ujg_Ou&OW%|6beW?4d>JoD)v|^)OFc{W z&~d%Yk#C3E(30d-JDd%uAFmZEAFpDG&+3+D)7fFRUJ#{98`71YL+8dJ2%-{Szqy&K46ykrEQqFWjBIydA@!T^-H9_*q;+8Lzn%*wOtMLZyy^RD?Vl+9 zBK`U6I#blq?`L{`c@t}^B_I-RdPZlnS&%G}^x$Q>;y5*chnAh8Vy&uq?9Ahb#n@!; zDgF_!MPn%|Dt>q z>$wdj%q+q*w_Q_zNtJeg{(*+R(Y&TSOK8WGn)m9-ziNqyO*cy^COVZZ4T}~KmZM!g zRu0didsL5-J^tenIO5QO3dCb{(^)E(AP`CU@&t5I13g}+9Gx1?<7+h0i!6w;jqSF4 zX1#ZOmNw{;T1OwTd%W@R>op5~-(X*qTHi;&1Vac6irS)?^Y@RU-QlfW?7FFgA zI(c#TBcUqFjtHbANw>>0eyfo)ubQz~#gciK>g&B+$JknqlqlZkx(g3$--OT9MII-O z(t3-ZSyCZCI{Ost$UlV@;oGl83p}vp$d6tapXJBPx_{L&eCDh9zqQvlZ40(Z5?9er zZ&1i)d$WYee)`GmS^p_oWSt-Xvhl0-b3~Miv{*5-K67$b?;@IBtt;K1FAsmHT?(D6 zVhQp?O7wk$E@OB?4qt7QQ-a#2VNcy@k*`gvo%4e9^(C_QkE<^S>%E5g{aUr>294q6 ziuq~_BPR>(aQM($zgBdJtrnu`#rH8|`Px;@wH|$@t5|~kP(peyyg@Wy{j#LmvC0fJ zTh1Z+&kSE1UA*1lt&iSr3mC^OPx31Z6bIq1b}oNwU0T`N_;zElrE0!Tw!5MAKSf8o z266WNjPk9CgLscxUQeIePO%{nO}c%53x0fgITn#5BJfu9v2k(Tb4Ps}n#R0QDc-Yu z8#c}4Alz6UY(A6v;zbQxEfL}0aliI3d?>5Z*g?1(H1;*8W~~3)hCnoBBI$?JxSdff zR2C6<@^(lr<}tigm0wbw9??i~UL3(zkW_fCE%$h`=d{eKwpt=0W?zQl-aUX#qrSp3 zZjF!^o^SisvLO&nC$fKPu(`=HTSihL0?(qkPgXQvEbsnHD!()z#`oH>DTKgUcust} z%)>k`#OoJg@Sc&ZQCx!ZhNQw%*zg-2%t1pt+G>f2VV9#Bvp?44ChlRjpfG(fwge&8{XFJQMzl~FGQfvV6|dkG~cwzLD<#i7AulE;ajY&mWXK7JyH96 zaTs@|HHf<Y>$gx{=+C60@1Xq&FIhlpFY&?Q17DdLyaS!Zmx%Z5Beq5t4Cw`na|C&puP@* zPHelNqy9Y1*H%kJIPHk$*X!7+d~PuTfjUamKBvZytxZxO_w7Co!PUE5|#xYtnclO)>^h!*u#m2)llmTl$ODWB~E;st0p zQTwE|EXC_LXv6B0RQqRKOs#vhx{XKCBY)}p&epU27ZGg0eytgOZDS5e75JrDYSqvx zwpxf5_0^z@ht$1iqS)*kA_6s>sC~LmX{2QCieQgOs-gwsJ)=_ow(-a#|K$;2?_~Qg zB1)XkP)>&iu=ZECnQj+(=jqtp#a0W^qQ3gMrv|%yQf8^d0}-g{i8N zP3(yWB2dGL`pRodIGZ~rUaNC+o9T;lSM!*XeQk8HmZ*J7tnI(85!RER(g zC+aIpk>*Off)U({S{^@phG*KOSQ`(lC2F5M!v?DpCq?rmzS~WaF~w3_FNw1u8b593 zk@I8Le-UwGP@-09R~UatJP?5zPSif%_Y~l-Ds|knY}af{n-Q!3R@KU1Dti zMMTvVjBnlO%*V>xP1P^gp|5?9w$(zksIT6y?a!05J<|5lcpw5boTz>FW{co;3%1b8 z?NAfZyS4XA@?%?Cvnm@F%Y&mHq=sMk+s32Ui7NW$8MSTyMZ~V> z`?Ruehp_qU7Rzxjx}~O&h1M!NqEUBA(xFa=)XPp$tUd8S1Zq3fL}Y<1*hnc}Ac75~ zzB;^iu4j9{N;V$*8&vTK3@vZ_FCxk{&QLbr=+Dk4EtVhO&ta}S&DmB9(Wtv9cF?N^ z%hpzA9wZeaPYzuER*L=^M*5X`FL%nbp!_mnmh0A zYom*`P!m!10A)ag?99n06T)Y419SbN(Kf_Q*KXz^O+#(}MZ}VoF04)ECcGs{HQqb7 z`DV@-TP;MR?vkWQE>DyXJ^c9y;(-X%U8t2LsmzRKO6I_^yfN{ZuxhdApzZNC9#{)C z5qYpK2dg!1MDb^(m&heuDyAl+O|c<9-0J30(md7nUqsBwo~XqX3F8?g6(Ue~p(dip zexCw-_uS5WCrLG9L}|U&>xnkHTK`k2Qed3zzlc~!cjx_dcec;AL@xNRhyJm7gsm2$ zQFqaM83p_Em_ZM<&cp)|sJl=Tk=3B*SROQ`xmNPrV!6w^LHds?zBV40KKkm?-NCm1 zB7#+j=AWMAR+kl6Dj-nXiQ4DNl?Z+_Z+<0u&Py3}6lx#Q2RSL{2!8$eY{k9Pc|pTr zzN?4`Cxpw1*-EuP5SUYoXqqKjATPP^w6bg7OMwUKNA$5uQm6M__}lXKZ0^zXf=)#5 ztB9yah-ww=S>PWC%w9z_MTM&?BJpdfd^_)(Tlvdt~)o+b!8rr=`z;Bj8idZ zbnyHxT*}DH%3psiV+qnlO7!OPH3wcaUwif_+XI0Idcegj)6ba>{GfAtcG=^Gup3}T zCZetHq?Y8VcCA_dhv_nwpd`36NRp+)dhJ7@5Vm~DLxBf+@-feozVkC|y;j&1!Wg?Q z>>rq4iD>$YQtN$Mq|*>~G5EfWB`68*M3iH4oU3~Wk7K?KZwNea#}VThT#x&yJO3TW zvQeZHmSFCq$ipXZZ#AQAGT` z&x*rIUzR@qnSj8E6wLXf7v-vdq3=`qu^HR02)i@Jtst6SZyk3}8D6SC8|rsY#u98f z?(_7P#kqPc_r-dw{E_DZk0Ow@huL)$50||@J5ImNcdiL10F28)GrvEFuHl(o69%6Lw|s343MBCr1PZfw`9+{|gvV;M`3E>fcJR1*)E zJYSTpfAGK@EaXSI$T{n?5!vdq;%V0e9vFp${OGO8un}zh=^4tGxLZOy@KhtlMzz{M zie+R5D9tU;g?u%PrV`t6F2`v0r0xJ^`K&9#X$kYAL>^C?N3mSDk2G;wktrbXOBJEd!vsO3ltV+X}{{PVshdpD>tU+R@9NQEa^F-yp9S}xZ0 zybnKc=%R4m#YjmJabij?R`!AqFZ>4r^L!9ZtG35uWy17+{QUGs0uMYbi?N(9YQ-tr zqet>C9WDuHYRsq+^KlZ|=3+lWeE7zBZ)Ge&y2y{d>HRTQ2`V#^kL&YV#*;T@qKGl6 zmk;}=Y*-w{dwsqnATaX<(G)ZBqN#FX`53+}Pr8uvgOVU`+SN4wl%Ro8Jm-uI;iQi_ zA7X6n+As4obH6ZN#P61Xzp?C_k5; zcH)2KN*8$GjYW)gJ~=-h4>;eM*CeU11f!!x9<^uZ<6n+<=A(M03->6@l|V}LEz@}l z*R^WgeZ>s{fj1w3)HBKg1NrpT7c`frS7oG&c>yAi<0m6{^Poan^T4M90wdxv zQeKk$9U^&|xrH>R$jid*4x{`LO}WVNWB9at&9r$L_hc+V3Grr0Uu%9H!7D}=(&AIo zg!>@o0w6!KOpK1=8xwM??TcLzvImeZ-YjVZsjrT$x}Y_nzQPt_U!jB)Yd~XOmd1Q0 zjX911j=4A)qd9JJ#*)q_cfVK>@2T;`gyDoe(Sy%>;g$3;wXkkH%4)GvM zQ7^I-Ig_Obtu<&VLdz7rEplia&vAC4Jh10o;blD3SEBauARAey$GO#+WFtdc7}i4F zMbU<2hwDyuxQb+lLwg%q)kH*Zvh@ukTc6d+i3rqcqP|){_QV5ZPqZU@BH9hnIw&Fv zk}k9|+WHqP`k(Ay{=K+v@_dy`qg3EvX{Hne4mI z$-e7JJP?6eP1IN2$c8NS^yg->)}j>{Yl-^mFxjcAk)8SmAZ z5NPv8w5Z`Y+1tC4y?yK-2-Iq#zA8vI{RgX#Ht9+&N2@&667|(C@*AX+-{3s?4bVS; zUH}oXkbD!}$v5FnJP?6eP1INQ$^TK9{2#-q9q7TpTB5!>(I`XF$;UF7d@SfoL63=u z=tF*-zsQfnNGkN#AX?OL`8pp`FOjdvpQJ(rYBf<`^(B8)P4Y**q`pGG6MC0K#4_@E zrIF8T6!Adc7NSKBCzD?-d$V$^8~N1`fm%(}S2M_W*NuF4`$;PF(V-_!L|FZUAILwL zbJJo$`yg7>aB1X&w0PO6`^X20zDCqtsEO!IO@7Y5$wo6v`io@xH%w^CZcm9#bpFiTt-ofXTbOijIt0BzhgfVC~^Q1 zsJl=rNm8-o8teqcm!y$Y7$JhSP!n0-D$Y=nD2C-Fw#jxoT2!urWAh_OCyNd z2hpgz$ZtR~Ub!3Csjn!;3lXS&Frt-C`V>d@j^fCgQXCm-AB;Q`5s4J5)`()&A}Ll4 z5vYAIhK*kMqjYa@z#MeT!;vLd1>#nwKe*xDx65ri08 z)I=C_OSW)|-%XYJrd^>z9t-AXi25qM z|6Of7<+0?aJQmEmISY9#sO`w!UZ{-bPWdZ^r!N-5O=QxCNr<)!8iXSpf2ulTEY6*D9;<51La)~v>= zl-0PAvKldm6SEpceYKDBId@P#XJ^Xi#9UO&=R|EMNyl!rWm146t3r9Hm{W^+siKB! zK>4-4lwW&>@@p}J81rjIeYKA=i?2~;@d3&##*AgmEEe?@Yd=>0D>vzP%BjZ8Ys{%e zZAb5(x9+C>eQ68}q1@j0q)K@c|8}lg2yst}{_xJ_? zX5OQ=qnDuR&4Cnpb0CA>9Kg2>@XY~HUwPBo7`mjSGJ)Psz?U2F?F3O@eMq%%@BNke z`t((TW~gwuo*uq^qOoJvOUvu4ZS?1JqK#?;KTrmbdu3O?KCuxWRA;q{Ib)cq)j5Zg z{-WGuBe2eMLL7ST#|wP@s=atrT1C33iI9>cWvVs#BCQGk(0hZ5v=A*K+71ig!A81P zYwl7Z2P=dH>W_zvGOGRjVF@T7rnepwW_-Ss&5QgWBmDTj(68DAzF0t@PW+VQt)F*_ zG6t0RMD6IB(w)C~m6P9Gwo%0rMSYHXKJEM{{rIR*BQSdoYKLq2G5qU=UYf<>0^wN~^dbw^x3@s!VA&jGA z_|YofS~+dCiX~+`#^^Qs_p{Z)j4_HFcszucy|+)Ro3va-?ubTyl5~f7T&(P^RU{rr z*EKXo|4{P(;<3GYG=KZJq`=k|Lh2ew|NB3-O??cGHEZvKwOk#E*nQjHw=r>*Oc#OI5o}bh5SgjJ4f?5{xK=7I;jLeM`HAcdN-rthMZnbQ89X`+|7vUl9Spox867|eGgU_|FGAv1f>#rys=P} zY=vfOo`J%t$UQEK8oBV29qxj*{vijxeK7og~9II;;eT-F>TwchJ zUShiy#fN@vtlpzHAduEj-&p-tULV_RM>ORq&Kt{vJDQbTpAv=lWClH+sCRzvZB%`m z&Fg8dar#)d*2W&UAEX(2EFQ-v2HchR*Ip;+U7Rt9rmv+bkvwQnNhQ#X8SB3FvMHVYbH)g6R@1-%J`k)nF#)Pe(Ey$0&uj_+&p{geo zugeRBmLp>DwxRlzeilPsW7Ua1u>st@Z@RMb;ZhY#aK93H6j%_ze-2AmOv~q~xmJ4X zwI~`!4dMQ~3MxA9esjI)9(OoeD2fedg zU*1P=)kZdW>|2s*d5&P7rNF<7HQ$N^r~-a8C^#`vW!?)QUB~;(Rw*UaevYz5;}l z=q9YS<&OtAvd{Bkg_8{SblZC#`j1ZajQLfb5sy_HtoD*>EMMoPDwd#BI5xDaWxUj$ zM)zR>PoArIrYe5=N$TU)RSeewX_h77>8Y_NoQ%0&?hub@ZNF+m$M~|I0S{Fy!FPj@ z66Gki&%@8Ac4NsmR;uhy9zDlj)r_=*cP+>R&vx{kpW?3kR8k`*Jy@+`|6sq3=vzj2 z>{i3LJp4XMwe(0?zItE_=D2d3iY3SoDUmJ-r5Lg>7Tl@Tm@sC<4uw(@1E^ijeEmb+X6k+H8WCD)9zI= zI{V+YAOc@*lB9pKz0@ME_F)zJKUA?tv8R!eBt6{zRqKDjmmLc{CP;;75wZC4aCw-= zD7Myhg4SY9r^b3*IpfBW>lQr2<2y`}lvc5W_G4KniyIW9VF{kwS9W}VsOI}}hF<;# zwcP%F4=wll;q1WEP;Eoo4yhH-mp2++y~{#?MtZEOT`g#B4=L z4q;_0d1_dKJdiiNO%+j`^={pco$7o-c>gN<&3`?w#{O;i4oSC|HxxCmUh8bE%acJo zYOHi*amVO=s)T+j-pTQ<-fKX*=f9_&jK|-sePvhQk^QXSmVJ4tsz?`K$wEpL!xEW| zZT-}PT^svQMOug!5!L6cQ&Pi1S?!D@ixfs`bvT|Y;*CbTX4;k{b0OrTV=)>kyQ z?O)S)VA}_eeQnELjB#WSBHO5G(SMtrn!6asiaxa9yIN@1Ano&|Evpbgh)Hc!EI~^M zQlfXAPdc%oB`hqs?MxN9V=Y9}9VfCO+g7qRQyM)JqzdWkY<9loVw_75C6uHnH^wT3 z(z~W*535*fMhn?|e_&nXc<-k|o5;H~a{wFM^`=s6&nDsJuc^m-n`{4TGOn55TAbNH zbI&)-sB`E&jd>fgd_*7ptc3Pc1w{DZ_U0}j4UPIsURV%Ki0N&aTXjd);eL`}Tf*M0 zyr+$M&^9;2>9h3=C*2QaE-RB1r#i({q>C?#p=F9r$Qhw*4k11h0!z@Ag_P)fkk8w) zrJG8yEd`TQOO0SvhnV_6(`@#DwZG*wCK?rDRraS zxS#J#dCQX30A4M_T9qD*H+Nsy&R7*I(Os>KV>IjZ;GLmOX&7AQnfljj@WV&*av-n)$b-U_r%L^WT+yj3VW7c_AgzqAGnQ zrnX7Fw~AgW1X_p|5l;S5?DcB1dgabJfk(+tG3NETeTzkT1mT zQ1KPHkztd~nLj%lm(4l6j#rH_=Zo!X9QbIp$&{wvb$pc7yNJNv#eO4icv2)QSv{9R zpKcPyBdx(C^Msg=My6|aFQi1@CA&3_l^(9iDFJ&`tc6mEh$_{i*~ig0Qu>xlR8d~+ zD-p53`Z(5>bZ!~@{2C&zZ;dhUTH4LXo{-ZE(d21(HIDIK?bQZ(U#eIOdsjqM3J+)c z|F%Ss3T^Mmn@&rG!r9@PQ#6;dab&#=G*>W> zG8WYRX~7rw(7sQ4w{mwjqE2ppFKwxcwGdtIn74UyttjJ(y;U=WH0#Q8FR3Jpy@32A$!l3xcIdP{pS2)Rt+uD0Ir~n^UY_w%c%u(J z8x&=+-I+BxqVN;_=BxOUAELd#S2oWsJK0FAZ?y>LrdI^}&?|zMoENBAg0KA{CGs?k zZ_4h)Rpc&Z*9ktBW-Z#Ai@l06idFk)$#=b;IcV!dWB&Y?#G_FS6Vozl@W%zYiX|u& z_8WaI?R9t7;ZRP#GuJ-?5A12=M{k%Gd9Rc!--oYRvRXy|P=k(7J^$VmXY9F>VR@Ny z&vU`OIAcN=>-p;Qh;*fNfdH=9>nfI@Zwe{V{XDz%Q?nhpL%jonKPupAF>{{C7~}KT z#}?#A7RckyY{zDW8`T#G2<&M@OH$8$>B`(z0sMW$2KD)_6`m7=rx-)_qzSJRqQ^{< z>PN*X>X>l8r9vO!r9wpao*v+Nxa3shLn-Syamese%E{I3{8#S--6;hTq&^dac0 zGW)YHuks>Q@ZDj*RVsDIGc9|(QPIxYyCbq)QD%=E$cH%}Q?Uf4!k(s`)1{R1ba(_W zzwDv#QXzU2+xKws=$$^*7~b+0@o2H<(1EAP(R@#9Pt~{8tj0rcO*Qs*yk)_+4e`xG zTIaW_Dl?ai^F++ud_hT96FBgHhoeNfwCi-P8s#)DAOv8;AL_ff>by*C?Vxk-z}y6yLv3& zwX*Y-SDZ#8g|=)ZziJeR+0wW7t=;P9m^+_&Zl9?z@_nr+^$SDy7aweK}z)U z@PT$IM|MW@Tko0R6ULrKG`&HWt+e*==2$+$E|-QS$Pc~C^bLgv^AEhC5j;U7h$T3J z$d7W7*(Ghy$$`9$<+O@#F;?xoBDKSiDTcBm&GL2W_0$6uC`tK~Hfg;#59L$t*lSozkPtll zlof9&%g66+!AD))qoPmn{fQ#_xP39kw84)pA!m!|PV~RWkjErdfuDcz!gpI!u8b-m zqFNTv^@6cR$5oFk&jSnSq4{GCp7e+ip~FjYhfA$^@uUMPmLL!0P50V&W%;Q(E%@0D zyH(^~zkCV3aK9L%s{0d*i1_)S1n=+HmKP1w1*s06$)nfl8*7wKe`rAoX?=8c;65kY z^UwmP1;pqoIdzX+vBuG|4=q#Xd28edG; zymOJ|dA2IVW#B9swe()a#n(r%hw?~e`sVp6-jVS(i8ofV))pSh7T?;dbT_S5(E@?D zV!TI7(&g`MS-Y7f*vLmoDq1}7c8@j(Nit3Rn`Q6k$#(0jRkVeneFm*Yq(vj%Dy_cu zVKv(fRncyU7AUk#(aWmYrYeQ^hp{Cd#Wb|Bq7@JAe%9}8=T}pMi#f2{kpbZ%< zo^&oL-$|QQY9#A*tDS~+W3(rWHhsTFU$qK>zU=3{XM&Ffy$OuuEAF=JaB;!-G-4B7=u7Bp7;#m zq4`s^3e^^=7~_Gp5KS{NqZ_Z$Bo9}sEKxDK1!FNVMuUt|?W4IKJ5L>5th$NT!GAFf zCCkR>BLeyvThj7)CEttHKQ!)U9H?wZx6~>L(R^5iAhlWbpcE{LPmR^b1a>o8xaYRs zo&TdmaeaNFd1Rg`>d3JxOh|Y4#aMk8(JeOF?hhVs-$n6^e<;Rs%LW+{g`dUf-h|k4 zFOL_ZC8@GsG|$_kiJGr#4;3XrZ@4Jcr@>?So9*6O*UHOJ}OsCTz! zhw6o?mizsJUhhAL=(E#(jib{GdSz}1&^K1>W%Qj}hwGa-_bJ5U*e6_v&zdoE|{`rzcz6@p@J$ zZ|-nK&HZ?#g0-+sC?Q25%?{$v6YWxJ<~^fe$(A~yx=eIO%qZxEl*m7LB8)pyUo9^% zS3&OBSICdPOq$<~_x|vYX5XZO(DH4Uo9fev$Kvp!UV&fQ=_TlY==mblj^v{)d30t? zEyn~$h9#9=_SUmE>1GrfSon|Lt-rGepGm!2l6n_wVeewE(rYl~O9~nS%X} zEyo_Ad;?m8_h}9OyKRGvvk%vxI1|+m;rz_NqVnOy7zNh>&O{OMDkPjYNSLZEOn=q{ zR}t32wMp%u+hgO?-de3SubSX`##)G`)9bc2{7(6erf=&@3cY(Kt(~5CX&0l&xguWk zTlngh#4g7DrG;rcJ`tkqoeid$guoK)X&fiYu36oaPxjqt>J*rR`CaI(M-i>GfWltG zIt;b(aLp*_g<~U0;S z?H@5gym;-6rV824C^*ho>sjAXdJ-Yx*A^f|5Pe12xUj+W_Qz=jOK?pfCE9W7hVZaq z8%_OBY!}uCBF6Yf>W_(s7p-7PnwoDU|FmVJ$>ro+F50(29z%Oy85;A68)PgwF`srd zl7x|NM@p2<@i3Y{8L-h5=(WOx`yJLAbw1WM-!|KJ=TncO`DvHUrbdnCrQkk@JN1lH zvHI1dE=B>#x}SR!;&sc7rZ#gH3;Q|J6%o(9qIvrpsV3L!bJW1CvHIT+x)@Ju=Jwj! zE>_PM-p%j{$mKPrORWBmcQXnGTO%{;hD7s#ZWT<8%EStY#a^+xOGa1Ye)n8ng<4V{ z*6e1i=xs&Z^^N9}Cr&Y4K0Qsv66Arr>8{o{n)^L zP4plt8A=G$CCP0SeR@z=qwJfaglPJg2mju9qbYx7XNI*ED9_Kg|V!Zx9_lJq3Tm6s$$dv9tvv=D0{ntVkb(R@^DPT79U z454@Ne1$ztBX~cWw}{_s`YUls3eF!K0}&BKvpq3vqp3j06(*d0ICpUs&`p?Dl;hfs zrmhFY6@_aaSC=F`qji2KFRiHjOu_YxwGd6whNOLbCvP+rIwNWyJPn{GqFk9eA-tyd zMpO9d?F#BXtc7T6v|$iGeRzYZ>rYYdA{sTSB(102V7#%>G;zQ)1@$>WT1tBq?ku>g;oc=lRd=@GDb+Wc64r|QAl5=OAzE+RyJ=l8&t-R9L3=COfY5eA zw~1v<_7);UW?m727AUkD(N{1^Rc=%zF_<@#k1JS$JdiiVElr%`)}MHE%X3^oiwD}1 zMT@ZVpmM{~>x22{oT5}{Z9$tXjmL+K2Dy`hxlvF=phX95i)4XxUDmipuV7wo&Lpu<$GQT?l@?VGrB?dZ-Z*lggx8x50p=aQPTmJDH#J*t6V_9vBwZTO zXs_GKVD4O9Y&qJ1uoon$@08+hwcJOouMiKFcwkln-fPiIO5ahOQP#cSieSFj^|;cbz+KPA zMhByR(-K}4_S8u&n9$CU=Qw)R8xxe;_Ha9+>u^WvtKAWC?zNT%^BbNbB3s@39tB<7 z897fndO3ZcaHw6ScEY4k3H!Gkpn0|Bn1Z#QwGa1f{j{C2xtF8YyA~}yb1rCS z?4Dsogy*@xfBo@bZVo;sNVO?vvS%)%y%BM{gcqXeYt5;1-KNoaV*o-&_1<>Gc24Y{=jxtSgm|6rxPo>{ zwAP7!HSevF4QG&4KMRWp9DmU|c<0=%y_MGl^YxC$6;U1+?PQ>2=ii`tF3dPEwiN zCz^j-2hcu)Gn7u2?)H1{5aP1^aqF$f{M$N!J2md}6u%o%bzfuBJ_AVmAfnv8LVD|| z9gQ)KihE6rE2cj>*U<LHg4vZbiO)G=c_e0YM7JPbT$Tjv!1UqKb=dSK!_>%k1IGwQNtl6vKpK^l{}OX z*9d_n*l)YqMw&kt?Pm;du--oo=lQzlGR@uOLgL&-U%KcGFVyYQPAB5gklKMW1O3jT zox0qzXAQUi6U>j76cOm*#nnaM47*f#?{nfYmu3mB9Q5`gZ+h)*jGbF~T2cFHMd6x2 zO)ajE-Fy7^<{`bCop|7^#`Pg0POG!sB1x*n)VpX;#C$c3xS*L>&13i9gs4S*h3f-t zmbg|Z3u4?Ew+l2LI*kX88lFFKtw_?275y8wBZN!Q;|i_=Jhvky@>+hl;-0pObYdlu z2hN!FPmiRQFV?}>u(<@yk_Q8GH(J_}^zMQa3hMCDoi2IUySFp89(MG?wIWHrj~yGz zG#<5RJdp0W*m7odPAB8=vSMDiR_Fzq$_3o-kW{@%DnvZE+|V3hbTKA%a`3{nLT@J& zJlpU+@i^;nT)|n5x*aJ|=F6=^d!A5Vb@^kqW9&ywi0Yv;+{?}G-?U)NiEo7t?sb?(+A1kN9{Ordp{_NdbR-BPJ{3(`J_2(-P4 zRyFz3#^gleAyGSUzT#|0O7w-*=Xuy8YXIg6JiVjAn9wod)L|?m>$t!mR z^AgvODX5WApNq33H7w`eXT)O;X$Cx5;7k+|9V(7<>raS+G=iutabAgIK0fp7-Yzst z!f2M@X&c8GPXlzXJrcjC8u9plbbWPPRm=DGu~0+=MNw?UL_sVB*?SM1b8G>zuv<(_ z6jV5<2sUDOcL%ndJ#e<7*xlXT?N#5kxj((n-0yq+$Ma#`)FQ+ik_vkYS0Ayh$RF3xkq~tVfhBlnNq>hseW!e@cj<`gguuSVTVSk-dT_z; zy$=boomv-r4fk^qQ7CBVp5uh5KqoTXA#p7c`@^u}$WBi}I8j^SSq=9nu|E!Z&)S`b z5C;i?a{?v7b~6}GbX!^H8jbcjw3eW@|7xp0Cme&pq3@Eqg{aThl{l*4X&Yt7QAs!S zMO^o05RbRS19use9p^tqZMFB06xVBI4t@ z0d>z1A|Le!u9heXN=Ps2w2otq;|)@^YcuuxE938*ExPeC{=V^YPf9d;S0mrrTl$R` z3y5RYh7XpWuUcSro|9;_FWyFD&vWUwYR2EUYFHC_x7CSb>3jA`HL5JMCT&PGcAi4E zn{QcnZ^qwuZ-}PYB`J z-y&NfWmO?W<|4YGCj?UMJw*tjO8+0ktgEA0_q-dW{oy`J-bV4p14QL}JFgiLzOe~L znfSeGW=}lk5hBik?v@CFRLD<66x}wQc_(g^ykn*-z3avso#;Ms)vdhdka&x+Gu1mQ zIiERrWSp@r@m@hzIfEgV5R*xdE+eNaNY#3^#n_an>dyE#qT1m>tVYL;(!;_j3Q{5Z zPVy*Y6XLzYPqzZhOX$O@UfCesd3jMuI6ly*TdMr8eF3IXbda z)PrXZXJ_tP1{!s{O0CQJ%`u0$ET@Y2vUdR+ zCHFHmn0a2)tP%Itsh~hLBe{XGCn4Or>WItk3S06cN@jaJ7?$AIJ=R3GwM#wOw?}oY z3o`s!#?`t;-O_N8&W5-<!CZc`!R2ZCCCqJqEq+=KlapbqMQ*?U62aV zC?VyorTn7VAJ?_+Jmk+%60BD|z1GcPVh(#ZN|Uq-3|kSk#eO3D2le0^nuCw12eGHH zKSV?+8YOMW9yOCj363}%$2dZ1rKZtdl&oZ*UtLsiR3jCl2|+XJ{=kh=Ak8R5;QYXu zM*coDYacAwD8wjep*@) zm}J{g`0e)t9`UUh0`bmY=Zjx5MX3Z{uxNlpU#dyrXP1yTi0NipQcG z$Ws=+aOMfA$yL>gIYdx)5m9Whh4<>d%HQ$v1*`L=1lz>JZM5~rbDB}AB|j2ud(XAe zPJGjOG}vz8-In`H3sO!Bnj<>>RDvygu`sPxnvR&QTDTIwMpBz+SW$MQVwnlHsDWYH zzFk?GAErLT=G1%9A(NXVVjGC9b#D;>PAQqg2Mt z3ASuYTWj)iokz0>3m@x0MylHPj-WZBmyJ!ZwQJZ$i-^z>&!$`W@*&qH&z)zjC_7T! z89`$qrHvNcPDj}7w(vbW3d@$^+=?Zb7YFm@(B0C_Snj;Nom4d_hk8I8Z!4IyrS|4j z4l_!1a7BXc&cN1M;vAjF0w)WfwQ8+&q|_Hdb3`{>HQv_rKugVetsddlyPbs>R?Enf zu3ojG>_`=tG~O06xRsV8R!7uGwD5ep`^iD%;f5vXTZuYRH2LiqzBgsQv?Q{WpvT$Q z<8AwcT4;+u=P*aMA8#As)Lh#?L+7!wIc44}5-uesR8z5JiX3n2)i+r4JeJ*zI#H&n z(y=`Ib|?Aa(Lw?bM3ne7&h~nKh{nfd*Lf_D<*sakT*LLf6}3gGZuiF7B91iIcGlAo zrH{w*_SbE4V&pz6mSFB3Yz2Bz=U6Ncx?__Ij201?hX>JgzPdepI)khx=$Jta^0jfQy59M7Koc z$E6M`%8pbyyLGXRO01_Y`A>FiY1r@2(trGpPL5qjmFK&l}80t zEWuX5nrK`t>A^pkH_9UhJyKoDcD9vE^41oX{%S%!p570)^;qVqWhUwU@n$mJYTvA< z)ETiuXe&ggMs={wEm%h@?5JzrrNRI{_0D|dK*}f;wMDAj!5wXD+xuxNFX|Zt+Fb9; z18N^p)VTLnEWs>C*a{TecfJ$ewfZ-;P*9NVXyq!Jr^hD~O0}|NcUyzq9@>W` z`Y6fXw;ONqGey2*c_nCm)vu>5{Yh1Ap5ePmM4TKK&il4$p$uwqNI)RJGA|n2qLzAT z&vw5j9(TTn^P4xfDWUxnRMZx!+IMSe`?#T&X3F`N5PqY(^OrjxE5Y(ZE0$nRCu{|> z_8kc2jZE2g5(+n_q&L_GHpaLb#o5#rGY~%`zu= zsHg{0VMZt#iJ#i=pJQ{gnbW^mkqR?HiHNtpMqa|lMcKKb9RC_#(YCR93GIg0TNCP$ zel^hc*Q8>a(`bE0z3kG6?`&;Qo;jBg+A7-?v+eB4;+px~N0W#szp^ygFzt2F0V{N5`S>upxCeUPeuY@6PJk#ZIMq z^J&G)C_d+Fb1b>`rJyZkKoMgSj>NkJg8jwAaN19*B6k=Uw_j`x4rz zntGp?{^ZR)nigeia-CDLeUPe>?Q8l+KXE5AA?-L>X*Rk{Ix8j|&n=vm;DAkkl`D{n)+H12s^m$%mV`)C1_BG`+uf&lG z(TgmZ=}kS{v<<0G2+?9(NuFznY$%tsrv83k0Yv~`aXV=~tUzxBb`YH;y=O*K8CGKi1p{cMO6*~+Wog62qt8Pf=1pN-$S z9>%-}F%_vWGn$CVw;)x0e{-O6xO+IgTsSuUd;7dv!QIaUZNn#~r$?+aXb&k5kHL^p z^{zTTdp4FDtO%`(=ohPoraSu<)^6?B<7@YyzpiexW9*lboujr$HF=gLy>s!B+NwZ3 z-ubP=c{Q|G4>oU7h>9hcQ4V#YTZ8mz>h?j=%Gq24xh11cdi?1;TKO8!OeodU<#W^f zjQeiO%k_*vQ4c7bdKUe7sg|R=Z5e!}iZ_AhZ=y zc|=x8PjxM%@d~=;XH(Xx6E8MoCmQ78s4Y^R+E_FFtxE}QM${cbOj)r)eV8zSZEe*_ z#S)Cc!&V?Ky`?ME#)$*if;J)oGrS?1BEuRsS9kXts#NkB#^051lYX<#XIn~%7bcIe z?`aRaeXyB#J~v&Taz5?$ncUj4n@>rqD?56tUJdiJ37O4=) zl(O7=1V`CFZ(EkudhC0fdB$^74g18j%j0ru@*!Q1U6mZwU)2k+q}w4JWk;&d)1%X7 zRdLb2Z_@RsBj-`20io=m?8H%aq_W=-pEj#raV_$suE*8E53J1|jbMG64_7f?AIdHw zMy7jO9XgFse$0vDf+V2Fh>7{ra`?WtjZM^d&cR7;)=bAS%KR-+97_r=vSW=xa%%}G zPyeO)mvVvD^1L8>)Gt)vfrw%=zbd_Rxo900=$cO}T+iy0y(McA_SQlp86XR0rB@dQ6%^9Pl zw~68%z8((vb?&{b<&x*7(rwlTR9==_vz&ZtLY?St>GfPWcy>V+lqZy92_j}RUl?GK zU9^xry5@F~Gvtm5E!cnrXO7w;RlA5)0gsy%*Ye!ZHD4SvO%BZ)%?yo)37HB}57dvm zare|x_^9DZ#^6YflAumEi&hP6a^jfNoqdrUOG=G&4}6o5N3(N# zCbRq6Rt*}5L)xJ62x1&!Dp zo|mKSNTq#@2yA<`gto#--*I~7PEh{pIEb0cMyaSFQekF9%IS1wj*_?8Kz6ZoR~1Vz z3L9&pRrF}O(mT41BA*WDC_A=7#FKr2JF*$H*M0T9cI@>_%C>Pi*u0rcK-leG9#}C) zKCNs0=cZ#(^8)V=ch!1#)K3{3>8tB{24mr2xj1TzR1>|H24?p!rS&SNpE6d~-J_K3 z(wm*^F-%2mkxI-pS@Zi7rB%g7%G&VG93|QPZhznpSA%98{L*ye=EcD2EwXE`-SqR- z)jUs?55*cOdwPfn)E3dy=RpQ`wd)t9;gGrlkEYKL2C8X}T7lcoO~-%k2)uBth?Xy} zezJ5A`L49fUzb(6_ESY|k*ZA5{ek%hme$t%&^7ljd{gP%z6*O~>ZhW%NQDvkbk}#p zj;VcXDdWGk;wTAf>y|5<(P539meTVz@$juuh;@_bRkk=!0ny<0qrgnp0$P=PFHKb< zZUk=aQ%uWAxfCgvg;sz~|5BCJT>MT&*^$a`<^8|{8D+IfJ01{XWoCBv&c7A=b)t`o zvLh8{!z9aSMF-}8FO=19_qkkJD5aOg-LJ9d70^0}Cv|jbD!Y)OhQ(WWA2t3AE^B6C96xMntyfU4e znZp>ov!v$kps$I;M^|DIlS;Dg#qO%uK1j9vvz_r+N_lP0VSQx?^>SmWJ?pdV-#V+< zK1hXm8w`e>sh(^=IXk6QHb0J%ptjB2J&g7T3TQXd^lxW}?f$Iu)`QBWRRsmag`*{n zt`5bt=Plou?!7K*{IsvE*0HEQ&wsV4$4b9#o2))6mSFBr%sD}xvP-M6nJzxeaadCoOHgyHi8R0C%Sv_0p;XG|#ZmSynI6Wk zbW?DEZVLV~cpB3-7u0$>==WDGZu+vL{c|W4bBYLTA4JnV+-5TyQ*?_mw6cT1qvMq_ z#tj#WY3rB0F}XRHF!t$IPHQ(%Z>uj`P3+jWTrB^oG!@$isS1B6MfprCYwjEMwrViL zhrQ3`$)q?%Xe*?`+@|!7;)wt@H~o@4+*FaHB&%xHF+SZ}Sex?KdsE?pfyUcqifLcl z={H5&3E`t%k|+HOf$f86S{d#Ju{&PNm291|2|QM;_AzEJQC6#!^S$ZKu$so!+be0k zE9f(-mtPP&n*2c-l53xe+9K8Ul-kDVsh(PyyZSdyrRpZO+)#?yzBEu#TcpCgCiE8F zxe#{x%|))lA0;(BITQO;q@+H@F725}?R(0rLR1JRGjs^N%_|@2M?9JkP%6+$Lg62piX46gK zz1XWB;c|%Kj*5~D>fOUwv{zNF&ZTdrb$j|59elhsTezNuw&Sz`Z1x~urT2!-0-{G! zFJtqLwY7SizL`qPJ&f1;`D)vb>20N!ieT4E%~XaIi&0T_qzXON!?-L+(!x*anwM(Q zmwkvoqzv6vR7Kg53bXi-_s-w}tiKd5cSuZEC(MmB=2gY2=c8Sl zqFZIg{OZq+k1HrQN;<3}6>2LYI{6P}*RQ%NLr2XL5Xf(l-7w?S1p(TN0zZhy^D9Hy z#L2ytE33P!s4Y?@6&+@rm|)VPmgp9f*e1hRo^Hv?$=!A;mSDzS%vnSklm-w?izcI zV4WH~lLMQ^35f8w(Z=RC0yN8oU#1yLqm1KYP1@GEdh4EhJc8vp<*$6*X;e{Lq%zKo zGF~p&Kzk9Qw^eQO*z$Q7r&Jr4L(m+lFxL}V;wTsEp)M1oUtN<_lmunJdTXq4%hiTj z`|`Slw`Kj2YS!}N2+!Q#~Ay)Y^J%r(c3C|*GQJXVjZQ)VmlROM=H!yMRuGTqgagwGo_Qo+p5ba z#T&2J3(+=w&TdAja*rHm{GQraTNtJ5(Vh@T|EeGjTGm!YD%4g)EdEaK$_Dh4x4-ca z5Xf(L^LS%wtLEB_-8zrWy<=GR!aHOssGy44BGr-F@kSmIs(l=)BT^D#nA5oTa&7k~ zR@4@$#9YM_f5xzSGp@;lUfi}K6=oq85r^8uu!RrL`o|BdCbU)L?RewlGQnB}zZ~Yh zcgGt83$)M@Ug*9C_QA1i_U9tM#{=e=x zsVE7`K5IaN@xbU-TJ`R_@5ihkv8;BLrzq(=x%>?`JD*aKoJDd@R9eH@3C5 zxSEcbT;0N!uPH7&E`4N0*^z36cY<+ljyBq^0y;uzV`2SThRA01j1^@^D$L$YXSk9U zmfb0z|IOTAtSAY}UhQ;(v0$w>n(464V;SYZ&SO7Wn%4QQfHEr^wGT-ohFOoRt>ZU$Ua?NVOq_^av#1^F=x$atFQPKDL^?|MWp2cQne5 zI+0)BbPH48<@WbFb;XL3pzPt<$UFW<8?DbToyXHn7IvaXBdN)aQvxE_j|AhTieZ}R zYfkgkuL;HxL&7w-_d259J_~btv_$ehaMX&jBh_un9qyDGroDKfBMu+4umR6LNlWjg zS~2f6=ED{>&m=_TiCX^4R%BRF5|sUA$wcE&`!H>*yY6#$;|#sWn$1hfKUEVD-HGaU zNSM~NTrTq&`rT}9nD(%Yj+k_gTK9aC)cbXs6=g@Nx}_71`)`D4v88oHsq+@raO@fB zIat^7k^KidM8Q+~fq)Yd$0-|lD zM59ZKFl`}GJ+GW-tWUn2X;}!%O$$pjPLrB;uv$@eq>8MXXdFzwoDZ@P=Pp_pV;Pc* znkwX>N1a5?eZE+jU#paf?w6HY}HKdS7DMI86N`+|hBYS0G zOMcCejFEe-$Q=VE@^*Sx?L(&&#Lk#iUy-= zFb5??LA%yS!kEg=je4U>Jj1)$0}?N^IyMpyA@jz zW0w$3cNv!~%*#7d`r0j3Xe*Rme664qjS}yU(Cf$*& zR-{5S&SpBj(#o)>hliByl2w==NQG+*S+MTY*v;41|82A?=z-dbi27$OZ2i6rX@RU- zaV0~kaFw7qVOkTrrp=Vrw@ni?M>MXk^pY8^)GzOtsw12F(uv@(p zslLM*VgEoX+=F$GMhh#Qw%z~7hf7x6$xwC?;knqtKIC+e>qKW-ai>SAa2KVljW8u;6`qOcX2RdXN-ZoXS?0aA;>iMK7ZHty zSy=3*5wg8^s_@bVo+k06Mqb4YY4!P4MV{5|rl2`e;c1YvEVUm+Eq zILT*XEuBR-w3EK2+N*fdL)k?{xd*YV$gI6`WcWcV%8n;}`~sj;pBl@iREw4SK6x#i zMUe_m=LUm^cP#Tem0zAx*hNLzkqW>!tZvvFKHFUn%F|*rW3}h_$`atiinYwMle=)oRT)+ zf{+Os?@Pqnk6s<3*qE}iqP(vwe4ir~-dNE2>e6s_bL>;Oc>8g}9RO0{9T45=j~>ca ze0t zL|>_shp>k83MiV-0^v>usqiL@yk5cvu|-4T<#$_ls(2TMH$|czcN_F$&8uc8*DpR2 z@@(U+Bi`td9Vg#Fwr0^xB_U>jin1dW-WnPVRj%}BEo%8HC#G!|Zq<+q?=s0I9MX#g zecL9VXmwk~`#scFM1(f%##VNHp*U`QU`5&S4jJ#3DH3T=Z?>k*Hl^Cfal)M?QsFHw zWnz2ZlgVS-E08Wr}jZ|nIpxg845Z3L5 zo${beL5?@(sI7?Dx~@KZW>=au53^TMcC_7~m4mz{6GPbMTOXCiQ#J{91EfMriovkO zxf%P`YnifVNKTHjBNbYN=yjC>j77SXQt}?Gz|l&AvWtj?`4u+ec12dXTPYP~N86of zi7WD~0UI5kgRL_jP*HZILR%PlC%iYZdr8}rfRp(+%8pcM(<95z!DgFuXxf;gtr=w(5hk+g zmm;hFl7_x2TJq6{0sR9g%YP+T<``F%Y5AWD)^Mak9|ZFEnOJ~zX!JxGx4k+?*^vr8 zBj}5zoPph`(?O}Mw&7^|N7+Tha`~-Np;AXSJ)@C|vZEIY`fC^rMS5muiMf4Poc9;O z0|KegCxmW_`h8b!mHet4`R>b6cBDez7TO0tTv0+(dMNjgcID{rfwGGTpPxsSXO>>< z!mt*?yRYaigdR5(`Lg<&;y#$Mv+mhB%8pd%)nhPZzB#KD9hrk2`4GTScBDdIBZ`pz zv{SjzaEP+0d>@YfHz>P^u$-Kuv?Wg`?{Zy*mtyhl3DMJOUjJ3fkO_@gSW+I2vLhAx zWs%QBvBk>Kk$KtdO^pP%FS0JVB`Xtm_f|UWA1HW*Rd)ysbO`@sGyZ&TLeDC) z0<>^fI(~>`kM=~X=#z$0p-yDAOm3!>^$cN2{Tw+`AsYSU42HE+jmr47PApOm7Cg_8 z3jO`a@AX@4<;S=frS$7zf?pr%A!=@8!{iAcqgY;3l;AaqQlbAH zpPSITk@97fDsJuGE1K2a6se+LC`u)If41IV-@5c#3$|*lGe;^!qpzyLP;$7x)$LkA zR=HEC;LC|r=yOXwxYg6@ULsD(*e?3kq8_5=WhUfQTdy9$M%NlF=z)H(=m|{UYO9>p zd^tkdqLxk^Wk(-j^fsn1`r7vD&H)8jBzZ2Q>_~+k&17Tgd)Hbk(V~>|GUK_rumAcA`Jg_~-I3LtW)O>ty zCmuDs8N2A&L&b;$J?$c%T7JKFGTPl0;8ZPyV#tPd?~%^>Hnh=N7<1I zBdur-RxQYXjIX3Tc^||vIt$~NM9t4Fb?1BQ%k-*MTNNX~Frp46B;Uck24IJp+U&I@C$jeCqo;e8a+O ztV=|Yicx= zRgApFSY(Xtr99hByYTT94l7aJ7pf>bQepfsMK3#aCRUbzpdCtS5Yx`8Y9b5LONMq?8C>cU!{z6nJ7drBLd^O z>4l2Y;e3lrXXV5bn-C$5R2Yj+Z%&@*#LssdBi~>1L&Z3A)JfF5+REO1LgAB2m4_}W zM!#c3KT1gN{B(-oNx`#}PLqbKSb_+Q$fxhxy#0BmUw|@k$4(()9jP!k0Of!%_TtOz z#>n%N?y8t60OROI%`2LQaP{?KWyOO$LY4x|&wv>VDC5cZA>7<*nDWH6mx{6@73Nf+ zECsIz@xDJRDz!3}2ssCk3iCFQ#biNW{-|dKId}gvD&~4XokY#uHjLnxM)p-sOmtE) zp9E&xKnV?o(s_W|2_i7Z1-;MNX#_vq>9y?YH(JOVfmC9KjSOn5PC@BX z#=5maP7c&b)co73(Oi3Kr`UPsP%$G2=1V~d>E37mXzo4on7nI92^C8afmuonhV*Bn z_+Q25$jS{#$l`%im+5d-T#Vkpf`3WVY z+mG3#xq4pm+;c|Aw}c4H+(bEq`dN65E#sw>&v%4eNJxb_qzs0GiiMY`wb1`W&DU1U zD1|zSnqNt?@D-=>$+0!9R+I#F!Yo(x%}JV<2;C)RxSSLanEwhhX_1HNBnv+?wZF7u z%@rXx6;feNFN5J;XA93?p^pE~ttbh~KJ9ISZMC7T zmU3J7Rg+2cQ}-50PW3Yc1m+{d%x2_4x6Q(@-7`x;TTTkO!jKActdUK4k%d1v>ErKF z_o5XuuAxq%=9y&)^&5=|YlqD^t zw)9vNbGIQC=Df@Dnc#I^HTSQ%`6jfWUlxnEB6OxJd|0*Q(OHqY3jdkip`1{2~j6e zb2mcFT6|dYZJ#RSfkdf9J(4Noq7V7|_Oei;$V`H0~__g7NK1C>qfK9#=6!-$w!fDBp7qKbk{!88^V|mTg+QKb%TZ77*f=F zBgG~o0(00R+F)qfc{mGvbjLc!mMBPtFJfR#lwl)d1oMc#B9)prL68a&V#fEvxuaOU zhKcIT9!2$cktqhNyQU7#WyX3jYretob-*b0aC@kFw{Knx+sZ=NJ$>S zzO_$O5C0e0{*9Tk#aUa&Hj@3w$ds-$@1h=DI@Z|dZ2>J;N_O+-Di$NXRci|j z%whh1bZpjdzeD;-W?P?Fwyu~(+CR)$#gf4T6O1v0zM9w0j5QeyeQI}ME!H{8W!%20 zYR;j?V4~`7_+{E@4Kr4v-_h=0O;7r@%HlEVww_UL-L-biG~ki6CcutkNy%M(v#5@H z|1x1s6d~;x!QPjCC*|3nCh+K(5s`&h<7+TqE;K6Zw|z-H9%s?)q3q4PwNf6_Diupm zc9BQqSQEQy@RYwjEzePQ&lYuzcBIE%`wylg0X|tg9HaF}y%Wg+>~eW`xpCLZ97`tO zYmr6uX!Ag_!R0>0dlTPXzHjpYqFne-+{WhXQT7 zBwf~jG}TY;X46~OF7J0!xqQuRdT$nv{7Oxz{$S>XY$m$k2G3K1xoW$ziVccuW?eiAzp%$@mdjziSTDBf~D+EWFhFWzw;F zhpmX{U2bd^)rl@S1vJG+RgK~`6Sqlgu8mi*t_8QEZHd| z^zdAqU>iY_T=C3p?nv2G^%i|`#LkR5kyr7XIPUOsp)??&ri6$kFaJgipCzIVhT`vI z`GZXhrEEuj$q$x~v+1*_t_Cz{fJ(_tKh6g4SkMYJL=Hu5R0(Cu(Ww@H#Y`z$v{~p{#e;aUhzT8S& zo`KS=)L4ckWoP6M(9!R96ft8>lr_6%AwICf4e9ps=B#m<{I*F%l~|#$d3aKuEU8@1 z7BWBVT{G+VppW|71Nmw-Vn7%H{pY!`lDNIjQ=NIEG`% zw6Rdu=sTelF{6a^McDYp^%w3Et-Y4uT_Y6q-R^J1bdB@zLpy*%qT?PX>ue`m#S$6{SCLnO|mol3aS*_ zsH4E6l;@Q!s@@k1n?*$65P$ai>=Q|<<0WYBvt7=TZbz?Z%k!k_F7(+LAm4jGHyh(cL>c+4H z-!#FR$ckLXmtFt%%|G-?4M7il!3Ez?A$zU8iS21nTvAVpud5(Gl#t$0wC~LlYP6Cn z47j1-$UsT(6%>P^c~T#C!{*G+HmiPYSj%OFzDh6H#!kQ?9 z!2aPZVL=h8Z2WXVDtxa9UqPWvh3%u+Vb8A8*lf|lD@r(yMX6ftk7G%%J4sz>wBy)C zg!uAF?8DK_IU$EsBEm7!nbt*Rkx=%{VFdd4mvFgt0jyVopj7 zyOGjTGK9Jd5j+_AA|m1=V%gYNC8YQf&cgQ~_8PvMV=#>Nj$?%%@08BWT`at)gKZ`9 z2pKVeonBE^F66EWJTPto<0&ZDWZ)*4-69!7|nB4$Yrs9(QvlCV-KmEU$PJ@ zgYhP!R1u?wupC3kGi~AqAu0u>5)s+G+Orp>>&rgva&i1p#CQXYLm+ELa9P~U^+4J@;jIvxfjp2mMOwU3*aW9E`O~?|!dEJK;EVZ|u3T%) z5@+m{IxNg5AW(LUL!j8c;|}KW$TUByd9z2idP{dx{DkjXlmvb2 z=>+i7fgQd&K#srBns-}RC~Kz=v3oD%QWLYJ^}h2%IZ(B8E8^658tX$nYRb^j3g~(m3GRG41r^lKox@LD7_Uu@9x%{C9 zg4aEIu8WBFJLv^X|0#0MTm87>-kVux!wW6m2$=)LoPeSCw=19H=E-$p2XQPhXY9#B zrw({+!kXy4JMER?RcorO9qGogeb5gbeYwdGU}!$(957NY7S&onU`r#Kax_*htZcrv zRW8>uh8v4d&5~sG;8!N}-^F~L6ie1lQA$`=$OR9K5UVr$d32P#MhJweG z9d+i&ZASIus4cbv`f}6$QF@IMeQCa2W5y7{%NsqSu_p31yfREl*}7e>vMx%<%ZYl3 zh$(|Q$|pN4lk<`tWY_F#S>H9KBVGz#zUVbeJmR)WE9S44R~C%pSTb~qOPc-#QM%Pj z6V^oMl3t3kF#7^I{nRLd2ey^yRXqHTi?XQRO8NO1dTAY66#GC#oQ__sE-Kqr-rRMV zkVklZkHP7>R71Y}#JwOr1e62q}xT z5mA0kRkhKLrE=u_(SqjalZvfCuca;7s#+>6l4sl+#GgL8lGP>;Om9r+{fQow^o~h` z#p?TRv*hZo!+4BuW){N3_S%H?qCYHUH@@{uZBetayt_;fAu~7f!!^kz^5!PYSa5UZrpnldQGC|A>|!h`Ai+-KT%G7*qzr` z9I_By0^gZXD)b|zh>?D7ytd*ew_Myz$SRNguqJA&9@o`A5$mKJWj|EvCT?@`ToE(fnHMEmg{O(+$M`We;CJqOxhw1yuTn7OZse0 zv{ii2T6>heGR+ZSO1!u?jfZ8ITe_s(lZGKBoNVM*t+U9wvDRxjs& z**~0T^y5RjzxSW$a8hWiXWgP~YpLFeYaGo1E<>{Ve85zl$MYFIc+E1^rS5~DDOiI1 zP(r!`I2FhjrFW8c_*N3E8K~3ATftd+6gXXgczliW=Y6^sl@2ubVp!5N&fnILM#;bu zE@rf(P%^81&3KilY|@eKZh}>2PNPmX6Cv&|ayDa4l&5I;H?`7_V)DuYT?DDdO(0WBlam{42{ZWwfX#Ac}OaXKPM8{5)OEW1G=?Ues>K z`sw%WWpkI}bHXc1kGeNzSb{u6JvO$RuYR3YO^)-36s% za({(rhY#p>gUgpbtK+_Z^mjLO6%Z)9L*T9S7t5M!E!*peR|PXw-(S0>{GIwUEI}S< zp`j>7}Wk6bgX%|^7(K?Birs$UE1M>O?Yg-TLJSGk=sLYwzT)NgamSM^JMvVh=&JEUf zP5ZZ_G z2yFT^SlirDmumE^3CgR=Yo+z4MldYdlygsDE-geGeZ$p^mL|&9^Tdt~y5}KzPix1} zy3jB>oALgQ&!sd1Z-HflRwA4ml*DY9)1+p=>FGu`0xpWc`SZ{mBJAw7I=33AC z`na0>?Ywf(?~c^`MIVMG$OC!P_s8pEY>*|l#E&#($Q>;kB4R?zbIRJq8UA~F^<}6n z@GiW5@ zsK$|q3ht@6e~7!mBicFp zRru*2U5F`oX26|O+y}ip;`oY8x^*tM+KRhAo(9B|%uzaDO*EI4@*ejPVjA##B_j4` z4(7G4he-<#ZV{qV@Z^mra|S9o)S zH#!ExxB@#AFW-Lh(ey#W?I7Ny;SC#|+wcESyynNsu4*UYUKH;y#XHOL@5{24c{$avq1_poG@nd-?t?2D7H#`_DoUhu9LZ-?nDy3xd@ZS#|IJ67O$n~hZBU3grR zF6`s*_0s1W--J9xNG0CsZ(lT&h5hI(oo~2G$TWpiqHQ9KEGCbwwWP8G!c?^Opv6Q) zly4cwnv5wZjT}GAiuO9R_MjDrc22TEdXf#Y&Hx|5&WSci(W01eW)O>xb(FkIq$p^k zMO&(98SO>(+JR)RJx%snv`(YF7VX0Z!{^eztP5GHn_R8I&@PXbYSHejdqCVH4~RPC z0f8O@=m8<>QI`BmPRb{xAi7*azXkL!5v5A3*NY99uuGb{>Av7IfoM_lRpc!)>r;lb zyg^67lLNg_#GNxw*O5wD^6@%EK3?cYf<9j2KKO)qIFd(7AM!}SdeI|A+-nWwk#dVX zQpS@<3i{ljM~c|G<7+2cV@qw5%Jz(7=+}e0rMTB_uT_XIB|kEm{K(L!2>r-#Po$TD zwyse(kl)ft@>@b5DD+#xeV6iClINL`JkOHJ^9+5t(DO{(2UpG-#v2`7BrP>AQP5uu zcQSDwEKiRfu~n>O?o&W#f3}(?t|+xY~-oj<~-fnqF8X4^!Kk z5^^Q-FhxI0^e`27&W_~E*@%2OP2|go-k<2pDelf2%J}g&QT64%-Mu;bx8iPzyC|KI zkF{fup18>8>)CPiz(o&ZT!U$pkax7*kxc0qc}Js07CeR`jPvza??qHDvu8!}R~KMX@*0cl2+1ih24U1bVR|T0~$U zVBetkuZX}=f)e6b5D~ZzqE8vF!6E|dMSiH0h(PYB6QV@~N`<2YN6&vFum`bcMFeVy z2;?mw#^A{dS2$exvJhkbug}L|PocKh3IY!U?jL9wLmQib7=vwszV832hXG4)e&DJ>R2lBu#A}%h%vv%F3ucWcmD@L zu>YMOc(TOVCGx;IfivpA=Le2zoF6!*vv~ZG3dbmp_WwkT!4ZdJ7e}bb1IG`J#Q#R% z8jicce~%JeUvZ_zu^_fCuAI2;{!b5%`Q3xKl3@@2cYolTfveAdw=T|3oag`DR#<}C zir#I1_sHKP5oZy$D5Aw4#5O_MaW4@NV{k>r_Cd6OFrd7+`k;Oy0_8<2oby?TF~55d zcQ2F#B@}p!!P5)!!*&x9cq+nnLkR_h0aqNPLNw(<3Z1>T{q(`SYUyq2s-3B83ocI5 z<}F-jlr7u%Ujfs#S6jCl7kG6}JM%tCd)9fA(O{??v2D*KLd2KYreev5bunr4W0SP4 zP1hQ+Cb~UuJ7LdOLWGsvrXtnFC*{*t7EaPCU0m@m#5_~N-p7O}MLdw|>BIhO=e(Gv zy)Ll)Ux@D^33Y!Xkc!X&|9>8jCr$AAEfrFcgaQA5JxFt(-%YL`6h&Z;%t8O1cTq(6pMXH=`71qscI$cxTxBW}=%uQZnaYIuJN7QjOugGbyF5k*R0lU)aP3} zO_V3Q$vkOqRgU!{KSa|=oL7{6xNyrFzP>5t`5BUyns2&Ra^WT;@^k2Rn6FNru05-# z^YCmPuk;`*@2~T29LE*%Lo~h0exxt6J(;IAr}sGZ*FP@~`t+&F6{M-vC zr9Ie{q}@BdhIssP+o2@d4dhLq8icWnBOlRp-`;(t!n#!CmCt%Jw+UU=j(RmstJ{2; z5&5N!^h^6h@37v^SWY}X-gHo0d&lzSEy~FM8ts2(6rxG<9xK&%?JDvE7rp7Vm|6k9 z^+0~Z0@|-VQXom|etaqM*tFk4?bkP!?_69;#`%H#5KWQAGlO{QrtI7;c8Nk72K??1 zH?&@+{8G4db$Q@S$MAQ9M+jzAf&D!QPYf(ewhZ53#61DC< zS{Wu&>tZV+KSYxSt3{^Tm}c#dhw1t}|1++TAGS0_2_5Onr_svL$ZonSj0Wg6L{oHs zu^s9t8j0DS8B`o`$PY&hy#+BVh_9!Wp%|?UII58!qA4H1QwKF8JeHTQUPi{5gZyyh zQ&yF(D^(M%4C82Jz}boX5KXa`M;(-BePVeu%~~q?vtA)ToWT@5K&wyr_7(XHS{ZPa zL4JrPyK~VU%3*4&pEPSp!$0dT@*_R|tV9&sH#3NBqLtxJ%n}7xOXP=W@-{KQpXYz}59Eg{DrL0J=*tego~O3WGhM}1ANe7gGTny9D}T|fU2)Y-*awjx?hIsu zoLiK2qLpDeja^~)f?WpDlqtQ>M7br++N=Ak{(GMP*>`b=qxiwY?#ejVUe;KegE;Sy zAI*>RwE*?roYdLBhK2fb<5fbJP6Hxqp>E6 zaGOw`Z5bY;B=7LkXYHRo6?uq=?PT-%P`tKW;Y>As4*s)40{Zx;(P@!VvUaWDM%r%fA%7zBFzK-(L86$0rgenLdAQ0H(}kanf(@9>z=G>jkX%+9X`swP|sc;u$A=a znpv5Lc8F4D)b|lqQLGoyw8D9o=auF*QQVKp980JN|Jh|=ebis`*sflCxJc=ARbH>T|C5d1>l%Y#*e;)sC`8P!C?D9&AoMh<$)mxOP!= z0gaNg|JUa@8nDkrgiIsx^*>Vm8F7fl5lT60XtcllNAo|U8pkV+V~RMOSe{iK8KeBz z?kCJzVNSqYp%GwmN955&K{0 zC&OQ!1-K6@#{1fw_$T`(tV%?(Cet?{qJ7`T26XG5tSzgc&)Sw_o2f-sNAa#FORIYt zePN?$b`~;jGa`EH!tnuhEXmr0PC8;l*l1pR`)6yp7ll=<3njs^Kqs%B$TJ7M4#N+bp?$$heBYBavvy`SCS_V{ko~&)@ zvDk=cmsMjnB^qXE1#;?$6)zVnk(++1URsDQRoZV2v0hQCLFNXErDsF_dQVY?bs++4 zq7y*9_VRfeFiIyjI`fl6cJbxMI7d9s5tE&#f=fY z^wFO7d$gm3SQD+HtE#Z&^bIm8$e*XXW$=N`lC?vTTa8$+uo4-9HsoN{ZhG=NPIjDT zQQGhMj0miW&h2%}Dc81-;(1zUQ!N=cc_CUEoSezr6nW^FQQ3?08mUeBhgzrkwgJi7%S&60NQLOXdED+F&2Kl4QV~JF*>CiwGY9JY zmi8aSoxc%(s7NRFn@U6+E2*gyb1zRVv|@m;?xG~PqtfYhq*YxtXI<*dLlJs^{LvO$ zK}4Lmx>PMur7Zu@!AIBpk5q`pRh#yxm}Ay*gGO@muV58dXI!;AO}fKMQ9mv2tKZ3Z zS2$zsA2yPg?iQkA3G&05DE@qInl*RZk^HaxEd>O&6{2YlE?lIJe^r(@>gpr371k>v z`oteq1ANY<9v$9aIG5nACTdQ7IOY!Z`CaNk>?s_T#N*HC`Mb|Y|KGU67DY+^7vV=^ z*PF&JA^yxL>cKxJa_mjI%b3|j+1V?KH!f0H#d(1BqJ-qpI5QtR9_Yp+niLjzAOdTm zR~MdCV>4IvPko|F9OpAih0;>2rSDip-#J^-&WURV){8UPU~s-3$mFUO`S-T7t+*N> z0&B`T0kGdE09^Y}Lad2$vHE%`m1*Y;r=1hmSF9ITJA1?SOT2@s?Z4l_X(5`*I@D&o!wp5ch2IpbK+iv_2SN8Fw}U|UU9pr@T2p}3Ogqv zuqJxj>G>Mv@&BCwa8E@EalfJrX7$=z@6pcbM>{9hg*zwi^K|z*uCcn;)R13TQk3D2 zjA)V&&LvA=g=37`s{08lDKlT>i_iOzIU^_|m=c22AdCBZWhy>??X@Xx0j^D9^P zC|DPwsW;&a7j-0%-=P!0bvgmy2?^2EgK$oi^EFiUoimVjPOJ+h!Sf?UjC`)d`HcYH z>ribg)`e&q`EcH)69BJICxB==0pMv8(KOoOOkL8mf;uyG6rW%Ei*VjWNpRJsm#q)w zH`wRN6BfCv*(cW3SB5`dqlgw)QP*j0*v?A!e2L|pYoY}L1w6o>7d!;WXto7hcfA#wN zD7~Cq?tc&gKPxK#ru*}D?KYY2%m`Nx9QZBOmLGv?(H1jwUbKw*q(@z~>Zh6dmb4Ny zt4*ElplWU*L<-a+K;>qt@!k6VZC; zlbXb%-E>7+z0{45Ja^NCwO(y%t@c;E3EMTj@5r!sSj2fuXs zfhnYZ3$=2WXuW){4r;$vE!EQhMC%on)>ET)wo=f_({yf9&{?R^8(ciCp>X<38+2a)AdHKp=#U;f@H ztBka;9b(I8)+?_p3{!d3^qZ!A6MWPnQ)lYUD+Z{@19?l*@e@UrR-R3`?sQ*}s();4 zwdJ81y488Qij*X2??hQi?q8XY%b#LGi$i-Ab@d{kwvy|j7yp_2q6ur^h!RI_$EF|T z9H+bS_EqWoj4*FCV9iYZ>-_p^>2W303yorRUTmRyW8yFK?$dGl#>*Q?yT3k{Q})EG zyu;Uf0s>{nHqkyqp<;^9+hAU@*8>xlAP?kC-;$lmqAY&bfwwO4*tBKW8}lXCc>QCE zt?IUi+12oDvu)#i{_<+-@vpJE=gO)i)sEFUmCz+^dD)-~CahKBR1I~+%UHeD%yO!T z@MxAx`7yN(k3RX?geB&#)z#D^v3jwy9xC#dq!qmiDJ`R#@s)#e$XE+y7ZE=3uFB?I zludpuQIM)~p}J~eDOPWKpoE&Hd#Gn-$Le)n{!Q)p*r&Ym?1Gt}8vVh9UJbn+qUn1z z*X+u^7VUYC{O?Ryf?DW&(OunmF5ad$(k>xx5n>P_uq5V*N&Ry2w--f9bo*Y>>`Ina z?RkL$A`e8MwDhILg96IiaxJ;jt-U5}A@&DKNG~;A*(kf04(IU?ADK?nOEUK;JJ%-f zj5tYM-r;wji`soO_?)~gyg$8T`j22Giq{GA(x35q$^Z7MNQu5Ue6vw*-!PmW$Z14XJim*|x|~UT^b7LswS2uHuI8vKH%;pkHZ!P#t^vKkKH7@%qb6#`(GWCY~J{ zID)qubyGkfT}0FEVmCLks+Gd|k%R{(q(%Lq+4}=|OHz8+SN3IgS3We?Efdy4^!QV6 ztWxQC{bV=Wss6Q%%%@^F&+YNhge7DdnthxjB}uCCFo=8oQ;gSt_sf{iHG3q}>!1Ew z-Dgqyk~U@4`dP+n%hIRll{Y=7NT$_-c6@0KXTIk9855RlGR0|chyIRzC=Sx>aS)yS z)XvT;j%m;TY5d4kR`<|u)9Bnmqm!&%vyTrNH`<>Obz))(eyd(%9+&#egtZV&BTBQ6 zdE1EMFrpkKG>SBPB!iSBX-;|pezkl{o_v3=;Y%F)p%JCoJsk3rq{1HAxkT+qq;{aZ zh!zpwKIP)MinrktXMGa-gS?$)_le7wSJMo?yL5%&cb_-N%8Mp-;7J1>ny>_UV9!!^ z!rnr>Z@XrESzvY4S|983 zl#fqMShA*4pw?tXj6Um4WA*jZ23o|882!KpBlc{!Py7MzbvdD;d;ZHYc51X#9 z{aIg)I2feO?i!g zY-@i$bDkTY)NY#z=~Aqv*;f$eHLbO~`=a&OhQ``pXsnt4h^WAmqA!}T1o zvFO$+Jb0BKf8h4Wgce8fu4a#^MX6}5#*MXF8Ct8+noP5=?$Ez(Fzi2AzDQEN#!gzM@I66YtEVcBF)}s?k4J^W*%32 z)=fIRSWnbzCLdSDojYSkaq8JfzS;e#2}^J{5-CyEWMnJLobvQm-16I|hJ&4~7uOTr za>s?;bEG6mojzZ&e6vpAeb28Ec=YIT?Qo8LiTa0S$5o_6^I+0cOG2$k9#G(4A!fim zD{)s%cFx93b;k1+x$c{=1fvX$KImP`OIcX7-*}#Rd%A$YJw!y4UCm0j^wh@l;M0#y zU-DNy+=|b$#c*93_o#L8;qTwLmqj<}>`b@Ryg#1TzkJ(-vhR6T)>^UkZ^Vf+M-KbN z|NbpW1@@*}$`NAb{~&$^nXUi&{H}#)LhMSn)F6b{{~$bT^s^?p{6-*}-j&&wZjlKw z|B@&b>Icyj`)o+Jv?9bOLZG~;1#BPP1Rb;?bvb=+S@F(26Y2zOA)4MkD^!WSI5du@ zk60zx74`x4jZM2I(5~ZrkR83K& z@>tR?(jtwT?frq2=I$Gt_0WG?2ApSX>eJD66ynY?w}SU&HfpKuzE{E!kw84*`a zSr1O&ackC_kQVYt>~YQC?pNqugAw~pb+SbA+MRcq@T>@H4XK;tZ}*QBz1F+!S73A` zPgrx+geBzF9Or6CiEjD7{nPJra3s&_l5Rq}SPP~7eU4-IyXarh?;<~n8KiP1!?({T z-;O0HAyT5`H8*FIkvsOFsNE7tQ%#274J5ydeT$YTt_QzuOE)QG?F+~= zpoL>CMAQ9n!}eQVP=9PHvCD+>63zzHKF6sn-A>u8Jb%?k&zJkO(a$0}%&a2c-X~TbMMN@IN z*3`V2>YFD<|FK3>~5jXx*Dz5EnV+_ z5XDM2l^0YR&S$=gU}I)9RUhSz(eryLYQ<;G)y~(W^)|cfs;7svP~EOY>y~eIiAU|W z!E&2w!};`@qZpPTKcqx4^~2oCkb`YG+g@I12kskxD%M0DWs1=+1qBd~(eLsohjO&# zPjVhj!4l+w8j+;5O+oVg#>2VObFm$WSid${t*gf9Ykt%x9&4rr%I#VV=ludkF{~B$ zAXrT{$LMZl15^>w`eL9wtnF}qeD6qxCFRNls{!?6^jdrCt76NqtjVqPdf1kK4EZY+ z+krfgH|^p~Y$89cFr0s0K2p#w_MnKUJ0qWx{;4&u@Zm}dS_AIsi@J*aRzS(opcTK@ zvvVr$t9$qcsbl)b=m9SpswgeJ)%Yn^KJ#-h_qjWsVJ*w@#%iX4F?#>7hX13h@*}&* zQ@0P{)+z~tuCV1uiQcK69%s3~tq*_M=MF=MDwR8c~jollll9=DbG)N-K=&m)>N3sBE}kJ0C) zHdaL*6UXnD>qbj_PS z4Sg>E{W%jqdB#`J6}A@JM=|xKib`&};s5obMht6VZ=w$APL6veP2Wd7XH$yz;;47D z7?hCSMCuwTkM^p?n~bc^kq6d7G~G3+mr&MM3FHSpbGOWA<>8fDso!Yco*nJ3 zVy&rRE!Ax)(R%x024dru3OvZIGebdp=B*Vjes6SLG(krLgeTS`)%yzRsf&2*Mgc05bneyo++V{f!B z%`tYoKE@YhRrihI=Vn!vQ4(y2h*+9e;!S6D;&D$335aCgQhiKxw+!`E$6arso+AlY zwlH{P>z+?p6W*G?|0~LblHh6YjAE_S7OBy?Qr|cY{}N#J`#ESL-`jMO1?i$BBEor0 zU6!nm;R_?b3W)jLTB>IbN9(OV`>5O2v`{0cKU$~y5Rbdvp0XZsU3u{wZ5fsfxY9x` zupwH1I>}Q--h{Z3M~N-gmd|`)sfV)T?2NOvBsov0E0@bRlD}x)hM~L|0btxk8NUVc zC_fgr<+VH;`XK`8B3hC{3fGqRb)~l^#;Xili*zvpq`CInbxZWSA-wd(%?wLW3rLB^ zN75vDum1>sV^>8XlEGRiEqy;&xR6pftR)|M^sFDsjF@uDn`mTZVmr zwj}mP&e}cYpVvooIc>EC>7rC3;$^YSN|~h2e8<2dCPbiJp@q_05TP~sjiGY>h>1y0g8rj2+qd4>hs zR>|lM`nj}FQ^|HuN4fuxXGobom{khs&j-xgBaB+~ALz&E#gMJn9+GD?EA z&{xvg#E{C#U1rf*%{7U2xvQ#khsNl|cQjIKj`C3_c8t-VENh@HnBlJWeiyArUiG6f z*r{KLk24|qmPle1QfjGpM?~u>-)gBLp>@>(rK5GPlq%{M=Z0$MveCNBqbh{Rv194} z`}Bo$9r~Ia5jdA1Z%OJ_Z|lCwgzzby#E@3v_-5+fG12<@KDAY(MCY{=$0gS$sUnMu zJa9dL{3Jlckw@18gM6MPg!9>Dl7umcJVeCW`ffh!sU7k3bFA@j%k#dgDNIgrx>BPi$z1$_Z5npo7nWI$557Bh{Uf)5=rx=~> zJmhNmXPmoQa$>Z;y=E;H`Mq3PLv2V|Psg_!R#J8SzjDx{ZamMVIHAvxAEN1O`{Liq z`PxPJuz}f>(XV{ffO66LttORK&JMmy^V&t?1Bl*rd-&4{0P`ikx zD5KSY)RTLv@VQJ@%Fb@6_O1}Ej~Q24MSdO!ebuiGqxI@dDiM!+BTlB|8a0uZOPOjy zOGJK%rjwuc@od`l2rd^WX+gU}H1ei*mp+x?1tZ+}{z(sI^ajTdH&?qx(cZ$^TB?Y6 z`cG-j=ezK_ahZj796Qxet=>3V?=!xVij-*I=c~%gy)DnbG>SJNUG$0QD`__99Kf9t z^YQpqD`iBW??N=i)K8LGO85XidSI|Hq7aR<1f9q%*v(#92k`q9ItcRz&T6PbNqX7m zKg%y&=B@Ko;y5NSLdM9M&Qg!KS*|VW&-Y$R6FeMx14K*Gw7ah?MW4$2)^j(GV-4xz znt{F^uykamsOhZ4>u_N;f$JTlMETTz`O5>9@|NxLIF4&49I4_MtkHg$<^8j*mNDxi z1*vegg_LO2eyS>;ex8%f{5XaqEtEt=e3&xKGVaAzOB3ROvLg>fOHx9%|17SFG7k%; z6*sKIu@?3d%?8twEY)s@^UTLL3Nak|U9r#0&e_bSb_?ax%XegGqi9QLW0JJ2c>sSg zFCPy&zET)bXuBd}k{Zt{-iqKa_LQ{XSi@SPRQXz-O7R#uk^7g6GNA`RG>&;XY3Ms3 z_0p~?ywzb@K`(=&7SZ&*^U4_6d*Mi)yUveP^km2nJ&`2UB`^Acyl89kqUbG=AEGHI zb@RXS)Q8=8m&iDV9vS(eN2Ra(`wUXN<8^lVw5tWZKJr5}tx~J6m+Log#3!C{7Az6@ z;mkn0gEXr>p;_$)&1yI%kRPHYsn5x!rqpC#e&X+%!uUYT#~F^kKaVfX2aVatihcA{ zFs4G!8T+WA+ShxAK5JoFnhin@+_4l-@#Xs4>I%kGh@QWxks8o=h8`AbAWWU#%F8D< z=bIMp6jrH-ZaXkgo!e@LKJsoELfmxqw4D33ncejssvs?tq|gjs^?LeDT`?KihF@Lg z%VxS)c3M_H1!*Dr(Rp9B(3_ch+3SB1!gX>{#W%OgKlX`}5fSZFS3UoArv9V#U;mS{ z?V6*ga(RKueTT%#SPL@@F}sm6wytJZe&pTH!afBk$Q@<(zT=_p2#?jL{Z)#j%J;p5 z(tC12zJ5|}1$iLa{k4axM#kzDPL?D@Uf0sf=jru$=dCkjlmyY2A9|>BXT<6=dKicW zof<3qiZ5mlTIN)c7D}?CUrqHr<&NgAWW2jwV!FR_wsCgeZR<%HX(2kcc};a$TC868 zXE{PV*DERchu7il8+DN}YZB2XU2CeL_ha?Y69%IH*&#~khA8&)Rk-}HZFP0g%~(C} z{HiL_6{RY(shzTGkrS^oxS5Q!5P_8F+@O68rFoJMU!US4W2P+Tav~-2?ajt2Ggh`> zcTNXeHk7EL`mBl7j|F+CNO#tV>guJFv3l7VMjqMpaov?-M?SFTsTce*=dP{}q@3M# z%c=?pq$EiZJ8LQXvitClxwe@w8y6)+N^~}HrnjO!aAQx{C1#-*_wAUO`qg5pigbsS zsi6*xi`91)^f0vBsf*%S?j@^VrvqzqrMh}?U##9O&O<;TC5nB*J(Qety?L!J@9W{Y z6H17bBq__b%*uypQI^nWorIlKq+2?`TfH1IQxDe6Bvq0ReGBmRHamJRzpz^?pYT=_ z=gicn>#B-qie6*uD0x>_;uTMHVYvT^JDZrlElF9uyp@f4Yw`4uZx$>;9!QB!0Ty{G z9p2aGEyuqW5U2%2Q>6c?w30Pw3{&!&ILeEAx+0JD7h~jwIiutYI|p;r3C1FbrqiW# zRoUTRfxp^5)`EIRNl-$1V|{XO#c%OsmY9tTR)PqmME3!_4px4wXe#ghP=KTTpoG{y zIt_p0qZCYc=fx(hF`bQ-p#p7%WN`+|j+VncGS1Bd@oXjWQiV%D|N`mtWeW{oHx3Vs&Bp-R@vy8M*5}bYL zUF5;}l_i%SvWI)3OSmWhr*M8@ zu0=^i#GK(n$g`>tg=7Dt z)+Oob`#@!D*8wbiOd$b*c8qB9)PCbqO%L}ote%JE!$s`#y ziY*rr2dK{jsn54ipJU%*-(YXjIM35uwk%yMul+GdK%kZ2>?28I-sRy3DFfm$Wk6td zG@box_S_FT&C>qlOk7%%oA;qy1LtmkrD82Q|I+OF3?ica#Xx4{GaRLS2HHc^?71Jb zGojh@8R(2n`;#+qWm6EdXIWqg@G7(W4C?*?YAgW~fK?Yo$HfAFZbq_c1br9MVeC#Y**=>*P`Vp>GX_ zwMNZvsjWH`t-rnMZDa_6cAM<1#$HLIdHd>h1zlmwkrKW0v!}h>cuy$L>9vU=-NfT9 zv?05r^_J_sjf^CRrfJu?i4)&4s|z=sZ!Tor=RMU*bE3TY`i(qQk;k^~`I-OF3A|d{ zlZTK8)sVE`k zo^QL!&V+X3;YSAwnf)|dYW7oWkw?QLedJr^`|_5v4jX6Nj#@NZYW7oW4-bCJ#^wYyrt{E_f5A-N3@W5J#rnTCZAFOia&V2joA~ISAelda) z(t2=Jlw7v{aQ>}YErwQ&V-QCHWyGJ*Qo0SB$SY)-Zb2R>iHO+aoQqd3*^YPYw$Oy* z4m}Y{C`rZqtFqCJM)QO@UdEZ1!vmnl5qV@u%FUIlZFxfe5q{`#(5oSDNm@=`bngDP zyi#&Y|_+mZ&@m@nCH_Gwt3VzelU_}G%`!zZX`=>E^hNEAf zvAp{-^9y0V#%f!$XHa3SLT>}KJd~Fe_t`jCtA66HrE!xxmXFWI8!LLvojOAU`4=ieGcLAYhYozsF9;4T2 z7pU$IY^XJwNjaBajSRYv$BJ^dyG?oa=~XQ#34X^k#vG)j^o!Bc?i(kHHT(8vSFU&9 z6TW_ANEam$5#M@+Sq}AS%10F}#t|`MLu0M;fEfK`pN8tkUx8Y6$~=6S-QeNhELg6% zsu~|&*qdWX`uK)g1Iqs6X^m8*M7Li=<>hS`wBa}R>`6u0adyU8o9<%0*_qA#X9)LQ z8qZK(i~uk)ptZrhyu4J4HvDtJOR0!Jx`-w(I;j_{*eQ%JsxgmYYmqKSfOHev`spUM zL|MbMx$`Ko)7LXEsP5vW}^`v~!q07b!kqp*CX=&G>TtU9Oaw}fwRdXSd!CI(8 z$~A}zmXEHh#{F}9bL<1OC9ywt1#DpEiRoj}!IqBX8PFThnnSZ^O^Tjj)RcW}!UKtS+SgbZwO9-N80Eb#D$U1D zkontsp$sL#TIefnSr%UQEDJi}(d?NVbk3#Ovn=QYOZ$__LHP{H_Iw69)zj?RB8aAQ z9PLlG2xVD#70$@Az*;z$AU`@Qa;fZNWTY&oj1;6rXE&NXBL#WW4S&Z&lb=yu#$3wF zKpwarKz@W6veetiNb#nO6r_ct3n|gday!TQc#>2TDZd13ArBF;Dmo zo+l$B>IKBhmu^PzsM94ah(P_&d8B5~2_Rq6dVt?)I#KLICyI2cr`dBR=oC@2=Qhw< zU9;x|Q1(vz$$Hi4)bd}qC=*J8{18q1q8I<>pXo%gEuARRsh(!f{Xl-Sy4U{XOsrWE z!&=g*U5)i@2c24`oOU*HaU9l%{18nq z#hzPg$#uY&cc3#!v@1j-Z(4bMs>)7foYA8^VM2 ziFTcnLgcbz<5SYcfC5jXODXnOfz2i&SJGgejkt&YCzw5}#sB(q*qO#kJTpWi7z||H~vgH&h`7?5g zkQSmvgpZG`TqPb2D$uSotW1#yqUqa=!w2LvmjQgl)n>wq1#4kHNm2`s@}|BgDFZuq z8pD1@k1F$$~JVtJ&IS>u>r(RM||!?dNA zoV$Jb2Fkg^5rwrxsfyNF&ze#OUHS9QM$VnXUm+UDye&(QZzu0_le`al8635UmZaeI z|FTY$K{tG2979ir{LmB8x5#}5@ynE@H-@`f&|4xuMAQ0wZ4A>XgD%ta@2TjKkso?g zNoq*5!C9IO!f7@@uaEo?P1%NZPt|jx47#>_stGL-`Qgk!IrM!7_#LJ!y~UKJhhqZy zA)4-{Y7;MKyAi?Dvz4@<^&vl;;m9XmjA08h&LAhGuZW;CNX>r2D}K*Or?0$y#_228qO(oMeJLWM*6U#Y zg-$IG(WxbJN7-p#T>Enx?vdDszZfuqExMP&kO!jaL{YP!_R|hzy2_2yS5Bv|C<&tJ z1XHu0tJ6utZOWxi8(^7qVUdwJ;Gl()EE!Q7w>0_oGsnJD(Qm#Sa9y%6O9wqUi)v z`;+@I_Cg@PNm)qW?q^eGzVgtTQ+CTN%5FirqEv^nC_JQkZhko3YMiAyXdwbA(f!n0 zD)JyYeI5I}g^YIv;Vm~viSF16&(E7*e8^_^u4SAkYWCbAq`Tm@hn7OwJI`&|J6_pK z@q-Wk=6$AqlB+%R(AHAU%~#5~K?G8wD}lXBaXRAVV|av-z2mq&2_-~Iv`0342%AQy zmSyPFlFkG*d!7~2rSmWCPi|E8w)feNv$grY0{M-cBF&!Ngb1WW_eNdH$NlK^bsn9* z(n+Oe&&;B8PRBhg_BMK2niS9$bk)02A-p@9F3{Y^ap@eA1ln-~f60bbE4j)>( zi{KfME{-nBxeM^;6NY8yzkE;0I8qTIdWQF18}oi87PB)=avE6{4sVGPA|+}^yBhoi zWuAS|Tm-4m`=GC+%$h9i`OFSZ-1Bvik^ABBuP6z6R5~jDzW*ESQC5k)#t5-T6M}k1VBpq94*iG|oQsVo0;G{3B)11*{IX z;4Fh^oZ)PlXWYm<>(%YOFb|?6I0s8os7q&F;K(cXBe)MkS||z5)O26}ncn;;WzgND z3_6^V5slG+B)P@b;dv=X`v({BFDDO{1s); z4WJAF4-E5rS`i$%Zj14hn#1TyIn0&9yn`C4sV8n`O99^_Zr8@`LHcDZp zGpgVj(Atp_?a-f!o7|55Ao%T8n0k9XZ8#TjB#=OAtETVhEL7NticjQAa7e{4Yz03pd?re+ehEZd=BJI z+7Dn(5rqT~hb{&0^x7cggo3^YMMWL*hFv@yC1X>BsK9bb@XOKK4z6k$2 zHBhOx^qT*%b&2|wH^qhW!5qmx~^ zd8a59>gwZ5fA2}>5_O-uhOVaM$!?k(6vmHtIwYfhuucD{X74>W67}WGK#Z>!n7VMW zE8lgji83ck(qX&av6jfAe2(mv0dg4sw&;+I_xs@8M2M#BwmjJ_cB!xg`5`4b`56|N zI*MBEPc298$;mqo+pPrA^wn>U?50qX>MKcwJWwjsh$M}w7wETuTE3H7jyw>JdZS%u zzS)vm+m+{+nkYY)Tsv%xkE=93s;#_s*gif)sSb`gZ0SOl=t-7{C5XU#k?8xV^Fi$W zts*>nN}#~w;3Fri-AevB;$$_(U}oDG+#wfdh9zDnOGLU@OT2xr!&X-|k49~88nsx0 zk{~6zsqjY-8#Jp3|9LP_LAqEAHA3GTygzKYM5ES^MlI6CenySZc~tF9mhI#j&XH%p z66|x4hjGi+ukp$3_0KTH7!w0VkxmAjPz{9rH}1Pun>{QqAu_#kvKms&C#le`MC~rKW@A2wU6>EG z14~eENQrK`-8928gWBN~5%&KO_EC#y`UdM}*L`~u!xi=KB-yQLoLcVL1pV0AqUQJG z-&Ps6xU25IXoa>^-ecYKZ-{>9*FueM{yJa6D}@k+34tZOH&@XzH}0t~zZ#_>C0cns z+~IYa5Ig=#l9BGv&Y|k-1O4oxc6AzRs z$vRW5y)aDwI3kmV5*oHHN&5*=>wgeP_k8ReHKg81{nj&IE3H4=-S=!EL^vUCe3@?@ z6O*8qa$|xeidItS{fvD(3DN9-T7IC|8*BGRak}EUO`Yeu+uEXhg5Kr&L2CKji>3E3 zB*cyXLG-QUrrobIQ$KqwLC_n$MAN&N_c20TCtaa-2X`5-m0L1Jzh3%<`R&F|+Uv^G z^}QX9Te+Ne_S(0J5Tl6)YLs-P*>#0lpnadQeQZ`zkPxU7)GlhBvhJs^-MgK5gb;#g zX?9Ee8jxGrHwF0*~yiMlG= zx2V@XLKv2)_GqCVDju!-Wb3GsrZv0up$;X9pY`=VNr>ab1GTuUte2`ZpP?7vQL2b= zKODb*4k6zEPk&Usdfe=)#q00a>{Fvw{4(!Ih|?3pH&M%tKf~I?2!VP>kAps#_S?61 zO#VRq(V|R}jI|K`>iS4)_Qwf&U2lzexL0oNWg#B9i3jQ(tsVPGk~$Bnvu_6>IuQa( zu(jAXbc^8kX?qNxC=&uTTC3w&waMiv`u&KHWnZSg)uh{J@y64b(^m9x!fRwd{&Yjct+^VWgh1!sjT?j@3B)H}{H z*iYn33NG-zL_8)D5A+#0K9HXz4IEf$?=C_#pq8UfP`jvgT5a#|ko-3xMv`{XUQt)r zKFXOWV&1=+5Sxexw$N$aakIA`uQy5B_dnKNt45Q3j1V~pf&LXOQEW$>Q%^ki62hAh z*i+c&VmnSBtGK@+AsSFS&_^L%JP#3%Vk8xM zXOx5xV7rg^zLv+go6lTg+A1gsN@&gB)ZDvCqCTwI5wa3?f2*8r#6jk=Bt*e@2Wugk z)*rdH%F5vFtY)Ix}Q9+~SKc~z^O%=)~!@|WvS^Sh#n`rVwGigb~m zB(>S|S~fpk#mWzAtzZf24JpxAba{f5YKyzF>m>>)I8t#0*Zum->}!eBKjbvLXr>Kb zN{)U5*s`5f6s(2q2;OU_};IRImi;A|*-MRIIq7rYvXQ z7W*kk7xjjeB*~*oPsMd|C3fP>9T~?Rj>i!_ywqb8X6VCwqev>fR0rh~efPS~_q$wY zPYLylPplpnuu#QXh^Bqf;vJM9kId|8A4$OyoUf1)O*h4Zl;)R)v%44bD+QF?YMugd zdcT#cRIG()%H_-+q}(~uj}53?P{9)H8>B=lmH`8mhLOeDB|5akv5jN?#K0D6bhBvv zOT!M-@+l!bmDL4&*w69~gro`ld;6D!B}-&zNz}~ z{vXUpiB6Hfg((}R=Vq%GY!(pcwLMY?s{=1PJIQp@M|9jLfPlwsBm7J0$2fokJp zQF@b6rB$qjXi0k0bD(nlL}}JJ(IU(SsA;4`XGJ8HcR(IiF>JGpbg>=SK01}j8le;_ z@xrpeB}UMd)HqH(8WO30`dic+%^&>+Dyt8bX1B&!Wb8GR1SO;_?*ToPk3N-I^N2e# zS~&I^_9kU{R|!%kME7IWeicw~q@wkqRnonj-(8i@XV$VNz3VCHqj1!U9?rYN8`*j3 zDwdY1wSwLmeH8jGTHlNaSNyw;V7ns63%Ww>&X&ijU0tT?nN;JYzk+#sD8-6DVJ|I3 z`jAYEJ3MIS{fgEh_brT26pC< zMc{!}i8e;LwP(93No{trGKCHb-pAa=ORX?{hOShOQbit3U1X))=kmN+)p`OCM2K(E zExOoB`H=M(dlZo-SUdXN_iIb2f16|V6}61DTIiSRO6CckeDj>4$_I`f(vpbVaMl^tpMQO1%3SAUrc zACJ=?yx*vbJlugRYp zu&^S1;bIq?3b@IF6z4^nsYhN6lYO=pg=+wD0^@yRDxJJ!Nkn_g<#T2?9Wj@|$*HC;x!=;1_PvdAky>0JIMlUuwOybsbv zev-6sw3pJ{xe7Pu8ZP)m^v>uX>7LXht(D#LQrT(cn&7Xn7RD=-xm>rQQsG5WzW;uA z8R_DzCe9xNk9JkEUD(Owe+~#U4$?(_6j|PFt2~L%#DfpE6y`yk&v8zq^TF+Xm2ECd znQ!_EA+p4IP?T!#*sjXxH?P>MEPgV^1{hh0JTh$@q$m-S*@J3xWUPg;4@LvD>pZo; zlJ_iUd2Yx84}94HVNiwreyknK-6l%lfwjaae8jh5{Oqx>mLn7A$+%C2>wZFL z_7wnq$(l8S=cRae9>u#@i{f3)9`A~XqG`SP*n~1{mI|?94fG!m_E_nSqn_ zt#7xPu@<5!r|8`&;!WmuDdZFAIB?sA;4mNgoobb8n~VtkLzF3hqtgo^|!cZ>$B1#Oq7%Y$d5~K5fWn zb?wbg>@K2UEj%%q(!ZFNHZWG760w*NmnU}M^?tNw?=F3lua|MtZimj)n~qITu@<5! z%2?KcpT88$)UrQhEJ3{?C2IM}hJ4Q5VQlnJ7X|5}>?o}yEn1a}-@m$ut(X|7;9eN+ z$+Wo^+WL01(%EjZlEM=YY1uFI5 z&A0YVPSEq-wWwGN(e!H1%3QpCu_es4exQOSs0E}%H>JN|EcntEHhq0p1?l36BJSKu z(w^D5`0SEP*y`Xw1@(h;ksp0AGP*kdyYO^2ENpGpxyCBh;rq}VpqHR8?|UY* z&Xe==qdjFoSJM+mS_jct(Yy0j70=aaKQU7jJ8-=ZUzWUI#u7x}%W0IWc6BOSeyR_@ zS20<}TKIO6h!`7`je8!=&KE>hQCv^$vOWz-(BmQxs))wEp|5_6WaHHfIrBqHD=SzF z`(H#fi#)-?(>wDrZ#T)vBM#pBMG2|T8@ch&+TYl>IfVqN&| zVp_ow^!|0v#VS&w{X~~iymnJR-l*bC8EfIot@xrV?I#{B!fP*S$b+8u6W*3Zx=4xc z?4Q+|uhOloRm3HEfpcB$O4S*9T%$=U)<#jN_5=mdrhP zbJx}ERM3859?aXhlQwP8bUo>>02L*q)tzrJpWCPa@6Ec&SPS1sMF}Oz<<~&&9XOSB z`@BS$&m&#NYZGoy(fuzzHzOrU%H6yRPnrIjEvep2##;Dtb1!)7S(2KqYsdH3%fffQ zuO(v%(nU)2ebn0_{AHIZtgB_X>|>78;%LXqzp0BEYoRBiJ2|$8^LsHvS>apb1gS7a z5fRp+VchfKd{(h@FM$WXI*n~2-@d5_FTL_1d)vFHj3p=)N=uneCBk@(XY<+dg1v-@ z3_YrdX!ma`-ez7dUj2S)L08y=s5eQvbZ!8b!sf8Medh^%j(#4sKrg>9F!Q5*%kb?befmM-zSp5G~>OKnW#j_Ua{OF8j zVKzQJAREs#tf~d5gCC`pyiMk>2^O!d1xL$hG5anW;B&z&Rn9drDw8@tU?znmMU>%I3-hEVL6_wwHh zIx6$-_mHs!^JI_`om#qwDlhN6HNCubm|?BCmYHh(+(Y!ie`VHw=#$kBV?ynuwSdnnn3FCSD%dxj9E3?blUN!&y(gLzQXTy#1Ng zmMPu!pLJ#tkC+MF$?txxmOICWa;(+NcaOQQ+D&(E zxky{y-^(1-B}AX?znpj!da~H`BzU|MmQaFW3FhA*CECk)vchuBdxM5i9Jgfo_3-EB15M4)}9a5s`^%jl6U5n*qWx5;faMYr9Sncf~jc9_d80gAT zg1K=>iE_MJ?O=JR&wEjyV~!Uhs0Xz_eO~ZDc|NuIIQi5{U!w;d*?-i7n!N`_M8%X2 zJZx@d*>k*;VI_{tJhBqaZY5-)nqa#OY}ZkOxeZ9kHlmm@qUO_x!mI~G&`8t%jKP)P zNAWhFV@-GI+zV^bh|=sMN<@%nV0O=dJ1oeLJcjnimkf=Z$j?R>wK%!9Fkvn744U0D zhzRmmygT`;&g8Fz64=E--jd;c_zvsgvGMXK8s})EXeDSp^c~BPLF_Y)+Kx18apa)2i?-|h zWQFN!#u&s=i(^n6QT=XNv{QB1^>C0DU|4ha*3gcAX<9DwoKv za*$o&9ECFu^|@odqC9{_!6|${ z@1!|uf9ptn?FT=ao%2GH5vBvG6Nskl_(OiE z5&4Km`rr^t)+-_cB|$W;yoR??PV~)|8hAdhVC|un$!d|+J zTlUcx-!tNpoFmI91!^UlBCa>!I8t#07YL}Y4qnh(H$5Inh%bcLK0ML%=4u0BoFiQk zQT?=&!sOGYw{D#U9y^y-QP-X8saLHvP0KnjhuSW04}Iy41mfXNh*rvJ(*b6~v>kb*UxC=OXgk;o~`aXRJkNs~t`GyOgc<^IKl| z=kInnq9v?FQd$4BBZLsK)bcNcz!IE4a9*JZIXh$P3;!@}SR87!+!0ez%dK{elBPAg zrYSq&v=djU2S5Dob4R>`GaU7-_NULwpLOC5Hl8+_D|8m-L8L1p3XLqo?|CGe`u?_E z2M@9<&2Cp@iP|6A%|VDgWbGpefh9Oo~`zWH(rP)Up zWe5#z!-urYky@EXEyfHO0nljH{*3cC!`krCDcMp($unRrq$?si$M)sBLP9Lgmu()- z5%rNT(d@p2{FU~{!%ZfHm3-nN!zV%sMlvWZ<#NXK<$cH}mL{Kw2=Z#0-6tYil2*G6 z=TqF$EK!LI4KM154ap~JcJEAHTeEv@T7MiF!)wrN@QP*wjKVNFqgg`xGk@GBME~U_ z*`l{4joH8vr6OGs;WB(I->|neJGdn<6?xDcrP*gPn&CA23`e`?g(J8zb2g%xQ#ccZ zh?Qnk?ay3WqeujIQ=(X@@GL?sigZQ90+$GWp5}8On$NL>=5q~V2FH1%B+=~5KOb(* zwtoyvMY%RX?8}PV9Q0sxx&NwuZC%sUo_XEMp4t)vvdYYcJ-R( zL1&r=(K4{lMMUP|ZTO7=*;3n+wWC!Fwkxc0d}s`&(X93_&1yI%aID}6w#`v=7jmNM z9nDcV&T-U=2oLgC*G#|XDD*PuOGMA`&6%+)G~*PZ83%n7dN}lzbOWZ=k2RqAV-w9E z=y%bJiij`zQp-A;KSt90f&Lu5GtLrZyVj+q>@)67sWme$y4VfPmQq%Mlu)^QG`6KjdCD4Tk6o?mgtDQFj^83Jt*p%-8sba z^|u#wM35N6i4oaKm*Gk{`NY}e6EQZVG2z&a!q``mZc&6hggo3v@^Ba-W4tRO3J)Kv ztRN4UZChX}M&2~G9lL56&r>#4kqE`^uW)UEk-ms%S|Xf(h?&iLCj<*V5&f087yiN} zocpht%_eRQma!J@(2IzXCBwPt>vRn{eb*=EIBa~D;!A@Z;7PKXz7wQYzhN8;Ik z{WjSUof=)SVy!(s|M?qQ_;O|vA%be%G8rx3kz)n>x930`LW%ff#ah++jI<%<y}NH)^fgmlj=`U})8Hl09oi(gQ=)(r$ zHxGZ(sv#9=+2C;)csOd2gtp(m+wqRHdWR6TspZrTtAWU9hocs0!D{gMt*a-bRYR%= z^q+KPLuBa6QHwNf`~B9|AJvGq(SwhP7xjk?k^uz1r@MEY zvMF~KcjSlX54F5(N0)G4kJAkVT0Yt|+0~q%@&iK5tW=xL9c8j1?$`9PVlA|3Ns0=2 zAg2>zP-G&@Rjj5B@tSS3VlA|3Nt(5v*%0)fUHz}94N-LHM=RDso0g=(k%=}$bjSnN zzujB2(GK^Yt{T=to2LA$O10&OBo(!X`LEk#L-eXpOT$`d)AT*g{GleJ9Xp+}@u^>{ z*$~g76b);kP18F+q*X(^q-DPNaFt4iR1JCuXjltv+9nkx_gIc-zP*E@uL3F45>2u z!(sVo({zU^$!|y%PgX*GZbM}Bxx@0&rX^_y>B#60LuX`HHbjP9IV>M-nld1&)>ir* z^yXa`ud?{n8lg@&Hr-~sXvb)wbfbe`Wu+G(lJ5*+j|zm@5d9K+Sg{sbD4i9ZE2{J$ z#K#kqzm%zq4YAhgsugRYh0>1jtRHeWLcE;ygPnUO+Yo!27T2&AS}5Jwe}c&d58}nU z_!qMwDt-3XuohY zXhX=Q!Zoag7Ai@Rq*X(^q-FkKNta3nk9qP)4Qru=O454LY9B(7mJJ?O1ChbQVaI5p zww5z{%c&hUL`FLtc8nHE5i)7ju3gfVX7I?+mBWtFLTOKiv}*4`>JJ+tqdy#Wj2226 zbR>UIYKMi|Lw#;TWc0bij?qHNGmwr9yXrwYBfGL8GVID>$7GeZ-@iTelR0gb?uB#l zA5#unsuzn_cYKVr*)G~KS}5JO^rfiMj}S}gevy+ayVww;e%8{^#?X4`-SAxx68!&+!P^xfU(c)1rL0&WHIi+A3e4XM&9OwzCxT8|`spK{pLlMvJ% z{;ujc8$zBxQ^Q(lJ(R;jEjC(iAhI=`T*=^Ztz?3Rwa|L#+t<(WtOp?)l2pXQY9KOr zIBX29hrZR{^?(`em_RM3cGwUZ?Qqx_S`Y0^kX8*{EvNsaE6w1Mp(}@tq4h}8W0K!! z`8R6MoP-%R#O9rot=Rw6n>O_CK3{yava)aUE=K=()QTbMSlV6gTHdT-Z(=`DpO5(^ z8wls%V4k(8Vnf{AI#k12*iUrAyJ&@+LWm11dh(dBS!{@1MPoIrh5bbLg)dscwh`hI zA%6CWu^LhpAG|cxVP9gNH-Ys6+Y+f?8~EIkm%v$Y_T{)1(F4 zZ^NePH4jsJrPU&5?s6f@gyW;=iddDuiqu;caxvHcZ-iQ{+H~7*%5Ia}DFIQrcvx}^ z6PDnJLP`|xcJoxe?DFJA9?v&ntvfTq)dL59)7{pzzPhPvTn3NlBWo*@via~V!#kU> z1ZNziM7I>Y$*P1+?8tZ2jWHrJ$7%u*oiDnp8_&gO@Q@B>SAI3?z&j0@Wx`r9PfY5U zlfNYq5k>#YuJ~=}!1Ks8g*6V=+V(KJ8lG)-29J@8Hpq24gz^0zm1TR}W~_>4#7XM% z4!>)isF!5!QFd+yqFBr-Ia9u2yjX!fCM>b9ag1mZDM`|?r<>$~n}_nYUC-CEuWLU1 zd&eKqjeEwLuROE!*thI~>Ez=Hyvp7QrnS3MHw^TgZ}W+sHTs#8T;|y%`4wa~|LgPn zH{Eix@`2?jA#QFH5qqAMwN`BHKv@4Eiaxq)+3@ceKGR~B?eV!G74fjzd5~1rKT=W4 znbGnR)N*^olCgrc#neX2sZG{Dx{6)Aki9Q7oPVyFX2NJ2`H2Xxg&Wuy>W|m8ZT(@3 zcQX1zv-bz}p!TN+-D+j$qi=NJHx3LJB7KyQ`d|BFS7eFYu*6+tiCBX3k{Dl+wR6MT zGn2KWCqo2{0`1TEsFa+YS8dUOpB-$oUB`S!wyW7~S47aL<;JLupixVs)8+vTZ;AY9 zG;4pxx!lc@XWi||^Zp*S4*yD{RE=1Uwr$d_n#UxND&l2kQ+ zd!8`fnGf_{X2M#yGa(|*_v*vHw70B=77@{EWzDcoQdcZIV6ZzKXZ_+U-X^PjAQe=#*Blz^|-4_@9>VT$vcFP zW5$2<)QH9%R=OuOwK@;G)`rz=>nZHL;!Y}3qI>RoHRd0$db1qCMU8pTAr+dSx)KXB(3_hIRd6gewTtKEk6$lHcv3C>rdRF#ixU^`b=X1jvJgn1AV zxQk1X4139*_>^F&J-QiltxYOp9>m>Y5%D1R7B)C*ZI;?*u&^VH`@1*?Q|3VKE%KlY z1eKWWvor3h;vOmGupHSS@5*QgmXL(1eWpfAv|<_2N-jDsJ1grq+Gx3h2cA?SKbv+H zyLL&7HoC@qjy!N5mToHKFXe}%t0lj6<&XsTdPM};l`@#@%AM>AdEm}1?!(euNSR%f z(qtt$e_M$|DzXyC?l7Wl)~>YAuy&+{(HZil^+(Uf$|thjz~8oO<6(>_vR%jSFz)qI zhN(v%#Td0QG-_#dszzjK#EG~MOQYG5KSAGA_v)kAeF>Ie^n#Qq+i-thWq2nGyVkZJ z!xG#bMt+j?Y)pT}gS^l6zir;fCY9lLaj%y=+@I_eiM*(CD#MFn2}WcnA$>WS-dHIz zDK{VYDqdJSw>>gKUE(xZuk%*YR$UmUcFQqI|2qFO?GBD@rzmL`^KrM>eFCD!%)x4x zm6P>BAvrWe)7s!`4JEBuQJ(PNhJe6T(W;06>a@9&^?X`BiY)ivsjUQ7bKyP5r!g!+ z9=Ot%q}0QnN{1ew*{=Lqgq4@~$AN0*n2EZt-(TA9(Ee)YFO&3kD~k}1m9ce|{PXUz zn`^TPh>l-F)lDBF^_;1HX^1ANa#m8d@6N?fcFf9=7PbS|36j+Nbrogvjl4Wo{mu}9 zZ9+7CSClhY$@^C>zVJ#M`>*;0_5JvX`ojC4tY|UfnsfBLASEa^7oT-BUf3@|{U9ZJ z4eCIMGJ8TC+nI7+IL%la8KbiN!}U2iGHL&PiB|Qa!}Ri5vy!ex2J}_#PMXOqyOIP1 zo@Q(~5u-XU9-(8WK9ocam9F6bHEXXCCCF$Qm8*V^i{H7n!&1_O)^d`9a%wx zh;DOfgq|bqn-wY1twTL}DZkV;Y(ldwZ0z`GHSq38{i*)WiU_1c-xc-jrCk1*%AB3! zgi{&R?&cQL)Chfy?)2Y()Q)lEdMUZ(RCaAZ9K#aiha;H22Hea~^?*Y3_7qWZrduMhmcx~@AcisWgJhzZO&p_p@446rjeiekhQMLiV-OsI$iQBk4< zbIw^$!HnU|Y&XncI@5XPj5&MetoPOIxy#%4dp`fs$L+VPI#pL!ztuCj5{=-%Gd-2> zvxcy4)A9(2{dW@856PkW*J6dW842;~p?=}IzMvE#dQ9q~w9cNxM(ilS@fVbVHkjt_ zvwliqhv6(X@r}VXu-&WOb52t8goWz2dfO`5l;M-Rvft0xb8I2@k0>K@zDaqsemAS>P=ez~ zq5VKKF|endH^;0z!mex|Da2$j2Jq4C0q<2JOmB3^c*AsJ@q%pbmZhxv#Sp<;YFS`z zhQZ{hkhM&!kT58tfp>`heY3%)n(^9^wR-+5tG{Nvfav2pFC%i}7`@AfWg4RCD={le zGP{nuS(Va39P2`@L~kj6^;h%4=))|%%4h+Bx+9wWs}m*7vr231-QLk0OW8k>W73}h`(>~+*)Q@5Aq zbZ=9P!GN%_=5FQobf44SUvJcXwT3m(w}gUso4!}=Yj)lmEg;?{4{$%W#b5u}e6@yX zNxHV?jcG&t1M|N5lle!__3mr7kI+NHR%(bq*%VcK?I^p`Y_Iq4Y`6K;G~3;+vmI-a zq^+}C%8v)-WBcY!6l9aw z!fdWkCC)rIAe!SZ)Vmqh@epO~bYE=#xb;waFWEBYHW|%7)ySClx1T;^*lG>s(H;F( zM|15Y+5BX_I1_1JaqHYgG-a~VpIL*3n+N=7w#S%zY_`sDn(fT`Z{iyKczifuet@~s zvKWrP^uAevkDu+QU!K1DKU~fx$0nrL*fr2Rcqx5j4N9R_;%s+N7n(~fOGzJ3D+=|+ z{t*#0cg@zhi>0u4ab(GsEbPp!ULSdPn$=IlyAX_W)4kfJKKyQ{hpgZei(g`iuo!0? z@=G+UUxGE!y|Y7YZuNID@{2Kc@@lmlpIXwJ^I`ozvBBhp<1gCBk=pm97=5p)q7g~A z$o@Bmoc6LVzk97PZ{FdXaT8~W6d5-^{^J6*7&;H6(|G`EqI-keO?f*y8+50$0k)RT z2AcK!foS4|rwrh2h#6+yHq#Xm*jhT{XgOz`w|6@6VRR}w^Kll#Umj$JYj^2XRR5i% zVNH}V(o5lcE)?O{=Imuy3bhgu6TdX%cj;6VN2emx7kfcOoGvw(*T{@#&0GG(=C~wl zF(X6uMfD13!C#ZLm3pWim^Y7x>^*v)dhI|y>EHxrS1em#f6g6|q&*!Hs(%|+P{W!m zo(wlUnLXsmU<8VM5zUB980Tp6a5SsWNb~Ccue{o!(JVCO1;bxZ2G&IHg^%yT+dZ4Z z!gm!AVoT&%YF6(xUtGNQzJIu0ce&w5|SOf-L6`8za^;Dp~t-D?%@S^sR9=&~nZn6_@wt=Po>8!8KwTmZGzP z4NYepVB;?H58z3r_3XIU7J>aqry|XIj>4KOry_oVPDT0YRD{y$RAjRfC{L2ElpV%< z^`F5KpIFXnHtEP0ZMb);R%LLQ{<)DvBiPV)IPWkmmX(g&#qgIBXQpayXTtPBx4vbH z?P!=Wm_M#Piwz!m+&FXExW^~^Pt{!i4%O}cvD2_7dcn-A58n|T&+NOr6A-v2aIH{; zrMoYGe`*FR`S*E-zn~11O);_?L;2z6vl+XwgQ4!&yJ9=&Jjj>Qd9WOv2eEh2?qW|9 z&$3-VzP3#Wn-~5@VB_K{5?AdEn!7Huve{UgyJ%~1?&4aJq}~o)xHZmz`vhu&_L2A{ zbT+VhOSl)|*#P|&%jO(w-JQ|r#NAok2T6vk{Pf7s^G1(M^siRGs%uPN?>CohcqP+zG=4DjDQs#51Z%CF1g*(a}e49|dgHWXtS^EUNS z-qBuLfc9GIMOzdHV*nU)pznsK3{aZW9+kCqrYpwV5KX&*YH%qGo`dE7Lox0@yy^Y} zV||!?hH*d3ZH8jpX7r}p42)S~JW-4eX8U$l8q(cFD&0+B#1zl6WZ`TPR?EGC^8V+& z0Y+;v_9`Oi-axV58(?%9Bf?^Qmty+zLyA)$qBu21&oNGoQEp50oLQsi7{^BsS)98R z3uo3?INnX*y#d}Q&^N<=-hULJ$Tr@q;Qa@+!?KGSad=Cdnt%Ekr^Xu|ykimf4~ijk zBZhp5V#s)-gw`2XuqB4fo70$Irx-HchT#ns-hWwc^|^7YUy^S1@s1Af*hB=~(R1UD zzC7Lb;msl5_TgP2eM#UzJ}!Cvdw-7ioOlO`H<*${_vhTWKQBi2=XlGCXuMaYnB~$G zX563erTcTd$))>q+kLHw$a=Dg1=4MJ8r_ED{W7BQewf~xTzTJY+=e%x+i<$|w%uXl zO*P(C---#h){EfZ=S{%_{Z6Z#Q z!4S$vOef?HVJXojP9)xv!F0Mryd~r(VJXq>P9kp9Rzh4R1V*`V*B5Pj3h}QDrjwx+ zGN`bWxPMTK6>H0prG=%$J<8z04I&=dbK;SqB||$X+FgUAHtZ)?4Nr8~)7Xc!e-Ize zV7D23IOM%yDeObKi6hRP!JzXX&K+{=uoU&7jf+RTaMIu4!x_9db8;JGP%gBPqQlf1)av6-AhVu(UjQl7ISIuA!;5^0|N(_jfxd4=L!K_}9 zk;j6iaE2P+|G00-Pza-Z1I#PHQaD2;X+GsL7d=x@wjz*0Cv>1$9w^CqT{EXgh~%=3z;JTI#ZBcBUP;hd&heaa;> zGQ%!XE}8WVVC0NpDV)=mY(PspjC?iBOT$t)r-_S0bsH^jO|mfe4NKvirg;T>Ga0cI&S|<6hFnX`mc&vxr|GMqKl3^NqF%;~Oe}?SIwxmzGWD|cJn(bO+ZuU( zMrI(+X?jVA@=}f79Y?)vJvIECSC;dDG5bVM- zx~8g(=S=IYG?>!jsc2`{OJ>K>(LB%RQYI{Ao%sekT11>%dB=kIHn58umcrHb|02?{ zlof6Cf{3tcmG`ryuWZ?pRt=4w77+=i42xD@DEkac;p!3*+o!L!AdJ7U6s|52AuSHE zAYw@tmcrE~B0kYr8@;=mdKpXM>Jkw@26jm|5a+3vu@tVZ|3SD}5m*XWmx%aG^T|N$ zA+4|!t}YQ_w>ZRth^LlgDO_D5f_l}0FnSkD;p!3*G=dg{F@ji%MzgJv>HEK9PP4>< zFlGss!qp|ppt);7(A-VOQnv6eQt*m`N2;LzXWdDs;n#HucySW z`j3o>QJd4p*Ux4dbOVGjedK?j?S3mvwy;YisFm5NZigf2~ zAC=+w3nJ*>%!>Z^Hsex@eQc5`SU?b(S;q!%HY^C~Vh+Mq3V8?rKLUTj{y}a3m7!BR zRB8w6i&}|@%!iG6MZ3!UVHf&(-6GjN^NPQI*mafGFhq7=zS&<7TC-AfE79EjRieMX zLR(2A_~}Js-s)Q=zN5W}sNT-Qy+o$J-f8Me0ZrbLTASOeb@};(y{uwwPxmEf{q<7M zS7|73c+IBnjhFlDg~u2((LQ?;Yw5X%%^y6RBVz~AdZ9M%YOKG0)xnrolVe}ASN8pQ zz0e6V)`hyOi%Pk7>gKP%D{5IE`OdI2ueH(3(=zom3D8_(_i1e%|Mh{lb3xf zbDXVh9mtVwgy_og72G%0_t$$iGPGLrbRfGpVxsW|v&kJ+!2R&q56Ntw3NVBBc2a`kYAbu>uGE2C1pP-)R*4^OF zxxyKlG>`YwJSIzhbG2O9CyZEw0xN8@1}5j0DpwQ)xL0)Kse*eVU%QAjGAv89K<9`0zgeCNG1 zx&4Oryn(lapcNvpCOQ?p$|cuny_0pWHHIVa4H;tCKFSzr;-Q$9R^SUadB|4|x@9Du z^w+!4TZ33{|8q?;29Ql`al)|F<@{?a0sZRnPxp4p_)F&%a>j>LfBiPucC3j`UY!_ z*BLubhIPlmdgnG&GxF>qE4t8VM}>WzlpC&3S&IF6WB?)qmRI zA2wGG`ehosab}dUf7m#Q$W=r%ap(ulkk?FI&Q?DRsJd}6e?0Le4!!ovzcFqjz&WUJ>s(lNPP0RPQzeWtEZXJ!l8zUmZbGd;>5z zUQOifI`t3`C<8rNNxHi|_ko3T#`614X{_hlI_{1`{Ph>9E3`^uquj%r2k568F40P} z0q$3whUnev&!;tL{P}|rdc`!h{P*pOvUi9+@cC>Fy-ZQYkt(K^QwY(ql0`;_RR*EC z6-_cSa%7B(E!Ju;A)1m_C<9xI+EV^UzJCr3n>&{KmlF}GHLLPT_WpWBItihM|F&Ze z$;kb`TG`r!8qyosdtLV(AVi)2XobCt8q#e>qI1hlgqZLj#E6JB+{ejZpI(2Jh8kMN zqm^|$uuo__GOXi4Ew}X{y}eU(S*v9v;}4R7{f=5;AJT3x`qlndgm_*-91qf+TW6(+ z$evvF;0x;AxYB9H+_ja$c8G`8i)DDfmt}d` zi+=j#o~w=XneBumj^Nh|RS#8j*~bFuwZB=* z;+Kp*W$fpvXX=;&3Iy|G4*MAXGNfuMk1Xx4&!JU|7K0GJ!_q(1>CM0FFC?^MYFcUT z`VTS5&#%(3CP^B6PLiMfHJYb~ivAUPFQ_4X>2GP);n)k5Gs=U6mSZWje3YBfIpA=K zk#|@R`lc6_LKz~0S3lvF{Q5RK!`4H+}d4KmKowsA%cMH%hR$>vw3d-KDC3JK?0>|I0?M>t@YDeg-o|K6#EFn3Wa z)RsC`m$20a7x zivCNq-HEf^FaH*xH{W7ppDl-a;wD9Vv1YR%6zq1elf!-^kC27E&Px9pP zp8U(YqcZ-2o+bKobo+X-mh$kNGw+aiNkE{tjA+VnpU_Zl_hS<85z)$wYYqDi{YOb^ z9`mbwv2Y}pS}jk>lizpPm@K@68%ImQgpg}T~?^%WPZ1BKQsP<>zuT; z`KXd~VweZpu{V-0oE~W=O>7nb(HP^9q`E!7uv#}f__?xYW&8zW4p@_A%=sM}^RYDM zG`2STfu%6ENQ{)BjrqMI<$0m>Gsbw>w8EIBh@hFsjhR@JW+MKAHVS1M?&|@Do=d`+6X&joC|rJz+|4hD57?4luq9Xu zXDIC-vB%|hWJ^x$&N6lbn}x%bidKTYG*0%)p7xIr+CR`Pp=Cfc`96i?(f)z^1j<9S zBo!|j&sLCaPa)e*(rr5@%EP^c-s@{#h6mC9agf@9`yI+dv?To=b)3DS@%Wv_17|hL z!#$C9XWGw~(*EH{O7qeSSf5IN3UMEdk^K36e#X*mBlNuY4TNLLT6wgi zAKN^Ea>F4j79%%eOlHciNy>}C-AtdaHe*;9YEo%HT*me%WAwwG%ScB57Ou+Ux=YMY z7B%2;-Irzb-Zeu1=(SQq^o{ok87W`K=$+>qh|=~&WV@9z%ltG!KumU;p7Etnu)fy3 zOvAhx`fm94Jo1WL?O2$@M2@8}+g?Q69pkEu^=c}2T~M2&bksdhwr57(Vj=qJKqI@q z-?5kS>(V0*HwpI_WFUG@3$KiiHAD24iw(rt-F9;Qgf=XC@kEZApoU#?_sKYF3eo#+ zGZ1Tif5<&gCCM>+ygAl|nw+bAhTo&NMQ&_1{KT}+E98?$TuejehHW9q+!aHe$Y4H2j?Eb?@;ROLiyMDjHGe3vw9d!dSsz`O&e(W5%L$^?lb)hEqZHFHA z?Hs1(4Kfft?`fvLqT8EJO^>GUhv(FV=pD_24i_I9rn^iu5H96(w@N`Od(nQ9@Ja!q zU)>*fI5;*;KVm^_&M3udPxq5c+>bD{Qmie+dPS`+DO=2H@7iv=%EfT33lUfoy^ddE zQ~H((UMy{Wq@k7VWdh8P!kQ?HZitp%XOPO$Jthe}k4osuo6R0%KHaArC;Q=UwPaW? ztzh>Y>tlK)@oDZ~%x(Yv)mXLeR{Mbntch&<+!0JZ+LHM=j5Dl{yVYKieYCxbfEjg? z! z*>)$4^&*}tIC&s_~$h+Zb5C27U>JZ$Ap+m5}98IIV~6a#4B%2O9?GCvvEK$s=iauGqh z8vmPiwJ)@*;ru}jv3>Lk?QT2fGo=liMz$U2DAtP_(r#e)ig{0}pI*tyUszFyz?vv( zFvgV+@7+|MLwgjiHPjI2F}+V6x550!ht@2cY&))JtQS`oy~#0g6-)Q2ZZZ!F6RZy+ zuqL{@^ZLR3GLq!`2faDkCDahtyd<3ro}b76ZjpS%KG2>LUqNy%N%@rcuP0OZ4 z3$`6K5fSF_YHaQDIdTl`QE2s1L$r_dPSNd6ZjFPySoPl`1xt-uk$r?0fr|9nX=-$> zx?7I|F&y^{)PyvIoinLRX?b^JKl#bM2tg}ElUA@h@3HeWohD0Nge*1Ig___?LG-TL z>mYgW?vm#8a}$K!8PT}6Qx^8^6SAvML3t?cIJk$SCg?vmny5_TnZJ+u+I3-$6}iwu7HIYwieH`Dv-q zyF*Ww*1XN*q;Dvk%B5tFFTm=4=qGr6sELT69Y<+QJI*QEanLtJO~^8UPu`ALw}_8ohqnYXc^6 zKGxIp@iN&ghyvp21+5+3$`r50pE^a$`o%WFSq;%>i6qH&uN!Z5zJ=`Yq^8kVwp|!4 z1D?X@rg}n6IXrHGJbZD8AmcwP82sH5vl=nK)*Iwv6UGP#T<3@;=D7&`xR9cedPpP!9otYX#AiAssMDnGoV>a=K#aU0d7`>&0=RFB~=V zSE?Ur#uAlVLL3fH^djON$;hM;{6Hg!zaWCf#wMFi6UD13k7)!o8bQ#&gat1 z#;J1D#}L6XU@36~i!QL^FQ~7&4DKQ9Q8*qVg8GU_{_HE9aX4dej?qhn&HTBwuMmNA z7ySoGicK~to0~2&`;;Iy$I(PBdsT$)?)olsd6gus?7j#+YybPq>;}o2)0Z&4B>zS^ z4X$fn$QM%DvdrXx{Pw<^f*2Sk-c4_(|`nT8C2M`k6uB zGZDRbeUj#OIzq2s?*qx0y|F$w70zG}&sOF5h6uiXfi=2YxnzSE1dzsK8iEQN1<;L9YmqRM;lQADsqWd603h*Vjz@D?Rd}K8k<%u4@cdx7vAm**TO%<>TA6WL_UY2ptTj?xibWPOk}J1S0paKJ#EF5Zrt z9yMd*=Tzn>9nr@&1!+B}#px?I7>ETMI`HVhC)tC0Uxb&Y5Pe{6kalokoL)A`K)ea? z4@&72WoZW;`Bb74Mc@1o%qoomsqh?j~Tv_h3GQt1GSXtak~9M z1JU^0B!2OAO|$*HX3YKR2yM>&SUvlCDGfCd+ws9QlyB_g!h$`gGn9@9tchZ;%l-J< z#%r1TfV~W*BYOIuBQ%%ivHH_0#yi5SY-c{I=^d8d>bmj9ukAH7eA5eSlB7;S6M5We zAGUW&swsE>QCh9BF?zA9)h`E>))0Na&nWF>WQ;z?y8_8*n$m?|;rH3LMduj4A%tzh znk1>vFh71{`Z~6)@m~4JwqR}Gi^=+5zg5&wleWqztz1Bi9yZj-mOVRt6nET^!SXk_ zZ9?gYz?vxI&}k_Ds$F4Y-V|XaT}Em9<74!Krz>cPzIHZP3wl3UPjYu687VEidE&#n zY-HRXRy!+LJNt36zV@Dz@OBrzi)6eV-Gc{u-ena6IKy919@a$p1{>@03KQS4HPeeL z%_c=@W-US=S-q@=y2tniYr)x*^{Gx3Nvkbodhi#Qb8*+z^JUZ*5m*zwzV~$?KQZnH zt8pNo8KoooXvJvF_hf{A@@iRxCLRX)5{ z6+Wm^JvnPkw04rdJAc_+PDAvACh;1Z8?JB7DnT+ro%`~0o1d{Ei)J!>R}I^QHAzzT z2QYJ>s;HzVxN~m&LV$y%RKjN~pf`x}#Q`Cus9nsP6O3kz}+D9m8_p z?!xOlD6AxTBx?4TLUp(C1vS(}Y{!qfm3e?mJAN>4OL_6{iCV49PtV6V^mK&dlxRlj~&uXi^W8y48fM5CO9kU{(Po4uX8aEztYD?M(KzU z*I>_Y75U%>uh`(-RRvpuXk7D>G<5egb~ShfyZ%q0f>s9GgzJ&G25Y_e!K#$aWYPr- zhjt#V9o@04AHkb!zrgZMtYt>&sJn=;zde*sD!GdV`pyt`14N_MrWYN8y7HL*W0*sQ z!V2ya*e0}(q!pdfCRe!4zV65pb~V%l+eELC#Ej;DT}xvtt2SUL9TDQLR`K`*{${~Q z7I1oqusb6fcTrj&^ri8ecQkXSv>7t)+t?=D;UsC%r!G7`6L=z zL-}p{1A$l242S)IXL-Mmv(?bPs3DM})Q0~%>DDKqvqTA`)c^Udq*e3Ki z=mdGSBR{wP23x=%3GG1N2Yow9D%Q`3pB*uceYp2l@W@bi^Z+I4-Y>p>D^qrp= z`faE?dYSa*z@b5WWWrq2)fOLwb|4x(S(5R=gU|1Nl@+P?TJT;`cYM`Vk~(bi;7Yk9 zmfof$N9m|LdgQcoelqbcX$Q<>9O`nEj%f7y$s-%yh&Ro@)wIs7HAi0^(Ri|;$hM0I zFXecK{o(SRUK!6h%b@Of_94qKpc$WBDVSv}uP>Zf5RE4!x-ofEieK2>*_^+;mvAaV z-SHGgdu^3l?A^wK^8I%KT!OO`>W(Kp@~`r^@r(XxtjgC?98aV8ekPuf>HNXV@oUG! zSjzBr!U+;}7ZIC=n_1s=tIY9vf`n5l>W(LGNm}{&vbpT}L#CrK^x_+w^-*^`-BY&H z6jvU;cNcs6vXpQ>7uo@DztR`kW^&e}eH?QN86rdtP!r_4Pn&|BUR z7eU=I5<;y0!0&SV*~?5lR}JJCzd$rbTj)EZWt;O$jndiP{S|~r5o&_*Ao9XXk7Wx_ zn^~bE!-OafBE(3Md~&J$=eh)@)fpv3icoiqOwoHXT?Q*YF_lfzf4pZH3mftxN%Ol9 zrpteR$;3Dly<+|-pK_*VIX-ezIpwrVqUN}Aj405-K~-` za7`KR>t-+bKImDBh&!$oWasu{xIS!)jD8e)PAHppwXtTlMGxXP9rwARuZHN^`zQuz z4%G(@H?%5SSLN?wit`QI)(CGdBf4sxByH8YQ2m!L2I5Y}7y0&bA6~KNIQhrAMD5$s zP`%3CeA#rIHDyV<|*ajBL_Iwq^8aK5Do(L+OaV z5S64!2N8qq#4leB5;L-mXz1qe~(ctxdYna(_LRy{LH z$2L7uk~G&lp?cqq_Jp|lTUljc!*0Cz3|BM$a>+Q;9+^xpTsX4Wz#Ya?%k>04%hr?_ZV)vfaNacy{X<#HUQqwXT&@X@|ZyVQb5 zU#rJ!^_;3bnh~Z)FO)Py&pDE;y?z^}ZwfTNa5QLZ6aI458&+O(;P?_WzDbQWNm8kO zev|>Wl=&Yz%uqVE6h}k`=41bl~m7{dr0T4|wvip*fVam)K*M0oA9l`>2=Ct9eI3)BVYRa8o>iV-7%I$Hx0KRu`LaU z@R{{CxuJB_9laWQDSi1^w||dD&;B9udkmX*IV9JK;Rh{&x!Q9@%i;~k#-y8N<)Tl ziYRNdYK_x}?YfzX_2Nl}WbD}{Pkpvhu5~LwIOEhiG)3EeI$ZBG;sNciIW-Xjdt_Us z=;>ba3&+YFOJTj@X(IjP043t#GdG8Rxr94<+&{1;Nm9o)G=H9!BL6~P8AIvi$46?F zYL3&h{}kIqHgW%B=F?!IoSVMhgRMn`(CgAUPhWndx|2L-%4;F|fxRmtx(<%uDSK|2 zOWlf=aW3KbMV#Vn9@0 zD<>olFwf2k<#VS^(H;he>&JWkJ8CD6hU@)q-u%x9ChaUBZ^&}x|IDk)mz9~K?QIdR zcm4R#QfftFxIUmlw&mYBX#L|}xo*oY+++JU*5VVLu)2ono!@`SM6@XT%91SEJl&7a zoji+eU7Dy3-WRF|y~?d2dcl??ZD(kh-m0kK!z~NkENAx%=I7qqvGB7~G`)GKem1s% zhUhdkNh^FdRG%>0II;9I)s^pep3I#t<~N;QI$67SEJR<^ps-?)7mD=na*Q1wPC0}ZJeW4H)XQ6=VXX}erFNE644ik7Z+lUxfSrOn$TcFNcej0cFGOpC+1yf$c6xi!C2wX}k34NGC1Ns=n}EvsC}bmnb_ zND7uhuSP`tF+E+*EL5FO9$R0*U(nW~Y>J)_E34#Y&U{}VNkQFF2FfOa5cRINT-vNm z+$rPOV(*H5wYcv9rFf}SHpTHc!cF!B<4ys5p5sJLo|H}lk9F9+1=M%eS`U&t9F9DLNxB8bRV@VOD>)4 z$Nv~hZ!W{Wjq??EY8vzGz4Ad*7e0H_H-^>{(dZ3O9?P}@vV4?o0_N5gb^}DC$3eV| zN^9k{iw2k%lJA3lBHDID6I;FO?v`Ka9hTkn){A8w)TA%3nSKbKjHs2jZ$itPv&Ztw zRni3CM{F&vsGl_vhvmpwmspa~kKTI0QeuxH;-US?{VnM|nGxmF1m8y-HAGBWbE;(n zLaZYMmJ;U@BEH_;zF#G+wp31ISW2AXh`1uJ+5eCbHR)v|EG4cxL>z6^XI~T{hEvP2 zlxPhQF{e+tRwD`V7a{(q6!@Y!y&E&W%6=;XEtxnoP=?2+Akf~LYln};sr}=^^{g@_jGGNLhxOv{WSgnRL7BS^sbjESR4eNROCg$Wu<908&c5{I znTKW?tQXbFdO>u97V+xR+2ML;X0UgjRPU)=$e)*YT^z{pyWw>1w|!|GYoh$9zqgyK z*T2H<6E6d$W1HxlpysfUnzTum7yDJ=mGd=HP&%TC0ijxXS#%#2>7vX`smXI~NR-P= zidUbONc%dDLCRT@PP zCnPn871sQmHG@rMla6R&K&Vz`9p$*!?WMHcY0uyO=wq;{Y|;@;j0-h~ z4_Bo?Kcy9MSjG^Cg}5rV@53Xyc2=-z<;l^VS4dYStjQQQx?EuerK9dwO{3IuLt^w+ zLkwPD>Z)N%r>O00>4)hCyUivY(bM~lQfr08=zm-`5WiInRG!TGi}lW3$6&YFq$7Hu z&nWffB$Cn7;3r-<)`1M@*O@qrTW$Iu)xq%*=nvPgEAn9?E+B-QR@z zBAPf8s+FrsyzqUam5u{TfMbink%U@ogx-ZW|=wqw;AU#0cp)8#wOM?=kFU=KXsQL#I8gZ)TsN=@jtf*1>6^tx=$pk@ z6GcA;H&Q;o-(rev*P5I9hpU~5*{dDRrJ*JipHXv|ft(`m%AW zHILPx-vSKIglf%QKuwwy4p(D|*&lhskdb$88Kt*-Gjl$>?i{5f z0&9|_RXv(3lMakxQyyZ^Voj2C-S0aKytB--YxO|>#5qarw?9I^viE%^ zww7X~YEA~vh2gR0$O${ledk6S92Q#(5rH*PzVnJqx!~f7OkQWne6h6y(b?;g)TlEN zdY(E)CX#82t5W_avnFzKvg(-~p+C_rUr)BRTx`e1j)S>fXJ=D+hY!sCXrfwWO@uzb z^}9?uf2vlt2;KInIT=+amn~(Z=O!>y^HIiKs%p!q0!_qr#I+eK+aEGBR&^&^M2ztSvwr?|3y=?$u3aFNs-$?LY+9M7hWt>nnTnWw3eYstPjb{#3Po z-x+J7{J{oaP2F1UV%?m^aFmX15@oPuFPIeAmSxWr#~k|y(G+hFHF4Lxi_B~4)#F$S z`v-enl5+jxqI@m3gVi!}uwd?D%f)s~ah@x$t2LAzzb&={5m*zgk9W*!)O@O~tBdlTtKN{K&U`e- zIt~@q2kI^>%OR8yxw~^z2oX!SS-$E7TqBiX^>iU}h62UrnWaHMC^dCaj6>?k=`d z3hvR^Zpx2BYl)g*n`Y0&5}$_HRv;9i~2}vsYRQ`#I{4`z|q^8kbhOuAd`&Mydvv)3(!Nn{ZF0IGl4Q zrSw0SShLlS1-}F}!JV4oi6MQJ6NksLT2b$ftSy_*fC$kqSsFS>aevdmeBv?1e!#y% zH2Ohwm+I%MRLLqQm)-rEq34Bd!kWkfDArkd(Ebj+0)1U*2YO5B4HCO;i=R?;#ai~) z?%xF;4s}PLk^B<>P-S8DmMrn@REC}&>W+S?Bpp6CNf|n-ruop!W4lh!dU_g)!KTZqQfB;{uG?WOFcY^TbU?S#^? z9eCcQF@H5c>F=0}&pU5##WRgu8QX~-b;mdgegEUCyYkwx8ee|CmXTv( ziy9yrqZE?VF7=C?5M7ryC|%UZF|ox(5RH)#Nh)0TnW?hm$Q|GJGH!Tnu@^*Rw1qs& zF};){>EBs&zbQuUk}Xn%nuzTvS-7%Nq+2`s>OxByr6U4sqUd>YkR1843!nR_un;Li zG)AT*=}XE5wxQ{Dc5gyAgTHHwh0$GzYRwG8I1^>8_YUA4Ux%) z_MNIeGD*GNC`>OtB9~@YH(8z5Gfe;IX)aCF%KVJ8 zfxI*K;2#)D$5MzUCWoJ^JgB-S&t6iNqjW?U*_^Dd>r1_BvZE7ZnVF51o5A$$(!+K< zh1yYIS(rY!-;Yd0=c_qYjdCXqI~s_p(at>4y958_z$P45Xx)} zzs*ozM0ebqq&_+sss~)oM_Sc?-CCJoZ_j6Je$0GpB&)l(hw3lN<=5_xNmiSV57oVD z=GR_*PF8h#ORsvKJcKwjzqPV_gFXLikMZTCwCr^}EX2?NUM3C?ZKcv^-QV`nQ9I=u%-1!R-|zWZYonp z!C%nYVNJB6nwCxXEjonXPI_!)DA;ZRPb zHAGV`Kx`*v2r&Uue#|#A6l{@y>;*)VR_8sG17C`8`_+pX{(|zbCVCIx(K)$t)(GA^ zbAbt^W1A37Uby`|^DlJ*`SEopWo#k#6{3kXNsQ%IQN{U>`o)Ca#r*@(WT|J%ig%M@ ze9^?;g;|1a!d@U5-P7gb3+bKh$suNJ2O`8-(se~4cDegFe!p(4&<;f7tfY6N-hO6( zcWuwd`Ck+eINNdEQ2u$4tMZq#BVXqBm#}J46P(Ay5gxHaUNmqxf0dTNP&y*SRl8-r z6DxIYG7tMRw;44-G+GJbetehs^MCsBMkPQdDdoYmId>Z6V@=)1kq^cDfU{uJa2HL zGw*cdn6TrZ?pPC@?&4c0n`6H)cRM?d(y<-5KT48+Orm@tT;_{ooj6KIH14AGEukgx zti_AYyjVsdjyoBmai=CrEqQT|-wN{JJ$(dksqTj)wIJn{c=rFEiTf_yY~E|AtQ+=_ zWw@0PJOI=k{S|s4Ho2C(xJ5bM=7=Xp>8Lw;HImfF>kKPD&XHgDaO3EUAR0X<;;;>&Q6qX~a}VY2{^X=mKd4p~ zE21$zLoE+(X!`JzFNzTl;+Lpaz9`mY;fu;vz9=z7R4d~b5m*zwM$%}V?71dc?$j$# zh!kOD0&B9ciWMuXm>43emAQ;w2;C`@bu`v=w}NsBwB$<2N;$+2E6 zh1yz}=8*SaX3oJ?D)d%be6pk{lLBw5eGk(Q*LjbBCq?ctq_O9(Zun$ zaJHG1vyHP_oP9Z~fX-0^+wzrnddV*3D|1{qh{m--Z&`GAHuWNoS3GgNh-al*xtzwD z09Kf7r4hf~F~RK?@yNo6M@GC1)ym~G5INj2M89o&MZQ5CFM}^iJS)}8Nkw_Mx+JM} zWjDD3@yM1DkBrzNs+E(9@(@k2S6@G66>+@&+IiMsg{f96aY>LTD+{_;K3Fd#_vNL!~s+F^iXkv(|Ieco3-qC-O=*M4;n`LmL zR4XqW(Zmo_b2!@xclNUJauH|S)Er*8Yvr}9_~HTP>Hl)PZ1a_P zU8s*jE9|^Kr+ab$I&adQ_*jmx2!rdU^{a%)vGDd>az6rgH{e$a~z7n%Ei%p&3$L~bU zGB~NWd4>IhR)X%;Mr>vSe+}lpy|iQ4LPVn_lB9edb=g|V7%?5lZ?JJ~b{ElT?TmNs z3dy-C|Klm;f1rIuG+I>ZU9#j1k-JjPh{5qNp0}wZF4TtkCYW zMoyf~L&m)i(eyp9DsHj|<$v_0{14o>Q6BEQbShG>$O9) zitQNMaZO7rQx<;_dz3sU8%KERv+XSnHttqp<6%Haq@?-Hx{fE9rrD~=$JtR(#(j9UPz literal 0 HcmV?d00001 diff --git a/ros2_foxy_core/fanuc_crx_description/meshes/visual/j3.stl b/ros2_foxy_core/fanuc_crx_description/meshes/visual/j3.stl new file mode 100644 index 0000000000000000000000000000000000000000..cfcd596d2f7879a610886ff2e792fcf2cd3271f5 GIT binary patch literal 208384 zcmb5X2UHcw@;}~Y5l}G$MuHJBfs$sL86<-Q1pzUlqM{hU2ngnYVa;*Pao06tf;%m3 zj+g`Hu;#354!`c}yWgqC_x6AOob%3`wfj?{ySlonx@WFWSV&l;l$n`XH&p518yTpC z82^L+1OMOu??1na2-Qk9NSO`Gkl$*@;CD4Ge2$$wX-JLfsP?UE;j?-3N$Ja_j%qYU zK124Ll=96xs|d|)e^4sFak$s|LhS$E zT^@~LFaCV$nZ~#evF@yz*&rj2FCOt~8~2~ju1@h> zs%@*J=?qc$dlSZ^K-HKYzV{Oa1f+z}-ZN(jwpIbZ4! zB#{a2n_$Qtj*rMAgpKYvHoDW;=)y69qYFnJp-iuAX;q*^LPs{ikS^pWB2vm2BxLco zJSI1Re6>bCPfuJ{>@sA^M>k-=IVEw7tMU10u|-P8YajN!s@5!N#=C>^jKxWW_cFC` z^owoLN_c}PDpE?FHCHO!V}m_ygN-~cmZ_$?TGTeub@eZ=p1WdWe0E!MQ%M@!l0CPp zy+~T5*>K%9zfJubs^boSVb9b5Tqq5=9*fshDrH2#UiDwOs7DT;D}tC@F+sZY zB^iI}n4@vJV-AO_zh`we_S&5tq*`9+W_)(tBOd?(&VveIQ^u{FFai92dhcF+85zxIoDCzbSwia^L`j0E&gmpI;x8uC%bXp3kOE1 zDX(YjN64-Jc*rK*=2FjUK2OARP&+>iy&^F>m$w19Dv{7 z&NE7-)3WyIur5%YpEy7frOM7-C-q+Af$w~5YUGj2tUbh{w#s#~eQ2d-WLGmjH}6tk zy*3}Q=N5-MNux>z;xA8Y89kh-1xm=DbxL<{&6YYotAY2Wg$O)&uVSvJ6#Matk;lGo zSCo&9UD&hxz-dzLS=I6KnW07=dW*GB@>z3rS*2R4$YcMUe5qgV4f*QGUPc~}Zt=25 zl|w#mMR?5adq%2tYP_6(eW(#3ZIYC?JED!f^36SzD!oFC&mVGTEAU8%=|7`fwu5x*dQBz994p6+Ty=;+Qa#pU)_56A}pen!nrwD`E0_7ZUn zKWBfD4*ame-9iJ6JWM_uBDjRpOO;lSYVM3*xzsb#fI4P4dU3Q7VWP`>g&x19)V%9& zluAb&3cD|z?-z`>AFUzq;E17l_G+3l-+cT}LBAM?0Edl?n?2aZY_(qvj@BTo2REz@JU}A(W19O1+;Y;rNT1;He>kOV#B? zJ9U=RHYSx_o4=$VI}-5N*MA!kCc3ZeBG;wae&ZluD;Gvdl8+`K8e~KQBSzlIXMwRF7_5)$Hx>ayk0qh|cN_kFp9v z^?ff$tJ}11tg96pm z!qKK3K%_*&-br@uHE{K5!A2e?PYn^AlFbDxHTGRI#zT4ZQVIyHj?>$R7I(FLr!pgzDxVsn8_hq z(u61+A~?SeQ)(-hTK8l;t~S3TsU4@vzuibRN@b$Ud$~vWDQgnD8>P|_HBWDoYCV1+ zRp^z$q_XxYR;PkeDmctIJ|;Ab$XQlY<%U!##Y|3dN*8#*=pIJr2)!(OL#o0Mix~p8 zK)Rw%%foLkttkF%vR#hQZF&V;wb$9IO=PQ<_cD0{ z{%l&c9HFn~9?UbOG0(7ITcY5vIKt!^I70UrBbZNo%6#H`lECs?-PiJGlTYLb-B+Gq zes>)6yN8+I<-PQMLif8Iq5JuoZ2z#_nScY?{=pHZJ&He@_79HG_Z17a4{m4s;9Ry3 z@?QF$TA-TtL5|ROweoCt?!HkvLbsAk7Pn7l zar<5txAR`6sF**S;&zVEtz;j|CeE{L0<&y__cF!p{MnREaD;9pds$YL!Lp*pW7;w+ z(K87CY|4r_Lbnp0c^zb#*P<)My?8HER>Yr8nHNXsR&s&mgJW1eXnV?q%{k2CST^~e ze2^n_E1ARc+E|v?9%gwhN0@R>{%p!?IYPIR^(@=&$g=GjEZgS2^c>mR$CPbzgl;86 zS)HLGt21P>Is-?TGJ5`OsxxqeZY9|)3NN>Knp~Pi;k=ir&cL5dQ8-8FR>F!zm{p4Y z^JndI`+7zCYGhUB&#iqvRt%(HZ}wn&t+mg+R*`f@p);>46+ysW5dA)>1>M~GDnl1V zJYuwZ+4s%kbfHdqU85)>A^S|eUtTN95&!YK#%Db*`8Pz;>xld}7Xyums$cB6 zC_w{xyG3R73XsZ-`6L?)j~*1sM@q z?Fspnvi<)*5GK3gJal{eHy$Rt;t1W|{taQWD~{0T1|YI{i$03teCYE85Ns55>*LRn zn*yoh(8zrLytThS?e}UtdoGHAwlsWbLppoI7vp^B^Hda}kD|2?oDY4TiX!xu|I@=b zAG{{ZYoxzQ1retGoaK`6HYgvgdz8G#b{5?v6ie zob%Xr4QYba*Z(r-kcTciw3wni^tC4XE*)JIq0f{!=l>g_x9IyI9|e7XEXo5SO#2{5 z==1+?2vd!WBlOxCKxFY2eLd?t4*z$ZH$WI?P;U{}qrOWNMd))YT8utVMG^XXw)TN@ z{=X6WTC?_nK2evpC=Y$*i1YEk5qgUrW$>}mqmQCIAi@-7aD+ZL|AsI{862TUAOD6h zMHw8S*N_3iIOqCI=@9@&=+Xj&anAL%Ca&85Js-MN>lw?x^U!Tn9Nqsdm9C*4k^N5| zM$Pq|UbJ1^j}_HipIbc^{dXSF*TVVu-+JhCtH+}Ml?T&-|G_v4&KmSxOb-^jnf?mY z?u)z9-QR3Id8EIu_xb#zV*=T}#B!08N%>Pt@$hfT_RY`x)YZttbP6a)mBs1m+(kWf{fg=VW!HNZ zsJgU85xTquYRr)+dU5+mqfR2?qx0^a?^kqog&8)N5N2U|wHEL&>S4+=Il@%yvpO58ZwWR5*kBNCSjX4>+Qm zDz>M?3KsvD(PdrH_2s>O8C@Q?n=14?e*F2&d5mA`x6^E8!Y>F@Ud#2+^IfA<{$+B^ zcDMfpValC3LZ3~J7@62Qr`qbazaUKcIY;PuJ4Y1n(Kn}GP_thUupXdSwvAG8)!755 zrO&Ninc)Af*Lnehf#BT2TIjza^tpvK#D7ER+{MbBUO_4`tG>s()( z9N|=FG0jGP~jk-5T_o%&!P(=5IN*zF7UDhpAG;Dd`r&dF;5lCC54R{4Zk# z=SHtmaRk@q=bva9(3j}wq6oc3uiSB|^om|lgl-Lbb&w-;N*v*B;j(+rgB!bGi#R@d zEt5;1MW(EM;F{V!t`$e<)}Ze=BAO$5SDN5D_iUYCMz@=a>8b?}jCQrWX*=5a;ZF9< z5x1q5u1N>|enG^}wV?q|9E?_SbaW$He`@vrSV=gu#D2^Yxm3FS6sRUk{8g$p%wJhB zf5j2{KB3p)enm8ARuagpgd_C1)$57BBDgj`|KLpNl~hhioDWlf-lA9H#dR(snzB{v z%2q8$=%ZMmnpW+vQXOHVo5DtyBlOi-pqfVaS41fDyLFl0UGgy5l|0!#$u{E zb4sEf!muB>i;Y4s2DKAeZXdljfA?<4Z~ z`XiGRN5wrz+s}JB!W0#Wy>!b*C@^`6bnebU&2fAZ`A{J&3$ycZzr~ zQwyids;89SDT4eEde&yQl>e4ewVi=$!Aspq17RClR#)d3{r(9at}rWQ_@ z)pRMpUj+Ff)O_v&DJ>*}I9LC9--p$TDZk?b5uBf1%c83jq@2Z>q_*8wcizi{;Jx$= z0%ic8R(F%u1!a({lYidcG1XW(npLwYzxyLninuvL>SUWv-oCIi*1}B)&cjrvglL3Z ztOBL6mPsVm|L1)lR#&I|j*r+2Ry^A=9$grZMT|$$UM3!#pI#$v)V7Osq zdD5biyR~(3$t*{*_A#|^sn|JZKEKJspLI$tj^|4&jyY&|Gt-O+Sn)7bLd4sKPdB`g zV)vVA3599G?N7*q^VTVC?0ZU*e|v7Y`7vEUz#EMs`pVh^($>;13{|WBJcBgl1F#po z3CeDsJuD;lzni1w-tI4q6-02)r)L>w{0>T=hudl4zoi)wrt#suO#DQ|!8*ldx5_n0 z@7SMb^w6&K5rvuM^<7(~CH9ZC!Ye%lsW@GjJL|cqgUcf6QHl!*neAdkn0Ro69^=B; zcizlLQrBVuWI)}YcMVKYG1uH=?fhA%RC!;vv|)M=l7F$NwZmMtK-F`q+|uWytQ!4D z_Rynjo$D=}F7ym0eh96bGf8rYO(XMbwJx%1#Y|YwkQH^W)L>OQ>D2V+Z4pxo=V9_) zkRL)ZjZR25S~@v7>E}He=s8UYF0CHhO?$FR%B`G9EXTdhgLHW>JRtW-oakMFB z;Lmz2@#V)esr!OJ68y!6?NNFQN1Jvyky2>cjneh@jfux=$;iXhi=$1^5`WgCD5nOm zq(5wIN!Xx3BM(yxr^`)8GX=z)3-qJJ0JG_@E4zk?#$oO1(NOu;aH2?Zoip(yi zo%c>Butk(akDL%1xB7@=U%Ir`cUHP_tV~jIf5myUaf&y_KK%LT*`49rE$RA)Qko;< z0qGWJx7B&CN*?i4MBB4ysWgk0PO)f-drO^`e&zuwA+-J7E$JEK;afxx$U{WzYw|>z z;8srS_x|TtndX3xm1*2WMEBgIQsnCMTEhOHGiaJ~I0qbIntv82GQ0Z3?5ZBKE8a`D zQQfXMLbsA)v6G|>X6+}KwR42Na&&9w2-8|YXeL{OE^G~UU~7;g^!2Q-L5|Q@6kq2C zw$A5eyk@7m1**xH@MqIH=Lp?PaDQdb{MBmauXr!r_v!wMBTU{7p(@Oau4Z2JJoBO) zVe-5D*;J+A2;C>zGvEH6`F3yS+j%eD>+8OqBXm#A_mAyt|G3Qd5021xFMa>u2z~cC z|NgnOt)`v!v_u*fcSt?zH%hD5NCRF<^V6OiK8;Bi-f4hn&O_fHKLovzedjHrhfi$T z7Q-!PF&sze@t_{VafCh}9#P$-N#W_l|AalWD;PWL5i&>UR+4^Up`?CGBNp?1B1~~R zM0130iLY30u#M#g29_J}UZ!kKF~+OJ38z}nqqbYwm`a&A3|-P&6LujeaX5ib_BLS4+kkBbg<dR8c)>O~=->_1YQA!2n)? z9KaAm7y=hpa$rllKHl`7Pm`3zFMKJagwR5U7{CzC(`w|vUSAUe>16w{N>Y+i1hIl4 z`Z2_`tjSUt1A74~|R=tiqFovwr=G$?`?#}LU3vHxW0*05LH zo#wQh)oi6$^JYa5{TYIfZs3>OF0fbnz-F{pu{p-M5l5FJQW)aRv*x>CFF1oD!j)u@ zX%oNZnO!U)pWfw6r>4(Ss_pWidu*L)4wh>jL!&7*wU38AO21*i49Vz z7R{*R#yN`fSP!~%sWY8##&1Kn7SQaj^Xm4*c5W%JJ|!#SdXrsgr}DFu&D+~j$S*hF znYNj`Kq-Bk)i%%_%eEx9`d4}1f%CHaZdZCRX{M4}u`PxCAR3{wm-4j^YHhr+V{`m? zt~ae6KUo=g(~m+lnD438b&6ts)T#; zOr_;TM+*5JuiBQH?U|y~+QKWhbN`;C&D_)g@2KrcD%5nNlW$B{q9)a+kRL>|Hx6^$ z$&@AyrM>r>k=Hw$(S*x$l|I9qDdcy@!;Px_XDP>i<8Lcm_|}{lq>^|>croJU(45+s z&rwp3IaA0Fq7fSAGK$=@|CG19SF{Fg3G%Z#*o;O#o3D(Gc4j;#SLi}oZF?i{d~Tyb zTY~%`n!Wk5qYQbtG6t7i-q`@H9j+CKMrd03*V?DQX5M8uZrink275uj0_Pv0h67U!jVhL3wj2)y4akbFGH*@#$dP1(h}?i zM;gu(LhUzi(&p05vhCt-_~~75I^eG<%7zvG6t26Fliu|0*lZ>EEkDh2AF@IlI^9J+ ze>++53=g-sQoqV`l-sY`(xiRfbj*WnWzI*Aa0*$iRbL+~C+E?1^kYL@Ee~8Rx~bqxpiaGyDRi3c z6s7)1jtDF6s+GyL$5SR?3|ku8tF&6$WaUtxKZRZip^v?$YFq0M#Thv#Bshb6`ufrl zKgKI#TKZB$r2u-$Vw^%P_+DE&a-G(5(_p*__cOp2v+jX(WXxDa9imW338BLoeKq^b zgYo->!Ge`QNe=(fmX19>K}p=?%XmcBY^P=Q?17(exGcjKD3!<~eD+5}-}mWw*8cqx zv{$%O57-ex_fF4JzIK)vkIzk384}L1w=)-G9!|7{(|&4z^*4vJ-r;O-p+`;7)-7_KL3>PAfjnQXT}jQ4ukxS{QDb zSq|@5n54lLxGzE82%Q-3gBP^0$G&D~3{YOk1M)`bwf`k~d`fRzIPARywS~RJu{yQd z2UqrABON(!kD+Bi+l6z()?o9avh`j?emTE4hP@zKw8V*zZyUA^>WD}7EQ8^?gLVup zAE5wgecrnfrE&D(SPVS?T)}Y7Bh-1$YD4xvo8*Vgmq3pLeTj%LzfguezYv4BWtEno zw}ieHdROKXpM2Mx*2Upw7B({M1^qen;0X0)yTKr~8_WvG5~3xjtvFV{rKA|@u^p#a zsR0H!Q*d8`I}t*zJ~g$gormMX-W`N!3GRJxw?pUw+d2ENopZ1vPj1A zwHEUr9&c{orNLfs4~M%pLMvDVu#rUoi&+E!d%=;0`xT1-Sd`KDKT!sZCSZ&L(Fmon zNX8R=%6r2i85ps^s2HMuMoW1tTAI$HB^VV!eo$KW<|K>Aay%MJi&#VkBQMAgq7h1D zQD5Po4RDV-u0kvd`N1(ns4|NzHy8Aid$Pz9Mv#ynL?aY@#8bYALUElBRs{MC7)`>N zMQ8+lE>C}7C{q?8LyrUbK{V5xMd9mN6#jxm;n06Te$Xmel))nXs!DDAET*{-Gr)BR zEgzw;ESspqvWdzE&kH#Yj1%DMLZ~~-SPm~M<<*sCEHE>HaS24TxSeH1Q&?8ii)BU7 z8eov%Bs4#V**<`OpKueCp}TjmN`;5Hwc+E$kZ-x8g8&1JY2BEc)tjGxK0^$ zTnT&HrA<5PJGz`2QG(|mCpZ3P=x^IHFDWKdKtQ_HVxsAwuOF50ANCB<|5=PYwR%lC zzwU4XTOQSpqOsGEy0Mx)g;vQbA#dO1Ma4h!N<5NDU@s_@h?u&kCwX5YTvKYF(qPN| zjcw_&NK19%3MX3gy${7ZE!2j0nlhUV`fkHIXW3WHzQ!`9!`M5fPw4hW_ zS~i2dQ%U!n8CugZ7Y)!G4E#r-D_@mU$ELKPFaNBz zS5RAsX8x+r0J65>Ozrce(SjvHx&wM(I{O4tU0?G2d`h(;BzXG*tzSzs8MZ*%g*J`Q z#6Hf%|BShI&ely>QRh4{Em7i*(rthbHRNI%n0ii$2;i~kUC&@5PwS~wIwh{b>$hcE zx!y;`wu?+5n%%EFmqdEbpQG)*FhPcrKnWq5`9#MGr0+~8t$aZkhHD#2(z}E=Jr{CZ ziHr1OQZ;(AP)m0oXE<;m1;du+EU$^|zeK6-7(gKJ*Ucn5xi<}YgSMEQQap8KAj{Wq})jQ)O@CrAMHvZ8ljXyJ@A7+ zPsv_|Lj(kj03n*?oW-2*Us3(#j*VRio*KTZDAHBYF?P* zM{=`=YJ+^MVmP9(7n~;+S*}VZuWHTJ1{QYFp!Gppf~$b74+|%9`(c>&XGm)TEgbd| zSJaeix3odEkoKCbTIk8(sudBNE3J~7&3-0%l^IN+=Y+lsdOL&$26V-NkwmWh`$`SY z6r6*bt=iLD<7O(AI=5zXUT+S<0ooP0M;V2{mVX>N(5zlFm1b;hyXHjEs4q*Eao#Qr z@!|e0Io|!M{P24afxUJ`N7JO+OO+!lT#6uko2@hW?OrAKzBHIjk)!CdeKVBeHf^Y- zMMpYmU_ zqv@8s>B{?At?3-^7`nRe66IiZ7Yfnrz3uzGaEo_G<+f9TH8?)dc4ZPyTl5;Mw7tRe zs8#kK<>^=6%KOfFk^z53(6iBFl{YKhDI5hjh6r^tb2Ip_-Y3tpO(s3gMAFL(#wgWK zxKlU^5RDM+S%HjQTt==N6G7^0?dgdDS&AXhokE=;8llws<;eJ(73A(&9fZ+^{2(Rv z)rjimUbnjtIc?woVFsa25X~Zhd`o;L{*`>RLUX}N;P^l^`yx<69DaQEy8L(N`5Np6 z#|Mr&ua}f3l^1-HZg+_!aHgQPa1;>Ak1Ankv2mT;?CD?v?FWu1L?aYF;g0;`;(2+> zhhPG&xYKW*a8u7rLj9+bK2nzug&qxGQG4j z3&ZJvrDK#2{_Yfx0?cs{x{~ULXS&wKS;e;+U@vHiBEom#W%-NbiQ{9;1WSZy$eUFM zZ5J7)zN?Jen1u_L2xqPKmGr7|eX})F z@wD`!qEu6RO*0g0JRFCu&(a`w*bAar++O;&)-%KnKYC_HAa{uFwmghxDx;N0%e|OX z)#o)QBmE}Hqh>jgmJrz7DM2A!lr=f{y%8TN>MmEGM&d}%>yV-WGxeU3( z8VRh5AT-)0&Je^9Eek{h90iDG-^F>=TkFzmBrbcaR34+beX@L)gyb-!F zdB0YyML+!PUNsGB2zx;^i?15jA^Y+j@wSzBG^im&Cp`_IAs5Cdr)soinim#&kctld z<&XOuNLZyn>K-v#8MLb{z33NC7t`U&oVpT)ln~nS+Mr!r$G)rPa>y(1t1k_>K3;iJ z;7g$-uwIJLhTICIcE14J&3B3hxkCh`#BRNmY)Pu7l*HfSe`pTYfwalOETvQit4#yh z9s2mugH^^WTatO4IIOEDX*jjD{H0SvQg@;seJ8Q=As>GVb%K--l0I(Hj%9SgTkGtS z)4!S`@7w=cQ%di)$){2NPN3F@*fM8sDn!y0&g=okd zp>4xtQsufCemU{Dc5$H}9d~l9lKsYyLUhV37Q0WIteo5zz%=jauaMDmWqIBEx&$Tr zQ0uo7lw$!w6pjL<#3Gru(=>U1OFXf0BMiC2DjuxKv6Hxoi?o{GD&g*BeS~_ud$daB zK2w!9O#>*TgwS8F8<0IqTj0=I3uP!T>;=*6=D?0vQsXAV$8&3HV{(1yv(!n7|L=hm zqN9uZ&~5HhmFZRZcNE6;2_w;4n#&%2D=^QX(&}v{E6$(T7v8`qKuXLfKHH*MZCED1 zf71i!zENnBAzLZo6F{LPuri6z>|3E)*3ANWs9R5=W(g~hkP@q~^mixw6F$f_&wi1i zypV^8I2$#P&^bBsvMF8i9P9hg5q+j8?sbAFL|@vg()zoymB&rE=6A2e5^d{kX>LXd zk`|!S_!8O5ydJ^K!|9^{DIs)C>8UxE^N^1<8!A*%VK&j@p+arHu#+EeZdbuRDv1f3 zCPkle#Laf9)c<3)a;#w>g_4MRbay?$5n^0Spx1%KAOyj8k#PqwnTUoeF_K{P^sUR}xcoKDhrn@<{Sf&3sP=BWpz zk%RVj@`@yR&blVURRqz{OCXdTi8ZG_jyRKj=>~c-xV9lBcK%_Zk{>yP zYwRDbLGBO%DIs*fSSfN!iN*u%nhQG)L_JRY)}A{Gxc$Q>de zC4_#|EJNZvqi|42V-4C{Nk%>)Q<@Mbf z5Ey?zN#NejZdoKWA#=Bu#tu?x0=Yv3q{M16?Me_SHU#h6zEXp+2t>ok38CWEe%E>q zNWqcM8W>;<2X%s!5K2&6kaz3)%9ifU1U+DU1!Gk94LbLCTAAzi_*Qcp0=YxkVI+&t z9&3B;beBHZ^Uz@p#)c3Lqh)rgUw)=e28D|yj` z?zo`OU<1sfpdOGCLVu2`M4Aj}E8naeB4kBScCl)(>&7;NVqXmJdfJIV?of7^8?uvX z>#OqP*LJw>3kL%8Gl+)yCqf5QPrP$`W8C+>l?F3jm_b5HY}KB>qM0LKDQ#Y&P#t`E zQK8lYmMG&_22i*Yv2)H(m@MqL%BxL4BVj*>y;LWa#xV5DV>|-z`45j#j0fxmd5DN- zk)z3&K6RyI$FB(y0NgFt4OHoIR=LGlJd!zOJBT#yR?jPM>^2#;SnN=##Cpwc9Yn?5 zxxvA%q{r$FUduB+3NZuhbue3{i<6cp{igHp{r2$cOTNao_R9TwPJ=Cll~iMm?9jqs zD#i@EocfaF4b!%ISMrW?{s`g=o zFuE`zgLPkoJWpQHN?PnBGx#2e+kAc32}v=}2dVrkJ1~ zr#~wZGrZ~93o=dI{z6%q!tX{cs~$<7T$v?5TJlYUEs!6igpi@dC?a2LuDyKqS=v*~ zn||6|T8*66hC)f;xe<#K%~D9<*iqVz>wz-t1+^6s7k;FX(Jxy|)svky$Q_~~Z?*=D zg_3U$>*d^RM4+}1{qQiR9zJDMn-aVhUeI(gS6o3iFn%A=yQLv>&ZgN z{-!~Lv>-a?C0jS6&DDB`S}-2;utM5sd9sCFIdV7@(@A+{)CO^G6rwBbQ>eLxg<7e2 zONOYwwx4td?{f4D_>VOl4l-PUf z@p0s!(>dvOi4p{IhrJ*gA;%zh@*((`{GzcH`4+3ttJxN+wL?n^(b?nL(%XsU)%-L3 zByQlM0CJ{m1#Rvp8v<#;^ICY0%g!e1`Vxox73E-`It0>!Xu8gy;;8cK8RIFk#pM>H zap&{$$dlDb4W%ue@u0lg@vswx=w(a%Y56PV)iT%lxpSsReX_37Lc>6+5J(G3BAz?1 zwQEM!ZgQ6!U2`Fj7DQXM3Z|btEY&S192t**3r&dIKUd`@akgZ1U@+ZSySy3};z%zH z_oq?e6;x?ULkcM&6#9+b4X&QIZ^P7h0%<`>;29h9ySAUTH}SXfj1&%^5h-MX*1@*~hr^|Ak`}N4-ymmCX zqq%Cn(4IQnYDX*Qn5#ot+p}AsA@o5LOLf>NexKncZb0Tm70M4C>Jr!j`9VtTt&|CS zw36E=NM%|llL4$Ay?AUH)#Iieg_6LNMpiX&DNTmV93x+D5H3gs5s(tA!|k;vhrV8u zKQ*@}cj6*x$3|tsO#|COsJuAuK5hKV@8bzz!L~8HS_7u{E_a_jt8h%@= zU4D+dv{W1!UNw^5xlu-)FvCtjKuRpis8^4Cu)icHZD>FSosFi=LyM_at?Ve25K>~N zedww5a9^l=$Z{mP-Yu3sDD_k+ebSLay6{|;oi3el_R2mIFQ0usQqbcOxGf?g9^G53 zb+uh1zr2w^j>Se(sa`SFZnvGl1M)^_(XpzeYma<+(5^NDqNR5nb@h9yEScv>OLdH+ zm9-a2%pz_jz57)mFNRUM#8fu|dkuIWM;$$%D(_1bMLgU&Q~ngZOun$RkDxg`QHH1Q z?EbD}HGIAJR5^B{k8peEYuc2GdK^C8QX4san>_bPk{}iA1<}l|YSth< z8ZMVdKa$9It9Uv+lPbUe=|rI(P(OC!?pg!y9(h!bIMRy1(>F*L-Y8%-{eL>*^F7wf z*tSrEE%3Y!QbK5Oq?uHEPp-VBWU_FgIJaUaI<~<9rGs}<3i+`&k+SZ~Pg9S{jcF)> zE%0;^o=qY&=lyZRg+Hhq);Ed36L5Iu`FTtnosqR&@y%(*=DbJK5@dZsjC`?j6oD;J zDoBa#YKN+mgQGm;(6a%;St>jYhm;U{^N$&k-$uyq8b$~_;M_od2n9XZZn%5oFS+4? zfx=ipNkoM8`1|r}HdYS#p~4Kpv4UfWP?N(JSEsm*k?;hOgJU`1U3`AD5MJ|WVyk> zJ=*2aOu1Lx-hzjN2+@m1zn^1xGoq6e`+hWmJ{L%~~=pw{E5CJJM&BN-GSp<~fEQ$5_+{?m9wA zU?j`#s!ekx-=Z(c$?jG{ybC3Pu{JxK(4t7vq$YCzR;7iQ8cG5qa+c$SC6N7%j~QNB zJrHsO7=?>cnSb^mJ#L(mJH%NExdD^}W-=_wDBp{mIBO?wTX#{&SfC^@-(lxbEryei z2TvGwmma3UyawhUFsEYYIO`NrN6VF8tt&?$Ehq`h`q({yhl5F4nyq}e|6C!vgJ_r= zvRdDP(PZziBZeFrk_WR%uPOFM$ela5V(MJ+o^r<1kHS2f-6^t3 zCwj(sVl#3FzLRmtq~xn5nSh7s7S_{hd|=B^>i(?MN}ARgXzB&XwM=9Pb; z62}tGMyWoXji(SHRyl2HeUd+@d2W3#mB1EQRfCjR^g7Uyl-g{a=N0QiAYFJ;2`RCY zhOYLcl~hiOc-U4rscsk1g!(KUten5pg=Y42r{#mXD%;}Qv#|aC4uK3@Jxq! zhCgM}(cj%LF1fLAn+i$@DY2V?>>CqP`V`BX@YarawTU%a;*)1Bg*&O@jYjL2{-k@{ z;=I6uI>IehNEcE<$T`}N9Lw35cjZt$0Rhi$Ae#M#+XEkRu*L1X&FdV5dwo!I5fSmc z8TqH~-Mk5x+=V+u&`O}au~oY)mh?J))$7{&(xjblx>57V$)EE39qdbU!|N(36Kc{S z(^IH2zp~alFDla>|3|qjISPUiU&0;;L*PW|Thbcxx zR+Fs!F@6(heDqWAjw5#FKm9a`{s_9^ZFcate0Bpu8cZrjYhGnv{2?G9zeC^0(AK@a zdY5T;nIV)neMt9C#quhKUeI8#$gp&}p=DXcy5^^R5i#}HKoT{)mSp3xU4t!9Dkv>` z8?ft0^5siS4a)oE^Dy;7d(VS8;fsW2eItISIFOIV<#&(LXf)AvK(=dvg7hm_c_ zzQv6syGAz6t2ZT4gLI)(_p3~$o>Aw#b9Tot9=ms>lg$l&^H_h;UV|-=AEdUaI5^a%RtA0MQCDk4>jIUUKQo3_%ky=J&;%bz~6)uiSs zL=3-^NLL-QQ(gttQ4!j>Cy{(P(m9u|xGKY5kl*YRqiAr$a!RcI52icxztp$!Ct@2g0<-z;7E(ab}IXoNHe9}?2Cbl!%|qEruUBdA-V zw=%7=ms)vc1U+B6JbN6tXL53@$7t05z8=JLg;}1ms2PT|pj1#=gdz@LQm_8bydznSFw_u^6`W0WFQc3@IY0JZ-qFRL zxcQsbwA82`%DdrF>KrE@>a%L1vTah33ME9yOLHO)u2b{c-Sxt087kXTrzlIB1q%pB z389jwYLe2g6<0kUxv$;O; z@@$@4%!u3?)$me`aAr>vUBiC03_? zXHQO0#n8~JErzrpT15Q)yB)c;W^3M`t9=Co)E1%mGfp8@LaD)dV1HtzXQQftNbeaGBtVCXraPZT}e zfaQtAtCV$Ke^e;LoecVRaaZftX*7wU=6RRDJutxi9L6GWZ)fj}h72YbM-|K4^x+R7 zT7q#KjGS16oYI}-hAhnup87_EaV?B2VZ_Pa9!T^ht^*h6m3VF^#O*MzfiXP0t2VS0 z*?BqFE2(>&kkP|R0nCcoJ(;o>H0Q_Fw70K%5m=1?b6%t};eB+acC2knc_B?E&J`6} zd+Ai=(ItO1z(J*JzpY7=k=N}vn*vG?vmhmx`#rpkLq>^FdWRw_g{y~h05ovBJ}ef~>CmUX+35nYc- zL$f}~aGgW+`mZYeTb`E06!a)+`*G`me@*^O){{y`p*XeB}J5FH-xLyNI5|82e*z@+Ms z+@APYdC0R?l@&ZSM5m5tcW^3AR{lA~HSg!TSo{5=inms(Oj@;WOV>V~s9dNe>M{1b zN{6qXqy*mfV~B5Q^|jQv033MUnm~EsD2Rv?70k)1pmsQ}$6yW03(=4_d%NZjU$Qjb z2G{EoDnof8x@k^ZnjSV$se99(Nww~WADL3Kr`%v^H4Jw$i2nP2TUxyQ1ZB_+K31_2 z7TSWDDcGs`bPaM}!^X#*OjJIM@Kf7O4x|kn$12ArC=BsrutEDca{#uy=3;;?{!@Zz zcH9`ncA26=N-W#H|F@P_uP0u6X@Ughg}oq}oi43qzpSd&!)>P?m!Z56{p5ZS{g9TW zOsv7949{y`JX)P=9#y$4IqeXL?|xq?L+%g(DX}lN9BWFfTb0Cn9{WPmknU-UT#^3**wSfvQm2Qb@rfR0 zd60W~r5#P{oyorT<*A0=X-79K%v6GtJQyPU(|GxN>*4tND63r9(xxzsj*rYzhHdgt zAtmctv(}DITFZYQCEvr z;16%juSHE4rLb+e}AXisldj#Qa=Yg-amqN-jS~KVzDzs zpH7UReXEaAt~&D3b?)4Nl<6`=p7Fg6hVdtiOCcrxoA+M0v444@-4#wB)gG(- z_#(;{3MsLh1CcZ2SqbfM%N?aKlox6% zB5ntGYuWy`IQft-9upQxhq8B3FZT0LA$r*A2s*3eSOxFnqdQ?mb<*x)jQmFle+)Ad zI0}#wLcMOZ$DWVPaiVnzxus7yy~_N@y|-;t@bFQg#W@$%!s=YOa8p82` zXm-=-Y&TrVa9O@~C{c#JAR3N3JE^v*PO{n$mOHH#=N#$;M}gUH=j(qA}ld&DA$i-1> zVbwxOpj9#+k-uqY-?YGOLK_L|10uv#J9Sqx`CdqG+<5UR8LlEIJMH6?Ph4;fdCuV+-8tM0pIkLxku>?>sqZ zs8cote{@~K$HZ=ZeNuHCap!mS?2GTfJ->~P;@U%&WL&yaFI9oM{I zt-+lh?wpVk^X);NB*)!Vj+@#L!)O9ZBI?ojN^4RX7sJ(>e-vT{h=7#Xx57%+AZ7A= zaIfGj8AcXRb{Ge-RqLCpeU_5(S>o*lBQmHHq{K4%Q-0)GjE{_WTMK%?XbHxTtPVFa zjQFLN#(l4jmmzm3JB%`!ziQZs;8$Mw$1`&wvV>?D$+FX>gNwAS?_=;(tJ@lkonb5r zV@4KPTDB+c66(m;L(MVd4rPZm2Nubs_8~JGo|o4Roi9P|5DoJLb{n^zC;RGIIh-1D zL4&b6M8jN!Rn_*(TEp#D_-m<90`nSNRiTR~PgR~>@K<4;!1nWR@uY&)VkvX>4;gZY zvcrsw)fp~~B1hk=@;b{=2FM+vVcy1m&ufn_DdXQqUURRyAQeQz+>pIdANY=Lw|J*xE2B+v6Mc;&3k5HjKO%T;Q} z-jAYff>g+ly~E28RSg%smaP;Kch;(O3wtNZeNm7K(FjG}?M&8oDdkl%`iGD^!#W&9 zGw<`XD@mPk%CnGt83?w(Srg~{$>7msYUFyawsdU4^LS+IX;LNgn0JnTe{W4ivm4K=Qd>KmxU(8a2 zPGZ_%_*o_JLt8e3C)YcZJv*#58|O9zwmkbF)2QiBmCl0{6;eW|OXv`CI&!||*TPH# z-_;U&*#%-c4i!_kzA;AO4||Yi^|Q3*sYf)}a-Nm`tp6^qjxKapAtm;OjiiBO!Iv4@ ztb#5w_!5`U>xrjAN9{6GD>rDx^msC?AE{Mrrq*@s92vG$yXHf~Zd#~U?le^)C4|Oq zi6EITGBliA62o5a?)lKUcP!Md7mFe)UTQ(i|5UYAi&|jtg)cR=yC3a-(o((GzOg!U zP#|5K%)ao~xB-)@rLz+mBDd292e%dwP!hOki#Pd9_b++Xi2rWy6uUb+9*7lt~vivsb7)*W_8dXGYxH4W3LKvnF1p5emL#A ztc?1iy1fd~2%W23oE%K4rqxhm1w{YIP&x>kt0dJyUCO>%ctAE+pQdmgNv-E-Ud0z1 zt|g~p*aCTodVHAE2G9AnLtb3b27|Amsmoi%(oa>6DL12=s6AiC(2V%Q%C|F37>`kB z9dL~GOnGB$YXOm*9Lwr{my|{K8wzOl{zv6WatC}wy7A{w0RhLy&n1S&7d}^3+dDEI zj&;p&!SN3A*hvu>wm=?GTDG4L?vAzci{*XYb7k-aJVADFbDi-peXlRz=_DDpfbVLl zkP@p*{5@Bj@91c_u{)K(wGF+&zEp4Kweys)7+#IyU*C)S`Sm>k0jr!4jZhuO!`kLP z)DU>GAAz)fDBko&u>;EPr+$K8LFi0CMN+J{hqkzFI|6$_zXGKdzB?#GZDGzSYF=w+ z1#Gr1P}bO`M`#VOmpC7FKh8A7NIrS3Vly$EXV^=$!~oyor0R}p+OB%B7_Mh%?IL1g zR4RG>WP#>Vxr70FHRy>%57*&JXHvH56wPhsWexgT=pRMD+c_^7Utao$Jh^`{ym(|3 zb$_>1F)!(&LW_YT!hHLcAe`>KUEU}mY}PoAz8-ZxmmyT(De`(1ZobRk+q;4fGnos%!C75d=boulcg!%LNiSuO$(h-SB5=1X$q@k4U0 z$V42~z7u`f?U)ktwTYT&*^xFJzf@_x!$pOZ*jJjXl_KVGJ>@u?_KaN|b-T7r8F{jq z3QuJUV>;49@>0cYx(l=RMc>Uyhn2B%SXh|Aqg*gMsV+FG)a%nkg_PKP6Xna2FIHXT z-{;AF{A}0fqsnL z_+2#KkW~3kIeqsa3~531>9Vo(OZ*EZ)Svsr*WD|ULFrrMQ60STl(2Yen{!D?{Hvh~ z(RXh$uf6VtQrUtd_IJ7=we8hRrrSp0&i6ae-xm~D+n={nAzipO*)O;RhsxLg`6zkb z7=d9gD7%O_jAJzSo-^c5cL!p~9iky`gf0!PN=~L8kS7jqgTG9OqZ?1XP}YoeP$7C~ zaunTgySO@HtR2&%UFkaH_{yVl)4Zk_whSwbqT{NRQ2#7ur$S0BgS>#W`F|=>kH0bm z&EftE_e6xu?T=~YwW0DYH9_D3WjBPeuPGNVtG<8DrShp$i%f|tkeiHdilHP>!c!X~ zXw`0IRrA#xu{CC^_Gw{E-iNS37}A20z+Ic&5DG0pR@z0&p$<_P(t_w8^Frz8t>)^r za2^4?ylh9-KRGXN-&r4TdJ;h^Z7!?YwzN|r+UZazty0HAHLt)C>+4t$o81|P=^LUj zqy_yh^vCQzoP`BR+LLY=vP(oj*&&)mWbNyct=GNecaIeexkG;4rU%m7&n?y3wmgPo zXYFL#)a&xo)3xyCIf3*{zw)Z*+xlw7ae-91QC=;ZQ(t{JC4}~Jw^Seg&h=RSupx13 zaYc@saHC_5A3Vs0ylwTVp{FQL58BBgyV4VuYw9*WPTfGd38c{Oe6eg^}_P%yN->8 zUJ%W`M>e4)2@bp>4|A`A&Aa>14@1kV^O`uTP$x)x6?BzPCnBMAJLTxe9Lxpr<{J_>=y}rcoxu$$J z>7X2o6q<0hoZ9SiD**v1u~_u37wHssOtw$8z-#u(lq8f?8;tc-p@fhU`_8sQ8p&O8 z+7LLYkyfiOre71DDUJP971D(<3VXX|Loo)H1>+zQQMcbP@_Ac1`9;bg zd5ssQ&tH{LcbE4RctGClHtx9yV(YU+zI^MWfGFDm(>wUN^260fwbx`i@z@LH-EJSY z23J@_lK1iDgxvXun?g&DJfNI7=&y=;#EczHnsq)Qd1p3}pj5CIM6-;(Tzg{k#~^vt`4afA z3*NMPlY@$rbC3%4fRtEnVB46aJ}qx(WP{00c8qFuK2I6jBtV69VRX)_QLWQR+^`hM zb(p92Ww1iipB+%XmkksUkP@pc?d?V;RkxP2K0lJ98!EJCfxsArQ# zlYveQ zOS*@UqqVnr+SRua<^yUjj#Yzt?3d;LsVom`e_w`k3+akd1$Q4wVoyx@e`H;CR8`H_ zz91Ngfr5Y{2H0R=180VFEG+B-6R}Vf5fKqYu)DjvTMW4Oj2r`7?C$P-?N`4IylefQ z@%!(tHS^4#IkWG?j%O5px2ukAAp%<>n@sQ0;_}u+OX)|Ar5hw_2DU^wSZUqG^Y9Q> ztmPx=e~#^gWgK_1f`1T5kqUBIkS?WAd!PNkJA|vvY>nF}H9ilf{dQh^e;d+HF zk@eiVv52%wVMDg$=D6x(yVyfI@7hI+$0f%rZ|xRJdlVwDC5p?a5GyX$i_<+aGyQS* z!rcIO31Wx2<0qOYA7c|e3rTw|wu}3f$yB&hFR^Eiq5OOIt+bybLf&iF3>hef9qp{Q z>9m>QPLDmreV2T~*0n^15*OH?KaSG51lz^EonlyywGf-{=VjlHJ8?W&AVNNuM7(Y* z^6n_9cUqBOIxS%ju_Zbu@~YzO%4=-=a98Qnhwb7yh|biP>xtlhDzXALUeXy35%Q^T z*o@kumpRk2WxkJO{lHV7e1@}KSyAjedX?3GA)j|o-DznkN%mTmy&f8#eQC~XmJwg- zwrAfqbB-rg?1_x1nNd*O{`a+ca7cTpSBSMYXjb~67lzS4~zdxiD~dcmb)BRwQ&AGcs+<;>Nlps0XC)J5XpXpJ(2Bj zm17I?7JV&jdlZwbgJ|)Rd*wr~M?9z3BOY~IAlY}}1%|(3in3m)IG6K6g%neSF*ArJ zR{8(Ef+58eVf+oeBtdtBVf50**qoO(q?jU%@qzay2;o|}5%I9zWVRnZN)~#wh047; z;?;=z`QK#KUwmX(f(W$3k{`#{iVsY<%+?)KIhJ7Gu_dy%XS!G>UEaZZ42tB~Uqr|= z=-8wIJ7Z;LR|*c0thJ~m*b<#f#upNm=#?hDdK)Ps9&4e#QJj7clZbUH$twKlB55L8 zYcaN-_;(9giGv;$*kji&9D9Q8qCAsn__6xzlJ6OIz^$+Jt#GvX70CKQFX}X-7j?=k zUoFiCdL7V`P9FFFz2G8!UF^FYN9Iqj#5B!$C5EGP>^tgM&Py~?=_Q(jL>Yi{i)hs2 z|Gjq8cyea zeJ*;6-Mcm3vGq0u-b>WrB}55LS-&p+!Xb}4%W$p4&GhQ@=9M$l25#jwl!rb~vcp}q z7vbLmx!X}5oGHAJIqdhvFE(2K3<#0#D{uEWcn8obG=)iDPc z-rpvvRoZ2F`)=EI5KeV|Dkp~9iJ$kX8hz%@Q$tt#Y8~d*Hg?sUr5259_?Pc4X`Zt< z6W553*f&^*_e3?6hiH21_h-Dg_34mejQC|iT|#-X2di_9aw4Hj1HNET8+>nDLwSg% zSEut<0=jjdBTCf&I(8-9rBPS~^^G5S) zzt&3#>>*-j6@~|b7sYuFpOD4U$)ViLxz<&<*M2-qO zdGUnh)M9JCRS%Z3YcT!_TOu#O`<;54-F`N2YlL`X^;Lh-zoOd+(klQ zyND(h^U&@3{tL62)7(A++d?lp%BFYXOd0whJHa|{=_Ii4*e=SWyIS$KdhE4+#C5Mr zk$_kWzclRz$2@c=n!#rq6Qx*AoI!a$s@|K%9DSpCos>^f_5f-hY9(bN(Lc(D{!ugU ztyS=!ivK7X;YF*@Dq4M7M6|KsDuZhm?r;=4NGqJ%pF_&txL+1r$)?atk3 zcP>%o48vU*<>4-BG99w6qxamtmHE>N0C#$nhiHmtxMD9d=#)|N$ZYBCgYxh+K(95^ zN#>5VJF8N>62}t@%0o2qeq8VrMfYgDZ_qXcwE<5rc&efIis(cZz3_nIJgFtVmny}l zA)2z{>#ooT#}4C{X64yGbSE>SDZh>)3Z>JMJdWOkh$h7B)8|sK1ivV@ME@v4gcHI( zaC8dR!g>DxhyjG~%}h+eTBu7hV%2{#?gy`~g|%=skP(Xr5kWFGZgZ}UwQ$9e5fOxl zB1G{xUK?xSe?mrdBt#4$T%Cv4!dm!Gl@WsoF^mu&Ustb#wQ&9T|A?$!`L}zt4{M=j z$cS6JGWB6EMdR(aY+j;ej(lX*)y(2!QW%mW90{Gh{lX;;+Ys& zRCrw8Z&_&9n(y!~X&gF{q`qC#U&9=3%=$K&#@s6^7N6K;S^un+l;hswMIB?}n_lYA zxDFb&WHKFV=qPUgSY}B)DkCu49?`^Wu)DnQO+RB9zc_%m4sB?3Yu#FP^KYtQEkv74 zA(Y`3XrY20>4ti|yy;D)*ndtSRt8uMOb#;?VRSjFBw^G&z z3V!;BCHzhae*0QKqe-E%>YSib8X_uOb zu1_^GELeh!P{<)g*|J?m3VU-&y`WWP9ZQgPs#Do1MkW8ufYwbqq|-Y;9Y>0gmnHSz z1u9G2RKbO(7;6@12JF{6r^|?XABPLyv95Yg_aQpgLK!lnL*u8z#jz#D^#fIh=vdP3 zpNWR!!dn6BPRvTjmWUCk%TQsQbJ9BxT&!a)WC26oFyb{>KTynV?x5EikgDHS#~VJ| zUId&<*e7wGA?p}%Q)PsSBAp8AGlt%j_{flFqW-T$W6f-9b>r#h^sNqV3lp7271k$D zx~XHWbHqp2F+7iYq3ri`88O(ko5(#Yx8AM7cm4L*VaA>-MbzUD>3D~NTcS%VygQM2ZP4Z zqP-~a-bznwlV4y7^3fri9oaHYH52D!K3Y09b`{tz){>d=V(InM_G52Z#$ECf&Rv@r zyP{gC3+psCDqFf4`|DRz=iTx$WKIqx$d_JgerwTfy(LyhWlv)xp><2u?kmM)K}#mn zS}Q-XXT()Yyx}EKI<|}Q$O4(iPkd0WSPrFo2`nl4t-CRDg|~V#ri#Q5NUw~wt|anZ zNVjx|V*-1E+>bI-;jLIV(Pnd+Wl%sKQQU307 z%Z>YO1=d1&GUA+OEv|S?wXEMABFR9`RAgMG=+B)G^SR zwp$!1ehEj2wz2g?}U&503u`P}^Vo ziwE*>{6Mk$l%t+GAyry;5rHc>o%D$l&}oK?zB+NSj;lV_!d-&?=QoFoGy6*Djz02^ zgZqb!$m~B-)U55M&;MCT$Ndg>XWUWgUF6-Pgi~2}eg6r0cgFJr?$i{Ycr;!_O)f<* z#k?@%*#K)H+GHxYC0>;3UrK)>=Ghw``GDwPRJ*HyjkF>pKLM|Rm@KQ zYZ>sUfW(-EwGd4n_b-8BPxL#Blcfa5yA0k^@b*Fxjs2NuQtZCv&^h@Yg=oAXk)Jcg zN7z-qV@au5o8v7GZ5GW40<{3R^Y-fvS_i$cf&dc;~uFKQ_*F?!00ecDE2a66pqgQO*&N8V( zILDHp@h{Vp-z-&66;IT#CCVlzM4lXkfD!``2DC)G+BxdgVCt1e_i%wFFeU?AqF9_> zz1ikZGuck7A-r?_I;wujS_|niRvXlyoO&Y4N?TB9oR=DBJe?rOQOhI>!e0`K@7KGo{J>gqFDo7J_jUaIOdwRZ1GgzyjBtWsY>JMtVTKnqSq; zVEQIj>SH9W>Ied*GZYR0Fmag4ZMMz^(@r*tnK z&nGw~rRVq5)sy-}E!Xcc>6uq7YUT8anoFx8>Hpq1tiCOhh467Gub=3&OF6QB6tBen z(&uZGS^8y?hV9<5AC%rDHC-KADhqM8w}*c5)pBL;$59+huw874Zg(#S>W3EuDz(nU za_kBAF#PA*^zS$Ks0S~MCmB}#w(3i!PdzxpcPL->Y;F31g?rSvOXD@H1-eU!Vm=%7 z+`V6#uihLg{RiRypDU*^_|T?B#>O99Mvp4RzEDGpx16J;!Re zVvq&$r?oiZ#F^i|j@)C`^YqAbZ`En1Vzl?~E7F^jZ`HUh9W|M2k`v-EA!-okQz-l`ssvt zN(hGzk1SY%Y~09gN!*5oBg98SeEhaiVoFDJpVm1eZ@cj=$;d*a6Te9^Wi`W!-JJoA%g5a;9I&f?iJ-10Uw z=zSd5srmv!4EWeuOgh~!dp=q_kC$fccGWA{-)j4yUW7-_Z8ih#U2X5hC+qlBL;PKfZ9dH^-U6d9Lue1dku0YPDaqrTNG`D@1Qfi0_@s zahxece?C$xJqs~DI*1T0V^Z`MggA4^k^h*OGeU<74K+lsshX0F@C@aI$UOf^Z%K&L zufDONXSD2ZQe(fHhUjS#xr{6sBV)@G;^+AyB9IWB7p5`P21J)#QZ5@2`^Sb5aaBA; z*2q(Q2QbtIMAr`C*@)pi4w05Tb@CR?3Gs3E3I(+R(V|yGaBm!t44Qi40?TNPfGTj57eYaBL5rxW6`)vxSc&AHcCL5)Lnf^Dg6M1!>sgxHiP2XU%#9}8+6qH|UA$VQwv zkxaUK-T7Vi*VX%1(oy3OebYWi#x)Ozbb15y_7%MxjpKIMBpo#l(L=A~j6<6|oe;y; z?9LwfTZa@KH4f3`+vR+#*!rglak0_3Y()H!>pE&2qQhNIWq;lAF~12>t6pi{gL?IK z>w6tF4$;-OZ4Ml+6hBn^u=#{aEdLd}^nQfc?=qdC{vdkfi<;?Ki1WF!UZ`*m z>ZfPPcu;;2L;XSYq4i1G2>Y|E31J;LHCx8@uQeFz52BymUXzXJ*D#3?GsV(u89y7` zQBZ#no##nfHlm4FEkZo2wNCF#z1ldWn1cF)=;hI;vk}Ey4w3I}SG{%FGRF3CvY`GT z`m~;zjTlt7JZWOasioQD*nI4^1@#Bf-xG3Vl#4k?ezm;8IV0~bYUrpxh;H&VXB^8O z)J&&{_=JAhGID(zsH6TM+WBkFw<_(KM2Imxy|PChkY~D%`h)1P$8+W*dGBgMTsWO+ z$(r+`7nkX%KZt%%t5){N+kVVi+g<9kwOHoG^9C*58EOOS(pJynhc6V1*NO%>sw5+A zyG0P9d00V)+JI=$Xht?7HX^I=WDL);Q+6jVHv3{pGR|dovgMqc$MA z&A-L75p6_XLaa#5K@>Z>z>L~}=+jT!vk`9=5BH;ZxOydZGmRtROm_=v1ET$HN@OE; zG|79ItOl#?^{lV!&}**+wE@v-Q**{K;K?{byj`C2bw`(dYe8*5^vv=Rp60HHe$H8C`mH{Zj_AmQoH?J`GauQ9K`>HU>Cvwiu(T~#@jV7u57*-IiyrHPd8e8I?H40n3$VNCC| zfas{s+KKSWBxCZfRm%RSEqI}FF48!t>QnWv_-dfaY5fH?wKw1YUGPq7XRod9@}CS!~Zt!AN`V7>Cd-E zXnW#b(7*QVtK61vvtxL-^^+KuEPiVe-1u1qeRBxUTYV41cCqhG zqN}l}X9KmVKL3!6#PS_1?buLW*?%*`lF`ojl)!d_v^pz4s@M{F_4};1G`Gk2>oc1uO74_;t$O%hQk$ArH zOHqa;xDLuAw+%dLj%gIjw+)SzWP}Z~5>H1A)tcowtD-#OTk4co*S92a_5B8aYU!(c?mU|RLWcoOXsgFi!v7yfD<&;vw z`)9mX$KiAU@we~kX_?V0kuMfi6)Zs+*b?d0(OC1Xy@}kdqo0CnIM(`^=p}A#PtfX4 zn@7D`^l7gpzbTR1@q+$XQZ2u?2-%yU4Y+E{u_el69i48TZBFFh=esMo>SL{01-wNR zp+Ked%}Zs?#hqj-)!4hxD!9w;i5}I}6sTQqEhnCq$R2MRelpV~s5DXwD0{ zk50v%1#9{L_pS0y>`4f#urQ15l0@FEWup{TcY zNyfe<%hC{mG7wGgf8_gUc3Yds?K{-ATwj)Rj!LiZm_EIzmx$h+pgAXHi1a$HVoO52 zRv|PO?VPRV`smLJ#q%@ks+$pkJwY_B4EGoKe}9_54@Fz)i14jjOf0`SN}JWmIlbf4 zpSsoF80}ExGLmtpT&l%fEuK#s<)mW??(NtT>D7p-mK7mU+*Eb7bh2!$Zqw7xMQ8~N zo~Li?NN310gEZ5GPb8zc$8U4NGco)|$%)dLA>+K2IJYTM8@upQI-)5O@aqh7$$W9V zNA3^_F`|o=xZZ21_Tt|&>4+vv(c77pDB9IRx~$T%Ej;_;nCPVMFx}j|+YmmlQ;OcV z>xS&R{>T<(j3ouD^O#oQTA4n7(%tK{4A|EuR9h10WRUL0RMD+x58`1@c1j2wEutxQ zFuJKSZ*3Q@)yggKcGoiedO)AW?X|bbHH`NMORD4cHq;K6X+|=t-RiB}T+^RFJ9$Zx zapumffQ0(pv=2v08HlF)c@1lG=iS};n517imY_TwANieEZC9Gz_u_qL`bqW@N82E^ z*1igw*P3wSWO8e@#=WxI<6J|iS074@RX!}Q$8#;LE+Gof@mC)XsH1(^6k;HnY#E1p zDQmy^@rHF}n+*0UPf#uO`wL&Kd{Re}acRv)|06e5zRI26wty0pfz};5w_8nAu6}9E zC)O-2eOtM8$6w<%>2@Vzi#UyA*w7YrydPfHHUsdH1ZniwWj`> z``z}`tHn(xDSwVP;mxX)5?F#Va7>huJNuq_!JuDk;qva%w<<*5P{$l^sPXK79!!#P zr+u>W@4&p=+q$!a=tch8V>$j>1JM+hVRcwpv9u5`F{`bF2>PG5*FbcZRc*9VIzBhg zAJ9cY{45rz+GG@<49Y~KUDdkk;%C-cTF_YPRk_~Bl(U)iiqeKg5@N^uR%+-{ckRrW zD5KquAhm>#ljcz~ju4GMY*oCb6yYP!wH8={GUOTj>3l|+!yWh(wT(dOI1U-nB-llN zV=Q6E^A43P+iv7>Et}(UH4^{lOQl|wT9JqKm_JZa+aySq?P4!G@pJw!)v1Lh84=`< z?nwUVf!>n|G0E6$nfc&7Yy7mQz!J2Dqm7*240Akh@fdW1*^~>H5ZEh36Nl;07y4@t z#=c+bF4^?K8)~43pR#La%-4JGpTTz43YSJc?SKAZW61x!uQZP0&zI=8Z_Z%_clQ@q zg1#HMS5Du8b)ipSj#nZj8HZmFO3$|-U0qpXl7aFl@9v)?`tUUkSg$_)BpEmklt;b^ zqnyz0-c!02QKi??fCb9HcjHZ_CVo!Bw{8GS>Df$R3Hm?e_s>&4l@wclO=0g`6baG3 zHaDskexzplH8v1U*-jtJh=}`6oS(81XwAMnqKVO=bsQGb4ZyEnc{ZW-oQtu!E1lS{E)equ-vl>gr()3>mS+k=~CQ_J>`mUrk^M z(Fz+A&3Uv6!SxL6Em=}8+KcJ=3-jRbB?Z>PamWa_4feuGcjw973ke({em5CW>4vKi zOI`Tb7I`HEeqBUU?D-y5EP3~v+5NaKc{3gaw>3Id%B!s?QPzmO(9x*g(n@ovS(d)l zrc2et?>I-kz0rLMf$jS2X<)_IW|x^5I<_Yhka@dtx%ZU(UqTch>y*(px(A7k#%fqEg?EV!TpA@g0_5 zdYk;WLsw&ZqMSg>$3N~hp*`qc}sYc_7vg#xPgBcq*-C9DRjEFD6MmfJ%>KEHA z-Te~OMT{-dkBvS2S;rETA-@~G$iBTeK|bNF{&^%B=yyhWv>TKT6wc`u?mlAqJI zQ?OA~f2($0>}jBEdZ}q;Lvb$Ska8uktiTZh!-j#cFq%wz8Z;DFj$c>ux|fyMjqznl z`CZEjgSv?2=QumO=NCgiFvc1n;|+bQ2_41uBG;9f1@m!yHyCBe3^W_^bQ0{sI%Q|C zd=k4c%D|TBBvYlMaGo$sdDB0?G!Eq3kr8LccM1J3*o|F*3kkmn^{RF?Q7OcU_rHHn@};7m6IrLo&q>^jT{l|uEAwtjzEos>LPjWh zp<+{Gab)F1_VDCqX+Dr`7}3PUc8!UypRM`A6E_)_V6WtHRNw0(9yD;^RhHdjC>{Hb zX!88b%PUeU=HinZdr7ed=tY(p<^FukFV60;AU+Kcut-TBX6g(QYp>=m{|aeWqdVL4fhuh?QE$v}=@lxH$^En7e&KX>7N z?oN^n90$rHZ^lu29k`$qziR(o(h_6{MtQ_ikm)G8)DB>KcQ%vW6UJyEncJ{&YZq}c z%A3{kXezOVA}=Gx7tvdE8Kp&PzZvXm0bgkbkzZ7nq0OKi_g%MHO#7-50(lM*O>YTJ zT%rekp2J)%{iUcEj7Y(VG>YKK0;eS@Hjca*o9FAx%gtmXN`*_& zZ5W@1F*6id)8nG<6Bxki^$wF{;OoF}vef9tGUA2)sV8Ine0M2Q7JG$bA{n(dSr$zA zz;^0AImY;4Pvls&a&ymF8WcFe9R0$jZ-udOG9uMFL_eN6f&FtKQbJ&q9>(I)zqX!> zeq!np_P)qaDM}AzU=Qh)W8Zm7p;~s_ad$__(_qZ;RhRCu(Ow$Knh0#6*8Aw79a@(4 zBJ|?(7G>@?SN__gImZ$spp6=1@20gsAN^OPlh432O5>^yym5;*k_?QqgS!vO@K{t! z`Rr-M?~1M*OR!h6H>1al_lixDHGkz5EXlyR!RS`X6E1n*+&SqNo3pUH6!(g8gt83x z(aFllUU_*$-p*3AAx8Ylh$_twD-Kf&@lH$HN>Rl)av5=sJU`dS^Ak&+AN-=|`H>M} zZS%8%rJ2&SQ-U-O963f%noJc4G2%Z2Y8=)=G(~y;r-^?^6Y+nCnkeg4(;DSP`h{hR zPnybcje7 z_a*?rIoh;|3;I0JgMpqDdZqHEi{%h` zu+G>YF{57vYoWJ>_NbzjEurLH%FH#?jJ_MJg&raD*IIlmM+mWZ$(l6u4`D6zI+;vf zn}AO60ZVT1sB-_c)Bw+V_h7)-GSPbt;_BN8yyKt@DU z%)}{*nfT`E!Z8*DV`CmJhVpy^e8!3hb|3!$#=oIo` zQJhQ`ViLv4;J*mb7y(0>78Hwcs12w~^8SG_cc=}B#%MZXt@|&o&qQ&3s11n5h&^Il z{4aK}C&dn;HXs_K0x36x;uEvRv5(>tQ5z7Ak%zSUPz+=iA}_^2qBbBJqZ>`8M-*q7 z6+2jk;w(`c5RDO(IkB8sGDgpr_>V?r^hSu);G zOe$&vqA}XkWD0<|SJVbXV?-;(uuyDm*2vdVY%Q*qh{mW{ich5Y-Le$F8$$8Bs6Tiv zkFk=~p7e zeTvgZ{XsNF;1d_CYt9U|q+9^hA4Fr6KSdi-zCqSFyeZ!Rqu3CQnFN%<^IuMb8|5_M zE{tf*R-mu@U*1Gx%9}uqLw%J``lTp0BZx9B&Qfj$Y8;|5>w;`#l>d>H&C!qYKTzWk zjhP+f?V}u%tgMt!$}vHWL$vH&`uVVk$jbTADUSs;4$<=Mt_kJJWXVXUTp83jM9W^8 z$CQtgHS*e&kAoVAXw0;sXm!f@$;uM?mvVkk;}DJ6Jml5?FR$nzY0AMujYG6-5iU-7URm?; zf%3di;}DG*T*TZ$xnxZUv5a!b@H~iU%o3v)btqpgE5mIv<*T8_p}yiB*JK(`IdRho zF^F>FP~#9S-?pbw-rYh%WaZtV#vxk1(NCk?z7>S9ah$88HlQxamWfN0KbVzwH<$7U zQ5z7AnSu1?B;_b(Wi_s#97WUyL}T_LF(FVMgxEznqiEAZv}{%DMtP}O*|K;3%1cGx zzigBFN!hX=2vPU1{94S&mA~%mCnLp!Vw~0a@KDP7ZTn_gw*6|{uZRBf*F8>|#g|Ej z*UQIJ&L|?bx1OAh{(U5#qKY#q-+3D$+$i4}?QJ**a`v)6aQ^FE;E=tYp7J%M`Xm5sgE4DihiVvM2$vLdw(HLq9NJxpM6DD1o)|{g2VXK)WBE z;ml?9yT#`zOH0HHtcCG6GQy#Ixc=Q-Q z1C?W^Vg=Shc{0Ll$X0#D?fnN!)E_FzSp7eC2jfG@N9osFu24_b9z!ym&TiCqo<45= znlV&h33!+Oid(8o91yj`UYal5lo7xI@fYLCG~$4`o>54tQDdaQ{$j5%0*Z1o3YFL2 z2JKQ_uOB7wE2141=ZU!6h{ag7RKD+ zia{2ymvzMY%9Hiu!^%krhn#PMN-P9J_I!U~>GKY{BT0qoXb6(#a<0~=UV!POq$uwn^qqshCwx!{^RuW?` za^uQ~*)2+lW#g9mKZtHF_3CHWQbxt4Bh;35{r+O?U01+LT-$iilIvjz$6CV|yBR4y zqtxB${r^JDy4qaKdofTSSgR1%=JYds4OjL0Rd$Z-ykK^M_<_9;vHG z;h0c1y&zesmiWB$yS`Vok@$C04@VngR^?SoUCXN>n(pVD+lq*POyc7liZ}$e**#Y# z7>nXF1BzKKR{biCH}Y1$5m2b?9@;qvm#rpVI+Yfi>KtZR;?aGiQE;`jI@H5TlX<*e z{_Y~on-A&Eche>QUF6BdmdLN>)kUOyo2P#o`H*3|$i*wmD0`}dC^EON{wL1Fkrfyb z*b*_A#WfIibu4xL+@5%>6$-!oes+-1kMejO(x}g9}%>3w;uL#vc$iO zJw(~WUy{FrC^_0r+|2lK_XQk$t_2{P)~jD#MY6k`-H%<+5Pxt|yxxJ-W& zuvFss#c|;H=>IXRx>zgR#JDHNbR6N3v!jjWWxfVnY4|){Mr_>PSA4&DMt7`JMVdim zc$9mUZfK%d^`rV$m)ruGF5B!FV&tw@NG*EG!MIr@)>zicMt!g(7oC>c?5Zzb2Nn?P zH(k`RC&-40Oum$T_O795QvYB5p38ZO;}_e-mMHgiWUy!(Q&)e#?1zrEuwCq}$>g10 zOSF5kQNOvZv=}N$vl|)sWdj=Ui_kDwb@ix9nvvu>xZ) zL{m2Tt)`-a)f#=Cbsm8w_^ps%n3!9LchGaAtN6qUN<6~IVT!#azrk5ml$twA**m_x z#Mq16s7cdW8?|=SRfDYkX+DbQwH22lKIv(PYD>(+AA%Yi1OIKPzDa9j$OyZ&xkSM( zQTmR2?Iga}3Ble*i$Q(Vu&A!a&V@CM*DrdgP5XBt8CwSa)N2f~7I~i364)+sydw82 zMHRoY6H8Cs(KpqvC$I$D#g@nhkXlr{ZvIO@oLXLzfg?wG#Ew5GQ}4eduimO{KZ$p6 zQ27_>$CfTsi+Ls*m51apdIe8aM_Pu{I3|pFsu%wC#B3E8Ca?tAbdkZ3{G18T^btXd zzP(ouiQ^a1?l#4YsrQrA##JLo#+S_Zy33nwy3>Ky0>3D-5X=0#KgWF6dkk2n&mP!D zVjjkJu_dy@tt=#r6JzwqCru?8$li4gfJ0kiblXZr3Zqx3vcA<~-`coxN$Or{dSkM!{Q11ym* z!lairkSDWL4{Kxbx*6)#$ShW_x1a9o&DxrDyMw)@mo~6n8DanJh;HS1!xH-;oP%a) za95LF_8=a}m>F%_l;{EN_x>cJ~7Ca&0 zSp?50#DIA_R%{$JNH5GPO6Np8h2iPUWU4!2keJ=Ar{4J0D(P;3Cw)B0QZ(+*CZblp z!+Mp8e<=3#e=mmM$s14P&%H2HJ(gQZ?2`NWqwRBs-)~l|GH?4`t;8@1MM2b*5jM1zjnT- zbiF)Cvanz+L}zia>iXO;FBUOxfWVTSL$9ZI&9_{&?wa(M6{lpgQ~FikwSGmb3=~*v z!P5unN4_jpk98jN7b1PnE@g#7S##gKiDFanMu&HW+)}$(CK**OygJ;dcBUE|J=s7@ z2<2`2$68jE+vLA*WTL=YXoryz;XPhh9J@`n%sHGO=3XD0UTwlbwaWa72HLL>O__QN zCi*wKw_A_5iInVcC=XjAPL5Zdb<4O`=B8ERB-;|okP*jrhvfi$=?LgRAJ@4O_6p_EnwZ#3ce)X7 zxiB_P;C}+=0Oy9--kP4$w>MhrSDmyS|DCAq_;04%zDBc{d+`TKf9q&ou0HvRc45NWILPfX4jQJw$U8h!ZFE+ zb(`ZXTJh!jgmT094);On&rB9|=e&v9$?tCI3AazG`_;)B^5jzFfN?|V`ZG?q?2h5i zy;tcgrae?UoSGytK_gEty=hVUm9nqkEIsY;_B%658VAlM@<`KuermPe{=zoP>{mlM z>;M|*l2#^uQ~JCW+f-9j7K5@^y~+OR^G#w@+io07@Jq|=#upDB@-MgRiJo*YOqvg5 zI+hU?lI!XEz(P_$%s_2lXnMdWCa< zy}~h3u4QZw#b(4T7FKh(#N~}&6u)#9N8@Z3@y`wAr(ly*aD_%@pF zoYY$Vy24r;6`ibItr(;>A84cXk4)CEC3Ns{Ew}YVf;U+N;yaH1gU_o3lqBR#LWl0{fClw50uDw>Vd5h#;VJ++-y}~!VCOcAl84FuI zgkvon6Uruz_@^1{VRB10CRbm+*T-F3{iVEi>0TEtaId{KtyvjuvmUD5yy&DI?^;$% zp3Ko79J6TeFV1Yl9k= z(>_1#qM>YxNlo~~Vw&U;Y58h#Y&W9oH}&JY657ttaBb?gXO!#is{Q&MLA{C_`jd6P z_=2M06$uf(*G9X!$6dQNw6BI}VvX4Jlr{IPB$85GIkx4${-Rp%SyAo1O{9jhN!#zv zW{dJgDntI#_C6VN)FtuxwYm95Yp%n3s%xIuY92?Ds8`)vUuSLXx$xSai(|V*tW(rq zxgE4Ln^+CeCezN?=WL7FOL%^Eln}G+E~)h%J89dhL}@Yq9wT0hqV%qGG|8}je4nwT znxf;eLL5s_2Fj*aT-!fqsaihKs!kn_((!*MBQ6h4VpUVlD0W?AIF1l?3DLy3=$^%LHO4i@UJx}Kgww!>wRzzYwSK)UY{UsxwR=Bye z!fkaKCY_K`2Fj)=Jz96WoxGvAyp5K6_29pCw{K*!fwCzc?pRaSWy?xd_G5(j^53df zxo@(82w6rTt#EdXz(sotFXE$*)Fbav3j4UgB(uIR0v zSzm(q8KO1Je4|Kmo}2afQHgIG?$0p~4iQl`d#HVLm)D}I4^Eg83MmD%{kAE@bXvA9U2V4y}Vb@8UJ;;lC zH9BmT5;(FuA8_ag!xH3c#FmKvYE*S4`FUS%_vMzv>e#5nseqY>I&0d7O4^*D%>h-1 zb=A5mWl6@8bvDX~8xg$pDl@xL_6YZA(qH4-Y$YZ~%(|d6!{$x?%c3IqG6%u11lz@y zh;i{*9{;cNhw-&h%Ox4B*X~v}bRMK_kNc=%E(qO(^Sk($S~85+CjTJTLiR-&QF(h! z-*Y2}^A;3ufVB{PrPDOM>aGawPIwmAWavh>v?6z6_=6b}r92j7b(9fl!E@4@b&BP` zXU4K3J+A3vnn!9=23}Qr_zK;&T$DC>U51KTFeX#gZ!6OVb&lows91)zke5+Lto-vm zZFl~7zOQ6Wi3bu99{aZH;RlClW8bCFIQmyzn8xkm`P(iv8P-C1GUC9!f#&-Ej^>*O z>{YzpRo2~h#A%_!TB*Nzb3Mp9L0kItQ~>7x5byc)k!BMi7S!CUU@c^Llo4)wlg!mA z2TQHutswU!BCsVoS@xY^?(;H{?>o6#%3VVAw_bhq5_1x?>-kmUnw*m|(Y*0lzuTaLA$ofmSe6IWtN<8V70o{G|O95UjgIoVv7zEyIs8)-N~oC6s#Wn)WosUL}ad8fr`Sb~g;$o5EY zHBO#rp7be^_pepSoOE-r{(M)0=2|~PVsex@8pDj@=B+;y`J-`H)35~PVM~-dNz9xjTgIKD=$N`KN06prKX3Ww;J zw~I0^by%(UeLhS(_%nriRo`KFnpKfFZd)uwkKmW}CYvL*C|IBsS&Q z^djK=tM;1x`s#l%U=}e?P)1G&=6eEd1lHxcyBh zfwd-ItgW_R6`)l<9AsejI-TLB9aa+Wx8(Qyi%C3?SPRi6(<+ZtrN31WFH*gjz>;w85RuQlRpzLypiKWgfmc7B?%lWuoO@0Gk) z>hrb<-U4g6F6%+j4;8daR|ovX{aJgn6-*|1F2Wj z2yuiEVT8b1C__e!Yh}+$Tq(sD-)kreIrmcYjds-fe;O$>EquI!)znmb?e^qE1NkhG=aO#pi)SjH zOYHdNQ5_}Q656j0w&)Q#li! zn~z`6iDO&HMk6C^jykfJ+im!?!<{4<$R~sLIg(KzQ(3+?H~-_+S+d+=uTUPvWlT1) zy>G4g=9OIpexDoVI;tan=F^h4jxpdX(45ftT@YjOR+ z6@#K!*W6MTyENjF`O65bg)F_eDw#|+ndg+?k%4@Ib4h_K8P-Cy$+XS)tWvx|Q(mMb zy}J!-EuwLKq&4wShVti6OJ3%+lfd;HxlC}EpxnOLwTk1rV1CXem&AC2{L8o#nM`G? zH&INX{rTO_S9IL_aIeK3m0oIcZ|#41W+Y$!ue>{BEkx7*BQ?P9#Kmatv1-1=k%D~K zc=|Az@|X5a)ANqt>w+do=MqHV35T>KadX-bIxUq_LUcS8;n_z%UzJE7U_L{qzFQgc zsSg=e@B~QOzBAt3^fr6|3N6V1Qry!&C1u^-R4c=M9ayYX~FK17Hj zSN$d454@$yx4X8(Cz^NBE!BL*PP(NcqX*ttN!xQzGzZe%`TFP8{&+{mT8JjUnlaA2 zfnG$I+{;_K(IXmf-X_!VT*2l~zejVM3VRj2>mzFjS`$nreSTB(l03v^QL83H3k23e zG;!$-=#=)1>?O6yUV?TJ;dVlNw5&WM(*+zz3CTK6C7t`Mc zD9^w5XKd*Jt3cs@cK(qyT6wm|{yVec%4ztgQcvbZU`+4n->980iW zY>BjeU?{WOZ(%h*^p(6z?KT}#r&Vy&qW45=D32^G_lB|kAxGGfbzyu%>u0L(Dp#%X zy$B5v=+hx?k<-Ij*ww>qvV9+pwa}X-BQ8A}!*Y9^Wq&60;^@`$`uD5q*wIb9u7+zU zn;3h~O=e5$USj1=b?0ry*lX!~%V@`zhH9It{ZPm3cGJd-0UG*^Os1*lr?B@Knartn z4@m~rLNwW_%T8sdA~V@s{~jDmuvgeyvJM`Y$Ht7i$IL&wNZwbsUnRBOp%t|JX+)Fvr8WqACSsyM)l*UKd5~;{}clm+L>LNvXi}TBkL~y zqfn2D3#mmTW;=Wh^G=cfQTVULe;4KBe67v4`7UQsoriEZw`=INAam%a%V(ZRTY;~?J+OtYMwUdE~YR{-WTH3lk zT044D)o1-qZ9{k;?d7=IWYd2PBJA;Xeo^R{ZKr$e>(cF`)fMAmcf0ethD zRjk#QNlYZ|)rxiKtIZg8Bw%QRz1kAdPixipNI?BPdo=sdep)@t6SAHsrVZqscTHx| z3uiGb!CqlY6m{RJJ$HF`o24vFkr3EJMAMCaZAHGr)mhj)e9Oi?S)}>dbu+f}Q%H!JVXwXYK|@lSvlwQmW-lH~PEwT5FmYq4w2sMr$4 zy)LZF(`U|O#p;yh*zUt48?>3bdT2GYg@4KT{-Y89+2p&v`_Xx6J}QK7(dy(6)#kY- zsfeaX*_3YFr(s_9M*qUF1m(%|k&w@opFJyd-yya6ry3)*(8z|GskpoLxzb4O+FDI( z?Ojs4*(O=*(Y>+uVuTZE;)44nc)wdUgjKGi3`=mdc{db1b^>zH0zEztKUOZvM za*O$(AIFmS&n9WV`?k=k(cK?gqFhTN9QbEeYqq3JAjeuCs3#RY1GQ;ZPJbcR5Dmhn z7XG4NiyhJo-d(j=TTr``7V!A8x?;(Et?IJ&TGx;#)T`W!?0ILW#-ii;)eK9phd3sR zRjcm8dt85{*N(2jeU1#$f|fDuO%g?-z_}Spou%ko+14)4{ipBOzx=Ag zu@-)58L{)m1NJS*g9SK;a*T9oJF2?2;E|VBetRnoR|$&J3(CWtPWg)Z749-bU=NSP zwAA)DsiQq#sZg(e9(ADgwxHwLV_=GwxP@SI`0 zXO@I$ez$!!cdJ?&wnWVJPh5DfsYS)QQw61Ob-qf3mUmi!=24`AhG=@tV?_aeHZ(}@ z`#OkYPjKXNuR@F5V7}K%F%}xe@tfc}C?lp)ui8hhCsH+A}}T z794dHH4$f%tj?r~Ye*9VNE2~2KuwhOYA5~AiwAz!H#|PiaOK4Rx%{s!*P$jmU3?h} z+BihOE+fTdpmm2lylypE|HDgJROS%Lii5QS zCExC?RqcZ8wR~Gf8rTx~QYog$ieie2c8!tZWUwbFkGz&;#GGL z^=344XntDhwMLeK-v{MU1cc8Uwtbnqs8pw{XzO!H_4r*>yZ&H^f#aw_(OXt|9JKv5 zu{83-8}G9&V{3`giwX)XSw&G=`6x{_>@D%ure?C9;l-KP^u7XX!TC`u(^ALghgPMW=71CY0tM#J0TF*uik_<${9ggPXS+hoL zz=$>M-o6M)2Ao9=8Bu(38}`ic02A5(F@PI1r;oaR6zs<1q9(_ zU_h||R_t9=6crT2f?)3jtcWP~-o+009=P_h_OkZg``Y_Em)-l@$$sDe&hunGGn1TT zGMOZkjOXw5ljSAv0aqFJr{1aZCbNfBSDx6~7Pf0Yr1 zF3u2U`R9a-PYx34y_3dEn0IgBoD`+`>S?VH z@9r9x&e2>R_4dc(#BiHG#NMgBr2oO|!CQgOx1Sv@cAU=>A!YkY|AUW5{%`2b``F%M z*iN0e_pYDRcR3YD)BI5`Qp69>7V8cV(0K3Ty;AO1XUv6g57{hUPZ^}~k;8kt+;>0p z@Dk(o%SEL^vC^&#AA@`ZQ-(iUtL^@KttS0J{y*3nj{YE9t7)8ytWjHrB7*#*on^9G?mwyth*&tt>Wu z7EQB1t1X{)(>T@Z&K_9lnj4zswKRDt~>&H20}BlbkN!jN^A+S0%m`l~O~aaD9Xbn(5M|9Z|8 z99Od$78zE~FtK$i{+iheL*0Jn(`}AL=0J~(Y2!=m)bkSWg$r@>;&!+u?omGHM6Z zN8s#WYT}q{R^Qein!$L@k4iIC-iX^#7Qpwt3ZD<0V`x zuC1cfzH0|PKa~~(eS$TvFK-1I@u)#Fa4J_?tLm4oe__~!<3oDmo}bD2xBNF@TtrWd zJ~cYuCU`wo?%5qrzFbJHd$+6=JUuP6b}zD||50ycCMJ&Sh{gAu&bNqKiJR#S@iT^9 zgji!<4OV>i)-w7Zlo0mmi}Bs`_89MQEuW)lr+Tk5l)rAR*|oW^=e)Qk@*i}a5dg#E zV@3V3_8LcQ&0mLAw)eo@5$XS_N7A{v;OJjp6U%z*PgA_42E|ME3_g^{Yrba9c8sK$ zjMW@(s)zNLSSVfjM}YO}oqAs4Ls6CT6jhm#`zVidqIqz)fB`egYLQNwp7Z4`4f8kS z)04fiqjdtw7{5VEzRcYc?p-tInl}Gx&xrh%N3&ZyJ>o^NixNKwou$BvFD-x zXjO542*mg=5`Qf;*LaKaw&EHp%0~Kw%jpl!p+Cq+5&who|Ikx!|3STdE%kP8ad>a% zqd-vxpG*REWeG8I(07$bo!VC2jSKhn!}^KQftz+_V_)lN46eSE;#d6^3qM0+ zV^vOd;g4*z9}@llK`b~v7!E#JEo}Z0g7e}rGA^64K$RT^&3CR7V&wpW1VOeU*4Nj8MSgGt^OAgMTnUsV_U#hFV2hC!^Fwh3RLqG zgW<)a)k1kHq`u4l`DSXXIBF{ktEG9A4e>-0SRX7QEc<-d@e&hXqgHa?oldPgyW2W3 z>HJs;!Rx`%igGh~r)cIp2+n_X7ZLW^WI3bpyzQaDU9Waw)#lL{6Ke=u)@>Kwdf6X; zuXsrHsAt&}=4>s!N!>7m=2qSx7|S4lo%tLPT7v0$NSP7 znchL1N|xc(F$jj1D-S=rZQ(vr*;}x{K zJ&oEPeb8#?upsi5I&K!**Y$=z{%Zv<$s4g5*EsjVp2y>ZxVALcf;Uv0RSKGHcrHaI zcqCOueD%u^k$ZcLB@*Q_T_w@DA;GBR3h#{C`p-~{V<(rUz3SIAyl2ul1c z4IIJampl@pC@T-wh9UKfz~FVIftPR@oD=QJoSrWlYn|Yk**!_CQ{&d*CbcKN%3l<; zr}j#;JJuD)dKlxo+w5vW#RuQTvNG1dHQ{`RN32BGd0nw&suA&UZklMZpe@wu`c?1} z&NpvRCYC7I3GdpSCWKR#B|xKh;)cHq@E9^j_nMQ5FRyk)v#~}*L`JGu(kC1?J}eHr zg!8rUw-B=(BXRVdhlDUVnnUWh`{H+wCzPAK5Wl=?haLSMNwH8KnWFermkQ9f(qoa* z(-U|Jm&Z9N%2~>)x(h?WN>^Tz!8JKCd@g1$Y=b`6-ji0L%NL4Oqe39a!UA~7?ch|b zd#4qeefSY1%lJ0m4C?A{iy`%Wfk$gO6-U!aa^E!ZwoMSgG%MgG?VMB5(Xut#X8j0C zJva?5pNC;3trU{C^sX2ffF!ia8tB=Z$w=AktS|udBYcPCm3Wg z0>@Z{;L4RXkyF{tACEVKo8pK4#t41qv@{X))f;@CI|8TTn#hRnQ9s4jUx!6xLa2n` z^5iJz{PdsV^{~TY@03tUD;`yq5j(!m6qlaWgEFn$B*dbJi8#Ay2$oH*iCViZIFQa? z*0|Jw>M>)-Ut+1-0WoGWodp=v1vlFG&kI`&JxTq!S5M!hx6YdT>sZ zU-ai}QEagzoIUIVVV%RV@H8Lnv_M5p^`=iGmhbC_&+axPt>)jIDeP=&!GcrXl2%-I z8L`Ftp>UtDTO_S%13c!hm_FxQ`-i}aw>|OHIU^#!*hJCtMRka%8wk9F^W7ilf%DtA zW3MSK3Gu1Sc`8`#{Gmt z;zi>X;^K<#z$5=0!PdJZBY5Z<5w`cCn0F*nlEKzz$T?B;BWsOlzu}=+n->XOI$Lf3 zXZQ7u?FF&9)LIeRvoml_IA6YJL9bwVOchP{RDtLcD9PYx-fnbOt;J0-g3f+aUfo{$ zADpke$5Q9+Ea5b%2F$Wnf&Vqmm;Zm-zMc9=e2m{I9=>iP^()So_fWba-E^*4Ho_j7 z74rq&t9eh9Wn5hNM$CSwiKh?3q%p`X10RnHxvYytoV5$+qCJ6+B0fH3#F|Ur#o3z2 z#l||J(yk@nmEo3;GFtzUE^htl39g5of!jWAePkJ}^9zGj&?zy*H(0WXTn68pq#cu( z#iFlh2;KMC0k^eW6K?0}boATeuz36hu`WtT^9Se4_aiBKetEGd_b>oTe60q2mf?K) zd__Ce+e<^?HrGY-?Y`1H$ocXam3A5uGlcm$gu-DJrP-O!oU)9iZ_0!Jm?r{*WuJlX ze{uhTavQ$O5EmXcg^+wR;C=$1&t=4_TUIbU{iQgP?;`m=Tn6`|=(J&Sricq`3A?5! zz&#|+m-||D%A&h1bQ}9wET3)-yoB@R-XLXFd6p#_-;IQJUQY%0^f;RPjC7Jbwl?hC zQUsEg$lfd8`Qx4}WuZ-5BaX#%1jXt9R6SeRyG6tP=s3YwKYYc) z(KI__Q;1432dh;RBpG~F#8+hWW|&*HsCqmG+Bw#fWN;1nx{dB&^$CM*Pc5L6zLB)r z-kF+>?n%-3ywcJ@88M{69?`;TFw9FYCOB1kr))gDHX5VOWJ;?^MR6(D3Os&Rgj3BI zs(eMy*UnouXJg>~l2M^Bxe$JaGv#zT^^ zp5$ebJm1DPeq0{Optg#owpvQ{;QI3Dhpbf%=l!DRi6LN-dMtqR;xc#}D$1*W+G-8` z4=#hFc}vsEE4C$UxmpSAnkaiFYYgbRI2dB!U7}*_)kwva}NQfd$5awo=1?NrMrKt0P$=mVn zvA#GZ(mS7{>2+Z1Yyowm;Zj_jo>R?=+>XO2ex)Av%9mvn@9hKXnG)br|AiEF?whz7 z&(`XLC$7ckb58U>dTka7t9nE4W@{xG9FasZvWtJm$nxp6v<;iZx2)bU&0?*dQ$h31 z__#wKeBmCSFC!XlstvE(7Xhy|rM27Z*5QkiJ+W+^^n8w%@r(0bOC=l@od{BO_%UdIt2wm@|v=xrTHmwWBRGNct?s&9&Be#GLOs)N8R4 z%cOP1)mg^?_hj&#M!fkwpjOI9#*`Ac!>sEf3l!FNf@ z&d9{-mpkI(xu*%yI4M(%Z`u-aW-A)!%c)|cGwF0=CmiBsMD(9k0hTm*BnBpVYU{=> z#9`0d;iia3`5eLH`*aHFad{X%@rej->Zx%mu9b`!@H|88zuy$P9W|2>T%NAyLUgx_ z#A6>Gl2-LLl!hVXQ%CLg)%Z>W-@)pvrs9X|t?)%@<8EKdoP}a`QV4viXd%^uQ{_;M zY#qhOJg>bc#D}pNqUceCy!I6}PIb{X6sA1)RjNxeIMth7)9CI*7$W6lR+M4-!qBGPDe+y%dv|=d zuSdfPXcpZR2NtSK2>QDVqtHk<}CrU#~=nZgYN$I#Gv3=GF^{71Rkr)xRQz)O>NIO`3FWnKs z(Q~X1wp(Z1)!!-RidAv;(6g+s#!Gfr4X3lsKGVX@XuO1L#W~TrSO1&B!e_Jiv8lbrHQ{FhVs8tKx#Wo*9vDv!^gKIDtQ}he20N&d zR-CFwj=;?&>f^p6M#P)47ex8L)`(UEI!k8__&EUIAP<~V*&XNZX-SBtb*GAItE#|t zOVl`DPSw@c1Issc#}*kz#D+d=#Fd>7Meh@l8t2PmOaD2SF_(viM^5ID7Tn39R z8Dtq%ToT08v6k@QL1T@VaIILxi?muFb4X0`Tp=c|qtiS8-V!iy1lN`_Q@ooXT0X80 zN4x_i8N5Y#i_o3XFXzOF)b*m5TW5{)N#KTQ*ob&-jH5w3Eh0&i9mFb z{1Q&Z{W(P`e`3C9o!bdkR=KC=e7T><{YN_cQLQFyr+vIG#<0kG_Q^gb}@`d^{GfvZ0_( zCT;0V>H$<2PfP;+Okcrx1u+>xM)XKS0-jnlJ&5jLZ7rupj8BGrmCOnd|L`iHS`a!6 z*B06KA4E=gfI4B#An1HQ|9=o$e1>8X-)sr3C^shWQ*AyE1F>?6gfMFL^mjjO`bRM| zYLz{pC)QqG7%9$hTOV-$)mU(7)ym&U#s8WyL)Y0l;b25eqRel0C8zDB_lnX-sii!U z;mFfcQq7H23ExLxxk+9HTA9$a3-DrdK<4PN@Mc}2YNRriaCye>fBr1B)w~}Ws#Rhr z)NNH$GnPC!sp7|z5eA-Tf@hGRRZ;#bwOEf32>)s?A$Z0MjwUPGb+P(aqo#1YyN#5~ zf@i7VvgstplWXd(%8ejqySpUANcFBEwPeq2qt0oHyWSB-L&#@(E*toi*Ux3@o zc<@p)B?RZob8pd2y_F@@0nLU&uKy+}D;JkxM4M#O9{tBbjRuw;0eJy(77w12Lq_y0 z+$;Cmgt72&+uv5yGzN`SCTqttZ_v%+K7D z!_NzHemKsT%Ojt`)iXyuodl)xeGA&kqzTuZXJw;!`$MzbCX|gN&asQsx;!(9jHq3? zd+wa0NpL6kZ!2oDiA<9qo(Y3i+gmboyB-(|TNB+?UPGRfL(Z9*Hcy}X=*3uYA6Pno zBX~X$o&$t3N4o9LU37meT=7~Jz)QFc&WXGXzr5TDFUNxO!)rObgy#X2GoI`^qvakZ zyBpX=&Q8g-;+*J2qkqTTHWSA}$L)zyHWDM1$#Tkwkw4exR{fL$Pvhl`q`XBrn&Lhi zC@b)&9xylYqcE13<_w-MgJ;>Lb4z6>1dM>eP|iJ1%3I6xb8t?IvS7)TM&Irxf_MDX z0vV=%&a;v5EG2ZFI_j&x_wwP;m^^-7!t>S|Wtcco&YE9Max5qdZM%$-k_?{jmCK`y zK&dkVtZ&3a*M*r?~zD;kiucZn#&1THhlKKCiDTA-E=TjueN8 zXX@cse&9629XKzehX2foX#6(Grt^sd7OAIun8AfP?WIg?>>eDldo$$wd~CN}Jv5~h ztUuFU%KpvsxUqXWgm4KwsHQhI1J`=(rHm&$ql27>CI0P4byrJkI2YAa%3s3kA?NaL z>wI0Uu2h9XgIfSE;e6R0BV#@0Z&V-DbcH`_h=SHNwGYoW&N4q9#l&f`KQ1katp(X^}IkFJP+w}$os z%_Ib`Ek{%Cozqv;-PL>{?`pjQFLm`VPxQVKA@vM7Q^>AUU)1vkKPcDRy+DSk|M34| zx|L?kutKrE$p&@kXD?VXq=A$ph4Ynr;+Ckds>fPy=(5#Q%6P(VR~2~SCT%II=2T8x zZ{Q7WT6)5NsZ9AYjGptqh&uh2st=mBgLb)P3+iDS=UfxZ3g*}@wi(th??v^P&`VPv zl%fonW|mUTPj#w{-<^W7Zs7ow5nFcMRi~!}!t4RHB!p2DGbeA1^J!5~k4eA$(V=-T z$+&5ILmk4AkMwuZ<^|- zD38=dYR{lS5R{fL9_p&%_|$f&McWo=GV)YAT=dtc5WF57tteW3lCiZP?AmZ$&v+Gh;U2?>6Zq< zo|am{YCEr24~#fc)L`sa|NKD%N7L%=aISi;%OE)YS}(~kB21A2EqI62lRj>aQ z0}DUp={YafJ_YjrMXafDR~=I%2x2cdX+|p3nzL9$b$t6u#mMKGpY`x`h~QJT%pQT^{mz{ro4B!uX7i43FX};FDny7&6Pvz|o4*?$t_l)Z0$*^+-_(k#A;>Zx**i_j#@o zT2V3{Wvb7bwS%I%vKr^bTY>i;T1`wbs3~L6?X=gR@e+Q! z+gK+PCq>y$b8SnSYv&&fk?uS5yT~%)IL);~X|8n~7pie8e*aiTq?dlH?(Sv{BNLlS z^|I||pDZi}))t+lJJme%telHAc+*jJP+fCq+q<>K`En|r$yHJA zoHM8^+)Bc^{v9;Vmutd2OVTPXbFI2>UU4XSvZKaJm@jJJoM?xa;y&4D-M}u&U*j#x z<34ih&L?jv_-}7Xy0Ok%S4Jd~?{k5CpYpxkrJMJh%J^-ve6$ls<739(9zel}GTA;p zK4e4)S)V#&eG-or)%ZNYt&b65vSW(Upz|X2ZQvj%IX7Pz`I_c!lkXKAG3zVE+Y2HlBMPuTT`P^%kK&P?8-#_xZ9 zpHN!Y4yASNZ2ty=#}@dy)`<9beZG<6B{L{q;+AkVhsUgVyu^t3H-0skVoP2WTUzTR zza+q8OH2ms0@SVAGoWuq927phP0EhX<9nc(%=E{PHGZ_W46F2Gva z1=w)!@9|+86Gnt-7r==4w{<=KiO^?Jgx*MH+Ji8Dn zsZ4tw#&6TE43j~vyCX73o%M1UOkT320AcdNj8rC{QARYTeVnGWk8_9iag2OTwKaa5 z_Hme2B*V615G?p}pZKIJqusWziK&PE(Y{d-WdgFnGnDx&d1xSRK5dB?9TDR{_|Z5Y zRoES7Mfk({sJ*(#b2b=TKLE!?AaeA)wU*fYEaH+4jR>*w`Y!Ru><%z@^o4@9GOcAe z+O4J~j&ch|oBsZUh>MPbhTX4~qRt^0A7An%#H^J5 zV7PotY-;GK=TuyG8L@D&H++t+2i-+&!KHIFmreNq-fR`IWn06yr>_NHZEDf=z3-%vV1b*(;rePfP`{tUy)FO6?)J!oDVGWOMi zv*~)ld2w{-+2**RLpauH;7*9kotBHsEyH2Tq{7nbj-!)*SHP3I!!fXz5pioz1SI!7 zF6t}y#pM$glr^9gS_&8Bd~M5Hpt*B6-iR}5l{&g5xYsj?$oUTir{cQHh}NAd!Rl5u zA#87P;L4_t^r#KpitiBlM_qwS@8VPu4G&u4ct;l;6KaVs9opc-yAD+I@~W03 zgQGKwT4LtLHn`xT5pi{0f;hURDU9E10bCQV;f5`hv01gYcw?;*kr4S>%pI^&IPGl< zoEO(*UCSzXeRUgbKhvHNZI8Yd&eO8QOuKf#OLn+b!zS5nF|Mi|a!!=R{P_;CzJmpH zoG5@x=Tsa`H!VU!MgMuBVAih+aNmHhggGbL+isdFJR?&@6{{Gi*TM#4uD3;((>0Ov z&2Cu@PuaCa8-F{hNB^z^#q@q4nZ%m7@LN@U>(LIK&)Z69I?*`I zR(wfq0^cWD7kC+_Xav`gqv?H|n+{@JKw}8`S_60qmuIw(CQft*t6{vjc&r4}jBEv5 zcU~usrVQh!7l;m?@#1&W!N6;1-O2{n2eidf?`tAQQ$*OiiSRue3VqzFNdJRt$m>Ka z;Xif?tIp=ouL4L~afJLo=EGZYrQA}H;3oGHt|6}<%?8){i&>AG!?Cv&B(3;A=Y5(Y zUX`8-%ULy`LPaO3?{ZCe&!_BSaSl*q!V$4xoGb7i&U+#sU5fI%+8nWmUXPqM*9`c0 z=6)%+G4wiDLP@ZArzxA@v(4@{~)*}S}PR7~P{Kym(eb zvR7Oy9&MwW78R^u$;}=ZtYM!)J`Hajp;r;{l#4~iqa(6lKR&(@x z*5_#MqtKbuF)bmjwn2=a`%tXBZHuk1`eNHN_Q?M^?+X-3?O7P6=Xr~M^E&`Xa2w3~ zH0|B_dqIWFX(D-yi`3h>49-bWUbpQBr@oyNm)hItD<7(g)^uZi;0!n9t;<`TZqfO4 zgLCuK#p2$Smz*KE?!5O<%}c~VREzbZbm#XfFX1vcC-UJQ4}>-+GQ^k;ll7DRs^Q{o zKA7`|FLF(ItJ7VwRg`(ZLz-|1uc7f0?pbn9it@heKrQh^rY@qzNpWwj4_Apc2HQfVU^uBmoYmDDF*P;2txB6ZE(F%q1`yTg!NkMKnct!wDuWpMR-Lz~2 zJUFxkR!?;zgx8J++L~P>)J@yGftQT`RUapgYk~e_ose^)d`r5bT7!T^x=vP|fm5mV z>R^1iR(RUp?mq}WpA0cqkxwbe&>k88nnS9TWX@*uX-(vQ?DdFQENR<22RDbk`dLZ zx3AE=#a-&{TwmVXWklh2Df;P+Ch6J?9s#_4xQ4t=^g6ItD{a!SWW9Q(IPibV{|*0} z6w4@W4bIo!3dhb48t+TW7CS6k%@5PFgHY~QKON~b%8M*fu8X~n_g79O_x7#D0^xP7 zNumqo!serhQ^_?q*QTg3BNK)4WCRSY;)L5DwZU!k5&u zC(1P47T^2TMDAJ0K7&5%rMhxZV>l6P3$>%2@WK1GSZ&+iJ258jg`;Wz<5Ga$bAhLr zvT+1V98m}NUTlR6UF?u+$o~!H#aUWg@B7$C+-o*cst4~eG9sm6YhB_U1-#F8mFmG| zaM|>BP1jkfdsZ-XYTyW4eB5yFm)2<4$`*N@c#F_Ur{VYYr&^a5d2i{iSC`Qg<=D61APBxw+I4ANldd?20YJ)KPN-bEq)e9S@ zhhtVfCtCmit0Ct^tJDPzwf-09suhwwVX2uPM(k{YKU6p5e0e`s6fv%W_PtZG8hpiD zst30#GU9Zv>-tu)FT|Wap)m7v0~9sG@$x1oNd}iq_nntE(apCFgk}d_pwyp@@WRVb z47GAYUMJ3pPPg^!r(Ha;Bf#Opt^fNWwrk>voG%}nbT+C`b*)F+7ve+PS}?9r z0E&QMjN9Oehc5czqVb_vt)H8OrcEkpD-!=b_q>-`{olN35keifhRK z4c+v%jmrI4xDmu&t0(n#&X@mxMH#vxOTVDKK^$}KA@xL#kb8TD!$q`-4<_g+Z>?n8 zdEezdpVsF=393U;0Z(qbN|u51<)cecYI^7Bezv|XQU~^x>=j4ImceshNB!fDO;vax z&x70=@G(#OoF(3s?i4*Vq(Yz~Qvjq*&BitY376BT(8X^Sx;k>>A zrw%s8;dW1-pucxD4wmOd2~KrwcOx7*6VP&x59(j}V)01=or@R|#gokRFGk0}@aefi zDzWmz(+L7Q`1(om$SuM_{0n63<|*Cu0i;Do!5V46giTs_t@SUR&UA?Tn4WbN7Grg z>CLniTgPX_w(iIheOd#RHbX*sgYc42cfFw$~89c+{8bL~(}V=2{`0 zJKSpXMsOKicaEkP)3=S%4rX>2QDbb>C)540x((ux6P}1+{#c=Q5Von}iCjb4scvVd zKUl2^G$>O;vZCCo$uhk5cxyv0{}er{DUzk;R*lQ1RqDnh&Fgm=bz!8hG#m5{^~Vn0 zK{)Wchom8$h~Jc?rBp7f+62l7Zbdno_UK*XHK$V@0!qDGE_iLZCR{^`suiiDr5HYl z{y)uuQ}NpJR-m1R;pOzn!-8RZf*o)w{x{|Mqjs|>ZP1&;VvBQv;O)-;CYMc?VU(xV zU`I{xIifil0{ z1-Ag)uE;Vvj5X7{C&fUIskuU77Kd9kE}Q1_1Jl&dLl>;F+b!Q z(tVt|Rlrc^ym%Yosr9*Uhr2BsVb};nzBZ873`&WM7T|QU1>AYrSYK|99a+vsD3%8! zN6S%zcca#coKoH3<>(`#keMA$Y}N=3yF-wp<;X;a%PNugsViLWc0%wH9`WFu6eT2~ zEG&s?4bO`>>bZ1|=JF^Pl8q&}-g__J?{}6~MI6oRM5lL(PZbA>_5#P4Q&K&C|7nkr zll*YAcVi5+bHMqJ{jjSWy&9yLEx9X#|LhH~YE_lmic__qI~q$j`C(@HU_#6+^Y@w2xRo{9ED+kVD+oQfPRo;;6-ifw)MToYao8R0f@ zfQY-&3J#c;)HtG)ofC$1^Fx<`!T9l)Bih{X#S`<5^;i_9h-b}vfKu)+!8LhV#sx3l z_QfLl5S(+t87l<);mk@#tTLh!mT~}`a`>N|yd<=Y^Ur2C$WA?dX_fvit zyC2bFt}A+-@xyV+M#PX8Q&j7fJz)2ikA`BV-ITw*RSeeL3GkA+Gp> z)+6R6j55ydpQ*q6XDsZ~_t5ha-d3Cwt%`i^>vDG{L5H`M1n0}Cc>T!wgwIhs4(kpz zAAJ*CcTUCIkXA*fb9B9Dc7X$P3Tga*@V>*-BLMUu9b{9*y^IH zj_(T}7T=Uwm-j2)Luq!-D``9O&t9vat#k4HWVXji6K9r5LT5^RYbs^fgQCNkpC zpC00Icr+x|JS;eZk3l|~>CNJQEW>rO4BQ%U+b&zUDOM*%q2|57&1b4K&N-EAMFUbM zimXEY;9i@(f@{L5WJ?`(%T62Qk6@c@EBf8?M%`i+)$-0*{+%CQc_Gk}e7K=i{IT9+ zz_Ud>sVC|O6x9}r{$hQ*wh*<<4R?9^WAAKRoVn2lhYlCmr&=v3eyJ$Erasf3z26E( z+}a~bu5d&5#f@-?l|6EK98Irn7F(efUVlYwn%y64GwtxlvW6Ji(gC?VISzO5V3_`( zXFu2%a!hm@XOC794RJ-XBXW5hP1!;RSBAO0D#O?r72ruuHSF2j8}s(NA(tn|$S(S& z1voVy31g0o6lry>acH17_HlAYE{~%rx5%4dSd#1rU#42>qU%=2MN_@;=X_t}@_0;6 zQ7TnEtZq1&0*@z;&%K#$jq6FP%rd^n<#9CK$BDXf&~Zm1w75J?pFGn6AFXMKn`;Fk zM|0Vf<)#m<(azh$jB`~q-uqVQ?6K#MhS;l55Xy+=S*0P2PU-#LYpwAT9)aYXXg2UU zAXX%ngRIe@alX9g^YKWL)K`|m{<Zc!CQS9pcmX~PxKmu3TQ z^|?HbCNG?3oP3&b*3pc^dm@*|X9n8mq*-lKgZ|=5WLw~4g3IG*+To>{b2!bMMQP^b zy^qV|GaT*kc8<`8=@Y?bW_|Hjk|%a@3&0UwR2=)(6FWKu;DeIlKM}7+SJvo$t&W2( z+D5^t`1+HtSn1|{-IeP7$sJ*Payyd@V}(+n;!F*457VDGln8}~cuDo(GPs766L8FXU6#{eNcyo? zNPmj8uGH#E*r#FoUEdR7?3Sl0?+tv$k=tr*!z}&4k?}BfXS@#|Yus|meK(m9afF!s z&cT}_IA1Q0W*kCHB*e+j{r7MLw`%%nEy9YsR)BgBod?t3^du9b{vO^8H7c*mvf=KAuQ%ZPD=h$TeLE4sbB6}iQc5o5M2 z6S`i*#HhzHl;!6CPM#T9?Afvd!`1CEF=ZzeelE3d{7d9+5sIepVDDvnO}tBM0EwZpS@jfn0Uzr@IDt3`5pgyuiE zGWP7-20!<6G;qE@!>izhb#1WLRC_`!`20)s&RQiN&Wq4E71v!xbgrBu+@K=N?&_~` z=^V{v(}-H#LX>OS6y{a1()g_{j-Fe-GM2y82G0pc(rU~sC-7NwTzr_~to6HYfprpF zVOlj81LwPEcV!H`*BTRIjfe`9pNS_yHc;)pgT{Gr1m{Fi&Qb%#hzczrE4hMnr-9#U z@cIS)!<_dau^Vn5S$a8VW~Y;^jY5m4rj@TsLJMe8X_=ZlAD3wx}g2@Q8UGyx^#*a zN^6{o-zAd~rJUQs#}7Y5r^B=K4vrRhd~q}UJ+;1pYqF@61;*D2M`e&3)uZ@@)-bK= z50UX@p;YsvA{N-XPdK{ObTi0^j31R?%482Xx$mZ)YsF=7*_1&!Vzww`-I7jP6qW9) z@p^DhbS}JDC-}L!1UO&Vnag>N9%F%#6`Elu^ZJG%iY4}_9gN-Y`cge!iT-fM;+z`ih@{bE1>WhMEvi#UGYWo2_3v#~ge8)eJLV)|aR_n(i*SED_%` zTEop2-}L;}AHRdgInlkl=AkfgZfO`6xLnK~XpJ6QR7_h32F};fiBb%{KumDZvO@|M68E z`cxiROxM8q+I6+Y@qY&3kz0baioIe5-A{(W+|Yw6iyIr}6|=?{6$Lh56DXm{`Z%u> zF7BP7LZu4@w+Bo&k+_B&O)p4(-6ST}=?tG6oYC_VE{{dINvo~5YrwCsO(1&PZ%`IYer*SLP!g|*;}5CL#X$3LNWN~SacjwMyKxIn zBMQu+ccd*u-72YZtHw2v5k5UzfT7-D(L4B^p3f89igHdA_h~p>{IY8X6N+0%vl{2i zHKeQ&XFmuvwJOB=J4!PrN652Uo4u~!GjNX>aM4-gb1K)6&v1(3(I!HK8bTp8%}UaW z&zyXor`_;+Il{VbMQBC&ulS72HR0X>-9+m6i{4{dBi4HRPP=uFN9`k+!l4 zXg;)i$-E-2iP18cyeNvvJV+4d&Xk2(&S8@8!_nN=Qj}jC(nWK>xuROq0F8S{-1p)B z9K9gfbQtWhS|dJmuvgg%+rU=z|Cyt#pG3pX@RQCp5_Y^73qn(+5yks1mrdjRcsQht z(1~5cUh6p(*GfiMcif~qf4`8}S1MW3>iZo#^!>999++Lz@T|2HmU-J6b3PigG*^80 zO@-{g)XRZmBn0=uIht&ue`#2JDM(m1Z!IBsALD7R2May`E8 zsI47Xl;;0q3ur7FVQ3%ifrnd!qx*ITL;CUhxF)m(?m6v5^(d2fL%+58c3t&ZB_g6mSa63=?QJd<(aJOS3XSbb%;4>#j|9!UB>F=|( z5`x9#3>-~+!VL$*Fqf60_>wl#Jjneyt}X5AZ;saLegCF=Z*yADYsey-2Hql+2Xe#> z{iIDb^e>+D(fFU@RQ%5>%2cOzBC2h=S}13f#{U7Ql6y%|qtbBWLXfE5qP1jqc~6uP zRqMpU)itZd&M$U)ZVmWIgOa=#xpjl-96-k3=KuuTgEDXrN%nmf z|8v&hVz(1|wo@f#)!=A~xBqjV;mznHdS1fiaZbwrotb#_va#UOd7U`=?{gW4=v>B| z2v3k|`0tr*14olh+&Dy?QoB2Zul=EKQ{DwX(w=#!F2r#Dk~7-Vo_XO)A%-;CcfP#G z4;#Kl8Xr&Jebx1@mjw0cbONU;pYDuSo%}GZb+DmIsw-~4>W5;i5wU;J;oQ38;$hb8 zWqMw6iFT?DNBuB&FG})g?R24J^h%G6vqcqn>%$ z59*%0tj|q%#JEa+__}ptLzQ)om@wWCH}#h5M60{#Eoz8!3N*a3O~+;MI&n0;kk`Ct zfNQNDQ2OFGNvkGH9nmYs4@Y+mHaMg?;p}(5czK4g=6BMj=+=H}3&YaN0jIh<#t|3N zEtu>{_#Z_6?l5s=Ml_Txm#aTl!X68s_rn~s#)kDn?Xk5>BW&=MT9?&{GSH+i7JvB1 zL)@<%mCN8%98H;Y3|+*TKu2gaDFAd!>~YRzKOA)#4ZRZVvB@W2%qxKgt|6VEdox2c zf+*;kbwKLvy!Xj6I+wpK;xoEIohsv`5yg8Smrc6>+2=*Y6a^L(4VFf2$C~yyyqF)B zdKe^WNGoANR3gOk{~)*(SDeG`|Sc7{G*Jq4%Y zwdJiqH>3y770Jzd!m44%^qh+SO?jM0_E;t?<^@At@~wHh^S{YuQ&es71hKDg9IP!e zNN^dPilgcM+P3Y*=efP%^21Ad-ZS`E;TqBkvfLKkn+FMS=EfYsdo>?}eB4l59oiRA zPZMJjF?|s3~k#3ZdH6I*%EGvxQ3M5u(*}J}hKh2=Yk>CCy`=vA^J98; zp3=bQT0RFW%FBi>n)5oH7-a6EvGbG$jt+d@5Rce4#mNhde#zK@<@GO{`9rTiTs3x{ z(!kLRHu++`*G;kGCL>~;OG9m9#1~ynM-Pqj;+pVzUQyQWb<<$V#(-P*10)aNe!d4@ zwT-|}w;T+d6Wyt{dZW+XlP$I!ZK-kToQk8Vmz15an|Q((YBcoFUM!`zF}gLw_y|`6 zN4IQ7ud7n-yDM8Aj5XhSPTy+U>)e3#12oQydzP}-cfWie{qkSOM3nMI6Bn3Ho6XNgVhuxB6E*k*LqV0 zQKsb>?ZJCH{57sEo*P)x!1;2Yh&-~!M|3{VSE$)VQZ!D*b(azSUGC-#z5PJERr_jO zI!ANa^eV}|Evh{o<2-Fvn=(PyMu#VDu=~)O2991`#2)uh^t_(AaW&ELViB>*AjF1F zqojK96$JPC73Jiw(xUS@1uhTmtZ`mk6L~!t?om`c2@8ga?)KWivi8__LOZNB)5gHj z@|rU&t&oTv*cgiC)RguO_*#~8qB&|qaZxv_Bn&UyUfP@Be7QWz-(Kv8YIiG9WDiZ$ zcn!JkyiRoUK76k_b4CdKIn-XNIoE`@I_+kReCpqOeNpgu*I8;^t_lA)bPv)gQCCuF zFOJ@keQN$cWUV0IQaybP;oNn~_Qv`s*M#?JiY>iy)1R*YQydEJEcHZ=<~^TIv9{i+ zZ+Or~s5b^_yub3E$VV6LtIfTVJLOs+Jo0mq#vs>(kAKQ?b4#xu5dK~)Eg2?_bFK-u z66Ezwu+hRR?NwXlgi7{`TLxLHu^A_HgK0XL2mxR!Fo7ed^(w1MG| z)BsHR5QL{j8s95AKcuEsa&skU;#*vrKRDIG-Ts(1Gzepg84*7Q#cDMiT8oRt7D#gx zr|KH%k5MZE(XnrRLTnzNtT}k@S7&UwrsE~G0{k)ECkS1>dr0#YpOse$OG^ENm%2tc1rf!HI~n`C^iYON*C_l6LwJ$kMQuZN7-T|QDv#u5a@k&H@}dicjp>}30^W~bz2*VpIEp=rJ=v4c=jw8&5G(tP#n_s7) z;pR_2TwDoowxzTO+)7@g@{;}^8)57Xz$*Q`44f0)1^BQd;8;d?D75^C zp6kxeOc-u}ANK1eum!s*uqQTSj1184NP1&w`UR%zW?Rk@oD5r<|wa=p9%O?+& zm+)5LoD?N%b$|WyibKKvcZ#0#md&^X0y;mQ}$6 z(#|hZ`9I)&N&X+H`g!_ul~@25704mp+@*Mw8a zmU>WsGhyx-1HFFe^p^9-qkZ{7c(va6e521`%KT;gHf01;lu3slsLLP4z@9n!0z}ua z_SoI!TLHq91&pKVq-?{&;^C_y5b4Q4=a@yJLe9B#Cm_rFqLpkxQ4VRT%wXFqVEPB zUVf13!QWfwZ=ur(y5q&g=2cx`DK zo)y&GWC3{l@b}zkuKih2?9b^2)}KD;c?o|3&M3pgiQXQ_E-sM9$MIv|^qh*nOD7{P zMKu(eg@eH3jGgqFAUpkMV5jtGcCLHaLws=yfklICG+x4AtmJPI(tho9NAcGof0$FL zwj_hU!pLJMbP8#DU156*;Q3((O)B~KJfxwA^h%{~lDoM7(jPK9xJWNA@;HpdNy!Pd z74DOK;lypXf^%f1tjRo{#L5c$qGizzQgva+}t!j3$5W}Jbc(^-DGB|?Qk9Nb~)DY+GV_?jSs#a zY<=PkCavAriXa57vX@nt@NTN zAHjT`KraIw@D%rh8pEeTH8ftry<%C0Q_}__q)I51NUf%ED(WZMN?O}#rQR$!ae#QU4q7*voDQ2WJ z2Akd1@TN~BmZukbpWSUJ-En3ug7gPJHV~O>LgB^fsuF_V)s}BapTFoU63aJ-E2^cG z*MK9qY_hxdb;RUVjbZUmSu3qw7aZ8uA8TBqysV4<&5%Gh_14u98Tk<~{$K?u0}X2* zT=XyzXEzPOvdPA5R)&SPV&&yd5Y|xvUc%ZZNY1MA;N=6g1o>Cv$iLzU)A%s@R~)S< z;YnViiA5xQn_e7v3D1in%Lpm!Ax>5egVnZ`q-+bkwp=#l<-F=EUd9iEMjQ4O_`9Y& z+qGG?COPBDBa5eMsx|<&r5+c&gllNDD<)2qKQY5j_+9P{7pwo25WF57O*ckDzNt-Y zVjyqj-yX7wmyxe2Zxq*1Q5rR28u%Tn6Vv<2Wygt^+ZbGMf|GhE7dYW09uCsKOuJdtP z>sa*8KB|38$i}eG(HQ74Aa8M}Y&^3z8huY@=23Q-PFvL(6;mMK({3Fv;cv2XPBcf= zKB|5>kphQ$me1vUIo0*m^YLDw&bcy{z!oht6$~vl8wExacO_bT3@5A z7w1H`of1okT_clWx1Z4QS8f{&o{RR$u~>FPXdahGaca+Ls?D7-u%JT)Jul&J*>X;_ zclV=>y7Sd&Iyn%m=OuiN!{t#lYVIAiiIxO&$5)cx;WgS1Q>1c=SscQImDIXV zbRE@WmdQ}mfwW>&Ve}ndHXh5a8>L{It+_-okfVg+YYKVTaJMepUw5WBsOUZ z#-$I%l@nLwaZdEk&()VIBqqT`3oAXR;+n{a;Z2K)o8DvK{-}pKPPJg@91MOKi_c!q z%;T*<=c$iZ6bXcQlA+UaD&9UaVru6*>atr&Fr~e@VA6wjx8ICUd-S1qc!mY-b)Ahj ztHoj8+Y19}9d)maNDmkTRR^3^In|$4((u^2Saf+eEKo*Nt!^f^&KV8o18f8@d6zLA z4Hx1t3s(nn*@|)>{nbuRN$~4tpx`p9w%?A2KJ~>4IbK2Gf%EWwzgWs_ZBJVL_+c$Z zR~ZBGBR8nLglok)(F?2PHmDwsDe%7fZgtnIU0AhwG{(dl0@G>S9j0*?btW@#%gFiY z*di8dj2Huo(&FtR_4(Q{aO9bV;4-*Y%ew8tTQB?L?-dV8tF}Y8svnjnL)4t>Dlg&k zI43%J=BiU`olb!*YhDEy$67P82KBrL1g@tsm_=jIx3P`i_s#RsgGQ}u=SwPiGUa!v zHwULcMyXjU*O%9WbD}6t+hc0)V=2%#<%U1!#nCe2wsWr9Cp!gtSh?u9CfqV`PIUKG z%T?b!PJvRji{^4FZdYW)6Uyk&KP?3s_tgh*O?dn8c2ksYG56JSo04Go=E{QirJQY( z@!grBxP05P|MaUS-#4l|rjCI%e^n5iN_{;Zhrb$zE@LMA2eG{IDYb7-3Y_Y-yWrIY z(+k9@;YnDxZvuLxB|?odNwia)fD>1JCM)V=eM()Jn*yIBTl(`7)$ERbO;>2rS!npr1cx%b8LI44@szdot%JD37>>R9F)d6{01_l4U!eXFI>s;KgD;R((8$AT%` zmo{)V5luTk1&<4-Y0hIe_Hf20$j|yaXZ|Uwc^)D}h?Kg;hU1RCMKqn#i}4aZjSQ38 zt*)k^yx4O@(+wMWHQ{`}5UF@-aTUiM<~+Oho-;*Fb%nZ1ijP!TropZOg zRl=Mv3mOb|H=BxUX?s&2RmkQwgDO z@Oaf1tB*2C${2gDa);GAzN*%G&ppALsvqa6`hhjXoYkGR`e7ZbKNZNB*(JsPRCWF^ zcZ-UZO>70DOJ6=&cJ-dnzT6baKiFNwx;n-_K+t?F@F*|d%@{6qX#GUQ{Q<0513yAM zru~om?&G8`SAVU%a`rr|Y+GeTnHnEQU5KWPj?ls6q_ZsZz+gpR133TL# zr^@LJ3*DWNNp~l#y^*5A+siugL$txb=q7|obQ40MP+Jw=yw(woyno#k(u8gbi8k(0 zac>juQP6pW_5PCYzwR$l@d=)xM@n=5tC;r^R)g_yOaVP0wqB-oe}VFtTgsV zOO6M3_83m!(@Ao=+2|PEY!r98f`qiNPsp3jkr9t6#G?!Gz#bwG4sBRczpffna-0+x zxsN-)i>+{;3uHq6a`U+B`*0@;)c&uCU8}dUNj; zq17Uq_G{@LuN3ldO1mr-JsI*tPedn|>8`L(8!n1F$cv)4M6ZTus$V(IHC7`}edf>< z6+JTYLyt;#Y*92wq-ZdWq5*n+kRPJy9p26t)0lchJVO}Ud!$OA`&GX0u$gyesR zNd?kAay`dWT99Q@Uh;EDRbgmx+Nr+vLB%JCz%x^HA6bp6LbH;?rNUP}sQ3gj*}ry? z&(m!^<>W{rq_|#eht>F;p)lg&T#uGwh-}O>)j03hpe!TZ7P6+EQH_zXXc0leJ0T4}9gH}mu zFG6G--2#de0B^bBa#0>pv|B$Z#^;;Ze3QSp ztHd<+dQ<>Q{qR9+G&qE9Py<+6-HO_av=EkBA%GP;P=?md3+GmmiWKc2g&rv@CL9T7 z5srbZVB_i>0x8kWMsNNRU$hOBYG~C2T+8Ab7bzJGW@p+vzxYw?mH3R4$}(&k`?AlU ztuFma>v15QZ7kr=W-b;oN!w4zQuw&*qO$s{h)r+ub(@+}M zE|Mjj@neY@;h9L+^+GtyGWfHEJtpeM{3B1r)hApeuNF7NMKi+LjdlTS{J-5e1X7|3 zecf=;?&?HoRF|&;A_monWG6=XvyES7{#BD{_a8C)ouSlaL1@kP@9q zeb7OCd2+HO1=)#MJx8gK65aK}T!bqZlEo9b{G?-pW-+gIK5WmT#7v}H>Om9>-0Z_f z|2v1IsxUKN_*8tScu)1=`cZUt6iYnh!+z|WlgT53E8G>)hadYd zc`?TWdDEG@8SjNl3xcFVpXi7Q>_K3kkdnbrchDU5bovZ2e)V{+A7wktVhiVavtbA)DNF7Yt$|!D~Wyf`$+iY*3$&`{De1a=N*#COLbGNtV-Y7NUJB- zm(B&wV)kCXY~uaJTq{J=jX;evjPkRo($mCFBJMO`pO6ymrJlFd*4Jq)ZWzR*l`G~l zudd!Krhbb|q?>jjf&II30$Vs@D)pn&*emL|@a7Z^N=x@@&1U;(rfwdOq4Y=vn0@=1JMHQ%18Qp@451+0Z(pOBKlkS8-l+tjM9;994$xOP<{JNk11TXjki zknX;kiEQoR@oeqRUDS`fWti6BqrGG)^;OtBFOk(O?88>x+pi%4Dbbt7O9!f6?}Mb= zmZ}2Q@lisgM0dBn8>V(#5+ofMX(#k4G@rfs;m!6%9u~0jkCbSCuJL3gy43o;86`pVj;o1meQqCCw(NL9IGmoKy*oZo*fK9eZ8w2xt&L}d@NZIG4QU1Sn8yx18PDp~C~0yS zFo)ghG=Z(_HINWd4~l8Aqiab;6Ih;~*1d@lxokAQ84bif z{|(Ua$>+>?mR`(<4WATkLQ1r+_I#VVer|m!<#jy`xnnCt8w}qYc2wf2AJ?x8R&f^* z(T3OYtnpp)N+T0Us!MshsLLKU6-R%cq#>sfOIK6{6|(3%Qh7`RQcoL&sh!?%g5!=h2z$;1WMpu+k!u z>QKd-qJzsCG53G{HKeuf>`d0HfG@k$Ji%n~h+y{z`LO~=#tysm6QN_1LeKmo~i znkeNDKB*#iY=vmj_PbGHvH26Fq3UVH^%&*tn*&%C`x++PyTctCgQ3CmSg~~OiPC^i zR~3AM{E!m8=k>9#w7LF$aa*%>DstZ$AI40RDD&P~-Zb!82-AxMF!#@HR=-=Znly=y zTs*7UOGR3U?lmuj?b;K-{DMai;+p!8c)D7kbY$p21!YGxGlZ}j4Fg#pZ>y)iFn^e2 z_vNEFS?Hr6EtI73&JZ@OQUI$x@xOFBfAwI3^m2+>^!)kBj8AZlgOn&neVr(^9WYDW z?J`wC#HS@8Y)3H)}}KCbpM~UyC!NyhxWvoN!DOhxVH&)h{tQ0};3q z!u?3H+LKGf;M#%GrDN_!Y=!G6+?%BPGFBys?QJGW$J<`bz$Zu-DH#mYPA(NI=L(b- zzbjKXXU&ZnDSE;B=h(Jlj{ph>VdFvjN&A3#_W#ZxJlz8X&7k3njsPh4RE98`LJt9HebkY`MGy(Ogzz z$QS!jo!PUCIM+0Y%daq#;iU=~@kNVJ*^HMq^yhu{pc}RH0IazHhDVfQ~w1*wceVF89nCIyi_kMxT%{S2T84;KQ$vQlmyo$2E)UNZMEt9 z?4=4z(-d3}AR1RM^u}SsY1%#SYC?3?M+&Yv5REG&%Bf?9sb`i2Nw(>=x%D8@<=1LK zuiI+Jj@wC&<39;V3laQ!u-B0gt$2gH!j0k8L|l#H>JBMU?X_2HwRcpIw5wx2ZtaY8 zas5d*e_g7tJvv=O>OA7Gh-+Cy@N4Id{;gQUa5 zx`|j%K)SeAr#plOJyY#$>qx^gD{|EjL?9))hyJ6jCMT>H_I+(HVO<0(6Iel@6I-E? z#{7;!(#h>(M6A6aU95x{3@&p;wN^|cX+jxC3F|P3KuYw!^T4I*+C`(~_%rAp$AUmr3V$5njLb6pu9v zlCVODH8Q^9m2j!MxbD;>>D=U|T$K~)Voi>A+_$e5o4K@+l>3#r>L4Qc3S>m5{bJa) zWnz(e^gTMLe_}lmtC0r7m>D7BhUSx`RnOiDSYyR{GFEY^GEw%8sAY&!<2$cJte&DI zJfisPic*%BCcZn=Qo`yoN{Ez5ci+qvtFI1}_FUX3Uc_=&5~ql8F_q$;#TY+OE2YUph%U^a<#vGz{yZKqY2rqR2W z&q`M1_6-n$lnjO`qX$WodOsJ76qzVu{)syc{Jz1gX-%Z(c1K0ae^s=BJ0na)q*Xn(iZuuCRuO?&CZZ`9{plxd7uJdX>-`l(;93OHRFipT5G{FT ziar%5YF~EEVBJm(Vwpj$O_=-OO5b3(m(@~=+3h2$B^q!DlpS+BI>kEdnpkp*t0+kB zT-Jv?kT-pG`sjBx%#=&q{c5lleK?i{R2s_c%g#1omVwnBIyn$JLY+}!jj>ij5Qo6b z3DI;~y?BOj>q22+SJpHRfxSgEos^9>X_H2kRI47SsZCCp!=kRaGsFELt}ceLoz~8) zWNqf;qH6q3dkvo)a-Gl4boXS1-497fiR!xx^Jq`xhH89TKaL0X7Bd_=b7$kP)##U? zCYhUYkrQ}m4KB@R*VcJ5-|t(JsroS}K%0LuQZ2HynTk&UAz@}MLc$Bkhti_Xbyo92hnuadChAv+N+*eV&@PJfs$ZErSFV}_zLUIbHrqE zA{T3s2TE%&JefN}x{-UiSf|1c5&adm!d+Ra;wToZO_0%MBkm6P)gj+#^ zBqrzw)kT{gdLz0<))3q78N#j4u@#IJAyhw4DdW&0@p_dVD#j&j#m`{5^}%$L+kyiZJDK<%;$qJ1g$SyptnTh-mO{Ya-9HoRZwo*s;HDaTtkt~Jqp@o8bEgX9 zV?ut2rZ>H5&QH^vH_RHN!AzNuAIt~wSVD8YO&chQ?T@N3&nD!DXv#83cU?~v7KbgW zpn=Ar9-Ba~h{xbBrL?TV9i%}+B2~~=3HhP4^lk>(;H;nfgku(a6)gw(fqjrK*;S~P zc9?AN>4X>s?GE`Nn)bHIY9k4eL{E!mm)Fjmk@(eX~doGhfZ-8iu=VY~>WVLgL zMXK0CU ztRSn6C#!8jR*Tk&{18p2EXZol6OXy%8Q@7K@qA)(0$Pdv5Lrm8{mO{ZSESiu1cLAH<^* z&G{Lc^F|a6V4gFPA4*H#aVM+YOjcWbNF)~rkss(4@wh>{>qnkpJViCoSJY!J`WOuR z$!c}7!O9b21hgE`a1HE(;$RiB!Hwh@I_mb^+5q_>n$FPwKAHKTj)!B&yf~(|7{Vs+ zUYm?``F@-vga@6oJbP)A13tkKMM{+E6T*)WUmW{5U@M$w9ufQ-asB!L2W*Af$0Krh zT)jRZ1zQ2y#3O=!^BAA(nu4uB!oLtFe)qgW(&iLw1*7m6B4>10y1S=hD;Qmgmud^~ z7(-*_xN3qUwnAUaBewoV6mL5r6r0$N zDF4gQ1>FNU~-V|+Wees|D!a!e8-1)ydp#lAP^nX%BQ>o3GslW8cK*ZgA8dCmsHVHng`3fETdW1O4amuF-SI* z_F{>tC3MAgrtDeDhY$y8bQ7#&MV~*t)b)kM^W{SMZNE@`eC;QeL(Be=%he3i7d^aV zIq+eLd}x4m&btv0`f8}w>QtH|jtR~=^p6lDS|^EigqT#i&OV&mxd*DT@$G7{cMk{Z z(f$6D8$2z~mc@@HL~i0SgAj*ZzBopvPhgv#iA;;Ash7?l$dW#p*oCoG^|qgfvO#uj z*yIY02q6<~U05TZ;vAaZ?r)VO_9jH#1qV_u zJ^P2P8Qq7~ZFRv?t?foucKA?s?Ab!giHXZuiNXEZo11C$=A=aZs7;6yJ!`fyu0Jcc zdQ_Ud%HzwR=d4ZDm2#n&!pv_<5Tjb(Z*7k*b>9J7!T2z+8$uXJszJoV<=$!sYy~6D zY0NK+nnj4?X(gR-Zc#H(7Yqh3;?ac=(t)l{IL|o$pl>v~Td5z3gjlt?TpDV_mVMVO znV*))kvqb5L>ml6iN`=f9N95G4d)!^87-LJYWzKe_a+59qGr%JD<*EK#hxARt2=mp zkng5cWPLAskyNpS@FpIEpLTY{R)`Kc){r$jSC2KX=Sql;grM*6YBwGkQc-`_H}1{i zx;nD{w;goUH(JpXBA5`R>Nasiy-MB{&z!4tWAnRyv7nAo&62dF9wGiYxgZVoDlOL> zwqiwhb~W~u14+L9{#eTLc=cmlimDc*MDH|^R3U_D+-^xK^qgHi zTb3PmtHB~>4P`CQ=VA3PRbd^RMv`9H5RXfQ*jJ{*KGa0;U4QBBf5c;$l}DTAPN<{c zIXTVeJVPq#F7iV?ro5e`+DklA*k&j6YM_0rM1_x*$ED}X=j34OM-pk`0z$a0G&!M$ zqvj);_SJ~T8A6Pxe!=PTo)-F(21DeoTl=#~nJx5?%0pz=)%{p{ZF@ayyT9B$W(4sV zLOfOx;?1@loVM@qyKHeQxI)h5HeE-}r!NW6SdAcrtyItnTQx}8Zuz)4S$_C)hMs?A ziskXZP4e^7Ge{HZ9TSn>G0{dQW;xz7$6FHDq{yioqx5DE5-jvxG1=}*ls^A*q@_vJ zKDoidXhNhB!ix~0O;0#AIP+g-dxz8Vl)za1eaSqQ?vGE%z0Sqx_ilB!I9M!lrFt=h z7)v(Ti4buaoAx1MQ>FHqI|pBr2P!f8KW#iRuQt3Y`){=(8W4|ALJXhX+Ueito~AyV zpUL%CM{}_cVqHw|GNTC>K?rL+KRn2fvnY_Avo3?- zD2;AwD~~CkouIdz-C>l-{uZ`K?_g<*7Y%a6Nbh0#VQQS`ll<=A84T@)R*)psU_$J? zTbPUIU)`$fb(c++yA|@{VmqBAZwZR{qM6t$O9yX0#(_7RBR|*pie1?CY9se`Og9sUPDA zvB&RPiu$bRMovlK6CTfEHWzh||?x5p38{7xrXwS$2XVPBKND z@)57(eS!1XxRyQH@netZo{1H|Evj)xa~j48)MKz_Mmt#4^S&fi_==HE7y&STz*rH& zh5BL56B8Pnocg{fZ)`(zQ1fCma~|`^c*EzOe0g0AD?ehDniPLm?t3hT5T6O*MhFML zFbC9K%wAEC>8&m5$09aEWh<#t_6>`l+M`n%g5SdAT=>a8nTC1g9dQf$kZae9@5W#n65$`Rr)A!ZX|M10{?=RH&P z^alpHW&cl>=efi6KCj-I?)u!Z_?(!gudw@Qy3p=1<%!PJ4{I)3#Pwdv)lyURu#gOxozU&83SzH%63QyiNM_ z_?~*p?M`y{Tt@wMcNcx!_jdC0jP`^mLRm%=LfGCN>$KyaX8N-y!{kn*2kIRrw$#I# zy2(EZ^wZZG+UZNbb&$tj>p+NVglI^JyNf0{VJk#O4Qix!9Y0d`^mik~IqC3cUe(3Es{-5)Z3hh0I}GjG7nR-xO2znOy8$l#Vt}6=6bH{ce|&@u_I3 ze3bcP~ zZ*k5Z=_ENJA_(#HYTwj}cPBCSP-b>DDly37|kxR7~iN{kKD{EA%<$u5dpPh23s`r?q&rgAn* zmk$_%}4^fl8Q-!#rgq3@zM?|&l>rL9gu zzl7cn{TO8#G`e%CA9u&~N!5mr)AyVzBR_awj`M2h?Z_t*VjUqu%au#>Tj-|$ELd0W zGNGZ4-Y#|SNPWwYD)N{7wmRJ{QXxs49!mDnf9`(tWatOccNq-lovB_zW7VPWuvX~F z&|hhJYwB;}{bc_~9>k*$NoCFS2dUH2(38OmLPyU>=Q7BmthEfgAH~uzV?nQm-j41U z{cRtgp0wYG`3Gj6tqEaW-K~fh9dV_IIWC{Qo}+%m5#mL+51jWw&wxJ0U|2~! ztXYPgZD>pM87&|8W*1`|*@K}D%#JE7J*mQSy<{V@kDUA}YDr`&X2rPvbO>(8%rl#@ z9tMdJ1xecn5D(kNN1f1TV7`laFx`PoQdw6;WsCH6LSKUZ19J(gk^Sz+l?UBgA>!!g zDwfdeN99yGmfe{3D%0lNDY@Y_tM_rH8LUe@R$cH&?^)G`(UfUSqe6J|_FN1u=jSPJvl1YMqVKx6Vy9 zl~3!nKXA<~JvhT`YUuLA)Q83ElRND-?R(5jbPj-c^dZEUCrz58mqG7?l*s!K!j%xg z0l^OFWzct_SE6rDk|tW~iMQKFq~uAD)o%w_Or7iXwK%+v(qo^WGDROtw4m>z6ODve zONesE=cQsEg&qez(XWbd6d^A7c1rDWd8}SwdRck&hl)D-5A;gpuV|IJpAb{KbWFom zh(@pUM-z94Hcmlbg8l=uD9SP@M%^MFtI8Yqq5nX?g4MP^tL@PpS~}sX8Z#N*GwdO~ zvep0=x~UFmwP>llo#&^~-A0J;NAuFqI?>K~Yd%aotl3iV1tXWYqXlC&Kwn-YgmvHG z$dheOXm`Q3Z7o@w56H>AV*awhA_7Hc^3;be+U-LtLK{TeBp#%R-H68u_c^JUtE1ha zrO^o?>UlgNeztdXv>zIz7h9c6_OrKPXi-tiBK1XW@0eyz%An{xjr!q3h>vGqw7|HH z_Q=~{V2dQN0@d{U-l>#|wsy2*y#A=pUQ>jl(ZpNSUh0Qns4*4eqGk}1rk@}=>w@hKt>6|^%NkHN;j}ViSMx-Mr4fC7~82*L_K#Q9@Ez>;Nl>z?lC4B4AxBFS_7!KbVN%2 znHyOA{UNMao~81P2aB0=p}y>7!fE;TuBFV=p&zSXM5P(@BHwOHi2FrOI-!Q6t?=5u zhIm-BzJSpeoG?yc_KI0Y62mW~Sg0TUh=ZiDr?SgVt2q^)C{b6@LE!z5Yq_Z zT4GNsRzLWP$N$!YG=mGs&P$WFOB>@`VLclBIkzkKr{Xm!yb>4BaRzZ_X^)*#a);&n;zJcx1Icatwn=A{Gw#o+onG9`W z{HS=#7Bxlw)W*7kwEf-lS>g8`w^ti)d1O%J9Sfovw!&CKH&c*aS@Yf0y7e5<4$z9w zx@eb-GJrjVxcPZPD&``nySyg0BdM%)hDv?rwjA!in`NvU$$Ha9BaT(EdCBbL%;D@u zAA!724r0ah$tkFDq19KhvF3qn#LV@7jqYlaN+BK(KOSs_J;W%ABSLqp)0{gIqFCsO z6tq;ddERPYbWIZ91qNs~?~3mKclsVyweKjFGT}hxt+&Z6@8RKWiRHoT}(^ESwq=T7Yv3EG=tV0uAhBdN35!#Bz%RX z1W7fW5J5-IIbc7G^>?tN5hIxGvprm&{_Hfod0EB*TOqo4#l37{+9=k+Z#1o)TM`fJ zZXYe34frJIck@Z3O;f#gvR6GlS))8ZHq#ypA*@;W^GQ*u2hMC~ojZ+Sp^3*$8jW;0 z8tK^q2TZ6vzj#wR6dG^=u@>4y6AtkzH)8(7su745tzjKqY73@v? zg&3nA6zD^OV(wn!IjJyjM+s^FV{R>>%q2R}7!)Aks(Sg?OjC=_newvQvskjXjeJWv zC3niOuALh`x|!kJB1GI-d5W}kb6(SOZIj&dpE!mHq(tuWV`HHM-LbXPW-`YESM*4U zJoP1K<uA?9j`4`Di(?gOc}KBm0FP+7?VkAU$x3W zu8?Z|{qkoVLo}^Fj=WbM)N>SF3Qm>q3HAvok(N|0r7rI7A@uqdBDI*CK%RK6{5l|- zosB(^&2PZJbh;eYR8+aUQqCM)_nmOE-ZZHm)LSu=MKo2Nhm}xYR;nZ3`5YwS6O;rg z(Vc*e6NRHi9K~uZnCm(AgGWd|_A5WjTol&Fgi0t0%8tBgS0-?mdU|_1#qNxcG`#+{ z?4A#uFoVk(Fz=#~@f)wUZIoXen>C3WD~vwqG3Z^Hd#UO||4zz)EN=;)AU_;+gCSz{ zHq~wNI`zMi9ujhg)jdNr)n0!~HG!nU-l9}IkAoqRf@eov?A39+gtms3%3IXZ(Q!ic z6OuUe2EBa`m3VB0XsXG~O;u->OA<~F^473U36kj051p*G_YO5?|9o}zLr)E#K+pd= z@AIk04)x?xN7cE`cnwbi;Vv>#qJvI#*Q$L^k5Xo}_Sdi#?m_bio7WT7uDR}+4|`4F zq(TJtk8U28W%z>_rP84dF57Y1o@<85n!^Uwt;nB=6G0*PF+QkR!q_nto z@)>g+w=d7{-Dx-cg$}{jMbG$A8b0yPS3|bA-IH@qiqa>os3KqVxFuKk8bwm|_VE%5 zUD+khS?QzUlNmO5OkXBs$sJ;2|JonS)o7#f!oE4;sSOh~Y}Mu8g{IBXX>#1Zv;IOn zips0(bP1%rwJDrbh`|0)t?zW4a;R80F{tHKuIDMu4O0KMtK`#{`B9+nZO1=WZrm}7 zwVwrP*a}A)=Y~$uH7hC}&i|jdaNBSV>xqyv=rJW*%9~fdlIy2iPa!Szwg@TnGsSiv z$7wjCSb;=J6r)u^AItv)`R$DB){lGfHr%a#rK9GRJ%W<3dJ%Z#6wW!|Y^ z{ayKa4I#gWlX`MvFo!@1t%$59T}``vt*2h{mpgCFU#zpzYH3)uRDYiQ;bBGp;aw^C zo6xPxeR0Nnk8BnpOMKY{9w_*<+PMiS{5(6~sB; zOGraz_Q>XuGose9${A_?G;S`((qhlGMWnL(Ts3?GCkL{5GzpkJ%z`F7*7amt3OX{S!Ayz zmJzcj={%*%M{k?kK1@{a)tH!#Fx&6V{5B;@?;ZA1&g@&-(lIkqpJiMvUm9#D{&T{r z?Ik;$F)sM$fZAu;FCIAvlDqow4T>4azzI(q-6ttsm4{yrK$K_1!j|C_hL zP`IpO&fFfS{_8YJL+-p4k;eQFaq09><>b*a>ez=N*;y+&;9o4&qe%W~r0(r#uTO@z`wnqwdwt9>u`RAGK7n{_NBZ4)2 zf;_C~97@!u?Pr`Hxz`rv9r@+qa zT}UoQ@uN%$DJXNLYv!&!a_rZ!x9QY&n0fczw+Ivf`K< zbL2#uc#`VHj~~YMu?LKEPVk5x8zRNL^AhCVgg`W%Jx?|p2Y)?lymgsJ3>a8STIoAW zK9oCNM>OpTSKDk{<9Xir^BRvZtvM&f`9;Xf^2Y0kCM{|A(s-`x8ROcMVH(PdW5xG; zc6WDSP@!T%w~0It94q8UH#Dub6Fv+pBt+3zVJn<}9?|=4jdb5S^M%Fz!Ze&)oEu)M zn)NRV=f3Ax4P;C6_g}CA5uxuVV zQD#b&cCt4GyZx%>Yty5#62@#ijC$E)9{2TMguF497=TVwTf9tYIsVl`fN1E zqyL8ba+=3Axn{#?9r+myo?Z)tv$-~k6+8KH2pk_o)BU1f)(FRXJrE~;8KM0xNlrB2 zrP}4d$j*8nc6VPwEqLOazI&o@#$&szQ~p69%~Vr`WZo%yKkLx|OcIQkp$CvMxa zocPMe-R{o{i0#{#l)ilLp5a4Tg1ZDvN85J{9BahHLl)BLnI*odc+} zCBxW3F|K&dONEkP{|ttU>)U4R9L|JWlr7?R z;)e*^PWy`Oe5P!{QU-r%n(IpWv2Uy#GAoW*J=`Nhlw4iN-T`MR8`jGmlt}vDhY%+T zk^lcd%+Y0edxO}&(7xVZgh##Zi?6?VWb?S)IybYG!ex^F}Y^PNcTlQz%N;lge zEbVTmT>C!|e`L31f6&vXbTN*p(o?Ozb}GkXbm0iO+ch84`tq~b^a~5+Io_#~Qo=eS z-#i3m{=m{|_2Qu%;%SfPrW((jsoA(Ts?x$%vfd-qHfp1ihG&$%Dz0mMmMJ) zEhphVhy$NEFQ~mYs zYv&SO#7)=BNXNf*%0@i3Db3zRjmW0!P_s1KK4Aod9FG34Rji9>cd3kIW7Anex>oJW z;b;B*hf*CvJib^)s!s@{^*8zt;-4o4#9=NarC#5AWRGr+o#UGwkPVVl&1wB%7xhvs zLwEP1H-N1FulLWJe_JDzq_x3{FC#dF6`jKm(R9ytyuJ8y#|JTKo|^=bjG1fnmd}>@ zDv!7l@s}ssRql?EYsYPINOw;OTMY|tC7Ex%bPJce<&9@m?i-}h0W0O5 z*W;K+Vk>dwgXQu=+EJ#j(T;v(Os(?KnEObWgij#LU`UCowKK{HGs_ni%I@HKeA~2J z+UL4f-gY34<3~N8pU=5gg>>hWKf)xWd&p(7`1MeN?3^q9FCHyV_7lpLu@{c`g-H{S zPc|)d@{%8r$C0v1nj$`LkdxNLG2}=4gNtkhkJUwlHye1V5X~cE^Cmho`p(bVHNQMu z&L}QAG0yZe&vyA~^Eigyj^3zhbj4YwYSa`OD|}*|gB-8M&&NvrjSxR+l;CwVR6@Gg z52R!;1lOJ;Y~0yWuvF)Jj;#<)H%G?S6q2_%i6hqrOQ>Q!vEo^ za}e1){+A6@`{JV>qxf-?;s?eIYd>?BZ_mjMtgUjil1KDlwt^S!v4m|7&PL?q3E0Z|J4Zr;p+k9l@!r$2k}$bT zHsVhn^=A&Oh(9y<;7|!Mb>DRH<+s3WL{1iFZIz=L*55f2Qmp-1$y{*tcjJZ|VbXsw zd!5s0WnwYJGqid1F?0j}>B?sB=|7C42!SV3U2Jq#9CWJI0RZM z+9SoN1MP%nQ(KD8yMj5-fajL@Gexm^X9;Vz&JvfNo570+hO%eo?%GwyyCJ6pT&k{hDi7X=^{T` zdG#tF7I}I@9Ny5AJKcso=le0FQjT@*0;SFQHs|RY=vn0?ow)?@qOlfA%5sI33U`Tk=LuJr2Wop(mo-P)*omG zh(^t)U9t_=_D{~0AWZh;a|T4Cbx~#eOeeEzDTDCsDvv;`_yUhTf7nOdxlJg{<4 zZ}%UJ5$5!*tF&|s)36ny%U!Q5FF!QSG`h8QSB4Fb6^2)DGuVtIfAhGPR;hFvkOTMiEUn z8~Hpo_jPeo)rUdcP6P78KGA8aZl8sp!xk$m-9tI4lobNDC@5UafsQA)8&CnJUK>-R^5 z*m!UO^>MX{8n${n?3(<(@>+{_CR9JtElXbdU$muSbL)<~+o}lheu*k-ai2g9pCDbN zWH6Lk79fs1RZa~%Jds1JdypX?dFgA}GcDpTsjk+O1^VWR`r_tTt=W-ctZu_Smh(&f zbfn9lH5f_nO$;hgRW04#mqR=p{X#E)@fd8`bbc9}S-%59Cev zWw;a)ioZFgmb*2U+g-9|#W^P+ctluIfOz_BIkgV;9D9p%j^jpOk2rJEdC>0N>f{If z3}SClLaOPzH4$qx$fpke5~QL2peFJ>dc1jHp6D=NJyn+G9L`^$Uh#;E?H&oa!}lvY zx`k?J2WUme&tQm7u~*Io4^V5{Ox4hykspuPKhjA!zHGQMkM<_eXP~!3uSD;8wHmF& z1(jEQ57HhBoWDTNfD+Pf_*ubNSdBIJvwBg821pnAk(PKBSDuv}p?vh`JvH(}G`%6c zB2Pw?V;*w`#Se@V$Pc|X)c`zinx*dN%mvPdX&8$zeju8@kCS>X!!3PuMr(?L81IlD z#w$8y;l0=V+P0xNg!Wi4rXoK?(;L!bA7*$Ky_DXCcwpQ{ei(OYbiXb!`$tD*+@g4n zxdHM+G=0U@_E|=!&)fEQB_5c)AV16>Xmsrtnmg5vNv}kC3FbJ+57Fe|8t)OLVNcW} z77xwsQhnCS{jH^O&!IYRsedfkVDSHZNc3sypl;aX#UU<+RAfzW7S{VW^w80-(5lGh zuy~3&sBd=ih<-~evMzax=;bPS=!mAgJ-C24;d*|plS@A>d{;a6p+R~5S$GE>B^;l- zEnDh$)AF{WJNe!5Rr83WmAqR2!~Hp_iWHF8<>ZT&m(@IV9&z*AYw_UQfvWGbK^%|r zKbx_85e@Z4QC)SE&|uiqxQf`rx4hP5TW4)j?qO_WTp_)}m@fLDQxjO&qYC=5^MW3_ z-i=j`x7P!kv?i$zbgV5dTwPYX9NC5A;coB7`djkrYm0Q(krJK#@T@O}^eV3%FVa~< zS~v+f-2U^PQ&dH+9$WNno;xWwkZY4X#EVdDAXgReRAqp`sRZz9ZKU zJzh_qir0%ps`bwf)NtH!&UwV=$mfDXmjar3Q$G#o7Dtyytjn*6xth7Fwd;CmsH3Ru z$dB&Kbe&IMNB>V9yum}mNQQdFBkHc$VmuLgKsCmVmw+w<^k2255*O`-R(CVipHKN+ z0GqKlTs~y!XYyCJLh`7)>ORn%R+A^ZKb^oL5=_ql>mIkVa zLx6;>3S7|Tr4OcCIvtwMctpRU#mxx^R;#|Z{W%2glJL76S?hXCUZPc60Ek-S+#=g&4YhTRbMxl!qwqy&yJ8C>g6`|=@H9#9*gHjW}I*1 zuEwVaaR{u*A)5BK{fmiO$)`${Gr^ox*sABPwsLBfMDf!k>%Lmi4^%jAQ$>zx zI?i-pu$71KEZ$F%Xi`!&!f_mlg6w|g_MXxd_NHJqHP^he!Z_e^|p04BjZ?J<&4%x ziJB26VJqAP;CC}zE*gv@KP8#hzUC2)k7r5!B7)^LwCm92=>o~4^CbDlCo7MtV?LN) z<-27rbSzB5R!A3jHYnnx7&3Z>zRf5}`yWUP(bL*56`Bl5kmpjply2Z(w9IV(pG`*5 zceFPFPmnHT288%`H>YC`&)v!uYD86F`eHlLb^O+`Plcy#cyw$uOAJQ zkSB>Fln~Bu|ar8NDda!|$8B*ed#+GV&B3aWD>I^r2Ho1DhCcyRA~^ zRtn&D^-&TY(YnE6vC@v>YPT#u31cc`9Dl|0IakXImwTAiyEi6q=KwI)@;r82qi>~* zwAE5qxkx2k-B{wd8v4eQP7HEU_Ne$UmXcUVzkQ-J*||Qis#tD_tyXa*eM1wTv>ofr z&MYXR7w^}TAtk!?^!!e-$DvE=u+9A>Y!wyUhZUCV=~tFG{e`$UudFmQtA#rAQfDc# zbv;(^h^^lFQ6C0*BKxwgD~m4IRL?)siKLqNHNSMZgOkcoyEtp> z_RX^J(ip}gD)*Wpbl7`WJ@CqtLp>#g=`K88bJ zZiqTYcZD6?FP`vkp@wuFD{)UiD(n+|MB>kLcR>j@YGW z7qw7};S%-`XAS3uYJCUp3tgIhS0`XCZd+0Ch|O5RJ0Ra zR+ZGMZ|crzJI*>^9 z&ghFXb=omm5Ga<630G>CnxbJV?MvD0R<~Ns{0kxU=%!Zi?xQ#bOx5np+-kAXEq*>y zM}EY^@`ndq-eKsFH%f^L;H9d2NXg7;#Utu>zMy90?W#0(AFVatP+Yh2c+qQuj{L?t zYuP+Jt6AT0a|{bqpYETfgnXaON%g++#_U!B<->Fyam=rZ*4@6nvWs=rgvD|;kH$M) zbmZsVu%d32F!z%o#G|9zb2V`NY^A%c2PakCH-)lWtr|X3=Mgh&x@bSLB*kT;owhDw zOg4`;2g=fmGJp8FobQy4u5_|F@u=6Qp5}UFp7PmF;-soo$~n80^Bqa&5&hKDtzj2;(C| z&t({0;?d{#3?A-%N5m&EgA6IrT^7G*uwLPk61IXFWS}L?V6bZ9&tIA-;SpY1HvS1 z1s=}IBio~r-z6Sh$y1N~<*BVa{`UlYFhfcPL+NSV)KgtPng?y2%K3JXMCad-URo(l zU3j{JSu5tl`9!?Mfk!mxT}r(gQP~{i7RvPlZbD#ypnjAisZNtrgSSrQ?)?C%{_4k) zk;4R2xwgv3-h4E`syyxv(3uJQ)Qnt@9-80Y=Mh+AM>O3$?0!YL*mj=(VDZ?ZsBY@ zi@D?bX5;Vv1E zXwoiRtTQ}Z$t>XQQ#xqjfT9FMSxcrI4=2vmBwcyPOx zUmjVq?a?we*qSqB|NfO_jLZ8@thY*4iXI!LVJpZ>|Jnt}b7rSl?9D{wmBoicpd`3A zN$&!zJtO+ui&4HkAIxWpS1Lqn8(k>uGOQA?bds6D=(mHjW{_7s~3G^FFk5|OS!p{StHK>o&XPqIlRFz z+~>I%W;aur-rPfiQDn#iR{*s88k0*3AD35cyL}+HHo#R8Qlfo>$p6H94!abmHXahT zf*E8yqHxV{ z6P19fQzWE|{E(8t@T2Nc@x}u`<<`rwTnzxxJmPd_d9mv0C+2}ALnW|OhLsSkywKjn zlHsDOTP~!_s3(vQI&9hy^$;l;Nvd^UirkGncozGSOmPIKNckdu#`@8V-<VypVcBpx_U zF6IXsK!<3)I^-97mnM|pd~tkPseDS&K4bWZ`0t6Whet^}Vf>PS9L4<9jxjuqqrS1* zR#09C(6>vZ^mK`1_|11^?c1xbOvLe!F%N`30H-pwL8`b_iG9KsNV{zu-5Tcvx6i6Y z^BgnoB&r?iNOlGsXB|fihKO0ejpkj_T}wPT=a^J-{5k?g!}?KVIB(sorag7*a81ff zw3yM}h|4jgA2qakk8qVBxY z(MtC4j(=%51@pr>Day|HP`>*5$3(UNKN{waUyPB^${n>nuQMg9{h$3MIGS;EOod-# zfHy4`*W+uRrL}jBFUfHVj$(~-0&l99ZF&FE`x5KC%_P~DaI|`y6T}3ZTbLg!vm-G! zsu4%CrDP++QS2eYMt=`pe#lUJ@dlLR6#V`J&Ph?8zbV97)vWfk7aDO)g`=3ui23ms zwSpgdBvxG$A?=+p6^@4v9;UZa@d^oX_TpbUa-4!zGRb}kFPWw6&tVsN|sgJf2gSZ!5envFm_F z6t9-3MqR8?|4z85&5RtEIB-=2#hL|bH5c2`fK;#T`C@YMcE_4a@m{eOhP5+zb-JRa zrv7{@ao{QWoD=JxST9wSl@UWpjxjOzzz6b)BBsLo1V#BX;TYMGG}vA(Q!nXM2JboK zJ&sqQTy)%wID7ReEv4NZ-fiJs7--@3VUKfezI_<%Ik9gYqS6r$9pWu*97N`pim(TJ z43l>BXqTd+asZ+~SPgc~&8uw(s{yt~V5$>gTUto^6Z078tmxYz=050*E*1V zZg2|D4Z`8X1eL>qq;eps;EcsM1sD$JIOX6R2if#>RB~x;mu&imrO4SHI;vf1-G%!f zDQ8|_q35X0b<~2=i5a|VC3*=*)^i>85|>pCI%16Td=S~fb<`7Gdb`)S_9XT2%Dh^a zDtu|K{%qMEAN^33Vv^@-c=jk(?@M9*mY3nhy1QinnU}jXzw=g=d^wS?fi5FXFDy!9 zBDZKoGgarAp9C|vkM;GPPm4-krPvb`B08w&NQDh=wbq*(aGZiA#5utUmf}Ho51gY- ztyo3!NySvNuQp^oS2fmS{;dM#Xy93%&W;GsJY#A~Qcb)c$m-4Spyz&8T9*+~#mbV7 zBN-o6ssxW87Q?1*574I-O{Zh2&b=JVGUV{muk3a=c+}2HhW^cX>Y^n%PN{q2S61vZ z(JM!1)p1VXm%%;~_nDdafa{f{_P|v2hxcVMy@K?0pV9)4HxvA5o2s3(An(!~r_??k z#_o*lryp&dS;u7pU39QYwiIZ^FJJqG=L(+4O4ezw7vtw0n8(7j39S6_`g)#R-(h@w zC__nw#1{O1qbyR%m&Z(IaaH{FlJ?BHj2OKlGaa-c9}hT|PeNdR1u93g_-2v%*tO?@ z$G%m~sP`{%+MI0}q;g=Yxf>$cb9IF7(dj)Pz71(gtEL~IZEBf?W2#Ff`?HzXWAtuM zZaZYe<@U``wLR{@QY{}ki)Aa(To3lT13V`0aHB7F7UNGp zq?hUnqj#vI*tJ`|^)+>l10pn_4b50`ytbnMXAP%(YaPWdwU5>J1zdDs2|)`VA4*!C z592r7&uNQ1rm_p6-SnKdXFD*DE?MTWu}9kI2fk^*BWOhz;?ungKk@F8RE|xDX0xcN zE%lM3FFIsI#Op%z_toxv!ttjP0`sf%I+iV7IaH6nHXC^C{4E?#vkt%Z|$= zBQ|G`BE47k=ALaAXpxN;vV%uE>Z6rqjsq2zvRyC3^v~6rI{JoBXCXy<=>v08;E^Y> z3|(@@iihLQzT7u8P=E4TTb6ZbZ=i_Yc#>SZ%=8mZbE*ZnlvB`R_Uq%AL z!>=bjeR`UPwFJ1CPnW$C72E2JmrtI%!yTTyhz~o>ibFw^ieJvka6Fn4fLq1h#Z= zjDCG(0pPKJL0`J2#sckiy_Oo59hXT)TndgO)6)&+%g?9M9+p_fdhh6_H>l|D(EnJ@ zrY{NCm-lXbAUt*^J2JeVo@SdLtej!nD$zkZYw&q%vr8q%RP}C8WZoaf>O=lA5SMlj zpt0Wv3zDcxwUr)zr68|Z^8aE+2dCI^cG(t{4o!G z>vBdWhwB^v%DN9;c8HHB>K{Y+qEU~0B`Q=78S!V2Dzxmhn!L}^?-By@>y9ON(=YTPY_ekP5Q~^K{G3sflTqGq=DVdbMYd{hz& z{Bb#Csm8jGCGBic+$Vi=g7d`^rfIsAm9EfLU$xZV1|D>+#*xRqQT*(!0D@EM9#3E` zF7?!3Y;0%4Il;Z{FBRzV!`?h3Pj`t2Mhxf_$Bu6r1uq@910FAEKk9pBw&tHcko-O+ zhK=)|qECnlx8X9$CI82FD2a=TR;L_rp;H8aL!DK|yZai1!Qv^$b%QUv| ze75F5JH5akdw@q?&mwee$#VRy#~lgrDsVD8J~>o>HD{CUFLf+i5;0KkIb{ zug1;L;s+m+%7Lk#eILryiWBtNOAQ{+=QSl8&voXV(mW-<%!_07<67&pZTD=L$F!33 z*tS<~^iJ71AbL$~Kn|Sj#Pw3I2&Tfa%ZM_)a?_DzOY-g2(ol@R{OUd#$`;n>p=U07 z4|u%l*Pd?c9-|G6cti57@6Bd>8L6jQ{mO=A$7O<-<%+nI5YJ}3MEYD5=Q|bjo%x{e zbPD}$>j9C=dL1VE>d352Q5H|AN&MS1;}hHEpg844qmeAkQCCm@JPX4)!7Hx7qYLmT z;KC!K#|$>3Ze#sQhSxUC4{ovsq@#%k^6>1{ib+yo9+xXcvJyGk=o{@>K&m;{>(hLd zrfMzU~a8z3&6Y)C6@jntkcxKW()>(xlsEOvz6ZNhsS&Ph>j ze9cDgjIr@~j#3m$;(IloHLv8Wzn|vDM(i5LTKB7>S7=oNcnqufjoGo%LZ0ivyzM z${XtY(%yXZ@oE(3izR88DvHf`URZxqt`;B~dt@Ye`c~sh+E;^HDIx{?H{+b(mgyhY z$Zw0jXzLp>iY38R*xMAmsk|?dW?L10XoF3X3iFT=kJDA4X`2nuo^AD(cwmp#ZwDH( z3}YJWrCwBla-_OYiUx*8X+_HTN`9~Sj9y0M?NX6;Dc(?vh_69$3a(LHKDevj-~zeh z_g%~QfKeJhB5U>;aPcvogtMVff68V~B#lVB>0mi4Q=_HktGtpWVn z&gPOvhNY6r(QbJZtz2%Aw)ewH73+hT2iCP95?i^-bQba9XC|J3v@#2xN;-AzuH#tEwA1y}|1>^; z^=q)I^{GN{O{~eMho|<#l3*&lXMj5<%i_tm-9vcSs7Jnd*MOyx%Tcak6nzvrUmNpV z8V%=*rNVn3IR9|3MCa%B;onE+k`Q=Tgm-$NCz6R|(49fN(w|@LSYAwp_i%8dsz+b? zsrMYsD>6jG`C>`%J`r9x>Q{mOd!QO`v~{S2z&l91dxi7tu`%S($^pDiQb!H%U$G=u zLTJI>;dFME`C7l|B^usU&)FNzf;PtMd)_T|;C(yjqQ36*^q5NAt^a0ee~ziJl>*-F zyAn+rjP1?0d(4&g&X@|@AHbg>G?=Cu6sOhNb6K()V5zW;13Xe57NGq)m*H`RUP=gT z{lNAa;KACGx=~>~egBIZw!L6Uu!PWei?*Zbdr#4R@AXQ<79niQ!u;U<+ReFW1OH;& zzUUV?ixgHTjKH=mh-GoU0ol4Vh>w5!Uc;6xY$=k<5p=a7?btD1`@3Csj;&|do`~&? zijwr|7aBM|Kd%;2K(fPODr{R+l-e08k+gAv-2YW3j_rn6Lb)7Qzt^INx=+;VbtuWP zH51!+F+Z58YriFrhiB%k)hd!b5hJkW7J6dMti%JXwFALgi!HR+$|;v4TUc&-_sm?a z_gKcUtr%%!l9e0I2N(7x=lXc^-w#)nEZaD`gDlm;O4rn8!>jUpqpEXkSI72b8IjbW z4cW5#FLnQkVQ_0Jfkk#uZB?re0}V2SHNF~bYthBHZ6Ct6=P&2q;*If+d#!;rNvB^f z+Z`bzAg)0ITkd#Evg9>hGD=`gJ-r-&hVKye;Z!CEpy503i~OY5jR9)-ZzF+667zm= z&i`U~56BDgi`l}Obc@mI&lmvzzkcOQ3Ou-^?yWJxMJkIQgZnB7@!^O&Ik)efU!GXt zA*Cd-oa&MNORI)MzLp@N{i^-IiMht8$6>1L&z3Ns=a&Aurnl!wIi8$5Si-o54gSOFhE$PHK{~Dwt74KUu|X) zQXorS+IqDS!_>-`8TTtiOllF&6z(*%YE0UaH1zhRHh{n>RyhETbGp#ahg9ylhV;4L z$K-*>ooLPCC_2915r497*gUdA>t`Y`6^^p%jGqegRl^#j<;_*(7oWadu3ho!n<1_9 zO%p{KKh=jciC9C*-0K4foMM#&>Ib(|vrcWuq>rg-neNH$k6TsT=OOod-s5ijR;TGE3YDw3DJuiU_tN~GX?v4nHxHzF&t-BBxq3^x(ZcU~mf zV<^(%)kDA z8CMF70bsMM!@22z;kV>S8cYY+^%8cweNY}w@wE{hiac;E-Gio}e z&CTzW_JHrWaQ-x7iZ2`)dt%6h6Y4je4mA^8GGOU z^lfrPYmtKUwZ=Tu$WY+X_6Iz~TN#*NTJ4Qmv;1g2=Jy4DhGubWMGw7iTeiW_EV`Et z(d+*?e!uZ;-w>=<-FyO0We!x^rGf&-(;U%MDFx8Kd57s!$N1UgoX!VTB`xb-w$E6T ztdR*V%+i)zw3>ad(vYQ|^?0U7#Z28NYiKDw>}+}6;Mev;5k1$a(&qO)@bGwxAAYV*%BKsx>J=ews(KvHvk~7;v&3`S- zR~P}`mOcm4UN76(arw_sK=+(kij=+Wt@T+6^R5e(7VPEd{w~bqArR`R^rXyDcb=-W zzlpF)2xzNJz{BzDH;3<20_b#2bCd7o6&?{CWFjzC!$lt*PuKaIJOpB5;(N8w*#3Nc zt<{<#RmQSy^t$(ccNjH2p=&ce(QCW;9hk9$-fd}j_`aFTp*DLoh?mJdRWqop6hNo+ z5{I1A*Kyy}@}a@J{N#U39#*RXy85eHdfZ;cl1y7yjd`!D1)wJ;u=aOr z{Espw0#jXhSww%frj!dJ@0t^8cDJs4|MQ2$$Ty{>OdctH%x3WD|E7Vyx!O7S{=7;d zyhtDZ>wCCI4+u>4y+kv;#p`V@h?ti9)iWOk@%2Tf$_PMP^A+%T@kd*Ig!_0vXW8~% z^^Y3PXLV&J0#l7T8>H9l=xy>4hza@csQtDyHCmP?My1UznDsj7!=%M7*f{#|;~ zaAXHwSx;>utdaxOy4kh#x}y}ct^^|M?YzWm`U-8pCs=DC-;~~9QdJqS$&s~PTl0Hl z-Ik7>bGpFy?kiczmv0NSdDDz_Fo{_yfKKTdW=)HnDwfVfMx6Ypea_xl<^c$+{UImY z>^BbIE_HxMmrJ=w+0I2d*Xx-GOjU32M@Px!{-#s{;j_0CX|$t&cJdJHIk6;=Z~b0g zjx*20OvJZKtq!c8Z|sU!w$4nN9zJKE$wr#xuu=eR?a8H_b{*WW_Lx|PpHFQAgf;Hu zzAKe!!-k=1^$7v|V&NhtB4yN?2&-)XA^P;xmj%hlT?@2*1&rE78VgWaH7ZGUssC5? zUd2yZd=IEyG44zrR=r`glFG9(DLdz^{p^Kg-6v(`G!eK3ty)lWoq4W0-Zi4-s}(SL zgif!+VD^DpwDz@T?FLpV&8GcX1il{~$ViUm@}v(2*D?_)yI+%P?w2BrEKVM^0#WE% zPEu>_H*(soqlpkZcf6xdVhsY0+d9{64mowOl_ke&ILO~YJxzqz_a`yWGaGH4XSFf; z3B-tOm56s}8?tr65ECKnK1pn4W-r_8jmfaZ=g?^0I2zAi^>|U(M?t;cX;8%WuzNRCcFRTvV^G-6 zPSh?%;-hD)%`>}N)vUf`qD4+YHOiCCW8+D?i~~)nL|rAZL6Kgz=T*A8Aa-}@p>|nW zmT!3jI-J-QNfC5$>{sxOdhmG9%G+u9x?Vq7|4567BSlq*Fis|%XtONK9)dUc^%Zp|{nL2T-bHGfJcNY>c1S62-Y*zm zmmQCW;lWz-I+VHllaaP0Q*LTbbbzHGXy8i4jO-@N-`ztqNd7o}` z;pb+1uQsV4O|*Q*siSj^PLA|#AdhY>Z1Ik=)1o%Xt>@n z0`pUp+nIN$OKihv<>@`mayWSyR7cWwWTPUyU0TpH;Wzbau2HmD*mu*;aAQD6mgc#) z?cljBtWiK$HfrWc|FusyGkcaWwzyqBo1z?#nxfXs2XS#LHZ&3M9)z&(Gw;w5;oI2j z7TuU<+HV^$8tf&1?Nl!`9!2+iJXhtEB6Mt|+7&5D%vsZz zA4FDN=1@K32hkpL6Nr)5=ljhdrq*`bf$wYB+o_$|(>dd8qlztOk%=8x*SIxMj>(Uw zsyp`%qG#M@nh1{?%~^Juysw#`yCXZ%+h)r)VB+`V(LZCUAy;Wk_X^;A>a{ugrD0nu41b%BubN0+aaSG;vc`Hh`>@CUk*LA7q zmx92m*Q)%2f@{Whkxp}|JPPN9Uo5m%XW&t9Kw91c!0hC^FsW~>PDtiPCGT01V`M2(^sDjs=CF8duKOlS6H*L?;!Tr1UWL^@f-cL zJfAk0NC-m`CqEp|7Vby2IqG+*YB_%Jp1&0P6Z62lVU4O&MO{&%3ICMW=p~jl3hG_# zim}HY+=B4(PE6CF4xcp6-9)5ViXb|=@HWL>h!Fkz6ud>&xCuXVyny7NDCaBqLFATF zv(&QZdhp2LYm(gud+A~CJs9V2R8`*;%EKD`Eg^83WItq|HO17N<$`#cIq4`)!8|0J zlM+6?w;FJ55Fb4f=3UqWIBiSV2M&9oLG9l6QZFS$@Ny3?NC+%D_V)wbCy$?6cX>bF zWW^526A<&jyus?cdWu@O*I=GIbSja!gM^l43P}s6mTxzy^V5vxX%FvLjl7&x*gp+> zh=C2@byoF(`$+yJ#M3N?6M=6;V6>wA-EX~m7_p((JW!6YgHA(9$QjQN~;nXRG;f(__Q?K*GRGQMR#y; zPM|YXj8G?nUthOquu}uVvTP#>@y#dLe;li+dJK)`E&OVmh?Kf=V4pG>vHt8FwSe~! zey#FE4X0plDv7t!|GuYsy;Cr+aOkVaBgF!xW1k}IYXoOS!)B@>Zryp@Vu<$&vO5vj zHwvS{qtVAhz45&(pK|k&gus$u-!F(QGU2-VsZS)&Bv0{IxNnLo4 znr}5UQlIP9ttcmNPxG4;P@bnQKuxKf2%InWX9DZTm1XL*i8Xj! zm#UJd6Xs!{MNTy;|LYg`XIXx(tWA1@2dxHXEeOQ-CU5rlZers-F9HhP)s-c&=3PKX z&svgLDxnqcl_Lko^)A<_wMqcuSYAK1bwC&XG2L5D?s13;^*4C=WQUu&l=bC#JMWWj zPD*_Vk2J*&BZ|O?nozs8bhi(WD5GCFM;d71FwSehI8S`5`Qq6J`@k9q=lF;BIbnu- z4l|q$W;i^H;u#L{fcdKN1|RkF`>uT4g-4Pnxk2Sz8H{hsI;?zFdf9i+4CQ;$|4s0U zgZeJRw{GATU8-L8Q-J6O2)tU#R8~zh*gD?rd7ix>m2N1Yo(NP{zk=_IYxnxj z`&ypg9#1INSY*vYXdIwrTwR!W?i6dOvNkESS_m$7uQpLm)}#A26r!@Wjj1fl3rP4RRW`C+ z52ob`z9m?vHtNS|7nk=RpZ)HuH712n<>gxg<9hS5O0O|CpTsQVJk-d z3{VbX_iY5W@OfYh_b_eY*n*wJge@G~$lHPq*)2AnG&F66jnuuk}ZD&_RuM5L_F@Esw} z=v~e^alRO>3(o-)AG5l={|RI7jL&|Pn04+92vH+7;e>Z8obVnsPIv)fojb#~ zb;1h>>jYDAfakz-@Eka7cn$!SIQ33qmgfKfKJ>2A=dKT{xm#ypKby7ThQ}5lgx6FOvplu{Vb!6M7JQ>hS5SDM;Tr`A;r*4wEZ-}_GrX@gq4p@@!btpwc(~!4SO+Ss~Xn&jGGog z$u})veBit+*_qL=gvTcG_yq)>`*6P2S_^38@oVxBwmyu;{4RqRYt9D&_O*tuGuZl$ zR%+tEqklZK6!LY(9<<8U0teOIo!4nTyWnhF@~5@R1ZYb__%{4ryCwU*0uP*m5tdYd z7%%)@0b$7wDb`GF@(@1IpDGt29k)HRPbJZ^RFdqL_a~rVfDe5g@S)Fa`p{!PZR|sj z{ly~aY4m`$!N4&?$Rph(r5s$s@i!N`i zxG|F5yfK1r2^44I#)u^qQI~mv)pkYTGePHRpV6}76c8a|j1=c-sPTvPoI%Rvb4B2DN4(n>XWltKl9a zG-p?Y=s)rp6lhn3=nZne5)!&1MBC!k0NYMn5!f<;+x*8oL<+VVU~2;6VYZ+c&+=?1 z+6f{4(}KdnhCQo(hQQvR!n)&%5N#{>lK)5rWl+p=h_y&=bFuok^03x$=q1+v1HQ$+ zB=cFk8d;)n7K;$WylOBqwYx20Qcu8-IqG;nxQThU+ zD&4EV&K#T%J3?Og{&KKtdetqKyX*&Ti zEcGyYF~h$H3?9u%tn{`hih&M1E{q$b^##OeK;RUdFV4y6eQ?(c5R3bcF?jeR9_9;h z#@nJOYC7;Reoh2V!TI8x6eYuWc&ib3M1xcy3G^GQuB=z)@T&rF#xf3GT}UYhPQm%& zoXpxKMo%)#iaBS2?6K>DSb?e#&05&UBCl+qJgle zaKwMq-;&Fr^-C!SMnL^I$D{N{0Gvm`hzbV8@Z^$PRQMeNG;WgH!#Qe=y0Q>x)JiWG zKtv!I=P|$odI`r=X!dbIe1h3$03a4rp%MbkKGJ&%a6}LlE{c($Bdw7Zh2|*cRn|IiB%396A(u&1kZu; z!|3Wv?)Dw;he{>KvHRpGg0G*ApbZwSx0hd1Q;I{6d0^g(a_gTFbYSxm+J__W?3g?B zN>jpSjplgBh&PcV>5)IOYQfDl6;t6T=5ln(@2!T@8EY}1?O%#jB$zvn-ii4sN}He|^tO+`y+-Lt1gGFg z;5cR~+^E{nhvq*2&R(wWE`n1~JKJzhaDp|t53PCbg}p?`ZV7?ovSPHN3@8vuuil(s zA2Z;T6ulM4k(Ck8`ZT967q77g&CgBI$YD5QFOKA^D5QNLUE4OoZm(?WyJkBZ`Yz5F zN7)6RyMyiMg1j&6ou;Oj;_qS}n75*=8t6e^3>jjdRL|6RO&*56gQ;-TW6)lo)}pg6 ze75^l^pxTuqZy8&nGbS2BxX2@sn87Pg1C3T4lQ+lsQrUmX(_rfmIO-(bIJM6H1I}G z`>1>WN>R*l{os0o_dlRt-GzRY4f+-CeYjuAy~Nquz4!0%#bXfnc039cWgW~6>tJRm z@&RrQqUfD?WuhI64HY&wW#8jv~ z0O8yZ4uo|OuXlLm1gU`1+$Vxm&fVP#SZmQ<&4Jf*kkCXJ^SrcI<9MaVS_VjHB8;^w zdFM3-)>_zkajbt}-3RML$@{2qK)^nVqg|2lO1kqkFhk$9^seMxk)bETu83n@4eNIx90 zg@!EcAW?f5dmLwb03wgjccpzTYI9>|&{MQ1Kp^c^+HIqLWz1bB!k8;1T~x9GpuTHE zeb)xJ2ZUxRStiiJ4vox*yeEKYvf$_az+V_ZwId(>oEE3f1UO5SR+J+D{Oe3iXViATSl`eLqL|JI5O8;XgrO zDm;pQTvwP1>Wvxvj5+GZ2uuZSVmj?_II? zcCFXmeP)mB^&5Zw-#q8l`FxUZW+pS4B$H&eZgiwi`?lTM_H5a^Z5y9f1AJ<g%vaj(3o4Qxr0G7;hwA78;RSj(dK_-?-65E+u?2&?WNg0(D}h8)ZP z8v^<&1Z!D+H7P33ZwO2B3$F(5#9EnCWi=keWpMVi*jJg8Az%FZHeCKRN28&p?Ru zYx8P%w?sH~j3eLu`7VgAiK&YwCulfvojxFNU=&diKTn|Kn;$&isVfKB9u{ zBgs+xa7Tu`e-`j@0L3-Yt7f0tm7zHL#l z7HZA1(4V8W&)4JfphD5?a>b)6)Y! zSj&>h)S4x^If5nWAL^^GdrPoA-?zwE%j!2%YgX@?BUq9yjI7E!Rmjbzo^X?~7U~Aa zrX*D&4W1?q`k!=@u>{-2mLy3huA)hUZ@z7ju@>@<+)C0Ql6(M3ev2f>TG&6>Ba)QM zURnOou_sGtF+#>#r~~YEL4!lFmi6D%vxWFMYGW%^mfsPL!_7vhSj(bk+LFc9PtUM` znVlAuROrL1=?oSVQnKamiG#GHgO~qQM z8`P#GJ)u$SMqYFnjan?R+BK~NN3$eNBF|uu7oAU@0c%;jo0fG`qVY82U@fcPOs!eHYtC1a zbeQyUfxKt}&1zT+b%P#Nl1@)=qP1I`>VM{s=)~=M&o+Vl+YmS7$KV6{xi0y5{`Ou( zBYc;?*1qv^IrCUwVgA5clUhC2F9mw=xA#n6Qumm@k}=33hX%(9^G8^fPx_n!8TqQ? z1r6J=G)B()Zv4pwbN*;HWr12ebya!h?rs7C+eNe_Mdex~U-inb&WP+T%sAL?*7a^i zi98wky@e)M)obTqrB58U1^g4qu*B+7bB?m~Va{-pRJ(m0_P67SnlHy@8G8{CUMt*< zW`jIfCFFhw6Rjlx>S=ys&1lcsFfn;`8hJfi$IghrQo*Nt*h)ba>7S?QO58 z57Dq>Q|L+kL7NbsqwRNHwB1&xvTFA9hvXWS%4j$aO6T3DuL&*9bIng_xOwl?C(bRw zTlF%z`jqCGI&Atjx%h)x0;0mG1U<`$(mcU4rGaQks!Vp(f$S>HSYH8wob+y^>KD(I z<{#ox5RJ1pE~^DIZIBPnZ=hib(m-w{sZ_LG8&vhN+@a$;75PPL7ZCxeC#&HV%F2%U zJv8heq=y_zQubSS;6!tXghUP)ClKo^Q(PSlP4Twhl|Fo;MgeXLoh!%%v zv@zPTH5CMFN3=!5w0udbNOm>)_9@#|&v=HT$l~1`6PD!Wno*J>NP{g% zgQ>|g;7G+rP5h-Rn9%Kr&?bdn^)B*`iAg~ol_VON+syQ zXG?QWmy`zTUy`CTu2o|lDcO@T)wMyF_UT=`LinAhA_7~Iqy>}vsJCkRvMYVdYnNm9 z=_~7p@HYoj7>F)+T+w^PhVX-trX^N6?xB9^<6xUt71UB?QuOtYLU_ezlHrwVpZ;=O z2=6j0g@G;6O5b(3`r!IJc~hg#THZ1z^@(Rf_||gYb>swXOp=9WQ&clQk-8*}E%xv8^FIQ-Kr)qHmTssTT?f<@@e@BhS!gWvV|zUPH7r4T z*peg#T`9LOGP;_)>&-xIw%-kX+t||FecN{(dB>3^NeBApR5mm}DYuF0q#?hEz?LLw z_r1Q#=4#nl;dN1h9EiT(?uK3@O$hgFXZl2!{>znFpJjHXLJ_U|(;NEIqal1?PEm4E zj`_>i%K7!9wn1gPYZ=`nW733Te0gIR13AGlFG+_sHId!-t(UuA?4%)eL|{vjG&Y@X z%i-b98qBGyWmtDZU)?i=@4Wg=NA&GBk}gZR03X^f1w@91womgXO~n39L3dYDiyqCA_?Gg!kCq=zj@QsdxC zY*d;1%2CZnyOSn^@t{vW?*Dfd19?Z^MJoVXPWC;~F5j+OMMHiOfh|eWhg;j^`Pysw z<^3o@4n((Xox#W);={{S_9V&6)vsu)qm^JE&y~?Sq;og=h2-Z=V>|`PMLEu{Y{gox zJgiRGG)zX%i9T_Vr@Num&cX}U^ClV(Zg*tMPL+|zoc&ux>d3o@sQf4|JN4qd+)B=; z)$z_~Y`pBlhYj;I5M7{*yAhGslOG5-_iCrOw>)4|Q8s#Yc|i_DKa(;U#bF+4&PZcS9G`(V_VqPHuKXX|lJ`vtW*`2|%8)wNLbN2c zTDL-;7}1mEI#Aw*)Db=DMjGQ_y^P%MRfxFicD0x7W2tDiww1d!JhO}8*)bz8T*uEi zUWLY+l7WwI=x^L#l9>a&7nT{SF0df1XAEonMLnLPc5{4lH? z!*y-V#83K;eC~Wjgs&mWQOota(z%O+OlkNVic?tEN?zaTlbBuS6dBWl!$)a=bBF025g zLyz?r|9bGuBMKNISCx+3QELvdvu*c2%Sc_Q1!!6=^*W#qD%^$n1_mmv#(&aB?{nwP zV*Ct5Pg?$14{DW#|LAD0+w;ans8b$QV|!Ik%`e4cJ(Nn?H1jp)xIWTTz4qY43luW$ z#=X`zkIKZoM)(n8@7pMK=DX@_{wWU)OOPJ6BuNji6w=mB(&RL^iZGNG*Fm_#A)SW@ zXr;devyUgH$^yS2ZKtpUdbJbzc-l|qYN^QSG+On2^;pMc#Z{z^=;I6b>#bAz@a~gy z5~6aB-s0KDHl&Wc<7!!wB8ND% zD_iojmm7+!NFC8G!Q1s8iv#(>UFP0-N5-_;=m|DWJ<-WSf5dIPE|0nuzKR zI;p2aIP)!%N9(vk*X=j+@uh=u8HjGZcdPF9B#;+MWk%KV_OxlIcRiPj`hQZ9I`WP? z07A6RrscYyo#jiJNki(0p0Q|$Uixwg-f@IE*IpTWLLF79ILrAemxk04oy%>99+a^p z_Znv+y1cKduGr{c9k%4tvX*=vUqs_-nPQd=GpRT4RAj+x@(BoB6~E}WSMOLdga-$h@scTF+0`PC94zgv0>UaB z*VH0n(D)$rAIZU{cPXG@NrC;_^l1%Ca<@J%269WsByZ=ad9D><7tRI?djsT3M7(@_ zRV}&1jjfzqR>M9)X|We1>D#^gYWxdLj`^pipby-oU`vt|pqEk?WUatnPZ9eH}Rvt;znh{l;n zl44?Os$Sb7*^s|83$q%|?Ks0pQsJe$)oZR@+2iW36{L>5iwN7*Yid%#y3E!pK}PC` z#+jPdqO13)j*VO7ffr&J&ic3x!dX<3QVx5k1Z1eoJ}t;7tjLfPl!;=mw#;g`?t_@t zFI56kM})YNd0h0PQZGjX=29!Iz!jo#HSuph%!7{*ReCP^CCZ?bLN zo%-yxB(4*m{GGx0>xMfYd&AejH6vN#iKVi?YcKYE>gzD1j=YPA)y3}0-d#dj^RaFM zSBS>7uOx*$KO$E+8Ypk=+@9e&8g~;YlO)xcRzvow!B~la0vb|BIdBI+b~QDKwdh=m z-D*)^Me2ygeS#!qE!mRQJbggU)pClATp=3wB9henL>2bAdCi1JseJ@FaF2t#CEB0& z=_nuS_4XGm<_id6i(sdBq*)B)`{;X;S|FQ{)z&$7KUTG)X$6c;Fz974_!y)XQkrPplCXdswO_!F)z0*|J zkUAp7z4K<*O6+R7ZA$GY`Gpt&qH(WIv8Cd5*r>TL)Ujv&QZYJ!yrWEXqBtY9vdai( zyZ03nA`=*&!6*gI=gp#J)^oqSdS*Kz&Vam&h}P%+mg_e6wjJ~BCPZ1}*lX0F@b0@M+wsdogvd6=tS~Y~Ck?gUDIc#g_HwJA z5bMK;C&v9Gsn*c)YW=F&*z^t6gvcH8E+Sgg=%%*Ha!ejEv9%BvMcy%fDM{TsOj1An zg_1N{&8%)->R?%h7Zg^O$O+0MNd-Oos>-K=Z0GLsLhKb0xMq~3 zuYavoJ$zHJfV`1HoEmw@H6zh@a9-7J?vOtnsjuPM5Tn2t>y@MdSB5D?$M2UXrSGDB zH996f?|arwujG{I5y-(|v8GG-@_JeISEUDjF z)gSmDbiA%r$%(dFlB5=y7AmE*0j&7vI;z?3<;2!}M2p*rXWLIOw#P;CH68`@ij5~3 zDfUJ27xDKJC28{F6ys@#od2LjRvT$wbiTA$p< z86k%vcyyhnM5AT09JxpiEI~O?KAH!!ZB!m#>&b%M7OKbzqLCiW22G|ZM|TWl*(ENU zC3$+hXN|+aPwt@w2Zi zuFP7NHZv}sWRyu?ldt~kIBBrpg=I>`frFU+z%vC)R#cd5R6bIZr|UH>QKVtYF`eWX zdvZ?#)ZjW=0U+aXC4 z|5~oBEzy}h&Una)NY=B%@6>3cQL!rgcGF>w%yA=(a`h{4*V?lQvGVOkrPSMAEYJ;bCrvIa-%n@(2%53A04(*{4)gi|^Wpv+2_HMeDfY{iejSAPVy2~02BUgVbp9F$V;7hqhm{w zbnAYg5?H+}>vK<4k>3*Kh8tJzI(X*?i*=+&-e=f(rA$&=wz%ju)$9|?N8y>5h}f`m zmf}9S8q3=?x6|*YP8-2@yWMm8sMu^_{Os0L2A+k{y1j6ERd3me6$vm@Y!~U7|E-oJ zY2MY%%3oD#Qyknwm}`GW|3a*ryiCav(UP4$`cg%H(W4?gNjhF5Rw;4Aj}4yY5KbDV z4hk`%qqB0~&bf_;PeYB>{@M8Yxn^|mT*(Awc*=6DT(e*eOa8StH1t-5dAUm|3~^=I zF5$DHxxOJQTv>j~T7a85OIPBd+=qS6G5vi8S_~U8^+RTaE3x zlS@O(KwHA|FN(cR*`ciO8WGU(u%^2j59Tzk~O%k?0J-n)wmtu zL@auol|Q^v%!#njq4Tckw?15S)H%VZcem`zqj(I?#7Z2lt6>T5moef^b8XSZ%Eq)A z*_D0K0s?E9c4g5vXSJ$IqrbDVtzTk^lvOEx*tkoT z1=~ft5~FHf*%vA^GX}7seQm;N2FBq`8ow+t?BISSQ~un{H=vr6h9xc5LbN2U-+V@i zJC>VW?;XKz*7h)NKmYD%9aNly&iVCUr+qYY-jAKFEZy$P<~FR)T)YnHO=cW*T#cy6 zzkmCvUnu0xk5uy)(2{hC=JSg$T-m5R^%-!&qlUcJXVDqd`{8~ZTau(S36ff6K`ypA zK0=^jqLatDb3RX&oVbehJguy+`d%LQs+p69RSVn2^#h#`epsZ;ZM0vOPIqQlV$!hI zC`eC|cFxM7lzQgQ;sc`@@{W=tJxOZv@56+$&plYz&^ioz6nk1kl*+Csy{V^UOSaLvBKxV&M59y2!pf}oUD?_N`ve+|J`FSS%yaO9XO=ih?20o+CWZ5B2lf);-m>{h>RK_( zt?PFgOInQYWc+wZCwzVHIFMU9Hz>YUInW@2t(%aCVJ+lPMC2l_77|yZf8z@K3OSUd zW97Fhz1LJ{t4HT#C?U3s^du=X@~JZYbT0NXF@hByxl4a`$d9-D;3;?s_tNp*g}3Sj zS`_C+vZp5+D?d$9X3wq0GWN;Mumm|l8>8D)#&YFbXl3?(uaAI0t`JQtve{FW$)Bn* z&$qb*t|n&RsUJ!x#Xs~(&5=Wj>GzLUQl|@LX=|1e`U++lq2Fk|OS9UnpR*dnS}^zh zhM042rZV7CP4+%AtH2ek0620;XDsVxDNWoOuu{v?3kV#Kh^D<7&Cb!14{MoJnIR|W z=gq$QHRC*|Jx(I+aS8_*&QWWPXS0?y?r=O(gnrgmCC#?#>}%hg41G9SC5}g$an{{a zE|kf`ww|oY&_|)S!?{F~Qjz3mTpO@V%hL-tGjV?gR$>t1q^?}7a8>SJqn(DUZCs0* z2y1;!H-s9WQl?eS!<0M`8m{hfHHoWCNxF77P>H5pYQkMr#hoec)nGi*Zu?5RQOcB& z`{ko4yZq0N-rB{RTv;V9kul<7*0SOk=6@^lLT?(TEmo>z7{vZ{ zq>(Xxfwj#4Rs@OWkFAT9ppk>v-(k-bi~?fR2+$N;ipZZ@wT8#w(GZV26NZtzay%Wbv$`gkS*?=fhDcmrZ=lzoGVG`1R6-2)`_(f)U3-w z+3amz%lx}nuR0paOO>1?MvmURTy1@9XoteMt%{2 zElE<>6vxyIrK=zZqC2+UqbD8q<3n0{n)=vZRh>;2hWBL5C-_8^T$H1iOGWL* z3}1F2X;Cah~?dKvB)a74rDJJC2u_Zd3U zeTL_$atpp4XCG{d?xZ%}qejPWk-NW&(cmne&uBm|c=BcB%87z};+aqSi#+apN;O}i z@u;k2K)>gbb6o!GKI+gKs3hWujxh=}#o@~FkX#WTO0xxV4%WTcKV!C5-dsL`zg zyYFTwO{W!PNFC8|;!cR9RB2eTHw)!#0g(*uFmOb}2|pn!)18T0bZ6qq4l!zgXt+f{ zh*Yu9%@`>{9wwD*XF{F-YIB_S$%@VcbZfOj;y?1+t z)DaCQ{DfGQ{F-A{&tL%oHwPTJzNS}nbjxD*&s!D@Yr*>SH$>t5gTmkKkZh+e4`IkJ zN?VKG5I79ATun$9i5v>wp3cZ3#C}$$xG>lZ{#<{Tby&DN! zA$lmiT`Ej(mk!pgB!JGNFC8|Mo)+=&BE1NJRAEwvl>I{h=w}>gjmz;gK{aJ zu_qq>0s`(DaNM^^(uun76rXF1t>5a$uomvx=J~ zr&irrHL5QGN(E(g0r6G3ozWjq8!)~-ToY$N9*+Rvs^VxK4GPgoQQJl>F`FC z^WVCF=}+57jodnCc+p*-qA}) zQlkvR)gCwI$?Y3;W;jxjcl1OQXBerq zlwN?wm+j7Q?nB;jZl^pG^hU83y;1ypu8c4{qa5NXKw{!9`D^}n^1}Kxgf#>5j%yT2 zdiE?gYgw$S-0fgRVO@f}<2s057Snsq8}y#@fab$+^@67(J6OngZm(qJ@de7O6-gA!MGz{<7a$NP} zDwE{s86nT0H;OG^6%ck4$O*1wC24t$BCK(VP_}taPhm}s2yxw>Jx>ev?(=22+tMBa zSI9f=6C~+JNjsAQHz=9@_SbOFfqONSiEb`m>t%aKZxlDSau?#Fc*chNE4qQ5v|6rw ztOuLn8lWI`};bAR2ex zl9anZyi&q(Lrz_{oq)g{J;ny;-fOD}b@e~h*t`T!;base=@_w~Q5&16e*e*h`MCMp zkUH`%B1Wyfsy=_`V7)heRgn`!W9)=_cj6JX%H-5+{0^=m0^>;--I1hX^nP$9y&sHc zIT%KSkQ0=NPU23a*3NXT&#qPv##fCT5!e#lxf@nQ8&WILW z=tS{+Y3=%elC13W&-ijuh{IuQQIb4n*3&jjPs_f1$)jR46J-+Oe$t?}&D2!+>2$YI zULp31oM1Fkl3u)irOG+OSW@n9LR=IPV(c}1POx^bNg=js)_Ng^jJ#v4m-aa28)+Bg zQ?Oee`DBbPqf8iwrMQoWO^sT^S!hQwvW;t8T**q(_*ci(abrre=)&0+ z+WMW|EOLem!)P|5aqUYliznH%RW(wuVy^dOJW)WIuqB#t^wQxwF1NS6nm**eJVli4 ziQ}pUR|b;wG0kMPZl$vF{dqkE1g_^0{WG7;*Pr=h{>yAcIej>`i?cS#k(^JaE@g+Y za=K8~A&#}gdC<&LWag9cqYN~VH-=*^amHy#*^}Z<9=GNBC-T2MMU)YSTl6T049EG3 z@~ZiGux^xrCij{O|K(3KYhk-0!puN3>SqR;|1ujh2+p|P#`d~K}cQmz% zB{)7TG-bIVuHFR%Xzul|%N1<71uMaw7w*Vtu5DaKTl?=j`TX1z0s`$A(LeJob^0l} zfIv>r@@ZY-XVcyzFgY z+CQ?phBk`UhgK;`b!bHGp%F#7!c??y93ME+gj`{mjf7(@3vG^O+Ic1C3M;=MMp(CF zEsHDDV~{VQ5ta96t}tQ8g0(Eke`@gm$df9Jb1TyvW&0xN%%g07rsRLflWNvNJzH7%DBB+){*))xv<3@djynrM+5QOer#z`< zEsHC&e=M#dADY(wr#z`rLi{ODs#(iIm|C+ClyQ>~f69|;*0Q)VwPtZe88->>r#z`_yZ8>PFDue|b_(O<4$2&lck6sQpu(RI`@Fm1#>BS3f<&pYo)d zwJga^d$lD0>3#l`C)KQFY0VrHR`34waDU2^YSu!np*H`|JgNV+Yw91z{Gaornzbz6 zO&deMLY`sx|K>?GYgzqc+A;dBKj%p`Ygsxl#|rw#Kj%p`Ygq_WYZl_?T>Gaysb(#U zD^qJ0S3l?4Kjld^Ygv+;TC*fKXNf=ONi}Ps)~wz&XQDsnNi}tgT0@Wee`b6atORZB z&l%rMyF%NAoaDrnmG>MozMHm-<3mLJDdW32J}iVexuc;~-SALO4(t0;n;tM^X_;rWh`EcQ_ z1fnHr-HC5%q~uz`O2vQ(lq=w)(E#`Fn@l`&~7LJ&HHf5luHU%erVOUM`o%m8>S*p+|by zk|gyCb7;AwiMAOj{25Y5-VrTH!=6TIr+e*@AN718ukJnCIMlTwFPwg?@D>^G+|ur@ zWkzjva6XpT-<=@>`wH*uQ>GB_lv-SVe-?c>6T@2A(<0(M-5oq5xwCLRE5i~$cp;6n z=}p6}_S)gicWk{zpB3&1XTLqcxVpI-e;-rCAtLHt_R|VJbg-UN3n=)y+qcaW!&i&q zdkeO+rRq4vICLP2{}{SlmZY^CJ81`GRqoO*yZq?tB*WuVByaT3eLKEb7vH#Feo#tl zf3*M`l6QrSZ>RB2GPWd18@9M58eIYh2Pz58ngb~lm(V!jJ+^|60MM31|^+PMdQ z?Ax6aDrP3gnQx-8;A1sjaYq6D^p=Un^`+JMRqP8nO#b`Go zis$?hn24|N@isQSYMj+aYaAab&*~JZVhOg3EzymXw*9pjCAZvdiCsY8jc-KLor(HI zwBw14olKikuoC1-q|t`#Dv0cAV$T8!mY`jsy-|Kqp9ro0kfHM6{h74}+Hhl0Av+KH zu~;v=dyFC9t;DC#j@L171KrHL9H_O5xhm^#yfiGqTld%! znpjrD7xwWP+Zyva1@f`SpXs?S_cmO|hVpw=PLh>$PQ0X^`kIsV%owC$3BHiWmMEq_ zAV6E#bgArUR7^mGOGAx>PvJbwbL(&U09sYap^X`uk$vuxUBfpGNCVLndtF>YTR-il zT>48E4NFi5*b>Q6ajW{J))Tqfi`v2~Y$j}A z@M67ft5D;0|17*izTAe0*jB8dwz7d;4v%8mbGeD(qx?Mr+6~)IVpzs}33P%8!R_pX@m3R`?3-Lc#m^@MwKd5ceL0U`92@K(Q}^h~|xx!Tq& ztd)kf@U6c1@@3)WxoWE>d*vz~t%TS8_>LO6l_dM^i|VY3F5#zUbr4>Y$NadVdyYKk zC|=KQh=@v^+NzF;^KA{){`AJ=zxA#mU!S25+_lEB>TQkR-k9v(SWzuGG^HGpdw`G^ z2iCX-wnSM~>iMdp^Dmbjbz?PbH}L2U{Yaa0jw3DY2EHDmc;byz>hra_>`LdNgn0qqK@)Pl+~x51brYU$RWL6PVr1_lWnyvkgNnpDq0Cz4@HEx71BD~ zSZsSuBMSWzjwl>ybc#&A-GzMnR`TuW&(VLNU!lEPDKBluKVd9e+P_qsy>M1TuT3|w zm-=ao^K#ats+WRuIIdpAIjY67!djqbFbi0)R9Ii($^us$bZheIJ9T%iAXesBMuzK8 zT$kbskY3l&3c1L>9kPv9$hd336|%VAy-$0CbF?>@PJ08~Vd36DTU*Yi@M>}77P(+Jl^)ie!RC~ zPc^HBfh|c=inuA^VfzzRk9=JVw>qqovpx;8HS_MFb!$D& z5imuU@AhwKta>`e(I{#vdo-(|5$rP0u_fx3^7>>wlH;#bS8Oh6=}R82u^P6UKcR`E z%ND!6&AFxmntVyjDEZ*fTjAX@_tUUlq=zlhj(%UX+@|q{fqzU6k%RAp{>i0RVHLTU!cafu7?lbC+tad)I7->{Icv zI&n&EEui~tNB@@ziMOUR!{wj-j)VF7CPr4SX4qGrb>y!2+4;0nRlg-+TF#Yecd zj$EbQCA!6ik{ns;ACuD+Jg0VVRY#EA_VKRcYWq!zj$6#wk@AD1pLRVlSCO)W2&{co zF1TT_dv_Pb|R#6AV>dnnz2x;Lqjb(fWY|$+)oJk1vjGs%JGMquu2! ze0`T7y}@Af+XJp~xmd2YOVq6|!!#^GIa=*=<&`FRP&}(JA*!VGV0H5DRSVCuX;^Zx z9pyQ1kVk(JUGO&=Dc$n2`r(sRAG=M%cCp{EB|0}q;lW;c?^T-+4Q%(HvYvcz(L%aQ zy?npXm_MnW+J8$bwQtG(TA5HU`|3UJjy^+L3bV|>ymW5tTH0~P)`H~dU;U&KJbS3x zy>DO5_^{sI^6O`Nxg{+P9Ou}QBo%6uPmQW{$L3nooYj7<0B}|-zNcZL@4_fY#h_+H z<4wkNYDCy#Tg`Xz8kQg@*b-&_3La(hY2~_OxW}UCG*U zJfpRXw)^s$D&I&-q28(8Swo+JV-S4|&FAEO_L2AbLf!}c6?z{LG0)|Sts8mKYve`I zQ==CZePT9RVjbTeqm6yLu(V%B&h@>M^tC73>#ci7@Zid`bu$y+<2zNk>!MkD^?YL} zmtIyv93w=BMGZ^4sa3dJ(MkFbU&e!v#5T6p7h~Wi-w~r#nEcmH?04)pk*jpX)j6UuxAxUi zC?R@L5%HP0qA&Mq@pJ3#Kz>n!A|hq7T5;|@pjFMT}mUMT1T#~{v+wDuu6Od6&f*zc%8ktZ@zXav%a% z_ZUr}Xe}YW5+YmS@w;#(j4@qYYtt9<2=RdsiQ}&C!j&+_!m*{F`Y`1%dl#d%c)Eb6 z4iuRn8m?sRr6Q*8LR)HZ)Q{JSZ>rn(NIY?6LC(t8)93k{cR%RE(;9u>S-W0%Uq{RV`v^ieMOd`Yw) zv_wSH%$cl@amP39Kuuwk0`)|v;e@zJa#YONawlpEBU2(G4asqV5K}kbERFq+J&k&D zp1x}Iy=`sX_uC;@3wJ4~8~Oqm(J*b->@?hyAt&`Z^|G&=oWk*aQ%lkZouxWyEHOHj z#@;_8isl^AKWUh93_Z6%Ky1C_&gGy&dV^*K`SFVH9hV!uOnf)B4AC$p zH~ntksyj=gZqZ7RHm&-|i`FN*+S=3DiSr$54LvIDAW0urh(_kf?mLiQ+>?tD7Rxh~ zShXSqwT7b>TcRA;M8llbzB<~IJQJ@ObB86t6tmq4%Af3 z4^teW-wrDM%Qv9a#xIMZH@t*+O^9y)O?(i}_`{#YVe_;CM#Q zfV61`NquEnd-u|pO5;dHoui(9S;_M=x?m+3o5q;+FB*5oP7r)M#`iJuLQwUctf7DMBl`YJD3`;e)wyU~ZEp3!6c9JQy3#>!p?LQrd{b5Vm{#Fe>DthK$3 z;CDx5UFzsqewn6Ms!RE>erfaPd~S{?)0besht;^|_&dwi#7%u2JbRl&$Nej96LU4F z4!&f={O}O;`lxekiQa~jAdEpgV?o_e#ET@K zN{Gs9Tb9ALuzyfDk~D&7d?Cb+hevkd$iWeeXqs!&NZRr(G1~oQu4R!1#t|L?1=nji!>ikUHUm<95XuC+8zNkZTnB%-elUzH|%OLM4lkK<`bk7(4+mQ)6PAL>Ko%9@=^mK{?HJu>!{hpcy>C|12TnC_tCt@d#zxLRtQL7dXU|vt`M;N=^_SZu z-r#mYUTa--{o=^9zpZ43%qq_Yc?Qocdglv;`REo;97&-{V%_Vu-{#uE(-z6Y?|)apl+}w`r<9oSW7fI5Djb>xk7H~ zymnejwma^o`cFEUp@djVl%rHoCRVUdN?Yno(G0D92jA<6eVse;&a@i5nY7KZb^lv! z-m98qC3gZdv0kw$ZHy3;4&HFER?8D3S35W&uq8TuO@CIdly{GM^LTxM2I>P_lB9f> z+R5K`YwB%#JBHM842m@RH(jx>MyJebQTjR%jvSnkQ$*%+)K0U(p3B~XH;TRQ%O!&S*!y}TvNBr94vRb)mN@LwKuCQrE@F^((OjO7949KnleXzE?{H-j!-UF z7{agwwTUg!w;(>AQJP&`W_xvQ5W{xG`*8n74T-A_`kk=IBW0Dn`-U*o0k(_uC??Zl zm297{DN#9k2$qOFiakwp?N&t&iQAwynG+*;AGC0^e0uv@yfj-}V6ytXr9VSIh~5Cb z1npAGMzXEzvuZsn_{q2*zieZ7#{Y*;;c*FRNws?}5Uq#|h@ z)!I9F-dtn#u{%aNa8*lRK8ef6R?v5TFWz1(V=Y|oiin`J8Q2AnTH2j@H3Z2EtgXsd z4xg$Q%lFETwCP0Ay*%?sAE5QN7nHFr>^Bk7Vrn?6wXLZ3EaYI%aZ}#IJp( zq#_#FE^>%1(Vgv%;p}DDX?4XjSBAXfIzg0Ub5c=O!js+#?^k8)QRDBK-4chwlbyzb-R?T(DmcWfD@OVVIMr0(}h&3kO1 zinT5T*m?Yh(R$0ClXVesvxUqm+)S^fJ%3CLQ}v{OZj0#TK>5kMHWtEkXQQVjEr0^H4_wwnTSvY*knz zS5>{aCWVG280Ey4Naxj~nE#V|>YZnYRiuuRV~NeF;4wR2(wQ;?f$NMn#>FTb6&Jl4VE`pC%O6b|sMv^72 zzSE06yid3L3-?j6fSMC+@&y;-e_A?lQzUDa8;EAn%P zLiMQ6;{-n_B6>_}$Nc*+wc?{Af-foXvAvW>dhAp0A!^dY&w_`G z-Vw|Vml}HKt&jB+mrIflj?lj*-6T1D2+@@gp^rYRSb{zgN0<3^t`009v#c&itEtF| z&{yDt$r7KnW9QnGQWt(cD$qbQ(vu`l;wn?0A!<3|3aR6mN15oJWwYKa^Yv0{uTgzf z)B*Oi*t>bF_hxqwhNvDaBdLP+49uTSdKGj-!qN5y5=Ygc`cnwnq+J4N%sI*X`NbIrY^z zIYGt}Tt8q-bVF!qM>bfVr0y9yUsz?V>JiSTj$r!py1O0CGllVgKHBvx=`;t$sV{b7 zcMla-H&5OxS6^O{f4&o{cS;!Nz%>J|C1@Vp)Qx$~3sNuJRtT#lL?b=={ztKP>_R}S zT6&BkV+qQE^ypq+)_yF!d;v9eL_J|8gKJ-;N4dh*_hHNDbyCB=`Uxvbk1bVs(*-5< zDcxH;Qgx}yUGA6EyG3>+$xl!3&o0}8)EQ}t39ImH=Og%|)+O}IwW~Q0O<6VxF`f`v zenZ?`63HjF57Oss%-}#Y<$)a4n^nD8R~>V+p^R;z9O9b#KG7IOG*YK7CcECQ!4G=` z>LttHwIdA?vHM+L_T;gzS|(Q9P2kEKTcZ6(^Zx8){!;3e6#;U;jZu7HXfb`zHPw!_ za0N);^u80vB5B517ExJPCteJz$r~;V(2dTu?bs6Sqv{W21NVoj2fN&|VOzM$6cI6r zG!J@|QoVmv5_VoVqL3clvbYz=CKoHA`p++A!xE$+j={>>K>8Y6pn7xHO&j(Pa)`Y^ zd21haV<%7etN-pq@v~1%}nwP6;k9?Ie7;3 z2Ds|S@lUU|CWYD#OdiDMjZUM!tCru<*2JG*uauY-UT=_v0ugLx_@us7?qh z!FJ96R!fr9j<}lopc?bul3O!N7MCo@%bf70yHWprUBmg``hpYf)shkU2w~Q;O0ZpQ ziB16s5wImU8~vb~lg5tbPaJdNxwBpCn+9e}zrLbWoe(~Rm`n&P!FJ96R!j87LPFS- z{c=c^E>0RVyaqbnKW*rwff@gQeP=X|5Y$gH^_P=|Rf6rB|E-qjW!NtSgAxu1ZgTtU ziwFk^QG#fcA)WkQ%lbZ&h^R>j>RD5A0b!z(b>pP*>nj+h2J;YNdNKlQSzkecKBU-E zLqeE3H|b!z=Ko~NaF__|izt*gitK7IAxb49uoixG;}^o~mnF*BuK7QCtT<^{-|3(j z8F3Xx{gjvb>-Spt^@v}HR)k0%Q3Aq5TO-Pp41kJzDi; zB1GA2cJ{Efr)Ji&#vr0iM3cg0c%zP|2$6>nRGWonvpW&iI6$G&d1H$oXDqQHAWvr16-z zGGzfygz*712w}=mhH5_`l!>tH3eg}3Av_2{GMK&lKRUP2CL+17XqDkbh!E1?l(S#y z!ul`EF#lVYXd;sJL5Q|x6me{@UriYCKui%(`dMCseJQ+!-+`Nl!0gyv1RElNBZ&R+oeuKBhl}gEmhW9 zPQ=L*6Ir8QoM^obJ zF7+31BG?kpAcWah%Sm#xzf453v`$2FFF0u=%aKeY4b?XL%S2e#fM}COa$k|oO&ZsU zqZY)OS+mQ2L_oGEzlnlz;Id4yPcJO#T{{IC;YSp%X? z#6RsHJL=^eMu;VZI8*$vJpXtK&8%fvgZbY=J83l694DvmN~V!Sh$Tb^YB>PSO+??oj-OQKP+00s2 zkDC82w3Eiqz9K~2m-g(^x=XT_qm=?By7}MI!N6TrdC{Ru9OhkKx))A}!|9L6b9Wa~ zfw~i6>A*xRika`InR+3`mQ2KjL+fSl(<7XS`N_SAXcIBI<^)Ic?b&rYX&^-2(<9{5 zht@k0$-VfKMl#w&WZK)#(I=ldf0#6=efccWamw+tmc#sS>A*yMh%D^bJA61vZX(Ru zxd{cFI1$MlI)Fwp;uuLje|MpuG?IG}(I5vQOgXMo?;gt0%4XKGder=%+*eK-$$dp9 zKM(rHvBzGrJRtN)g4veUi{^hz2V-y4<@+D3vj5bFiRj~7LcXj`SAaUbx%-7S5nFmJ zvtNrEL$_ld5@K>*FZp|qCr*Ubi-|{Nme)%)YbE!hlZJ&h z5pTkV*e6{qO9+#ztJ-uMappt}FQeJdOr7RLSZEXR)+@sPqIs)iME}qu;SarJC&KiW zG23T55f<7+T*&BZ{~RBmj4=C&`pbzZySzuDMZ-dy2=o8cZNrlhW<(GC-_ym$|dD{cAtTiVM3vD8j^^uG)Yp3k_ z#AYIrN2e2Ep-n`x&Xc)HwnQhwvT8(|h-AA;MwtC%>fNkmS-AP%LYs(W+hufTLXT(7 zKD(;7d;X>1o*ZM=CSqpx(8QnC-s4$3+fpuz8d|xhVwQ~glsnP1YOIB5x<|Goo;8e1 zrN$mU>O@4|ysw#7jc75lJ^Al=R`0Nzx}nWq3YK7e*F;+_(HEx(vE`7Py0P6~Lev?f z!y=+Z+c-9^)l;P`eXqeRNwzpAS5~`X)cIy?94oizwc^!1n-B{(d)KmjY>6_yFQxpb zAG)dY`p2qR3!{!0jig&)gxE)j8Utd57&1mYu_Zc7?bn$dI+RoWxMZ)BhBfZ6mKZ}0 ztlfbH`F>O?zB(yHwoNZuH234gcI`gtCfaI=cJzfiuniZ!DBW9}5)c^QMKpcMj1XSu zzbM5BfweFKEg~9d5$qhDpFc_GrC|x472%5^x-UAU0ZW;^irVn0Bp@(ujPYd3j5j8l z4S&YeFYR44EI}Gbo3aSD@no5L9|@mVrnazpHCF(pFQN6P@G?-6didpJbyt2*==mkm zx%RPY;Y%cZp+p(2cNM3+?dOzP4ax`zeBp#IpXlp#MC1C3?+Lw$29_WV>2qSb{W6w8brDnreC^+^5QVxl=$7 zVegD@@bCp6-6N|NEq7~?Ro=0opMb!3clc_LBEqNV*rM*XmwPSkFTB)48s?7G+P9Nk z8b2e|rY@!||>f-eIE*O%GPfYjb#gn8hpBBhRl5Fz# zqOrm)J*0uODFfy)RSt@MQ~vyvu1*@sqm$#UFub?;6EU&(|00lgMANrxKDe{i`QLt2j`zs$b}RX-l=OAgq!!As^^F9s@Mb2W$tQOAWZzO|E5Cxi1db)(Ii2wU zOFqikKR%jWeaqBTty~z)6Arw+gYkX3Nghy{-7KprjcWP`2)x~fx87)v)3+uom#>Jr z<6$P@J{;Z`M%t7gu1+1czFT?qXbo54RxxrVB1RHdBg?5u-QT#vd$!0SWf!~Njin>5 zx-47aT<=;dZ#)aZQ$WgSZEMON+^wU|(O)=scgZUY2cDQ9n!Y+sh_korsIL=61fHHC zn%b-OFGj?z4L8}Qx0p-fxP1>5Zyy2#2Z5F zBLtS%U`nLzM_#r9P20g}wxA(i8I6CjWRp$TX z{Riz>1}rGWO2(_U+}BGBt0i;PS~0|FZM=Eh^iB4smAq)pP+?{Wt5tllElu-M8kRgS z>dn)in_$2G*~@@2Pl$}2!r19&ZgRh*qD~rCySL{1@PX@!Ij#-xFt8T74j!Mlu3`A2bJU*KJQ}ek}be)^9dY#(BpZ8(26YJ=1#^Rj;eCwLV zi3RK~#MOymHQB|%1=KdRG7E^9TfV%+b16{G_zfz`^oIa#tl9^xZmW&c4xC1B8?vpOR!>v z_bBlzLIoPQdc~ILe&UwW?991SO12@Tgsc&$XV-k*yn@d#ZEe$>)VtE0Fg7k%vGC$S zL4sXvE9lLK&7JuF82jqDs+#BjgCYuIA)pvY85n>dio)H!XBEZ34p1?%u`w~g?vBUq zeiU0&?m71!yIUU{v3TrmAAhs=vO4F9&-cea+}G>OduL{2c6WAWm$su5WEIm2rcSeS~==cM#b9Vy3%VtXizV@YGUE^fe(-Cc6TlfLsKZ#TE*^>L2I^?Lv)(kZpL)tz9M4=76 z=-8M!2A9o;72Ov@HI`TVWOQDaY29;*l3*WowFmY6n)Beij_0jBM7da7T}jew(v=>p zHMX9zv3= z&sCZ43@3Tx!h0OiJ%M)Y|HaU%@&N^ZiECe#RS2yhm#A>ps)yh$N#iH=pgSJdC(|43 zQ!o{liu3!0ur%mSEoohevUHDv<>f6XJhys8&eSkkAax?iIPR;nKD@UJ-}}_vK5W?O zX7ae5d7-ygh1?}abt-W%dsz{Js{18h7P_{hJmf(hO^=wCOsP+v#bjWgB05CQ40yeK z>ri<}@f;dPLwrfDNV@#mA@VLGhYo@Dcx|r0{Priy6HdH=+8x$Cl8!lgnauz2LBU^M z&h%%c2PMllbA7R%QwV9{=9V5c>E^VZq*1xNDyG6x;aY$--0T+guFoVgztKkpOER%v z0BhbiN&e>l)Pi|Kl*P_inlCnq^r-hjhbVm|kj2qN`LB{xlzoeUis zvP_$Hr5uJSI3?R?iqzTEI3@YrXGrK2j1AQf*sx30*9AAjW4KsGu( zQGRsm@!t@?zwbidS6e{BM{XdvEG!k)55~vkUi7Tg*f4C=5vx?$qt@!>6n@y|q19NG z<@bzVoF0Hw9qRX_6M8L;$Z|hR@Rysls<3I}GH9D#Z>?xik|ecu?nT=T{cQN%(PHHx z%EdK`OM>&-&YkJIO2Nv})azD+SiMG#3S#A(Pgl>R{E&m8HMeB#QZKLJZ(8J>--A9q z(c0veeolwr+6qY^eUZiVpGHrAc@KJ2hZg*EWna_4iRTIaav*OAyVRiq-MsFjRS&@% zUMx)PMk@}on9^EbA(#qF#rge0-1=ID-hQ#&^lE1aMKhT$JFmulPgZYab@Tp9ML>@m zgR9dfp4CmkZb1}(33^bHxxa2l-`)23+gWO!qSfhNXC9lJ1_$Ue4g*Sgu^B1j%$0Yz zFp4pY?z_PX62?n}QVlxL|=hnRgH z@pm(xyELOkI@&35A^9l&^2fk3tiXmP=Dp9It>>JApCla!Y)G3w4per86{465OM)eY zD7{jVbc11#axK0H#Z*{xeS0K+u1k29vx-wt^&-!xCQiCi(3 zA-rF8eGvk0u_^}psZ}Wc!h2=*YWZ*dYHO=7nm_d~LtZUFho})+ik)_V+bDLsSrGy) zN&CCBq!(6?Cyma&*V(JH?JKetvB~nP$FJo4R|43H*Tdwh<)6S9>@ho%-mQ>9a`-&6 zp73VR6YRtff9A3;Sss`2Nyccn*WgJQ4IMp^l$_~n)m$L39&cZGvo4qF$bqJOp!wAE z)#;gnlgZ^!ABw+x_VQz$PR7dtgqHbI!c%1C3u~P*CnWSEs~T` zrx%U>`pr;!nW{)=<&9UeNJ2ntOzA#x1?=MhgxyFwd&fu9>jH`a`!6sR|1CT(V0~65(OyFynx2k# zBiO5gsrc_-XWKQw?~@1oKK9`E!Tu!d_u(}yyj1Y^z{>=By0fd&rPMB6)IFx+zkjV6 z62Yrxf3K+$3Vt~3o5Wr<)E+Wq*K8?E+ulq!t(J_s99}#-qxJw>(i42I4Z!!>34E{E z^NW42==1~-PfwaiTI44~!vno^S=g9L?{ywCU>+%3*o&;(+h3QxjJ?^|%PmRM=5ICi z1`oa4>mlmjPZzR1^txDHI7?l>o+tqYNWQLpReXYh%GJfK!8~}^Oa^t$OA5{Isk;*p zp8_GBpzjuhGp|W-=2aEWyzn_7J|)v5-o;b;V8M06qKjo!d;*F+1*ipKMEStU=wY`y zN&uXU;uBYVGO9;J9`8;IEH{{{r(e=#*Wi<5)W?8_1DsTQed?oVaJG%l$?@5?9+A?2 z2+i7>FI=uUR>9};7>&k?8FpUlN6>q2`IT`I8+G|OI3|E2L=1u?aev}S@F(`{KRKO$ z5pfIrx9}(GEkpBLqpAO=T!#K0)5AHHhy>!lMVv&}uFb9Uhb=;gBQmyrj%a+XVFae) zzeOy@KM@nVU5(f>Zmks|s5nBzd;Al@sW}Q$@!uk*=>VaLDaw2Fg-I{DnZ2&!VcEuz zw&sG0BZRH}Cj#mzUDU3i;t1h^{wLzr*3aoJvRhD4afFyl{)vEkGIh%CC4!10M8En^ z#6e7jc&PtGKxVBi01fv-`xhaI}Yj#Q}N#-0!EME zZJynNR)nD92ocxyPegVvvBvudDvrqRG5;b}c2Be-1Qkb!_%uBa-b=E3yHzSd#StO~ z?w^S45oJXPDvl6wcK<|Vk6J52P;rEa<@+Zh+cH=Yf{G(Vyx>0(+1AI}O9T~12uq|# z@W?YBlav0t`WwM2+$dna;@ z2U>73#H4Z_xVH;5NBr_rbE$ZHL%Ul?E$;0C%@HD^)uzV)sM!ZlUz`W-?E=jazap18 z58mF;?$!|{#so%lgox|4MPOfp7-3I{5k_CEr>|m6@U@SK9flk%h$`lB$m1an8F9CI z>%^Gg2oYgyi*-KBBcmbKnIlB6#%PYnj);eT#Uqz}fci9`IF;zt7;WW|9cOJr_yGd= zD2U3s+Y)WS5#mI^hByJ`1ImgJwTRJ(2edhl***)JPlniYP9Zl8YS$m) z+c}k}QH-|o&}9$s3zkJEqMXSmhxBWe+&IYLC>!wcOI zr~ez|0z89U04o)WRu^cF5IF*pv=R^xfqE98I70ZsF`6TOWpi*IuK@vktf#Ly>Rz+~ zNBlaQ;8_rJp#1xgH^Ivl`4NbR^)y3dMA$ME;z08ceTG{RBK{wvksi<<%YX;ZPzZk3X4{~KVLewHgbA-sDv1Pt22I@S3;#9(WhS3}$@^oxGx`ISJ!-i7{ z9~nk-gvjQx>G2%2wgc@s6}Oz+BZSc$A@YrEb;aw+9&(oum4?vP{U9&N7N5v7k-CFa zcOgHDQ;FVy(TE4^2YHsze9#wII8!#H_0SL~+3F>JPpju0({(MS(K@XX0>pu>E~8Rb->r7)T! zL@ueVJ*q$p_JX`rP9<6mqd7w4rT@xUUktggILDR$7WuUZ0rOysIhDw3=D$UTG)MeuL6qrj zMTl%`ju3I393di4;XVN15opW8)@6Dl9vb2S?ZI>Pc}_LxVnv9|bdJc@!-^1@x{&po zogrQ2Z&~piA#(LOk6$gwvzN2;oprhT9Fg4~)-2;+Er_z0t%&TrW-~{K>}Ag5*QmXA zq%ECwm3NDHjX& zAy`9<#=POZqG}1W;MWzVad3Ag)&rxrrj}(>`wx|~7V*>YLygD$$B2*YzW7=h#zxUWd{Cohq_3Jx0rWTsdO@pvrWD!y@I?!?HASLI6vh1ebR^ zK9#W~7r$0yr>YN=M`pbMgx8PCG}nxU%B4+ZDW<~O>JgPD)})2s6;}E=ds8egMq}QR zRB=`#I{&jVV%B*#isi*J5?}2&N=^)j3wFKGJp;5H%NX^@hR{KkV9yx^?OYBVnZqBjuE&d z=!xdqw9c&ZhA}_9=+vVDY~O{Ua^49~WQ>m49KGGt8t0OIO zHHcl#(MRrc;h`@62A`5j(uAny)Y!iwsnRD8#a}Q#ToRnC-Tgw|Py1~8@~JJowL6$? zOKBw^os}tL+1-PJSb}#ix#Kx5RlV_E)PC5X>3`I%L$SOVflHF4;ED$NbopFE`p618 zJutehV+cE0Ek=Ij!y}#Q(`Gb(W&mk+)sf;jA{<|&*JHkW5^31{(ULoE8}81jM(;s1X3r-v^1GS$WQ>lA4rMGjL|!>B1El&k zzX=`YR+c2ZcBVKI4A%lK32x;&|Hv@d$BR4(PNI9dhO)T@9vIs@Ka#N|QFW@Y)Dgk* z_zL%cM@dhO6!t7dqzOGJ=8h4#BnW%mRFd{T>Pc29k@VcYP}X)xhT^XaVcvfXs zw%<1{xWePePR*`MM?Ne}nk0DW5S7eT*}JC&fA3P)+- zQ*ueleLh7=+rOXmn$?9~x>K1M*MFxscfFIb?DwOquvO%u@nVg~Al2BUMoR3aRC51x zPhDLZw^v~u9^E%CRUgWF#QL(nB*A$ZSryigVhu45%v+M?ca!Lfubq~ zt2&(-_rox&a3zYVaHN|aF=LRs`Yt#R-S1dJr@3|_kmX$1jqdC8Q6AR}Zgm~f+0;Ao zD@fJtg`c{6iW5B*<3#b74c9BNGKuxn{y8P4*Sw)rM47NE2hDmEL$QXK3Zo%rV&+ED zFM1y-vaP*N4~*_{Er6AI-dtUmz}G%?R6Fb z%pJ?FM_ehjkmPlJNTNMsX!3{X5`G&byq;Ybz8(LnK(m>(_)qCW=&sjZ%c(Y(vL z7_hup^FJT@vJS4(&65duE~L0#;i_q6C3^8fiV1&-zT?Y0Jg1q@-p%{Bx_W6Ct90nm zlKyb|NU(;OA4Wr_-h!#5hMzZWUb}`)bBvy!<;SYLpK2by%Ne9vyEvHM2oEN$vnuQ3 z`cS=5GnkH_+?ZhQSav<)z}sDqhf)vDC3`h5kE z%r9e>dFVDCHCbu#iuCG{qiL^N^G%pLmR*lw&Kj~h(vKY;vCurQN&$w^ zyPtY9hn%y_YX=tu9_5!u(Q}KF$j5vxIz2GjcaINiTy23lZ{0$GSUmZ#(!Y8++8S~* ze*EUizV4W54)HF;q7If~`+u8k_6#rdH$Af481ed}3tf_YO2OQ*>=-Rcshca&>4(GV z{FMO)%pIfc9(b|qZj;SD-gBv*?P*P`$95z+3ce;dS{27~;*#Kvkw?9iL{Dexb~#$@ zKD#7))MkV^?7-3g6P!6-YVvfWyfgPL4ImN#~g8{ z^=Eo3&nJ4bV_j#Mw|sJ87=7t&DRy*qqWR+3!l1{M;SlQ_RFaf&K230(F4hT`1QGE! zZ<%&p(nx2oUTWz-OR@unE14CGt4@!_9-!aW7UqwqIgg6nJe4_%Qpv2K-YS+C*Mc6= z?ePb4(e*aj=Ur39@?tdRElGy3?)1){4P;HTiOS8vUhL`bBh1CtyE2T<{o0fH778%G z7~=*~MZNA#M-^CN2)&&~aNIPm1zZxW;d0I*b<|>{|DpkEd^>n0YeGlrxWJvg=?gL2 zCpywDkKLJGs>7v=(0Uj0kw(+&tC%~c!f1F0YephXIb|{Qi=U}XZ&Hely%}t-v(uen z^q>l!tW4vMbfUr|e%GJqLkEO5ix@I6jo>&-tP?H?Zh_i*jMNLeX&UX_Qys2(vSD-2 z8|z+n)#-IwR6MQUI>^xP;zNR?yfHd#ektabOOgX~ z^15<~txelk+o`lDo?FE}JuJy(S1(pmE+&tA!)Jrs#VXU}-wr8VZNakS-teTKI+zw7*oI8IxS*xbA`of1Kg0H0$tUF&iBY1kf+Wd1_6|cPU{sZd-@3EYYqUCoa zljw?tDCUmW)HrWSl8g^Olbi8PsPpqB1arq|yt9y`u=dZ>TY!~|Qx2K1R2YqSFYwCP zUpdvMtHWuns`nL)z`G*6zk<3-t4^PF>q|oRmDcUm&nqWyV8t*2-UbXd9z2NP>CS<6B5qOu1_q#A^zXj5}zt5E-2wX#ED1*A-96kL9WAS`+{@Bh zYewq)3|Mwt63hl(p)~!}cf91;yO4?0UqWAXRAx zqbhZoH^u%7jK&@vI6q(Et+sz!mJYgjiC_fw6k(qeWK_k6(rE+jNb&uZbsjG)3Dya+ z$rGoNiRX?J<#`94Hwq*493n@y zc3cvyUhN|2>(g%xLtHCR>}kY)SnU0jq}#98k+T=Kk-RrM>b!$kc0Ho#86V|BlQ$&c zT%68liDk!LRmeE>Ev|Mc@P>RnR2c2 zfri@<`!u9YoC_20yDk)a`|()_K7o*=`1?P|BDp+CTpFwM&|}&42q~--$%-vU^0ytP zI|ab9E=wVt{&FDyGgX@YghtzzWWyadx!xNQ@kZDF18 zDG=1|?k2R>nbM^DEoa@?9hL;2O~LJZe}vLaP3s#1Od+~cGK|ol-9-&9L`|*7n__-6 z(VfI$+3{H++}F3}47m!oSzSETh2qmme0GOVrRoe?D(`7-ifQ>LYqEGRzCk#hvM^P ztP?(0g|`~lwV;hwl_z=nIOtBpu_Rb0@N(8~M7M--{zt~;s52>ofeoXMyLw}t*W z!dn*yfMv(0?{JUTUAUbxZHeOYs4T_j{a7b_G7cUuyH?bc?oTE)vDfK=&**W~0=y*z zZ_$m2C~F&gmVEu55S;iXC1^&Gmm3@kg&oQ6GTVn@1ZXZ3W)VQ&cLj%CNOCgAIX6SfAY z!j&$At`W=~qj5Y7L@qnGqqTPIR1B;35FCYq(Ku!XJYF?p>BjoS$ix$N6m!S28|i^aic9Qy-zy`=P|S-WZ~YVO~3@jh5~9A5+{4YPVuFVB6--0fim zM>OFGA-x{+65G+z2W}e@BR&!wXN5g1*b^d2Ynt|_rM>f;yxwfm#YSP-^@u;aL5#uX zDCO(7f&@oUVcD_o1kMK+_N1NOpH`Oa>=}lm+i=7dE(vZB7`L9(&-d9h-KC#8X@-Zf&hByFj8Te*@sfwVl{R)@g# zqu)Cl0v*+!x3`lyVUfC18O#IohRov366*Ty&&i;(zAEO9bJ{lQghKH!y1F2 zdcEnZ?i3lXmf^P0z_#kcg*o6>J=le1*Dgnh-@K;r87st7Z?C7`xK@OI8Rw?pFZjGx zpm|9URs1GUb=>!i>`N#>g}f<;vShs8#cM`5E3zx6o@;ZG^qlOcL*R1pX+NxxTZXBB zKF&e=m48L>7t90mmZb2Og_V=%j~kx5kD#K*?Hm3;##DG!3olMBzNO?Sw1<>~J3#Rl zyiUX=Nzz$kWhJ<#BPo7z7{ye0MW#pG+~`Pibef}#cdk!`WjK2Nm5kR6c;1DVVk_Ju zeeVxcmTZgDA#k~PH3+XYCpRLw;Wgy-J%;PniFkd5c|$Dc`QxOKN|k{#x>8JqrP3n; zYImmT`5r6AYWofN3%2dp=7TL6SdMnPnx+I)^w;TuR~&fO2HXCT(J!;FC}A(Z6Z{3w ziI_LUQ*UTVJFa@DSOzcG&74>&J)*1+rJH)CE3fY6Q{}Ut<+R+rAuHWp7we2IDnyv3 z#?aFBpDE{aOj0lc&kWd;4kr!G+tdErKPmOoIv6kl*AJdc;JkKcI~q~sgCdX1G~q9p z2QCTx4BeX02^XFzZHlMreELFLKKtkqNdZmi(tJ;pB1Kbmvood=Xx>95DIHoc$F($N zR0V(CdKb5#9x-vC6WP`~$u!)5q;BVh`z!9paNp9|!fK&5JIN*|gKqDP$0HuWl62`~ zv})M(fy^-N&_&i@D}n6_>}v})R~Oa%Mq(2u>Ebf5wG#+#A0=sTIalTB=Oc#7MMvm7 z!a@>0mk2%hj0&FZQg?{&)KSXCU2!^}KBf|N#oGoVGmG`7ufiXg#&lS%>sOcx;>}pf z?K$Qep&T)Ik2_VWnG74}Me9}on8%k8N46~>-TY?-F4d3Znud8*&ylEOJ#_Oq)}vU5 z!fa9br{>)r{6ukz&rPM>(@J#kf}*;45ZBMeoWU$pjX_3YcO#U5L6HJB2hsVIrGM&cX zN#T+Gbtgp8R&sIr<6K?^e-Y*KR$KN+V$nWJ%+nk4SR9X~-gGSZ;NJb%u3#!5J8!i~ zUXHA!x5YgAByW$E-%gP!rJK{FS|=1tCF+N_T6B^N%hU3iIV+RLmw2+;#IEN6x~KhE z1yhMO;H?(7peQ?9%ii)PiMQag%twZhcB8BNHFMOseOWADxni^HKBQqURi($gSzs7y7IHzK`@o5H{NQZ zb{}=(QIn;|N6~kzIBkC>FTqr}ZEi<@l{3AjWw&4gv|v?eLHBcc3I2l1#U()u3rLj$ zQUysn2&TfaV`(935?XK`XuhP@34*C`{oopb*#KJbJ=E^a_G1aA!fk+SUDtxim`eQS z?JN+sQTqm3@E!12-EORcsRTdXmxNR{%PeIu4%9XE86QA+?B#t+hFaCm z5l@&6FqP1Wx0=x0Hml{`>rQXUCW9NyIG9S*8*epHyS7>FI9O48u%gF1uGU#N+&0*v zO492eKgg|JanwbASmoN}ysT-h)7H_6+aLEHNjeUQM}Wv%yLJ`)1@}r^68M%RiCzFi zTI#Mnmn$j@fdhG)vmo8Qwg28 z9n>S<0OBSf3d;|7V=7Ts+z#pyc|ea#fEYaH_8v@yN7R2JLNS#<^HHluO#NDq63ZAR z$Lf5vLaZlyePXjQf0~=N`<550=j<=%-cmsOk=u*49#LHW!>OPKd$sc|Xx@l%itqeS z1XIl!26wARl#|Pp_&Z|jlA&~Tjq=KZut3rwmpAh)TVD2$E~w*ydBfW0dlL188_e2| zsh|vf;RSD^R*(Z<6x1-f{0UF??9>+HiAnrj%WiUex*%$-p>wBC3cd>--|~)20$;`t z7ux52NoC@dXzJkP$qWxB8P_y&*RUkp=a*#dT5mRb1-b!`CTBX*cc*hG#?UN+xnl$_ z3Ht7=(e$g<+f<|EjqsXhJXzs#TaA|n7SS+z{S;4jVa;UY7QZ6ENYyf<3dU@wtA9LJLjh95#_tIq5fNrrrRCKNwK_`2j&fDce_W^SMvkXcbB7v zISV{li(ONUt|f|U7@e<)Co8zWuR6X2*ZkmS9Wc`>HESxoc}2OR^fN zG3M#F3Ttbc!aD?^EzMU>76z%lgybO=?v5j4?j}aLrGuvDimvo z5x69XhnqKq?sX_bF7J*aSPzVD+Orh9bHAmz`*>H7s&MTDI(Np(h&h)JD_C2Mo&gcx zyK2Un8|>h1UfI-KndbEeF+J=^L-Lhm+s3ppm%Lb5Tb#?2O;|C}ye_Ycwy#Dhc7Nj- z^Y#2Lfbc){jzm9jrd~AyDdvu4*CU+Ucc!6nS4gj@+5~gQ=qjDO*yhAB=G{j)kIUY@ z=)rlX46i>OQt&=+HN_S7jsv&Pk-^^*%Km^(&q zYUjgtl$&jixm5t9y56oi?Rcp_={wm@#jix*7ZGqta68NZXLaYW2zv0wNfLb2o29S# z&HUt?vt}CV!|KM&HcyzGPp1?3mUizj{gz`iwan}ofw^PZF&c6Ka%Ymcrp7ehq$(j* zeOcS_3(XT371S{L%w%8oOr2$}+&(|(QLS1n+Gg1(GJ0_logNr{JjsvkE3weL?gdAr z{~4$rd0m;Nbc!LEJJxB-Jzo}HVTRd{IRWB$ysw%SM`=cE1i@b>?)PKof+m_*W;p3; z0baW)m8>*q-;Yi{(qF;yVtyD6CvjsJlF3PoJ`Z7wzdnLr55Xl#(mJOAHTFjsZJYYTbhTwU*7R~IhSB~zby(T~3w)ng~huwlN_&6y6)8b&YrXS0zy@MZ!OjdmjrP#M;fT%VY%t$d$SeH9qW|SKY)E+GSd*y z?W;wSHjVdE?TqktU+517e+jr0#A>vjO|$NNwBVB9U9#R5rQeKV5T_QRVtFwYMuV60 zLIkP*?I{^vqn*0cz5@GpsDU}qOD%r3)t?==lA+k+?+UNIR zHZVDvmizS4g5UqZ?}9+2EUQ9Gw6PLKI%tB*md+#f0_#n&Aplec$MvAh`l(Iu4CyK~6cAu0E-hfcjpQ!{(`l|CBbQ5aI*67{&?cNx{q38LMU^c_{I2q`vVJ>eeMv@yv9Xi z{#+uOPDQRld=<YM)$q<0ns6UaV2n>LTdJ5lMqm6bludnIUiLbj0f;5>(X`$%S8^%TRXy)il}#yC zL9S3V!-C&t!S`XqUEVwE(uGf4NuSCdD*l4`;gVpNI^dGQtuHkliXEk5d9k)rONOvo zw`kOAijC!hjeFoqD4m&Snb2@2j1#)Lf9uo!{l5qUVu~$R#&AbcCA!KclJ^-6|NsW zV$9>(G}^^mIpSPG#TsHX<_$Oe4Q)cR>dp=C;9pp$IYyf;6HUQq^^rvZ}~h<+)o~Hl8KQ?$hlwED4+D z&-%tB$#Q?rqhC@N`oxPU-}9YSFn5f=CBb`;J37&tme_Rp*mLFKT7UK}d9>{D`LhM1 zGmDmG?t2EwSC81i`l>^d7`pm_FS)%khl*ck!ml>rlHjfvm)`W{&OJ)Nz??cg9(*su zt~?tcH*098b=X*%1!Q)Y+kVdpJPtkYP8+3OR9vRTnDCcj@HWTchH>(dbGbFW9^dEm zr=yR?Dt;jg*8(m{l6>cNBC{VkskH_)qS)hwCAojnhe^o|W#{LPz$4nH z7hRzpR@D270aGn_@5{P)w3VH@=hpOy0fyn!w|k_rtVOB`%Zt&NH@pS0cp%NY-N!W6 zWvODx@5e|$2l?~7JQ_x0e;Gs$^y)yvOCB)f%X+Qzs^K>+@LLzqch7gA-govIax8hJ z;4he;-m4a$(1ETjbHMQFp`Hi!!(o1Ku9mYc9X9H_A^hui9S__#m>)QGR}G`XGw+xz zry>=sA(ljsn2={69c^Bql(u9Ta4ljqt~Yq)7~XyD5Or0FdUAo_mcm|6ToRlrR%lDV z_L9iH8sBw25lez~f|)b2FFpVJR?~@7+ZD_mBlJD7ly`r6{qS6+*26#r_Y922Js;jH zD$R`H-`9L>n zF#?w)N!v&l>X@9OR33X!XG^f`*mi+e&D@&4&6laP_nM|)Yl*E7wi1x-G!Sm(+UP^% zGJ4yNCBfDXdSa0_H0Rnw>Bs8WtC%}R=xuw;R;_4S@21M{&XS6)Ge+aN1Y$q#*QfUn zYl>6qD+SM9SSMT(#1y@0L3hG~Ayw(5_*F{L?p`WhO<^K(rjEL` z4}L2LuY=&lkVUm=wXOk%auvLF>k=%x9^v~cnC>aK%T#=KsBZ0pWyk9|u+#y?Xk?!@ z%GF!7RJ=mMYahI3gxuG{&1htY08-q~Nw-eKdf-(p+$VE1oYrPb4BMVm)U8Fa?0D@9 zw|HDFN$WRAO}86fSGV59vg7qN>?U5nBU}D>W$JjWor+h*Sa!UI2VY-m6B_%dG--a% zS+{P-vg2KbB(-lCNJ~t6WoYXerrR4}+3{Wkd>QNPsd8bGfz)lS+kar$@qP#5OF}o3 z$GOhen9;AlZs&z}EP6eP#zfHxAw@{;i^X*NLHwc;-W!5cFFdII>C)t5!zkTe4a=@a zeEYhKl-XF07@zgh?I5x2c#jKv&fW_R#;PUB2zi8x_nCMvWP zyM~Hxdq~s;y-x)EFRsdUzjl&xD;=T*br zNbF&Q`!YUnCw~+tnYp?M9bBL3yqp-J_r0FZNLD&c zi>8m7I;q$fie<;XUhq?&h*bMb^q~*OY&?Md#y5TZ*pYS?oNcfGu?M)yBy zO`>}E>wMu@66_s@RmR%Qq{|5dEndn^#oRGM?+ZV;t(MZb?Eu=T%{T>1h0)meE=eO! zmr;{m8|aOr-nvr&tOqVhlJYx7(yl(k$ob+$bb4S9JwAJZGsvn>NUOOGY0vtq?%V*& zj!!ngQfrB(t>Z`2fDsKN@aY1U9iN`SxpPKg)%{Ub8eHZi!6z~JYzm)+z)Ge~a~iq1 zKdC;?PQ__ zQWeY{%Z|@j!E3O#9UVL=lN@pEKrnZV#wW3obZgNc#Ng;cgQ{1dSQ3oJr@gTMXi-SH z((@H@cWbXh;8SFL9u4dEdVT4^OSuhBW%nqUJC+@vc|+`A?tawUH;UY!TH zCCN0-iFS*gMy5}$uRGPpXngt(>#K6BOx|hEdn2MGuxujw6^mmR*lHY7C&|3Y9W1|K_{a<49Jz}ztc zmn2EVr479t^wHG)w4{qj!Dt*a1NXf)&Ov7v3R2RtT2UOOgJW25bc!SuzuSd+RjX=v z5R{?weqc#(lnq$81Ec8PH>XUSoM#@u+%W?C93-j6r1o_3$WBVx=<|-Yp)YI+m z@D52YRq&BRWM2L-rB3edx_uOuN{`spdbtu4KZ=a~>sO{8#I#%R3K_4Q;S`|W4a4V6 z5vIMhM*WQJ=LoDV-ZMy2nY`tcDQ_Lf*P6q1y9vxgM1S&<;N7JHRDCoxANAU0QbZ&v z#O7P@IuWlQAr9bFDYf~*!=%4oz|ZUfj=-yBjFzN7E}c;B&KyDhSkp;|z}jLooFa!+ zQ{&vqP_G{2h=_=V90LnpE#X)SxZ9A#szoBcliQVzKQj(F0?V#nCsOam>HvuCvmbxN zfWKfKm^XN~i+xct{#s1xr!@JQp#V|0y4Wae=fQ`(wV--?gho<^hwBh{m7$-V*)}g# zh8wy1ZSeY;HvzH08eWTFG@ORdi&As{^@_~hdG2RjaRja({faDYb~W{0{%2&>g=?Qp*J7Y+5{gtT)@x~fP;Q3LKT-{~m z;Ob_??${vR%!y|l(RX=Ca3*~26j?AmKsj#i`ZN0sB9t|3+p&FwJ52w$Ltf?{p|pT# zSur{}0+)+tJ4te!F_g0yKYw0%?8-(jCn%_=+|hP=h`*JvE)^PsjyUf zMC9o9bbO!B%FZG?Be1;K&g&7AuQ}6esY?`Rk2<=!7R!!xf_ITGxEfyOnUucc)M#Ct zC2j-UHt_D!o<+)!)wPIU<-WT3MBJBfACsh9S{rp-qny?#Z#*V&e-*#E#Q=L1>aR{> zM@gyae!9IgrV>23<%3)P9bA-rEzTI`xsK3zKQNWh!)AByzRn<7+Y*)9sc}006{Zq( z#b-On41-xM5@t0onAPySjb}AI;y<#_G)yI;{2_+|c&vlGi6P-8!%&oc#<^puM2-Mt zM*w2Q$eM;w$eZYdvd_4NSaXqw067$Z7za5GEg+{M8D*dGTEw+0avdOt0ucX}ea2f# zAh?YZ2*{xT%is+>rUQ?zDEo|438}cf5>i191t9($2ia$kH&FueKQNWhoLd~BIpk0P z;xW`!6UaWRgtE^#m8e~AS48bX4h10oE&Gg9;ZcNgC;;&v*=Ik?<*g=S_8~6->Z&;8 z<0L{pPFZQk&)f`7C1mHVhO!C(F%xo^MncYyin7l*m8c)yYAAC75b=<^#52Q|qwF(I zCE9?u8p@6U#J^>qaVmk}ttJqV#{`;>hukHe;Wij$pK&T76>l{m7347i;tu345zu2S z%0A;%LUZ0~LUYJt0)zqTswmV|DU^N2sc@@_+J%e=K>SVrr~li zKd@II)f|xO`;YBEv(GqpEIZZ-avGooSAym-DEo|Si0cQ}8>EXs3-ZjcZz%hW*CK8M z+%~!v{F!~mTS_1xSLSDH+D7d%XhELgb^v9caVjAdRGpbUDPLD^@VN@xzb zGP-^Y^ZCDIpK&TtyL?QD+O=7@f6G4ORJhe}YyM~UnXZ@MF%R!Sf@OG7)nu51vd?%g z!L5ev3dF;u)HI9*E7|~MpYfiETMb(!sH@z;11cJAkK-lKN zmcXMcSkVzE`;1cwsrZ-|QrYIg#Hlq6l^}=r(a~SoXPioC&h3iO+%^y9g6y*l$UZBE zvd=gbZZ%Q6wt4X1vd?(i;#R{J^*^)EevU!j{ zerBKXzKh3)9`SG4XMB7J1Rq^`MBZN+Za=fnIF*o!k6=B5>ye#B_cQy9QweRkmCz&p zE&Gg9i4nyuksk4H*=L*zkEs7d;Ow)XJa~KP5fGuM@+>{upXHGF1$mo?>O5*JJ9ewj z_;3G~CuQmo2EP#^S^vdy$Y?3RTDy5z5x+|MI|5S`Zd92ScfKd{lKvZksm`R;VJRn4 z{tpDEdNRKWd+@ob@jrP0W6L2-b*N55HoR*|m|y=zs$`p-mP42-B`0AgF75n35SZ%p zS#S2_W-jRA|BDBv+IHuIY<}SXe;_cGW$9x1q_O7zfxuKvXI?bA$29(TgiUdf7gND+ z^Zys(Cl&Cs{HIhud0;Bg$?~6?|3qLas5k9DYxgGtQ$gEk|Ji~+5ts_vU;EEq@)Lon zppR+)Up?_B74&26fA)6ZV>yJWV615Wb3|DYmxDdq+_m3fu0So(|m5g z`0sU(>dS7EYqJCOJq~Fu;qufnRe|3nKrANd!~`!*VJiOn;HV?=kL4j&M5W+8a^cf{ zfVc&SuTk!F%Jqg;grMSxZH=AT>RxVEL_oU4j=J+(Bd!CYkzFLs`^CqK5L6uTzF;Lb zW7AEUOEvzuC)+&f1X#OAfY=e!jTSp_onR{dyX$MlzP24{MQAsInOkD_Y{b!wR@6gs zR5{h$A=O#?Y1=IP_nMa_+4~JSG|uDJqk^n}`Vwr{L*S9<5J(+6)vzK26-NyE@Je>M zT-u75Quww!&95lbB}dGS{Xm}O>tIC)DvsFt=K@)qN34j*K~v;9Hv$0h8W7c5jUuPl z4Y48w6-P`Of5w>6roI)?WoEju_uLwQcm)V(v}FHnqpb)*m5neXgxQ9;YvZ8^9)Pe? zWlLp2Qdw+LW$U2`JwPfe6-R(h7Nohwruh@#0d=K{x)M|z0rjS#+SP2e`vMTq9;#>$ zLB$c!HX3gm-X1>w<+bI0E1^AZ0%Cdjf$A;$bt|1Ipts@lB|O>0?Ao-j5T5Ltk@HYA<6=jdZa2r7;c_Jbqx%-bO= zDc*qC35flJ-Dy(MMplHN;s{|sIHFDSZ?a2k{&MdnK*)wjx}k!v6(OiNLf8+Ec(JrN zn>pqPScdU{@L17}HvV>no$CyUselL@m_%>irdEWY;t1$VjQ1su z*#D{;^YgC`{VE+0n}(03B^D%`Fctp|{gv_l$`Qq#LfI!@C+NG20I@i6Ahi!&u3#$u z8^#3VV}c{%50zm>-z){hd_W}m#L%Pujw+_&zlBxfi0V1=vyJbcWb@b`9!SlLYgiG2 ziX((ofydOfA4svL9jpjJ#Sy})am4%`6Xoe`D*z(jw$SvHwWCP+ z*F&rbLB$cms&T}UQ)$Md*Q)};1rX55l0SbPZAA#GY=qUSWh2Zsgc+m)9*W=r2rE^# zR935&EtSP4)m)n%iqHe3vQlvb=w!8O908hJY?_Y)1k{x(>Pk>?1k{_=s&NF=u4b#< zNq~U%P(^zPDvl6VjU%81HCqcF1O&9XD%xC7afGmH909#Vv-J|*6QN(JqF)Irju2Lj zBcLa0ww^cz5YTs3(RT$EM?gQeS~ZS<-mckt`(;4D_)x|85L6riBg$&kI08nLW*bqP z00CoA6=P6PaRiJcXu!L-H%vWPa?%KM^gMH zyIiYPtG;aIp*g#Za^F?qfGCxAKZ0~mC$(SnwjzY>;|O8ZIAZs@19D@FKOpP@QMso( zt(Cix6(OiNLRdA9*tW!;Ev}jm5Ke%&Suv6p^z^kN1QkaJtHu$1XZo@~eme*D>OJUj zVQM#OcygU!D*jtoHIAqm5yrX==nDu7AfnqP(Z^?~6(OiNLRdA9nA<{T@0T&7Bx!)? z)@3wZI5pXXsrYYU)i@$gUBdDN7Xs^(28cEt2GYxAmn)cx{}xt_Bev8DWOg6cW+O%y zjG^s39aT)le+#R|5jU9|oBaL*Aoc?f-%5crd}<9VLQrvpuxcDp07+K~;=FLB$cms&NF2TFo|UIReJHD#p2>;s{~YI07t# z#bz1)0zJT%D8iNqDvl6VjU&MNSZvnkDImaJDZ*X}Dvsd&jaxO2;J^Frlfjl8n0tWl zCZu66M~U6U&%J@zS?qBA&Fny$)A6}FL*HGxevN7GkuQdAbfiF7cPX4|d&^8?u@~(% zJtBGA0aMtbk;<88gT)@_=WasmML6OnjkQ!uYzsWbZ(Lz|9`xAMdfrbSR;f5ugRl3@ z>k@1{ej#=xJu{i=6jT?+H_`F99q+95did7z`B`PH-ECKGM8Y@A!IPDM$Dhh!Q}DZ- zYUKA=9in#CvzAQxrseGdgLbF+cT433evOI1I5y=BC+ zCR(&xl4ZgC)0WZqA^{O|HqG?s(@%%{GJoW&Oxz9c+&cFkgi}ld+*an&x2hE#-=2$~qS9(Om zV|&HlgQ%B6%ULxSySw7&j9S}~9$JsOg|sqvqO{jJeYBj_(Wu`c2H`UUB$N`8NfLIC${H1D0d2QU=JX+(9zSg=DB|+xPi=Cz~J1eP8 z(`u-g3QL7~L-bC-0h4NMrA}U)$10WBXL2gB|EwJut7VM{({@)q3iC(8Uuh<}bSt&i zX&XXNbu7?WySc(&OLF~WQL8l5#_bBwf}Huy6q^9i01%Y{fxqB#F+YgQXffTisZ^xe zrGt-ED!~KSDCP&FcFbv0mT`dkJz<%3CoFcqyj-D^TcbEF_k~*8)%w#xs*dHRn(BTY ztnLgNqu?(~mc?n&8yaX8oBLWlA)+LRdwn<7WIv;aI@9r-ZnvGfueEmYafIe@afhYM z<2G8Q2}bQviB-U(4j?2ztOo@Cg85+yq0N`AGWCcYr4|X=rrVzn+7hS5IyThWM&-8{ zU$xb~`8Ls(WR~`awa-VhX;+(3>e*b$Cj5n$i}&ik^cVt~Q_%biXwIp`m$Iwlw7$io zwMPjhESMj>w&{P~bliWq+CP(6eE@hzFL+$r5vP4y6RmCbDk4K<=Hua}1kb^0)mD=U z{?ZV5tT8vxDm?L(Id4%Ctd=GXG}Rn2O6~4{z<_1<4~f$nylAA|d)3&8OM(pPpo6B3 zpNn*yr#| zs*4YXn_@waGoS~SHzp`fvyZ5)9le((o)klK$aGKOy3p^2|y@}5N&7G&`QI@APR`*UXNb#4W9?i7*8v`_l(8pG( z1aIi=fY=O(6@b80SSlI1JW?yrK`Ozpd+%IYT;Lj&%6)d2Ah5XpeRUxH7Zvs_+x)ABst zVC5l7f_wVy_LKW< z&Jj~OTKey7W34Mu66DvWFh`pQ(-I>0jFZ4dDiQB$Rk;atA$lOJN>D56llW=!|RB!4`lJ7*K4uNIgv(v|N zq;85F(5)390@8Py$}yFc>zP3D7tDi83vF)Y4R1TGIBH5b?n%egs$=B=eaU))kw0HS zt@_4K@`lVn=2N$dwt*I6y?61xd#3MFQ*1^qI;~l(4uNIIXvhj|n)0O_#a}Rw?D1&j4L4J)bXWG2>_XF5UK6(6dP>5nz&cycSjP5C z(b|1Cu#B54L8=wy;`cwfHHdy(KZD>e1y7FGQekYY3{Doanzbb8SN@w#_YynM)G=?Y zJVd#6?)|h{M?+ZAoaf~!uLfze-c@BA0yN+euyVYqSHqUHM4r4>%>@G24@Sefz1(Kg zIpFaLc;K=IA4<{=de&gU3A@FNW7P?I>VQ|K&*kH3Sz`vlR9Gim3$VVL({=wH(7fh` z8M?Z9@^!rS@g-vmhK`h9IZx4=$JJqB-Hf0|r4o}&hC8F^mNyd(Ru5G6xl`%!)3v^S z_1W6|hm3Q}%+ShSuFob0M;qZz@@vs1DRl_7PaCQ8A#+J!Mz+@ILil~US`&=1EO7H+jll?=rx+29a7wczig6bXb(5nXBXoam^oUM z1W_+nn)6%(nt#(}6Q&9sJYB2kTA#f>dhBnAkbt@-hjOE-vD!Fm?Fvb7jbh%=OVVnZ zA}SB021lFsTzJf}Bpwx~Y9HrEvF9!x7O)H*QcREY4yQNHHc{}G7FS_S9Tvr+Z+eOI zD68)s#s?i^Dpa!%b?%v_@KzHiie(cgYF#JSVz(0eTCz5c(cU$sEYo=b@c43Nqf%gL zSDI_ZEFA*#SUqBj_ULLIR^UfDKpeTcQF*bXD}BCvmh%7ldh58VmhXLh+g?Sn0I?H0 z5Clce-kf6rCU(cQ8(UEjyRTi?7}xHWJ=?wQyym?Y7It^XcMUL}XL$cUKmIx|_B^v@ zX02Ik&6+hc_yuVoZSnw)Wn#zQ(~D{Q=o}=qidGYedz-@+jIb`I4{!{R-(?zkDnoZvB1P$8nv!4XlaQ=l8DbL;5$<+E5%0OQn0(gQ6W3 z9nmrIDG+z>kJg9oX|8Dxey^hvTZL_}St8PEb0@%&<@r`>mFu8E?DU2 z=R|&p9o{rvXU(aHPuMr^a9Fuw*O_Ct?6jv@7D6<#B+S#@e|=DwA8aonu->hdgSVjE zcl+nfJeEWjD!M~j-sMm>tME%i{CPh_NqaVj|iC2}Ts*1|7B zG{_&v_Rr{(h!C+bMDq*?XJ*7VLi8%{ZhYBQKM^6~Z5$!c9O2BqxJ`)2TQ!Vo@kJ65 zBBsX?0?iT53=faTQMS_+x*1F7TvK@|5jW(&1)3wAStRd?Mz^mKM)YVc5g}reh~@}q zrb=3(@$gra5!E7E=cPpalm8ZIj&SD8xDaB+FNy&?UdnhW5o1L(M>sQX@^Hj~=Eki@ z84X@a#BmYL5zefh0)!a%sJ!7}r(5d?A!5ad<_KrzP)Cp z!kL{^h!Ay3N3nDfLlY4cB~OfbbA&*1g!wy9>I01~_dmZxj}nN)xH?A&G)Fjdu{eTg zsDg%w-6tcGqw<)^RV1k&s_2KqA@(^qLZCUqne~>JBYq9g1kc4@3P%VuM>sRsopgF>sy_cR4 zB)giBU9l&`5dzH-&J4lVG`eRhbkmk4&kwQh#1R6`5zZ_`KBH(3YGMwGy)BLqXpV4Z zIzAv8G|x3L&&B>3M+h`W(5y|)x#X=PU7`wIBKGJwLZCSUayhA0q_0$=ueglyC^<(6 zG)FiytG*D8`GoK#4JUtbYBi1)HPPyh5Y4Dn`$)sd)SdOp^tcx7Pd)!Y8jd5JJ#@BR z?$aGY44}~sCJo0C&QWxtIl?(^Tz1bB2PY5*Il{>)Cz>Oiy!l8px{{R4B@M?BPHAwW zIl{^RbVP$oVqem59O0BWCz>OiGR9?>OZz+0a2(;3YA2c_oN}BvKWIkXBn`(A&Y9yx zbA)rQyvr*Kj$@e^l#{hT{m*OTV*91)3wAbDnFs+@yW} zAPvV6m@g{O93ixlqVUn>GV_@g_HWh zL_eGw*{N%jTa~<{$fbnF$`E7a)cQ_+&Jn^&(9S3!xWy6ta9S3p&EN=OiRe8@jv%Wh zcGdT?iV}DG zga@c7&kn8BPk!C1`c3a=pkIq<^fDDC_rLS?&(*SM1Gh9W&_72{mLr@#^_5l=^>q}l ze0R~qz%>VYOt<|#9TCEVR)o@LQD+`VgYdAWc*{ZJ2KGXXKUl%f5pJ6G! zniMNbx~C|prrv#ggywUrF2l7ft|oE)$#0aat?w*7LYuT!Q*kZJONliu|1I*%6s1Jt zC2V4e-rC-${Z))WU_5}gP(%=DCH!~S{Vge$aec#IDn@QFmXQLncbs1J-x^w%e~V}s zhvB6}e1`uPaV~|eH`3_!hIZ$ zaPIt=v>#QI_M`NY2W+^nhWk+*A@;xMwrSc|t3>;1oxH~|+(pEFHI5MbZSkzpzRTi9@p5P3j~vX^MIqMV}tD31(F@!!Hv z;0Tdxl$3cEO?gXgDSm~e_;2BhaD>QbO3EWER<1%~ZWNZ{zlFcU5h7c@qudhbH(TN^ykn)j2|B1tv)e@mv!;7o|8ttOqzkWF98*gXBsRawSS} zgjjQMgvf5B`>Cl_B)giBT~Uf7#JYwfL~bPA#!md8`JsvVAxd$CSUYiq$kJ4l z%t29#BgFcQBSem;qGV5+=bD)3q7+AnbuCATJW@sBd1RzZRG~{mDUJ~9T8#WKq%$b2GUso{E}R6Vg_!aCzG6WOJ`*W@tpE^bJAG= zEX99|OgD}YdA)RhA|ZBDj&LNM1;A4Lx6o=FA##W5ToECvQy%gvItzfM_-~=rI6~wn zC!Gawr(EX_bQSNpzerRHTh*BIO zv>HcLo+RL2 zpEJLNpPZaQXRr)9If1{auQ4N-$JW#gmZ1cPoLGJvt(K6 z8b>%+6K@HTw|Nvh zN9Q@Q6#p%>8b>(S1{}eqjGyPkQpvv)wOTSFG0&RrTu!2)3L1DmN}R4rZdKxm)1-5d z)DKnkLzLn)gjVASXM}~HgQT(2#8`<^93iwCM>r!a{5&V|LlgWEr8q)pHI8sbSh$ps zBx*tug_hw6p+7i6#2k|PLDH@XX&0q9Lg){Ua7HFB6AhYCnwU|d6h{dC!4b~L#9czr ztX0LV6{R>roLA%sXJq0mAxJZ*LNka`93k`vNATZCk%=x}8ye@b9}V0Tm(w_UbBr~z zMvx=8>H@P|?-ACSu%tbDj7%wt@!iL$dE+1TqUB$z0$UyMnmnyuVqOoHLbReROVh@fmg%Qj ztk-wjnab0xF#o!V*-ePXSSH<)Mu_q*Kh@m5zuT}BX6(p_tAsHA_^D1M8u$hCmXJ2J zs!&_w-=@FR4E^RvIYmeVY13_1EgKo@@4Qvp9A2qnT}T6Srs&43y@QR;T{j#!w_%2Q z<>*wa?_Z&ghE22Eu@uH(6{Q#5+PY|AxccJ6PAOx{ermGSv_^1Z?ikiYdlS^Ey!YO! z6{%HN7sh%KO}8{(9cH-pI9KhzM&VM97uJjYqxJb5o6+Lob@j=Cv>MihG%z|$cP@Lj zF+#3hXOG-wsQ9IG>Is(qu)1S#`_Xo+iOzo<4KvQ4d(GY&f2&REjkdI*YGPI)A}|_F z5qfIX#79Z3!Y`Pmhc(gqe0~$-{<#;d(uAc_s}PO!Nc)~BZH)0fsvZk0s$pG712Y5( zajLX&v)oa22O;pwB+90`(laUB5No2mrR@ccptk$eO7p!nEQM&yTOP$JHTLimb_J??Vmk$yIis*&Qhd5)nvSQGU#?WBl^Fz(&-4z|elY z`#9LjSH|D5eUz0VE9_iML8E@yKDFLvZz(GbEe_U1X_g&o8=Z6g%N}-q#W0TyX<)V( z?XfKLv+ddNNI&8kWwhPyYL9psrk$A9!Q#JL+-qi@$kIxRs#4AeA!ZZeXfgszVdPfC zVJVi;C#P1azl}AzQO6jueVe`C=$fWquVCxb!t{=-jlIkl$4gq7mOi!5sW9E#JC)zb z@%XRwTF~Q3%*&{6;Fr{Y9kaJsx4^tPwTgu`(XH9j%4lo;8PB}0c^g=7-9OShIvHcl ztQ87bbBd;Od=DCD)_7ltXt+)MEWNo6cdidY!m&Fs=Usbvr_ytE-?uX~iU8U&k9$|A6oU~gqg8PUFt{PwJ&VbpC1eGrISJ!l}8$g zrkK>p4f@YtTbOHXKLhLHXmN@TYog5l20LtT>ZQ_KJxrn@&O0u-)iG#yrnL4S**aRI z+ql~4Ew!MhN7_-V>YQ(+*H^#U2JeqFuvE$&0q4%>XhP)FzS#y4f|n9s_;0b7iZxMQ z-(@e=_2LEFO}`P+{J@rE9ID!l-K~O(OlV83`s>IZwRlNC_Q~ui@gx4s61yHY*0@xx zu~m8NHv7j>`46QlRi6+(MdqpV{)^Y$8V{5ZI3K%wA7dXL(oFjv)tnHS%1%~4);*%X z?m5`NFGvGrjBdww$*H~lGLfC}uO-b7ls+T1;&}BvwYh9ZMWW#~;I?|uJstCYCQJLJ z>D%oU#}z(Q^-VpidRk^LnydAp3vEIP5fyb<&GIb+^Y-c~%@6D?qUqg?t8dhScQUbj z@7ozzSMds`>`PWnKIA^GR*HE({z_JDTt#m-+@=_Rvo6*bTGjacD^-p1bR*&S}BBFumOaJR5ttclJ7SRq<`nh17{ zXkcB4mJ!RBm(koNc4W^xRW`6*L}33Yhu#d*hVM;?`?q0934uLt-ZZ`A{`~Cb$a*{* zcM~D*65=5ta73{bqG{jY;aat-XJ*!DbUy?6j69GfF~2oW)vAQ)JqHakaOR*KqvX@R zL05lUjarv%)jLEPIPb6&&Uw<*nf+}?`fX)j0>UMI#Y+hrCAX^d5xbh;x`k!C+{-{+ ziyBTwSY)FHl8y2w8-;cWtpSb#$rV}7^U1cBw?tS-Y&-Ue^e){4d7N%AuQ zve%b7m7-NA8ewNv??xK9j>6W`E#^ey1R;jZSuXV)>0t}$YzFoG4k50GzTAbSkRG;> z)*pmOv#YIUxVY@ZQN&gun%;II#80BJp@e&797QZ8_rsI=agq?bPuKLpF+qw}gQln^eE8p+#gKb9-8GUW?6RGF%M5E8r zB|C9^a1{Qx=e$)*y4LZ*b61$dgy#atPb3;Q3Be;lh`>B4%-N?GT&U-J2*GAV_#px{ zk?b?vCK~q$G3jaO9z>uPMeR!K52EoOA=a#!Tp2mlu{yn;oVKO;l>M|LXDN4q5c3HU zKRCo6IaPj6dPmOUIn0;$N;#0TwEm!0T_wb|e{TA=N;TF#>t$1|c4Tu$$xShKkH+nd zkQI$nAYLYq)t+kicO%aa^>nol-?A#`^X+zy4DJ2xr#yNEwRqf?cz%x%cZo*23@i5_ z0<(osVv^*F%Wl^zJ^T=X8A*7SkfOBI^FxFf7#;3|l7VuC@Pv>spsPf(Q83~KS~^WPFRz(=YPG7@k5Cla*e;Z6lo*t0y4Qeu&gJTH*ePGsODMaD z=3G!TK0l7EoaKuWho@Tq7r|$3iQSo{`GKP#pGz%IJcSdUi-1b#1#_dswGQeZFP*Kue1-U zV^+B-=7zt9o6WWaIBMI*n@1kR5Eq3f^RPvZ%E;U3HPsza3uc({Z}OW+I|;!(fbu?G zl~K!}zLGikidw}zfP~{|_u$+{8zu9jKkaqfqQWjaSbRVxLk4B<&uwIR`hT<4wwGR{G7$l#F3_V;)upOLR9MY zaxWr|5~4_%zsyFies-K)wC6<#ZgC3sZMp|N3mhNR$4PQ^DY;cxFVe%)^0X4Beq11g zeKzw!Ukx=JqG=bIT6K#M7tGK-I6k;4mJ!@9;Xd`cS$=y^mT;_O#92b{`}C{0l-Y~z zMOniBIknHMKkx0vmY~-s(-=fF6ykY4Ep9LBD6ALh(Q9cmR$TiW&mB`4XAaImnMM^t z>?Oqbj>9F3gQak!>7^!TL|B6ruLD-5i5b}9&Iv_%N{C!r9_jl$qY@FxG33Njc&~*M z@uO!>t;E_E%(Zl=25V#o#1>MlKYEm`tX(ub*rXd3H7tcviGHx6RA`b@bM4cFH5?PF z;TK%vAZ?0Y4H>WItre%ANk2sDIeN&b=V@1F`dZZ^`wM-DJzPRyz4H9rsPC0jv=BX3%XVimZ2T7xgEkR49DAh;#+j2cRX3I4xO5@f*@Blf8eh|&5 z{_AZAK3Z{GTt;d51wALMiEguUOQ*&Z?!#RF8Injt-0!j@XVajn>5iBo&FeY5rfdq@ z-{p|`X+6JHC4AnAIFA`y*&kiQB?PZmWcDLkQHo5iWb3kG1v_?OfQEJ9_;9qKttkB{ z?$f#dR<eiBzS*@nsHLS}V6>AUijWuh|vpZ16i08D&;`6o|d-tY}G(WJE&-uId!Y5{!EhD_C zAN@SMwBd`#F_&`w8h**vA)RAz@o{FQ^o6DQNbmOT`=v&)J80t}$tW263TGpTKSorHa8m@$0+GKHf z_>VFREzaXuF}sN4bH?uGitDL}#=bToT8ZNoSi5T;8h*i*1=d6_VWuso<(t@*1#a+> zXrNU?dX&YQ)l1tG-j8+bQB})ZDZRsW%UH8z+d>X3g=o5)>Y=Zeq4Y3zw0vm|zo72I zn&@uBQjN5r(NQe-;xtk}&@aV4k$*)T)QE#i%KB@_HLMru(Mx8;kMYEh&cqLtCFG#Y zkHWe0s(F)T7v~_#F3uH-`}}OH|5^E)E!(z8Ev5btks>|^g;t`Ri4}QNuWd(duda{K zP?Mo1Lfu7PM)`T_yDRZ}ov?u#>Om|ew`y(lLp3nZEq&L6KQ*)fsDtI6A1hT^Tfsb- z&-IELS{WQsxrXZX|CAAdkKG-Q>qS^DeiuwcljZcB7r6GvYBr_r00VdR9%NY?bZc&Q>)n_@ zD=PipY6nL)>wQxjwJPS&41Imr7Pcp2xU}1cr8YF4cj(0NcjkhR{QVbug>m}UOq*EP zv~UAUrT%O7q0U`httoW^EgA78WTS4p+Q_<=4>#}&A6>Ddh&zpnGWU6~9`fO-e)CtP z@%-ybwbyCQO4#6UX-nrF>a;x2%I4y4J$9da=%SmKwRnA1YE?jNYrSEXxBBiYkp_Oj z7Gh0wuUg}QT9{XPePPT}mhhsC!+VQ|)v)t&bHuDFj;yQQtfps+ntQ5vJN)vEw5q?HP(BCr8Tfs_0AS|BsfM|#b+-!k^giX3B9t}?`AiBRgqm%KT01c>G)b@ zq;)3qOcT+>bGIn%=a-`T2kp6z{n*&r=D44b%c?y;!{1&x{T*Xwja+31aXY^DJ2?? z&?)NMmYMZ`nhY`Ctc$aEaOAeuY$|Ro&p6FqW<)EiUCGi`hl1hun~$4XEei6RTWX)W zp~loYrq{aLMMA6}LeKLa?`mD2oKHeigg)}9t?Z^^Rz{_t#@>h@N@ zF(pz$VA~O`C+2cm_uo_MDq@LgX`cz$d_;6ecqJdwK2GXXRBb)A1Tjrn6 z!pe4*IEdqe*%!3$d}FWLquX>guxe*1%L4cAP8CNQ;@Ex?2XTK8_YLW# z@f`(K!*ey8RzXG}Z&15ZmR|D!H4o9KKs4|R(!f5EzAERcHPZSruWj<^V%u?Vk`Oi0 zYhx~tW~XyBly)sK>qQ>jaZv%<@#tW-FKbE3;$SIx-+5nb8EsEQUskHQue9TiJJo3I z=)EG!-f7mWJ}Y*|Pm&VM%aLh3o6uRCc{hM%`hJmNT^KvTRWaRb@H13v_|uoU)^d~j zfxGXBruE0!!CIFGKCJ7cc9KrSs0v096s67J{#xFd1=-DN^CbkX)e%j1I{nvG^DgAZ z%6C04A+YU;rV~6%Mrs|)XJvKFjgsEQxCX|~6y@8#p<2cV8QI+QttE?tZAUbD`rSrq z`>uV{Q_Xy&V_m4JQRh=m(YpRxy7ZaZN+pJ2y;uq@k)n7fwAQk2_GG6veP!5NEQOp^ zlrqG@8pOf(HQl5v3yFi^MbSyM5^uk`XtJickzh-AC4*>Ot zJO@K>q|+uI>d&%n2{TZC;Jm~6NT*rca%oj7Zqi%sX<(qX#8Psr#s+7$1$Td|7tInS zc{1pipkATVvY!Lgp95d$+g=YhP@iKdxgRxNA5}jdyP{{C+tWb1gr%^BWO2wZ2`0a! zYo9=dRv7&fp6tV+XNluRH~e|D34ES?HM52fkbF_}CQ%=g{g`3X>R%YEud80hKud;P!#*jB z-;g8hV)z%PUkWy6cFkd3`{il5KFe#FnH0-Em$$WGrn~j2cW&!Tg&?buo#zyFe2~s~ zGwQuQHB$?tOXu5WoKL9LdX&4h=jU4AAe4E)kDI)hbnN(<|=mfFIa$cG~u_oLtIom0>_-R+2ZeqJZ*YmK}TJ<3SQ;%WT3 zxvpVM>a9O+Sl_y_Im~+5#?x%mHpuE-sg3pL%3S8DwKc6iFIrjqn&l%O?oHmx#=e_A zM$GpmI+k+XZ?_8HYiBhnd|-`?ICXQFk-&Udj>-ku%BO)=k#oJQnzq0-jnnyC%YOE> zJo0;(tMB<*w%!p|`D^LPr@pbNztLiOT^8A50>e^$3i?>LPexeLo&{4NmZxpW@)eF{ zzqa-^`h-p~S;cQ=;Di8cLf%1UU$0zN=Jmc-m(hpKOkstsQ3p%V=w=#_iGB7iW{hZR zH---`YdyG8+S*<&y@hw(;~n^;Z$!{KD${-a zf&WF8aZ5L;ANb0HjA+^9JF6SKhF!c~-#|{`yu`RMhdT*(df-yGnc;8 z^zlI*4g7-rz?x{S=9ZH!xp7w?a%6F1Fbu^{H$ShUCfdVG|R6iU*r7J znlZD{1ij4B;Rb%ew&N;XQ9hlF*Sr4rSkH55q(lQ(^hl5Hz`kFM?I^lDuF8^;5{)K< z3Yo!bko9Y}Pl~bncldY~{i!a?aJ;{P8USSpTS!s0ItJ_aVl>;=wX@7~&>!+xom}n3 zwt79(=e~(BuwIm1x#usowKZ1eabbmPeq=Qw%36mC_pqW1&M_aC$Y;Iu?qo&QykL5T z=C{82jkG4cXQUJVy;{q7vB1V+^X4(IR32}4%V&CoHNDQo6o}7+$hFYM2Bkn)Wph~7 zmJGLM+Tu+_D@ySaeT+@Lwz1_)@=AIawKnQ`dXHuDK;uNQ{Orz+Nm4&TkCe8|@gpt& zKPH=OXC=%3PJ~rDp&0dJ`=|~^&p9>Nq5(bV@S4kQv;)2XgXuGeG(gBRI%3n-OSp%bf$@=5KT9Qj0-fTW%$5GTzk*T z4Jcz>ELzXQ!isi*139v_y*RJ*k)F*NfS!qokfVI$oBbYHoe1O!>9Hi48I^f ztVvNE(dms@pQ{+xvOJVV7kP91aENtnd9bzX%{&?_mXO^jv@+Ou^lhZXLG(C~9&zyL z1C~&#kdeNAQE9A@n{A$`R&bVTR@bio5{)W@`mv{z+Zry5npA3guve7?NEwx zkqu;v!@`a0Wk*T(M&Tck8?A06m!27VpvaI4J?K4 z@yLigy*jXnJKn~-mK6;Ag11h|-cmY3^dv;uRu!bXsn8>n5f+W^Wg6YTX>_r-IJ$Dr zJ?o5Og{U8!sUOHS><9LbZgkl2jAhH|ZsgfiTIxBr1m`C0J707+%nj8Iv+@LK4q{7C z@+r2|BC~Nlr?)X%c_;B4TY_>-vzF$$JI(V)b0QheXOs+-7)5b;U&I*H2~Zb(xcdGn?^=m*VKli{5Z+t z;58ue2?+0YeX=M z%QisrEYTN14~OoDBVY6}`J&$Bi=u~wz9_bk;y$#3yhtm^uC#(gKM_}u*h0GNl6=v_ zeBs+-GC-?lz&3L`c?u{((oPN@)Z@5>4dq|41 zb!&bWzHJdZ{UcoR$Z%~SBLXwu*T2x(;MeAE2ChtSZGdRXtZDa2&r55Z#k8WZ8j8qwSutAOH=<+(eiuEqtaPsVFjRNa-+U;9-g!M`2VPrj@k>Oe&t-h>% zW{~gWmOCFSNWKroGSK%yuZH%7r*CFI$1BFLt#u@Oj(S(_`OmXI)uFW}v#(_uYljbh zvwJ=Aw3aHa4$Mx#tOeR@x>sB~akdf5c%Yhuz}A3w= zba(69IZwx104nW^tM0#nagVQ)YpM|2a2-Rf33P@ z<1{v9dp8YBVa|-4S+gsfyLz>6EPHdKpN3zsUaX0tA6NfYGhCj>I(_J(ArCNr0_iEr zP_G~A^ScAsw;atR1ZG(vT2a;z;vyklr$C_eA(~?P^GoR0!(&OM|CNPF}Xr-f_y1y-pJq)n#*7v)k{ z&059|%?Ot`h?yfuo8IQ|ucoeG@APq3hD#ho{@*IIE~x4Bn%1jA{6)6XSyHK`E-cV@ zYmpj$S)Ink{^DAwRqLIPBr$X|1tDedY-gxhnSZ)(+5%2BI6JzB2zREOwab`8+*ORbSh?ajBgv-Z{Xa-j6kt5&I8 zY?<9XD0u+HCs zH7Uw1t(V@Ye}aDKN2DYr$iYuDdmLJKC(s(-i_`c%{Fr{X!4v&bfk+L%AOa#2gjhV{ zm|nQy6a6e9@C(Fb99R?Gax=ZHwsl-DUBC2GP4~WxqxD7)YjyB)`)-fij@4s4trjm5 z>?;a+I1bw*Eal~S(n`O2*4Cz-zkaaVxI!9!iLdMFSbjRf`a15k9c!XnZt4%zhRqDp z7j#)FX&)?Ay;=Qbm)X3M7&jff?KwDs9q=)LF8Rq;#gfiv~->B?x>cGR`aZ+y3JY%tJT@H#DxRrW$&T9%uq;&yIwX!ymWZ(2vM<%6y8 zk-wx-puM72HMPxIX6PMq7SXWOyZ-Kuq3#jZs}&bhAjVNv*w}z5Hl=tKsa2S(h8bdt za^}w(TK`ijt5Gb!gurY%MAP}&83Ee!C!uV@*%DGd9QGVXgl^fS9mSorqv$c~kqt)? zcNB4_kz5Gc=gi}kl?}MN(S~0zLmg{Ul=B<|YVQw{LC!8Cstvu<& z#!YLd;up-uMv0-@7GnBqKXVph^GnQAu@s&+krBH~w$?ILtIBTQ`K02Q;29Il@uQ5C z`E9iGKdZ7UOWsNdJl}w5%1?aWS}S-w4;$A0tAxOo;E4#z+1}bk+j}&K^&Njk#V<$$ zTTA?S)mZC0-=EFTmQlm@qLj#pe;akzMhtdip=(d7I6g=ZTc{{gX{S2(hEhqMY0H}0H=0oiG^219pu(V8^FMA8gC^X96k z4bYR3TNUEgQF~$x)?a>pqoR&Ny(0Jgd%Cpx!#f}JjcKAJy^DGtEd#xGS2f-i?)pi0 zTRu`l3n1ASVXOHT6>vz!5E}_pT+o(1-=co@?-Pf1(8mOVQL<@&DQBh`O znH{)s;(AtmTz|>ppk0zZfY|)|)pJo(S#W`U>xN8bg5%zw-0 zvU0BUC99SvU32#3@d!Qrnc!9$5UnWxopm?n zt*UMe95g|_xwne7Wo0vKjXu-<=s<`S5EE?G%rW1-Ii$YzaUH!Gf8LYEs?YESY~#9` zMypDBG#q#22fjwEDDkaYvbl518*$})G%SU$5zB}R)iWDczg0B44SuIqXj{g5owFWg z7@o5uJ#3+(M0$m@s^0C4uu^waEQRk7;M>x)@4TiTo0P7$v3ro4)DL{E0MUwKBgA|{ zEJ=aDcbE}PG~C9rZ58?&j@lDc97Sw9zI8zUZl;l}L&LU4|MquOEQM{CU$#Elcr459 z*4JouY=VkkuwJZ*&Oy#Q!q(sEVO%Qthtw*JGhqCI?p&sPh8OGW8mlVzv*DL4&4a8~ z<=R-Qvb&{_lK81(*!)F9jJ5SP*|6vMRye-dK(|?y8^dZ<>ub!tB99fm3xQ~QkABo9 zX3gwtXiNT3u`cWf(pHoS&x#lu!cMb&A*Cc;f-)x0^RPMnjr5~R(rs3ARIh<$t*v=_ zSlzWbcKa_s>+t8Emid>5y?kjOtJLEN>q7V9G(W-`h8wwd`?E`%=d1X|@wudRBxa;F zdebaB)uh8ZY0f_+>#GPpj0T5wwqf+Kx4mFG>#<=Or!rCuvbE z)nT~1b@rbKE8EtKDG*t`2N)-w&tjR5=9l_`QLc#l{#Git;a0fgB%R5e{H&j`K4J&E zlq)O{OHqX7cZ^I%L^W+>*fOU!Li>!9^c6}Xjv?*cWe+mm{P&Xey7fxZC8+Ii+$bN; z(ZaZLA%pQL_Y51>g)}hYO}D+Rf6aEDoTj_g?5Lg5)|<0lRJC%dUXDGPZkw51LTQ)O z-SO$*eluhB4p!(@ez(ZvmT8SSMLy~iKeo`YRI`jn%wEkqS%22Zn*x#giJcvJ;LlDL z8mggXLCb(EOUgC)=WkXqeXw3-a(~GhU<+>?2{!|Jhg!Ao@b&qC^?TVp1<1e%IyNXu3?e5Z8A(~EF^vq|ppKs_HZ6VTFp>_6o_t;$3v9Fb`e^%)_qewsUPU0AZ>~vSG=iD-Mf*+FYG5piZHf>uldk!xbDgd^ghjEOVJtu-fl-P z17l8#a{S~NW-D->?VHs>8`SfTc`a)u>s9q~jmiZSv^9S!S6+m53^=W*(Kvn#JN7%y8ikq}5@!r?!x*aL4& z_t%w(gN<9h)89>g$rcTj`!U1%Vfw~CHEnhM95Q0Sm;^oY;00FaOgE_?_`(ssd_-q0 zv%9csx1OWf|Seee|}d|ipwYVlPVi+4AcE(npv>SIC)tA1<-tJMBt4n$M#M-hcBD3RINJ6s;! zvgM0g73!zA#wuP8L{omr^_uLPrKw1wjr}f}uS`Xs- z71x6@jf1zd8zW+Z4e!B`(#i{ai}Wb#Wm+coV&Nk_^N$f4Mh9@;K=%5k9!twE_uj~I zyzDFai8!NVpWzgFOEKgv6((;9qaWxkA^&M#jk3Z53l}mfH7hEuopF3*DKYm3Yjdg$ zwY@D?Kx?|+oh*E`H7e&NJI4Jmwn+Q6MF(od9z3(X{W(|NAMBHe_;Y4)JH{33Qmtw3i4vX~YcCpw} zn!auk8@0ZIwEuzi%KiA9VV#=4)RDN_tiLv_pG#stW-aq|V9XL@nG`)I#H|uX;_9V9 zV2l*e@UqUPioH7q9kN9K;rG z?I`W)W2>-#l#7$@puTft`#5@+p0~>69OOO6-8Y zqKrM8mz|gt7w{x)q(lQXsvH-+dqVH0uiX@>zMV6D^?=aePo8)BPorLXEQxBW#^c=an=ydH`4x>8r9OjcoTX>YIHu ziG#StMLkdVixQ&tgNyo7Lf{u{3AT{#jwYV3TRtstEb$z_pkIpg=>FZ&?TyKMM^h?lRQIv&*P?ufN!*0n4j7%Y#vcg=vjQ?u-8t-n*k$fMr0Er{bZ3)s=l+iT0 zH9{h61!#2f3;J3}kIof6j5OSi{TJ6gox*L@?|RXPL*I^WV(S!XXv22slRrF^ygnZB z;{4~c8f&7rm+8gObbp@={2H=MqJgnRq(}J-N22(BXVIM(ouJp*`3*Bk_4421J^(oj z>3s2#TI_=Kto!8$Ql^t^EwQG!Vgt3;C!g88zRp##F5K;t(ZiDM`N3avRV;<}Tt@W$ z$X}JGdw$YR3zSFE86CuNqc@9btWwcf4XLwC;yI3$Ji2L#=M9PHhluAmi;(9i3$!ak z(!Q3Yy&*|EYBiL0oCTEcL)ynm);?%iQ2WT5;X|@D*i6;{tuR^xLj1N8baOpf&O2l| z!^m=?XMvWJT9t_48k}xuA}?bdc^Lu43rN`_=w(pP6QzfHYV^k8)2Kv#yy_80FM&Db zmH!qQjdG@AtDuoan(k>>%<~6Q4kYk^Yzo%oxpJVfV#;eFVj>%u%_8SQqqv{B%8 zd83gBy?^f1q9&G-PriIu*4zlbx1Nm|ca7l}%tOYSCnGguSd zLQ6C<-e1o$5)G^u^PXiIslJyo3hjHPS8%l%AV1RC70l}-eh?zffmeDiLf{w71jU*t zBHX@#k-FALoANA&fz&bg9COkYWiTN&65{z&8G$F95UnVuV@nzy<73&%73HP;c5DgK zrrh%)f3YrUjvYMla<6<}pJp)p%IkyC!|4dku(diM%20 z%v<%FPqdqnd$#J)`E)Q5uCn*Xbge181yE#6s! zciB*`!LtI|(ya#%#%~XnZn?phU`@0lYF0s8+^v*h6<)$Mbz(or(=)Lp@(oRU>-5n6 zsN0jJ3EIl=3*Mc8HBrhPAvVOD&Bq-YAAQJsxDXgxE_6{DLjSK9M9g9j;|~kyahlNR@hy_e|jZ6STYZZLs#O#u%2z?~X2iae8`k zKUNcsmPF%V3L1E?7Sf}&^X5_97ggdr)cYSA!WShEAdyeJ9PMThjTS`XRG2E=Wq~y0 zR^_I#T2EuOg2oD^4@XxXtJDWys~Hc)RZCBjh_e$VQI@L;`Dd%{GzVw38f>5*#5pL> zsF}(7>N@Ewv|f0ITh=85$Qo25YY;=$0Bty018SAYwJX;WbP|cI^LDb%dC8umXMxt4 zdQK%1qiuw=ktef~JedaM$)Hb#o(zp{B7)DGB%TmH(er~Zc4)f;T1A{p`uqPxB+hvr zZ9(+^AgGRLi&MuDmHF|1(STB%#&3H6zci?qN%jg5Gy?w@4Ui=}()%C8?|#7eq_8-I ziH6brjewEnx{F#PIQW0H3g!e~*Cy7K%vw6It9<6lmpOqXd#U<(tt6spe5WR z|J^?sA+G_P+5iwqG@`{=$vVTif`C?~=m*qAUnCldqx(P79u0L7b%}=P2mSy50S%5g Ar2qf` literal 0 HcmV?d00001 diff --git a/ros2_foxy_core/fanuc_crx_description/meshes/visual/j5.stl b/ros2_foxy_core/fanuc_crx_description/meshes/visual/j5.stl new file mode 100644 index 0000000000000000000000000000000000000000..133e431d888b1e9c1a2261a99b18a55cc7bd5ae2 GIT binary patch literal 161184 zcmbTfXINCd^Y|SVtk}DVC?JT6qKF`{IlG4{O+gd|m7)S-?}A|OioJKe?Op83CVP%u zEZBSRz4!K?!_EHgiO=`d!z->U`DA7?$)uiao2by*$=!N)>z^>NTi4o&X|=<;4M+)1 zNF@J1|K?c{l4kA4l`IE-siJ9D!{u&j{adZ&Su1ANd$GTP8Z|IbzVy^V|NCMSwf4bq z`Qy3_Jt5P9SPewpl`lG@h<`waKHz9J&V_9Hix>)o35bgo zP0esFR9AlySwO4@B7WYV-8k3s*3Rm>Iez&yEowFOKf)d7LiAs?YdqbaPoHv~UXEYI zUQcvZ?M@ivDgS(SYA!WYr(5{TrnDCNZD|eE&b|TiiZ*WG!Rxy#^KMzsb>rrQah%J; z#!cPe7AD(Qo~BQ-X{uVdgv&v3lYrQ<)tg=Hc!0e;+MVNE(J#H!I-}dkM@4RXp=W1lBR~yXjD3?k&B3+zM)gPrg$#*X?i4eQ!Wi({K z0L|wF=R*H;L_od~Aj1}9c+IOO;ao_b329{_q~jKE)*kGra;&?Ab0M2d$Z{YW@2Sik zCO_A;n-eDCT&UhmsCI#f0)G_Ex=za_tfDv<_D%Qe_0$A=UwOUN(0YWtpU{tQTE2+w zJX4C{6jZJr`yc9RZ4{q4^bT|Sy`AA)NcX>b?cHwm__ZMpJS*@7!?{rX=ut1w6H+as z5WjRKk~fVX!*DL-0}1ss@ZfRphpczKZkh*2;#}x|jtIzS1v0LJ4Bz-M6z4+nOh_xJ z-ISzyyy#E|?(Tnr;#|lk6YiUY*g{=Z8*+!0B0DI~h3d_OY8PZo0)HG_wTLY_Rf^(V z*f+Ru5>jMhKi&sC_~mpdic@g8xFoO~w8{eydi>r_aW1So)|QaZ;K9A%!R){j6z9VA zgKLD4D*t(q;#}AVxYqymV4r_INN_In|6jefG|0FH9@IfA!MTvUzaqmV@Ze*xqoMx^ zhI1jC{)#@Opsu{YgMMTO!?{qs{T1P6f(K3D!EL#v7|w-#gS|<}0qC_uA&QoOUW-$( z*Kltpv%NRJ%X~gFgyG6!lA3B}6#v8yryy$+bO3_c}J>WlGr!v3+kh zKlOBp_Og8wVsg9er|NgMk(=iRLO<_0zLxaygeSk*Vj0D?=o#s!wtC!N-hTfu$21{R zPv%j#w~qYb5_<`!p!zZ4k_f5S=9=#D8!MJwBSRQJFmYm@zq(*inEbT+FwiP$?GD}D zYwuZ=fOrX~tUBPY)*Tuu&mTS7glZQE|9YEro^SkFw45&CTx3$9diS$l4ojQ;7t!R@ zA-2)>GJX3pQbP4^nslS3I;)bqTfVbe4qTvv=^pPp8xZ~O*II0ehVvSCzfVaJCoYAP+SwTWWi8aITgbACF= z9c_!6>V$=>@l)(%hfC98{Mheg!#CJ9mj+kgCJ?yXE^|Uv%W!9T$3GHimDr&=?>wrS zwD?2Z^A#MQ< zyxJ5`$*#h9VMeyUZ@603(oX)=S(4tr4O7FO+slb#?m!>h-NT6wS)iA?u2^NnGWJak zS3fPTBe(9?(G}A$8kDu+&9>W1i+o=(To%>}mqf@mtHo^mib?cUg;ZhIH?(SqnmD$x z?3+78zh!NZ+O@K`TxQh_u%pb_Cu~?p3(2L7mq1`^F-^$UT9Eg{hXE1+6RWo8*+w%jKaek>b4f%W&C|?xIpA}4N}L3`N+%8&C+95tU0)chMG$AvW9-=pfHQ>?@JC1rMjuLvB;in$Aj+UQ(tq58*yOc+JFRsNy zwl@%GuOA3R*{C}h46+i$}?B*`U>DkTD5lG{`){aJ^$0h=BfaaLOy)>VX!lwRHx^HHxC>Un5TO)$7^A^(M-; zcjCBZpm_Dyh%?V%!@FBGm+DpD#&8Qqu|zNSsFp@Yo_AJ~*3S5(!*L1sT9N4Rs5o!D z-bVURtCED{D~?1+o{5mQc^8dq4t>xaJDwroc#b0~vI&UMix1QI>u=b@?I98#@9J5mLp&mT2zpK}37z`Fz>$aMi9%9r^s#yvCR&Ys7f>Dbz}R9$QBq_i_d29<9{=3AN?;^^yyw z33065oY%^-mli&nOMiR|Q{7KE$fdJNn6ORQPlOcBjN)ybEu}RU;S}3}30xA)`n-Ga z9DkJ->TpZ21Jlbq!_}4(9pvEj(onl+`=s#t5xhmZ8NLA@-mX$E7rELpUZ}qP)+jzD$iFVvx9lA8i&)HuKT@*)3Nu>9fc zG+ujpN4lZoW}gl%!&IH(ELRBbZo;*IO9C0eHF$&YQ}o6YS7~!vu-dzZyPT9V)r2*{ z{f3ai{w;YkkNtGEfk;?7CU8lx9vq#@r=Fih<7Z5#HXdOrD^_2gW}9fj^rTP0>ajBJ za%jX1uw!b)Vf?@kUutuqrmjash?;z|nS6HEA``X=mqbYVq?_#OU02%vP@-T5p8Mb) z4E>|g0v2_*B;D|#pDJN{NgRu^$iX3vm*<@@&l_g_y@OYup%0%>pQNcx*^yg zzwNljglhqpM2L4GFI~r>dS=~Vm=LepFsNB8uXpr%1Ks9dLVuf+omQV>x z$GVHete>5Es4~x+Wd5M7`nOc4=nb;lKg&#*?lM16ZE6aYn>88-GE84HdH>w4x*}(C zbk7Yz>V;lm^2$N8OxPw|5+Selw$=qi|73ZcI!m=5`l}}wwUHgy`I)dLIHE#bE#2*t zJoYWidYK^MT-b7vSTN@)tM7J_z3vq%VSO=;Wy5+fJCZ+ooybn#wUq8V2C3^RhRL7m zOfg~F{Yij&qHP(ZtFLkD+eZeyPkQai{Brpj;+{Mt`!+?!nJ@)BBWjB659D} zQ*ODgt}uS!_0Hxre|4i8Eyr*F2IKkk3tL&UK@EB7lTH$rj&&D_+eHKU>lSy}vf58* z?3_ULSW1+<|97Mb(@SRts8*Kk<+ja!gN(?HnS7~!k#Xtyhq_Cn0@VkbI>>9jmNj9U za7l!W`LTvR8`GIDuE(iwu)jL`NC!E?GLmCW@EnDZLt7WpD77=MSp7J~xv=FT!5zji zi%aqR!_dx*eDn-J)+eElkGUgOX#sS!t|t`0jjS>j2w{M7Ay}w zkinnyE6cWQS*#5XXR}a3v`zsxuk>Q!%O})R$8^y@y z-_LAB$kL#WtWC|KyxHYXI^S*qYFy74`JLy%ZCDf04#n4#+l0FE8_jm=hPVf+IdZK0 zAocJzFRwuLP1yR*xjqw81J!e|^FOV^i0cQ_g!H5P z=vdoce0Y~fIw2QoW4P7{u|G46XIRx?_eSp0VNYS3a4kT*l00~+U3PqX^*I#VfeBm^ zA$hs&+4~P&x$p54LTkq~Zey@YEwPU-Xc)s|m#P%EYOFi15kl&>$l!19A2+%#Dl7C_ ztO;(Fgp{`N;V$>TFr)hip?_dP?6qNYMlofYJOACk9*ms-MH#F+juM1~R4~vI+r0Rn zE+T=W51t3Zxxuy!eog9~Gi|0l#jy`-g5wITKRWpFk!Po{fom!W5e^f$BtmX|T*s6e zkJz9eQNs9vb;nVgkfc_vXyd^j*|U2w!oCmI9oq!+#L2K4>c2vl5K&PW2eBqN&cp79 zb2wkTx1_Q7xT?a4g9&jQEI<1u``NA}E8erKFsfnQ@wiJ!*2*|me~dG8bsH=Ycs$1| z8A8gR9mW$&+Rz1giVn{vuqJqVtzG>(~rH;4wSn*7j5U0drY!JOnx0a3+)|_}Qisy`kw78wd z4=(RSn|0ppgXia16Fm1N#KS*{XZo3Fp@Us1mW~Nr5+TnLW&Ue>A*o`ua}>|jF^yLi zgcvi*@tnTa()aGs&4q%%wO-QNb+h~a+J$Z2XdJOL&eT(u}Z-#e}U-Vxf;Sm+~UiY

oEmc`K> zbX9t5KDNqhhI8Rs5Q)IeiEQ-3Xnt$|4~F%{G?q<>OS~ty_)?X(xVV>LeKCD_Re*ZY zK3X2!RNLh&{B9WkyuLge`0=W-ZvQ~FL~5*@w`aSAX{Y!=)ip0#HUwA$(IBM~{k5Y3 zf6~H>3bB1X@jMpTSpNTViyWP@R>U8mO+_)?R+t&{2=+Cc6UFVT&T=dR56Kv4hWR7#;S`dlN*LSg; zv0K;|uQ-nN#Wa>ph~?Y>KBkf{8)I36V|_6l@HtSuJfNjKxWqKD;~C6k!gR?#t!LUZ zdO1-28|g#WRGVCsiE&$%4xBS^_bpOJy^Zi+edb2vkVAn;w&~MZxl_K+LL!&9HQ1tYb@uz z&Cp{_@V+msik^;VA#caiv(tKUoC{kk67}P(`I+Ha)aMZ8SYJ$I*@Vn?>&Wl_9!Br& zd&sc9n2szIs#c6`EUU#wgB{nshw%~fo6##L7aIpP2v!3UedLw1R_ihSKnhi@TpG(Y z2E#WR$j!$Cn{x$5RhS%iMlP@&AZ*7iKUKzsFy^oya*rF};q8;)K zPyW^831!oZa;z`Tg=uJs#k=xy@(y~4&0|4Bwq-oU`LstbpFvhie9f; z*60@zs)l`NBsVrq)?<3$!7w$xhm$qVZFkB_BRVu;SURSwWrwR3j?|H74)X&Ue)iq@j=E>)&PqljmX7JVkHgiZ^g6Os zBN&M5UDEjMa>?|0_@{$!pe(ywJGn&l?-Hi%O0`nwIn|MslC6Q*Gr^r7TjVB#ZhfUGedY*#5bKWnJe-WaX~JEaSCwX5KPQ~HW8HCFA;f)TI^S@wHJv#2V-A*% zb;pqpZgRYZc9pY|_L?_Xh*y}#@sW^Lx-f3t`W$tZ?g%jv>yBeEj32e_xy9RWbls+E z!f1e_sA$KzkHdKIY8UDh-P(wyW8LxCMaVgy?)+`XWV&d=c7~;68jo-=r{1aOb3cxw zBi7UqMm0?1Q55<|%cA`8=sEPjvryrL7mtH@ydtE{!c2ZE@Sbj2p|wUV9qW!~AA~&E zl*mgJAEQg!@q%ILn8tGyLfYSS;C3EWe9m9;6=oTj#`7RJAN;h0_3P?mT-0R%$8!-p z%fNFj*tu&poNws%!zZ}MeIu5Rb;q+ou;WoXer~)y_`^RC=1p&nCox4X=z?I@TS}=Lw1T2yFn~gp^ezzNK;nUbX#ZhNWW~ufkwOzjzu;IoOsLD*r)Pb7C5= z^k8*2HH+4DY0GU_d}4TQiS5Al5i-FA_C*IbWcA8dFkuA^m@JnKSdJf`8Q<@4ZVXQk|s}pjewUPQi@6H+aw1>v zRFl58f57%`^-;rDm5|#9Z&2btgsFv}yw$r8+NvbYY_AR)^;X~0bF2bmRB|eJb91AG z!}c?rvdJn;HEk{-&$-=D!6gxLr)z(1%5fe$&P(U# zt9a0)=v*UC88^zvpIgXEseLw44ek3*zu7t41UI%Wr}1_j8q>l7B^geMF4RU{ zf3}2tyLBxWToNJAL94x>Rb9{urzBg&ss3f&>Ajn~Dr0&ks1FS9^ri2V1Y6ik)p-s-^fR2T)OyK{ z)EU8F^kLQ(Dy*HmRpb3Wy3_KDg9M_6S25Ljn5ALoBu91S^9rhZx{%?(EgK;AfsBuB zX41PL1E*jaST@`*8Slic&X%VyYf`?VdmZ(gRY|#Fw@=FA;a`+2wUit=-C7liqCrl) zQvV9{NC*|QN}AY2o&4aFKDl8b6_-Rv?L%R_fvqiFY*~@x7Kd|Tnvmi4!TjZYC;BS4=w`Y8RuzlamhGkIp=_qvjw z4Mw+(e(KK61Le5SZFl|p=BwVjK0v;(bBswm!Ftzz7+-O4ldfEJBZhNbENoDvh`#du z7Nr&OtfZ0IN5?m78x%-sP=WqM1YhBz%=uvndUp$-mkvohh9ekzRJ-oC) z;2m>Jg9p2&^VJiJ&_ny37%mHIDE6q3hQoM?pH_6*68=;i2P)^TH2@=ms>{ zZNw>f|67#dS0$4d+Id)a#rl;I=fZY~M1|SuTsO8Dtz5jeUgxXaX6owW33Blo z3zYh6o2ae-bdndhT@Nv_^@%jT*{ui-xb7|xSgS%=k{UF-x4b^ODG&#y_UCoG{Lr29 zna^;_(xN`8@~AB1Kn=d(gK04RXW=kU#L247D;Z|`T#F7AV&Y@zqte)9E&q8_U9IN$QOVtIEgQdAhq#-&)02;! z{a&|eO(TK8y5Dv!ul5i0ked=MwqO5l&m#xT(XH9-%W(>pf#W0Gx`#-;<4k$_8X`58 zjw7{5m==d~HIC43dn$6Q3C<;2o)_4Y_v`;dN7Mrh*C@^9B_skO^-_q`0S*rsj?Q={gXIyD1Ebnt7}Y+(sD?*KJTi!5RDT$qcf;sRVRXhL z@}{!gRDSTCKHAT21MX>rJce1uE|_KLVU~gCJ9w5MTHblcR@SyyU3$)@7mtY9qEOk| z;Cx)KUTV5X$+(njNNm$WWy@og>%Q|0iyZ^N=au^$W`SAGwCtP|fp~Lvv2y3oX@m7y zPk|=nO5ek54iH;ri^RpKHA?4t*9?bMcNNpHClfS{^=c47PX+hoSbAM=OXW!)YIr>{ zQq6oCqty8BVmMSK478f;uCNCsThfZ#k~vPADyO@T(zVWalJlcsKz7@-HS-7S} zpU<`8Eaqfk$;}WT$iPI^2C5=CS2kQe;scg{h%L;2ENn^#nxZ*QxtIG)v9c&_c;ngR zuenbi5RVo$rNe>1x$ulk)M`6e{-?MV{Rx(1YjF=2Ex+GfVTDVzq$jr~3m(M&z&622 z_4)ox?L3OkwC~G9g4!x$iY_u_l?o8NhFc{e{Vlt*u@>X$Y3sfmr|cTMKpDC!&v4|H zr;1C0vx%yyZ1{w9`q8tWAY*CpTT|6C{sz0pkt%Lugp^cMS=^Ulba|D29OnwNE~2Dx zZv(mVH{qPvodp&fMwfZ_yk8}}Y;*qlNl-Qa!vi@szwZYrl z%Dz?=OrVgDFIhKxX z5@l>CwTd&s9>7oTqYG=_icN=cX3s?DcgTR#6hhD2E|6)LvQsa;ft#6_Mz<={)-~`UbUn z9L90V_^;*E{XSlDhe?H1Jfad(p<^~{vF#`w-Y14*3$f)QA$Ob2h6LTGgNJtz?7%W` zNpM%~pu}4&zDPq|EjXU<3|!`>W=!ZJS3J2usS@j^HuLBrFE6tQEWf&;K98BG(At9> zc=i2t)k0q*DgAhn+qwslJ8#%jGwfR-8}kRI81B zWVcuD3Z7-cnzK%I-td{PG<)m-hI8RrrbvAAwB=0=jifV;j|v2yWnvn>I818En>IW| zk1zVl8u_@ZSp&PtMGMVTux~I8H)YGrVFPA#l#VREB+Op1hPWhHpM%fi7ha^znp$w2 zf_;wV!Ofai^V!@x{iSrfJH{EcVVzlcu)N=6!Mc}M^s0UE068h>Io;fiK(^IPvULda2^Iu|`}jp0{Cb;V$Rg zU~YI-PFfP%Q&@B2aOyk-pV zo&AbVI6s8ql>OXSjh;I|p7CV99+w2IJ>7}>Z`4am+!yL_o#48{G~C(lwwpCL*Gnoj z`i2gtV0pMC_o$;)X z+$g!JA?iF;&+Y0ZzvxX3Z+F7$7mJeRTU|$ijN=jOSkl4vQr(JIC{Dqe;F1Wb)wmG9 zeX_YUXy{jgIDXGlRhB2ohklIv%Z`nwb-et;T2l6+(bSY6srTY~%X3nj2wI6U3jg-u z%^KK9bxKbc?7%+9CBdBuj}~mavq4H7UPtQLzP1`OJydSf?zREfRkpsNx^H^4{L9q{ zmb*8Z&Q49JAO%JFOQEJ(YLP*K^6Uyv47EC1tF4v=$bF7IH{g;8@tIPEzj%M19(HLe z;j%C-53QSw)Z4G(YqO$7D#h$WFSqu5r=HjYnEf+cVqLmCc=%hN_ z>rns=8LOAJ}FGX^;5{gMtza!53hr~FyNA4 zjq~CbJGtZu{WKv^!ewDvBn~dy#2o)&G;CTY32V~q=?CT76l*!EY7H6Nr+ve_f<=N> zOF=8_1FRL6M@X^q?z~#yEjpojSqZmr+;*{VV3tvv@&lu5NilOq3(*I+KHMtdZmltt zr?sk2>u#(ljo4pX4J%htZuI1{;Yx&$x@2VuIeO(rLy^buo=lJT`nhrUz~}cPJMijq zbsBW2kc4x2!*^v1VE@~3`+>iR^*~ewV%=ZF{GDNH!t1yCq{rI~m?k6!ZVt5C+<+dM zU5lQ7AF8^-S;6H2jST)>6Vy=Oclw1_f9Rct#H)67-|5!|RtBw-kEZdt-y73Y;iUuu zudr7?OjKP5zSF1JZil$r0c3=Lj5{C$r(hXaHnjH68N5h}Gfi#u*aw&UBe$z6XTQ_0 zzE??~eWa@zzvG?0_AWb+u^))%$b$9&TUfr|pt-is6bf_!4jXinwFgH4=+ZHOMyopptC%@Id?7mF! zzxHiL8gC1AHGZb(k20;})P;ZE>I-*hYDlOWr*{4NR`2)P17zH_>&1OGI?*Kuwosgc z-Ra-AMj= zB2nc?55DDr1+7{wN6-pei^pKNlL~fB8n#k*9qhm<*bY&~h~gvo;NuRuzH^uAa0FCJ)>;)DPo(LcZ$u z6ssl>_yTBhC8}o;kpX;7H@DOHwI1=I5MaTe% z)T1C$r$VI0V-$|mBJl`jOU+=mL}9i>(1?s@OQKfoU~~?G(b;ZJEsAGFcytym&zmOk zXKgCc_Xp}qcy@HiEC&`tP>)CDQ~H8Uux(wEmFP~S5mo9EWnU( zAOeW8cb72VM=j{D=6xiba9`R{s5I0ct0lmy2B%UDcV9bI~{w}dspxiC%0?@lE+dE!QO z!EFSeTa0+FY;m+Q{J7slKL6~2@~BH`!;?>Lpw(9(y#5D)=M0#JbDYv&**Bd7jdSWK z$iS8xxFr`#Og^BPH8rCtY>!vUm(5k>s=Ox1uzzUDd!8*#_k~1DI0er*a7nNaSM?=xzEF~u93C&> za&a!)ZwR@)>K5zav71s|lqA$5YLy~U)Aaz0>E=XF97&aM8^yJN>kYn%OG;%YVu#U4 z$9~d;UvErycl`{*UWn}#w`16+P9Df6&L2j@#`KjU*345b4mo3})whMvKXB`T^N-CD zY@gE<`et8WpxadGJ!mKdCG}C5;yG z?I*~|C5t$n zP2XHi5C}XM#VrQ*^lvO@-g(>UKQj`A*(;VIuC|B1JY=+=dXFZJ=_<4LN*4SD^yEBlK@%Kd9(>#r4!FsU^XWnJ6_eS7B_rc3ULKnw@s z01&ocD((J#xsiV2;Rm|DE#l?+=RD-o3&PY(76FD=sorwLg9z1j#!^_<4glg95T}cg zJ(!r&p`je{T2kknK4_Ttvax)^)lc2Le+{e$hXIiT#MD;lf{dM|%gD_ySgUsvtmQqg zYRQY=G*;Jr`vC;JJS^=2V&rXl)(49$a)mpch|{J!|nP_(CoI^(FD+`B4~ zXErXSdRaGuR-*Z1FA$|qba2O7;hKKrcF7Ro_(0h{%eR2g{4w-?suEnbQ$_-50x1G~>{3li=1YVn# z;AL)Uee&*ImQ^P5(JklbZ|>@Z>qjlT=%e95kcFDLz8Mf&|2POl)#4qpv2PD__mo$K zhpU;n9ty4zxE&3I)(00vFLKBI0Q+1d#sjef2wOL==D6Om2SuVT5O!espD>GkxKH33 z#WfB4B|uyN8Bh227Fs(#qs28%NCprLh?CaMcH>&aXX&`s|7(efyYqJ9NM>u<#&CCu zzcMhhNWXVoRUxQf~?5Smt+KeYaV zi4sGb%OihCB{PVnh8uIYbc$rX?>YRbwzxJL2)0$dWD;}mH1#QVNGPPy3o zx89U~$W$~eK_vO;4Y||Nj@;ot7SO!}X457T8b!68k}`eThmlOyIp~yhr|T zY&ZT7e@tjoPv&;sYHav91$&bat+j6hV&M^gckHQOOX|rj)4kOumGTtq*?(nd5$<^7 z=-qgnz%fzu$K0BJQtzn_()62eJ+U2l|64rAG55g@JzKhC0-s=tr)241ho;rDxutev z0-wa$jk_+#~tzowNTkhU! zr`~%{M^z*yLtPDnx-$4Xcwjs5>;<=&e|xQF$CQS4?zlDJITbDmPBXxcAc$ARCluO) zeY<<}EJM_-*^0HHz3SLzreUmMmhyB}duY283R+3y{*gjtaQl73@KN_d`7=pUi&Q>j zc$#%u*_jm##H<<+;Xp>0v-9@iwuDA#lPAbguUZW(yw z6k7@WriBE*(;!Xi({2~`Gj1iK3~iox6o}bj@q(z@som||oZ*eQZ zzRCaH3~4P8nXk^c;}IEqQ}m#D2GF>N<8JIVe6}sxVJ7My@ZXIi06sq#iR)lTFlcq7 z?luqX1MESO&}67UWUoE98`nF|CB%86jZwRS2pN5>8LmYfsWJWEXmG38rEEOM!97Z> zU2Wd3%>de04c~>W#Zgq0F$f6F=WRQ-+JooL_?{HD@4tTTG<0M$90Bm0LDb5;VwrTL zbu%1aagP$U%Cq&8W>0jGCX9aTiT#XQqDYuq`;0?Q!b}Ehf;EJ%Wm6K2h0o{c>WmvM z1=t^x9zoS!a4x?tuQ->sT3=1UDcizc+4+ z97*|?LBh_&g0KV6{GX0BzH1UzR z`+--fSRTBFxS$$+u%%uOtDPy~Ip<37AZ4gkrk3Ok!VN<_t2{NYPJ+dZ~Xa)b`R2MK%!YNoDE{TvSosJvN^hz^! z4H+)Tz-vG(544(E+&ICzCcSqfL&9Dglo!e!#d`Nk6bQUFz%(J*w(}1*cfZXBuS}9~S$*$h8M;=Os~ld`UY@mo zwjs9o5+&gs{4x#sbH6N|=-|OR1g8lE-kI3DWRRivtqdh4Efxq%!xrPYcFS30WPhne zy--8k>JX*qg3dC|g=zRYGqwtgrkz-9%^?y_!9K?&!Op~@bCfoJse89QS;FOFJFtCl zZqUg_$2OMd(Jdn-Jky`^{DR?Sm#4};_}!ny^p)X*Ttsc7HU~Re0>S?W(Rsef5SVmM zdF2)?V;b)JgarAN4!+7R6-kk>53n~e4f~0XpXkq|!^THRaS~3!8sd`RY~pr#DJjU0 z?VS}WVSVw61=H|Sh`qh80dwcI3pJBsR=+d+ylbhx{^cf5>}DnRXk?=njkT8X`V;QS z^v=~iJk*e{Y~n596ue@^CBcgR#YL(=XUPM{PzjfdR&;;K=nKD2k+fwS+t{R?gv-Tt zh%!d4{Y?D>F0fHg{RPW$E={9(92vxZ{(76O)UL`z=3U>1W<C{K}Zjv2-j?l<_lgk}kkwIa{@}KgaX7tRrg-tw!!pe(a4@Pam9ZcvX6dviVLs zuw(q`VRYQ_87!)OFOFw@Hza28T6#w5QanV(G$9Lbmyr^ymSLn%gg{`+qbi&=*sZv) zwB6zdGOph&BkiqQhRp#2=j!Tw&G35pYbD1+uiA{cXc$=SnR3Ek2I2=0x9!WY*+AeF zTrMsN&OhA7P+npWJ69u#<6PJdY#;2cwJJk(hD8O_wUK zXEnz4#Gu=i7{8%oSBtJo)Ndl@tP?loSKCbQD;ox5Y9P=m|R5T$Xa&MMA@Y53~5RxjOc zeGr?nES=*Nq25qQaPku@8z<_1>2|YBj#ou^9lgEgG3kI+QK|itIM8bT1uwR;#}D1% zgK0eZylg5OWYlMFjaBhFN+^j;UesN;ve7`gr14OW%k4SWM{l(?i??W$po%hbmv+}( zX*`gQ|BIM@tc`wYnZvy6m;@Em(AqsL=>C@*bmP8c2(^2w z^!Lnx!uL4B-r}?@(~Ok2`WMGLfL2%Sej4o>?AA>#nJLun+RP}^`&GyE%X|I3zgs%b zi#ftKqvdkaI4&3a1N#a3U~fk@<{wweb`9mY+@(kpToSxoAL7S)e2%AM?}8mDSN*+2 zNpxvpIP2I(#XEY0Y}wtNP1~DJ8GKiSbKx(ML?XUM3`^Ku)5p;!o#WPkbr;*!EAV+1 z_&kWqywuT_R}FZt5AOlO8;y3YsdrL1 zAJL+Wgj0(DQ$_Y|=d2c6SW?C%K};k4=2wBxczB#a^I^=K`oU26*yiRi#bmU=+ zr&65K@tp`TByBiUyK@Z)zAa&St$uPx-mac$I!^s^T(3BEWS&`MGsmf;bjn^Rma zKCg@M_LLWdN2oLYl!e;ueR(#mX6nH`D~zW_PBfDbGz(LIK4@>ixiAfDgRqNqNZW@dwh3zsy9P~f(mACQ`LdpRmUyy-T)lo9wb7B~ zCf{}L@+_Zlb!cLwg7?ngjg(5hQo_-)yhYJ94ClhTY9cXi@JE{RG@g&N>XdWyOAEON z)aZ|1-*T`#e0l~W&XPLPp)mnGwVSUGPQgCFCBdt8eSD-1hI-sSuP(#VF^%QHi*gg4 zq*c5c&&hqo@QyG(b!gemMLyEqPo1=S6Py+8|8bP&H1yyH7FXhbCOFDJsgL^cYo0Oz zoo3*Y2)SW*nOb#k$Ilkp#dZ~Ump_aMQzK$JD!5!M58mbc>MdopuEdS?cQah0`)a$( zw|U@oO0_3)3QzYEx2jDe;RXj&3B(^zlhd?t)74jAxE& z`}$>ItgX1=2_2tQmM{IM3CAfYCjNC2*J_QcRN}z{R?(&c$K~R>(id`&N9tOr<@el% z+O<7?jh4D2^T{i}Gn@<8bcT0bIew>?+O)(~AeI7g?6%Bb0D)6*xws@k!hWxz1DAXA zpjy>A&V_Bl+Wr^YpSSnm*jg0Z|FV4M`{Q)!<3P@?d}Y|r*bcFk?EmI1t%#_^+u83H zdKC6K_9l#+5U(0Ry!z2NF-M3|sCVJM0&kuTxK7(H?8sX!m`ZUx$MFNl6+*UOZ6O7^ z6yqBg-J^Jv!Lb&{VE6^%ePeYmHwE*jW32P*YVaaSU7LMN(dzBQfLdx|=^84oY1pBk z){4G!4dJuTR}k72_KilHOM=~xsaE&r7DI)TwAt z@7}zoV1Hmg!CMx4T@GC5UJpJlYMmehw?r%t-e;KEn~sM2weQ-t z6yiCK&R8D2Aq4MC);^fTBOJLPL(65ZT`^wWnAL@rb?U*RI<6Caf0ehcw_W`x^?gaIIYPOkexIAa=>{((SLsx<;de`MoaI{~yAfOC!v(3Ay|xfqt$U zz`KxY!n_^l(*8HsI=o0~-N#>P`kN61cQu)ZfS}W*>;ec_1{)`-fQM z6Ib6R|6i;%`#>YiG`!_qva#{|>`Wdw$ui$^b6sg#ndyDgk4ob#yXBVzv!zmvjaH#O zd5Cf-pD@=IvP01b$IhM9RZ~*HgIhpG0U_9dYe6I6R;5~J`CYI)2xNQ%tpX-l3U(kF z1|$QB5L0({#(D_%s#BPulzdIhy3c)-s%+law!n_gKq!7me4onli2~_@?i!(+6s}fV z+aB!b3PhhAf8OUnRj$dRAh`x}!7f@QR*FByo z4JOF>gqhZey>Zpl*54|^d{@(I2WWIi(+mioy6Fo4(mtOs(;88>{B`A{mpc#%Kx_v> z^-GeF3>nd~M(mJMmCJU)5KB`2(<+}R&?KKIkdaRm$N)mKqxZj-=M!d6X)??-vIB^Y zKorz2)p8ZIhJ3G?X^kkTEAU_p5U2n3U_N2?8m2X(z#l-^#av_^J|yv07}bc_7tWy;(Mf}I{PI74>|y$mEZ4-r-X6|KG2AW+FWV; z*am911`t~LK;;wWTEsMx0fbgpO~LZvEwibX%Up}v|7IH50k!K4L_4V6@462tr3<1 zmz5T2rwe3U1_Id(73ti$JDqK4Gp!Ol!o4 zxIIcxuOJ1!)C1xrS@`Pq4|WlHDFpJ3j9%^l~zylOdE7sE_2J!{x{PaQQ&jf zvkc+gxk}EmVU{sQlw#8UH@BsEqY~7-_t6FIDj0~=M<({*lr2Nj6-;Zya@Po@U;8j< zS1o}!vU&|;&4%X_=GK5|jrba;Q#?ByEg%j;ZjI7%nOlSQznRvEG1qOB=XxszW*H#k z5opvCG}CgKTLY#wqQ}%{rnsXGfY9t10ahOc>$O}3ts&nIGp!Ll?@TgT&X)=Zs3)CL zKvW6ctk+r`rZqw8C#3zE~NUW25Z)sl85VWvR0FuQFL1+EpM@D;`vMzgQ)) zvyVW-*W@>sFz#y2j?d}KaapTgrzuL%6jQ0GtyFCkHOq##smi3XT~Dl7*1o~QtPkg! z_#joOx38}0kwpY(b>mk8v+Puud1VdZI7OQ+X+F1I9-lvFG|wMFM&Jk5`Tm2Pehvxw zohBM?J?WHcj6vFP02Z+AXc0KjSc$1h1-i*W{g@*Ri%oJ@YL$ zmwR{1FJ*OHg3@APJr$P(=jS1|ynDhzmQ}ZfKxkT-eKWZmQ5#f@P)4wNpjE5tw*2b8 zDE2$vAb7CK0-`z<4^%e$JF6n`W0XCA=`fj91j}&>)(Y1GA^&V!!8*+QhrN05Z~rjQ zcc+KtC>L@%DW~6itGKVg8RUrl?0ofX)}(W%{2pZ{R~p<8qT)&oMs~z zaW?Z)TY;Ff=bCaaVwlq7ToV=3gt&ft&#oH}FsI64f(NJ1eyTi+%2ZA_c2O}6@6bnH zVh8&kX8|Q5IZn~~pjkuQ7T~+oKui9;^)7bSI#7_Y;GgHp?;07(l2r{=EDyfUB=2<# ztSx!OtoD+&mX)GkDxJ&t3pexd%{oG=cPOK4@1DnM?(Qz!xx+WXa7l!`jl6Eu<*j2q zTlW>#gZQ=~zJ&-cdCqHWd|x+@y;#{@AaJ?(78*n!ziBz`SKepNW4cK=19Ss~L5cmcirU|JDL?a-M{6*jz#WW%9hEFy=N&BUH**7y^ zh8C9~Itw>&@%=kO7T2!92dDb!@`{H_C@$r%KMG=^jK9K%FETSr@bC_YbdJ;8Nhos4 z`1^d3xLw(vFMF%%Zk+R#a0-4M2+M}ozd!r)38km$>POd+wDDEbM4JiYT;i)ky|?T6 z^zCbP_IfA54*Z&tNQAjlKI?onCKq+emtmgo;9U4U2tqmmvHM&#rqc-YDwFVn1ZZn6 z34Yhot2YmNQJiiYzLjcoga4aHp?59ti%`(d)1!FLJ7Z{It6%x^5_4Jj^$Ywe2D};p zMC9Eu^!;B1eo;)INyAFr`Q*w&eKMC`ptvlop;qf=*|0XKHk8jU>Q5&N${aU@*xi+1yi+mf)VD|ZG74IW@LMwY zWp>!pFPh4yx)R#B%MpfCkk=ICO$ENf&g#n(%NC{K7gh=~uub^Qb-33DzdhiRS)0~B zD!#^!f5%3YvAuabpAi>An>D+~uqOD0dHlN|aKC+W2ya>EuI|;IY89&;#%^zzE;-E0o!@ukTyJ{yI@o!eobYX}7onL8$He;tr*pVUnb{`GZ!*z9yD@ zyAjQ*-(7f5AHS6TV_cfzTV|3z>rOZjE_s}}cc@7h+N5$^F4jbRTfJZO3D#nEH9F2W zh2yd?EfRIczhjfmpVd|IiWls_y5kxlmNTnmg1C>On^ z>l>7e1Y+Uc`D|)$51I(C%HtG#YZBk4gtj|kF$)>*L$|l;BM?{yrr`!e&nfKgJqKFt zdVk?&=H@Bk%6q5Ddi&v#DwYkS+O-9YT(hT!+oD$3T3ie8`?aUWvwIh9=)T+mf((3j z^e7KjI$Dp`H+rO5-Ya$_J9e!yt@M2$$0=AV(ejrkGFgRlk90qx2XpVAfy$z}Df-}m zHY%pEJc!hN2eERxUAi4(hQQo9Q0aRvSZ~N^qhcE0hb5$KiH@v!Hu144k}lko#dlJ1 zN$^WFi`uZe#oFr5!fR>H9fOs#VLzl}bK0ml7rxyJvE*nsrlbtZdDu6N;}!O%uN@R? zYRz|Uj#PQ!)=KnT_%bHC4b;^&`(##izN*Q5cbYYr+)6^Lc=>wU(@Kxb{z^5{Tt4>wo|1JWQyJZ$u?&5%qKU0q zzMBQ;Vg&;2!^tP^98j9fiB*2~_W@#D?ai$E=#7kwPmplRvquM%m}RlbjlMp@IUd~c z`fOr1YVBcF-o;2b7uE`E3+J`omsmvZ5tg|vQo{P8-H5+rv^rwTqpL1t4yQcxS6&6X zL;0r}=5vZ0E&eE<@5d-}X4C^a7B#Wu?+OiK(;iU?r_em2eu@oL!s*0SuxL+ zuRpes-8=iQ40E|QO@AncM=46NYxQJY63mc)SLYRTx3NxZMFQIqIOdaL*fc=tbkiBM zDjrjf@66l7zJz;9I0ehl=8R_9aFd+>Vt1zQWhvu>^H;*=Gt+^vQ~2rs(RG#KRU}P! zf&>pvumpDrZpodw_W}tJA_Pl-1Px9C1b26L*TrRVb|JSrJ-EBOJBuz3UvG^o;RW(@TUrwdZAD-0A zY>)j#qY@>YSQBM8-ua!SS+gpBS@I~wYA~?JEz#{!yM#O;)tzq&UlQqC6iyg-*q3B9 zD3p%>NY%zwzN>0yKy49CHst)fSn@Kt^joF6D!C0OeIG5hZ0u*R5gz2+(66s};WxqF zIc*5Zm|A2p8^fyWeaple_y+SCVwObmi2r8xC(2L} z`)1!{8$V~%OYd&0u)>UcSd*rGCd5iYcoPCkVYWXNv3&9iw(Q|v+pQ_BmDcU_`Jgy{ zW-MQ~-S|hw#S}x*@IbQS6eKGS){9mgIDb%Eb)EQul^VRpRwi#t1M5X5Sd*qb&*{%% zK7O+GtCD0RlcyqSjlyWq3Z?6axA%(JXU}a&GLp}3%j$--^xHY3zkzT5T-8Lpe4CZc zpd5s9HLz;ZwDXH1*yEe2_C6{)KtZ4kjQXb;Zdec2#(S1+SB`#4J^+1mfY{1g*!@~H zbfRpEP$<=peLH!^CO-F35QUo874@F=x0lS^(1~bGtG2&C+cZ73zVC5w12YA*o>E^# ztR7>}vn|YtXz~QyJD3%pn@*oSskeb|kUQ2ycG0_I+1W?A^?du{jD(^M#P#sW_8fYc z6J@A~W*KI)8R;wPt&Vh8SYciRtckwb;fvYwCU*V((HJFPAATRLMudw`e7ZgF9GS!P zK%0$hZyG=STGy^h*3;m-okji%z7+4CqV|GD`uU)c`ZG7*mZ*CB4pte{F(VF(UbbFS~mW)jg z?Q6h(M;U!ZZ_zE;#XJdVPD?!wMR#It&K`6nOW7|GVU5w3AuVE?f@*Wsij3mi%rLP!Xe7{TH~+D!aneALjJ;mB;#4fWvtGHGAw(ASOec| z$um=weUwT>FRz=pI$Jeq+U(LL*zD7(*@9vN6dA|_}^3p1iJE!By*0Sc2zjHXdu5RGS)1j#8(K$cq zk@<8*7WO)T-|Lb~LCBW2Jht3Zez6aAR5$YsPeX{~#fr1}r~P@*wmb&D$vgO~{Y$ed z<{L+b#J;g)lXqLIRBZD!C-;9)(7;l*KinL*`&TlLZ_fA+MB8PjU1`Zr=6ys-152SE zlHo5IowucDyZZ<8G8M8W>S1x8o++8*{5W58CBEOu?$5>S0nZt7&)wLzR z68i{oGbF>OSg1a2ZaKdFZux&9(4X4!#@4i@Q^WLIqf7Ikb(NK@5o_K(bF5sK#|#cE zOXb$R>*eNuEUIIiTy@s*`dJQhV)>FzL}PXjim6`q+SXxq zMn3mY0|T>;!1>JCHHFLZadb|z>5P)pAD_Ka*_s#dtK#-E$mbk(W6jUvX#N zD{CEDUgtKG@04c)mzZjskTE--8xdmQ8>|=Qk$?N}3a$f_JbBiXstg=`D39#B^X}Vj zHq6LfWy1`t7h3`KBRgE?5Zk-U8F_`MhDzQKEQM$~73FBF&#LLg*I#oeeU2@PEloaN z#Tx5rU+3n|ZM6*SH5?^s59UgrRWH7}2`@0yU71UyFSzCZpXS<9$AXl;W>le6)VjIL zw$V#w_viX|Por_?{7DA$b#T%Sj8l`*DYH&W%Gco?ddQ-W?b;ruv z#mz$ZJ)Kw+<))faTlW|p$bYYqRgv-W)gg!NQ8{z?y-bQcI&_`MaHe{ z4;*El6f)D~$m>LT^hfC8dG%Ql4S7_ybOzRo+F~ncl(sHNx96uQB?e1kGjwx(U@wQUQ{%>4HpVG07H;xSsDZbpyPwyh(?qJJQe6{2ZQbY|Bd z{pQI7uhdf_?|TQ|aD2a)gZ^$^!bG-oqVMdd_v+@!(|o9-Aad-w?`X8Z)4X}On2Bie z#Yt967ZW`Bl=zCjtP=6l}M)=xhz z%y0IvDH&*{eR%3 zSTQYhKR6{!KQOyAuf3o$$5M#C`tg}##DP5K$8v>8kBv1N=xc_T;mgic;`jzN$C}6s z>0q$F`g(ajad$Z-x@O%CSbgH`g zr9X@FwO6Yvtgx++p{6;W>~(d%<<0jt58!guw``NUHZ^x#s#(N*GoyfchKD=GE-GS{ zts?(l+q%1tYuiIl-s3=!g1`};igp>#{k_evJ&O^dKFj3lb1pkC-#Ucj8W?cbJ{I{!q8 zm4O|SSWu<3qkSQ}x&6D01z4Z*Z2X|eaeRaFkRjd5*q*u` zt_tHL7S3Z*p>O?Qyt zIa&2AwK;#_orw6kqc@+A&>T~eS2o9e^Dt8Znj*ulPjU5IScJD~?^F;tGX7ZNbo8rH z+>Gq+O`4DCKi9RkLRmgxMGcN`%1!ohv_DhQJTW7WDK)obQx1rIn_chi)%cB8~DWKCbz6? zZb?XQVoelTJfej@s$kQCn;)iTI`YlR3e<*K>c~Wo1r| zt%x(6iWo|>=lTk~ij&< zXIt);iqdY$MY|^g!)oSn{cO>b?WjRbFK@J@$pmiIfcrRh?!Zh!SL&<=y8qzub% zQPYl)ZD};wmNc?0p)C|`OA=w(oM%?xN` zpd}t{y{bjHt!Hljp>tE$!moh_TII2ndT+3i?hW#esX?|Mr-8RUcyECB6qE@e;Ts!H zcPz>1js@?d@Qy{jF}X3}sO`|>H2j)R6D0>7?h~Q^={wIb&BxVx^eMLTKqn=q6PA*# z`)joKrQ6r#KW|_0#ue{8p$ADu+Wkjd@4DZ%jjS|SxkZLv`$x_*j~(mSLh?w-OCBlc zS%DrY=&3??sjptM>&su+-py~x(bFFK!$jX7+VzDc<5ki=w>4|gjHBlfmO`|q)g(`+ z8|3L!jy#>v&k8-ApwCJ3RU#Q5b)o?8Q$9OKzb-_pK3MAGW2d!{K$U! zCz5yDALOOCgS_;Pke42M8S|ExWU}9bf4`| zcNKxYgZWRjG3$4KZQod8TLQHeA&M>AXKNFC!i8@TF~q%{nQs1TySP_~5VZ)=m=M=u zPPp(5BJkg-lo4q65bic%zwPjkM}GJQ5$YdSy$R8D{C?ZIG>`qzI}%GFI?2znCiz)* zBtJ{^z(hYw714?OMRStBsM}L79sNSlmlIl-=Jr&}V)({K8T4_18 z(tB;w~7OZc~ppJO)>VU>~yE2j3}h@am_ zJeHEr*0-V}WYn*WVogc0mVmG$LeA}03}#YvW(>u1o}_qASqi@o>l>5^D^fEl%5;BH z)NdjJzYhy75mq#45`t6I@4nwwB_id=Qv_#0~q-b&($(n%>B!htrWwc9#=P-&8n4g_i9Y*QBy*DHf?8Mhi7bU9(LzfZR;+ar zg8G8R6G|d*BwA>Rup+XP5Iu>}8Db_8)_6sAF$Qr37yv_$+ISG0%g zO;PbO6T)v4;|_1^^4S`%a#gcp-;-kX=TaQ~R*Its>4|$0YrIN?6(OG#c|V3?^^?Ci zkchBG9HJ${is4U+?*B&l07g!x{~MPR!LHYm)I4Nvt;h%+CN! zl(7Ud2q7~eq$CkMPqjES?xlHB`PxjK?E zg~*I2J1Or6NKZsqV@V>cj2;xRPBLWfl5><>L?W!wfM|)Blazsm_S7=t$r;LDa)$Dk z$Wqp5K(s{s%zome+*DEqA*38AmDtZe(TO=(enl@!89!MuV3LTi`T%55pIaGEWUd#9 zuv!t(pa=E2%&KyXTK5y>laZyY7Dco~SearptpMe$kr{zX>u(ctq*$#eOIdv&_lZ_6 z8;V6HL`BMr)0^_*fb_)7Ef!iLtb931GI~?)oq3ddM!0?ncPK7>+y zQV}f?KXVIFf5?nLvkB3QRx5%Y|Hx)liV#hybxZ1R6Z896EsAI6ZtZ`3Z6B_ga=gnIvx`Kv7zb(1{Q~StTMc)0EZE z67kF8)#aDwiHM)tCia?z20f_Ht*l(sx{3L(te%3lO3Z&|-63gO1j#r~S-Ao!ubM1n z^_qOP&{D>)Y;TV!+ndbY)`oJo!JEWhv-(+{Ypv{Z;(5n(YwG{~UYM`jUhO1bpfQ!YJe!M1YdL8-*teZTa8 zEP_gQN{P07CV&;q)W=Cieai4R`<0qS5abDvN35(2f6`KMs=AZRj{2|=HQs|$G{;=ey z?^%d9JzU-R>&GaDd;_1(6uIZSiNBBeJ4-*?CPul{7T)nTVs&9=06*%H+ju*>ypDVk zeW2!c;qdbpFIww_SlY$lS?+DttMAXOutKz3Y!j*5*AthU8-$o&t|A{xeuJmq6xaVu9WQnlZ!Fpk@pU4T!i#o@dS?T~n+j5o z&FRbW=bI`UWB$ymV=2^DMWn6c%i{;R8I#jL)sZivQ8s0V`Bs|GW-#ABfV>Wo5Bjw&hID0*w!)P%^`{KE1HVe z-nh^8XPR&&1`BnHNjM=M#da4B-buvto@sfpYV@xL?qQ&Gk zMMT`u8y2Z&pmd)bcf_L5zGC&Ovd#uIpNXJNeZ=Ho8Bz6R-&^*ZcYnP}lW+s2Bf9L+ zXF~kwE7G)pZHZIxfPFi<+83vGHPs<-Jcsz*yinTE-DqY)0a{X-K4vGLe5 z5q4yN_|&Yl6YnF*LO(SbkC{`G-Pu71D1|X!D&k1 zF76>tWS5AP8#JCQqBcvxn=0{Ys8dS+_u|!>o}%Y>=_xzOH-g;@&8X*_*VjPl$h}0x zPh!u=_M%H|i5QkOnw_<$(2s@mHSkS}PoKn*E$u~$awVKt6W!fST+S--eSW(y_cV|% zmO?Z|{r+~A#Vlm5@p(HM$QRM+JAW2OdUOzDydX0d=u9fM~LPxi#w6Y(h;A;zE{zrbybPjvUnsr^<|E7i zR3p};X$fm*oC>+0Rbn6me~2p-yu{@YjFiRcj}HIoGehzVU}TRo$H;{@%F zV%z@+S3CzW>Jw{{5r@9E@^vP#@0I!(3kQD}r)HHB4ceA+A`|EH?_y$_05PPWl+k=z z8umE%2-c!PZv&+x0&9|S!b@1x^f;DcQx{|QFwMM8(W@JSN;na{zu6Cw&cBo>5G`XZ zzyEl`X60zfV)nH#>g6O2uap#fLrN*plIRUVS+lFXWygm!V}&O*Gw=<{!5;aSJ;_&c56X512se$D4XuKTa04MeCDwCOS&kUBYM}Izr~^WuL+eZ z$yM#es>dwZlu#Dp7G+>8Dn^#7nx9{^Snqwti>Dq_UC}&Z`a3bI>W_rv%*WYn&MlG6 zoRv^xq5PNWg--59pOZd(jYQ6I?Th~6AZMz$- zAZkV46z?j>B(!K>{U1@k6VI4T>lwkGbZ&28DU6UsA06_>9rRJ3ldl%Pu=kRFc*!|2 zG~PF1a|T~0a?h0hnz$A_Fk!T3HDdL5>Mr`V0wsBov{ek`iwLZV{zmIP&GqH{3wHf$ zYlRh}BafaJ6~9(VNH$;Y6F>ae%_3{mWaqARQoN8*57dv&Y9HR|d&`i&=)k3l9%a~B zu_v2f!s@UZ&d(Lsig^{r7_GL{BpHLpopDc;s{s(QR$ z(?d_~tj=Ro6*Z7AmO?Z|*JSs1t?>HF?)8l_`lh`|D_PlupliNPM3>*NRur#0-MD(Y zHn9@>=dq)|hcVB2F^2p5b)s1IHO8e_e<#M*qAwQx#dX_KmMz-G+RcnnB63k4)HdrptF0fo}yz^FMG^t zDI?pg>H2RAd-6#Wv*{=uxvPk+zPJ1i#nj+8>iZZd9nlN_h!bN!$JyPUN>=06^^=0h(_JZx!yna=l2fgH~v1;TcoNv%bK`6vp$ahzzg7 z^xspL=L2o!dCDD)MXw4Y>`QkAE82eD*+MifGQsX$QMPW+vEB8M$O`<$h%y{C#I{lq z)waL$TXSa!-%)O-3pGSE%GR{ffqv}lf(D%Xrc?AlbkpTc#iWhH>?KmmsNdP|7O^jG zL)l%QE=u$=w!)o+aN&43#y+jAjF9fy;i>J$-n@KSKph_Ys-cM3F~J^iFUVQMJxJsW z9Bc2{KiJtKW2hJwJ;ct6$^J;$&dHLm>diYnYQ#`Fa#s<0<^A-x^k81x?~#tu5q-6N znAlxnpnX!D)MMh-{cOnH!L0wrwn|JjqU&A?6CeFY+IMV~dOSRq)3rB8D*j22;K=>% z@jAjeV7R^BonYtS%t7LoXCHgbZc>jU#~!hf+Z*yMf2?OH9l5KB4jc3Hs6Q+43~jdP zC>_x~Plt#nf5zFpw@5t}(LV9S!-mYgeT0FL@EF~VHIbkGnDQ)O`cXFhZhOjEQ(LU* z+rvJ(N{I7uzCh6?V`uxRbs_)I!@sHzzx;bP?zQ3$L+QvJ(G;myD4cK3_l~6=JV2km zFhtbJG1$J@EzF7NnO?zSddp7s0r#aI!&+tLgZF4`l^&|(13;ayCW=IIo6Kf^k7H(+ z7=C1CE%9SU6Z`tXAxyw18{6AFRdpgn-3Gkw=ZS2FaN{T)xg(lvORM_u_fP7u zR9kB3g*pU@I{RYn<7$RE5q;)eebFLs6Z`f2a+Hk9>BVDiu8ZH8v7UiB5-`UB)4RNOaP*2?5T-4s9bf}^e{qx1Y88?0$^Xs=TB}eJV z9ns{0eS9E)H-4I}s#a3J`FEh`TRy^`W>lCH(P!rciPrmy+uOF0dh}%8RNXZ1?@wB#`yrK3(ac7}*gOJa@9Veo-H{kofEY-KPd(V(BmO`|q6kqCk?)EHhAL9yhA{s5}be9^K zii+-R%h=Fg={*7MjnwH~jC!T5IG<{-+**Z!` z1lB~hzN&3`)-p@=@tHO=)DY3A6YZ&key|Niwqf89-BO%&&qF)uH3WTUOy zp}Ge4Ei%DYkU0ki@XVz;*&Z|r(os4huqOHw&6QSs)7Epo1qICxFv1ayqf*mm_{?L) zuD^)S)Swr~5w3jm@ZHc%ZO_XGiVpF466zWFtsxT}$F!%;(VO3iXw3FqudkzYL|{$i z_qsle8#U&z-*bOr$O_RoOK4ibRU_D6Ax&7rwLLh_I5-ERP85&RGBfu}|HIWFFx0@g z51HV+LaRaZrhL%$_iS*=p*l)O1lB}%UYE=A`l)m9;}vhw4*Ay#fM}exDeKVea%@_S zgKYNA4jfkiTnAAnT5At}V5UbicCB87fol;m!FistW|u0&M^ofv^rH1TN=F3Nq-o>L zXDpy<174}~R)(w)jjJfd-KFT}I{Lz$UrHaL=z*&(WNi1J_#2 z&q5yY9geXai$l2n=$ekwkvr}t!4`Gp^?#VQVL%$N2^VW4zG;|`E^`kNN` z`OFy1v$addkO`u3m#JxM&J57gJ}$;j9I3)_UyIzaCW=3=F`BjN)s>Y_*4@C}Hpc(p z34rn~z0T)y1qJizx~GBCk-LiMwcTI8Pv?&&JiQC|(TK*A1!Y!Ey-NS>tAj7lGb{Uc zJh9-}hwcYA$Fg?s+Oe%wdnzX{WP&=;9xhpC+lMX=?%unYfzlD7p1d~oo~5sJ^y0OS z%(EdAMB_=1ZWKG6(dWFb%g^3=$`FAkNIZ*@zt4_->}LAr?DuM_9(W$a(>+DFHTuJ5 zq^`s}jIU&%bmWewV%o#C+^^UE)PXOWQ$ z6HU8Q)7z*OU57XIpRQPOkUQ2ynp1Q_MYAs3U!${PjY1}<6P;_f__^$9zA*2TQHtFM z5vnz+?}qWZ&zACh|J#xVT8EH3TE8e~&8f6T$Ne>VT78?2_BOO%VNJB_>vWdY+HYek zN3>Jo?$Abxc1GHlM0a=9*zkyLJ>FKa+#z=rarX2C{rOpMzBSs%fidY@=?9?G+KK zMR-fOhqg>buCXoCqZNxVaz_g^jjND-`qt}j*|1af477Qp4H<2{WHo5?md&5soXv_; zE%X@Sh}L?#wJbl3^)QCA0fS=|>p5~)5w8{}cRfrP&qBJYw;9MCZyjh)z1^;F^qjy( znmr7>=Rli2TI(r7A^0uZ_oF$>8`Dg=l|d$`6XlxhyqwjTt+V1aVw4*bM5wniC*86$ zj|I6|s*nN7?GkdwTOjfZOZ(98&5tXt4Lyb!c<+Qd;SCM_P4LktHseP)i|66WEg3Sw zdm~NTJ0qUu%8`Kuwd$hWU?D=iCHup_H#^y}x9d%oe#&hha>rXax_54M#dRXpM!%Xv zhZuMdh&tho8U1@;?{}8GXk%7-R#Qa}yt~89p>$I{;XK>${GjW|^bX36B67zYOv)}c zauuszeWYJQTBGpZ5xL_nDed(CYR3+bOQ!d2rQX+~PFRzsu1@wwR>!9>4q2Yfss4jbJMDJa2p$$p@)9B zd`AOsrxA^J>Ey+_BN<;GP?2RG(bT}(dyGp)j{?eb*E|`&@m-Ji32vd>(Ia;iaeLbr z_TY9Y{X1`__yHhy^i(v_|sYLY(|R+#Ull|qqmTzwRQ966Y9UROLv>)XLjkpPxo3-c-m$ z^>m8)P=YTnP*We^RbBC0LWJr~6+Xn5=V^<@ZycQm57psi zJ)Y`W<1Z@SZHPwyJ58%Strjm`rl65y+CCflz@c{=`uNd*GwP({p(F1jaU=;Uy)C08S+W(MLwzMhl;j0w6Kv?t#1hD7dPl%uf5k%I&xPLpZ2xn_eX!! zd#6|&k3OP^Mw=Y@W$dWH3-r|tUo#m;&s9XLcDSAgMzKuO^Xf11_2L8C{g%M447Z;? zT1W9JMtdoZs~gGq>_*v*fpZEd2=tCc*_7Gn`);=S+Yvp(uyBPHdM=}EiXN!eU7z`S z8S6Hv3uh10iz4^j9dT#sEB82fR;N4R;??zX9^=@6&OH?bT8dN)OKk65wop|BuRhU0>ZJ7vFldw1Pm}f_gshd3v{Auwo`Yaip#w@J12Q zlsWR~dp+cGP989>u!2B6&{jh`%fH6!``V=<&w*gYii0vxKk|qlRlx9D?9a&>pjmH9 zr>^R>o@Fbb*8-iqJiU#_^Xl*ogC;5`VLU-vXjv2G#VO`xY`^d1Lw7gUu@s)wR7BaY zf9v_1=j8b&6gDhv-_9!YKUT6{JoRbX#cJ+G(4I1U!KUPjXAPdCuqL`cKQYktroEqS zvOd(XM#I$ZrJT4!#$6`mRda7+%NTpobtPzsg21x@qG^Xbw7SmTj%V8o^i&XdDnc~< z*K*BqTRYz@>}Iw>3Ie&~Igu7St2VHvH4VK{^LOnW8BFrHfy$=v#`7q_YAm~piy!wEw9rxpHaDKCIbV9q`Th+9@)V3)JuCF2XiWO~2bOo*qWcSHi zkk@)y-Kg?l976=|A8_5(wD7&fxMwzpk>D(ELj-DzXiXdI%*}6v7BNQVc*U?TjMKoH zG;RB4FJ5bNWn+)$?+p1`+R8OiMGV^S#d|HRY&7-!UD?B7DGM$8iAKBcdbT*2>-RTB zD!XtjrS|#9EfrW;zv_CE1AUcqEsjJL(Qup4%g%bsg6jktI2+)%f?pT;w`cG$O6)7k z^T)nbY-Bj&sPom!ZuyP)F}3-}O}AXQPT@oov6eSx>b^%@?Axc-ieCoK=N2ou z&eQaKYb`s~CqZwwB~rOjw6v8gwbgF2ZzvYvL^uzad{wX3dWABsuvEEfOA@M{o@npZ zQ6iq~%+BvjdTJXyD@fVNpp4gz&n2|+I%dz?QhEq=-r&nFH{ZkR9O}fe6mpNcnMy2~ zL^&JlOFcXul+kZIs>9pO$*Js1uzfbq$|I(yE#SCYLbg?*rc3ntadFBTC0o%#$ko6? zjP{c&&TW!$m}K;rlheRb7Av`ySgeNTDocp)O}?yoi#;sIp-#$*W9cMU221mLsY(;# z4Yk#UiBD|6;wwg{VK4P=ENhUZGus1cW27R@5`f6*_SBr0~dgUm=ubI{lni+~rdum%l zGXs{gxXY1<^9tR{&@8%yX3UUrEoMzD*2Rm^rW$7e) z&C*=1SM)~&YO9*G;&i7K2TNJ)CVS0l-K15m0QJWT>W{{>s$nVY8=O%!t$&_coKG&y zcV7Ci-Lu`TgegmICw`sS|2TTcXPXdz5~9uEGTZSDj!LYF{tZZoKM2un@TTop3P=9G z5mJVn6S0)_EayQLG4v-ZfB%COv6LlG&VwpK>amApl=Anlh@~u@0KxAvzDgiUR zV#k9hku9*gIjf{gjKA4f+#OiMEI59L_~U+Ual4q!r2OsUbMWFf>KLyJ)Yb7#@UfL* z)cT_0TR=?{YofjA^0K_-_rk{Q3tJezSrcQ5eeEKJ-?3_nJj&t`QG-vtdP*M?mw|Vi zW{P~5T8W+8sw?%PJhBd^D$3sn7t@C{(D{~XrYMlAt>7Q3n}}X@a;5NSUReDzl}SM^x?+Ri%{&Tnk!60D>2 zbMqI8#@BL)u&%Yt<}=5ORml$~xMiXobJH5TNG6sudGX6+V+n8@VT z_yOYLUn3HRWhSCv%HIWxmzlOZjwB35W6*rmpi$UU#eq$1b zdc9g3t#LS2^c4IU1%1cx0 z5ATI=EQNod#q5i8^V2Oe4<*Eo`ym|PV7*wArVVX*hLzngO}|kv%5ZZ;h*W<3PU<)1@^O-D?du{Blb@F1>BeJ=UGkt7TrSqlVZ%Dxyzd8$S5-7Tu@y za)#0oeK2ifQLD-*BPzH7$yk&r6Q469o4&D8sPb1`)EsM~o9c_VnYTxEeMn$yBeg9^ zH1yICanxxQRad-srz zd=ZVZ$$r(g3qM(SjvntZh8?}#P`IBTVBDJ)W+Hmm@(|ImPzrn2SgHBAm~8w`g{=C` zpdjTh$M|nytcmPCHJ7jtPCwg%GI2(OE_KA6)}M{2&D3l2YKfjVYTHxJ4Kd^1)fG<` z`rFH;l08@(_(L6~BX^dc~Rg zB3Jb~_Ix&}$GM1HeE9k2wz!M+6g?2l_XUcjkLubJmdO89Kl(D2bqs##Ds?T+K<;Vo z)Dk`uTH9;24>2>=t|xk=h_bt#lRY@|b#vbL$#Yj|)gL-aNA4=3{Idbv<9oPk(6X8g zr6anse~`F7EXv+1ZK57+y?DW}bhb0Q>MH-j#{Vs2O>~+V(3w@3HJvSN6k{Owc0K`O z_vrz4kBlLv{wYx0nBCppb&}MhYkVE(o8ArnzP+fzr`4{QrI8-@mph0O-oCkOvikGfN{@pH|q@Z!0T>L?w#BbxrI zJImmKDRS{!zB3t0M|7Fnp`v8ZzV;ilr5<}frQ$rW99z_?k@7clMCbe%DrUSJW?y$x z_F$?!L-yA4&BE*F3o|BV4-u^{jkBi=3^pgOZXo`O8)jeV9-`=^X-$JRv4Tt5amT5- zI!Z_Gh}N`^Yu)+u?@pd+yI?3C(SPNXY^|jE^d6AV81>-$Sk@fLM+`l!d|tjsuOv6+gG~k zE+4?--RwF_NA8HGnc?LO)^AQ@zWCcKhSCwep+j@ACSthVoyoDgWARQlYVl}R;!?Dd zTOI#%k2Pspli=lgrYhyQ?qAGkmZg_SaPMiKKD@r7$Ig&QaqI3l`^DlxB%|*2&H95P zrMT%;!a%;*3MxW84$%9p8Nf>gbhIH~M5AoF%}7(!6|lMiA2=}!|8Ts85F5tYGhPWb z5uLEDw@7ighkedI$tu~Yacop?yVcn_ouv7d1V`+b7=&HZj9I zWkZY{%~l`l$J$no<@g5WVNJA?Dfvu)Wk&Ja`>W`y>#Y#(!%X9^v$f2Lt`#EU_HHBY zMr~8oqeJ-vdUT)8JWJ8XF64`)5KT6jEr)F_v-|Q!f0b7BK=l26D@9$#jGPzbUUc^5 z9&A{#cC0~xp8TuNYO!kBTccO+07Y|Ek3Y*~GQLd;3^6 zGCuc8YecZyDZ%-MqepwRNN#_ET^VTV8hP(v%{@>D4HXB=+obY zS44!dyL@dz3~iU)@ZS@{e|RLfq4WdaH;U}OWsRoCo#xVfTuhGX#51Ne2vNM+9{sls zq1=A;Aw%hi?sb`qT}NVh{wETVdTJ@#*^N2)ht0tpr6c<8mjv-`d?fc!U9mhU(^iqmG2RdrYnzCESlblo-c;dlQaK3W(bCH}IJq{j|FtMX>Bzls;B7Ip z&g_KEL#hzsWxyT%Ldn{Ee&^>5-@Ko2Po%xLDB(`uDkj!Mr@QI9^anF+y#Be&9Qk4? zL{p^qmMFjWdK&&cOE^cqh#s`d6w8LdKvNTyk*zmqxlz%~>JgkZS4Vdk_{)v_4Z5yZI$k%JuU9n@z;)EuT zE1UI$Ux=n-&nB$zQ9-g2E%n&QTs%#M+8p^Jx>Ddvv2@9qgay|nV(*RJuArbBtjUgO zMGr)OZ~vFLyy;XzI`4{vSn}l<8+SE;ZSEG$Q;&QlW<5Qg@Vab8bK9`j!fW}FguWRn znwb5aX1D=|*z~c%EG~U}j&D#~tcfxex}NDr$YSv0T6vCqQQO9juY$!F5KT&zCRTsG zuBvy9{>+w+XvUE*qN^17CWiMbAYKPcMBQ9pT;;AY)`a>4r6bxS<9G3U>H=a&xI_d8 zo?~}QMY1X5+Hlks(N|u77k%UMi(UZ|F=t7H-r@OnHn4LiUS!M4a#*CgE`63!+(|_XPy0Sba zC$p-zVmR_e^v2?vc|EY2NEK0%SWW2rkiOPP#`j0^bmE8b68XfzyroSAtKj=it%YALfij_J$loEl^oqn zL5%a#%8l#bkcxqTA53bYr!BV_BgYgU|1YcR)_{LDa(Z<fRzdFh%))^p^G=rrOPa`} z(3`(S@_t=}?^1~v+x$<~>0@16%AgpI(h-3*ksWUJEw;J&3fGLb(Hx~C`or+ z(e9M|qN=yn`0dGIEP0`(%HKSqTYeNv(#MJwfhA0=iFN?R53_(n6ZK;5t$Dl1$70Z( zexi<1#zZEaYP=SyKlBv&=>K<=->2PeR)D{->1Eo{?)8^+L|{!cx7T^kHsmPns@AI& z*WBNT%f0)E^6@22M2{c-m@={r5O?dAAsMdDZv5o|2P;0Tse(8+^RZ}pZJ=0JtBi?% zD4~<^a5r8$&|sHlH|1DrDj}XU8Z1uu{1f5st8rJg1bxiP07df^#UG32gZc`+NEtJt z>@VU`j%$Z%@R5f>eOvwx6@Yk2eHR7lt zmO`|qrP%Jy$Il<+`*Lf9q6eY}XSyn~t>`OmC6p&t9k(Up3%Ba5;KL?-)~+k!PJ@A> z%bD^fYK|?UX>*$ue|B;P%D>2?SdtC_6_V$VxJ*dB^aG|`3XtdUol{0rTell}G_G))H|Lr#+7TThP zp0$RFI$=$kW}oBE=f~W0Re01?k%9JhtVz>Wmhs{bTj=`h*0q$I21KYb?(QtaE7)G> zebaj>ZH3%XCr$fi&&exPs$hJ(e}Z8v;{Au(R#`eH=Mf==SofRi*hMDT3UqH!FEwAY zXqoNnfu>4-AVTf)yA4zF+mvhRVZT6*y@uRzjM2V5{tfH;*4@}XzLGN9Q75d4{`2$H zjo;ZB$cis(!tv|G{|e#vPv@x6H>_ap8heM0Y^{7B3U`<>$Oe$^3Tsxiy568%Tji@o z?l`Y#TFG@gS-`Gcdd=#Q9A`58&hdMsJ;U=Kti_TL)@E8$W!^>ZicVVH&DYro|FN!S zt=lVeA|ljzH|6l{%=UPuZA6+_W&J?zIM35vYTPK+?s-E!@5CM)R~FO>=V0==^Zmx2 z=ZRp|52||LYJjU9y5G*0=0`FtwNj_}UPo&mYz zu13>N21PT^9v@t(XZBTgGRPfwPUJ>baIMQsH_?@5;t-De9o(1T?u>3NjhC!^ohX)a zQ*(|xNc@Wy?olbQxXv1O*sV3oAJ#?L^&xi^@nA(UmSSTh%i6Awva>|)xc8+~(U550 z?&lh^%zXxM+++S;&zt>CF?Mnp9|E0OILquiXrghJH&z7V4TDHlvJIB)xo+ea1?yS1U@(0yr!*{h* z&N#>&&v2Ag<&VBB*N^3F>6y;TISRSsNslbsMb5-0pL2m7n694HkUO3xDX)Q6OE2B& zD_dVXg5!w}&uVyLr7!B@0rGMRW5tT9XJ@oC;5k~;ruNIsZnZzbcCGE8oP?3Pinw_w zg*tmgwuBZIRgV^Y0n0d{23tHfR73l@2;wLmxugA(>=S6B&6@s|Qhf}&@NPKs zj)+lg`uLw&wC~eDq&?@mhUcxryN&SXC>^=0h&9|(cexGbMgPj;LRN^zdkV4|TwbfE zE>)BNKEcDln-SClYtpn`zT4RDtHapRG95VH*B}$riLx8B#jKI70k2T|6GQ2Uz?wA8 zGs9C?s=o&C1*41TcoTzYylK+31{uohb21m?hl@K5ytTr6JiG;>oKA7~S)sF?Si{kg ziXM0$h4*cA?_4h}Pq=FE?%(z?l#bl-R*rJk)c%t_akb%dAI{Q|6{7LxkNyrk>!M%Q zp_zHQv0(<@BI3O&>O>xmIa2d`W6QA1JsWY9j@%FOdZI<15%#hV{lDJ^Kx@5^VzeG=*SAucoR#ld*Pug^vrX1BY$fHZ*}o*8+FpOUbl1c zfqr9Lg&qZRl#bkezXpf}vpd@B`8Omz9`@?WI~uE5kxrour6U?|tu<|3i`smOIL~I~ z|DYo)MB~jk`4rvl&5WXp*)_9^q6gl%#aBL|nkjs-@aCTP^=mCMg6q=SP zzZd_Q=b=r@pz4AC3?*9B6Q_c{7>8!b{@DMcA78e^OW&Wm0z>J@9lbheX4o6ScW(X5 zcA{o-1DPNiJx9pjr~FA)!jaiFx=3dQfgUO7+d_BSPjc{T{qpD|a|d$the0N)9(%{d z@TC)G=#ksnF_ex7tckoPn}zc?&u8hcmp{;v38K-HN7Ht%*ux%$`Ra3AoecCHLhe`- z`DN6}%DwyK(|1k@QhdCS3HtufoEX`jhrZgPH*$<)C>;^1Z`7L>O?d7UhxG5q_v`4Z zglP1|q8r6HH=cj?TzzrR5XCnNeZ0_HjC`GMr{+iZ-Ld5#)I|9^F#h)!z23-=>~;%o z+kZ%ZHTyS)(viE0Sb3xYPyXi@J>!u%Ix;~t`rnbadelQ!W!^b`>xOy;di)`Gtci9q zmpypX?$d2)*ELl96Ojq(L^&GI2lKYi59%K--DM~p5vqUUoms&=SHdKD6kQiZ#i6WGQ)f zuWPO>$s;)W0;3HPEroRQYF?Q~N6*!BWh~55I&xPLIW`;o>GZ6|vWaUL`s^YaZHweH zv7!V&MnBUz{@rdv4{X#4Ya%@=bYm?h4bs;=?Eb%4GK#x0(Ncug7K%$Pv5jrr&-G`? zTPO&$ks+GyIft)jud{GHWK*Pquwo1-YU>}?^UuZKGq*Wz#>%Ct^&DkbF%6O}<>X+o zdOF{&tl-R!iVQr_<4K>!Rpbj-$F&b^rB)A85O~vswi-I)xL5TplRcg5-Ibw=6$dRL zDywS*eKr$ub$KqXYQikCT}d=RuKkCY~VCYk^j0+eE!Yx9zNL zZ1n$P`y>LjMcV*nt|7JoaRv29;19{DT-Lj-DzXHmL|i_2|1eO{Lzyz|P2 zZ%_u-ME-DbTlGzqJh*eH<9{)V6nA6d`2)`-v;#Pk!&ud~20xK|`~UQi2;{Dwyw>#A z3^QFpUh-)U1K*$wikb#iz_vq2kZUtd)@1XYiG+} zQSlOidqZ`96;ySSE%Rla8ILF{*RMPiChm|Ct!WEV=g~KM^kw$w-v5ivq=+LE_tA)^ zwbr>sFQ4Tm+fuTzg1{D4PenhbkJPu6-N+ui>Y(@z;+ex5S5h|pW8`Cq-ZIY&HuP|; z;x&n^RK(E*!)@Q|mS@iv4K$E1wt|Y-vw0`0mWJu)H#GlW#5%=6nYcRR3P(HrkU6Yd z$?kd!TQ>!PKHG?fa45r?Q6*dY zuO($Su9l^$kt*-+Iz(rgSPEBdTAlZ1ho99hNaJ#W5_ zrEtYj5tr?``0o2}$4RU>akSdqs|X@wQh*mJ7v zjxowEHtKKPn3R+E9A8+m$>2Ak&R6X_7cj)Or2Hi~4`M0nSPx<;hZVI+ z5vPP$Ls6#5Day1y#Olj7!M3s@Ln-2v5dRgcFWcQh$W_Kd+$|wjod1f|m!&LLa;~*l zQN$@BUTyYe`6KtRs|SC@>dR7==5qD1G^dDDLVTvS%1=?Iy&zU!mcsFBwJt@RN4{3amcln_TLviLt@^_5<;A{;4-k`VtDt1tW3;x2m)VlWBu8%0Qepa|)iwSL9w z%TiYR$XO^tE)PrBB2h&oP0xX5?gY8EDyQ3c5M6JtP{)*L? zt%!Yqee>V3`m(1i1VtAAuQ!vv+N#upZAiuK>{3fi{O`75UD^_2Y!d}DPB=5HWj@AEPy|VxDo2UHk zG&7``{M6PTV)bPy>@}QM{ySD*jzsJ=oV&>Dh2rS%Q5=0F#Olk@j=hHSW6~`8&scr= zMOg^hYZfADRm=IXjDCt_w1HTCS;}H1d(C3?b5)~^C$%Y7KPRmQSjy5|_L`-6(yI1f zvHG$U_L|kYawVcHH~$fRfN<-#_AV?SbbT_(pJuc zD&oIl^<^pRi;^>uiukWseOU^>sDC5=BUb-^GUWHDB3619HKXBC&l+xyyNA&VrJW8*-Vs8=kq$=Jj2B7`qFK+d5`D9;aXYF z+!UNiVWlDp)J$M=(@bVw6Wj0s$@V#}^)GLx2*_k2`fJn`N6jL|%wv8zNe`{h3fHB@ zIeE3Q_4&6$R~@6%6*sr_$Z77Mf8FtQU2$_}mYinPjgyXr{mPmpa700`sMa(J_a+qn2`;O>A`OKj3JZ6_t_Z*$H z{ATi~ydgAxvZwQ z>E(LpsM9&G*}6hLk`dLi3r}CfS1(_08$;>HT}5PhQH=LqHl za+%K9{N}Y$j~sESbDLkv7a$p(YliY1-R|q*pO}tsP+P2ta<`2h%-?2dYwHr2jG=~z zz?!57wvERv5o}w34@GlCPyIi_z5*<(<@x^wu?Pi~l2VaWQBgsKcMp3kY*Deh^V;3m z0d`~ewYzxF!s<2AYj<~FyW>B5cn{3_yWjuydG2%Hhclm@nT^@m*_m@DKBhjO3-X9k zML??Jw*$1n@d3=$q%hn+SlhPMpVEWty!h2G0s*fuW$S0|Bd_x~E7R4dv{9@lpFE%t zPZ{!rdMtP6j`l_P_+yV~@jAx<;Lb;<`v0a!Lat_PaJ9YKq4$Rf=8k2@ zXz)vl1~R|-3LBcuQN!FZ`sI}e^nRiT|FKR;wYqU`t&l?vwxg>joAK!xZT;Dkcl=nC zV|10MN3`S{58m{603hBU$i+6+oMo=QuCa34a*w{7>B@&pFUlKyxl0G!cH^VB7nO8^ zFEx!W#4LBSvoB}!E0{Z$9i!o^q1hg5b>cg)LXq#IF?WpaS>hhO^~9YQn=PdJe!rWg z-oVD}{lMJpeWfR~(+Cf~a#0|c(DXiC81BKlp9};<+l@>+m!4>Ox37mXHuX9k@8-&P zoeki5ldsd%PB1oa10)(ePcFvhB6b9R{&HF4@UT#2urH zytz)DTDtRyOG2t@mk&o@Xws4m8f0Pv>fEG1@4NACr9!ydo(HtyB6oi4SP;i8fm9Qm zv;&oQS;|Zqu3+w1r{2fT(1I{d%~l8=?Th(nQ}5T+KF=Ja;3st#q|*s+-T3mDAgLEj zrknkeE$vE`WN%hgP_Vq1A4bC)1RidTcDOa1&5!XVix=IX&lBCbQ^8=4(d(b4(`yIa z`KvHdUGwLqTV~a}CHv$3H*I&pQ*=-%ch35Ua@-5JC3ruBt3SDv&xt+Q9;Y;1vYO7l zSCF5|7RWa~T1_AC_Truk1Gy~K*yq*B=1x(pfvvsy)0$$opGsd(%HD;_fqEAS=8nn;#8$;unnvGw=eS(!4GY4-8KyhaXRzHg~Y2UiT{Erv#bf7 zm>j^vB7~Q*FQ;ZsD^-V$z3$5J6U+~{1QyOUj}jhHhxJ?Bkc>Q6hK_J6#?MC-H!O4l%VjE+0+L{A(l%`d(Xh`&0HHP>2H8|r=BS*gU5 zv=h|5otovvG5T#wNBZ|(xZx-!&L3u5cjaxP%4~JBF&gHMW%oatoi2M-mgnz~2M|7P zSIMr>I94O~F%5Ia=%EYk=%rlcxX*ln=+U(=$#Jv++tACFVeS|`rdBqpx|ZXsxj-~{ z?_r+uy(V*MSCI9&Zci)BFU_~N$j>o)`EwgOG=Di>{GmX=4yF7(p&a{~_E7UVZKCfN zmFK@a>^YXiHZeQB?O%>BDk2a`>m8L}L1o#f#g8;hg|(Ft_h0=*zD!q{kCvTbc`+LE zhUmxqMr5^8gUuL`pJ911x>4m{F;BOb=Q)bngH#hDPDB^KTZ4W0<;7kkz(=mKmE)6s z@`K&x&5hM_KK0hQI`xRj=Z3{EZJ>anotum}UKasGYc@1EcNG5?ArN&}?jsH-^0Erc39I(f zfwtHb&7Zuq<5&_|kB^&%k$JNM*??D(40Fc_+!DN#WB4y~?-do;omM3n=8n-tT^*=$ zGn#+7UshaFG&oS#0gY35}fX9FG=m(C(zhCbKc7i-M$lb+?>>4@xv zr&r9zWj(Hziy}#bJ=x`<)fko+Q(-jhA9?qh3(g5=8-A8!Q_I=YPC3kc*-kr-(aUGK z(c@JJ*W83uE7_TYgJx7?*W(MZ!;!A^&Yy($+G@*jFW{D-elQ@Ad|q)vi|*8!6^toC zL(K|TcH3|)NuKlWG*&b7+zkYe8Mp46-vq&1(pSVY%pD_eOYqjAsJiB)siExpP{N8m za;4oz5PtKqEyrl>S#kPnuEK{+vH>2KidRmFFIkmE+ZADpB8t;a{xN*#PZP&F;g+C& zaK_^3hHRqN;>19s+Gd~47K4{l0%6lXxa_J+x{(h6dBbwy56P7TG#R&80L-< zxFyJk8#}GSPiH?icrLtEWoB{u*L{VbsbRx0I`_VYw8M3UPPY~I{IW#{=y?AYa^ z?0&9z`uFk}UU#jDW1VnIP)oL{lrA^&6+FH_^VRkrkxokK_H$Id|zpjhsm7j|>$db${{XP@cV_+z&cqECou$X!C zGIkvI0&WR12gnsI{(K7(+ODmnd0KEHeN!ijN9?!b51Or}U+YEiiO#u!$DV{QTEOKy zB(gkZ_(|VJd#Gzj8NM!;6PNXH_E@dWAN$twbAE4z<;7GO4d0_bUPenCa7WYDwPl`4 z60KUr%v)@*;~1UzY7brbvkc$WzzL)ZzZGSue=%%*SCqIuJ@*#S|jQD7DJaEIl#1oF};^}zFCSrtasrOZ`7F{=CrB+z$E7@HvJKh-}YS8a%^vVHa zEkVsjF}xRHOO0)?$<(vbnS++l%520CcpEg@Ik6;oFM+T2)EaA!Us9O0x?V-v)i46L z1X;yuPBNUn(ZDO$Y=2){A!@dF53GbpNQ?aPV2Orv3V_rWB zNuCUr1n=$eru2U4=FL4zvXfiNOI`*>$exVjuUcfquYBx%g_;ceB3O3pIe}lYaskP= z^P%RtP4?liPPirb(#E8o6^8AKW!InjO1>zT1p8WWR@-Dt#uux=KJG6ed3_im`=Xtm zk0w4%1K9A<vFR5H!`?RbUa^;HGTmsJ7`5|LbylsmkE93o zknsrsUUt6Uoy=;evWTihB)=WYj?W43CWL*n$(4Q)EP0DR!`?lX9iK(ui?;z+NZ!?f zEO~5UNe_(1=N-tIxE2!aW2wQ?s(VXk94tFNkwFIbfKXDsPEA&NnX7b;!m{IYo5{3e z>q_$DcvZHihJ$og!?NSEA-qrK$a7Mnb2OXn^;5&AQGB|S_4tteaP&o`CL2G&OFDC6 z+3}eg@|K=dB6lh`U=?%ZlFqeQc6{+J3ie*UZ0Oi>F8IR zJ$^Q~&8NVkRk_&a3!}I7WhH#}OUKh_5x%JbHdDR_2rk z!`!j#IOYVsJ9`Wn7}IZwQUIVL9I+_2W2{p zU~JJm1jpNO{0g@O_G-Sx+@~1S@A#Y>w4qHyceRIEIMPII0Tckz_||-j8Ebj^vTzyERWO zqOo7R`LLG^XfQrLK3&^MK1=!JNRKbydjK((`CexwHo+O7Qjydjd zV)!lvOCsyhK0J;%*$icUs!Xw9?ihhvf|{Qd@#O1}Hf&bfO@g^&G`zlLHA=wzdoy3yhdpvlP=h60B*Xe^<()C?t%pD_eOK?hUo2I!O4`E4N0;GFR zjK=q>aCTNVYrCHHjdFb0Tfuj<_|_WVlA28G`*gCLsoscXi*u0lz_+jXb{TH_-aXbP zmg~S)b}tf*xntS!9W?CDGyU1lmATlW-nGU-f9N;5&1iMSyjJ z?C5;CG|#=&S->+-hPh+e@om4!G}IKxQl~1+esx|A-?C#g&Iy2Q!=}yH{j+M&ld}*at5UWyzMDTH~)C1WSd{I1dCe$!n_YyJbDe!ShOb;QSJtsREI0 zT1KnAGJv)CW@eZ>mK|rqK%AjpC6;}lMSDIvC&Sz^8t2TwZm@hLOC2}Iy!O&OizErk zzrlGqCX*}V6p{JANYL4Ig7b*5?6@VkOI>28RlDlNRL^f>L#uDmaXk(Kt8G zWO}!_4y!(`fb#O-Z3{-=oI9MoXEN1mS<=#OcVQM0Tvf^h#4#%znSv^zDX+BoBSW+= z<6231eOPuGF@u+8$8)YCeai+gED4q!$Fkr~xNljeEC^Euuc@Zt+)6AvZV58B@~qWX zT;`Ho|Ikv0-FT^TxqpkjuK44lHonqFvV1|56kEbE8Qc=A z^Vs@i-;ilq+^F8n_Vii0ylQry7?z#mr~y8Cn@mm#XUtERIcxdchf4_DE{+F5#4EC% zHhIk_^Qwb`rAQHuuwdSh{ps>G+OOyVOM!DE8K%Ng$%r}AK9U9peb}?s z7m!Qjp=QJ7SO(^STLK@Bucyoy(Xp6_!dygmt}6eDmgG&6<@_j3*a9 z73A0p$KE+)lK*m2iXAV-YOj5nskuPlvj|4RZcxudVWpy(x!qa`f%^xeA*YDu){fP+ z)5=U3rWm8<)V(OjJ{->dg1(BsOg`1m&fLO?gut?6?;Q5p?&HX>otw0B`#Vd1JN9ug zZ+PQk=Y3|MouQgt%VAQ+7M4mz_z(J^mGO5_uD36x7}lU$2RZu_?^jT%x7vZ7{3n3q z8CzdM7^}9=^gu3q8HYUlwUrIZld~fSE0_xRkL)LINLi>=INyhCm@DTFVlNE01bgkz z=UU$d^+>#LODSs-OClqD(?4s)%bg>BbVhAb$}w)+)Ts@kuY5I8Sb-Z{tZ^fdwg#9ATRx~a=u=qXn=_P?#|7mTL8Q-84`+p-efxWxP!Lf`!G_u zcOQoR1iXhEy&${~*wxaTFuUp3$V~WZDDHQoN5!mcvhy`^=r!*ddYKmIReyn}Ek;s6N9~ z20yWv7*dUS<4Foa_emwV28n12Jl2a-X8T(tf60ua_4P58+G7 zA=YnUV=Cjf7&QaIV#Nr$Ky~II;IS3zYcZ9EA&`FG% zp?R(OB7fH&`fA7E+ghie+X$vI`b~_Q(YwvOL_JQ#q(1E1l118`(+&hv;jtN<{R4F` z>uw#vNic%zVFW*kRx!vHRtUi1T8&l!_ z!94=?gD`^Ypm+a*`dUnd#{l;_yiFHIFxdJnY)obR7UOInGFI(p;4vI{e1ZB}Ol9yB zbIFh@!!pE!9(P~_pTf7WF_oc{n6HNB8P>-e`f34;VCkRRG)!gmn^+S@?`BxIVlaa5 zVFZhvanLXo9veKG@SZ!cqNTx#hQX@EPmFfOEWxW8ZkNC^?10MqIbazul_9&BiP&Pm zItMEn30AZpSRYJf^pBYB*eXHp`GXSV3s|_iVBs*8F$Q8qVaq35QA}n07Nce$GIq6O zu%g?5M*>)COl9yBqh?5zu}9s5w-jh#MPI_#JTR4^lNdEa^Nc-eCG=Gdu%a7a$H7!a zzll*ZdROdM&{tqZ3xXBh(`Kb);qcgCiwbY-g(}nSP-VJ!vCHmOUGC8N&+YZqiN_z$ z9+PQ2AhrR5bamK`pWs=ETQZr(0Aep7x+f&c2*G0y zApYDnr!1y2_z62GBPLk&2(Fi_9HugK5_V8V2+el@kA#FgAr+(JI^Lx-`xfDcY`lR-t~xf_i^`tt$gmm`qS%Lf)UUBWZ`IOU?GpT$ z7I7)U-*4~%#FL}%EUrObtX_O|1ykL2eMn0@_2;?Wen;f;4PnnB73EIeMV6ys$LTuT z68vF_e3Is$a$KMj-v#l%PZj_kW4}eSgPV#g$MZNxV-0b?4SaKjUV0wDEp6NYvF6rw zEw)FTGVSgm4L`x{;+CLR<}zhJ8}27n;7%3y38uo*!rMqj8=(f`H{-`)N&y==&C!x z-2Z_)AdWPgVOhJ)lO_LCQ^8MgPve##L+EZO>#^KNF}J-$u)L+}AE%947v~?Ex~Sit z9Ht#!l;GUQ8F++5d$SX?18KTQRj|Am?RDiaeK$Ld?|&!|0Y?sNwKsRydfe$C>4DKZ z`u{~;`;_D*nz#U>^~#18?}ff>``B0oYl~&iJMRdMuThG(YAg`rT=FqD|Dwvq*4Y%y z9m_tb#%k)49KrWp%ms+vACt*e9LY-KrEfHTDve{LDccCeHF|dqw7~sq}hK&@fwFDb~!pud!1*LJiibx6!<0p6q~#3|^SB z9`Xi%g_ct=m3dPVy_{<1y-NO$sQqG`R-)}V(k=WC1ki-_H>~+fg9075;45RN|^OR_iE9h0!VFyU?nw6+ZT<4Ip-0 zKa#SgR5^CZQdYsTW1ak-bfHxs%e&fgf%vvA*s|dMhp1UcMk#fMmZ4obDtuXjjfy4d z3OU6ou(mQ{!tEC+Q|b=a!hQ`>u)G+Jc|)$j>D?)9 ze%P{#cbY3$UW{&1p$r{#SmAE*LaGMwJyU3dXm+S&3FSpxS9&WthM$kHQ8C)36?ym?aGeeL*- z_6p{XW#_H@sNFIc^PvK){=(VD1vSPdM zl0??yn$HZs0=mR^_?#mCOcq2iX{-6CzCkm&;>S&bPvmEqyG zbU|DMFZ10|#gdFHWJ}AuF3(5z7d-ZjUq%97QFiTWJ_U2f2;36fhKB@_R|{iVo(Z1H z^`1Xs7F4XjA5F@wVl;haqBq(^@SNUGz~h5fAUZy|2Aea$Tk#(8J?2}p2>zBjsaPl6 z68Ju|evpdiRaR}>C4#xnYmtp^iHP7oFF2~Zr)8(Li~Q|zecjIw-6_q-t0ueuAOCl;;Ay6y2&%=>KUogrm;`j)&Z?giWu)b=HR zBOL}dV0+^dNvDC{bmHSMzT}guiX|D9D<`egtt_9KP4K9ew3F0=uV!ufe1>4|7=c@Y z%$kTQ8@(k(v|4-pb*}vtQYY3 z*v3_v1#jPvtKCk+Pd?6%rz^Jy@>XknRjDP@;L~a3p%ZsTn8uHtVbtbL1 zwPyP#-yoMac+#`C!+6#0ZYoBPncI*~JRitg)Dq{YZ@+q&=iI2ly7l!^daRA3UY!GZ zo^FLy+zYrRm{*1FkQR1v%=U1qHuL3t+ViLn|7%)+iY2+^-H4WN63E@`eSyc&8EK@> zp&l&ZK!^o%#|YdK)Qp>fX3UsKE}!bpY-av6V|g+9+S(2D&`2-d?C&6us=zvDGOcMn z*0{Q};(c{J&G)7t&$c^6#eIcag51GwVdUG>o!Xz9y0atoHqhKf3-YQB0@bGJDYQf< zcYe4)kUF)rg)Z#v!Ox8qJhB}bLze7o#%@=7qG9e>b{R3Je=kyL^k8-%XFIcV%MEnl zU@u0xJ~pT~Rf#iyKr|Eb6N*|{(*FXo5Qa1!?NA;lgKXD9CMOL1uc8hU$jzeOP`Mtg;xqjmbbbNf4@ zcb^t_B|FZ=Gm|B!q&Y?p8Fr3dp5@N_`-TAG?^hvOmn!=$N81f!x#yjwciXt~5&Hwx z=5?;qa93BZ-U(2rm%2`mb#UX`ZG`5DF6ovneuOzq2w|8zmR&}ySY#h{7jjG1Iv%!Q z?if93!gac*sXPDnQ1H;soi#@;ZpM<5Z549q2JH^-^jRDeqMlxJj=p*B#;2AJRdGw; zi=JMu1uWaWfA!Wr49i|_%sm=8*_Dr5T2yU!_%5As*^MVNu?8Ox->R+5Rh-2*1vAVY z%Pu3zxK`Ju!`Gl~f2LYqhTfnPCcE?pA`0pc5Cj&>-P0m9qvD%_olh?w4MHd z7{A4j^}1)zx;r>C%pJ=vBPP&$+JWSb%rRt43g(W{lioj|TjzW5eTzk3y&2fi@^_;~ zY$b6}Ms<5at55adk0%GJ4F^1+>U4L$>1vRQTY`AWp%6C6Ii56eF3+&+Ayc2wM%&%_ zx5e}nY_ByWrdr)BBmyLwA^K$(s}hg`NN)t)B~lT(2aM!c=d|DQdAYjV^w8# z{I8$nMZMD+mKXN|ZVBqPeMhqL=eC*iP1$V5@?x|c-`(PuG%s7XdMCl$F#@*)Gx6w9R^pkP zw(63DH0BtMXC=%lm9S6!_K~{r&J53Ryw35Afeh0yN9|7e>MXKhK?SchED4^+@J+q4 z!EB#uW`o|k5zHMUa7*Cn4{gCteBZ8ZIcd?bR2Yq|1bhio4P_I28o znXE)*Ed%TT;xnti4d$q7T*Kr~%Ukqa_ z+CH>k?ih_dK=4c47Mu4quE>542xC|hjK*Fj+%ARXit1l4S}VL#_II)DxFwURW~)Nv zM@&4ky_8eI-Zqv*)}!~Q9%Mg!kFJaJsuau}BXCQw8!YWX8hh4cX(gN`za69TIl*Ll zRWgP&Z)M9KW@{`V@c9FuWS|=GjyvfyyFNQP#ZfwQVoC7H0G@I1J);4`Cq*nfZVBw}k;~>YUu&|? zaURmS7RLkd85b&~M=v82&-P{`C*~%YJC5cIN?E zqUB+s&Se;mC*YGXKI1~Z=++J9>RaltQZrl?9J9cZV4X~+g9VbwpO-qatNT|H%pD_e zOD0q2I$ucK+}12|NJKP_Utlzjwm{Tiowt$?-f&!h&0Hz&gLT3!nM^V5tC{UL)ndGo zrxd@!lHm9ZeA#;21oEX}6IQCxD=AWh5pw+MZu95F7T)IYX2BvU4u@sO@iOpzyb3EJ ze^h3(TYWc65jqs{!jUO>b@aK5(H)?gd__+$DV~TW!4Wo->H41y$uFC_j6QQzFn5fQ z+!EZ~4OkjIVoD9>IKo?s z2xCcb#1q~^8(4+d7l>u|9=j`;J4VP6VP9n*2^pra+(+_Ak!_5|5oq|5a=4xHqeUrJ zB+^#FF>f40#<5=b>cT<0==8zWS*e#kQiL8$f@9Vu)7zfD#QvE z-jUL|lB5Sl<69tz;tY38c~YVpOE_Ify7|Gf<9jN|{fJv=UVWz|8=kX*bi0IQ$G2JV z)i=*VWL(z*?AV@K(hU}t9p9M2-NfsDByZ0b+U^6*q`NzO=Oybgu5F`~&+V$PN#BY{ zH*r{YeA5USrt=)lwv7TA?W9V#eOPvU9|_-BAGO9jEQc*?HLbaH2Z?3Jcb*VW-2Tfv zvfEB=*YchUzNy4Fiuhg?zE~L8Gv%UxB{pGwfOMCNWyd$aP;ppmYs$q_UhJh)P3gWC z%Z~4dA)n#()s)+j*R}RaXX#ED%Z~4$O{OwU=cI&}?WuMBIatBB-uM<-*5lZuE-5Z? z(JZk|3F&Sd%Z~5vAx0K|$Z|R~I}54ORJuRMvf~?m@I~#5Yn2;L(3+_Iq&s>nJI*42 z{PsDWwUv9uM|;N)QSePZzN5#P3Xqff=zGe>PbHcA;R*`QrpSGL8C?W7uC4rYsyJT* z;_Y=qwY@!WYtve_lQJN%>@wox!@1g!D-SI8Uj3vj3oJX%1A(^)?meVAyzfkc8h2E1 zE(Vqz=bAuO{PlV%J6k$p8i!^$|J*BdN`*HG6%Nb)_&%gtc}0YT*?Z=vdf6| zP0KKCnJ@8<3s*3AEIZDP1F7zoXM;NASLRnfOmJo%&Q-%LK}O1$0@{?i9xSX~4F%^R z;+PeVOhMk#u_A1g=Oj%TQ9;V z$2FDWS2&)Ca}~jpsaamza-NWW>Y&UT6R5|KZW{1u5^_Jf&C@1!>_dtL^pp@dej&#I z%#qJE_wMz{hRCcMUcm!LZZH}u)~|okMz~xi_G2n%*2+N5hl=A@7!B`-d!CbdMtUoB zqML-k(K>tS?2+jjU^-lZDGAOei2kK*_n>c(ngoxLKbaQz1eA+SiHlUIJEfAOozS#mxedO%HpZ+e| zuP!5`J1=}ohFgMn)*O38T;IF0hrNnt*6>1|kBU!s_=E)S_~jqS$Lk&}0#*GA1a23f zcTJ{Ge=Z=?eQa48e5o5h!90wNc+nEnW-KeBblX!!-GGkXW*BZvnxT*O0qoMMnd4T0rszvPJIL!%@f*!RIc5kzr5 z%_28UDexA7b`k<-p(WOCnDm<+M)sMRPxQ1TNo4_T_G&7Ilp=h>AP^ZYX_!=Tzh z#XBd?xrH0W5ofeFJ{L$(n|cxg`wtimaR%?4mROfb(KXMHk`P#1>_vfp_0I$?@8ua} zta}g1zrs9>6)dEM%KK&EY}@maN|n&Mne}Q=gQ4Ob2k%5sV`3Z3Dl9Ce#0^W95P09k zXo!p6bYYXThbqaZK1m4NKNt^Sco;?&7OtlvP$&>LP-%81AN5^f33gTZ0Uw_k{I+kb_Isqn5QBj&{VuvR%D zlmPffE|wQtXBpu$+nc$rj8O7 zYu0el%D4@eP7|0)p6%s6&myI5QnX>PqOg_0D@sQEx!g@js#B4*>bi?ytA?!swh|Bv zf8?bUeQRcCrcKwd)yKBhKxA0zSL+hUyBZs`n+v;0`6bxS8&ZkA3$nb|d0UFob*dNL1oxhRhyzg7_y(#P zJEQtqL1pxh7&TOz1&AR~Ik^ogC+DO3T0v!uffzMZ{{@JDtFIMQ211OQfq+U)K>Pzd z#P@4op!!-tWk@AP&5#NzH39K&^|gY^&|Hj~p*d7)0^;B5YXz0jyJFOg-i4YkK>S;M zt)RlAhAPGY@jvQorFJpDf3L3<+_CIfC-@o^jNk_t!E30#R%nR(2lpGCYoT|Op?All z`dZP8cnt8^{Cj<^7%2k*)qt6!nXzj9phCJk@Hm0$YXy}d6;uOej%J2sr~`UD20fmk z`dUF{Xb#nYnWLFueg3V!R!|wECf0<}yBQYl-|A}x6&^J_n*X!DHnUwZ{&>y9dsyHt z1;ZvkGj~DtwSo$d8n!F{USBI_A|5qtmEbLc@Rovfu%dlXeXW@7c+{|cl&vVHGJcCu zGY}bj)Cs7s-3>ejgQdn)hE!tI45>2qC@1)Stt(j3K-dj1m7%#9HAC}^J?h`;YXub^ zHKTVkPLTgrUn|BIj~ce9|FgbUnk9ISLH@3_E;R<#*NS^m}5WAr+br7nr z6>}G_4;k@q^|fMs7znYtWQ0+}n~dsf1(hL{Siv&Fs1puA^|gY^&{kN9|BLv&zE)5f zD@s@*8S!uRwSo$-sQ-z;^|hHi#Cntw(7%c}(`NiT3jJ;TJF32FR+oO9T8cx|QQh(W z2hvE7Ol9p+=%@eDSGrV~$~qqZfxuK-EYE_W`tLsw zm%rmL1h}3@_ zkI^s~@K2v50+A|yTluB^{}GtVs`-B)FqO66`2U{=rm~LBe<1!ZRr!BM=z3>y&!7Ty zre&}a!2cF?>TBLO#D$pO4Tm_HF{=e)nJTE3o`}|eyZBb3VMois?+Snz3y2sUu}sZ+ zB3qvf9-<`$5NF~pkYWS6=sdC{S*FIMHKg~TE=uq_`1l|#Jh2G;-U*1ufC$hL_zAXZ znBQPP>~9*RWGg~-9?-j1+Xs61r_K_p#v%4P536N>nXyd0vN?~srqU<Vr22;P*;Eq-7$Osaa3-nV4xs zvs#)02(K~&lqEl>YhpZLCR(YMsre5UQzu+Y)_FXiQC3~pgu?GNfbaptJRPx2&3ck) zA5-O)VgOMzag>rVLYY)Cg34-90kKToa;u`6y-m0E5R>_LL?%_eHEn$E-8Z}2;_*Wvd#KpX=^ zy%2jHfvK#$`x{~dAgr@QM_6ZrD)Y;nJ@9uicMrh4vMoY?lPYtT=sc|R&5E$jb{%0| zA3BdLewnKP{yragIMlyDddx7C(tU`uo!SxO8W%fy`cqzguky16!gaFcsJm(Yru} z5ms9wW{Hll&Iafg%ulx^VqU@Dt+s@LE%{9<-Ij=1qVurMH!A{ciJ0v=!aA#U9$EZ! z%OKVV{M~9xG_WPVNtHRrqF5EfK33ep_vc2DaoksWMmX zZ-~V(OTaG?wgeEFmO-Zy{4)F!?5`lppd+m7Tt|SHAuI#@&a^A=dkF9VpFym19g)?G zSo2IP0f;{V0Um&Lmf*3)@MPQDR={ zh%CFC*}JOXk!2InEYT6x`2$p$vqVQ^S!(Mn5#FnT5MHW|$l7s^s{d#I5Wc7(70uWu z@UE8WSwc(JSt2}39RZpP4^ro0^(=L%Ko8+@!f)#=Q8H}1-n+sdg#N)EfIdsa$s7J| zoh8ESGe%H&cRC`=FVV+Cc!ThF>ns6@Oru4+S-x7v?+m-E&k}L+hA~I}l`#{o9%LpW z)jCTA0)8WJiCJff&?8O!&hkYwrGmd(XNmBAbcD69xIkoi$eEf0!a7TYC!-@^mWc7t z5m|ma_WF@uq9d}-ADJTv=*$s>-@E!`BYP6AFT#6~BvZyb!!P zI93%BX3dxzE5Dj;26CdNbkh+lgOAZ2jZ5eV11%8N(+i+&o7I~mE}`m zL_%?Aa&y)>a(-$jCM2=)0C_Y0HvMQq)ebRJoKXzeQv`btLtRT}h_jxf+dLh(Dp23z||gT6BKNQ1sIc<5+rUs-Li zwXZbjD~X4-udI89-d9${{L`<^4u=Y|$=j;yh((i}xcJYitR7VD7ftUV!Ak6~JzG zS0t$f72Zp-5DkVuFt^X$oju;oHPNon6Fz1<|lXvk1XTdw&1EKnRB@>`?@$ul1flneM6l` z7Gmkhg5-?L2$+T7qk!xN52M`-e=d_p3{>iYRDD3IrLA*rbNZS5=gZS?Mw-CXBkJP~MX@9I3Py$%S`yEUPAo88W(U@Flr-V?Jtax_a6 zL1jDfmzOL}3wu@rcYU5 zk0SrHA^AGml9tICJd7t+J;V;D>tVEHGEI3@fvo*DjXd4d$IwHk5<3&idBXAL7wIG7Q}MfRjKD1YmA3Z)%zG#mvk|y zZ<`n4-5#`6Bhz!KuPfvS9)GjZ10sSSq2D(Gr~Kmo_KO*SRXL^Wp zhkz=pCHQ(oVheHx`l`=weYNX#C-th2z54KqGspa(!fkY3a(jV?vb94ECO^sY8Du@~ zZz@85Txg^m49u?U0rpCdQ#MGRq>>arwfUUuY5i=bsYTKQ)eWmt!OrJynV*dHjaQa` z%*EspYB>;H}yDiV`Q!s!IADZ-%L`9zv=t#QcOW=E&ea%8dfcb${3J zSYt0wS3BJ=rFwRro0ez#4E5=*a%%fge*nK<&s@o&Z+(?M+mkf;iM|hJddo&j5X<;= z-aK_wCuLgeE868sN$}>8VrpxT&1tnZOjqlNmr`q86Srj8Tb}D&jLh58PRXC`mM)bM z5uRa}q^|uIs_xmmEe*G1GL`ViLDr6mS87M()_XULd)9c!h$Y$$^M{h%lnZr^YFHAi zxh&Pt9{EWR(nJ~dIh)SIkP44KmJr@R(=UW{CViD0YLc#pIDce#6Ip#Vtinw7S@DXh zX=ViULivs>&2vf&SBeexmJsWMW~#~KqScWP-=~huH&az=DQfOswNg!{9=s4~dS0CD zOeXnB#)%~((u_|pU51q;Tk{WBeoeNsU_^Plnd+_-MNJyj03uKr9lO+@teDyD` zh5cp5?aGp5_7(7JGX1qV?N+?v-#51s`Ycg>GNqVm(_xdYhjsk*-`4pCzfXjum{)f1 zq}0iOP1oFba=GjbwN_HNy5p~DRBmauB_E0R=%+;TjJ`4uxZmbXouO7+R8Fn1{tw{M z;cz~Z>ef#wb5icz_P1uJuM^6vQG2RT8S#BvJ~9Tz!x0ep36@Im%i`Vsf*bMt5Tmg7 z{xG*PZHDT$ZoHZ;-b)=b_8C1;eT2GtXMXjc0pi`CO#tBnh!cRoPa1X_sA})>swD>G z1gfl-V2}E1s`+kAkkU9iRdBm9Ri+gM&2P?iAXP8cSMI!X)TOdoYFfX?G_}>&K(+km zRNBZqNew#Yr`}t24G@hxd6T5;?UdLbxApNbM(xi(rm53xg47$AQzbNfr`qI0CY@=h zj6Ix7!R-pE41VIb(Gq0#gH+W)s%yVVg(Z>oQ?mbK&QZl%NluDYUOergdTe!6^PF*1 z(Y~bjmGyKFzuSCrA=_RBC=R0(UGuCbSv`td$~@f>INd3~w`+|c{KjKuwaR2gtb_8% zJ5E8qfh5(RZ^G2Zhrd#v<>HN5;qx1l@23hV<0Gp}Jo@!-tPZM?U5$9@q4t_(R{hK- zb<6^h%eiM>V{#1;>j8nE;C5wc3o3m`_X2K8z#mm59&NsKQlnSdt35-VRri#(sz1C1 zdXZm#;E_Q3ke+}j4G8=MOC|FVK3vBPA5P~1-mCEXB+W&SSbaO-k$ZV%vT^e}61cay zBo*#A8R2jBMO!Bi(hKYYCiL$w zNhPSPX9Jx_7DAkHI%J%2bcAt=vyPg6x)W&YsR(%Ff-}wxIOF^|u!SU*pt7EEbRJoV zb_ofjP0=`Zx~HAQXBuwf;Ik zt4?VUBQ4aDOt{^Nm0iemsjR)5c1SE4P2$q~ zvID0kN_xC}Syo+or8@7>wTXm=6aBE3r0_F{aMolRZWoQgZ&GQU;z`1WDs1&uPbR30 zv;NlGBCD}9|HI)`nwXW=`Nm((n_^1M`MA#KQWxov}XjQ>wuotq=VqY)A`VAhwAj%Z|2Wi*vlva4%whSVA~E zL+=vk-HN9tYIxLe?+QfL2;TY{MNYuGyb_D8GvgVDXNf=<2fh6{vYcLl<*+8MinOGbo6M;LpNKp4A$Kp1;T#vZjUBVM8-j2%)S zj6KTAL*L;{rnKv$N!2>9$<0ko6uj#Tgf*6-TTyFd0<0*9{rnHu&qHB9$371B0IZse zI0_(Mc;q9#^&%AVsicDaPmGqmOlR;Dcin8KB)`8+uz!yIMA_?W4_^3Q@WOk5PmNCy z*b5hktg}x!INi;K(_LXW-Qn{RKHUjK);X~{oV<3x$tw{~Uih?)PhN-ztlE1M#zfCq z7Njign{m5j#4-exaqgGn0mbeujgDS-fwVuDal2&oEWu`E#Y^Nk%1DS`X%LfX3^5rT zr@}EAG#=2B19(fDz*`F1+nkAUHezJrw-JGo5yJO5o8kND2qSWb=9O+stezV1$OE3t z@eEH!M;P%$fiR+jf`>RMi?wbtodv&SIQS(KA!aG4j3}r0ZNw}E!n!^HVGmx$Oz<)` zLL^mC8BtmB+lZuE^$3(}wF6wOesqKp zbr$1cppjId54y)O&IXzJH%4R|Nd*WIZ@1pc=m?l4nb|ZjOZ1E#fylBx=#E84z)3MP zHwI2Z`pvjN7~TiuOjvJBzAer;r5d*x*7>UE%m{?xKfqlXx-k({Rz#}tTilokM3$u% zJjDG+@#KsMi&ZLE2l~1bJbv3b(QO73R94M(gjEk6VeIp8+RnP0&=J;~1{hm?Md?{6 zsISDBXWUwfn+6?W9YGyo+^Y#hR`fg@jQNKS&YBn8_K9}I97S2B`fZ;;WX(kDydp5K zbVSzeWENT=L`xa7-8!$t?W-XbHL^+#w3Uaj)LD9n+gC+M1$qbsw3%rcq!SXnfhI!_ z0($6(tlQ$O8(zc%TKe|Lg%qu_DSA)C5z4m7$+S&%ds^~Q8&&*Xa{p**snB-%ZeZ*_ zCR6sukXKuIQ}kXd0#o4~E(@_fHeQRk5JVbW8K_j+5)xB-Y%V$}TPt;nHYRmqcRPBd zLlZT7hrukg{OlN()DooHRlJ|M<$*{`{TibrsYbUu8S^r9TxuoOR;|0uhHiRzBz5Zh zHh`$KxTK|LNUXWl02zV#jeZ{z^VxekNm|hw5EC5RT82l>GZ%j`Qo&C!58Na0rP$!B zDSym;WtkT`QkTlm97|GuZaq3}FioquzZLM5z7Y2)JK zrJjbf+6-4R&ZfIIxXD0?M=cnSmA{szeF=%z$HVX+Os2pI6-mGKo3(zGdnm|qsu3y(gS6=xz{-@ZsH{)@M#o3z;)^Pj)Y~;qdV-&EHZ+-9#zvEB`LZ*| zS@Aj#!|THm;+7!yV|5R5efAqt@my0Kf&DAPL+YRYk`D2?Luc7i(7bzHchc4CB#C8xMc1|_XEzSk^)Nik>AhD{|K_`C{c-iwc`(QBPuxN4`^JGD2lBg- z$g_#W1n(&lk{I5k_-)AUvwRJ`7qXWo+^7qPlBx&U^H(DIoTHzD+Z70dA8rZ!#DZqh zs>fF1c&598+xi`C@P^qQ8f97dC5{ZLK2)*{{c2XFZS&5jdp|W&ZO?Cs3GF(TPCM8b zr20roSxWuci0pM4s^BNsGRW(ENYl!e@{O91P0xo&2z5|}7^Ui9n%l04iqWv+xQ;Q; zUzbSA4ILm!g?n^{r9B+;50!H6pb{ z(8KHb00s9b)2|UN}JchS;%=2gbcA8a1j4Xgvc1X%JLivxzS?z%fjYvl zuL5E0oI)pKUxE7b(QC-$Q*E@gHISHr_6%&>WyJl7ms9F|-yA*h+9(C@OPC7xo5^%+ z)F#X6snyImj*nFEE{yj?c|80{xgBO?|b^%MR+-peX38CF|#r)~6dO?JGSamtJ;J8}=x#x-8WwK5gSuxXD!f=Xlbz zuBud8;-O#!zGIPZYc{N#My_<4uauUJq;=4P1rw4ISK8vsgjg>YRpGpYaqZkd}49h)} ztQyfrspwRilsi5|UDBq8x*^Bu7%U-e4!71huM{P&j|VGXHH95Gdw{m*dQ!{>&ztd1Pu4Zku-rh;;a7*wO4?yey#7RKl`(=#4EkTs?a4n_H z*~4Vl_vgesy{uX%xwks~&s{XgmZ-b<0QE|>sghlR_o_J#Qc69cWNLB+@=mFs&bc)~ zz1620ZINzPtA3uKUL1BZ#=Nhr>hpQAdOPr+7?Y`1-oeT(zbNv!c__h8hI*D(FZWAU zr);c7aZ6Bd(6YPIuzG3o;NmWVsUl96R10=bR;zW2{|)isW=~~b%Zg-V%4&k`AZ|C$ z^%824R>^9wqg`R0H=WTD_4;!B0Mp3Q!{hlU0Xv%YW0npx+3ke`Eo2=Dw%p zcFRb0?UKdnA;>e-@}-<+uT(dSMLz1*2I-ys{dElbw*W@H0@E$ z85MQKEP^PCNDzhTW*P%V%os3W!W=<@B1Tk9YgWXFilVNrn1LDYWliXcdDon?YtFj* z)rIBrY0i27%{e_!S5=3q>h9|5xD}dkX*XM3bHAM^BRcGu!UuIqR}1v1smdju;$7$( z(t&gi1GH(h6OBNk(VA#%b8aKn7K{}CK0A?!G>|s=S094;$@gd2g1J9bEUDI|xtKCF zT-5)dYFHEbqR*P}mPSEdyZSTsvRZRd`ay3oIDfKamvF?;E>4|5-kWyr`rcZ}umovf z-_Sd}Mhm{Pv^DQ`ehEW+hguEMG_FXu-zD81Lb@IQLfu}faeL9|{CLswXgc*r@cDK; zL#xCc`)*LN1nb3`h{jYqZkM%Goz}{ipPE)#>~WeRN_D)Wjjmi+oY}if)W7gqLkmYc zUIX)SJtLO69_%DpPP9vCuP8fyw3%e8=zhY~bF?980j>uqHZ>y5z={lW`$T$5Tw#kQ z(-Ta`%=Ti{IZL*ljteib{@t&!Zm#V){)N3J)94#nf`^>7n#3S z@=!znQBjUQzryaj*z>XdYjXSxJqsBzreq5?^IIJ*7JEwwJe$BX3wi^z@J9CfiyaRd z*;qoLv>4|=c_4|#9HQYtG_V9uOpsgh`Uo+L5GozqU7}dOQ zU8VCV<8KmT&tm8QIw}E8t}9GsxVQ+lcV**dS$L21`Oxkw=&ovFNLAyL_Yzo zDCM)P*n;n#XU%(zUdFHly#ciIluy5H58lh=I-7E1ljK>VKZj^~1;fshzt~uiAKLv? z@-nbDaa7WY$-W>Se)bN#bFseUk)bbw+|sFKVi1V)?Unt@h#=Ns_;CQttQa#3l;g6n8p`_NTJqH&IB+&jEq#T6FP zkk=o3->zo2yo33k1MyPyC$5TcWl7^It0*sDtQGeS-zu$y@h?Qv8=%b!@t4g#`GV(< zB?Rg&S&O#GsLw;p&iv5uMUrQU<5gY>e+pQ^y1wec_e9*4&ghXVnMPFyXMQod3GaBA zUhRP$2y9VoX^JY|`3s*>dtN>)|ouDalPMZ{j2+lL+?vyGyk?1LjxIkOSd0}sMc2oscv@Be8J4Z#)FbQ zMaAmPgfTV4$KAK9D0JFW*pKPw^JlqfqWM)1LX`gJx!U1tQFTtODI7~uy&Cxp+dfTH zuiHdmO^R~o*>knTx1#DiLf~Ho!&~sVw8Pf_b6!Mv*azLWU4r^Jq#sur{$^U8)JUw3 zbre^w+%%P~7$)-Vu@Ue8xoJwBGf_-DXoMo;c4+AgVh!V z&;4bhd&i|gLil5STEAUniS`< zk{pP}J!^{Oc&MpkcE_`|!(|${FOH`twC238slJ5RoCkr@BAQ;+Jy(uZTJa|fjR}^{ zagY<_knW$)s>^2nrn9Bz|DcRZ(}+|e;B*`wK)*}q0_Y1X1WmwT|5TQo}zOJKK3 z59e5deU9^=;w-04WCQpUc5+B>j(_1YfwJsND z4N67vBQs9$??>y1Lc@Kexs5ZJUQGYImu>v9Mr~DU3}4oBx%PEgC$YFeePL5#inga) zs4$In5<8;@Xg~Ibh(cwZX_Wjz{#(Qubq{yG@CTSu?8U8to z1zcOD?yNIRk|Tb=F74Cxu3{m*(7x;4GA+HwL}BtCuU_iIU0m-q8T87DXDkM`sJ^(U8t)iW(3IhOeD>Sx;Dd9f(c&RJkhG;8mt=_vud z)EPZTN!9@W%G^5E^x^#y(Q1h$63}Dy9=&Clk6P*9F&s;(4hc7P*uPXHop2JU=SlCz z?a`lw`>4;pjp6v$sb4pnT12lAJC{;!ZLmb-i*D(3r04Jz>emj@eAe@a=_h?+MaCg_ zNpjf^mRr9$&Ha~~YQ1ey9NPzHu#DI`NK3Qp9iY|=l&!Pv`+DhBMU1$mG!aOf?!L~R zoHmc_MxT;aHf&6`qV@P4q%{R6*|@jV3cE+i=N7p-eJj zMM5Jzq>C4umxl(P4ENaJE za*K@raX>Hd{jM51WRx@#vDe;L*=uq?|5B^6*rMTVR^8T5cWlVc-wWbcl67^fDLDA9 zc6pm?o{>0&F^E07Ntu~)ZGF2#1Y93>%e?6wpErZMN&XmKB#6IX|B zPSqDIi(*@*kKtH?XWK}d?rq!k(o07*W07f;9S`Om(vT6)p6UA62_;yie};3E7U?0H zBAr@(*ULrTRA)^H1^m>$~(bvx3yf!DBgU9MlrB4l>i3)pby zx88RjhjO$_>KnsZ;0Lnz~n1mE$iw-VPn>a*qw8-f7qf9hw z*Ue@T9oMVXN=}q~2DI%c6P@F@uTT$%7hx?6MoB&c>OmYa_O{Tl0;5+p@BVZG>I(`f(C7hOWW zD0-~ui^_<*LwwoV;?vo~)bWxBfFncpcQ<&ZcwMww#dc2!k)n6-FIl&T-(AWUm0HW5 z)f*~#063OpuChq)`jFl|MS2%kSg3d9c|JNwOZ$y%loQz~T+yM8!roMr-E$_Z*0VaX z8WkcXPX_y0mctVJu{$zD~Q|tDBiT{ico5n#A^CS3gEb2#8xT-yXWt zr^v_|TK;X8%oH=fj7yt;u@9RzF~Y#Vg3OLS3)922=NAL=ApEv>O-s%6V=H$>8dw){ zCChPomosx~xrJ5r8=Wore^G2^r-kdZDLs<4UDlnGF8s;@ z7Flx+t!8((R2w>Kdg zQOX?lXaAQh?Q(#DC6;>s(-PUEB)29-xwyxMB_2J*s+=B?O(R#@a~1b!i@Ky~Hx9Ko zdycxMUHEoMJ2{~R(HMQF6AP*J4_lEMXkZC)h3%#&e-VwnMB|q{G_a+S9@!6y3ad|1 zVXfVo84&%I%{$&b$juZ(=V}y_8k7^0nk`3eiG`Eg`&d|$6e*jH$i2s4LFCea_*9Y{ zBF_wnFw5o&?@;8{q$qoS#_t+fS6=i_ge68eDMoz4=L<6GRvNc0)O_X1h;^F2{JeV>3N!Gpy0^cj&(CbHxxeX@2l4QYrXMKZmHoRv)WEvlo+$6L z{&lFQ)YLNKX<#?K!XpPZ`tn2rB}5KoM02`5FgoY< zfPw9Uf61*|kD~4;Qq=vp<|7T92RITfbLHn~hxm4B)*>2b7rk)wGg@8JJ~)F>ODM|x zy}enxnQvI39lf$=RIYxt{FSRwQ9sgNUtC3|o?O7JO6J&)T+3oXX;I`t8qN=D^dVMD4u| zw1Pg~<`30J3$F!^6#FrOXdEXR^SZ~oV_h&G1D86;$TAjMTkw2W8JV19$)t{`>mfql9HbX zS9C6r#*b4N%0U@jw+8GgF3pT;=1HMR}8$6bmXe{r_oc5Z%A6pSK7GSIA zaAj#Li-g!#c+(qifakQXMGo(JzIzdYni@4Y?TZpusf2jlq;@j4JN6*fM44L%agz}D zX7%2O?VdYV#9T)c&UuPeBg7^`SS6&nV!JoA^E8iWHcV9cJy^qjq7}=3Z56acamSM9 z>DA3Y9NURCTd!z4VrrXTZ0jhptj<6WeyG(-Y=ZD-M zmiLMdksNvZ12ZpR-{i>gJ0aS?;rp=_@peDn`p@aX!-UvqbxG<$7>Q;Wp)@~c5Lf#M z(QLL`GR`&ZbEHkNIE1k1_K4E`-LT|GW(BkBWKDcI``UD-qm}tii+XhGP>N_+bcsd# zT=Q+{ioJ&YjQyl2lL=uNSEbLaa>WvpUj_5G+djf(@oNoxlk)WuBApOZr`6ww2;7rf zH>`wNtLiS!a7#SgL_%0Jb;wjFchr5@YuKAPt!v?G^6fZRYlMwm$J4k&FI@krd>%*@=1=dp2hz9w3B;2A1I7EB60SIpQ81azovRb6b{U z6mfNiXzb{{(H%=LCkOUsj_+gP>cz?S`>>}#&*y2Y5TaojiHnw0mSz;#b2IklPdS_i z2PR`5pdCbRb4I(FXv}Q)WFNMB{Pl|F)@C6-jeTj75xLfRLsaK|Sb{Cxb_dzmhXaN0 ztOeAA3rG&jX#ab7QFokcIBOA|mX`?1@@l3{W6F|6GD{n#cr+U3@@$YGhancKtMP+AW&f*J3#z{dO}M+Z}ZxqDd#xYN7|N zCfelpc16zu>7n(ZtSW>kOo*(e2M(gPM9F0u7AhDLwBpN#xmNtd&pC=ZMaWgmbEM*FcpC_8maU-t&skAuteQbg{*e=?@5{KR8jf0PS zhmARRicJkN__1K0e1OGxfWW?ptJJQ-b^iT&~nIh46;@2R(rAv%BQn85{ zYa*Y)Bbv3M7?#Y^!wonkF?X4jsRbS?DMDR6%zc0RP3u&|Sv(7DNOIVXxX9-9v1Y@| z4Kc6;PE5>jl0t}8P79dd&QIRf??MeYcQUsayGv_vr>m$lw~qObIxDr79m2$-Ee?cO zem|XUZDYmGTpey;NvUg_wFjRfMOG&}GuA|_JEs^uWYJCUW$z{$f%dyiWi~Vt1KK#6 z*S3u?bqHB163;oA*{N}+O^=p{AH6MkSROjY=oMmadcVnosQGk;>F=4##O9;*CA6Xp zZF@{#S1|+LM{4{{ zHZMs8KQC`Ce?8gM!DhYK6;p$_8mmrYBMMbl_e~EoOf52e?ltWyGEaM&A9O3A4H_9K zx+?DG5*uu_+4&+w`drH@wf5des21zpf>3;(ZIh@S{X4Q;CJ?6&norM zpfM7S>H$-ALnG=e|xbu_Cct~_fK7-(cobgTeo73np$g^fh8yta!dQvPd2g6 z*8a@4$|&RO^>EE)y`vD$o@V4wMr`XBz_wUBvDo<&jYStqXoJq%i+X*S8G94abdEFq zta^W`n;JY~ilncm+-u7$t%(`Y ziqe%dTo`G%!KC3(lc9z~w4&(!ma20)6k&lSqYTuXh(?*{-d#U`rgzL@Z^a-3^&sj; zJVTGZPrL0ilwJf9YP@_@F6UDJgUY$by4sUW}P}xI#I+{K>6qu zjL=$YiDz-_^~nhaQpf#WL{m=L*Uj13S2vi=fFOx0>`gqOqa42x16jU3x7a?reo~*~ z-n5KhJjttW(Ut5#T!_@V$O-O7Qyg;Xx8Ck6HnVDN#~WCJ=e6j4(0=>)&idn5OPKGh zG1A!t?o!}B6W#dZfm2TB$P>%}!37ym*VOqR2Le_a_+iFLR+QEDsv3)_uian3AEYfXOQNb(c0 z*U(Rtd+-;UABAatyrubp;|J%5JlaFUYN@Sgv_GWLjw2jL4306%Dxc5n-K%+jR^>p1 zq^a>QnJe4vQ`yk01UCBGFv)V_{E)f&vZn%ztrN>i#ZQpz2mXchC|gke^#c1 zGdp)dw$7+Uk)ERLqWCM9mmS#B3Zo?JjJg)lwA1W=hAm&WO1(2vw$A9uqNP@pR^$Pk zCl5d;4*-1w^Z;b*{Iud!cA)8YwI6w}SQmQ5=+%%enb?jM+!v`n?iFdEFM>84+l}&H zMO@Xb;@nei&I*>iKJ@g^N2UA>V@Bw+Q%0*7e-Ag%ufr_QrB_&aVT^XG zzG2b{FKSMdNm1T?EXkL(Da$urt!yls?IC=-cNOmLS528!n~Og8dyCculTH2^-9*|K zKXG&L0rHx|H0p$S`(gseo-B7PFlMgZCf#d0Pxu$aujxd*q+w6c(XXC1kotRp`t!U@_!*uVF zCK592MOs!t^XnRRA~UL*=s&R{`P4C!`?JS|ym_PHb_RbwRGc2+DPC^SO_&=M-%ufa zB{s0ac0N4mTY2eq73@K*i8Mp&3vAG*{Ji4}A8C{z0y$I^>oXp#b0>TLpuTG0Uzk}H zGp^D;L%qJN=sE}9v{zFJf$z%5*;{{e?8`o_b>KmH5ctLnqUp_-Qy#22aaG1im0r|A zu8>=rwOs<)9tRu#=O#Y`CB(Oc@Kqx6WPJOw(iLs^kNGkJrA0Ko)#!VS#aFz*Dp&1d zm{yk%XUA(|Wf5zspXGUe+&`V2Nx#p2z2To72axNl<6rV9$#iw+mp&!3@%A;O88s)y zL8x?JZK|4LVhi2GxHV%%@UDF{+BaFb^IM~@FfYA~fh9P%aW>P=UA>BYUcGy2*yeUd zpDV>g+l~`N>oj`pEBuwV{r(UU>0xc&)9suV{8x;a*wr$2m)9-9trrOPenUqC|3Yhk z`jK+hZ2ZV-+!~_ZUfs{Y608?%A`LgF0WTa~ja{ndDM^kTnmfJJg5E6%@RB2E;gNCUQhVWj29nY&NYoV(m+%i7%!@(4Wm&~Ze3qKIo6ex?fP6o zs5ff~W7Qh5YuGjkO*86gFkk7K#eO*dNW=T!?YlJ>OQwel&ugj)^&{=D917xR|GL9M z`_R1;d?oDU^a+Zn7~Sw)f@+f7Ck_wB)-)V$7mR8P?DzpJ9K5i0%)m}kP?l(~9&tS|Qs zYebpMpX;a%ipEwEtNw};uYye`>`hvKIQsD~zgx2(18faMpbbYfwbieFd_;>(c53Z= z9d!w!kwc0cDAj`BoNmoa=*#rLfcC<9XplIuYOV=o!geDY<>1L5BoyT95}xYly&yeA z)1LmOEo@}f@qDBDHWhPT;k|ZzSBm_^Qma_TZ{zu$!%w9brzUm=aBg(lnKWI?WC^T%zA7Z%Rg0qnuhthuwJA`(K{C! z@F`|bZr)y0NACr_8mx&Te(g*1Voy7B)j3U~(ZnfS-0a#?9Q@MSgf)@&IZp3Jney@i*`ia;#*a~##M=iupwD9D{-N!om zABdJ|M1NStstgI{b}8{Xa)KOUwt1pq9mhPn4B>n3ZItrR<7;VH6Giq9TgvKQ@52jh zJgehh_|}??D44jK{cb;&U##sSwH5Z7oGJhI<)v&$%klhDhw?g>U~YYsNl|9EU&-8# z58>CIZj>_cV?KQuvELZV8qMyu-8xynX3-f-m+F1Ui?sz&(f^Lzhth`uG#Wm&erCw%DUN$BH5@ z7T_H}x95}YER|^Byp!cfn_UCHzaC=PrXCcvjKIe0=OG9kmS7Kn`hs zDDkX#;c%cpP z@oOD2Sepelk|%@t`p_GoJ<9{5c%fU~Ed2Rq9laN{`q&Ee5=~e>-tIyy`<~cII_E?` zTJ~ORcCq1OG7{PL=1f|pqE9V*$VHDR+{-GKRpgx|?-gkvn(mm;ir$^}0G88=9zAbd z(aSW}bSlqZ@nqF~g1>?50rcTz8cz?^=7-xnVfm(4lh!ymUeP0`%wOxqu)>!L@yhO< z3|wL18W2xU6s7g+oot`;O=g_!CY`aM7cRH1ciL+9qi`7>;@m=dzZU7?T9nRM0ynU= zed_QPO&Uw@nBZUXy0&fm*KBK@{CxRTPib9?YYtiR<8}M8leF57r`0y@C*W#ZrePIv zi7jhzjUDxEFSQj)i}Vy_8IAV*{*(ceMmz48;AofUM>m>-w`mRvnu9pka1Np$q$o?< zw&rTI4NIUGr_f_XZ6J@UwE9=sp4Rq!Q{$S_ju%=0S@Mo!I~vZTz0`${<#`O9=K4j4 z3j49!GUyXhoj<>P&7^xcN+ zZO_KpoV>s0q7`c2B>UUkc&ZOZX46`2_Y@bg!V>R?@!J$fwttGT zc5|xwY+EfAOR!$KCR4&Bqxh#(H9ox-!@qK)g)DarkXy?9)pM9JvhBa>xicr26vYa$ z;Mh-;(YpFjBlgp3H7WEW3)yXn3`i1j<+p1EUb$p{>wUd6IST1>=kbP>Q!!Tg{c?sS zNDpgLl&$qA8Sj%0t1ed>GOQPQ$C~Ii`KzIZPv$B0u+tfa{9?UGkM_d5w>9qHx~3-C z{37)^Mrq2?xaaIT8d>TRHR?$@34!!5u9LXR>S|OqS7Ur@5soED1IIMw_X)3QO!~M> zT@l)XW3(Ygd`h=-l~;otj6T24QGH(eNOyR#UW`?wRZ)9)V{cR`cCwKR#}cH6BcE(7 zadqdzE_DrYh1BscL{kKv12;Z(Td7uV=E$)XksfkLuP*EkH2QQ|tNzXvjuG+LZrIY4 zRpn5KF*;_iT42T^h9ewD296j-Y1qTT_|-pF4WKt{Q3D_+@;pD45NtGDl&LN)aFL;2 z!f_>YbuiY^m=e)eO&G|fGnQ4`t<68qhl-i?UYRBb70aG0UJG8)e#z?DF2?Y8`PKWv z)4-DT)o)N~lBim~T%LHJ2VeaS*9!;L`jg5TSnoGh-`p-PROsclnUMuH$INh+svL}h;Cyz{66YYghw>P}M#Hr0EX$HnU;$L!1(Lb~68Xwjk zR=c$02A1FnFV;j^%vU)YdPW)5Y5|wzz=$NQiFOC?R5nJgJ)l0H-^Rdt@kAM8xfLbt zcz2^`|E}!slZr$GmebKcZ>?9D2oa0jL%Qg)DulB8CZfe zu-z!W#A&>-w#P=bbiR#x?ar3ywIngRVwee|W-+dlRz)e1#?8;S)zJeQ=vb08xKTFx z`4eXo)BX<7yBPa47G0lfyT;vo7I)YpXgYE?SnNbO8Ude#)RDk z+4f&|q#-AG3kGc$?Y-U_YuvkaNey_tSw{rQlslU(_h#r6phASPEZ~kh;JCkzB}fBn zqTTamlZ*lv4ym<|G|*-0KW(jyDAuO0(dF-b>VSuzrT)OSk|jUl+tGL*x=gj*U(Uex z!FH4T{O=ESjA^ZG+1mVE8oM}Nag5P+dytE9YiKw1cx6umXDVt5nMT9>m5k`L!fM^D z_6F(?jO)YMMZ0R-Ug+EEMXDihg7~Lz;n^Bzk9`AySyeFG3hgHn!mVzkIzJBr{VPOM z27zHQX(K|Mz5f{<&FxCN_*h1JN>USnStBr;grbzM$Mst!lhqMZBP9f8hmmt3&AJ(_ zZ~E%aYV4RGAu!hq=76E~`2cJElV8cyErX*Z1hxWZhoZb{H=^}vU))(UqJbqy1Lez+ z;||F&lH@?@D2I&j84;6qBh1-KmexHq(oV|u zhB;sqWn787?BKV|Bbj>#OW9#Cw+z-qZ{ByC!5Z$gRXtdkL<4iZVBR>&xJX=8aeD1l zjkv-R%s?a4xHrq1eR+RQ{Zw?aL<2L>U}hT18qs|Qo3-6mtwmg6334UVNG~vpWzPRI zrL|igIbc*`)=J7?7Gup?{>K%TAXhSt(o?GO_ouB@(?vgi5pkP|7iFZW;&)g zvQ4%5%U?IB5m$UA$uT=A<`<^;66!&#_nAj7QV(Lin0F3N0f~p(iB5iqt2p9n262Vdk#`w!uH_j1@=U|j6EF9(#bp|0OP-n4O~dTHn2VRLQ-$z+VZG}005luT@gebXTjH*nL5twBa(UhICMnC?^(Tc6{d&96UfD6t5?7dwA2Yeq-B&_HB-ToG-&~zz334UVNV1CJr~b892eAsw5+`99C6+ZH za)r5(DfVN`Bp!G1S2d%1W9j`5%%+SrDN4$-Nxbvpk+kLIF7*e#1tQbfNa~% zjy~)Uxpk}1{3t^6;}*>i)M_|Cz z$YTE-J!GRcMDg?8PO2yG8d59{?yAb@zJVS2ovNq2_8%^9r0vepSCbq3W5Sb4+z+B% zwb=vsjDb7U`1Mb9tP4-Wac@~sv|asp%fu^cYJs=Xt~1iZn&`&5Lnx2A{5JKMq$Ls! zJW2MN6O7oB z5&aq# z<>75{=vE@G+Sb{WUISM;ju@|TAsf9=mq>ggPh?@Cs zvqbl|M~*cfB5{Qgrg$%eb_ajlVk=6$J<`xsMqmUbqN&eG^5DHCz1NfESQknzb2WNe zFa6o9N9weZ;l}Yd4Sg&&%Dl6QblVBY=s#B?f8RKa&&X&B_nTzz~MQ2kwq=ZTc zY*G34S#zS%uI5cI8=`?FNCRn8+)~C1Jt}&O+IvQjfz)w5C?oE8l+^>rpGm3TFUmkp z@Gn{NhWlqS!>M{|RW;1OKES`^akY`g?n)ZFb~JWT_u<%;5%Hw28k4@-N%{(PE$S;- z`?Mu%FpsRk5V8hn`_O*K*1+P$(7oJj3ymen3Cfi7e=Y+34|#9l=bnR%KpMz9(vuNL z13e4bFUi5=$bksl3&mY^nFe_iWP@^iQ9ND1nq&ly4D>}%J{f^^;jRJ7BqNX$lmly$ z5m|Th41@&Pu}|{o9(z$_5brV?K2K+)w!B7<+)x}{bJzbsdtRI;Iw;e{pPW| zHeT83He0t2-qz?y8xVTsx_9q1swq>J=_)5u^A!+Eb=_Kz7~;w$PW&W

neAmH&-s zDb({}W{((-YRZ%|ha!@%oENDy9{zjA zsj9v<;@TShd;RfyBz-gANdp-@X@DA5)gw1?HF-RegK8gA6hD zku}>IbEOKArMzXjRdw&NqYSavvKw}am|K0k z7G)GMw=4-%A+oL&>@WoF(3mS#h^$-wz>V7zQ7sH#Y0Q->MAp5Fc(jRNJT&G?6(Sg7 zV-ZXUz2b3Z1eH@&saDEYsZ?8wpxHsoRd=OQk5~i^VcxYW3SLwy^*U|#S1ZON#z3l8 zBiolHR_6hsRGK|yCThkhm1bzl_7<~U^Hr&|3Q|S27(uNGrPA0WtLt2O1dkuQuY23M z>%Aj1jH6B|<%_Hfe0C>IT&Je7mhR>Z|D3sxQ}P zp3xlGUX803?f*;RdpElCg|3>344|5%QdOk8E84z z%wy1E|KtDjB|a&r1kp$`D#)k{qM=kG4~Rd_T+?=(?_pmTtt{K4Rt>QO2(i4bUQ{aa z0uc0Wg%`YA6JJ^Pp$vG``U=)-^1T^}*cjNWNOOdv6!5 zfRIeIn0uVXj;?qC2+72@_^O~%Pgm7y%kI54_o(KhJKd&HJM)aEEtkG`;yV^|%HHvo z4yvIJ;*7`Qq8(g`uYd?W5i%N= zU3;n7ln|gDf`ET6F)GOD3ZhHSdRr(` zAOH*TP+zHc#S481$)&EWKfzbR3%*MAQS3fY$X-D!v9Q=P#3PLeh<1o~p;gM=zPu6{ zEs43>VV#JX=(}^(a$l((;;W&SC&X-`rt$9vom_^*L-`gOmI#S+;a%xUjS?YVEPOTl zEKwP1xkj^;q0)tK-;@zBLwZR;rRb{q?$VoDuR3kkvK@^%*HtxP06nTZe*EROUU7?Q z-Kv`S(YX4%#~i)>_>abQ^onMQa;mDAzPg{u7;*UFZRM*}lA(~H2))8Jwep_m8dlYn zvz9d(n=ZZS5UohX-mV%})f_m_(qB(v7S$_UJ7UU|L0fPCVGmk;gz5FY|9*cQr&qlq z9_^FyUYvKI9tJ@f+y@n1RWBZLcze>(N3Y+RxF57iwO#C%`@i^tX|?l@--lK|y60={ z=bl?&{cRRG(55BdIaj~*d87LJP9Jnj#J~T2#0(hTx_Qb|_!*`WxvkZZSGIaSp!U%Shu*Mkq+wWIpd3yx5aSUe2Dc(9jv)TFN<9@&Qp z!KttCuF6nORrNz?LtoAPue;jX;kc$e*2gyUEnw>tzPvNyaT6kUDBi_xxYdg)su65rK5b6N^MGr77=W_w1X9;8d9G$i?-xS zL)L~MI^0PWL^T}Mhg&=euLocKzaoNGLBl7_f~1wnaOuvM6Pd_vRMof8r*=fYS`K|n zd{xYCo8CX4MGzeh2=qjggq~QJ7#M=`IJcDu^eaQ4!_~y^g^W@wMd%f^LpkC6fey{6 zj7G;+=@Ro|)=Jr4@r)xG4*#T@_ymOdN@Xags`}uN!)r?*+wYvXUtQ`PJ93)g8{hoL zGv2S@-GR&JwqCN;!w1)uO1eQG;-Pr1{TKETrBbxoR8@-5E2_J4vhHJAq5ITTU+Gs3 zwJ+=j$2@)rcLR7gO-Kcm>=LkCc7wuKDx*Zqk@qNAp7tU{Fzr#cX3yuzqN;8|97Y^< z^!jT~J-jA6XL05jeS6qN(XW6w=_h;Dk9uu^^|wFv;+pKpjr~>#6Ts6q?%gO6zx~bR zdWF|H`@UEpWN$CfRrU5FPFZ@(0m8U*Th>8fkqLwQs9`B5*Okt?6v9SWr)yywk;7=Ki^2D=q@P42fB?*8qzS3afmJ@EbxmzWGeB(1vQ-LA;! z&K@CJb;XW8MDA*N2jGsg%0>%X--U*K2$5c7yLzP5YOntW%i)Q_a?OPjp+1plS_C!b zM45M6YN13Bi0s3D8GI%@VF17F?R(hEw*KC7{S#Thga}HnMLhECqv%q`*s-58FHYI| z&;RX#^$PHGFTQ17izaH@?zS*{czQAVme;vP zD#tm@K1BF@MbwbIYKV-6$Zn9DuYeGJn;L)J9|O79hsIX?))22ZN`%y1vCBv_0|GG9 zswKSaz8J0L6fT^)g^WtHD$cT^VL-TyN-XdBn)fNS=1oRIXr*fW#k)a9%e{N`%i#op zf7^M$?a=x!Whg@8-*^59nBXg=(mKx>)883HMv)~tah6(%h3M3&U)f|CbGK0-TH?iG z($gF>M9Y1pv6al|YAzHqDv?p_OCC*7_tl{KUFxGN9_f}cvKO~4VxV3x5yGoDO$et( zfoO?V#hF7iED@T!O}7@gTg0Z6p}kf+wRpEr#&BJY_2Kfszw~ZPEfoJW)FY)Wmp&v-9-42em_N z#}9A^2vs|NVA<=>A0vM2R@GdOY}r|6mFL^@bq3pdMRe~fC!A~X?wvOt+<2vb;_0RG z)y|-ts_Ns9KTda8l$T^*S7HOL-uuVL6Mq0ZHs19sxKqU4a{K@$)<`vefU}R(IS_|V zKY!wit3BWT(X`2(z$;LRe|jb2tV3?#{j2KSd8QT!)kM)%^`*}*Sl<^~o$~lU+o6Aq zAK=WX8kW1k_wHQ3{u_Ar%VXy1=oP7nu5zlXYvVh%rs0XT^3|C^IaSr&6DHKZ53Oj6 z@QTx`Yj`evIAI{n?TDbAaTq~CL`^0{n-sAcEdK>$obdQRaUM+ZP#Jxv39-B`GKxK1 z>}XU~`%^!mR;{yke5$61ur{ps* zwRn!Md?g+Ys_K1 z5V0rPJ!Hv@qQi;bfRG4wB+jurPq02;BH&59!VD++7WMJg#;03%-Q|pv8bZWF0$E=v^g3?0|QZjIPM;(@OP~ zH6|IJcf+1o$`H#7Dn*xwbD!#&wJYqqIHslCeahSom~bjmJ7kU6B%2zg47E_?;bf8I zbxVX&t?|}-u3@}`5cbCsp%zNaW52RlqERA*Z_zo`hlXf*CW^id(Xc7@1sRU0#EY?_ z!ZaXg*cM*FyP{Q3?1;4zW}*VoQhf!{5KhekQHj2VRuavwAzFU^5bqWfnaB$1)pVqXIarB|yHqz8neOBrKt zUe)^UdXN!38u%(&?0{B^&?_1b<&;#yq805JZ+0kJ<&~DJg{r&SR8_~^x4-%7>F@5@ zR{w-bU3Y*TuB=)`=oOWxoM=aW9wmH{SE(E5x-lGLylA3Y*}7ZUfqjsC!xhn_uZxNu zHPKx)iEEc35v+^fV+~sTyAn-km0zv8_`RoSi6*p`+^wtbik4{hA@qvcq@1!&tV5Nq zXq8vwZe1-@wAy6xu=+q=)g-Iq{u(^09iv3(6_ux)Xh-NHTm^*j#jck2a9wvv*N?Eg z8b+(Ysn81NLGle(M3aVS*eDTtWvEszgL-AnRyG-9$FA2@d9v;rc|w#|5*nG2*3A+j zk!tS#qm`n(twFV-t^a-Zk3IpRmd{?snP+?l8mv1&J7kUhJlE!Iwd#ph;F9dXI=plr zv`&pH%SAhO!8+N|hY(&(wL^T^FbS>U;vrf!)rUbRM@X&VIp?0xVBGFMw?J6ej6x@$i8z~K?GONpq|i?W8i?DbNH`b6v~I*}n-ZigTsJ$d&NELVNia<#9} z3U?rrzCEGp>$?FHVlMvaiAV7+(Bx_O46l~kp$L_svJF9y^(?Wr@Q-pT5t2V~2MD`? z`co*+iqNLaGR9`AJc50_$hg;qHN>!a2-}~{7y@xRMKJZd1dY5SS zk`kd;GzQ8^wJP~$D%G~MTrDiA)FZSyyqH_6N!BpL-|cX6R<2%=EP=Jk36|S?Sm-OI zQgp~^_wJkFeHj&hO12}f*l_|?$TyEoh=X~#rkSWzq5BZA9yE-I7PZqW(xdwJkEm6P zKb5b_Q*DDb@K=knRClFPkI=W?53AUHg1(|5`fl#v1)`-_WF70V&vMI1p^AKsD)xD< zw}!_h9v!i^pc4ClkeGMGTF6KdjD3YNI6o*tGNb4|%Bj>!`6`uan__O3O9cCNwbHxv zFkdaaqmi?L>znEWzf0MUb$+qagl8*(27uNHIGHZfN14@lBH`NE2mP1=-#&vCJjHqa;-SIP3y+T4Bq-z*oc`n&+Wk_`2g@NJ6hK3{2lhzxk4&kl;g&RkU`ujC)_O^7}j zs)@t^xtqMuhmah_l@yQJ%ZNKpsEJZWs)AAm5Lvp~q}o>1OuTy)Ut?mH&;7eKP_+{V z=Is9QiqhI-d9SMO$9v}&iwNa)_%GMR)qs}Y<9DB%cHc#vd%jldEOsEe=t8|)-~IzW ztvX?F?AV_{9$#Vo)MLjqcl~IU_`B!U`D}fSXSOkfUm-%*$1OYO0RD>zP}hMngkK>- z*Wf<@4$z9Ph=BDA_2L!WnfTeDt|NLNAfi@=@GBw%Jw0g{5z%r(MBNK2BBDoth`wsW zSB3~uCm6!1q72hGY1N@Ew1d`Bf2HCY+L|W7c+lFXGL?`-+S9(Ha z>&Pj@qs3SdB{Bv@hOMKv5dmM(azpqPB6J-+0>qj>`P;-12OLme?~t!zcU#D^@3(Jn zg4{~c#2%IEBgXu`pYC37ZFaLEVw~NMm>HVwly+}I?Kb>eoH8TD!cGAWKN}4iYRqYUO+DJ67vuL<~l^c80YL-^iDM5Zz{XNDkyI}T?Cml3ZhmDw=>jU$58L`7f4D@tWvkeEkA zC;Ez4pi!c-HTlykLDQ&}A@Y?Z15`=Fh=?15f0i+riK~3AK7eVmyYs#CHkY|zA~!l1(R{9cCjDw1NH-8Ma2242Ha7wjFpmlo!3r7ki1KKMZx=4t1_}s8%W?R&6I#t$J5|rJiQCH;^S=i@C;D zqe-o7;*=~Iw7k;HP^yFmlG#2ta`*d|yGaJFC{@yGFjVb#Ks|@mN7CI8IrEd{K+q1@ z(55YnRIVbW(*1)~3ma;oYPC|8%FxYFo3sNq)M!hT!CnjLN|iclv;#KOX$uj#<0zGR zA@;Et53_}c*g4%-k;*(B=PTObwh)o~t5PKy&8lKvF{eV+Y7bBHK&6OSgSAkDmWgpM zN;VmS)f+09GEh;qP*J)MT5RGTmHalq{111cxDw03cV>6=qbm;l^c+4*o7o+)!Kwp? zuX22YRI^9qeQ9R*fDIPIeSs^1?nmS+rHttHVGznUM$@!J(rY}HQd1Z?0-^)3oY}&>W4&Z>NG~xvkbTKNS$Ex0`(>anMP8*=S+*cd2D(quU2Pf`VRq!+ zu6;1|t{#Z`dZJnz`GU$2gXpNkAe1UvZiwiSjDQV%&FqeUYW>U5O9r{_n|I^>C|b2h z#VjOmu4A3sI@S$1^&_AaPY^~GcY{83M1Vh^oRt1izeP?>(DnH$Td4lgd8Hqr{)xG3 zUWhrJ?SMvnrM_fTvAS%XJtB4(LakLVWSjc6%F?rDC2 zynY#(SD7VQc0U4^#~js4)rnIOEqYfynsZ4rl+)e=aq8o}4C)!~M(s9u-(s5}kJrZU zb{kxB?PHo>Y4Sw&5D<4RdVlRVZ!g(*XF{oV8*Cpn#{m8V;=0Dz&Mz_b{RdN@++i`k znQFH|@E?F2_-Y1Z+}{{m-whLNd51-*c0;#Vd*GqPHo4T!Y8_5}v?bUP?y*z%OqI~c zcG>|O>a;~<;EGZuI|hOsu%Sj<#133hs^kUyo_4^78f_sWo}CR5J!`BvDIRUw5@p1*no^mD7Lyc@4sD5c#1o`anHMbXDIR7E5&2xJ zROacyvyWdA_W@{!+d@P;{l+4XlKssAEn|tdwl~S_#aPr)QWY@NGX+|Q3bSvHoz7`&^OFk zrQ$l@HJ}}|0k+g71_MgPb@bIhu!A_!0iwN34e<>B$(GJLp@u)GkVmz!PD;3wYfw`69QDbfqK^qu% zrQ+H)343ON9S4;D+AUt;zjNkC+3Y@cy+rW0;Y!Y9BAh3GmWY^%@JY_&PeypQlPaPS zwf_ehMin(2_+*4qc^-c1nh{Qn0+sbY@J-d83=sdTSJ z;L^(?*b4u&sKtFd=kc(XCq$HCF^?J|Lxzc9LMT=A!v8=hmG}8!Wdt)IU8#Uh`$r_e zk8jO6wtm=JOSM$~SYWs-Hl{nsbcrtUccu6Dh;*Y!UsNg;yE4aOL9~T;KPD(F5OG z@aS$;?E}OpAVvdGUQxc8Q&l~4{r>e4A5CfBvMis`Cn~%H;_2?8qn968`KZlp?eg$x z@*~F8_jz=5XVPUSqwi(}*M7f@=%1~#=s;Cnfm)%Ak&tmYWat%@QF3}3h(8@NuKn2I zE1HbxchltQ(eE^O`So+Q&NAklHm-jA%Wt$tyfhE`Z}KRl=lf!m_vll<2YNneMj4Mm z#&eLNSGaZ=C8uYBIPT@E%w@Kw)!1c?Ef8cX5b7 z%)vM0RhDrJe6`Wji`3WO>4^eCwBMg08kvYb!fdCEXCUK|m{)#9WvJ|`It5jG-Dg&> z|KKY-nGEMkD!*$)H0p7X^;lIu0OAE8u8IhyLZuFRXUK^CfcU~32qCo5p#Fru> z#>1%4se9h3Ga`2C8auV}+x~_NZRiqgDpx%|J|w2&G~T@*QX;BJOH6?rM64YuBojy#{z6_k~%t zL-HPF782pUBEo%GRo4LV#zD*1r(%yHm3xtEk022_PCEnfWyG924yio0Tzg&-;rWJ1 z6o|W!iF+XvN#z;GwP!vNIj7mFfBW(qwdK&MNtJ7@ygTf*Syk+!Yi_?oZ4Y!&B680t zpCQD^qKiHsI@}C)xQK}THTPX=mHSl%txi4c=JulKK2fW{y-25q z&Ok)oi}F551ng*rJL#7IvHvk^c3ypJ2}9&PRd;0FQDY5uSc8<|J3ZGvWl#np$md_Z zs#+ZJ_!*{*Rr{t4B7F7{t$^Sp^UjL1+RNv>vZ;s&pRdGnbh$A=Aluu_c2fDQ#|5H*WNzy-4ma&Ow`?yh_K6q=PeIDureZeAQ0OCvFb_BST7+}xH7Z5 z-noaexV)z|7mWvEsv!{>xj-u963ogWX@zW0kA3au#5WpMrQks}A* zoxUY@18TK45NiRUSIAdqIF~(CE2Z*0CORW_fQ;kn&(}VG1+ zcB^VfAbthJ+d$|Q^3^=foFsyHpMFW@wW2mv)lQIc=fO|ZM%+2SRg}-vidNZGwKWj` z0%AiT$}2OwJFc%5e=CuDs7tnszKF8pAj73H}MuJ7CN zGtH^XjYb9U2E=F}{sDwuAz!U|mpwGEl*)TaX@~5bHuXI_{pgiZ=VmSW$<7(igKIoI zrE|@=btay@!Lw$E%TNuuc20QbXF$v#qP$|(_GoRiDemXe;cPd647)-qQz~}2EMs^0 zYSdZd+pk9NIwERiGPs7PdyHmP5rKHL84tY@{gd|g%xRdICn}#AN;?jKj3Xbpq&+@o zq9Ifs*T}>{W`3xT_kp-HXQEvpU!5QFwA8PaQu$n>HU$}PAN)l7>$z&6F%q6P;@ebya@=BgXl+#dO zsSKY>)us|b8M=r6;fBka5AV{(9zL_%c<$BaX1k8VS}l)S*}TK`BENdG@x~nQ7$T$l z5#-_15)fTSWV9e!*-NR>gk3IT>=386t(s!uR)F#*$5uoNvrI&VOZAFG5h;v`%d^Jx;zx5+D!*ku47ka}-P^ohNFl~FodpCDv zyr*RQM|yJ|egeAlY!EG8$vex;?xB0{+B<&W&xXk8emn9`Urqo(Hv_sKk#n?+f6nQC zgnCr{hFs`{%ol{&fsBhjQIBee69i&c`bYhiJ<^ZZWQ)(>Q%E0~fASu#vrj)lCnT*E zc()m1(~rm&YA$I{>_@2OnkCt$enggTF^^HxXbQr-iwMRXo!M0lb8Pw%$dWX@sNZsq z3Bux$dxpg(`bT?AKO*xg^Ek_n2-v_^p4+(A2xbk3k&*n9sWj%xd~>b(rjM-A-gg^* z(gN>Qku33=U~k`Z!p_ZKt;oM4_GKU%r@h(!?*a1}!l`0bn&m`%^G6RiKU(Q{AdUj> z2kuy{Gj-rl+i^64?l&SXTIIdwA=Td9s;WW8eOr(3oVe`uc8A`nD8uWKh`Y~wr8(`k zwVL>wNRTmW%#xj}uAFI;rBe~%J(!5^EqiJ6we#)-;&N(r^A+tW7p&M(Dz3c;6Y=W0 zuQz^t^;$3(#LUa$ zI>#W#22Xw<<5@)TVnk4>xJLHHIBO@m5{UbeC6kdQO2sv@FXobVRLw-CitCuKIgfG2 zE68ZO4A1H)FV;k^6@1S&yt^$b>Xj>k9bP#^qEvW=nRX*csLaixqoO!jWKU~%$bHJ%Vu7Fxw~2`8b)YYXj2o8Svi_UtpEHC~oxJ^h&80p%%4B53<&d%L9=q00 z-}Xk!L`P7Ddzvz0G=ZK48IR3#V13H0H$B^9M{ad)eCdtm!*AN=m6=4XEOr6y%$#1oKl3oJiz`seD(mut^T zBBFgjUjZ4T;N2U)I?)hHwQ=LZ=3S$1H5nQ4OUPgZXZ`I51%fiXRwyGz7U)+X<2xZs z3{g`3qp{(MubPaExC%0uOOHNxP=SatVx9Z@Ts{E$Wytv2LVLB5iH=BAdrtUA*JY3^ zx+oCQj<(wYtqc);6}ykw!A=bXvZS`uwPQLnvab>qeARPb!H$TC@#uIw;9Wyd2BI1F zC5s3556HLcsS%$$MeehQU)?3?qrrFTsQD3Q^-Ijb`H+D zo2ZbxJ(*I?8Zh{quV zb>8thcfOPnJ!&$d53!yK87I&CN?UqK+*7TW^t_j3#D5?I{fb%AQNCOwE%4(0YTbvq zfHg7^lbB_qA-Hxbt^$=JVuv%WN?utjm7V%khy99(tZ()e5$=)HeL6ov1WUhL_pt~P z;c?1&#a=>0j%};sc}0Y055Cs`mZLLt*cph(8Q1D~wiDqwo$B0bkceCdT!$JY!Yi$+ z{s9>q$Id_mJsPUh5Y`zYq7mlAD}g`_)>(s5Ml)2WX=VK?Y87|t8-Z93UG&swIqYbL zS~JV7ixL6Ln_*7$-aa*Y7rtU|Z&051b|T{MyD8i2%yv>mUY1L~;}8*L2 zgG9iK)YlNc4-yf3VqYc_5xb}%=rv{{5nP81<$iu4=ENuQvudq($zM*I2cN)vt2u7X zUr&E-mxY=ajD4|5PKZtH!B>Ow9w0cGg)4TJDX2>HNuazPh_~^xxB_`^-n&zCg$19A zXy3kS$9>1Peq}z510?num=0EztJ^F%#44dJ&QLC8fgW?cbTvB&w>O z0^&{}#v4Mf=-!tzrmDI?+y}&@h{)2FO0=!60^$lx$OrOl0NtN^=-%dOXB`FUcn{5S zFE*dsWkIt%@6?%!JR<7iAn!{p4AE}%)%%9mQgc=*Gg609ube*>8`AgOr>a^Am4+GrwpN2uz!8} zisq{~UtuzGrCkHW94jwbeW7#8pCP=0tBR+)1A*Av5MoCmLpjX=;pOap0 zyz=*dnpT<9tw3CL)ud6&@qAuT(UNgpNAO=^ha-ajGDPS;UEljM6<3bF4Ty(c`uoKJ zAy}rA^HhUBk_QAj zT*o?G=wxwX6~2&%{unt?2D)e`bWxdo3M$0^xEHBav#L5koDIZ}b8qj3-d@f@J~`pt zR6tw~gzW~zTcswD(G^td_ZMp>hO7pnx#y@`zmj51<7XWb= zewJ5;Oqua)cn>Hq2ZBEf1hn$WiQ3Y`VMdM9Qk&C~Y7%V9XU;qap9;z)PJgpK*}dzr z70U~c*pz{pp%Z2X$)zI4B&U5p?}YtaY61v7-Ni}2hqD2+dKe=+yO zbgw7PB9M`16z1+%Fv(c=3I0iUZqiHzM4q)`XQ*3e2r)?aVbaM0h&&C(8mxsHlv%W( z(z%owcoAl5{*1X4=X1$EpmSEzo1UBHH&}6k89(@|?u5paDQVp`@`NbA&FWKl_lYB( zGxU+&+ZrW8d5Jvyord&{Swj$+mr|+hQifc?chDuRbloRI5h4RxCE49lhFnqqVBKd& zD|?&5x-CNNqie^u%j`^NCkAGKjw{o zM9Kyrl8m?xoD5<8Zm5imQ2R=RUI}a0ifEVNo~^JLim*(KF*mgN%IkoC=ZBdQuE-kR zO&Jp`cRTP&)^w#SmdCYe1sU*eLWp+@O_WpNUHmQ6yi$gt%zB{$B5BxoWTVH-rcLMB!(=2xOQ}AX_Hv?{EkYv* z8T`9_jlp-Hd#A2w^0#la?$-*s4?3bFGP)%~d8vk)F@~TRlc85+4S7jJqa$hv0#wOY zU6I`-HD88kslJL3uXl~y5tT}pH9pCns-R(rmTRRlR1=kF2>f5Lqom5#ii~cFP<>_H zkl57w5h-fuU1=TbCf7MpK`XJN;H&bCI!OwACoz}6S7oHN(dPFp302g}(7Lvm2aPB# z#K5VNuYgGFVG)+$(27*9VOm401z%msbUSg$0Z=7<<2oRMM1deAQK| z5Lrho^6E;|t#veHXv~#LHLR+LsEE)jYOQh#Duw^YiO9M^kgim!ZE3mcu2kxgLaVxH z64xO%BD+y&RdgAp64^jVJnEuJ?1N@g%*r4yAzFwaG+_k8716!ml(cFgB=Jh%tMbHe z&`RPF?Fa~^QjfTdkiQba`hxSlZ5p2Yy}9exJoc)s&t7a%$Ox|?h|Wf9ylGUpbJ|gK zi4c!=?>XzQhWOns|B z9co{xm1xox4LiR+=f32(5}{PGu6OSGogo;T0ulEQ&pz%rlQ;_vwHz>uU`zCEXq>}t z5YVLzjge>Z{g@O~Jda6}o8FUHsM%8I3|lrF=Cug6p`xC`yiVQlH?eCfBdh~ekhk4ni20QG7wqT2 zU$9qAlqz_H^1ATuRmYAp8AmR=VUcl475ui{AnTF(*sDc-vSYqmA7lq%GwTMl1QhWSdXR;fZ{-Mff~y>o!^(3mTg#>OI; z5PC(kQaR!2l4zxTl}fd(s%Uvd%T;%!Qjg$?V(@N7@2Y>4O1(}m`KuM<5hA5j8rd>S zG|oz;m4slP&){y^h&7}V%{&q5a65g3W%oL0Zz>!z8Zo6MMA^A=4>rb zS5$_|E-hESTyOB^dG6iBDIrX&7^x=z(R$^~-uNqjVQc2qHorSE{N5%2Bgg+Kf|h!Q zbN%MM`wWNBDFLJ>vNYJxlT{xmDdXdd;KQ7^1xqU4eJr3$gkB-qvl`QklADUVzAHy(d+ z`eyt7`C`gQSHg3g_*Az)+ezs!l~J2{bFZo{vl_j6s~dYu?)0)vp-C$PDPqzi-QH%; zjcD+KqDw@6hK={0tp0F9C^{ipm5mQms^WiBL^6&fjm{o@{E>7u<64^uxbdS!YO^ z^!aCqj28XDm-1D48qHSy&nG{7@lwlPZoMQ?K}LSBi9YT1p7`fmXH2Jzgups!(uW>u zd3bjVcwztWy;kR-5}{WpkCp4P6DQx*T6P5#r1Z7#oGP!Bp;z#JuLA9y0%Fv$?+438 zMnb^y{N5k;6}8~YI<;u!d})urTddT|_N9nWG}qysPL#2E>$K6QJ$bNcm99V&JTs5) zrlNFA$dS|RW&HHX$(;!s-ei8my6)=|0U2rDnfH)|8&xa3)9tLiMmLU{e!rm;qD9%t zOVLBLGU|SW%20HYK>%LaLaxJm)v5|wb+cBtKk?|OgZJLsx{vBR$9uEt8!Um(m;}Ey z96fs((5mZ}tKWtqoEKztOa^o#X#k?>dggr8MVXS zD@^aVFj*eu?NIwlU#W$PKz+n_axmK;zx~Q?7T0|&Seordi9kcQIvpE|SSA?%}YSm|K zciO1Uf4bNTltHb0SHq0bv=bfd$nQw$w*#|J)6bTeubY16R1Je2FS1kj@j|Cg@>F)K ze$6=>je7miU2Mlmnn1%Oua8sm70oE@AYVV3DyLTc#c6AfdTHPYlaci8gy?f6-l zl2fUb?P}4Z^;PVCl6hBU+ll@{KhgV@ei_PX_A<_R{O$T~=dhpn>pEMv>T8|1!l*NG zzoeh{Vg^oq}X!Q-JmaovY%b<5QYO&{Fli=+EBfgN4abb zfAo2-L?~7Ck0C-I8}9i>jG$4`yFR@Ri)c|_y`q|^>{2U5s8%YwMD$Z3cTL0DBlLUWC z!}r}714GceKCvpgl%c#-6O~;el$TPe?1X61LcJ0*afpTqL4fD3QDGuu<`0i(89Dw> ztyLK@uM9nV8H$KCI6NXv-mz+fhPVC+f4h3xFbJhmzV&`YvO}*xtF$|F?OsTBM3nUm zldkeU$?}{(jJfZF8vjy;=BvhhScHW{Yg?c8My+}zN-_)){bN^1<^AfD5Cn#ftmx>4 zVPxpOL~nX8;o3W2sTC~ePT!>@Se~ecMYKo-%hP zx!9jUQo5bI7Em8DrM+hKx*aB4Y>CEi~%u*PXXYc{CV*5PT^1lh2cM&y!>vzQdtDk9s0$; zeafiA{_x1fM1)tkE6b?ay zn0>;%4BgdYhl^TmJ^q3(@C0ejil;_BvBq<4{Cus{M~etlRND3R8GZEhFqZ379D7uc zoXTwHZ~VoX!QVkc%cTa(ymEj&)t6qIW;mjUkGV!l<2-vr^rGvYG_fv<+@dmNJanH> zs%&|4*Du#!-(+%|KY{K9gAOuYVI6iKBEo*PIVk@L#8(Uvycn*uI^#aSSaZwgHw9Wb ztpm!B7g?gS`XYa{@AsMfx#gQjtXVS|n4EaJw{_lqz5&D=Kzzy&x-Ydl$6v8~^PKis zUCPLuRsdq9MVII-GDL=ImF^}$9%by&S|?g;(`!8OCK(ONpu7|3TLbd80%G@s&?^ZI zscAuin!O}O0ua*8Lb_*YF_&Jf8qB(0^$`Qo-;(!y^l)KD+940 zEZ<;}AR~Gah-9syV{EXl1F`g`liT=d*5`?=)!FTX`7!AoWQgmYzPR!7+B;(XeIOn} z%vUl*tCO#!_=5_Z)6};r5KnD3xxGe2Wa+AvqH93ZHl19dy*?%8B= zZG5zY^?^(@-65}sOmsWC!H&&<=mIez+YzrQU(+gbigwh39ePElev4C-HwH33yXX@2 z4J{seMG+Rk*tItW;@^ubQU835V4g)S$9l;2M$D34$P(t&Ux4^~%o5~JyrO*5i45qN zyLH;hSC*01-I(pYBHQ~BiOOpb^$`)VYU`nDtvY+5&XXNLCk=aemIXWBg&lLpswJ<$ zSG7_^tn+%P^W;(RN}jegIzyDrESV9q1hyzuiY5?z`JD-5IqReLZTu{+XjfBCk|jfA z#IvEvh#88tWP6{CATdn+Dlc}?dg!9+lhO;>^4Q_Xzg5OI#iK!KITv<<#s5S+UWolF zpM+w*AXb5|ki#AF%GGIIB374H^AHBu3QnYk9i(uX%Ego@KOEw|q zJN<6I8Mod(slNAGO90XBPJMrc-scu*;!0U7v3KG3YwUaGsNT#qYunpr8#Eib-Pox? z)$KmC!&TjV9^4h{BUf0aUG02!?K?N@VKVZS6g87a>(S@2e*CbfX54YYA!Y-4y}a7~ zv7SSggl-Vlp*9cr;(jyU>1@A-7cZ=`_c~8U2RJ1Aqc&qe3jF!@a|uKdUox5 zH|$|rMejCa9;a;2yU!vg&)=TD`9Qrs{}+Hz-PNY#H*i`WS#l+^SVTG$cm+$?XR3V`1B`1jV|`OhD>H#~!%tWw>TDpeE^ zF&^y@551y&MLESR0e`+MwsE=(>(EOq7x?=|RbBF*^(H<(X^+mwuU>;0&Y}j%AK;2o zDVn)^&YGKdLhkAn^@4I@eOwMis1K`yI3Xu=S7c*-QPv7Gb<(7dO3}kv9_l$zg*sPG zM}=O}4!uOXPx5q+vQY)hF{~wmbzVX4GPZqGiryjg#7^jmdPTjUoGQG~6WgIDs&ws% zsxAA~yPXX>A6makem7rb4OO1_swLiS$Qo$%Tdea=sPm*RG9}3aTH{~gg&J&!8q|E% z8tg(2U##Y>Lw(djeVDJ}%xUttmzccVm136EL++ZsahkL^v(Go8hKLb!S`f&qgy;&D zt@AD+S|R31EAX?}#C<7gh~J-j(V?~ZUt6uV%-!rh_jZ?`er5NZ`*(rv_jZ?>eAK09 zzsgUHsO3kUKeoQ^4?mpPxL|Cj_RNFb?_7L&cbx@(+T{AO-~am3s@lH~J!0QCLV z?!+T^IK0hotAFWlmvrC!`eaaHebO`_e%^=P6nlE50SdJn>9?{1*dDE)#A4=P_G~Sk2ZOI z<#*fms_NYa*RElSUJ6?6{`%&%qaXUBX|?MXTLbYHWX$Zkh9!F43l6QFb;eKXM{adF z5chU(7_ndP!%bEcet-G}W9t`8Uafx1uMaS-4p{H!y-5RKG_71ia?0pW zL8~J#IHd-N7Ka23wTKm6g`ymTC?k)rVdbT3vnqLA6=`ck4uI68!_Jq*WjKAVlz;b0*eLUH0>^ zKIIakr5dIPg3}&|;9MhjZcemfxw2F0STE%R~I%PZ7JHuBGqXwUPdqkbQV%?cmu3>54;?U|ByUbHN=Fy*+ zR%^GO)J+>?Mq#>jV|iGYM_gnR#`*c6Jr;hfiCL4YM_gn zR<0qn%IMfdXP}F^uNvs0rj=``_ElBvqHT0h&#NZ7sA&ajqlUU`$1d7N7d5RAwI;f# z`^q$ozKZDBMce42o>xtDQTLT;7=0Ddv5R)lMNKPonI^iZRT1(kYG`>C=atw+JLsZb zgH3c%t0LDh=2b+;F4{&HHLXyCK)hu&h`cflsZ~bDF4{pC1;V;P6J6A_${MEm0l$x3 zw1X~cTA^Px(M3%wbWzigoH9Cg(KfoMbq4gPCc3C;t9lK};T@=<^7iBge4ys{_AUMS?+CdjJtztGbRl^b;yJ#C- z6qZ{TWiCO6by4P+X%!;~8L^AD(M3(GSa+sX%yz6(wqqT;Xd7L$Lru`5SUIMZYgpPB zyJ#C-)U-m6V%>pP){vYsI(AX^E7K}Zde#S7+on}KO<*0n=nQmG)5<43)sR|c`(hWJ zfi4=fijy9-at%u~JKQ06tUKc<%!zu1YnNx}#Oc@Q?LYhBhcocD+aca{n@aStm@Mae zZMF8YW_jv;W^H9JPWL+dvcsLW^E~Z`F(;Cjdr>u1o2qIfX!Y8ZTiWj;f@P$#e@gV8 z(CUS0@3bdcmS{Gph8bN|OG2ytU*EiaDCR`+@{CgrHU9i7F=OlV-@ZU+3(TU_D)uGh zXs(qK{aToJI~Q9;Y2~Pf8C_NEaMLb0sC_KvMDo(^;~G+{T+P41{&&gb)jB`NEJ{r< zy|V9`R<5Dihi8tMmd-fiC!Mpb`)HR@4b?t&xbt_J2L8C$o3-l78uD^q3H=JQD5A$# z(yA-#zV1_Y>ZBDAY28qCRk6cedj3J}S1>1vg{l?MNh_?+MFfwTvRdcvBM+#NSKe8& zhGG*C*J6g-1-?4KcD3XmTuEACozYdr4mawJ&D)D&P9(3G?KT1AeJMo{=sgj^U;K7~ z&i0r^$t&;SSwpoCJrNOn>zs+5(`^DsxzwXpxVMP<<9*7E#=Bgg)p5Jb(>@4uB6-E0 zXj-|3lI`HM8+`RU)ZmktWXLPeJ6S`uud4QjujcsGJMHakT1s_iTID+v8C_NDL#wad zzV3``Fej3i&uyw9wTj&ioK}Zce@DM!)>ErI-DM3+^l#7^K8=30v`v;eL8^usT~)D* zPDB@VUv-C0mNUCPGgejXq7%_Y-B;cI=~eBks@O$q=%PTFCh6Wnz89|c#V%Sy7xld2 z`P?Fyr|@)d0KSS{w1zHfTIDl`S!)_bUzvT##Lz`+=%S`oyjyD#jQ3%%&gj%dYv`h; z6*3$YX|gm8V_xyz0ItO@T1OZ48st3y%U9QsS|KYVI(E@Ix~OTD@3&j#^G=az<>=H! zYv`iZ8T2IV8d58CQ6M?h#x7b%7d5ToJpivF(~w$abnK#abWtFz8^k9KR)gT1YB1Ut zyC|qr7fp8!TtjM=PvLT+2gbTgx-;P#Qmc%Xy9Picts1iK3MZ^%7pYN+E^1o&q({E4A+?GpZ^({abRx3ewDL($ zH7wDwi`LLZO{>aY>8T8Rm)V3}f_(*R+)}CsD*k`?JKo{ns)_olAK`cF$~Y^henhP2 z1`&S$s+8T2P^w&a!^mj4?n;&W$0s3_%J0bxt5uSrR55D3Pev$J-j{~aie^BL?q0gT zei9<@!s%2ryjDqu-zlIxcmY`v?jVrBUnxsk{Z#ODI^8=pf0hWPitEO(zKSf;JZMx= ztN(#es%R5znT@X?C;7*yqTl`pLaF?o{wK>&su=$vGSE-(J&jl38~(^Ee-3VD_x}5~ zUJ0MM2f|;zej4Ap_%^;pkcj*#Iz`)ipye}>-^2G!{sm95i11GtmT3Dvsq{HWyr%%) zy7+T^<07fjC+7;ZeeSN|pYwAa`6SE`@w14Ew$CW0PfnVQy35F);Zt<^sm7|}Q@D1v zqwCT$ntJ#r1K(Ws`5R$*Jy@<+%y02~wag=t)8Ag{jD>gW?%n)OazzAA>0RZmSAe)P z$0L1T7h;pv)G8qu^P0yz$Jrv7KAo9mQ(i{&zrUSVnHl{VGb?<%YV7e@dgfcotE%nb ztEC@dmhk0X)NdN=_X4scMzD-jj)!_T@D1+{;yUM*qRaSeCYBkO(PfTRRnGP@t2OiU znwsQ_Dl12;E3b*jRm*?z6{=G!IIpEAf>JG<***28?KOSKnrKWSazG zzUr&<*qvu~fvyL1KSFiS)~Xl!5m~xcs%qPhP&-sZ#Z{uB z?7kxUvkNcQIO@*3O-6`p8#2B=<&^d@Yi!ebV$T26NR_W>W>~GnY;VJkn}IlQ&i~kc z?pZ?gN?)0?ao*%dOa^5ycEJ6R@e=HKA6nhE`l@YGjWylqI|WNP{xVBxwLj*mSLSN%ILU^ zLk|8j=AdUGV;A^}k$qs!eN0BaqI|V0(N{;Vu}yvar;@L_?0u90Uv=GAu%lDhQ5QSn z73FI-8Kos|H=nQR(fp<6}yz^N_r3eziI`^n~1c~s- zVmi9|TlF=sT)%eh>2shne7YB|+-oxWyb%3%G7!J{(`&VN{(dB?w?wF?b8JooV(*#r z*55v*gQv(PLZg}E{~I8d+w}U{-#2~?_LK;V(`)UEhVhlgKW7XrKklma+s6$P z55}2Yjdpm~4iQ}a%JtifpkCqHBd8v!Dn{^BX!SOoeO@0Wf_eM#a@V%o zcGqBJFMor;NPNa8e->TWRrOcgHJE9q)RDdX>3&6rZ#4JMC|A|DaMxfPI}a+N{BD5! zxyw1`Tk__efLPbg=lB#=`ksN2z5Gedk`ry=te+p{d6Td39^HIpWG{c>wB%G(N8wz1Nz@9T^tNxbro4>MZ&qGww=dK3da!(C zFMnoqWG|!f+)BRV8BdsixbOjAWT)M^GcB-^^WlotS)QB4>%B%lK>VmN}|yM@tv*Szs@?S z$u;f3Cyp^Kopa2M?d3kYs6FfJJJ!o9+I=!7XmRX~wF8&lwX^RLD`9ue9f0Ud|GRhZ zf{%_g8S%SpAY;;TH@3GpZ;Q^^GyYX0RlcHpGbi*U*s&83$IkedRg`xeqJMw+{=IuP zKHX%{SNMhm$e0f@_JLLdN37H)RlcHpH6Cxkjvsz_QTvv!?^tvnq8GesTJOWR&odeH zF23U#GEP7K#`c`cEYtb$lC?Xe%2$-HcAtfTKoDD(%-FqIk*{b? zXhkgx8G9|gYkiv-bFWUyc=?a#rYPWk7GS**anfgbUgxvL>K^aRe zduGbrVBewe)y|0d*I@a@F|YC!<*WU1((yMUXYqIGXY6kE;T1(0T(c&)rq@G#oQV2Z z67hIC)~{gB{PqyPKc}m6zJV_`7{oMeptn@2(E-lFIGi+PzDJd%dbQ0b(my zj*7BuckdG6F(<-vp{khe-}&&O+HJ@yQhCg|_Pip(^DQ8zqBAfPN#z;Gwbus`xhF0L zt-gV(y(?Zf(7Bk!xHib8$<;PlPs28%|IE!A3Iq^=L^h<<#I>&~S zB~L}$*=eFgXf$*DiFgz9?vi$5DG{16UMu)KClJi`XY5o|B0P^vFHpv>aVpw#7#Zrf z?CFz$*av5Wy@#x%W;zaJ(ZnqxUD8Nu;5M=^r5 z(66|)q1R@Q;2m^8+yt%K(27(pooknYPwk{!s47~{^Weg;oK$Wh*KS9Npp3b2Dw+@8 zC6#-TYxh-&h!Jctf~4|%<=W#>B4Pw=pMhDN)a~6rtf;P>9rH4SL?{>+pIF$&Ia+@tXBJq zohH&bDu26_b?5l)y(K4`cRPM!LDb^6Rw<(VMq+x4uW*ja2%C2!I(WpthiAw+D#<`z zrL}Sj0)mW^mm>0-^f(XJ{XB>aPu40`UdJ;wVg5}%PYU9%%<>~pU-pl*)EeZBXgownA;=5CjCUE=)5K(YgJ0m zd`o$DqOXS&ed&{IhwYpxLp2`dx1nY4mOj)>EHf@=hRqBq$Lu8B2`6E#14Wm4tTkBH zTCS-6`oOui9nQ5{=Ze+}egrcECbG_^@l=G4WAR}3L4R!esfaceQ(s%AzIa9ZhsuaE zT!%9prwP}cGSE?*ekwvoMOGe~r`L{5ukniV&77)=lRlgXjYpgl+nf_=hsT+Apldh%R74*Zr-_c7CgK(4n>kfg|Eb7jP@Z=K%42;D ze=1Tc?CnXbj95I(qV>C@uRO!a7khj16{{=Tfzw@GPIt);mq!hqQ<`4uoL+gw>y9!o z4WyX!_eDI?sVHAjzL`^1@kEb#x6XN&GQ1m52Ihy9yFsf%kyr7w&9i|`0QrjY&76Q3 zdMdKL)??tOB6=azN4#rLle-3~K3qd;n>*YUumg7{>bx^SzRpYSQ2T;+ai5{i`wXOV zJGgf565(F2D#mAHRYPt4aLWK92s(KhQ*2SraXJ=A* zm*Ltw91-66%9xYNdmq<~T8OhoaF|mOEKjGRYaQUxsFk*UGS`q9jAJGJ7G;)OspP2=!a`G!dAoJL872Lt~Sp z8E5J?XX<`CH2yhb7>~c=RK%IOAE7yxv$FqG0}&qc5)sd}^#h|F zo^eEYUX=)*Yk!YyKQH>qvziFc-4elg{0pZdo@+_vmBY2yM~UE^_)DCMF3C>;5UKEY zYMHOT=BX%r@8tKVJaQAB8x*Iaa3ypD?0r3U21TQj-n4yZmHcdi`yi;oeC6x>jkHUA z1ItU0dN?tLqOvAh;{c$)IT@>wzxio~T zMCkLVm`jGpXg}}Jhx43t+}M1Y2s^#UIiv0G4D(b31YWIw<5YB6exjKCK3jyGaWsEa zUO4-B#tc0b`IVe~%86>}(t3rg}f#r`$~Nh&QzX>YLmtzoQgafvUh!Epm+Jo znds-5a3yC(m;juUW_y{{IbXF3DC6s>sCRI%<2u)xqRU#r=fhFwPv>WM>D!-k-D%BV z5GJzDR&pw0JlK7>lihRV*|w%lxN88*AHcovg>XlBX1*65uV~a%#@vv>r!rraQxRi8 z8Qd9`d-?=h2QQos8S$Qe->HaKl&@NTBxKYvUtL|CiViit+%4Zd_Apz=X$hSApB3dR z%2(sTsc&68E4ouoMT{-&;4V6~w~wvqX*|b;jO*~^=S`eB=g!Yq;uYnqS%N7XJAc)} zvx#)_@{Z%(fbv)?`1=Ns!DmHh;n~E2Q7fh5UgBD1#MbZ?p2XG9EKWtiSKP1MSFEUD z$2HK3&x-U^6t0v#G1tny(CTo^?eoZ~$Yai3)ML&X#9v^@@hDD3;fmH>nDj#h9|${s zfK$w!eA|SQA{+>!CiLLVYZT zcs!7wrKbAGJxXhZcKie0{g#}HoUhx#%+KiG!@CE=yT=!&qSH+i_bw6HCXe~Kaw?*C zsk_IVh#W!Y)kb($bi1627;_>#uZZw`3z>KhI>SK`;TcDS*9Q@~KeB4SimE+cPDL)m ztCon|AK6RxMK7t#smSf{UP45iG7<9&f!H)Wua#3#@RfHsB65G!m{WJ}eO%L~5ND0x zQJCSj#j~Qz%PHJ^rC!K>A6$kF87?oVZ85;hs$wTZ|XLp$!nspz3$;^Ezyh@6#-;CJz?h!NB)Tzdpnb~xj7 z@T}+>ITd;5bQwbtd%^OFaw_sZ=ysF{`szJ+_cL-T@~-B-DiJY)Ek@9F_g>=hC=rx# z1fD4VEXwd~AlhSIBAAJ=qkgiSirfy*s}jKoc9HEj$f?ME<+)oTXvd>C6+I}YBHzip zK1u}hHos5Cx@9j+mR6~V;)Uo2;r%nd*1OJ%2=B}BxitT6maASkj5Bq7&z;TAy)Zjl zukHC{2@RucO4KtB{L>46@m3Kwmqs)ZI2&~QY=9W_d;-X5n`$E`BEl=bgU)BpjJ9)0 z$qU(+>_A>6zPi>a+&XgdPe$A19661;+fI;me-ei(N)beT zB>!Lzj$Wr7n2_sXLRJ~!U1%X5HaSPcftx(alW_44x{wXF1Ei=is{S_{supJIT9~Oz zs;pt~VM6eHUJK{*@(R1D%gbxV0;lbIIBl!GFi^aZ*F@+UM?IQ-ReD4t7~TWtS(4GV z*OqzJf)1EPHA@t&8AGa^yJe2%T(X%VWsKHGSqC}WZ7vb5a7yijQ>xaWqRZ;i&QNxM zT&Y_B2ZV{N!-TAo?7q4jd$(-=1|1iUKIKxo}`k-YvWnd5Q zNk@g{GQIY_gDy<3uAy?m_r1anzUS_oJn5SkDFc&5PkL~#n8MSuB5LJRxNArmIX1j| zjybW-IgwX9&Xj?9rzc&zSDYq_chLE1BJ<6h>^^mIDsmZ==N*UgSW&~Dij)ewe$px< zIE(UqWG6;nc}$x{Ft`R@BfrRaKl`>zrPB#VeIEFz=+8^Y=wO z(y1t4QNEcIzJC{XY=TqK2k}(oJ%chZg{9mLS}}X#X}j+obRn-?Lu%`s?AcxasmQvT z$3P~ISOxK}K~3%&r25EwwN_}y|KU``I}_x~2s&T4qtq(iXQ=Z&0}*Z^*X~{QI=({) zGH}D%eD6sB60=u%((+jMLau`D)0)YBJXfSD)Qb( zG^;4|L5<)rry`?t1S^&6>^IJdn5k==spE8)5bEh18zMN1a;EM_Xf$*D<4mp3ijoY? zn4Dw7oQe`cvod>uGWt$M388+=o{lqh=jdVV(AeZ?#+kZ(%P_vu_~(qF9kXyM;!NG| zE6uT-mHnq8zoHRTPT~D17ON3|QM)`D?`nl)TPz27k_GFZNJ*&C)+$|Bb z<8GXac&;UtR}R-+A0>hl+2`=A=#KcTXpZ-0)i+q;DRljjy_2?F2cN?AzsN^QUq6NU z3jeg(=d8U(H;$TqzacWZs&rjdKfrUGi|kWEBYX26vT&nn%`ikpSCy`->N1>hj*ZVh ze){C(`h*Q{GDJq>bGV5UwF|Fs#sQ+^h>Wf(U7L)$%K)#gYn9Q4h@8kDcGTSt=-YM6 zGupI@oQQz0;HTg#_@v|B&1kbcav}opsChhc3`X`c+PoV%m5BZ;yvnHcM>A_xO3yM% zd1`rSVYXvrFRv*V5scm~y_kJvxgfp*sD=MAw~9#Rc#Q1jHK}rzl-ZEuY>1dWMC42? zGcM-q>CmcT(?&_mJ}yjkC&_3o>@aebM=+g~`(OrHrljU$#;E+5ILX zc;QjV_$)p*u^Fa}C*wPW@)hN4F^^t&6qEiBfbe%yxko8u=B=M@EWKjeWKj0L+uaQr zKZ1-Mpw$`i^Emm6^3`~320Qq9oQvXV!sARCbG`Si`k#M(v&oUrf`D#V=pC;g4>oSyqn0Gzq{CyFRy2K-1QNCK|%-vtg zGZyO04o4Zt-HzvOuut-;E_nsZc}4kZ_knkd(}ed#%HSt}Src3%7dl0K)TBP*73Hh7 z5^FF$V{u+;2Q_s2!dVR!Ri6(PMJl(DYxizxQ>+hrw;`$A?_8rkEapUbF4*%ZW_yj< zPAbm^u95AQi9}G_u-k2pcuYfQ*exPF6C=XvBO+o?q*lBKz)XxXta7;as*PGT!v5I* zjK!;#2=66C@b_VVWcN7~HTYIMO~69%depPTIvf$OFZM)@Ir*~AJ83wk^JU+NtnWS$4tG}so_+l2#rmSCVh1$=61fv zixZ?GH2yhbIE#J?-#Or)$5901%&x}Bde;t?Pm*UWeuY#XL6wbnszU}M*#2WYO}KO- zTt^q(d?Qbc$jmk4GFB3RolK4bB0 zh=|y`ve!cd_rSS!RYZ_fo^esD*ijV`BUrmV`zq}+p1Y-1W(U6ak;s^Pn^m=PH|Bw?U&d*o8{bp3^)=5nm)z-Ph3H2P4DJsZm7Dn zBcrQI*A|bO$0NsJWG|!f*LM>q%0L7oqW{YON7#3OTUA_bZ&ZvW)~GR}SP(%`q}apV z`<`RVr!mnO!G;|qcExDySBfRE#1gTA-5`R!%iZVfgEfj86-zXvSfW^?sQE1Mf8Vv& znpyjB{eGS&kCVISoq1=iHEZ6PU5IftE>X^KBt5%HmS*M6) zjsyR?N)J{&6@9Qy5zDL|qof)Q(a-A?u}lO!*eE?%jkp*~)ff{GYP6%jGv=uWJ$jv@ z8oO~uu}AZPNBg<*G}hYnvDW@T?@d@AoVDBB{$g#n`TrIzq2p-cdpOul^nqr$LU$AK ziubec<1%Q5v!UB>)^lp(%RZJp`nB5UKYLBIgjxanxj#VZ?*x@`rtT)<72mEO`6!HI zZy=6Vg=`jOA78EZD#kH2V_Ex#LVOY9I327;>uw@m@$Gtl@ZQAI82M$Y^v$w{&R6YNjtBl_4A*4-KVk6YBbzENkJRQzyyDx9EhWjH&hc zqMT6~XB2DMI9N98R&B*`V18uBsBSmw5@8-B!aSQK8to~gowdxjEL$WJ5u=CCcn!e( zVC=G%MIy^KKZvk-6XL4DxMD4vA1vFfCBkNNIda5RgK@=LHfve7TtbB97(8KGMoEKF z!djL~ShfsDgk?UNQNib|Wf_iT^EnX~3%Gv`MK%Z8XO^CY^UAkpJUqYdXNZ<2A0j|RfOG}pa)sYB93K?t15!g z4iBdEAZuAvvuv?jMR4RdV@A<~tYtHYWt$&W1V&xiO`uj`dKYnw*&22euIzUcU{cs_ zBBDjrYD?@RYBbegx!RXz8F_NLWzjcUXALA79He9-nN@i4|=rd618;uZo*~}XD#wd zVY>+(Q!}Wgu$zciyq|p^?Yjx%&OVTd3foPn6{6}3yNP(kx9dmVzMC+MvJd1gjHBF5 zXx~x2hTTNG;@kE9Xx~kkpVtQz$5Z=XRKW>=~7+jbKH;UmW8N{_pVfbdZn zt-z7D?Ir@k+bvqUhuuU#c;7^C_OP1>2=D(GF+J=i0>Z~wjLP=igk3S8yWNDewCHZa zdMCpAP`#^&_T7YykO&(`716$%Fe?&awyGj}*iD2SW&T(c;dc`j4eY~wUPZL;CM@EJ zu(+xs+IJHc)kIkARuS#H37a`Y*!-v>pxwBS(tpERf4^tN+Ev3gs^d+7R{6)lQoiKN z-whl-d_$Dm5xy4Cg`q#a@B78{uKqnBR(a>KV)j3ml6GUQVXeJ>cYg7|3;X_m5Yx_k zx_Ir8?+f~-pY>{;`Pw_RMOnSK{lM1#r=8!)ajbC8%B|tUZ$YhLt-qeqzjfFTM)iPT z8yI1WwFZ28;XwTMoRrlfDC@|(SYoZ#4d>Ply?70&1@1L)mogaEz%U|801%tKw@&@s z^>;&N8`k>w$zRo$J^G(gPVZQ)o+P)S+}?*rfO{R>1@YCgo76w(x~LftQee9ndEG{? zwL1BCMb|0_{GVYh_@ie2fUW9gD_FO_h;_T#5jtA%7Z1`3D7Qz6_j8OTA7lR)!pGGj zQ36K%H>?$-q3ZJ(Z|!~f$bb*vvD;vu|0_y-T*106_@I*rEjP&|%&0D2iSbj77}hM~ ztsN2Lry33HDY4CIabm~j32RXh>{p@4$(zcK9-b; zShvTxl0I}6Nh~2^YGwZL5$gIdgyxK4EuR^_+vhO@1g~|HZS-urb)#=(2DfYmFM&eYF_hcK;eGBs7_)>!bg>Ve+f7&Q)N$zicL?++^F!ye*orwyEFI^6`^f!F z_5RS92D-fuZ!14?#Fg63_0dIEI`70j7%lcWWlmfK!OrkcqCM2oIWK7SKP=qND$awD z2LVul|rj%oLb$xWPR&1+W0c_okeJcXB`LBxbt23`Il0^+cB_pF% zZ`#Op)xLS9QyYIc^$)Ypd}3&N?GZy-2VJ#7arVCk)>%I5q;&e(vo@~pICY4O_{u8= z)$yx~V@Egk|8!)>;2XZp@B7b?*5ENK7V}@+u+H+3$=UQxuHB@9PLdzhZ_9Vv`N@tq z#_-D&VH{{Hu6-VjuhxOpil6V>{e#6f5>|`<=Deb4tR?LlL$Z4J-sOwyULAmzmH?|s zf9;zN_{~CLHMZmY;;5;8g_SY%<4cmGx4$j_>XA#+mp(j1SgD_dmHMWFPLgZE>Xtco zbzkz_8p7(n|Ng1?-rdUzD`QAj=TG@vamSoB(bDx`b>QT#^o1+u3#-riJYD?q#P3VH z#*nNGjo)|P_O^V7`#(mzR@;2kebg&U2&*-BPg>`#_OBY- zHHKuh*F#ShPra}VTIvl}D<(732}?GF)sf%p)vE9FPL1svLyyLLkK5gr&s%BT?6H3i z6IMRjjiE>5cf-MI-)Sr6Q`djKgKe$(yH#6f&zdQ$j3HU|`Tn=X4mZ7px$@MQ(Tx{B zdp5n|hf{=AHhQ(zCfCjqR>n|T((&QR0eJ9V-SuqA)0Pufnnh*a8AGx%bQxF2|EypB zufr}9R-bLXervg7_b6E@L$cc7>Q!1-UU4g1f~_`uVL`gs8oLRrht}!e`t0hF!pa!> z@g>RM!0N~U+6V6z&B5J1ucJbqub`9UKG>@J)xr5Ox2z(p_I-Fz>z`wO-^q53Az7V0 zykG0fKEDL3zF>9kQD3DC9-Y_C5zd;qaqFoe7j?313_UtYevP=AcKqSlbwhq4taOd) z^b9>3zw7{3ug@8V+K7BGQC3Y??j);Er*G8S;EW5=(q>?_=2?870b`1+nyxHkvhgL! zZiuUu@8_@G@?X#*O;?sN+4z#=8nAlqwZZxDTUY6JBP<-NrenpHz^W6rn)&Fw4mZNW zvGQXAVso%M1-6^?3?3{TD?cV6=)t3Q>6icaR~HE@jdo$B9xR*((bCFbbrIrf zzcqGC$wXsGSg8jqXuKT_4_=M9dg8e`!pds~QyG4IWwd{dIe1q8=Sx=Q%#n7DAz5j( zgB3k^*TQGh$5xvntaRoGD`QAY8#+nGA=*E}99;Ia<>1BYs&5Sa_>$yq*y`M^Kk9zw zk03MLjC?ildktZwIjY5WjiE;;$)RBN2=diE{~RW)yaF(_ zPjEFdcLsIj4Z5-p&uWvGTMLq#lGENF20el(zQ=m8AGzt6$h;T2oDZ?y>GhG2@8dl zu6@GF7?PEtlVl6T)i#e_nr`*cA;QY*5@SeKhAvl}?VuUfePXDvnsib=06IZf8AGzt z)fudMfz?3^M|K>1~P%>sKVW_sMLCJuXDw!Ng#^S05C1ax%hH5K82PKn3$yi*4a~OD2 z7?Kq%E$EbpN+ySr5mt!N8kCH%LSzU-jVnP1C6hzR z2rERmo(P3Ak_tK~nGPr!VFjH~hmw(eWemv*bFc;_16HbJawr*Lg=|oVl97C649UvS zLCG|rWP}y60r!KF+l`^lK^b3AGAWdd<@P$1OqoTMAz2|`)u3e1k}8=TN=8^AbJn3` zgq1NQD;r->G7TshVWs;TVPy=-%Fsc{q);-p4%VS$EVm0ovO;dJL&>lu%t0s_`~p$A z;$W4jL&;cf7ly*>cdH6ID47P7jID#=?9CXGm5nbbnG{M!SYf5FL&?bcigi#Jk`$xhK1^`_gp|Ub9A`HpO#ut=~AXF#tY^l?gO*05OD47&Wro)Y}=GrxVMOJJH z9)yy~p=3n$=?H6{p+^TL(}0r6$;9uS)oy-F=tGrE3MC_~u+lRcgq8ZB<~&#nN+ySr z$z3!ED`V)#7nDo`N=8^|ETOH)kS!THD47&WresylJ7HxEU9_VmRWdo0jIh#~Bdj!D zE9jtP8c;IuV)dlR82a%ACDQ>VlX8TbW$G;J+!kADW&kTyGC7otu+kh=XS>GGql1!Z zK*41_ER#@qok%g5pq^&fIq9s)_Ih2gB(tIwgjG-T2P%=4`jIe@E z&@=CNszz3Z4oap2N=8^=rRVA;tc)R9LCJ8%0V`E9Ih2gB($z~?8AGx%bWk!ml#H;_ zwNGqi49UvSLCK7Ok`Y#R;=y)}Az4AmaCJsYs${yMWQ3KSc(7e#=+QyRbVJDqE94aX zEAJ>7Lyu09Rd8OC@BAcHM#EoW+4`gZV@vxYGc5V(NGh4!_s+77sfxY{YH1eK(gcj$ zkC0`y%d;MjPLi=uWD6d-H2(|EOW2lK(K93~8&j!drvJ5XzBbNe*p_+9GpwR{mhtb; z_U%{&QR1V)GxX>r836VA^ZP%}cS9tyEsHqMkgUxASOH+GUrz4I-@us++p;;~8CKEU zbKW}Vu8v7K_aPITIi8_MC&`E9c}ZgqW-Z&Yx$PN}Rh-S7gR3Sp^Gk6i!?rAcc!pIp zZS~MLA9Wmwb00FXEaMq^G@f0A2jA?jHJMRM3_UtYYKW^p9)Eb_O01l0%PRn5NLF!0 zT^FoQ$LjntR%f=Q+CWr>G4$gr*V+eP9h}~Yb04x&{UNKqG4$iBsEow1^2(x@K; zfUT~9>T@G3T)TcuK#X*$&Gy^y9;`v|u%5>yJ8~#<>rf*e=d9^k_VHMYJlJ97@L4LEaM*R#<(6p|DbPP%;^mjIhFr%zH($zCy_eL$b1a z2uY$!CWVrb)fqa0_oGBJ7(=p(Xs&}$GC7otu+n=%q8aqAm93&OzMy2X1pnBUvg&kY ztor_rkiWac5h^RuSH`f4RwaWohNO!*%I;LTvgsfhUr;g`luYhMSaa=mI#wvFl1ZUt zMD?kCYMx;gtx6_`lIb85wNK5l@?%0Ds$?=K8DXW-Agt5}(CWd1DD&sheuhgPYGC7otu+mr(R>qJm89FGL3`(ZKwshtQD`QAj8tq`EN+yMpDOu^AT+fg# zMYJlJ97;x5>AVwG#?YgKlF6WCgq3EQx@SmMni;@Kl}rjHBdj#b$nIC?wv5Tf7nDpl zluSymX^yJ1Yz&2!jxQ(~-uV$$nvsQ-F(fO^qV=F;QYaZ=r5RaR8AFaKqE*RsL&*p$ zy(c8Bj3HSWIw+YGN=8`e+9#}xAz4Am=<{W&WKt*@VWszLgq1NQtB6)5(+wpftaR-Y zR>qL53>}nA2b7GkvJ(%sYYfQ>N`|X5Y{fGfD47l@8DV879&FbbR?(_tcn3>ZAw$TC z2R&#EJsNB6^(Qs9x_?B+l+Q-XnI#eKi5+>GM$vj7=V55k;q&{ZtDm$`5ccFEYng_t zB5pt*A0E&!_1P^Y z!k!mnEgh3(JKmcB;*UVQ59=O>Jq{7}j35!}1Do@-G!TrERjwbHp7PQUC9c#5xDxyG zEtP%jizpd+(n9IOo~>gas`_oN=(*_i=wsZJ2Rdf|^yfCu^-5&OKCGoA>BcykQ2M*w z^lc^DS*z{oMtxeHBmWvR>S{$8lWMyj%{~?a!9IMu90%tL&lCNaa7Pj2ICRPb-49|M z+OGC47C)=tLsy`90RM6{m_|AM>9bmG7*PXb7V1=~yCc6~+B1jAM&qzRGWZe4fRw zJg3iEUZX?=ZPlE4V9xpB+hy6F5p`(Hn@iBgp6Fxl5wkIl zVe|Xut0K4iD=gbMs;rn3lU_4(W@^^55wfh&S5$4qO#P#I3-am6)U2h^Cq6I_5@G%i zc^7vXl7tBJtt)pDVNqE|`}*&AOm^R>$IK=`5^@#HDnW&cDU8~)>;>737w zmUeGFX~j<8->5w%Ngqk_Tqm}4eYTU`CXRn}-{Ia$3@(S<5 zJ=gU8mF0nT^xfnLx}*=5zN1!W6)|_-O4*M#LLX0W(kN{*m^LYVe~ux>BIS;aF#|N{I>yEt@)3G8ve@0UnlT$$JK-L9wM=ft7??ID&K!hl7Au+ z{XFo|UX9&*^fydLAg=uE^fSuOv?Ote)YbBHTgzpPC5dB|IVLs7P|Ib+U`76LP&)Ve z3F)v$#%F*2uosllhV?Oj+eKz7%YRyRA1MzXKBzwT>3uPyRy_Edj<>EIp8X5|+wPoR zt>Vam^-;h1AF0Li*s&uk=p^}K_BI_$^gc1`IB-(xqC{$OrXufF(0CX5tS{1k-Y_Ap zj~Vow6X=@3qv14CqdWIgIB)|A%mz1{p$+H{#dEWF4JsKwy zSB%Sk0T154+b!u0{rU^5$2VTR=^1X)Yi(gQ_vzQ0@cGz5;=Re|o|KOKx}UJR`@L0~ zo}owMIhpHDO?!dWZ{NPZ!_PrCgDYq}19|p|*<;sDkoDHF>U8Di0~hueR`-wo5m;R} zW{d11*oyPqvFdc?rbj2qrbnEWe!Ikpf^e)f8ZCu+^(z)!OZr+>Ow)>U69+ zljPnpgR)6rb>}%J<<35yRRxXQ4qGL#)fI2w-|g(5$)4Pk8HS^ zQ}Ya6v}65P0&}n*Y?Xe#R>RGlnrGZzt7tJ;TJXk;d3TX>j zwB{LlH1;2dFPYO;FF!vn_p6L&=+XF{hG`v*p_qf`BHCA7=?t~cYn`6qtfQw0D`Ziy zn)TqajbVtZ8%|x2zj@)AI>MJaJwuO9lD$6JC0`t@c0{!MmD4lyXxx3hVqD|*n1eSX zGpw-e7-5Ah+UXg-dFg5D!PhYd_Z~Z_F%Pyn`P`H8?WX@qSRspcdWIeiR@a@He-Es7 zMP_gcpwlz-=p^~-tP>l{gB4O@;#f6Zx$~jD4;EI)qF{CYm@OJNX%=;?ny%dG(eU{Z zXXW2$7ImzeuH5O-Npd`F)fcSpz>4EW=vg%#t0wM-j~Uds0<6ZLb5iO?=vh_J$PBO* zSLa;gmj%LfqQBz%^DQOG#$d&DkeSr?&RSl*YEHyBR{d~L{wGAq=Fq!-ghZIe^=O<3 zYleFUI?-FvGxTFhk`eIWU%}{fc+h*wGxTWub^gf+(lRo+z34@-Q9_jMQ*f zimRHlk7rdu#|$?FE2oQwnrG-d2v+|=T)hGhE)Ff~qM_y)dUTTf9hv$vu=))YfQzM? zXXw#5alss12644EbfTL%HP6sRJ2b=EnnlM#$+($Q^9(&YNwz-wi+nLe`vj;ZH}7hm zp+{q{hJ3XGSbd;6(Ug~G=rRLX)ijHK2G!@XOhu7-bdr4e!JzydWQG-0@0x=24E^|$ z-yf5wny-Fbr*vZ(Cnkwq&?-!t@R$)c%d(S}#stYr*68c!QS>8}J^&4o_% zirzEyI{u!58GK1T{cKZF9-?!n% z`mm#a2ex_=TGZ{4J3T{>PLiXr6CQ~gD_8coxaWl({l&0V zf`bsp%J1UacEU^I)ZlTR$oJlx)FL- z6*Qi7f~{Txs|T>+IQw{36?Bq}(cSh)tj;bP3eV7a5Ul=-OMRGLl^DH5TA^>FI@+=`X4A6H**Tl(4(P! z&i*2ugJ}O9l#H8qg=gr|NwNd-6|?C32TT&3Xj;uPbeRFHcGn&KVqoU7OyzXYqa}-` znneX+O3yR&6JAkm+)Qzccbi&Wt@f992!~lq36oGOZ(v$R(vg% zEhknH{vHeMV|_SV)tomw@jKP`E}y;q?zWA`p13jhS2$OQ<{r?ugy%VTTrXQ5<2Z1^ zn;k@y++Ua2HH4pOn0fB*l5f}5>U3qq?o}_pkbVwUGf((BPi1|7ZcMPB8+qny zxiK}X2=e*_ecbcJ`l8#d58t1&H2QGcTBjx8p5r$g;N8# z{>PVJ$Ug$B2QhMgg-V8Kp11mz@I>Q|>ot~vKlXt?s1sR>Uh@d2ADi%Cc|R)I2ltA6 zEvJ^+cH2wdyL^MTdKghcR_ueZ+umOpl|0MPKDy9H?rS+F!Z0E*Kk`*DjtQ6_KH7bM z&TciF`;^x0f^|jp87pVES``5g=JW?=l)vJdD0S@a_7!Vr4#eP(}DF zzCYhm72)k(uHlP54N*mS-}?Kf9{t@2A4{c@DZMF(F7u!thn2Zj32RbvEjFaaOZ7>qV{=h`YSJOihG7DA^Y$jpI>@&@@9>z zo}ALL*5u8yBadCK_;~(G#l{y6YOy^0hj!lVtLyCpKoxnLlEu6DOr}pZYSw-$ z7l#el7_9ydR%?zvAU))|jfK_Qw_Q*iJYpSb*BJWo;S>j~hTU*u$A9)ZO;~+8^nzlg zJJuFf#?X%s_s?IMnBPA7i?rB!q_A4|zGsTZYRd~NV@Ou74!W?o=ZST|>Whh+H7=Qa zZ#r-ITEgnXq0bc0zP+5VGKOSjXx!TdtDA=QPUqe=R#+W)+T7yY!gBh4wWfUVZb1(kLyu09lV6*dk6QaD*_<&e z39D~+T)p+uOScOvV@Ou(J+)Zto^#$qd>uMzv&P83teo9@@Vu05O?~@^t+8Wo7golQ ztPGtb6T#|}iKEi|(lv$E6$kzhcDhYi8AG;Y=p@+#tfqf?V0Pu!Po`|^mLCsj9k$nA z!pazu)lG-54m;feR^LBsv&O*Z`)3%0~B6jsL2j}NNv<%xNp&yUTD2X+xw+204ZrZ00z(=#NiXATs zH0~lJu70{-dHt!*DXUIbmND7*@ZAr3 zaL8ot=o2zgR-LXaW3urj$?C{g$H7+1KDbNnMp$#KIvuM{oJN7wH?Y-KpRbm?5!M_l zKPDh<0jsxRtMTWK?soR6IaYp5K+J{*fArOX*|%FiDXcUagq6lv&3Ukfud0C6FJI`N zZFb8g!b)RFSg8jqXx#q*tFQJPpFVQOE5b@+Nmyx&RnWLsglOL%bMVPAD>Y~zojKC3 zF(fOEcCea_%&^_7D`x`_nkTGu=19B7kS!S+Cq-cO*`!hF$$wZgr+swZ2`ghrOB*^# z&H$?=kgwiw zzSv$^X^yIUh8~?H?<3l`*zb#U^KC{7E6vEl${3QBX3;u+Jp#7+@5Fo46NarNtTZDF zD`QAjhQ^(0u=;37@ATq3#|kUW=fcVu`te~^!-{h**1-enhYKrR`-GJ-Br9EU!0HXG zI2Z1JK)T}%8w)F4`-GJ-Br8MXse7>c^7sVXKRv8CJr7+19K-?6@Ixg0M1%WM$}bb>118VWkr% z39Gl>-eE)N1YucbVJElT-Bgt%vQosZ6)ZSWO67OVTBm2LCIKL2}6ym8k7uJsglW|WP}wWyapv> zaU~2jt^^&FOb#U@tPtTfC>e_@VMtbpD?tY((}0o@R>)U%C>hCD#*nNq2WwC=V5LeX zhmsLi$Od&N8Oc}1kgNQFM0uZ$sC89FGL29%7jLhh?W$p|ZBNLI*K zbtoC+D^)TLC>hJ`c<%9bVPy=-%Fsc{dNnwhq>zWGuG}L$X3{7j#fE4Ja95 zg_XVzB_r!A)gL)CDVYC5ms2~>rgVXzG58|hGb>vpk#6=8DRy@P=}Hc z&46`K7?PEtgOZU`1Gc5COp6FZvVxMSL&;!0S0y6|wxz60iwHy45)i6no3*@@u6A}E;#l#H;_Xb@KFg9GnXF(fNP2PM;hk`Y##Wm=vgS!ref zD^)T%luX99G|RMDHijM@luQmKBdjz>wLC+Q4oW76k`Y!|>6wv*l`$kM&7!TKWO67O zVWk;aSQ$gIGIUTfIh2gBf=*yQ7gom5k1r^h97;x5VWsElC9I4gSwYEg#Q`f-GC7ot zu)<2u)k|0zL$We-P%_<6GQtWvfoq?zGKOSj=%8e}p=5-Wop`WaV@Os|GF+X(N|j7E zl#H;l6A!j)3_Ut1nb}Y>!pcrO=s{!X(WT0mGH3qmp8(;nux$MiZ7tz#4k(z*pPbU& z2dsSWEZdko8t)HcA2sT=XQ-AkKSGuh`8Py-W9V`mTitMD_u_k>Calbgo}nL8lDrO9 zyN*5}AB!^?GBHnih8|t|LiTTNc%xp-1ESE2!|s=r8iwIQJnFn>n7LN8_FsSp75`mfwl<61HV? zn`L82RyJ3#M!{C^zWYhO5zb`Tmd|j;(4+BGF?K9dC--mMhI1b>u`J^m`tg-2TP8OG3~ zljLyN>hjU!^Of&?rGstRn&BCemF3_h`7dm>_4EB3192w9wrpMU3_UtY`h(S7Umn=F z2&)=dss0dF#?YhjoD5hUz2k)Za-5g2Ew2EKAz9gag$xH5{&4Sx9fv5gyX?n73pKV;Q6hJJh%mC@x`*=YoIiB}v@084?@q{*98$#gkZqR5P) zYYB*V5LdhGccLI1D?3#YE#g`N;#Sz|Z?M%KI4^M{6lH08j?wj?wE!#5-TNPqkHDD>+frpAtc;-_AHG$L73Vmt zgNNYUhfGv|2rFag$A>4+V5%U`&sheFDRJ~C>e_@-YXIh+If=Niub8tD^)Tnl#Iny;ZAXcq1sBu7nDp2C1Y{L zdqTp>&c)PLf(}ZCcYcHwBAoY%EUtv1#ue{Vft4zm6iP-|A;Nh-%Hm2Gk`_bCCChEUtthSs^L~9h6K8B_phm4S26evZyg6E6hROrvfWgGAWddutL7#{V2(z z#*nNG9h6K4B_phmuXs;La=S4kD?w$p|at_7+c4812T8tPCBLObR7q>mctH2`ghrR!}n7lkgWSRmo&f zGPVx#ew47n>LU!v%Fsc{WKc4;4)UImurh{ZW$2(}QYaZ=g%z3iie!DoIw%au3QC6e zslZB=Oa>(*te_KkKT0$M)jLCMISAGW2eny&2c z0zm<&lF1VM;|P^i)0Is#$oPVi5d^)atn5^UcdbkZ$@qejNugvq+z1QD%Jh}oJqt=E zgOW+fMD0^JR(?#)pky*AnUt*5K80uK(Lu?iP%^?wqd{1y5A5tj?lcA^lR?P{D~$$W zWeolJf|ALgWQ3K*lCUy{etbd6q);*`+tQgMtc;C6#U#*i%;x-thd zH}8a%F(fNP2PKn2$p|aWGA+;0Wd^X~nGBRn3MG@VEzL45mW`oD2PKn1$p|aWQ7zBV zql1!3p=5-WW@KSy49QBfDDsRdnG{M!SZPKUR>qL53>}nA3MC_~^q!EgGKPM9LCJJL z$p|Z5`-GJ-Br7Nxt~g+&N+yMp5mtJ?Mpzj`vNCi~GAWddu+p_pSQ$gIGIUTfBcNo2 zm7RF7U1LaAdKU<+RLOKe$p|YuvtYZ%(4&Kr;TS`ako56C_qV0(NS6Ht;;@V%-SnI59zo`ve=1nQ&OLR=X?D7L;pE%AV!X8Z|}p`vN=J- zk@qcEY%pts9uQzv7%QtqM4adCeVA`q%X`yep~6Z$Xc~tI#8_d`Zs-a^Mh-t0HlsWu zD$90OHrLpPk6nxDMf>o6_EEBk&%20ayXIS#y$3B8Dt*YveJzd3o_$WJ^Z_5#=qdK$ zBPO0%wvXI<%_4(ni-o|d%k?4Az*;^^7V&vN_$aY;iD=c-G8bi@2LwhA6<$WT`d>y4 z8>%j8ABT?;ZC7Tk`Je2oxx}tGCW2TbN&+jkVOiA2m|CHlOT>c~4eZ0u^B#RJ9<=#P zghpk>o8%D2A$@p1d&GD9+&raygr@?{PnAB5Rd`Cz`{uh5<|+1JbDL#DFWQIMowbx< zon^E1q6oXvj_A=JG7din{fx4iwrC%IPWah{KID$jq6j~7&2~*PG%GBMFuts1=NBxq zX3uMs`Ifbe3CqTC(LR((Cu=D~iT3Z#qBc8;@N@9HJ*Z5?Ys%0(C<-S@e!1B2#>8Q( z=l$?swre9~8Qzpy!-p?h?7P!4wdT$1VMaZ;`0&OVLs!qAPD+HYHF~Gt*3Q_a4^AmO z;yu*t)&J%Ej1^XqJ}if`*2r7GuB~(C8`wcETfBVooZ8Z7FNr>W+iQ4Z*Y#h{zgd2j zhQH!jv1~2jYh38#xYPSK_FDY@++ShYRtC28La!C;|NY6$HGKUW<2d!yzKt)E65(ro zIcweet?T|mSVhFiuu;EWTQt5}>I!)}!4T}j@(25Pa{vDIeV6-PCr%A8jtv&uqS1Sq z65(rIzS4&E>jz$dJ+4QrjXu^|ZgAs+%@2}0iiThxHYbRf(7$he;BR+!ARfHh}e7v>RP0Wl$2s`2r=3#AXsSFH8?E05O>KWAyE{$-0-`+tEl-+G$| z>+aKQsm9p%7N-7+XT`F$lq83skB|O#X}-^p0hzzTvdsy$^ze3P*Y0`ehb_GJ0)HGl z|I++{!6m}i+Wx@hYG3_i17Q^rzkB+0-pNQ>{U4KO4JQAN$*->7Y1rQDj8Gx`kO6<0#6Jp9I9; zf!GNM*0L*}70WTVzX5;j)@!M35BS4hVcD_)TY?ACA3gXd^f5D8DqCwoiSV@$B^YTL zB@uBf5czV0v*$FfEL*Z&#BR%C7m?U1Bk@Ow-SvU^9I?wI6pzJ?b3$wOmvo<0$Gh~(-tX=kDii2p(^H!M| zh&cB2zS*dlOGM+c7V=eL`6?o=fUWB5znp%GeC69^+15m&k>QFm!>x;P9J}7jX=}L> z;cFp_7M4XLVjtM*jA5&%YvI4XU6vW`T$k7fGIddA>L3(8L_nyc;T1&E; z)(ZQCm`kQ%9CMIG2gJ-E*-}|ardC$67scuf!~@9f!!gfU%W^o&wi*zDk;{%1a}bD! zuzoxdZ6zxU5w=DV0qe@1I!P|Z$X7_VXzYMF$Xd4Ev1}_R5wM{F0T2<_^Hmv%>%E*mjrqY^rVUs&l|h85k0f~% zL-;F1TP@#G*+<{`zserZo?GN(JD%1KxAzTnJP-HzdDiEo)hgp)e}-TmRxbN6gulYF zjhtvJmk8{>+V29`^9;NT0DUz)+#M(pZytJbHvR2iVtxz{C-lA+`?LEARfNC7ay&hc zEtLqhmE1AW5!M_6$}%8ol|C>(0$<$0h_yVrittxhwmUSwr4pfWh4~Spp-zPQT*_)) zWu^XTu$GO3XkYFb!CH2OXkRvT$x7#-u(JE7MEJ7CG}J8rY3vFsAj1hO*j>iqYq7tc5&jCx9&P2473O&Z^IYa2<^-Q^vb&b@ zggX1f4A!UBiNUOGAj8QVM2yNfd@c6ZGs0hC*`uvoVP)Bez1y9*P*%20L3G*q65F+L zkW~-m5&>9wBIRn?ol$wl%eN$bBb6i2hlbrmU~9{D`aK0ST=Oohh_$0g}Kdn zAgjJ903ynox}GOG2Zfc5!;gt&YpFyU!e3##R*Pk8smjXt?h(GF5@FV5EgLOs`Es=n zixSq-s1~o8eb|zf%RY1tie|8=Cfb*)KDSxRS~k}l!q#?~&1D~!eOOC-m-W@=9a&kq zGIGg2IzsH7!pLn+)HjiksR!6^9u8NQLHddfabWv~`()#B44EMv5o4`mLva)~gt#9Ht{yFxPS^6#CMK4hM2 zTQ*bKpXDwomk1q)M7#2p`Qgj(6UU_XQ(Fl_Z6XL?RvThm_^v^!-!*7ldBx^-9~fTS z+@6RRf0S&v)}Dg9#~e1&Xfz?&`uEAq?@{COESuW4eqm!iA^u%nB>u&5= zebi~f%1-4yLywlX0aN|1fv~dYtk|wGBrA*1B)MqfX4zNxuEF5V))H3sESG2K(Mj?I zSoOoZuS4$`E3E9k0a+PCkCwLqQ~j=iu(Ic@*sd`os~GKFu+>2eK1ol*lV@zpp5hKkVdh!FLS? zA2KgzTlOrMXXw%R#VN2l^UP7{e=c5ASlL}NvNDDqEpG#+`dtGkna%AfB@kuEA+|@{DcSvs|8`N8@{aVDQu7j@eYcYtTg|c1OvTJ3U(7 z22Az423QA!2a!2LyKTGF+ra9e3x;MF;K?&L!os!N^k_V#2UbVyFd_Z-S)=hAZoz}d zuaTig%iDmde%C-)*>hH&q4OYG+7}+Y6W=vB8&96GEqj*BGxTV@SqxTNj~t)wdfO|) z%I;cuh8`_%1E%_2gN$w2Q(7z=L$b1!2=fEcemTBta6O(pV_WvDnrGVa(RXxog@!{ z)!ON>^oY;47gn01u--+69xYFWrTSe1VP(%*v0Y5TKf7(Lu+n@ktc;;Y%iDmde%C-)*;86<*BFvjT+dH|t(HIFfbZEb#XF@WDc@(jt!##gS+k2dFzxailDgw>PJH3#tfNA#dE^yr{u^i4f! ztHw7c*{(69t!!rzluS32jM+-wob(JmIw+ahP%>sKy-&VXVGKPwC>eg&z~ZXLw@h`k z!jP<>WMuD?B&uX`C>e_@zV~mo5{4cfluS32jK!6_WvaFkhH5K82PMPr8VD;yIKOKk ztPoeiP~%GWhC#{XP%^>_bCBOP5LSqMVMtbn4oW76k`Y#jaDLao;z}5jm7#-@;dc#$ z74j9oYaqGZ7?Ks{Aa@gJNtH|vB_phmuj>3l6WcY0WM$}}WO67OVTF7pZ!gnU#?YgK zlHqp^gcUL;zZxK{j3HUYy_zbS29%8DcHAGhU04}IvNCi~GC7otutMg?i zVPy=-%Fsc{@Vf@W3Yvjm4UqL!-wd<;j-1Z~C4=8AhojKC3F?7+6mQ=|!pk#!V&Kzmi7_ucp2PKn3$-s+Y-U%yXNJ|?!C>eg&Kv-#( zk=?H`beRDysglW|WEyNsbCm3UjiDc3P%=4`jIh!ig*hD=vL!aRWdo0jIe@|;p!!dd8Pi&EuF(fNP2PLC#>ctZewrdQ@N>^vt zN|j7El#H;l6A!j)3_Ut1nb}Y>!b+b#6%QIik1kclipBidPXOVsux$NtOtGcYpPh^}7bbO7(}`sis0|TRHW- z1bGB+YDQL~mW&};sp7zTejPmcUin>v#IX`ZW(-|RK;XLuseacWp?yphxpJGzAgi%E zOvqn^B6A}wT)R!j3guZ~bqKy|a0(y$np8n zI4@ya8tuX=YQx|`WWBNQ;7oki;5eMguq}=D!ZY;aleYm={jPzX=_9X~clb2MDrl&1 z*y^weqw=e8Uc$CCGYBhV=%O90#vs}!aA*y_|xd*^H3K2})iiqrB8$;$R^NwO|%wa=t`^Ve`D!?twA5mv^qipKXWQ~j=i zuu}bD_gG|~>Bom>qrhritbRk`Gz0JFuq`_y z@eKX=?DP(jG;#dB{Kp_#%xva+f<$*ZDnUC_>~y2fs*Nfk}+HHy??Ql zF|49h$?&@dW-HzY6b~9hKfa)3I-q1MuK3=+u(I7GX$Mn1k}BO;9o^l#H-K zzLM{3vt46IRyIEQt^t({ziS|@kgw!^CgaK&dUQ}SDU^(`LgvI9RpEq17?M>yjaDU- zLCIKd=T`$H4;n+Vvhjs1%I_KoD?26Ed?gIY%Fsc{q);-p4)Uu3mfM9PSwYFP%F`WH zG8vSNt%H2;-?FnXBr6-AeAj?VhTk=?bx`gWla(!o&7fZpP$i?!CyKt3uMu#x#;}T3B_jyhM_JjaiZJx(k`fL0G4 zL|K(g1|=h`G#Z4JG4$gLN`~Jx5LOyXcGklftDu9DNugwNwxu&iSQ$eX?O>%!CWDd@ zRyuQ}U1P|WB3gG7@@)|}?}U{xq^%4cluQaGBdj#b)ICG8(#!x>s$^0qnFia^993u8 z7*^4$WcXc!23cv2s(XeW9h6K8B_pgfp9?EvNLHFfp&?btq);-#O7pp}GKORo(W+$l zT?1jI`CM2TLqEQtWICW^gq5y+!pazumEHvcD^)Tnl#H;_wNF?XL$Zo!RWkgpfv|#3 zkf(HLD`QAjh7L+*1eA=hvNH>|YYfRsS7)*+l}rbejIgp354LLzt7v?oiAsjwH4s*b z{0mPW2}6(O?mA&nRzq>vJ;cLawZe?#l z^ni%HOD(jC z;jVAgbh0H~KbmYe#1+b0*_%3oh%2(!4DATEfp;*(qESbOc*EZvqKkb*yH~9n{iF!g z=D%vKxCabpGSMF;0ElQspVhn#+xv(ac`JLDsK&lyyt#1*D{s+0MTEYi)XB2el5#xpatNTSIT8NA9mN?n{#_#m<#vSk zxmsEf(VOjvcqRBo5Z~={??LUaAgkz`_CDg3Ft-KKqX%W=en#nNtq*>`2IclXqTQ>O zj+w6=5$!JXBUm^3$sxKpLhl2OnA-pCk7&g(Cpw9UGtKpZF@?D;v8!|5;+S74sYbgX z{QU3;&B0ZKjKkZ?M`Dj7mp)>|g=|+R+wWcn(XQ?@f{qps#tiO8F03M7KT~D3`;L)& z4|;z@KWQImpZ|i!5sUiV&Z}k4cdP^fi-tRKnpb4xaZPMT`0S%-=`UuY2NoZm9fYqG zJd^NOh!+_xziWV#kge@qLZI;`YqlD`QZRXiRRj^+ifaiG`o1D8Jpg^2g)a!K+v|Sp z31cmmZB7uO??eJ|Xs_Yf#`qq4`}#WESnFA(D&$p zz+3UML&cl--Fk)Z%R^K9T3#pO-PcUteTCkw*0Mg>U(`fbVjPd+t@urbl&rk=vGtWL z>D#$rbsrFT_ciNWP>$Scv0YdJXBjiFZxdU=-^}w}K-_`%glDRCtriiMKZww`jNy-I zu+Hz7=Xjeu!OHWB)^G!W~fkCX9k_(RK; zk!ZDuuuMdRzLAZw%)vOm#Jl0QFIGmo)gl5@Oy(UCEaRAex=hp)wQv`@5~yy=~7Sib4q;cKxReGq+< zB+p~yhromQ`UUpqu@=kvrgx22h@K_l21Lo4h!S6m37Jtbs$;Dx8gF`M58_SljS%g6h3|&TjEXZg&fs$77)Qg#VYP^k z*&t?#B$@>>H@$y`X!o^Pj#({cJA91sq^fH{8A_!m?&K^an(~Olzm~k0%|4-FCd<`|y3^WCDmeyR491*Rg%2 z57x4gvnBNt`dA27^}(BG^VaJp2w%&;w;vIop^y9e?Vg=7_fv^oL$D9?2m4UZ!Wyrk zk7wr}n%z3<)mwjmDBNNR8ZxOR5Ok5K>z&Dr=GjK*4 zzZxPlDt(~e?v0D1&qFQ$)e!hYzR807QHZPO<{#R)OXJGgWgmz!ezOKA=@M7+r5Jqo zqm13gl7D~7VmH+C-x)z%DMIH*!{&#z%RaPL!9Miwm>-;jbHVC?I0xC5)bd{@iHJ|j zdET&jZtb!U9j%~seDM9}=wp|`n>YRxa|vxCwfwhCBH{`3fqd1ld}Zyj4@4ioK!ba1 z@#`mL7JX*-$MVZ#77exh*H6^5@D*Ygnnz-{!FDx9rCpZY7n&HMKxp30UEY-|o|SJY zey!Hl(R9U?dhltiI1j1^ z^-7ZrZ5<>+Tf#UQC74keXB2B`?>3{reSSfNvIT-F1M?&0{2)Tt4~sPY~eew4(K)n2y?b6yQ zGX(L$g4xA;i!CMyLlg0z!zLEf|3IIt3dEBSPE4QK`C>u5@#=@gw=29{BP&A_vHgPX zV)|Wd=?_3$QoAO7=vRl9tTtY@_1WFm3c}Dt6l;E5+&kz80dw%WK{s*0fXc$)*nuy*v z{iwC`9XkRs9Eg`+dnARuyBwnF%AG_^o3T!-_v&Y(r7eNzx}cfvfBy~G(T8>mhiEzk zTG}0mQ5Z+sZyoeAu2AlRP*#Owg}?U);-}kQlWudwp@LBR2*S`r=*aPRT6dENCZ@f2 zx>ykEgBJTUG!bfDAl3(B_1CvcN1i&PWK~9qAPh}}dJuo-IKD+(J+Rfog3wqJghok= z2#pf_{dgd*ow|OzK74M4Qx z?;7phh;|!C4bg6W2wMB7A=>eGjrJVTE(naahG-WA#vy1OM-9=AziYJTh;~81qBTUj z_`}ddz*aRxI}jS}IikH}wehlbM7tmiO$7W=L$u@X8tplvT@Z+jI-*?=@VTIgfY0lQ zcKltVJx8=lBqG}Dh<1rxLlc2$uOr%l&}h#S`6u&(h)#`NK@)*!uOr&gl16)uXqOqK z?baN^<_8gINuxbSw4)!1c5)Ylp&cvyU86lmv7lWJUDx)PocA_mJCJ%dF_pM3~+1-W?Ek)~?BOagiAA?@sF5d&WowYPdBs&|L2+Lhb@(UnV`{k$I4iXRmBexS_8QG)Rhem!YM0*FK-TI*ZkUk7egys1V?H!1A z8wd4=AmW-4G!gn>Zb!7Ih;~6>wA3Fq4neaITd$zVfIzgTh;~81AJiY>b3?1GsEN>r zMth2A7lf_C9J!&1fIp~-;B$@k6wxjS)gRJ_p@mhcYJkvaPZ8}BiK;&&b`4DgqMe!u z2+i#&^9GriVsYgr5vqw$)@V-=?J}dZU73T1c8E^=x(aNCXipLCIonn4f-tmWRSVIc zBH9I^_7Q}kiBMGo1amv0Jw>z&LVZwo)Zd8M=4?#rVjw`$eV=S~Ie62WBWj^W-xgFvC z>?1~Vdk^FAh?v!Sh!Pn$M;_-|$ZFz`I5*o_!Ow-|l2|KbIK)Cb!p}jUOM0A9V%_Ll z$t%H|F&5hUh`t?Hcn`){aELCB+}F~mghfNP>%qElc81Z)4355WeaJZCl`7)9J?LjG z#-!`3pTX^YcpqrH;z3<;s{W9Xd+TbslOylZRx%Ftn%GCZX(QKp)6Oc+gX-*34F_~P zBHAQGrSunLx*ZWm7-kVhE15_mv>oANH>$9(a#n36BlmITqa;R;>!XXk!{;HFcw2q< z$kop>TJ?XY`a@S#?E~$HyvuVq8Ewq9|JTT4@6|Ob`pJz0-FTZ+*V@=$JHqEgpW$NW zYez(VE*=bLCvhz~4^J-t4)0(ckN@7k*$%}8d!0A1_stu&SUzU8j8K6y9DQk9U4Ng5@jwe_eZUsW(KC+l~ysYl%Kq z2Vx8mY|E~&Y<>8a@N2X{9D(;B_r-gVywdgF%JrpgzD3%F-j$OZ-x8jH0AkMb{TmnI z?HZ3@`OrPrt)Fn$Zi0rs)>9n5-G2iRmjJ=G>q;#hc?DguuIP4a*Z0S=wS*^~(8rPR;C^`jgI6>% zq+RuYrN1&tHbs<-##`|o!LmlB>?|~5karm++XBIF8`3^@g=Oo*w}d?>5WVou=&^Xy zf>(4FNxM2%dgx;YX4GByu7O9etg}`SI%~m-vvw8`e*}U|>GE>-*C&NlVy4 zmg7ioi6bwNaim?0gJ%Gh{z5KEkxOJ8@LGXfBDLTfo*-1v__a;+@!`aK(-VPE`$)TL zAL)-}YpEQ09pAG&B}PesjAL;n_dM8=^%rtUhFoIN-a;<1=#zUML?B}HjtR5qQTQ_6 z0YLaGWP&)B{#Zt|OG{W|fXMOX$eH*`0k2>Vwvch856l(0OTw1oUR`rZhFl^DWQG=U ziDiQpPl1UrblJz<=MBw%gl`V`E51LLt)((wA^XS^hwh5xC_S0*<<5{xGUSrfwOhFU zq-^N2kE_6HalAjsT6V?v=Ub9rab@<&n0I+attjoPeJcHxxdf|0hFnrX5Uu_YgnAIM zeF6M&7!dmaK~{E!W$VNDU1pyjA+ESa@rp)ViwKP+DO*cr?7olKJt3}~jCNVikyjYI zg3!4Fg`;aN=SRkN?TYWi_Z`;rlL*0 z!pg3&mi6KLE;9pk2{S`w9IRy{uOisTNLcsSr~u@2khRQ%ESuHCij#3YClj3q1#9W- zlCnilHQI^LNbDrS=7cLZ%kTS4M97^o4j$%s>O@1xeGWxXCkmPwoT~)x>;v%u!v(Hh9)9D!!ieb3_Bys4q10uLHGzaG!gbR41C^uPWqP-duIPQuPJMk zt!nJU&_u*1YnBJ%yt5C@QrszHEkExJO@uw8lO(Uex_jJx1lOo8hiJNTClT>^pEu|a z^zr_y+sSI6?OH5x6>U016Wi;HVQ9w+p6rcre06%3jaYZtj0m-l zMITrFf(RWs5NE-)aL(tj>pLD_;)M(EU?Sin`spAl|j)PA?0in^} zK(q@27L|P_5r!tho*crnQDw9@5bc7noI!-4WgO)*Q}BmIdjrvKaV5J(A`DH0JG%1g*>!l6@GO2z^=%h;xuj?*Hh~?&Fc$ z{S}spW+|F7yLXRfG#*`!%A~Os+ zxNoC|+|F8NMUN)J?1nGhqK{3^$QoneLDn))c{CB`*(CWrGTf^p_H4X{+|F9|B%ntV zVg65&?*nn}*@repBDb@aJtOGRL|BaB%fqnl$h(h_Xm<$9&hmsI5jG2wa|XRVQ%kv*CS%fTVqI}q*Ghdd+f(L`9DNA@YBol3^W zAx|!AAA;6CcxnJv8to~fT@bJppH^=XVe68Pqu?qLqCG>jm*Xg(N*8|^nh4lR*2EC) z8KPYf@HyIH&UL;CP zKZIzP-8S1*gjX+K)gX2?+A~CZPK2o=nM(VijN1)K;vmS{De7_7u@B2=%id3{8Z3upXkFN=6W-gxQCoi9ob7 zN`TO4??AK*f*G0FnFvD@foNwW0N%Heu zk8CV{*EJn8UU*o1uI=LcO(Tqzl&z&C*$IeSW*?Z|wAWSmJ>d~%-NGZt(Bim6_QsDk z&%x{viVU(&{n5z zwq`o_@Y|&ii$0>QKO!uS%RbcS(uc3*%Mq~;`T(x$=H5-~gW4J2i60T7oqd#TbI-|t z8tu}Dv0^P>E^89Oar|bpHS;HQ9AF~v6=)yQpN>P`Ll9)wuk}|E+iRhZ9uVq}-24HH zqURanbL)?NAS&g}g|d$|@f(Ma;x`V}qQZ)`dPZ;#E_v;J`816yM208}qOCuo5he1j zL)pi=_{GB6_{GBZT0J9le&jYkv@MzE)*t)Oaw3*MYQ$jEZvfEBy;jeN zpP`Q>?z*OXCbB3IWg8n=7M1?khenL{p>ZXB7%SHDMp(7WBj?h-;Fz0P{l?b)2Aj-dlwbo}MDVNvbLH;7N^+BCj zS)IwsGEs>@TxFc+td`m^~c`msdlI5O5!zNN}gB}-O1KAjC}D?zADED~uq zn=4XIk`DYb_cVN^U~Bn3`Z%NbY(sp8!9TaQ8ERh8@8$HQ+Sd}h>610I?%ut&Xbe+-z`7dMzLtOfY7h{6oz}O}XR*@f@SsMuuO#i;hR{L?!_ftWsQ^?ZB$mmWkUYE=7LK8|VKnLseweS{NT&bP3ZXiJ-; z=47xs1+0j$XQO<7EJwEg1H`r%`TK}=BJ9aCUyJ2v5smi77+9Bx|JTGB;vf(OF?7Q^ z?t;N!NDzcGkWJtYYd8rSG#5alQCx|>%`{V2(aHaRrqeaeI$@eDaCiNnGo<# + + fanuc_crx_description + 2.0.6 + TF and robot description for CRX-10iA + + Christoph Andres + + + BSD + + + ament_cmake + + + ament_cmake + + diff --git a/ros2_foxy_core/fanuc_crx_description/robots/crx10ia.xacro b/ros2_foxy_core/fanuc_crx_description/robots/crx10ia.xacro new file mode 100644 index 0000000..11ccbd3 --- /dev/null +++ b/ros2_foxy_core/fanuc_crx_description/robots/crx10ia.xacro @@ -0,0 +1,183 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros2_foxy_core/fanuc_msg_translator_msgs/CMakeLists.txt b/ros2_foxy_core/fanuc_msg_translator_msgs/CMakeLists.txt new file mode 100644 index 0000000..a1782db --- /dev/null +++ b/ros2_foxy_core/fanuc_msg_translator_msgs/CMakeLists.txt @@ -0,0 +1,34 @@ +cmake_minimum_required(VERSION 3.5) +project(fanuc_msg_translator_msgs) + +# Default to C99 +if(NOT CMAKE_C_STANDARD) + set(CMAKE_C_STANDARD 99) +endif() + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(std_msgs REQUIRED) +find_package(builtin_interfaces REQUIRED) +find_package(rosidl_default_generators REQUIRED) + +rosidl_generate_interfaces(${PROJECT_NAME} + "msg/FanucTrajectoryConverterQueue.msg" + "msg/FanucTrajectoryConverterQueueItem.msg" + "msg/FanucTrajectoryConverterCancel.msg" + "msg/FanucRobotStatus.msg" + "msg/FanucRobotStatusTriState.msg" + "msg/FanucPayloadNum.msg" + DEPENDENCIES std_msgs builtin_interfaces # Add packages that above messages depend on, in this case geometry_msgs for Sphere.msg +) + +ament_package() diff --git a/ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucPayloadNum.msg b/ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucPayloadNum.msg new file mode 100644 index 0000000..245b1de --- /dev/null +++ b/ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucPayloadNum.msg @@ -0,0 +1,3 @@ +std_msgs/Header header + +int16 payload_num diff --git a/ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucRobotStatus.msg b/ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucRobotStatus.msg new file mode 100644 index 0000000..7b1c9e1 --- /dev/null +++ b/ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucRobotStatus.msg @@ -0,0 +1,32 @@ +# The RobotStatus message contains low level status information +# that is specific to an industrial robot controller + +# The header frame ID is not used +std_msgs/Header header + +# The robot mode captures the operating mode of the robot. When in +# manual, remote motion is not possible. +fanuc_msg_translator_msgs/FanucRobotStatusTriState tp_enabled + +# Estop status: True if robot is e-stopped. The drives are disabled +# and motion is not possible. The e-stop condition must be acknowledged +# and cleared before any motion can begin. +fanuc_msg_translator_msgs/FanucRobotStatusTriState e_stopped + +# Drive power status: True if drives are powered. Motion commands will +# automatically enable the drives if required. Drive power is not requred +# for possible motion +fanuc_msg_translator_msgs/FanucRobotStatusTriState drives_powered + +# Motion enabled: True if robot motion is possible. +fanuc_msg_translator_msgs/FanucRobotStatusTriState motion_possible + +# Motion status: True if robot is in motion, otherwise false +fanuc_msg_translator_msgs/FanucRobotStatusTriState in_motion + +# Error status: True if there is an error condition on the robot. Motion may +# or may not be affected (see motion_possible) +fanuc_msg_translator_msgs/FanucRobotStatusTriState in_error + +# Error code: Vendor specific error code (non zero indicates error) +int32 error_code \ No newline at end of file diff --git a/ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucRobotStatusTriState.msg b/ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucRobotStatusTriState.msg new file mode 100644 index 0000000..6992e4c --- /dev/null +++ b/ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucRobotStatusTriState.msg @@ -0,0 +1,23 @@ + +# The tri-state captures boolean values with the additional state of unknown + +int8 val + +# enumerated values + +# Unknown or unavailable +int8 UNKNOWN=-1 + +# High state +int8 TRUE=1 +int8 ON=1 +int8 ENABLED=1 +int8 HIGH=1 +int8 CLOSED=1 + +# Low state +int8 FALSE=0 +int8 OFF=0 +int8 DISABLED=0 +int8 LOW=0 +int8 OPEN=0 diff --git a/ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterCancel.msg b/ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterCancel.msg new file mode 100644 index 0000000..278b1b3 --- /dev/null +++ b/ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterCancel.msg @@ -0,0 +1,3 @@ +std_msgs/Header header + +builtin_interfaces/Time received_time_stamp diff --git a/ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterQueue.msg b/ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterQueue.msg new file mode 100644 index 0000000..ea2d7e5 --- /dev/null +++ b/ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterQueue.msg @@ -0,0 +1,3 @@ +std_msgs/Header header + +fanuc_msg_translator_msgs/FanucTrajectoryConverterQueueItem[] goals diff --git a/ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterQueueItem.msg b/ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterQueueItem.msg new file mode 100644 index 0000000..6861922 --- /dev/null +++ b/ros2_foxy_core/fanuc_msg_translator_msgs/msg/FanucTrajectoryConverterQueueItem.msg @@ -0,0 +1,7 @@ +builtin_interfaces/Time received_time_stamp + +int16 status_in_queue + +int16 status_on_server + + diff --git a/ros2_foxy_core/fanuc_msg_translator_msgs/package.xml b/ros2_foxy_core/fanuc_msg_translator_msgs/package.xml new file mode 100644 index 0000000..b455ba7 --- /dev/null +++ b/ros2_foxy_core/fanuc_msg_translator_msgs/package.xml @@ -0,0 +1,27 @@ + + + + fanuc_msg_translator_msgs + 0.0.0 + TODO: Package description + fanuc1 + TODO: License declaration + + ament_cmake + + std_msgs + builtin_interfaces + + + rosidl_default_generators + rosidl_default_runtime + rosidl_interface_packages + + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/ros2_humble_crx_description/fanuc_crx_description/CMakeLists.txt b/ros2_humble_crx_description/fanuc_crx_description/CMakeLists.txt new file mode 100644 index 0000000..02af2af --- /dev/null +++ b/ros2_humble_crx_description/fanuc_crx_description/CMakeLists.txt @@ -0,0 +1,7 @@ +cmake_minimum_required(VERSION 3.10.2) +project(fanuc_crx_description) +find_package(ament_cmake REQUIRED) + +ament_package() + +install(DIRECTORY meshes urdf launch robots DESTINATION share/${PROJECT_NAME}) diff --git a/ros2_humble_crx_description/fanuc_crx_description/README.md b/ros2_humble_crx_description/fanuc_crx_description/README.md new file mode 100644 index 0000000..55f3354 --- /dev/null +++ b/ros2_humble_crx_description/fanuc_crx_description/README.md @@ -0,0 +1,5 @@ +# panda_description + +The URDF model and meshes contained in this package were copied from the frankaemika `franka_ros` package and adapted for use with `moveit_resources`. + +All imported files were released under the Apache-2.0 license. diff --git a/ros2_humble_crx_description/fanuc_crx_description/launch/fanuc_1.launch.py b/ros2_humble_crx_description/fanuc_crx_description/launch/fanuc_1.launch.py new file mode 100644 index 0000000..f4d59ce --- /dev/null +++ b/ros2_humble_crx_description/fanuc_crx_description/launch/fanuc_1.launch.py @@ -0,0 +1,93 @@ +import os + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration, Command +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare + +namespace = 'fanuc_1' + + +def generate_launch_description(): + # Set the path to this package. + pkg_share = FindPackageShare(package='fanuc_crx_description').find('fanuc_crx_description') + + # Set the path to the URDF file + urdf_model_path = os.path.join(pkg_share, 'robots/crx10ia.xacro') + + position_x = LaunchConfiguration('x') + position_y = LaunchConfiguration('y') + position_z = LaunchConfiguration('z') + orientation_roll = LaunchConfiguration('roll') + orientation_pitch = LaunchConfiguration('pitch') + orientation_yaw = LaunchConfiguration('yaw') + + declare_x_position = DeclareLaunchArgument( + name='x', + default_value="0", + description='Robot position in x direction' + ) + + declare_y_position = DeclareLaunchArgument( + name='y', + default_value="0", + description='Robot position in y direction' + ) + + declare_z_position = DeclareLaunchArgument( + name='z', + default_value="0", + description='Robot position in z direction' + ) + + declare_roll_orientation = DeclareLaunchArgument( + name='roll', + default_value="0", + description='Robot orientation in roll' + ) + + declare_pitch_orientation = DeclareLaunchArgument( + name='pitch', + default_value="0", + description='Robot orientation in pitch' + ) + + declare_yaw_orientation = DeclareLaunchArgument( + name='yaw', + default_value="0", + description='Robot orientation in yaw' + ) + + start_robot_state_publisher_cmd = Node( + package='robot_state_publisher', + namespace=namespace, + executable='robot_state_publisher', + parameters=[{'frame_prefix': namespace + '/', + 'robot_description': Command(['xacro ', urdf_model_path])}], + arguments=[urdf_model_path] + ) + + start_static_transform_publisher = Node(package="tf2_ros", + executable="static_transform_publisher", + arguments=[position_x, + position_y, + position_z, + orientation_roll, + orientation_pitch, + orientation_yaw, + "map", + namespace + "/base_link"]) + + ld = LaunchDescription() + + ld.add_action(declare_x_position) + ld.add_action(declare_y_position) + ld.add_action(declare_z_position) + ld.add_action(declare_roll_orientation) + ld.add_action(declare_pitch_orientation) + ld.add_action(declare_yaw_orientation) + ld.add_action(start_robot_state_publisher_cmd) + ld.add_action(start_static_transform_publisher) + + return ld diff --git a/ros2_humble_crx_description/fanuc_crx_description/launch/fanuc_2.launch.py b/ros2_humble_crx_description/fanuc_crx_description/launch/fanuc_2.launch.py new file mode 100644 index 0000000..79ec522 --- /dev/null +++ b/ros2_humble_crx_description/fanuc_crx_description/launch/fanuc_2.launch.py @@ -0,0 +1,93 @@ +import os + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration, Command +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare + +namespace = 'fanuc_2' + + +def generate_launch_description(): + # Set the path to this package. + pkg_share = FindPackageShare(package='fanuc_crx_description').find('fanuc_crx_description') + + # Set the path to the URDF file + urdf_model_path = os.path.join(pkg_share, 'robots/crx10ia.xacro') + + position_x = LaunchConfiguration('x') + position_y = LaunchConfiguration('y') + position_z = LaunchConfiguration('z') + orientation_roll = LaunchConfiguration('roll') + orientation_pitch = LaunchConfiguration('pitch') + orientation_yaw = LaunchConfiguration('yaw') + + declare_x_position = DeclareLaunchArgument( + name='x', + default_value="0", + description='Robot position in x direction' + ) + + declare_y_position = DeclareLaunchArgument( + name='y', + default_value="0", + description='Robot position in y direction' + ) + + declare_z_position = DeclareLaunchArgument( + name='z', + default_value="0", + description='Robot position in z direction' + ) + + declare_roll_orientation = DeclareLaunchArgument( + name='roll', + default_value="0", + description='Robot orientation in roll' + ) + + declare_pitch_orientation = DeclareLaunchArgument( + name='pitch', + default_value="0", + description='Robot orientation in pitch' + ) + + declare_yaw_orientation = DeclareLaunchArgument( + name='yaw', + default_value="0", + description='Robot orientation in yaw' + ) + + start_robot_state_publisher_cmd = Node( + package='robot_state_publisher', + namespace=namespace, + executable='robot_state_publisher', + parameters=[{'frame_prefix': namespace + '/', + 'robot_description': Command(['xacro ', urdf_model_path])}], + arguments=[urdf_model_path] + ) + + start_static_transform_publisher = Node(package="tf2_ros", + executable="static_transform_publisher", + arguments=[position_x, + position_y, + position_z, + orientation_roll, + orientation_pitch, + orientation_yaw, + "map", + namespace + "/base_link"]) + + ld = LaunchDescription() + + ld.add_action(declare_x_position) + ld.add_action(declare_y_position) + ld.add_action(declare_z_position) + ld.add_action(declare_roll_orientation) + ld.add_action(declare_pitch_orientation) + ld.add_action(declare_yaw_orientation) + ld.add_action(start_robot_state_publisher_cmd) + ld.add_action(start_static_transform_publisher) + + return ld diff --git a/ros2_humble_crx_description/fanuc_crx_description/meshes/collision/base.stl b/ros2_humble_crx_description/fanuc_crx_description/meshes/collision/base.stl new file mode 100644 index 0000000000000000000000000000000000000000..4947de029b4ade779a65166f85bf25711ea3bd07 GIT binary patch literal 8784 zcmbW63vgA{6^0i@Q0ORVu@MkKxd@1WLO~?S+1w+qG9aiF41x-R_!zXfCpS0F^v-15-n+iN z)_$$^@68?KM|YVyBXh>Qsq<${?=o#+moYQ49vD4!8vUQ29n7t3Q&k$x`O~#Txo*+C z9`U-d<+gM;^Mc%}x{-TzyCAY z64(<_(VV$z?L)7mzkRmYnsDWd_NLmkQ6VUIjlF&HcRh&2r(?HVbAbEj@2P6%5;gh8 z{pk`(hzMCZc5%Nu%f%+}5d$ApUSH5}$e-~M6WaI)i28nkrpjK6Rqm0WSw+)Y#XfHP zynWmF4>;C<=C;I+QMI~hzB+5=ThlhKOGBb#!4CV>hnMSl3y*JPuc}CTw{4qbJ+A($ z$o^?`9M3&bZOcdOXK!Am+p->am0lCCTfdy=Ygqq#OS)_zy@Cb#Tlkkz_O^+oWw>g% zHbhr_^KE2+TG>^6Ab}Bv$5E8|duzwZ1?tIyn#wbkDfYi_+`+LEo$hc`bl)?Tx_$Uu zbNiO-cX3;0A-%9Pvbz1+ZsG$8^oKOjA2)s($^I-YfiNT2K9DB5yeP{$fAhocxV{@L z<2^3kYxeDl9_;fZx6AD{z3z{;-@jLXPjv6?xz_%-vfY|C_f;Z+RwgPY3*0|Zf&2O-Gk3JM-pBGTpOZ~N-lFwkD2XWI%l&r;9UMo zPglkC2$429#*Ex#AJ^sVV|KM3En49$5cSO~EPXd^_GVc@B+v?Hgs9@8j!qdZc0X@Z zn1%#Ki2jJ4-&yBm-yKzZ?GJc8^t{_L@0bV0M|~Fk%KnG*#P>5*`oe`VB&5B!b(TFn z^}P^H)Vr*Pi3{HRCWo9Pm*EQE{8kcBn>`o=$XGvNsPpcGlzRukpHgSwV7Zxh+}RUmNkU=s%q~ zT8Vhqx;@TQhwfCpPrh!+FEv*Twr{R}LPj2pDI8Vg{TG~xY!gtiMti2}VdX=bhcoft(8Kzgc%D5PpP66OD`RcKFZwb@MQR zQDL-1-`CDm1J=E7RZPD!W)uL&PK5g^T&dm7)NS>5pGG9ZA%WErt0<4WQ?qVw)y+;I zuwSIT6ZOy4s~kB|CX%@9S5!{sr0G2!oDb(hJ|9S+l{p{WljJg^uN=@<+?RanH5K{` z=E~X4b7f-J1o}f2MPwA21By%&*e}w7%21**j85QK1C_z;ayzVjT6uL)NgYH2&!9QM znhtb{`WNdGB(UGGS}OK3gCfohCIciyWip2GVN`|^m4O8A3{+}FCA+$-o-O*QVZ4G* zy_RQp{^D`%W74su_VMSI>2}!1km4KFw()~hyMmULNT3g-iSoA&FZuq5I<5Mejk~31 zMH^2|;_ky*Le!s$(~S@~KS&d$EO@Q5LuHP7y{1zPePF#pnrI;t?U^{xfWSzQCaO8` zYUH7%!?kV~?^5YSh2!o+YQ=-2+`)bF(ynSf-@fb5D-*_n8lGrB6HAy#Z9t%vIUl+wqQif0r%)vEc9W{ot~fYI8HF}7!z9>5ZEu$d{-MeObzbb)gAsuk4ib?d~&sS+b5Z?a2!Yz8C~LnF43_Y&7k{5)lc;1ys_!IWjXGc)z_x=J327> zcE?I>g(^IJV;P#&IDuAp(<8e2^w9Ly=_i=TYCxbBMo4tS zohc<>T=25KN7dz|N`~Wc1TQSQ?VVun4o7rkVoJ#;jSy&sV+t~yD;W-bpj9|3li^&+ za7dsP-hGHZ{A|8E>(U3EDb`?p$JyOyG{=4et8jUZ@M0Gw<12E$M|m2~^)(#dOyY7g zF&d8Pa@%O1xM;iJ{^7#?gRO!)j#m9)rEl&yF5Gc6fmXQ3f_sz;_o%>!AE89$-!h1d z-gS?%-Zi>b6WA|~iLW}Q1zJ#$KT5en#!r5 za%uvtP}>D{P(dBk1X_hvpQ(ci>Yygj3L^|^l!6+S;3KRPO^s4eqcnk5VV!6yr-I6< z3A93$8B}Kl)mam0g|k3ps+xkTrU|p#xgEU2>Ne4PG(gGU*UKmQl{3Ky>foT(DyX%Z zFgskg(I3$_&t0eFZ}_-!%hXzJh5h2Z@vAIb%io9w1X`KX#XZTsGP>Ob-5!?{g_;3t zdoXgh#fnM3($@r9p)v?=6E55)G-0CRcDarIf|0v2ax+>@V856pf|0v2awO0S{c&bE zF+@$x>+D`QVS@E#-ZJ~Z3rpkA_I)FYKEl~&*r-&M`e+CDj;!JkfmY~`Xy8kO)Z*Tq z++90MLIhf&zu?utkyitbSKcr5{K$Xh|7ET)&l8!~4|f*7ejtHXSbd0Yn=soQ_Vo&D z(cx)+J-5AjUjKfH_XMtkA3dgPl-v8J21NbKrl$t3G5L(#Z+bR7fW$P?sQ`oZv|0m0L%JbaFzhg_5~KIyqrp zAoY46ot(f|d8CsQ#!Bx>q&1Q2aS3ZK@yE@Y>sylEG2kRjn9*v&j6=5pXt1x$jA|>S zlM{HaMLIblW8i4C4<_Wj{l}vUtk55kxf@t;H?T#QpjryApt*loaR1N*TA90u{+`I( zaV)qM>0i()tjG$zdsG5}Rv01C*+&PdiP@c0|AQq~P3AIt@}Z^np(_HFkq{y0tI?^- jdZdH;E2|77a2#PDFRY5HF&B4HRWv+App{V>X5{|^DM5vp literal 0 HcmV?d00001 diff --git a/ros2_humble_crx_description/fanuc_crx_description/meshes/collision/j1.stl b/ros2_humble_crx_description/fanuc_crx_description/meshes/collision/j1.stl new file mode 100644 index 0000000000000000000000000000000000000000..19ee82a275f3774a1a488683427500ff23503fb6 GIT binary patch literal 47884 zcmbWAb$Ap>7w!w!1b6oYhhRyjyD~kvTX1&^?vM=b79cnTclRXI)0x3#ad%y0kp&iK z;hyfKCvRmx?tPxSf9%eaeSdwbs=G_hIaS@PdHsStyZ7%txbx8N-3oRYRj@(#A-(E% z?!x{*|8XQ^Y-)k}ynNR$&X;EoIfpgwr%2_hy8k#^+`VkmRAox=cbEP#}7ee-iHR>^420ld)CCwU#Y?so-_- zN{m%07sO{gN~2A(wpw9xWD{OlZ6|A-YM-sxI5tNWaHkHnl{D#pl8zfdgR|ZQaj>H_hVK*fuMV1(E7bW znlZ*7ymc!3y! zz!Hk3T51c@RA(Bk=IbK@f!9Tvu~D!=mE^U3+M{J~4e8Y5_FCAKuL6Nj z2GWcTeE-fFG*H&`|I(c@+C+brupZcMj8*+wKrXwrnYwMlSpHx~L2KG>%iQ(qi(l0WKKx0yD+^$((YsDRS zMXNO7h1%iupMniknXTaKC_?q9zHGIe`mwj#@#SFtt3z_7U7HBk`XH-N+ny(EO1cga zu7b%dL^#&1mMdm|t&}p8NcJ6t6F4p2 zRv7kbUdv1Mpl6rEv+E(m>n8M-j19;+gny&^@qz9K+Mv7XDWOQuNj8u-$gx-M(Ce!F?|JZ>DAhHygO(!pi{9^gh>1JLxqAMJ8v&4JEbOnb&IV^&Xz4461ite~Gq!Zj zYiGKCTpL;bgL7e8=B}D+YFzIFy@c2^TnL}%^s_Y6YE1bi5O`g*XHEphY5Fho|Fo`B zS?CSS`o;Anam;@Sd{gla{=E(Cqr~3lcQ(Z9;vM`QL3N6I@2E~_@AswpU!y_XOy+ks z@I6O+zqeu5L%*)sZgJz_?`+_kiuME>FdLj)mvcna3A}Wwsq?})%g9Qs-G=5&wTgLF+NuP?~H9(60GeE`cth} zEG-WxH_M&7SA^?H)^au+sm=QzH*!vH(n1^Yd8L|prAVMXq#1j*K1d6lDXU{j`v^9$ zR7le}xVWv>dHyfCR=w|PpG{-jYc5n&X6D}Gs%W3;ZoB7)RbLytI5W=uC3RIr?~fVl zv9F%C>_QH{C+LSjpz2g)U$>IEnxfN;eJR&U+c`Wrzdgsxi8fG$_87}i@S^kOUp@Jv zZco&spwN?Pib75L$znVkCvHFjS=)YZ5jsKOF5 zc58Bg<``F+CmHr#MFLe~sUlAm)0A;R{F&bmfj|}7V=VG{Dc-eq0B;!VT z+?Xfa4YMdYa@dXE0k)n>o1aY-eU{1C+&N|V@=O+fWyKW>68Q#qRMJ_y8S@gPX$3i? z5ug7#8}ATMPatq!g0m0Cj&-^%zp2xcpITPi;q$hn@~-YwrA%OBg<4lJpOTuXRqOdu zOO;`xO4Gf1bbX3k^W$({Xyt*xoiR16V~4FWN;2xw66?3%Wkx+jqI{1_^1R^Qym*(D z4tnCO<`ai1w8vQbrw!#Pp6JLbtlDXC7|Moip32+Hls7_86-leOIoqagbWX+Cv~vg{5VzaL*xpX^QS@ zj#Mk;4G$L?HoBGa)%#t~oEqoajCH*^hS!fx={!95t9l~kV&#t_c9-5KN)whTrwU9m z=A}4_GWPW77~Y^%YG;M@-vt6yqW2@)?y)@L<2Ch&^hN#hYbEs^XH~s_MH^_FR@=2h zd6E&=)u`Y<1Oja!&6t`#jO!y?=EgrnVqAnW?0M16dhZ->TZ-%385?I11dY?LOEbI@ zjIEBd$rW-R@XyQEr*9I2VjGW=@Qi_Zi5)HQ6I4FPy9z61ZO0XUKXV8Mi)fH+KMU zJ$b*ZWFHod#MctxN~Wb>jeCwX^>9Cj^Q_;y%6(~c9@Ao}(&t_|t3C?j9bDIYzEbYn zdE@Vlxx01aeixd`cB(lNsG`}ck}!Mim!dbH7obYbww@CRRAKMRnBT{-yy%W`Qo{|2 zN(DX=EFohnx3uRwvV4{Iy?mq6%u6xnoLF<3Co1N=l*Xvi9r=>u-{kujd>u$&`yfp# z`q!;^sW++kk@O2g(s-v0m+i6?5*(Snh_QTJ8DXYL)959XH7x9k1~Gi{gvpG z$w)+7A_8uR1gg-tNFKM3q+)ei!ZJ>&tH@EqOGM4&as5bM$G4;?yhdxHR&2bQY zK-53Fb)TH>VKYWG!}Ae8s(FZbI&LHz7vVNXIL4Y+8LRdC@l-vtAi49iUH1l`RrRqC zeM_Rf1?PKf2kwVRlRBQ0eYY(#+UM`ZJ~k{n)`{*Q5qBSiNM{lexCTU;W*I~bz84~O z=_J~~^%>HPMgQono$#ulc9<#>SQ2qPIGu|&`b zA0@3h^`eWYFS)yYvU^+Rg2ozvdQ`XB&r^@;PFNds?H#O5x$lyfB_hxs(u@r~-9xLs z<)Yk*dN{N}?~2=eACWft63y&Os0VPHJtwZ{#5L#N*=jpS1Qk&I?~UgDCT?+k^k3w* zUQ~1sl*iwWet5g-l*n&s9hk-+OB&Di>S`LsXEUQ!1rwfU^A6WsjlVOP+Hio*Rk8DV#y z>K@@bxw#U}OG2mlYLmhu)U3~Cfj|{{bQt@qZ7J>c@kQ$WAW0xlg+3?7+WJ?~E+ze@ zKFL&p-~4Bad*hl*t`mLB+fXHXqjs(L(>|pBp&nZAClIK@XN<9ZGs&G-HQ5Uve&Q+?#t3Qyp2m=Wv(GFYA{#{nz2J6UxwTCgwR~{ zSq80oR5M=rUSEMgRr28(+<%sxYxo~%UF+EBJe+ngclV17JW@H_)w;|IrTy^Y3aZFU z;WE7xj1^f@JCLW}VX+{A zDzrzdyT5{+-PMuY=kX&oAmc-o#t{Q9S8(uZ^Eh5d>*A3I0YxfN0K^cAs1gfx3jP=j9#W^pkKcBuTn-guI z3hgl#lrOb5czrMrxst^>@2@=WEdG=KQ!3F9H)B#pE!{tjdAa4^RU}Y_&oN`KZ@+b} z_|%clEb>DjP$ia%e0>`D`rM|k565tPju~qc(m=~MJ}Yk$=N8G}TcvFYs#X~z%M-MwsQtmAruHc(W^IeaxS8rWO`#!!j-xAeb zAW-!#O@H^abDJ;!y$qGUF!K1v#(_AL@<%m-y#>Y%4jF{1$VMtQu>SVAKTz#$6YA?U4D%(wy4Mx=p5q`^briVkU7<9yA| z6}2HRwr+DEjZ2C-E@4Tqr5OwST9_Z}S%X)vUfhBNs_Vn&y!Z}<53#rr`K6Alp*1)?&ZJBatj zh{|w?%6JG=QG`ZGh>}s{hePDYL!e5$=LZL+mjB)!${+eIaL@>8HAm#tM=J+4X|P%e zsghs87NODLStWV*yD>cS;4pzemDpA*COhR9L(a)3$=BC0O;%-2hdPFT5AOlq8^%f$ zohau&SDAa!9dzcJWc6`OHtt$%o}bn{^`;v4|IW_2Ru&X){AMg>Zhg60uX&C&XGinJ z`zBZm_~dpw8&$XAx<-s<>@QPO-WpuXk*w$#fj|{TImlDAB$(^b*9LLXS0!tF^wo@1 z>k(Is2r#yGVhdh$?L>9HYD8Z>1gb=jSI(49xoC5jWzM<~9=UC(lIQTXAbnNzJo`{3 z_p=Pv#E}ig@({7L>3<1~e_&jMu{9@t$tT&y#fSA@=}5o4xBR&NQbqR^1tcwM!`g}wld(i>?zhtMYN<$|O7w-- zl}GUhCw9dIZV(CbGkE-$Xpd$YM6@6x?|PBI>mp5eaK~7lcGMNs^6xj5{5~{8jr03p zTt$q^tf*|~mv^p~(hhGMIQi>J<#X}_T=zPm9}d0sjI~>2=Ld%Ol8V<&8jS?1(DzO; zNIyI8IDUs1l#{ zw&c_ICZB#*s(H2vGnH|X$Bk?Xocmx2DdU&gD#ztA{~=I??Z((%@`Vo}UwAZmqtFJb zaOOm_KAMsBry1FyLZFXJsVraeaD*YhGJ_nag}Rej+~0_ z31O_DYi!z`)@_kC`rY)~IN92^qZHeE1SfxzV)~OXMvJ`!W3v|QklXCaCl6g5A`p1j z#P@u~z|C@@m&N6@1^NpFs=h^}QwBbD8NMvWwv9e42Rb69)L%p!SQ5Pdj5)JL$>*+a zm4aeK0##T-#%ez(FQ>?qL)N`&*DKAo{@mEWsz<7^BnumKv)&mu#rQj8l|mZJ$!DB1 z{BTHMyCKb3O|p?b-p0k953R{;%(w@5U6B}Yt0(`q|Ga#y&JVTn`Ps^y>mRJ~c`}}O zgcxa1R}bWoY1hf$r+pU)RAGFFu^|Ho@fk%{%9pMsb)pSaiP5FriwAP~^J@8JrZfV9 zDluZRtN#!_YRD>CkMNo?2tC4!Hq5`r#iM+DhVje&7yO4nl^C0N5H*6|&of>=Tf16} zsnTtr3L|EWjaWW{SNeOrye?f%2NI~l5*m3+9P*YFGj9oFI%3T!3yDJ(l7~PQ&b5q8 zCk~lT9s*TpkFg|o>ho{oa`BnTGdmV_9;IY{R8#St7NMXDBQ%UHKG%dl+n$;K%KI_~ z30!R<&DewWoRzPgpWIB1GJ)(_d8#qt>KL}KbHYhiWLvEDE2CA?XsNW?5 z@~=Dus&MYh*uS^N@>Q*lOG^uVS9`QwrjO2&{zk=*)ROK`!uwB8?Cr6<4iQQs0#!JQ zl6R0YAogX>81R@fAkc=Of@}!J4iIrXykbCL6Omw`!V)r8bj(=(KH{oWT2AJiHgvI4 zvT1*#XFwIckBp^yI+9P?QBQu|@P~>7s<2L!J4kJnr_XVzfbVyKKo#1f(I820K4$x6 z`JW0GE%j2&RBSUc8{R=&_lr@>=|s#V;zJ?=Rp{4<^D{K0s7y)n;-C%mgrGh0+@0>h zI}nj05rNl5Ixe=(AqAX|wRpN|nHW8sjJWE8N3QI`yD~gOpP-L_*MMmkmZZks!qof#PqkJDCN)Vx~ z7YU5lB5kylmL)z90BzuPsTDjiJtKQZgX|smx*g6f@%cVR{6o(*p?5`(m?mTh8PQjI z8|j}_0+A4-UFD&5)i@2ZcRWP=b&Y%nkiFv}u%$(Nlp&-+hEM_l5qFWM{z{|%DmuQu(%W6t z`$VC(LTsD*D~O+>6B z;&D-tK$TEJwsPQRXMUPlrlFZ7%_iMuRuD!;X@2ESm|4>7)!B|_uS00|iUiFK-R2q> zY4RF$TkdSVt&_aFgGk_YGiR#iUXkNvY z?;?TGKBO57FEhvafY4UbK#Kn;BHJ z#_>e>jg^-MD=!a$*#bx#D=!UJULFGbD5Q;*mj){@4}m2?nlV~CYp`~9n`>t*iD=^l zW%h@Cvq|SEv!7PN9s*SuS2b4K8mzWG1U@n1b49Cd4OZJ80##T-BUeo`bJfUW>Na!W zFs_2Fz}St*lg|DXi}8%KcD@|>!ZqA?l<9|anSMC($+}ISEMujbd~lv>U7PQqb?u~| z{_Yz`#~4vWRFN0YL(|hk#6=<&BqC6S@kolF&r3!%Z^b*)=!`Z{B}SK4Qaq{~<(_v; zM4$>=fw6U;@@q}4rTNZ8rNVZ@I#G;1p4gg*!0RH-*pkUk=LPbMo+p0^`9j@h4kW&* z;yXybaLx3EBY`CmZBP!RRx>^a5(!j^_q^Y>$IfIgSn`Oz>*+Mez@TS zv_nY`$eH~92yE72iF?kC-PUduk0^LukyyK6fYz-4e)&-0E73?`wh*m3-DZv_WAE4X z*Qz&m8iG+2=5v;%&elU`|k_Xs;OQCrfwz@cwMAvCevbvTI$Q5=u=rm0(0ZA zgp3_YmCLzqK?cY8e4#=;C~o9wX|Z+7-2ANWk8;J7$`>XOs6u-*syV|gAvLc#{O;TN z?a$A7sY2oIrDJN?KE50#pS&9G9zg9QX6bdW@W|rd`KIIbd67UBX74dJxZ?%sNc{mZ zBeof(vNn#tAE?6k7kP?OYEqftEHQ;1iA2pIX{`EP`);XWLz;YK?X$_bmw7wFgN(NF z*ud*zyp6Gvqe{xnD`s`5wC{kP5)XkYF|Jmx$}MU6hNgjwXNaXj6_${4)ovxxwiVc> zK3Uk7H=aG*J#FV+SLbz=ZJ6DL`Cg1=4gBbQ;=5KYb-trOpb9e&8Jkr6gL9f+e>Lyf zP6C0Md1#L@<>xDBhoFI~HKdC`;B}EEKisu+n)RY%4FWqIlvAP>xzOt|bRJ1Xk zh~-4|N<^SawBh$8oz{wCEb}O0f;MnoD$Yfd5OJ_sTvP@LoQopO*v3~qoG)h{35@J9 ziu+XD;?kcb-QSK`n%EODww3ZM&%P>V8BKYXNMLV(G(GLpYB^swY~#3-X^cSNb@2_R zeCis1sJ-k90-GEN6A0|P&>mv}4+}ecmCx+>5j|EQ@VZDdc6VtutxrrNUekUnX7ZcH z?u8ErDV+yzQZUC4^NSd3k~Ew4(x)-6o@ARqU?w2a^t3N7sQI+2#UExW??4-PUCd`9 zPm%kOv+%qAd`z{`F_X_7aan^GD|3pM7fMB$Dv&!^j)+1;SQ8Pb67%6296#*L>FCex zhYC8-2C6XAjdF3~iLgWjs>GUazBk3$_MhQ=d|hL&rOVuFi8e6vkY?da(mB=eP`*Ai z+(8)$v1TR*X8$40*sDJ?J6E<2A4>s0#%d;;;~I}we*qBs$uQ;LYnC}JhRAk zy~z?|jf3kCT)og~J(Oqpl=3X6()t4lEIZPS-Mp4udv~M_Pv3W+MS1MyF1mNN;d{lL zOT0I<3*vfm?J5!J5)r7v^$zVnr*+hFT1V+Sa?u8=#8Ryz;xG}p5)r7v64FdR_^CQ* z@fbd8Vs>ZlNl9Hf!)@VNK&UY0FRN>uZ>{7m# z>es!Y{NiVkKo#0Eb{1>q&SJ_>a+|w}DcdX|^H9jfrA#MH&va5K(+LS|D|~|)8(o%b zKPr{v11FDiP?W@N?x?|hL5gNTwjo7jG&3rL1gdafI>pa7aLtU$Ab~2JEi=}zv6Zj7 zRD$o^y)bajmL3#UYNs>^+@)Za7H01mPa=mWQ8AxHdagYAcbL6pJc%5hL=Qo2<=N?t zwDBZzcoIDXJy)I#F{EjIJ}()EC(%P-Nsy+U7DFrZTyrb&4H5p1^?5rfNfvcg+P{fV zaOaa4U9!*c=Nmeg=XE3YM3YEn!Y9SWq5M@&>oGoMD!qUl%Cf| z-Y5@&xnoE(R+{q2a!?*wy#LBW;B_&-jP`$=50|SI{9D#DozMp6t)V@}=0wVJ;ljze z?k_sDL*jkNrE$+GM}dJJE_Y`w+qvRQw=RI!$ zMdB(Jm%?Jk@@f0?2}Gw3_qW{37-?KLRr&W@PEA{(4Evy;enDCHGGyH=klF9aHWf2W zDYKtLX1|9(m6-iWy9YSz9`F#TqRf7eJ!6N03_BF8unWSYqLJE~u$zN+LCCNR!b6}6 zvu2H*7BcL#@DQjHOVy>hBn^(V^NBZ~JHF2!<3lkt%EjLui%$k-w=(vm_&H0f(qa5% z)EgBEREcv2A{_sVKo!n7jD0LJ>|?Q-J72IK*b2s885#Dyu#C=OIvq?Pkp3 zB$&f_2vngx#v-WS%}xF8CF*y_DOao?FLW{bSL}nues>1-?Y`8vUrt0|-;Ol-Ug?yA z_VK=O@_8#}91yeHFpHTyER^efKHjH~1gg-U5xbNBjgQ?Sfhx=|Gvb5t&-nNt5~vb0 z&nV6*n{iGgP=$43?AJy={;cwMHRUEhp8MHUWlPE1uAB$T={pYT&3fb3cYtEvGqqLz zN_^*&Z>o0%kw6vg)br#(GiF^K#FM71AqAK8;cW*^RdlaGo65$SSDsS?Fpre6mz0e= zyZ;q+%s=1ETpTmDO)H7G(@!unmrk=HVipls5)r71&w5egV%zcAJ7zT8xGv-r#i<~Z z$CDvsM%+CF=KD}=+fzb{r9P-#|Ay&o;V)bV{GEce^kGrE9C*(2JxdKinz-EEbhrF zHLok$>vZstdTxC`xqH%)0)Z;bRV81>!~N2-o)#%6I*co~F9#*PQq%hKNp&0g_b~sG z*5~;$$+yc@lDkvBj6S}a`K_2|iBCT5D>~dGbI;Ql|Z30)Z-Q z1v>pgz9Jnue#kO?j!2*i>tw{}Wj#h8LNR)}2Uf@n_OzSWR$t1#m9qHMm%}rQM5;bl zf~LxG8OGS^M&^KQW)7eYye{@#)KfpGDOZVq+L1sN_Tcm+-mT3~9LUcHj7$<(Y~n~| z(a&0nz4$@}SEiWV$e8csI{eXte0OoPlbx0$Pk zIX+@`0-fBVL3W#mKov$X>BOuPznmxH_kYk14!3#64rU8r76D_+;t73KgaoQEK1|+o ziXxlm`yhcTj7J;i`)HZt&-XzBRbr%?PV3S1(|QWfdJqXzVV#Vw^3ca7BJjFMGj@ma zGP=`BI2YBNR-2m=i!J_EP46xhD<@RAEcgi4K&VVD8#N0#)MpL2GBHfBf1R z2~=STjkAz6@A$KjC=b7~*B=F33 zw3nbyTywlGtv@}dVg8=L6Xwz0?+LuFxMMwm5$l2HETg>yed2oHb!oi==Ncq1q76Lb z8SN$L6WhS+;tJ{a1fB$q_I^*`b#dMHdjikBMti>}@VerPK7kS23eVF=dkOl)ZH3oG zzsBzg{K^B``#piz#oY?OC-BP-Xz%v~UYFiS&yJzr6ZjnqwD)@guS@+3oI#hsi1!1( z;DPoM^oj2WUYB|weN|-iuD>VZRYspE?zK!{#8ROOOPHWfTq>a?!s;%85pCe=4ogV+ ziJdp8o8Qc{49{)XXZkK!e|XM!5_4E+HQ|KSgomKDfhR9V%*B~O=SD@wpBsfXP$kB; zYdt9MOc%djjn+;sbMG6?+dUb^VpcKjqH~(N=#W4ame5$MInA{i610Nw>`O#@jEy|_ z!}6uFU%;6McHZ-S#-PvZL);5S)v$fp+#=|Y+k@OC2GtPOhV*TY>6E2XtZG2kha!Qi zBFq+Itk1CTmKH_MSU#S$^ZwHg@XLPLtzE2Qt`gF80%r9T(&#ofEFs550#*5{r4Jf$ zAh$J*zn{A1+i!khSxEsD8V$)l(YwcAq5{pr5`bL$1H6G!rz$d)^Sq%wPi8dBism9kHt-#ew z+o~dgDzwK~zU*b`+dF~$+S0;~J$ITZMXC=_!nUjtN`;YFTHUoS%Dt89{KAd00)Z-w z{L-F=Xn#4nPzbM@YYXj|Eof~Quv9thERiUpln`m6^LK+=$ZLLe<*)Xg69|m(it(tU ze(9u!YkKiq$*u|n#-Nhr{Iq54-iY`UHtrr!Qtx{rArLu`CjNKL7>yo`@*cOy=SES-t&unuVz7EoAL@I3`Cbfx?zt&%RsY|I;a$$#Mi{G@^w`=1{MK)Y! zNw9>Jop7&?JgMtQUgBg1qjiVvU8%4n`Gq@(@krWZ(qEQKv>U^xoyaEX_uM2JyQ+!ISPd`cD{-HC&>*o+krI*l*hKen{ z?ysKGgZ5#3h3kYsph|2jsX$X{alufYZoAl4sKOFb&+s~poZ)SMUa`wo`NEY9*5nj% z9b+p-V^PApqW?A{v5Zwa*i3r!IfU zUiDKjqKI)r+E>&oNY&QbdB`8<1OinQ!SbAWM={|Q%hi_^?L76Cy#j$M?C0rpvB^o~ z4|Dd(^=F0{@1W_GNAIZ^^P;$cY{m`rHZckG!y?UCvqqWZiWO4veZegZ8#!`LQa)d+ zWW(#?J5QrQ`oYqI*0IEa~y$yvWIo>aAQ>fk1mm zGd89`MgA`Qvs#;176`m9#`GuyqGm-N?E6WbRZt{Q6(Gd!diF2HKdxV-&MQx6(Lp^> zg)u!kpJ9(LA9gE3o#vJW0##Ti+KYUxF8`DynVRWK9=@s9d?P;iSC-N?B+wq68%0Ex zq{-BDi3n7QCjt$6QHl!2AJ1=mw_?1r{@noz(pbe3( z`Nw$2r>c46UP(g*0!xB4&8dT@si$f!l&8^`{^;FyCG<-P@l!GWdF5wXN4otJ<-krO z1Ol%s_6)Y7Q`BqJU*)9!DzOc-f27_H;gBw$d0n z5lAFZg(akw@YMa%o^s2ik~PEl_cC7Ao=3y1l?GS0VGI)Es*Guq>PX>-u1IPFk(giR zXHf9V8P-!R=;Ud57AV@+B88M|*bPeuTC4TEGCt_+;$qgjMQhk_C5-E6Iur2nc&WFu zq?FGl5~#vhG3CSE&MEaNv{;&6KqOEluC`N+3b(X=G)>Ay>vJp>s<4E#<8b>%Y16Zp z(%PY+d{CQ$*8D408Bt_xH?ggbEnFb=c<{G0ceY4iTOmz5Mi$rP=O!28?@Cm0tcx9_ zENj?UY5R7rf-ymi6;e$2Sq=WYU16U0XP`i!3fELL%a~q+f4f?k4_){u3T@!}4DC@y zW9L!Y@c6SV=rjtq`Na^7LDCr)o=9UHF*g1z3nWk_#vqU78L2J2I7V*ub-4b;5RVO1 z;f_k$IoW-*)*)@MTx918{W~Te0#z7qF}_No!BJOo}h{*;3F zvn&Sg8=*zk9WSriHA6qA$W43t=xZLU^{;t&qFGo%%0o^vO!MluP!6`X6bMvd{L47m zNQ0A&JT_2;_9%9DyS^4SJ{Nc8$n2mmhq<$Q*HUfHaOR=Sy%cTYwhc{Q5_2~>%@GwFL? zn*Kenw)8zOBv6Gp`?Nmys;eETn2*=J)AA4!*a}!eXKzW0L!`gD}>yo>WA~orDGP6 zKwmG?v`_fhM@#!Hb)&{Tvh(rhGX?EhHP3x@r0CxjJzg2;>qgrAyfH_|*g0ReE-2P9 z(cPhK4cp4&^MjVuoZ)`eIq@FFi-l%L5_=rIjrOG?fjb#-ETK~!M|YJfJP41zxJ)Ea zh4#qzx~`%0Zg^cHx~_?h3s{Z!LOpDKqnU0kyDCk?6eVL;_W!CpC3oJvIBrLebTC zi3F-dAM!sJvN^m;Tysceo+MC43FpbEXJjPctp zM~W+#{MWy>^GR1uX#vUlxyzA%7rm$G9j1tTGtE(9cG1HH-iQRM&^ydnfpJ?Lo0SSt zU*3rXs<2Mv#rYVnmZ@*&gHo@zq&jywc2Va@CEtx?x^Kzj_d$P8N>L-nnNrZv*vZxp0!GGJV|ZK)H0cCYNkk~ zOZnuw{|ff2?M?Yv?Lz2oMKN6{|voe9E9N|XcYLSL^-ageD3);Yz7F)OK14W4OF2$ z!>6z5KK;_<)2F$i+dRJ=OCl1D8e27eFWD~IONIoN3Tfkvcn!{o_t?OZS{%>mjCc*s zi1!evLVGm7T3JHN6K3TrZ?B6X553#;(BsZoYz68?zm(DT{1M2T&q*7N1gbDDLi5K> zrM0HXB!0~86Bu=}sk^OZpwhG39tBlmsYWQpwN9H9UhKgKfk2hGfAG!2(ps%^7T)#I zHGi~$B}9AlMFfYh7Q2q~z@LEvf!D=Wpna*qCAHjnId7e+Z4}x-71|@hT9H?FR^{O} z)x%_6F=Itk56?GQ#fV9acX^)Trayl-DOU^sv>CKGjr_ z0tYICy6;g?B}PmhJA8RPs(F%3vOf~25_i#cc~qL;{lmidWxFO2SVFW%J11)tCy$rH z*@6#&Xalc{tw8Vm=Fh)Y>xqVe>qZc&^^8CBZ-Bn_#mLJKiN+-thJ2CkL0#z78pcUlBD$er(!+AuD<^q9z zJK7_k{@GyXzwQxy^i3l+;i(6X$VgM~lfR5KC(6#Nd|GZ%+LR7@^D$C+70zrJ%?fK~ z3;OvjQmHiIC+($JovyevK(+JJzH0;m%Z@Z-d#10k{CsZb67O;ZP%5P9JQ*Sy6OlU+fhvsr(e8o#QPTVmG{0(^K9J@+L1x4qV}(c?F?tDN z^d16L6vqiN&my3F2Ca=Wnqo!!W-U8}Hc*AT9VrLt+yJT1Ts!yLmR%?ns_A~`cJy@oxf_cTB#P?OTjyc(M5`RmAYiHzO?fWIdcRefp03dG~K~ud8Gyy z?0g+hD-ftcdvxa6jBb)tW++cnaIrobSk2J@dr>jQ`liP}(!Je-d8YItA*wL?>a7H- z17qxb_Vnq|6OM+&>U(&n(jH!ntBP?>m%EKRg5Hl2qm~^)0#&#cq0E6x1Jv&Hek9qG zJrD_0iE9Ij0!XLhqX6V%x592GPm~lRe~djZSx2gSYJ_|{v$5OBL!b(yi?jnY|6%E2 z$q>2B*Ae>uC=Y=ujKmsyuq4=nH=?)MfH< z1}$eW#2UAb0s~VSBo+KqbZy1UfyB(LQfcRC9Mwyyp=Aqw=V%tJ?1U$;Es za6ewu?d2NKc;tWL=Xf`bJOHPj2hf1>04PrGGS3#ENWN#EpKim9_EUT?!*aDEMcn_T zh&vLZ3QP6Cc~otG;+1@1edqrW31!Eck0_qWdC@NwKS7xTiEWtA6-FA3vlE==*$GIX zN{m6$u3x9Q>lX=BiLKD*ZZGNU`WU&OGemD)>;Gz9Y6WXToo>9)q>SfMa;0G_BLm{F zGgKKjqKfdei%-m?n{LT!e<^Rbb@>lrUYAM>XF!bgODA6{nv(C8TMC4z!YA?g;aBqT z)GO7L#k%kxkL>cMwIEBNQ35BTF;vO;s zB{gYf=NUR=i(TW&WxX9B)&uKDUoxAt%`$JnG3l`u#!u%s95kzKD{GGHVpJDPNd4}M ztkT43ky0-&TD1UyDvZQZ&h}q5CGR`uq6)lh;@t4K5(ZTsHCmtY+o_ zj+|m_yUegjmRCP>%W`rf55Pm9O0mtqA`D`bp(!bKnfz8Hpbxr~6>w_DuR=3TDwH4#%N3;u4&WKF%5HFDsRSEZo zJoJ&{q>G!=$;oqt3O2B%(H_OmFHe(F=g1=WJ}TP4dyX`HtFe`hzZ+7Fw`{c~=F0N{ zO489ymG#r+Di})_BkrX$*m(Cd#rRu3F#rjSxFc6OXeXk8jf*wI@dY(IZJSo#!*3k(MmPUJIKuW$2guCyQ|$d*3$J- z-KbX-$3X&BnCnj8)SI79Qns#fl>S2`P=#?kIx*{NHtEKaIgU!FMFLe=LOMs-Kdn^% zdAjJWx9mK0XXl`e(j0f?{$dPLBz!JZl=e3Bb1Wgh3=*h9dvw-hgO1Ymh3jIXR*D3w z#E4?Y)8(Y%&re0Ir1&7(!04hFAI!3eOYIhPh^}~8B=EXO)5*hG8>=7pw2E%G&CUZm zuZ(^5XsSDsPU*$yq8RN9TeDSNIOI)q+PorxD%?H7*wT-4)i0$|I1aZJ2~?py@^b!t zHl~MreAJAx+V~iN217_jXkc z`ytxE=pxc|zUWq8NAHoHs)Z&ZFb0Vgnxcu77Qa)P}mn&DKa_Ltx z8^-ZOduM$wsQHL!`cWiMCAQUso^JKg#W4P3ODDkws>HVXhls~IF-;^;g(al=#af+x zwg>QjaeEqEF%9M_Q%;q$VT2FYA~ai?Urv2Bxhqe)`Gq{Ao{{9 z+*qZa{nmw-4-pAbl@K?itjSFy)Zx($c@n?u9Bt_L!z`f~1qgN*a;{j>if?L|^go0d z^Taw)Bb8}baY;9vdjwgaC zM*B8Zt)@*mQi0Fh^0^uksKWRct+p#x){b7U#Q$z7A4CFG82_ZREZWu4W@XLK-~81w zAS7g@+mgGsveav#g84oeU1V(j-P+oII$Naw_#}ZypbDdzG|RYDOBJA*_z+v=X`me0dDdp|?Yd_RNh)u`o4EjrH*BTeXAq?|haWBf1) zQI*ioQ;wHicBULUhM$*C3WRRM91UoXktb7yF?F2m{4it;Kh#4cP=ygQ+M%#H$hmdu zXg>Gh7NH)ZDxpsFrSY)G($Owqe9E3tmb4R-TYJ!0yM90_8%BZ9_fBW42cM)bhKBLU z&%y-)Rp{Sm>>GEal6-Lz+t%*cW9Ot^q48sJCH0?!cD~AMhCrYS?NOFq$-HX*V|M;@-w&`QTe$hU-u1qKu(zG^s zomE|V(#}_VtrQ4Ui808=sp>fLe6aJDo$UgFZ6%h9dIkx42CLbZ(EH&zaT9w9iXsyM zy^n`L6-GJeJj**Tq>)#K^7MPA>;0975LFn>Sa$1$)c5L8K5?r^=sl;o;|xp4Sh`$o z)EgAdNZBxNV9j*ZV>ePv_|u`E3dSk$ZqoZvy^iX;!_H@QE@MFgRbpFp%GpM}Nj6?L z5N)6e?J;)DaYHRXGz)({z7hBPE4?eG+H|GykBa(!PS0Kt{hc>Gw~W7}m8A0r3c6bVsxR!V)UV#A04(sa^Pz-)E)vd41$wcP{)RbmNyR!y${)#!BO1ho}-rrwZ~Yu0!jIeaobeizHJ2pRp{lWIra2^ zWq19hYPN{>0)Z;D$Jkg^RLqK~(336_ zi++@ie%;}!)FKgqD)jHup3!@iV@gF&lD-bJ3pQ3X*{7u_k=;6+P7OhOl=V`&YK;Bp zBaeGc@L9BZl;I={eTPeh;! zef_jzsqnz@D}17qvXf{7RoK#u)rx)K2%S7pVu=V;VF_u@&~U3-D&^nO>6XTBCzrWD z3ikpW4bS9KUQMzNZlmu8Y}{vu+I{~HX>|!YclobhvG2z9vU;tqZbKE))cb_&P={>Y zA?-~>pbDQ#I#c$jl@Do9f~OA571Mlhf5lO%x$<_(Tm}8GqPJH4Cy1Z3`0!8dc1I(D zDm<}*PIM?>*?Wa?_3CWP^rYUd;LWR) zM$U9L^p~MWhvw98U#lMi!uWG}xqG1FOJ!`hR@cW8Gq-_Gu5alpR~}!Tznh$2AW$Xdbp~F_CpUZ@%(Hw- zDG;bae*m3}bHOR)`_zmtoa-eJs1i#!^!XD>YfE3|Iz3arA6D}Y;;IN&WQ=Y2S~S%mpnR)u>bl%Vrb^RAC7zFZ}O3YAed7YUqgSRnfn`UUV%rx39dBsY z%Y;6&EsK_)kT+ynt^ARm*>I&NuGNxmdl=aLA3M)DY_33{3fqm&Lrx+&Lf_l@#V6AQ z0##^_zQHrmPo019jMQ#S7?0`lF82L_3D%6GtJ`qKfg?5LUrm+NhVxHKeZoWnM*yVB z4;M049p*YNh0^Y2w1J}!(sVxc__6BuBgdsqi3l8{kfwU{UQ#Wj@Ca$yG&^scExmu| zGTE&IXr6$10OFh>70+GORd<9mBoTosan5jchhMcBYd=})(mR4SP$l-e<9zNLM7=}= zs<4Fgea_Fd9P4LHkgm~8CU4qQv6d$}t%K-$fM^3}HS{fPYi&p1oC(s|Lw-#{i*tN;J zSGC#j`~kghHzWL%-S+LG`Y?B9d0KLjKo!n7=xp^mC)LOzUUH)*B7rK3JA39t6pt!k z)jA~g;oIBxa71<-;9j4rnc@>RSHT@M=X>Jf+ZMS)a|R?(g)*LP`-#ixR|>r9(f zO1-*SZ8+l)=M2h-_o^2W*{_KNsze{DobA5)?|?9_<(w(b?s-XNJA$EoGZo?2pU_?wuz@O^)lkH}_5}5XPkG)ljlV#kN-W`&2d|`pau|R8)M#C+c|UN@ zfO84Po@T!>hbT4{z#w-XEn5I%Wt6N$`?C7 zmX*aIfhx2|(btsI)R=7FB`r(QI literal 0 HcmV?d00001 diff --git a/ros2_humble_crx_description/fanuc_crx_description/meshes/collision/j2.stl b/ros2_humble_crx_description/fanuc_crx_description/meshes/collision/j2.stl new file mode 100644 index 0000000000000000000000000000000000000000..863dab58b84e8e3e145345307d11fc708c2bd5e0 GIT binary patch literal 48084 zcmbWAcYGDa*Z&8k_Yw%AD7{OG^z7XsHngQtug7l7%oh7>z zQ9%VPAiW7l?;z!Oc9Of_&*U-x{GQkIdU3z;yywi!?#|Af^O@OJt(z9@6)_-UaQC4R zJ&T6N6m1qUB&uomaQ6TCe+S=VZ20Oy{ELoTMADWWT07qa?`K!~*j3ME_SG3X)LSL{ z2s@T#_4O_Kg}3OMQTA8!=9!G`c(1xS`R#*X=ieBkw#C>3OIsIb8FL2F?~eAtznjYc z?fgCYzjvOx(kR$3mJgzTGiI+uRtZ+eiBCh3c1rjk(dS{DIj=(g17pr@)EHYX|I3=q zVnbtdne>tV;p~IEPENLV)@f%4Ow8N$#%|_oW z5-(R5(y6a3=qt| zj%{M>T9r8S=3h&Vw_7$T1X_K4lJ_HF;0V$a4}T9X1j&6uWklG8tJe2c8x zTi>%1j(4*|_}r9hoqR7aHl|`xF}y*z_Wa}+g}~m$UT5s)KXK-X9R;;tnkQ7mNIlT>32ulxsT6*LuF=NA44>ISaj0{Mi72acvjV>K)&N}Kc3-DGYq!Xo^`B^aZt&EDM7X0J-uaAGn>vP1eK#Yx%AGQzZkYsm zrB=52HVLn$dIf1@;Qo<;o;9z31i+^V{mCav-<9%2(NpAgpCY&u@g8Gr#r4uUpT0;N zNwphwFI~v=i|y@VR|9?J*|3ng^sG$u2Kw4=`b|CsgBl0YbMs!=Bc8*R=V_U(ScO2V zg$GvGUHx?@JLsiD{1wxdAO1GGS>wniEizXdZ|(~5c7HpIPpdlAJNC$AIZEJ&!Pxa! zjdw2giMjdZ4ux1>xt@2z)QNV;qKpd7So^JO#euWewDlhi<_~u6rm-Z!+E}@uuXxt` z@^|9A0=|(mj3lQ`{g)S{T20xqR%{^Rcq#&|S`Q78bZ8-`9UpanB=UEird=4?oi{3) z%bG@IO)gcym-FnKq&p8<+QXg~Q2a5rsCk%~?fob%d!1K$=aWON2}C^Ik<-T)hFL|j zcD5fc$>aNWQiSEyw#1EGvy+xl(j06s$BHPSm!aG#44Y}@i%=|8=X${lPwG`bT1S~HGJk7d;fg1#84XH z!bYkDS|yK0$s;&pN85#o0a3eyEBqE?23Ogcw6t}YeYI_ZGpdolWGi)~4!pisR9{&* zIPvxXg;3rGKr^*dvvPz$0*Mm zQF!94;5B2rDg@3M&>v&F+Ez8|T9LtLSJX0x^=)P~Y!P8EzC1vgmmtkpWTzr#=@T~+ z$NbbtA+T0hTgHCLU%|Yb?#DV!qjiPAa*<}N(5orpZPDS})aDt^8`J4gr)MkvJx<u}`OtF(=S?Rf)zc^g&~n>|JN< z!uf-IN15=Ba%-hp{qMa?J_`0Ue;ZL$TQuON;sfVxIPYR?ckMCe(leFx7WXP^%kIX@ z77m-A+1L49^6xuGGf`{N$BHX)=7N<8TGMx?LZFp8Gw2!~YaSXfMLSyist0|b)wPxJ z));!4J5O|GWY2#bZ65El)cAWq84=%Uk(@_8YPmiM-#BV7IK*foG7MA+w8EaIv3=xl zt$X=6?rpW&=)0s$h%;uaKYTaT`@u~4`|CmXLe;nPqM^gJa3UI{BG3wFI5d;VR@*c2 zK`igGbd}M4Nr2b!@p-1l%De>UD~wI3bYJ_UU>py)y~^+%*&}O`*zbNQTA@G2V$0sw z{`?ODt*}juEm&BSA1WEduYLTH@$dKJWvyx-%HYfRBwqerJW9^z==TH5nFlep@A5DD zlM=o8vNjVHg08u1h3{Rt{^0)g2i<+r%6a~1c2B>P*B|u1<=>O$bCJ?akz)yF}J1d8YTjHZeBtdK~Xta=bS0T#`0uz$CA8kDkdUp9xuar+?Ib zJ8>(HpZ=|ucB;@pg+PDUZ}hGuVs6IT+R^crLKI&*+3TUTQ@(&KK9!!gN9b19d*{gFdp~Dpuj9k{ zJ7as(W#Sj9RzEC=HjqH8`6E2Cq$`!HQ>{dWAl{2=)pPMmg+MEu)i5@x>oxrf`4|>E zM`SNlS(bHQY*Jc_y}(#ut)Dq7c!d~rGfKA`M9R7InI$=VxZ1+mGGlde^)vr1y+nL| zf298W*a)je(sR^vN*6noo51^w||!&X7%*AzS_#GS2#Oe$CkL)nj5pGO+oIlK*A0>*Hm1zA@uqXdLut3WZT%`T5tb&@w@{&4##MJCV+dz!J=W8-+OP6LeHXAfye;P`># z3S)Px#PR18%ji8~lR{vRVox)+CMJ%1s*Es3F599IXoddh`G^kY1%AD$b*o;9C(QAA zotgg37WsT{Cbpw~OR#D+&*KXSD=B{`9n4QNfX$(w@P9ka(OyJq3V~MRX9js!Y;J2; zu^nP|fhN39*aU6Ii4Qo<&%OTj0Qx}Ra-PUxp6K<@MQLs*uV%`8mwx->B{X~GFne_g zeB3Tq>snZ8TBjhGrT zYTW?4aQ{UX`eQ8jwQu#D|CALI6Z)G|UuEz*R@(z-SV*fr)_l26&wH%02*@!&Ab%gq?bWsjWO7;Q1uN6*Ml2elU6bG23ow8B1Qto5;_`pZcP+V*dT@bSe= z83WjOyP)q<@vr{U>W3o*l}G_b5NK`CEk-Xv z#GzCKTA@FBqPmvkp=G9OMQi%_%ljXCot69WNdZ25ity=TEcmD5+{zJe*w=mh^?}M> z=RMeRMt+5u`N8{MC&p1GO96TYY0hB6oWXMDBF@}^W&oCdo((@v6(~G>ASNG zHh<}}Nt<6}Xvncyv+aPTnSG6WPY-#ZFYwba%W!4@*JuXNpJo7aJ3f|koC*npl^Foe z3>dpJ@2#9IEh-zN5NL%n4p}P!wMz2W3fn<7O!C)|v0s;7HnR7NHD7mWqFsG3S^k%8 zbK2BJt2H|k*Y&BkFlDyXdg^&&%b-~EXv}7XK&yevA}WhPbL>Uj_NkUi?u3d==*vK=01hfAOpUK?2}9ctwgXoXjn-XEWI;BWe7 zHY@(VP5Z7xA8$yDF){*$u`D%yb$@d={WRwtgYBfWV#y08a* zpcVRKtVL8UKEF#<^Y;>&J^Fz1-j9tb_Od})d>A8BiA(pY^9C8JnM0~?(~!U!E7FX` zZwcb@yr%i6^(KYD*)q};Z=ctOcMHgF-ibeG%$q$;W&t*A8=r(NSBZbOH4<$mMr-$; zjN-csRF)CC1)~Ce`#TOy>eRBi{WLz%H{xEpB!6U*vCv*a#ovo(YX|3yR0xdLA|$}MevveO&d5|A-_oJ zm^_lG>-T~2R*b_kHm}AC&-G>tw5yd=0A$=XG7Eb-LR`A?QtJ`QKz%L&khp zGMLL24A6W>JM!)ua#$JdR`%4<1r#4hGv=B9N>sUBBym-6m_neH+Et-7wsr$ps3s?ONy$VTS& zv2C@nZ;SA8r5aj^*V^0LhvxI4l^Snff5~eujhU|zx_jqv`GIJ`(4k9fJt z7*p#QMII8Y^49%OjMmfqn*Q#Ox3|t%${6Tm6z{79TG1?%+UH*zJSe{2Xw)H=dxBOP zgR*eh@>k+{DCW|WBVGQCd!7=>L~tqst%~PpDoZLb^d-fw_D+9abnGyO&mFPU$ke~5 z{4YzNya`2u)||3d$u)i6FqiqTYiqvhv(84Z;^QUpQ&|+ zll95Om{bH>VceIoXUjFc_tjCnUWdiT9|5DJkE}(~`>3__J2~rs5l@QNF5lx>9TdxN zZC+taztU0?H|D%@u6Z&+cOll0u}k~n_{#E;TCVHWJ^i(bUMEY|uvbFWu@=p z`1rluw0fxsj1(Zv*wlpO`hgAG#i`}t=Hm*ZL!9iizHqvQE1^>tpUA(TF6CrVMia4- zh(A&hxPnBQh!?Z;?lkvlaK5qP1Ix|Qu|tTH^VC0fbS*QN2I%P<><~o?_BZRrh1G4= zD%!rgA;Cf)SX;Rg7O)bw{3~J1T4BCTwp>8Vll(2GTFKu|YpES>NwOUR+TjvZ_auMa zk!EcCi&>%vwcJN7e{$oLv^tr)tA$ob(|z^55Zx(~`s9~Dg{b@W`Xpx+)}vHai({| zUwwVCpB_OiUq~&V@T#JWp5LCxExebgUodT^7UDkiyOTk)OFUf%l2lp zehTj+*PndY^Q4_MAJlc$gD+2vqxZ<6h0z`-Lcc9tCKHLtcQ2H2=;*>(E%Z(IZrLEY zN_{Zzt>Oc%)LP9Y!dVH^`c@&(3Tw#NsWL(OWok$8p;_WVul2I-9UJ_i)LkX!reqrE zUxmP|gPLjR8#_nViq`20f#qTiNyCytOh`qb75bBRyYAfWkCX3qIRZG(2U;QhKO*J% za0$Hoke1Jf4$p^6V7Yk5$fs6^r`9FV3hzqBjP2L-2zt&(|6AR823-R0e5@h8)rfF> z#HJ#!T%;LWwRok+x!Vs`2r{oN>0H(s0T$@PmAf79F~;uETGJV?ZqI9@5HxbSV^^kT z31dAN1ETzS*CzaFx$NfbebW_U<;l_Buq@;3R|{Vx;VPUlYB6`(;q(Cd zKr3~9or&eny=Y<4XVGSAUIv~o-v44rUwq=3deOy0lcVK@z;#E!`=BCtqlrONW z`E<`F(Xi+Ng+Qxai@RF!SBBU{V;r5#@q01mvu^E-O)uN(Ilhgx+EwUbhxN+g!+aEG z%oy8QY_R#FRjBAPak4_771ofkmWzj&k2`hJ8rEN?H~(d<6+wBfnR{|5D;9M%@vv~5 zxxGy}?UcR2ljrs%s|698FK6*##!Stty&z&ut8!YkB$YrbRiF6iajbc1O@8C*W|crI zRjYQFh^s{WyHzF73Tw#N+9jjSXU7^F2Q${tv;Q1#b$c3Vmn)S`X$R7b-F`gU+;%hG zI9Z~cLZB7)G-F#yNQ!w?>%RZuAzvr8{oq8aL01 zN*Zpjd8#F$71E653m;+5Jlssoiz_LRKr3}^uyoH5v-rLxA|#@L;sdj<=#R0eS`p^O zoEJpIvJ(nHBZJg(rbO}N@8tY>>F5YkYkXc*d-0<}P^{0jLVt`=tvJ-m3oZ9Tei(G& z)K?t($|b1fGE3^HmDPN0<~@;oMMp!_Y}3o>E0@3#4)dzAcRBQ~OJF7z{ZWK|^l*N( zM{BXFN>#-NmWwoF)K?t(%JqR7QH+tw>%rlAxCB~Zn;84ubnX)jVKA#+8JW`f>0Zl0S)B3E-u*Zg@K{*+>tt)8^h6E-#U zI&sQR|IY5i7&}JmDLP2R9U`WuBG3x`(cCAj9{+esdQ8UyB zsa*oC)aPSDsaSsIgGa^;pVVx-1X`g##zJ0x!s~oAQ+r|tbL)x68*{9kz3+qkKFok) z=8tCK^~&+Ncg7pLI&+0UE6f5iHe+-np5x=E`e5AUo?;zMQcPp>fMPOynJM=ZA=(iQXzW0-%;LUL9_EX`dv5MPcf7+Iv-u_ zg0VNLtU_Sjk!CC`vIZ~p-d1CL;~<5=njlSD=a80sl6k_on3$VSn$*XeaaXuq^RwJa zO;jJXMpfqR28|Z99=%92<`k-;5NM^U6Na02^=mah5KFp;nHd*k@wUy?-TvyY*%oHs)wT0G zaaaGFi2bPuw89KOW9MR?>Id03#y(PFqYtz~f237g`@3E+OD`?HM-=}o=7QACcdSy- zhq?4A=KYZEb6VPm>F>0UWxt_MnLSr)aiG6KUcMxBdYydu5QedQubKD897U$+6g!V?hFI$XMPBMfs|KcO_oV-9RDG3da@7RNpGj zgAT=OLk84S2(&_fGST%Qmb%?3MnU-XD8A zSLYR5l#uVG+#B;LS+d71a>=p%Oy#_EUzH%@2oVoc5tvKE92;X-T36v62QLv(R$0Xd z)=;fg;hov|vg?b*g9i;20=y7q~7vz6|-dBLOgQ& z)etAQ{naPAeMqS7C>@iHHz&gE_*6#%%SBpd+)c>1TaeYa{5w?WO)d48&VEIDpKtDF zLRQ};&l`#5~^AZ#0B`$$hst-~Qn4lc6 z{K^5eA{~I`-)SRv@R-gHp6axNht~ZvD(kEPkia%koFP^-JErX5K?2J~nz8`*s+$c{ z)CowCQo*eu(o$<+hEXiT(HbCuHNn-3)H9e9QuGW+keS=jWESUWVw!d7=55`sY5pXI%FhJy@NFE|2VTz?^ZC{ z9F=XWmj3j2A!};Sl8O}6t)PmTv6C6M=wUksnTMvR1X`g|nr39iCVlbkL1v|^Lh*rC z=r38f>}RLedr31jSPq-ZNCu&)zgEsQphKr5^v#oMzimofbbRnIE~ z#`n=5W4*hrlQHCxFA69GmW$dS*>V9bPlDccbxW!$jCxl<@45t9kv~^cCa<7?E9eqv zg*qwO4&lVYQ`#ZRa(WjPR7lI~A>ewr1m0uRS4mEM-%+HI%7UW*a6McC%SD>8zQ0^E z%(k&+mNr|o`@LQt{5;Pbc_*T#4AondV>x-l*w`%Aj99%-A<#-~d9&%ajEVJP%_2)x zA83XCD8e%RmIsKsP%BsOrQW+#D-YDlCD00MC|mAB7Is%9k8&XKvZKRUyy{wOEV|jLgZ0v}t1=Zn|9|&fUtq^F1{uuk}%@`3d&XagH`$$LkDivmq?iICTs1_rgOy~m9x7l>9%iEy}fmS1x zU8eTylY$+cti4~ew?d#5>X~Q<=r5N9i&=VL%DV`KKr2+)&>pO6rZM-UKaXpFXkcvR9 z8WAon2{!D54BEvvas1Z0Zk7Lj)6)L?NuUqQRf(<>PJ3E4NN;YmJM!y;n@R21h6({b z)RZ~TqcfiyGRM)8MKoHfHzT4bDbJ9=*(B18jr??iUXo^(ZC_PXh>q<`%6aM1xp|ct zIb#KS?eG*QV$!;r3V}62nrd~SsJZ<8-H8in{gG}~khPX}36!H<0;s=2wHWOT`>D9u zleEseNb8IQ&BEpWA4m6$G-JiO1exjkE!O^-SChxTt||8kZ!ePHhiWraB+>OKqMN@p znXUaAUO^$y3KdX{ow;A!JTY~$HZZE5LSPNmcGwq-nDsX;(Q1rnq!4I@HB6q7IXOsY zW=5GqISX?#?x+^P*_q5*3V+rT2~;W|Ewh$V&){S&kw85I(lVI@N`FbP@}GPiikd4_Rxy@s z^(~_Y5fxJrXob2g+QBojoY?=}X#V@lCC2mMVbaH_`ssXVr7E4S60wtrA5sx$rS3(p zcXPQuY4>3Md4bu+^K!9XryU_7@A+_VCq{1RG!i1F5z#sofmWzaVk~IuJI~1Av0Thu zX58%4TKX7u@l_~ll~9pH`whN%=lPO|=cx#^LOl~>TK+NoN{#DU_0Oy56<#{(rUWZ? zaaJE{m{i@8LtG}plZr@qK2p;23+GU1T6wK_WPBZe-Pkj4jQM0r=YvPT4Y!|HTW&pX zxccCV%~5vrkfqLE8TXtS#-=^YF8G~}qQZ(1Ch3Th{5xupsF`){L1!=72Zt70v`YPQ zoye22R|W~ZcU4VMyJ0Pbe+Lf|XroO0GEX~Y#4bH7{@mQhe6C$LTjw8QSKj}nl`7-zY69qqTJo=FYuo{`s8~OT;C=$N zSZa=*e0aczOQ03{lW(?NT8MKV_nQUu_r};g#=pR2u|~M+K1z;iX6QUX?*1B$I(NPzDWLd z^hKnZaaCwig(O#AjtU70QcxZAE2xmB88WEbNTnmoa`rppTSoOUG^JLKrU(hNQhktC zP3qxNc1XKEFiL^`Z=fEP43)@s#dKMDH@$x{Y{ESB+v@|(a7+kfaeMky}GRvdQ6Qn@_wB#I|+4tsP~hq zNdcd)mb19?v(=wF3ED|*glNzQDLvBihWaYva+|0)DpVQwm!*!3R-THzX(Vi~^# za!1$as98s)?=0)PCf%P&sM1n*_xp(#sR*>fUZ5Q#qzVfsAK#NI41J&$3;i)RnKkA$ zN9Qmzcb%mWs0u@xcK1`+pfHusxuY<}(Fe70bOlKb=2z*F8qX!r3e|g*V+n3;9@oDR z+<2xBFWtu4_wfL`e%m}gREVh>uYyEuB%)C&qDhl3R{fs6?Z~n!&DhveZOyxT1I6g) z89C)uxKTbaO1_YxhvT771K=sjDK&37ex* za>7WU75XC|#~YeMejO)TmB_33z`A1}($1H-j%NCyU5wM4Gw{=8`&tLbgxhEI+)B$; zA7>kNF^BBRZOn^g3V~L5>J+VOf9_%iPO2|<&-+J@{%WYzzHEeD`dm)s3StdO#X6y< zx%GB)VIM!P5U8`m>rXqRzp82$+?rs_?pBk}?;UDIcWG~rKa|ghy}M&qT`Ob$_ICIK zC*%G{x|(L$fg`oAp9d)fTH$(EY9>s-W`cAQmS0Ulstz}MLU|+kJ6SV9x(xFp(q(u^ zmw^OkWsoMlPfRxRbBX~7%12S&NtWg0=&)SMQziK`Ta5i1FwDF+GDxd>YQ8=zJkAE$10ZaUgBarMtCfmW!dWNZi#n~$_i z6em>zt+0lS)vZ3ryjgl_qW8!)z1hSu)=Fx}gL`T_kY=n*<9;TupHn;j^pHZ}-KXyJ z3epCdg?^}_h5fAhKr6LYs~be}yMv~SZ#Qoh{l1^-{hST8vz-1{IaLGITZ~=k-h;pO zt`@PMeX9^?HEPThZ^KK&?OXO^ik{d0xI1s+NfaHfE)g4=Px214W9)Pf9wea^(sZuc zsBYZ*(f8sAog|0^TB#bZO`BTrhk5slE{Fb72#nUEKdHv$pvLw3)wrlBqUX_7K*^_; zJ5TLldTQzEbP2Sg=ilpp{u!IK;#1y)?)I92RrO_)i^{#oiymk5VWgR|eO`ZFm7>l> z)F9%IR0LX~%8JgJ__+ixM}+ohqv8XtFxyMnzI~bbdn4PLYffZT2#lU%4H;V1?@(`B8hs|y=!41{)c%lKWM6gO@WOEINWE$bfmWzzqPt{F6@Ih$0wdeR zS_*+ym`kTv_`+(u%*C$_Zv)i_T44=ozFVj{&v$-;)-gu`K5kM^d49>%4Y`%`OK6-2 z6;hw}v-Rman``!!VZ3aHbs^2)G`EX?6zI$9n-UTw+C z5+c=FAg$n%h)zWOor=Jk zAWb86^j$qK^vHvw=RW3D%IY<}pF~lf;?Ef)S$?0!_s8`2^m!jI5o>Qm^V5s};aA&5*&}xbDmfOFxYH;-pY-&ImZL#u{?R9YhB$H2 zUcVJk&XZBKQMpLtHG(u=&q?Ej1X`i?i_TReP0`P!DGDJ?k-n|5)JCyuxqYaUQr`yN zcqO?2;EKI{eOxAXVH zs~lDFlpiL0(h<=o6@fKDn$~Ld>g$Y%8#~e~KCp&J%iOjJxotWn+s&W53L#Y|L-}(P z^5-srR;baCIeHUv^e%x`G-q)A$(f7^Ga30`oVgFK2UMjK&6Z4;2E|2WWYalu5o@T{iuT<} zAI`ozB+v)abZ!*w<8<~~I&oekFnX%SMIRC2M2eia4-!}tr0JYH+9m5mQk_$vkibY9 z){r8Q6gzf^eiTba0;6?E%hM?ZoKETX71kYT$`z&GpobhBWY%7_&NKDuMLB-_@KaVF z>SSH;&hR zRIBoTMe00n33)2lk&M}VST2rsv^z88SN$Q4iMe`wr|)T;)9Z}w4?H=QaZn}ldw3`Ry8=qCRh`6}98KA3xV(gQs zyQ0!C&6p7{=b}l@n!}k>qm`;cx;5ag5W_X&$T*ciD^-y~Gh`EH$gU5xqS>;mXJL$H z;U>(&T>`CWMxNxHCzX6|6wUMn%=BFXt!UOS3FibV#%SdwoOP75@}haIB%IY2t@PZU z#$KQ|&X`@IK+2pN3ACbhiR+s()#RgN%32Kxyn^UYu5pBaje`W1tG0vY?ZQ8AM*^*A zK5zQx^P~~}_)PHl&`#R+7jgX1uakJY?5*taq`yj~#RA3FC%4LL3mT8t>OD~jRB5Rv ze+7PWKKR!^#%m3psRUY~KRTKF{`mt3R!`E7Je7p`U$sJ-B6m4?;;65uXmcN_1X`h{ zOt$<0wA}T9R%)$C<7I%xE6Is$Im$B}eVp;?f66n`su`eFa|yJsK0 zqg;PDcXi(B1)Y_bd%q$r3D18KXhpOKR+5qLPU(QxRxYPtQ)-O8S;i$Rj#2D_ztS zzr@8q4n-@Z>D-TQ(MA>`+NC1U3eWUnEap`u^GcyWbNscxMEJ1YR^0sYcA}Nr$-c_@ zwX?qg=cV-K96j9h?{}uywBkaMz}qZrhgYU5;)UGS}K0c`=t0? zNs3=m`C9%RhxF!jwQ;27r5;H>jbH8`G-3asOQ02MO&Fs+iYDw)bP2RV6^YzaEx+uL zvZq?M(AiUstwqJ2)H<8fQnb$W4tEK(!ZuOnr`W+8?7{ zDg;`oF=RSngTo0MUjLaKm^V=ORJVE1kC**9j~M>@PUlPxm%!`-(zG|@Mhu@*wUd$9 zv7Mf+;RNq~$}ZKqn9YZ@>f`ix!+1p254E4-=O_fWyv^6K-X>I1%`cq!ZqJS*`P^IK zTBmd)6#{jANYnF?cg5}+k`o#TbNF4TLGsyJT`G3VO^QR25~ zg+Qg7s?v*J{;#nh_JBwvts45ka#0&cJKUBA2_<`5?A*0 zGc(+YJ>dIlh`n*ZmlkT{RCU|6V*$pDf|hu)TP4s6YnZI^?v`nq=(k~bY9Fp*5B<@; z?T6WQFDV);lA@9Nq^@7Nh}yVRdboT!^p7?sh@8~BNT3y7n`D*Vn`7u9#s`v4N^{f`-XH_ zNT3zgkg=EK!#Op3XVc#eB+v?bfihThPPjvyqI1KMKr5`FBocv;O3BpiKw8#HuC`NZ zhMkZ49i7tUwsHT(pL`kIR6I}wWu!f|kp6B6zuiha_XUlJ1nm*85 z_sJN$&zO&#ovg0@PF1(fJmcYZiyh*@)6?H*3ro^)`JvV(WKaVzhqu#cfSR@`&|{9 zs@S6Q08BU!z$I{vgK9CxZq;dR*5_Y{38aTZA6RZG1sy52woR-rj+0_*!iX>{Ym+E@ zPKG=_RBx$@t?4`4n;RyU5Unz%=SZNHs)s8`J~mINFW#o|fmY~`)NNb4n%^X9;#}x$ z{nYKjR-17>?2tOSlv*Lp*!K_mnFmhh5n-ox>R+uHY85FIVGk$e8S02=o+x|TImL%Y zpY8q3*lYPjsU5o%0tGjpq0Aj%=3+A&fGgq%k-|ILZB7ako4_$TbK#Ke~6GXNA&ca z+gmJYm_6o)Tt2)rP`5^V$qv*rum6?K{B@_T5NL&}H^!%;`hj8s1}!=|t=!;$bQRwQ5K+*6o{i{NvAWi06NQDIR<>*85~k zoc-mM=SisdQZ-&(*S6!Q+T9QpZm0xWp_Z5SlC5gShwu7X)NFQ9@qwc=`Xi+i5pRe% zn~K0U1Jd+XThWZKKk%~%`%LwLH9?xrp%3iJ{iiz8-Qe|~-iXRG)R#&9F8AwqX~gmR zRlYPDxMvp8m?*Vsj;>c~Quzm@N!>%E4-!}|t|lpZP$Pmrt8-lI_03g1wBAs!6MMP7 zJ%5A)UO&q3y5S`Gr34oEoIlCa@;B$1H6EbrR?=Z34?x z_p2o{|F<2e(LjG``@nK>pI_Ppo@Rvp(k8H6+*g=3f!{7de`ym~uDatenfbqch2P3R ze`))`a&f<6+5~>51O25HLx_JQT9r^=`0 z1Ha&b{?hh=<>EQ}X%qPM5cHQef#s?v@Tb)d+!c-f()NMn;`dq8CUB=W`b(R@a`Ahx zX%qO(5A>Hdf#s@SicMzz?|p^e0zrRi`@nMXYrAO^_>B?tmo|ars^8&Fs~z|q3-p(^ z4=fkI@0~V*U)?}|X%kp3exW370>9>g{?aC}T+FwmP2iq$^p`e)`Bzcc0vjCk670-tEWo&F3TQwyYg#mpvNj!|bb?ugwshQJ;Nttmt%bSZc!6 z@{*4bzp9)xUO@%)IjyURmyt0FfmYaWjFo&;g%A34op{%%6#r>`GjC++A$DM^JU&`& zx#t|BGM99Hf0Xe!IPQmak<+8_EV$(b^qdPK}mMSL9Dx2{9a zy`<98hw)!N9Dn|D$)BqnB5m!99@^zbv1az|w>?-Z=ePg6hUkwJjijy3Od7B30XOu( z*lfFPfr*Z-=FTP1N>!ebu1|oj&n3`G-FH{D*b=<~^;NrL#q@P|Bcyil^Y|=2 z)GDH4kFi0dfpmybtJisuKn*0)bl&TX>mKL6vRhoykih#2X~qU`D&x6CM6sObJ(=cQ zlXrN`%xpfqYDm*p_?k?XJ_dbZDFj;K9YfdS<}*)YYDZ7HOV9`2mFSPoRkP~p4zZE$ zL?p0Wq!|l;w#{%_e(TUu&y#MArNXd&>#R~q?th|Cc}U-0ZW1p(BOm{qiPVumE4=V0lDUMifgJ651Gwva$8jN;K*_hGMu6CK=5=hh-Y?+iDJ zhy6z1?IXf}(k&8LF4A%o6)=j*E0{7;%iqpOjrW)wsRfMGE`je1>}mNn5b!o|3ADnI zNS*;9^EfGIK*&6fb7};tuJP;)nNbw}j3Q+YT>`C8t4jNdNbd@#Mz{p#htQwQrOKR_ zlS@S(ST1I>w$GH%CqoIiueQB+zQ_2-jQ;3Mj;C#T^ZJ{`+2JaI zR_Kqun{lfH9~jnKyqEovxLS0wH{+1O_Jy`NEvyOl0`=|(9r?q$ecE9u7D6`wFgZKm%3*pscSxp_x+^H_(B=8nEmR;QQa?6xZkD(CN_ zZjE-C-YaijIh)I@QUA3-0CU;?*unXJr@7qSL8fw_+T+Ubh&9fJSMY@e^1oesK zC{pfLdCx*CREUvkvQR&>R?3$)kU%R`i!tV$yzf7OpE9oU^d#rhebmOOS~cgSlbtE& zmmq;w>RCt*;Xfk<3A9qr()%)V6Vo{@^e&wiiUd7HmjAR+y2o6_9_=O%Z)A>6IV}_k zw8A#g2)DH>uVQH8KII3ae;eSvGd|o7{3VxjmW7)IP-FTXei_LBDxFWO^x;mu)%H=| z%cSM%Uni#zbzQ1r>*tuhJZIMO+Lu3luMlX3Iyt(6-w)*38!b+(m0$IN$}{vw=dd*C z!q3;rZD>6iKk4b~JvSoUPSkSyuv}F^_qn$lU);a4D02FS{?YLv-U8=(*oOlsGYY++ zw)}Z~Bro)-FoGAHQ3&*bG_BRX8O=9&YZ_Cv8v5Q7le{IUuab(=YzfqK>bE&&Y>4IW zq6--dc3B=I&_9TAyBX@`0}Hg6xs7lsT?JpGkQpcP(C`c{fPjJMxEDlrFr zTn2rhm0GLa-;LszgPR*`i#K$>QRVf2ISZ{+ed3)1qxpxeM;rCE$_jy2*wb_@XV=l( zep}xN91yG!Xodb5%h2?n#HlxaG^($NHH*J)fAIPj;r5|A%dJ77^$s=;4!1WnUvA;) zf}}|K$}m1CHr|-qLnY7(&+a4b;741GnR)9QhYqU*TA@E0sp~E>-fi5U*jkS>tGy_7 z@QeH1?HQ43t&pbkEWHbi{EOEmj;NoCfD;gN{F`;dz+zqPjrW|d1h;*3EV0<}lg8CK zv5F6+9ncH3r@F@b2l98$FE+OsYwrHwx>!4_yFF=!dg3C|$uXIkmjlGg1}Z_c4zzoY zUotU+h*hZw)bgRmFPWGX*30PpWt>tgY%Thu_2AV;ya2sxhu)hd+8i3{T|)2LT9258 z`C8QFFt*QVz{~t~MRd+~MIkV&i!|LO_sjDQf8{b~c;&m+>wi0=_D9wG(EFUj``jha z3KdC=y;vD$K6_eGB<;JUXHDpDg>?wGr@qMLL*R0zz`BTf3m z1>Xm^ zGyZ;NIQxX17%~zV{h(N%8{?pP$%`I|POL8nMbDAI2qgL=f?}_Y$j3N}y;7`C#$KK1 zAjU}5*egW`b%+kS1X^Ju8eY~ z#CMaN9(7{K7Aytm{>k1RVT0|J)w5d|JHaRg zow@vNdwy}s3NiMR^9q4h7~`Pm$B&(O_OIi_se0EH0%_~aZ@#G+j16auZV zhV*>IS2k{I%Y@Z^2+x}B#qJ=AWfVyj%fJ{1X$M>B!4vM66aNk#qY!ANMn9a<=kqSb z#3#p907?9L* znxN%$3A7@er5iz#%1jfKnJ$4=SVO6^G(l(S5;O~U+k`cgT22$RoGyXoBFz|`Ibgz> z1D5}k0*p+l(I`6Cz=U%RTmr2yqQh91!X3@_O`^nVia=5f(Ix0PxBL-W^haN)ARsMcORh2M*0`m2 zjqmS0&@SAr@~;|=!Zy)46KBGBv8TDkH0!QHpbs?~H7i>L&wMdZRNeoFUU{|y z+TT9N>BIiPnJmr1ef{}G?;0cK(gB6QYk)M(EVIo?JaXu&(IYI@%+P+9xpZ}RyMMeI z@xb^4W9v3%H_A=cja&2L6auYq<;~c~7rJZD--H=EXnjsTxZek^$yMSMU*O62`!|UV zDVA|Fe~G$rx4YXVqn2A}MbQuU#DCf$-FJ~^+&v?)jYlQW>cV>s>(23o+m%0aq90%6 z$?ADLj~mnGs|3~%{V^6jaEIq+@%Bd1jj_)6ChGdXH-Y7%KgO;fI;IWYchaajS0%7b zNXu_pc;K5Bt`961BO&yh$IsI0Pq=2>>#X{~cA!7X-PL$MIA2N>2it+=;dI_AMK-W%lU7oa+{@Q$Tz3g|E|SoOR5OV#US30-p=94Z)cZ4D~z4c z`s2Qj|K8^x@k8>P(BdgbA4R;Hh4MR|2cq^q`L1;dEEj3U5)W46?YqAa+w){F zYdq`YeQ#=U3HOw4#u~2Wb2 zck{Qxvy7l`A1DM`VGU{RT)4k^=A$dd%7lG-!q%Zy{X;$Npes3jC8i9uO7`w)Z@jPW zN}^pUZ~B>^w$CVjuy-p2jaQa`hdl0SqOV|l7HOVs9UzY1IH?e5MPs6S{x+S~^D4re zeltKs1)o+3w89$F-i!hf=F9_u;?BH3^rmNrSdXssum|SLrL+TS#{T}ghk4@8M`Cx& za|(f0YE&)f-acl%hD(ivRo^QFT47JqjI3vWb8M4|#$YQ^AuINNOGLx5Q><4PhTDaYJa%?9x~pGQLy#6HyoWi}vsxVe{9A=UE4u!c z|73n@$Cg&+_+0x%?WDgH0&9r==wym>5$1tvvxPXfMdUv*)zVH3vBNIBPQr50A7i3< zq**R>x_G*3t3sd^-N&xNgRzR`yYtV6&oG`BeyG>U(a(FLeYkz9bZ#H6km!Bop0LB% z@oZgrg15Z!&)qi)fmZ6utMaNa-Z}RRV-C%I&<9%Knu>Nvp9|xmz1|Z6lkO`7T447R|!lOstxHZMy&2 zfg39_3UOQ|(2C~m?y8TXoJU6{mfGIM=#~(t_&_UlRn+tC%>$A1dKe!qRtdDi8q$h> zMjf7g!6k8iO(wI$tG?d#Ph;(Di62@xTUO`P1`%WDUlNZ}5okptgV!GkqpS?&YulW= zB3{#2f*f!`?ZGr>z}XAV zQ7B)VtDTv>*k-Y!@)_}Cr>R!({lRwncj+x0CGdHqc*%>lW{D3si%K(90!KJ}=IL0@ zCvD9hq@dGBsRUY~Kl)bu!-i)2$V9Qb#ykD)u%=d)KxA RTrGaS{Fg$Y75ZcB{{hgN4NU+5 literal 0 HcmV?d00001 diff --git a/ros2_humble_crx_description/fanuc_crx_description/meshes/collision/j3.stl b/ros2_humble_crx_description/fanuc_crx_description/meshes/collision/j3.stl new file mode 100644 index 0000000000000000000000000000000000000000..5e49acfecdeb0e52471b13d0348b150052847c52 GIT binary patch literal 50484 zcmbTfXIKz-l5RL0zba}@e+JezKt&_(Nt0b%iEBy~Kd{_m2_Qr2;6ijEovQEA>r>5BYy*MHI%dcN2XS&x~bXb2^HdG(`RnwDd zT(@~*KQ6WB0Ypw9lyn4DxdmINh3Km*jE5u59XL(i_w66c=VM{Qu+g^Z1Z!%1h;IB| z8u#5A?Oj1f=Mes0zClHKw|^PS_~IkDp}NxA-|Bm_fvvTvr%!8xx-?g5JG_B74#c>0 z1XVfC0%NY3bIYzz&T0K>#DI-X>dwLyf||Y=pYFJB!FGF$J#TtNT9thuud;HF#qg^7 z0h3y_;X!NLawXKgd55Z53U9O;f8U?jK+S!rGyD!K{z>Y7w=MUG&SY!3oiJ2e`&LlL z9s6c|c-dJkSG<|}>qB{Hd0drLX}x76SA+a)HWm(QrVf2GJp~_^+MAF`(#m)4$V*N8 zE^pqmPxhbQK|LQ@N_~IW&l)pGQ71$;R?ELH%8lREpEiecxcb6aEp$#GpFgZJFYv4( zzjCmI+F*P%QDK@fzheW%)ZH_*O2zid-`eyBKj-W0!8?U*j@Kh!MOZ(SKcoyiHrn?0 z=~YI-HBUOyUv%A?pk>)62+__uP(L0Vq(5KwmC%f7m70q-SEg&3U7Y#a_&&Dd1{`)( zvArX`YujwxW!}(^?Ymox{ihPNvYm1e0^7heV5Ke(lfP| z{G*ig*JPVlf6w|Jb(RY{yIRLS;4O@EM2A2`OidTzmCjVtKgoWEPsc?Co$ z5I52hRONURF%~>~i5!sFO)Olz-Gbg~HXA$ohvQ9xkWEm>_4i_hcVZ)(v3x49;T<=k) zj~SkGuc@-D^H5QvP;p!T@c{m1`VDUhdxdPno1sn2c)2T!5}&`Gu&L|>R>7TUI}2&= z624-zeD2C{F}l?!lW|--fmLuH+la;u=6NzUD`m7i@!fC{TXC~LCa4OxW8S=bQk6UI z+5=@Y^ak$g{jz;i20Whx$8_`z#@}b?ijq`mGW^{yOE!7ViIZALl+k}U2=uI^ql>P~ z2j_^fe+I?^;THVY>C=+YlTjPE#|dg}*}SSc z>86t9vvD@vfQxo@6J4K|k3MtDddYh+~?uTSul?rh`|bSuilmdY^ra5foi$7LNShHzfO$Zj&zm18y4g*uY~gTO&==(E8Wz(cL&%A$Gzkh z?66m4W_wE`7-hU^Q;x6p-fJ6+l| z+hgoS);8kg-L=xU&e?g6&~San*%L~s-j&pLU1Ie$eU>Q8a(+}g`LwtF_MKD}&ei5Z zVdC}p+VZp)-(^fpZW68+-FrppwXK3$wN{kv3GS8S6+DB{v0){C*r!)>Z!6X`S4u`=E3LRypj!OWkLl)NM`<{xqUB7xfw{wca|b2badEczjL0 zx&Wi_5V#W;!zg^>))uz6W%b%a34yOaV_D#dst?2$c%m?YRrGGRz&mjnT#u3PPQ(OO z;rAnB&5Eqm3}T1co)B1t+r(J0$SBc$YPdGjGD$A;I6iGuoOdi4-FKKYNw2!uN<)|XM981tv zWDXz%R^b@{oZSn-;%G`et!Lk|{P|mWYJXN$^0|7e*d8U8<*z4ty==mXN z`_MN|%pKH8>*7^f%5!0&tsTDm=WfL3s_Oo!di=&CLG>G6f)PoMcB4hR!wK56LCJ)` za|28>cKpr=aS@){`%nLon!lK8d&`Xf{k5S9O>#I~lB zZS>E>F$$(3!t!OL_@Z{zjviO!R+h^{y!Iiz;I|_|A(lxyElt6P%!>i%f^C?NbQ-P?of1Uhxdu!p*{GKhs z;u+T8lT$C}DVFpA}KM!_t2+AUmhzHl&d$*?~IyAA34VMp+m5f!&=*IZ-#EE!Qma{Ewe~-(!1>SI@DwP#R zRP8`O9~l#Pyi>hBw-LiS9fW?c$l;Gt;{sv)XPHdm_?iN$DAPiX{#wR%4eXIZ8XX+7 z^P=SC)}PB+C2YQ4WQ>&EZj^UQSTt@>fJ5v>mGB%)vKOoHi@^(%1#ApdS!r;NJZNM75Z-nOB*nT*oSWZD0%scS%#Y z=BMB;!30*}JBG0fbF+!P6*BUKx?X(kL0K2wGO6X`14#^k&ZDlKePZ@hZaeuFb)7b_v!$4a=j> ztK>~u-lkMteQc||YCx@u@UEO0kxR7vw*>#zB`+ax%c+e@ZFWi7cE#{4YqQJANfXpJ zX9lY)l9mM-_p3c#V*GZ@==+CUl{U=m&)=0c+ah-@*Vk9)_ZpCH-tQJ{j|VW;#F^xxzTa_ z+uA4%6UH^Lzln_B_6QPV?e17i_g}u&ufIxH#T+dzAE(hgupt z#i~mloeV-YY>_*Mjg;C>@}O-YJmF?BTQq9?&p@?IgJ8H)Zo&2l)TuC7*C`jQdOMlm z@3-7OQ}bfbOmCjXD+$P^s0Pjwi<+>DjdJMbuot=)1W$6yHXoQJM2*|<6PP8 zF_wSoEa}9wCj5>lz>`krS3b3>r>5ksL)O)3I}Q|FE>-H>ioeK{ix5TH{TBi|}?I z>v69ipOgZvi>cR?zH0i|qWw%W_PBFCIgfW)-Xgz32z)*0)w~|>DyLer@D&4E^A<1? zo(d!3$X$_Y-yM6D7CoHR`%i|$8O5W%=k;9WAM^6@tgo980;{NpU);vq#));OT$3;U zlWOao4=n$w;P@qu`#}_^$aq`t9FmT}JsGAMGso_<+4xp{FR_7pQA{(YmiMys3LV1t z7oH{`TsPM088cYT_17u|dq};?*|?XDc;eBY5RY!Hw$Z(6k0mtBVj7;)3>&L%EtN++ z^|h(aW;~?e_~pT7`%?_tZ#JEP-eAjbVof>%dxB}kf_}GSAG8D8z-_`bL~Ap5)NXsj zOv0x;C6Fhk4%vly<49PWXaZhcKRHJ$u_A_d98`c1SS9LAw~ff62V@5#c*k5Vap(}P zx~-H)7s@WxYtdh=vEr?QTT9y^8a5SE|DG>T4Po4ET01@0=9fy(*s>(visP`1&A2TK z^Lr=$b>|Iv>%Yx(m!xcJQJ>N(9%azDXykWURGZ<%57)X$2&{^_(MlgzAfvh^Lut74 z_xjZkzPsaPeNuV8?NX3lsL~O|%e#S!J;9M;#+=U;5MkAW`Oo zJ03UvBzYBxmp5)2W{V*|iI}X!Oi6_E?wHro_;tXLtn#vNhvlF7`ts7}Q-a)fe^SCm zPE@gq&T&hOj+aJs$;Jm{YfA{MqVL_j5Z^T-^!p&b+ih4s+dL}r`y>)|#v>=juKI1% z=1+VhZ?|+N1XhJ+^h*iX?kRmM8!MyR%8oS6^UTPPo~1T$o2XZrZmf|?FOQe2Cq)q( zM$7Hz4W9+ZevaELiSd)=xm$+)4`E*s!1fp`1yQvXX;C$fB55j$u%*lWfT%wFH%1u$ z#{^o{PnRuZDF1`78gU;ZLkvX?;asKt_rEq!Jjw71-a2XY9|_%1896K{w)h7dpn`w3 zL`i__!!83f}z}fg)ZCw)aQE)(#^B0!3^8U<1X=6m0LmZQ$eLDEA); z+xdZv1S^fh{a4Ge3VZn9Hn1niL%4JP%LZ1V>+uHytI*YiGyY#TunOI~e;}}m#=?<} zG3lNt@Y!~UlPLFpdxhw9QEp^|Jheas88&`L&*6Sbv-jUN&~vAw=i|>Ux7{ViiU7LX z|3F|Bx_AG41#LFq`7l;9Y`=}W66OZ^#!C66MD66m(Y79E^_6_eX5Xpl-cgQB6&U+e zT`%=*QcAn|o)ShM<;Z|>^jC~^?K4f9^u3(4vT_`;k-k^6zqJ{AHfg9hTcoD;%WJ8; z@xXZfEPol)<=!EMtO=6UzRY5Pc>BaxyOCff1X|Nk$eJGW^^6pq2i*-!zO{%DxDO}x z*sqd zgup6%-WaPgr;P}`Q&f6)FgqW9zn8xHXldnjgOV!FVZbzFecjuNUJY|dsV}n;0;{lx zjE%n7NEBbW>riT~!i2ypvDhBuA&0dVL34|0xmM*Q1U@c4Z;aLG)KJVD>#J?l-3WnI z*dF9xHMnd!n7N_m-38)Tfx>EJ$969fL&ha&brG(|_2j3Pk~-1l*KIe=Wo&Qmdj7q&gIK8C-5;Z386I3AwrX!R1K}_rr=%;_labsnh;op*Ss0a*fma+c+f>VHpxrt zJ#4DJ_25=o_=hvEuD|53Rt@yfP-R3VX=dnNxA1dWpNq#d4M+HgHY=w#QiZ z39(|ughc^!tK}g!@Nw~ZgG{Hoqs6Z0yG;AuJs~!*3fqIc@ZY)TS+@xbdJmF30MwU2 z&uL_mA4tn27nnd#ZMr;w*SWfiCrWdz>YbOwM)M{y`bM8@id(TSR!ozu7Yn*-R_qDB z^Wp82d6ekZyqk9TWDp_H^+@@rz!W{O)rFwF``bc0P@W7S@NqE>HU@SUNn5y9vg`-T zkZD78Wqy7o;7%?b`;OZLxtvj5#GS~c$w{N%5(2Agk4(!#Tf6Q9c!lz01j<#>(VKx} zT##HGLg29|_K>lNLiNPbJWaLr@x^?ib{8jW>U5$R;u0Bc1+)Ts5|)cp}9@NqE> zJq~#F7QA}2+|W(yGPbvl86~jl>6TZvBV~RW3+-rLE4MtN=W*GmR3Fg=GD(l7Ws<_b zII^B-rc;SS1?6(`6ZvJvF5(Adq`ZQRls&JFW4Q&}b8#>Ys~NSOWzUCqp1>+c_7-E4w@;R| ztdq5bYoo!2yV~K)xRlNNC)w(8{x5?HWmYkE791*^dDe5zWNEsShxDs@oG| z(wk+qc*X@)MS;wX6~8^@Rj<{3NzDhY1%dU!yEmny6a0A~_a+2Zp_NfMBX9aWwmAE} zHeV0yE|h@W`hh`HmAO}j==izA&m+_>Wy&aCb*U}?(*-I`5iy{cr!A{=K|*UCXA3b_ z)yl;3##}y?4T={KfmPTZtOA^Hm6!JZEcf0O&Ig4oQT__ft^VCDM#VX0c;%0=yg(cS zqGLJ&tLW-tKF{mYkfQnct}D%m4XncX;*345a9wHz#IbY)R#6X6i=)!IsBApQyA9W8 z2PjK+Wm5mu<4HR(%~-Fs8>E^E*?HYZtqFlucnty8)k@!z8obKD?_F<42&|%BO@(pE zau{V~Dlo@VH83sbzlqBYG6JBZ45tS!!pLt=Zl6qu&jZr3=GM3zwE8?x%NEK%qZr&* zb!w*N++E(=n-KW8m}YEumRGj5)ETLsa%|?3wydDwHO>mo*u%L$P}2Z}QI)bN9f4Ii zzX)=pAa~Fp)PY_?cpTd!rc zZxaH0f@!#S8+?#XvUYsz1}E|MLt(Yh;FfCANq5^@)SfR$vk-grS}kR(+=ut>e%68s zBXhu>O=mpkzcYE@NH?5UN@LVj12(7 z6^Q2P2&|$luYANTJ!{{e*Lg{8V6Uh>Zy=rm(JUQ-kBey-mzY0E-6po-xmITp4R7?;M0M+F`FhFLp7X+B|OqbxjptxPpE!R!NOs zhjD%^6Cn&w>{pZ8^VqXo+B%>WpYbUtA@FfA4R`zd@6z_~O?b0A&LVk30k!tCV0A&U zKphj9c^19`ssUcxvhzq4tG4cv<|Rz1fRsZ2l!mnM`T1U_%H<@Ki}OM&+q z^XLx+2!YQorWuQZY+R!basXuGCYR>;ORh-r|GiwUg4V-&{P zXPaTV{$waG7`Vi8b7(#OvRz-bhTAWzaTe^^xW;e$dxfznnWk$8Auq%4n5!isHZA`m zv2%7S&Xm3H=VyCAHh+5%W;9-{P1?RXvAj}bZbIOET1-R6R*?uznKp`dXys?=`aUgJ zrPrzxR(xDaG<-Qj8xlE$w+~xMh`P#Fi}lO^HFo|JE6&n|%z;yBc`_~+mJ$N1aAq!J ze*t0i2KmzwScN@=`eCOo=Iils{6SKb_94<_i5wrJnj2=con3ooo^f{VS%Hj|saP#p zK0S)(wAQlBJ>S<7xi?CE0lCLmg|7_|9tF$;hsW?Cp`L`m=Lge_O2@h2IKvp~Ie{=LCtIZ>unM0ySi4KTX=*vEAD{T?II&TpMx&rT&AO_K z>$&QNSC0FtT1sW0pO5pq=njz#}#7p?se=HX(SCH7iD(oR+9&I!!PKn{Q z=eo!R=ZsZL=k2dvtuj_gpOfs!Lw0&?kxIG6@J8(l62f?MI#jqqx_xnrG((QzkJnNg z#(URZM~&?r~t=bvX(xFO^lsHn57?Tl(arB81Tn zdtNwt9)ai`^-gLrz8(MTS_Y1780X5Kp^j-1@!}}rMb_0&^b2gLEnF;}#uYV3hsP2E ztJYo1nPSAwCciW?xkh$MvPA9OU`kvQ!Ar$#w9Z|=RbfLWs5o<-W~)!Dwb`=z?RfL^ zo`VU2RVd;GHn_IfB2}GYp8R7dA+QR!4=N}9wo4vAV)*FO8Eo0(88Z%3cO^}>Ri)Uo z%4zQT%Ie#tl0f+WMG34j&aNZB{pE#WQthZ%-ae<(|Jbmrj4SBqagJUbCN%(JZ4OFc zm0`o~Ayl%yPLV45jpmy>&(`*u#;D#gL)CjOZBnQT=jl)Pi86oe9>-^Ooh)rBn^r}W zKd68$L;bfW3eI9@?1A@E^W+Jm`R97q2!XRdk%#bXN;8USpNfv=Ur#+F1kMq~G~|PI z_Oi|Hg0fDt^eueSmLohN>L(dx;JzK!qiU_S^o9|@ukNneDa$$A7^i}wE1AU zr~@f0!ere9$=; zLQqfe72LkztF*6fOI~hyPD0=-i0v_UYVa4S=8o1p@4s2Op_;hKM>V&;p->gJu>**P zK)ifP34^xx29$=U5RPsC&tbzLaKG#5IsZgBR1SN_vH#nK;|_OJkNlZ%R6gJeg+JMF zRIlP%+dmO_N1zP6a!lA+yxql)YyBy)2js8S9cHF}||NV);`vcndIsEh4b*S); zi+{3#cXhPyjQD384i(;4@lQ7J?u+(4z5Z;&p>pht^=HDqdzNwMJL=E>h7VD(RnW zIMz}f5w<_uu*czyvuls&{h4s6aIEi7UfCn5h7Csy`A>vHg?9`66XDoX6pwfRMA-Ku zGrV%_Q}!pqp~5raKN0rXwqe83i$)K>A%)clY(naPO2MOWTp0*8SWrLc3B*09AH)P!;mSa` znotdB%ncquH6SLiijMT1e$NfA!Q227ScN?_vPHIO+T0jkuX`SO;j@*M-AnKRvgs zSL!H!%2JCE#+~>(PEBT$jNR|o-Rzzz z1w0!gA7@r^Eg`KRw3NuMHGepe53IhQ5LkudGmH&6InMN{{XqU`{vkqOmEoa11_U+L z)e=nRr$hOMz$NmkH9MvCZTqX+M!vPR)~>>50p?K~>xz^W7v#TF-^<@7w9_~J^-@_o zqO6LegSh&Tv8>zcip1Cp^0)Jpz$#oH33&kCRYg+XGje1?5sqzO6^%e%tz1=Xt8qpi z5JL&9!X7eqsCaeZxn-R^=bAfjV3BpxqZf+xSFnn0;F?Irx;L#Vax6Y3pF2~G5ZDH$ z87teax_CBmk{l6No)GxBxCRq;%|7lf4)vNYU(Fpr2&|&JQ)<%-iJ)z_DjZLSHQ_m) zBKiDBxzcGDj&0y5H;q$2D^gMHN_a2NE}Nea__&y6?4fH~1?aC?%cUMpX?3DSyLTq5 z`nVbt)*yi}at+?4Bd`irpQi2a(*THlu)hzsfm=>j^$$Sp>uOj9m=CqDn83%SHKS`` z|HL&w{OUD_*uW}m56*74+)}Lvb>#DzM)4g17lPDivvRW06ctxwZrzkQXsOt!G+kiC zELS|PASqA%Wv_{pz$#pK2@$U*jVy%*w$y429m%(4aI#e>^u97d#c@#_jf7Rp?Sn0g zx+Q3by`u?%Rj7gsylUtdYvNZTwBr-w3_>xgAPgIZC-yofY!CJdo8DFO%r#k?nvD`D zkBrd9sE@I_nI~!!hEf6_7q>5s*xM#STRM;uSVh}mFnj(V1Xf`W8M`~@qGicYS8dzN z-W+8#s<`R`pEsze`f|o{{6tP|!}mUfz$zS1hPsJ)zbq4q1j#36wB>!fJj+#cQu%OV1FKLT84%NbA6t6*e>VRN=}ri&!e<(? z)wg(vaREW5v-MSe!$q~#wI5v=s^Xd!>>*=2|A`aB#^yDbXmQ`%apzP$_1KZ1+Ijc+ zCk8cqqU!qqB}jXN<;tmxZ8Q^WotHn57;v1|uo6%g5*QUa^6hfqJb zJ4P%mKQmy%Ue0bT^t=VG@6F9#eXG%j2R%nd) zvM)rN7vw=~;N#K?h1D}hi`eIZT1w%=#0FO3vjCOeH%ANgSX0yXRe}&$h0io(Y=w*# zXa2fmD)sCUA+QR!2{N#Kdy9yPVcNu7mn}zsj@4`Q_#TwC@l`9X9>J9zjJ^HZON^h} zR%?6d3L$Xa1fiMFqk&?5tEyVu=6!^~$EEr0iF*f$aY0i|#U|_~1Xkhfc=#&G+uovc z`wV91MwbYIRoFwwHMkNj@_L48d0OL)y_y``gI#V~U$IQwyTG(CqPIZ3u#Wn6lJ^WfPPJQ>qCr7&K)$Yo zz}d<;a|EjBLNrV6$>+>Nj}0Ki_QBVz;n|ldPT^xoMFbf$5CUIw>>e)P-6D?7C%1Xf`Wp@L_yt9&*!3vb$|wU`1sKedIOpKd)FuG76yaRhQ!mV$DG z=Vy7MHJlJel*=B0q*Wdba$b~5)yl*tE)Nsm3f5CH9nY<{niHpE74@oX>B*8;Kz2TP zU>ibU6>bw_`%EJ7(&|4M2a(Kv zobeC2&RNrTJv~{sht{=M+ODTRPe@igE5a+v@MeGvY-5-IWXQnA1kSp~+1T*)3)rp4 z*wwK*?AC(`titvfyHn_uZCA%5y*(|1FQ@I~s7{_{#WwJfV9%OdnMLC}*UW1cw-eRo z6w_bzk5^{4>7(Pi05k%G=RA6LNzwgU1+C8G5E0kiU(eH^ld?0sg^qW<#r0V5C4nZ1rcB(AKPHn3DCDl|KJDGH>!Zc)Z zeCML{8h5Q$PESH$74Cf?i}mb#X-lnkd{-kU(KmN#wMTqQwMb$K9cM%vYtW9I?WDQy zrF$dV@o)Dt5Q3_3WP4+w50X>qc06t{wP8FT_Q*E2$5^4yndQB;6`pHsSz#Ra_c}S8 z6Gx04t%k$j*A%}e#bi|YpbO;)VML(pS+g|nb$gFYa=}Wqc}nq8grF*iJ*Z>p@kR22 zT?E^1t0vGcg8B&9Iq(eZ9JqT)SCW|vF@UZ)pZS+jBb9zSejCs>t^fN{9c(lgup87A-qdoFOyg7i>q){Im@@y>%6CyRfnsT+iNiA`w zCCRge7(m9k($t)d_}?Csz{kZjWA)kf7R3^tq?E37S*bm6vK|)|XkD@- zRXGm3BjD_B#s)bB1)jec$-6F^XSwOL&~oM605w;_6D!X6#+lMEkE&3?^fBWw{-W+& zLZC=9p<%`3&`8q|=OO%L-}RQod8+cLCVkaXJ$@0DK|3;jZ#qvi*Y7Zh&uz1p5I9E| z=O;rI#DZ*E?-qmjiT8U5fmJjQ**qdq+thvt-&A=OA+Ug(Q+OCfAyH}AsGMrz=*t|nI%tiB! z!$_w6aP#+0aeVr^L_%PdaRnW@gWFn+Fs}}W7+mpbgup7C<gsZ|<=xjyL__M+mGkJhW%v zGj^$(lez8Aj(p76@0Lb=uLbp3)KYyJUyVGe_#T5V7Dm>W=Bx?hs$Uj?3H)Bc`Sef) zajLQOYF8MqnV%AdC-%1wreVymYp-qh?_L|AVq`|zcaW-g^w9B6;B@!zIY1cE^FHYa ztU7=)Va|T2&}>$!fv5X@6)_G^qJVep3wTi z_(Rns{{}Qhf9@5j}wWCu79M|T4ZtY>S~5u zR=)J{8teWAyOfa^C#X2%8%00hn#Z5&Z|OTYyCj}Q69TJnjyR0r>aDeu9X~g)Y}61! zU=_B>C)bkqVl&GwTAPlAe@IzbI*@9 z*lNBwAdbJcj3orldcZW)NBO-o51bdrJGTrW1kRtpH0%x&@xwf8T^tu@D-&XKZ%?sv zO01d`q6A@@v2{zvm?M_O@$m9(2!Va4z1npDCFaQofp4hQP zR-1;k@)DJ|#;V&#ZR1#lX;|lk`Nw9MfArc|l^g%^d&Z*T9lz0B1n%86(gSJduA2OP zW=dcc&Q5}TabU*M5oRoL@BN7lygxa%2VYVSye$>bOY@T(f(d~$d1y{iQJAqPFk{*9 zk`n@}usw*dv`v=Qt*pp<_L2yJea9I|P}6YJENvB@ylf?z5Lkshgs+kecxub6x!LTc zbm!L>TP{wW3?c|;@8B#OxUYaPvUl#JBe06zS3y25+Rn{!e46S?Y+x0>{_r*0da33S zb)q585G^ly$;9Ud5o*kUD+z&s%so zA+QR22r&SygwRq8^5vT|@qFXz>&opsYPP)|D*j3c{r<<=;&WRGh;?cNl-S)?Yl#vrH;qxe6iX1huuT#2zW+r{Yyvm_b(a5Z3ccC7)!4 z5LiXmYwI>GEK-M5mTQ!$PYA5S9x^tkV;vDQ@?`R^tYvt3%`lrM8D991-6`p=j`e`( zIN@Y+o@|uBD%>W>hg;u3nvk`poK$)QU-~U2$hSd?vczMGig)S8SsjdhUF#;b%iB%gSA`#AjP%P8vnM!Yb?`WAEn_5@SZ>(QX!P%)f<~)GI6*t~AQgi{t^I7&5eD zN^k)&U{hv|PijgCtiqWJuz$%HSFts2rTIqhCWOE$d{@HP1Wy$b*A~AuCot+2R^dzq z$bpJG} z6R&@QjbSZCNf9BJoRC2b_}ES_7x+y1n7N#e_ll$Ys!egPCw7QbIWg*!1rt~malW-) zwNVDu*|)R~S*%{w#GOqiWW}qf=o}%#Ehhwcb$ndxA?!@?Ru&q3r=f7K z8-&0rY!6}p=ln$JCwX|IzwZzNtFX6>?e!jJK34CtdGOzHqE5gdo@v`CMgEpZcI86z z9XMBWx}7l(bJNYIu2BN3(3}d0{mon~eo`CL>9AOl{pT3#xyzbT(K<=TDl~fm;`!Hp zrm&74Qi;QHV$o&T((e5t<>H$(uk3qa;k8@%TH412mS*KYu1Qy#y76l@LPd+D#!68iSGA1qNV3|8 zSIi(I?9CR*Yl;gWai%FD@H!q{iF?udveY})nXh?634B~kL(d8IoIN0)dSVY(?MAM& zU5Bogakk>MG+f&WUsyevw!hD&qqhiwRd_87zM=%HWJZK#6ReV98(2kG$(F-vpFva( z=|OB@74{ImQw?4jdEtA&tB_A=HKR-K`&zLL>>)14`X=;efZ=dRSjMIi(lUlAJa_C=XQgg@+=xw{o1@Nw}$3nj1$p9R>({6qoqBW_mUoaRl54XncF5Nh^;@Qa-lI6fVLRrFlB_b4TP zO#G6(U{76Q1FP^_G4xTwLwxL9&D7UlB?MOC^TyaRH-9mH%57=eCU1epgXD}-A|R!* zczZG2y!}g{sJlOSN#U?4TZEf!Ru(Zh9*iZTLG(hzj+uF9S zW20vU9-E!qL=cPa5%jHr_BNy^;gmy}XN=(-xV$5`01&Ze>R zBlyXSNtPC)ItKYfcU8w+Dxl-_FEnF?>(QP^n~vm*;LX?VBm`FB^)Kk13pX7u7Q=?$k@@CR4@=m3nHP(O1>*h#?~njn2<=NFv~vqgn7}H$ zD+0s->R8N+U&QfN?G`1kdF~~AcEzfF?)i&X?v;fXe7AA_(&e_j=^QIR!{?jL?$6?Q zQlzID6UOzht8klOg}02aHZuiceUldx8`wi^4>GVnO*a?MK9YCH(%v#WEQ7e#Ww846 z$7w5G`J-!hwLVTa`v7q^6D6<;@9)G|80U9u~mxd;#gohgA; z*h9!$dg7nlE8B2hrrAWx0Dj35vMEB1pMTMcSCsL3Bx47ZBQ~(gxHgWJ(b*sR2lUN3oTr$m4XnZ*!hLnOob)2TC+{V0TOt}i4LbX* zrJ8G9RUNP6(bYb$hZQA{{XO}hE4K)NRfawLIvzysrg}-03iRZ|hutLvR$+UP@e8YD z4PouBJ*<-D-<$Rw-a23CI+&WgVM?PAOEvcSHan7}HWiv{!Z)jMq?%jeE}34upv zbhI=S2xI53m+1(s!XCmtMUZ)I?6P^Qdjhe6J;CESSiu6q81LRsM_?89kTFm9`BIk7 z-S`&R+u1k7RSoIiLS5g!jEZ+4LT6fq)$mL!rR<^upTGM%A+QRsp26O@;UA<6HNyC& z4;eYOK~;E_?83cwl7JkqX)T=yVXS7@cfY_M!YCYioNdtKOnDZ=i$RaGD6Pj)@wyRS z(_!rVzx^yJ^Xo}|r=xjB$9z!5t3Y%er%q6BOYs}7Qr_|-2!T~-rU&QBm~-})ZF5dS zU=^Bw0^!J<9mH`nyTciEZXme_wJR<9Iqi5XWITog;o6-Y4eXvi+4-P=(IV< zoMID#@cuP8$_;C&Kp2tj^aNJn7&)wYRW5GpaWXgTL~P(b1KWeW?jy@;v-ZaEVWlsa zuvhrFG!~v^PkAl38L|^{uOS3h;j;j{2tLcAeV!G?JFH8Pd&RG`JlQrt-8J&5f+OiP zdVXR^l$I5~nBMciB0^vlj#)ESE3`&H-4Vn1zl~=R0;_Ob9OCVnmM1T7ID*&N-COPy zAS{{74N)hrJ#MQqwb$3;_&#G5KCeg~)Ha&W8Wl|ltio-Ax!Nz2SO>e%-1*Csf8*`+ zS~qtpBTiRQaRi!1oed%b5cks&XhcqE#<~U97FUm7lRB3uO>E%kFs7l80^$lpCo-fX zuqX8EL%V>u3`Dkc1Xf{tkQW|VQE1NDlIt+eO+l)@>Oi8B)R)#Sq1gmHQC^2?h<6!s zX#EQM^2bG+>9u+VDO2;CNOTZK4dII+TiOVw8qIC=h- za-wB*u6yTupqvY=OJ-h}X3V8|EwM0kx_l_LG$F7GM^OzisCB1^4&2!U029u3)4?~049->1m03QL5*Dm=S~sIy0Qk)uLJ-sWN@ajX&7 zCz-RV<=fTLah?pOVJ)>=9ud0pi#$Boix60aJ%n*$pttz={E8fV(2WpSg`=ua`Etce z1U&giUQnYTA+QR^WTE;ZCZ8qm^%*Ajp0UD@2U=&Ssmh&?2_$BTW0{Z-mw&6)s&$Gq z=L041EDZHHy0L@uKJ9DjJ*m<_O5hwwOhaAj=XRD;mWgui%MoI#BWHqSN@5yXey@~8 z%`{i)S|o-LxJ|SjEAo0++?wo=p06842z*>jL*y>(WZ=<5siyn?#)&?cT;)EuXDG8X zOx4pzZvXEq4=kzCUdx=q2c_)|28u!7)>yyX*rgmeKS9TlTN-;kUPV|cTrDj3>(-YL zScTSf;Ov(AaM&_zb+Fu}M=wHP6|H%fAQ=0sxb7WHM* zO_Z)nN~ovD4AF5WG0rfCDxo8nr0GDENT38(;fOb62z5Iu{dLZr_g_y5tfGhSQVGkJ#eBm$Vk9jWj8c|t%9otTyK4zCvXKxj<@6Tdy>+f#2u&9SnV~w@I`alt(MjsSbE%+s)IIkF#o!H7{(BvE1bX#dx=^rd%wM41S;tX4)H_4Vb9AUAf--+U)V_*L2&}?!Kj;lqe_=fpV$Qd|s%YX;U-xe| zT8Y?Ko3xyIHCzf1J1(3um7i3F5LkuV1beZT3K06ri>8IEDS=hkL#Xt&E|)xg>+#V| zN(f7SALV#PlUmuQ72NHPY;|MYZja(I)^Wm0DN95M|16ax1Xke~Anaw4VUl$1V_iPM z*PRepMPq%7>L*CQj)n00m8cD@!X7fVpkS!|YnAinL_$ODQl2SV((p@COt#Ttecs~o&bVdDw1WP+hgqBva}4LgwihwfsadLeJ_D9B6nlc5m<%oK~@;76&YS7!dj6j zQ&C&2FDWD&X*rJjF}4(hJF%9pHUQ#q4RWkW#spU3h#rg+Q>thM zf$&{hk=Vd0e5N7ecapc}q{Z<&&4&{LtLWK%H@c1a;@ZvTVlW%-vHmNU!^bF%GEY@; z)-2vT1HRSx*)KPiD#N9zukza5>X1UgMsp_*g&7*nZ^Z6prafW`h{y!X%* z%8px!YWl2M$G3j_1kW~Ej!lssb)*E&7Wuw$7eCN^jk4{qu^Y+s@MKfIBS)pN=FyxV zcMgjGvR+xfI#Il0J#r*G1Tcd>-PD!i8o%pl9IHThjTCzW1CZJeyRhL;<; zRteLnJ;<^cILTBp{;~ADIVJFMF%8)}&jy>DZz>}w-6{cZ# zA{YuI%=O}?y*h9v0 zh40f=Ub!c|9}vquVN5+QZA`7=s1c16&325b34zAZgl6n@J`c;gHan!F>qZd*9~Z}& zU~T*3WbML)OVZeEqj|uH@6xnF%M=gD*~VUBd+>#dTJ_9BSq5q0jW|NwOUz+0_V0f6 zi{8hK&DcN5{Qj?uQr^pyz{kZjd@Ze@N8p906Qx0eDS@94{M<0suEP&=(#HI9ci&j< zx9x%a{pkv2)r~}Qm*8sy^T90{wB~1BwfXsz@Li_N*UgaCInW|yQIL9i3cJr)1>QNsSR>%&>MrXgooi;x1Mh#x2v=r*mq1r zY^koV)*0TS-KDjG&3+WIz1y3KY(Y5ghu^^v3*TB*TLMI8zg#9v;J6s3;ZAJjtrds& zZkDaX34vpBn1;F{SSvF650~=`2!TDpalf?aph3J0?IdBZunOCQ{o(qb3%Eae7@tsK zmVCL*REzhH0qX6(PZb=+qfxbc-M<7@Uoni=37Sa=tTIMU_6Qqe@0zzsF4iWR?^_Tp zyL7s0850_zPU&|=!7(`+RSW-FH#r{=trt-O9~aZG(y;hSz}I_Gy!y~d#0G8?rs2KY zzjkuPTTy)9TuNY1@L7QUWQG+>J_N+TS(LykY>%QadS@v!GVrjjeGaFcVW9=s3}^9nc<0;^~{j$Ozlrsd4X+kGic2&}?wf;_TShsgcl*OC)gf*Jv+CT zSX5$d^111f7*$Wz!!sr-^SXxW=>0)5d0>Q`tFkzFxwyH|8WSP#ydOsp7|Yzfswh!1 zYjT+ce?njtwg=xVe&Q#tzde{7Te7-vpIBFaFO5}x28WQS0gfiXw}e(y7f#zUnm+aP zBLr5_7(n=j1Lngp7R_@mMht`z^3k*rvW{oMH0z~a>7(YH;brCgODKU=c;*c`MK{6& zch0ITH-lZqunnxj_TW2;U7WN*vWP}+6hB)4xhN=&M- zCa7|)Jxa%arx33&4Rf5g8Km~It9++)EFrLpo~tsq%%&EZJmjW{F@(S>>Q#wq)wMdu zXG;|d#fi6mjZDX8E>>>5qVW=ZreTG*^*~dO++I>G5hqeN1o3ifmMbmp(adEW7l*N^ zb?1S2WscOTH6`$I@!iANt5P-0LsEYwfA|u|m*+jCb$mZnc?ok4JXfc)?J=p7%y&Il z^4*V=z;h1Ne?WikX>Mgsu6y!O+pmy>h`|(d$A2k-kBcJ+P-{7Cnt9CB zvF2+Bxb_`7gByfmNvg0HVO?Dx!b8%gJ9m1rP#{Sg}3$LSDu?BC~cQdFHS(9QDX5 z8Z(d)IgG+xJ;j6kU**}~oyF+-q57s0dDJEi%jtNWh)0>Q6SP}Jk?T zN6T=x-)L+ONnLIp{xVJkt-i<;2gfT*GEXJd9C*wKUj&bfF|P=XH@|pA39P~+PS_Vm zOfr}AJYgF2AWkgLzvtiqm&HnRsLeoc0}@Y$HJ0$Y$;(0%Y1ckV;5RCLC-&@@O)HqQ zy>u>?66lH2F%3J{f4-W0JLafq(lbinJlr}eQtD9QFswHj*R^c|m_XoSp zGCwSx*&P2aPBeJAPFuKXs`4C0;rRSu4`FVQueNCWxRtr>?6Shc(n3EqV2q;G_a`eq z=Ioo9` z_=vyG98cbOsU{(?3Xjxa{o|UCIMOUMAg&@MunIj<(2fzsstN0;UWepswTKO@!ed7G zs;*njEqrwF=@1R3u_q+J|!ydm2%bEtA z-70->i4*-t?&0&htWjzmPSi0$`&x6-!@$E;k|metqX~gkc>Dl4EQd~*HebCaT^dCR ztiody*q{2s64S~V3#H65^$M%7hp=<~I)C%i$Dsj7zs2!q33~$fznr01*;EzXucS|e zx{1BD%ttea1)NVu;GPrR`S4Cm`BlW6ebo=s`rFh7R?(i*{okVIRoi};7N;Yy3VR5- zoO3MZACT)D-%<*knY*$W0)5oKU%$yXl7{;$xD)4E%)fwGyeg0oScQ8##;*PD)j|qV z8(2kqoVurcG!^=&!zW~71FNuykRi0!VwRvEY`#3({t>_X)SK+8gnLfxA!AuK`e>`b zM)%Kggupg14ZF(!Q%yYjHQ-?1Lbdq3L$&p*gT^WEv(#5{pNO6=xPk+>RTs|NR}dyw|x#?`+7#X(r|8;S8AyGt8 z93L}FUkbBGdkGEPbVy5|$|zMG=yjVp^E&+K~#*@%{hXGw06U|2g;Gnc=wUZw8hW(PbQdr8Up$ zvy{uMOl;8#7MwY*?eOM{hGzk;cH_QUN?;YfLdZPXz*J2^vRJPpF>tmx9>@6>!rAE$ zJIqNh{McBTRXLQk)gpAN72FNb4nRE-#@L-ub7fi}A+QQ}9I&faq-L#Oy{7K)U_xLO zj>mB|p=Rk!V=cdB)xnPBZ!vWpDyb>Wd|Dps|;kpaE=aVO8>(V>v$vOh7aMk9x0zapmdFs04U2-t%_s_ixoz-jW zCr2_{xBTF5WwMzj7X zo8t7Ai$imI1B8wfHmEX*%2!T~}Z^_q_l$TBwSjFAuannRkim7&)c#o{*J zg1w8nkGoA^8KYj_{Ue$XScUF6)Q_kl*nun_mmV2u4D44p9z5CaYn65%&E_Xyo@cr$ zO#wC4qHP0p2K>*5=PXZT$)nqyo`*0$FoEYIol&s^*>d1ws+6;iz`u)WaO#f&tFZU* zI(M`=c|J$!4=NW|bp{I_H=6mj%mo_K#HuLoO%|v;$U%AHdA-% zO>r}1j&q`UxTX{3nfPkM$T|Y6u%p5`=lw;gP#wbi!|37|ScT)k-qNIr?HsIs`u3j2 zY`tYu(hoXBb%ox7M}cO};zU-L7%q3tsR)5pcog7U#lcC8PY9IfjZuWaDjbjF{s3E0 BCnEp= literal 0 HcmV?d00001 diff --git a/ros2_humble_crx_description/fanuc_crx_description/meshes/collision/j4.stl b/ros2_humble_crx_description/fanuc_crx_description/meshes/collision/j4.stl new file mode 100644 index 0000000000000000000000000000000000000000..1341136996da22bd9320199f6ad16e979da86d18 GIT binary patch literal 24184 zcmbW9cUV-%_wdJp4LbrNQL&+-f)!ENJ9}?1HUw0_SP>f{ied>O2)5wY-ZhrkVv8k~ z7?rqp@9vUV5;ZXzOEhZiVq(+j6nJJ~a6c%SFx$saen=X1}QcIKQjvv!Y(@Jk$= zGI(^t*ujJR2BiCS89ZiaM8W{_|M_>d2qD$Sc&altW^1XAYHDn*mxGW=j%<%pc0%lV z`AfPwu0QW)?mOZL{Qo3}HM$yn?-N~FjrcNKyD`Pvga{c)DVQcCu2wCzTtv3!$eN_G zZ}QqlIwlOMZbt;X*QJk;y3utkKU}?~cIc6%?XL2f?E>v-Z#}k;F4b+`FE+1_qaEz? z5>gEP)NLSq{`>3@OHeGa`aYdV*}K}`jJB6f?5rSKx60X7-Qc;=&#g_bW7=8|ev(1^ z?yewzd^OH~q+Bn77(cSC%v!!+bxR;#tPVEq+j>j=&L>MC7(L-$S9)Z2e}N|C5fFQU z$O8h|D@b9Q5Yy&n7BjSbcbrJDHgVgJ;3N9??CSFPb_oSq z{?;;q1{}JfR^8Z0ny{~fa>&Qco;ziVoZF!VNKSGLm|ss$+YzZu2ySejc)@BWbO6b2?V1<)~DKjp1(k#3HiBRCSAX*gmviY8>S}XTPj0NXE+vTRwy79qU&?E zYugu@G-AtrHS6Y8fgr>sC0aG6eI~v6!#(v*@z(-@rEr@F`Q)Oz+Ub0@w)aWaLHNdD zv=(M}i2m%f1kc1%-S}qW%9S+nBKtJEo#?pIAJF8EV41r)e z_uecv0Bz98=3)nWv^JTVXyx07$k8#f!as&D0q>(BpW(o^vuBr2boSOHu!s;C4~5Tm zXa|g()1Sj=>YqD({(lj84Wc)}TmFl{Qbz*6G6`7c70!Yk^(2<+hy4Q+$JN$}r0vjj^a3!Mam-XX9Q>IDZ= z!T#PQuoN1PLI^B{Mze4NW}QBQ4$!ARJ0qDBLuJdNyLnQB?BVp4BgwXVbEe!ps<*

JU8@r5o9E{x_KinWGsU;;A2K6~m+YwQcfSVj z*ZsWW^z%Q~ydq7x8DuSaFM($4-X)Km+|C}H+=0y{Zi(VG$R=MuKiF2SM`zISa*0Kn zy}qs0e?XEzpw-yW=LQYpk#XTf~wqv&z;ai?1HqN)?*CwD*A`-=CQ z7;)5@6Kra$=1HyE4}XW?y^DLDka*7!(?XAH2U}UPY3#5u<_&X;$Zx(%(4!^8t0~Cy zfmM@Me0%Wao*pK$K_svx$R`5P?ezmwuMH;2LrWKQ;5K2JkoAcZ>E0@L)dO9&nf~{C zcV+r>U)$V0Ma?+M!2Xet#Ijj*K+qkvYZF-@uoQdKVy|G^g~;iYkeG|v^x}@^me{kA zVOR&28ZsnCADfDgF8UL4w{mytolwNur$sq>Zj8TDVe?AczQ4*U4bBBA0lv3wLxwz; zKN}vP?7W+1t9`R1w7hhFS9m#I2UK=Xq*RVEO)kq+)6xIjrh%Zea`_@v)(H=CX{~h^Uuxjgm(WI{;zPiM9 zJ~hRIK7Q^M)~{Vxfhf2JIZeo#Dleqe?G3Gd-FgcIelKnlApuurs|SvRYmq}RM%H_R`wfBLxCmBGSXMKUK?L4%DiKwAGl@SC^jHZPy#JNYBoF zJNx|DiCT{Q3vLcVj&Ar!4e0m8>R!3OKrksDS&DRE@+az?l4G>0_dd5WsmaA8$I(-J z?4pz_dnIJisyS-vx*pnKLBgz~c zPc81H9+{Rk$Px&q10rNyO0*E|Q5xFSg#8s-uJ3RVIe}GwzuqF%tJ&Ooed-8-z*0da zmdm>$FRKra#{#jt&nBr~PBZJlA}M;jYvkt+EQM(yqZbG)g`;I5qZbG)g?1dUYL{nA z8eIR7+DC4wp_S?wIj*KsZ}AXY`Qu)W{16W%H=v%qL~KnUzK;u{s}dV(_FAi~U5?jN zt|^(0dJEUskyo=LzXJ1FE!mgmoOZVk*#1l)uoUvBK*Y`OXla#Zk%Eh)=qn1UA2O?c zpgE?n(R4*JOT1z%(_)Bp^zpy-5}jaD&Soj|Yb*?zqd7PPAJbv}1TRl4qL_rG9LP0>N}(3td)y`%RqX_&6`x*gHxe z5Ad&w)4#gL09goQQ)O>e zli0hKe-p2Gmrs__*ywci(TR#PW>|hRoc8kfrtTvrNNnzoykAYZc4~*d>*pulmScS; z%j|O!*;x7NaSNG{B#0CLf;h1V#EI;i_Ve1w%Wu^eVnehFz^aizEX#Q-m6+_Wua8}8 z_sOMadO6rE@ee*LKejh_FrvY_H*)XOkD+%NF=X9Z>EaDpAdo(RCS({8eSo+M1d37x zDNH-tk?(AWKwv5MY{b4W-zvat5Aih9n*%*G)b9>F!|}`~q`Yec1%izYpJSLNWC)Dl zOc?X}yL{gv_`Jfjlc)zX1gLiiBc|3@7pI*qcbn`_H|D&xGJF5%<)vgis-*W7U$v~| zuJK@F4$@L_7(q;6DfT%ZO+sowU$ua~%7?zf1nxKXIoAhOXCUql^q@cq1b#2330W|3 zu;gCks=EJL8ucACT$USGGk<%hw~!Cue20*!kyE7F(a+S|pO1To;I-a_r}O0C*Wat- z+xCFDJKtxs(|c@6LOqEx#Y7pnbPM26y`U2|2xXlT_zYptX}{ia_A^isRwaXS4LT+SJ31V^s%l^uTQJ@s->JRyUZ5+qlbd? z0kl&yFB&$KCUx4NMou^-ee2#rIn}=r-MaCqkZp;1lxO!O+HS{4_0sg81p-T52ydy( zo_2-yPW}gUJQKwKU`MTw9_XA0!yJN z19bf6Ihf|g7q!|-UJwW@h4m5Ax^DxjR;C;uoRBYq23-e!}Qgn z-qMw^>4FX{B}U<%5yAAvlseWeZb91lUa#ef2gf*Sjd2s=Pc#!@uRWgDhz_$&w+^1y zOdzln>IG;=sk0*_)7(GQql445lz}tkM)T~_)$t$eE$0zA?gfaD>o1b7pRa6{M~)T< z9Jix24?5CUwxG>2ttQ`#Ewu%MYA6{CzcSx#S5=P__>RoR--tedm|vnBjd)nry1i0) zZGQjy$~d~z*3ItjKr^vGOg+;#ik6*H-s;u7vOowezg$;IoxIL=^>KO7(R@n;ec5WF z+Ut2$f#{2*aMVvo)F_!=^!2s|#n;i=T&|@AeX-Kkq_l?v>kxAT&(NWC%=G7K`8Fr4 zKcy(jmrdK)&A}_}I8VTBB4l6Jp>#v;6SYEVk-$=D1;d!PXqH5+M_;ItdQ{MXrLaCY zwcI&^{yC_Kwf`@BtouTmDZw9PI@;W8Cs>7PLN3)BP3xq+QfD4sE)ZA>=R1U~?wmwF z?J~?-+`LmDu#{-k2a{z>qixBO#|P=OQb?jL{+nny^+jKW#qB)b5i^#3;Uz5(m#0dZ zdE*5FOR=4S*DneAxUFpQnw2WOwTpx(<h4 zHBi`@HzBoiV=X6+PNd&%bkl3dnBXzINPBsYva}nOK|j4f1%kC4P89V@Gb1?dsm@OJCsxoQxT*#d#D|YM@TS|3s^xc4A~(I14L`aAjLKH!O^B z<$yTnER1l~VO*7v!duSkC9J3U>Ei#Bu(7j3M)1m1;e<=dRS7Gc;Po=5!&M_ItmQ5# zS0$`)9k}}CIvF)|Okyn4&SyJ&c1hvW@WQO(r{RotouwB>xTIXwPiDz~&qSE*|5iL* zb($S~b?_P~YX|r){iaIcgiFd*pDCPR-@O2i zOA7my2@r*U50#14Ic|ETDEj#zy#m1^Z(cPLJsct=CdCOXg=mOHYq6ZueH0yf@|6h_ zEK3PJ+*uj2J62}Twx7Bg)sLz`v;tyY0Rq1l(-4aSF$5}Ji=pC$zImtO#oI)PpJ7$f z$yX{S3R);y#o96VJp_L*rs1SPim_aQ{lmV|&5FD}>@2Qb2KSp#DG~@Qg?a(r^x)@I z%a+tJv|NkT0>N}(Pwn#azEJ&OSr=qqI`Q;QtWxCE2E8JP+u^DXmI9(F5K-?TxD>OH z*G>o-0P`voi0TCh+zVnmZk~#=WMmDeAKVqK65os4^bCj`AoBA?0=FFNBc$Ytj+XCE z`_gcz5VCKK+KayK_+HCCcV(%p?&I&Q;s^wmV(oC%`cS1vAg~mpU1!iEJ)eQV5K(q(qK>>oz5*&-VW@7rwM0)hlHmUAUQ}w%pIZ?CZ_^-Y6>c@(B zO+LPGpUm=v3b{k%aW!MXw~q(n7a(f9hv0Q;mhW&{sB-F+ZKIm0?*M#Ovhi@uD^_(b z33buMQ0Zi2%LzQ@crHN30@d>cKNg`^n;sSjYzcej781hh?Q4NJ^B#grVSUba6op#* zU8q&FZz9?@*LN>Gm)PfgjyZ2~uv;AV_Yi!S!L&fA|Di+Q;W+Iaj~_}Okv`pD&&o#X z^S&$OsN$<^?AaJiyWR^vMUEN;q{8YL)`QRur$$v-QYnLfTiEW~x*6X6QfTvT2cs zYI0Y%?dEFc{tCVUgDNcG6VIeBmOk?ElXCZ^3Iwi;Gaarvb;Q@@q>xFCrLWGW3j~(J z`Uv>|T5eS6bx&dXc4A`ml|W!A_RMRtgs>CE&%sMGZ_VDzbzmv>>}p3% zAZ7u2Wi&qvgFD-6GU=zkA60W_ z6w_y**0y1enW^8 zSW3Jh#O@S*HEn}sTH+ajz*5*kLT-%Dpy#!P>bSbi^me3MgG?_nGxb_Hzva!=Bfl?B z$W0)w05Rr01eX$Z#DP_v&qi9V?s%?S#dTmQY@xH|MmsD_%4oR_5pdfH-;FvjJClwg z$JA=~id!*pV|;`XvLw*{>Rt^yrky$(K66tC_{=%TzR7(f*>b91+sK}cTUwf^gY~XK zgkl0qAsSABbGv5I^iH=`)8?^y%ip5|q+EC11wwB*C$JRK0kxH;>(c4QGk4T;%M{&H z8)IO{Eyoo$;by-;U@11{#`uG8f0CR*z2_}b*Vkw+5LgQ9gQ|0S27R%7f%?CQX8L#- zV{XGzn1*xC>J?p@pqguJn4(3FjTs^2A4uwnvB;Wok9-GNN%zx|dPI`F2T152?s z@i|RM&xc)T`H%|M&yIM|BkSra`A^o_!au5@pc=A_@B4wLHnpPl;AS!J>@Ojf30?%;=IdeJ6HyHz=&IQYb-NV2lJbU(1#@l)BiPDs~!yb17d0yfu-*6ev;U1V3q&AUoVyM zITxBG5GUrAZa^nit#7?HH%!}G^r@VtU9?qe7~;TZA>wJq_pbuzSF`I{mz8WQ5V$Ij zX}Fg$whT30^S7?1-30=_*Sz7RTq`ce7C7@G2V@ieKJ@JuZ!BY9MhFC!V*3X_*&w9h zzNU1nM0aWBe)!th!as zDy5uwW4bdxSs>7^CfuwdL>szQ>UT5LG_*#lK;Uy6tdEdy>ju+HZX4AVUpLpv)U2U= z=r>vWvX75&Hww22X8W-&)W1WJn)AE2K;SbS@r-4h=8ys_*0Q=sC21w{^W^VqeqxLG zsFMSo92aQEQJ-s4-H0G-(bfq9A&iIXHa7HCzk8RZ5l@1wQ=W?i9&@ZuxKFLI9yLzy z_1MseMTFBV_q_C#x6h`3MA-!l!bCr2W~6W>u(UO+DtV z{V=eOvcKAT+krnTIWjEvXL{NU4w1~U9=PtU1p-<%=WSb5pV zyiPlFXMtdT*T^|_n&)kBtJuhEuQfd^5Nsy$ObFA2w7L^c_YXfTZQWHwW8ZMA3g%Rt zCZt(>JNk9@A<5@skzh2p9n;Rpa(?xyQqj?ORMuLfIw082cFuo7v&|4|!>-L@(buVW zObe=4)#DOQU@6>h&YaVzOb7&S6C+%G#j@1eFdoNXJPKNc$AkBXD-(v?S<>I@%#rnq z2d{*%HyJs#*+oF^ED((5RRd%d?1LzG)-&N1NC$r}qj^qE$mcNT^&xi-HF9T8U@12K zt~$diAlTi(2PqQ-tFRQd(3wq)g}mULwouP;cBQT}vtK*l){5;wHv#qAhDJ`V=bSt@ zWcpm07rJdI5NPh|*&U~a3X5L-Fj}ZrJdAS#y&k|TFV4Pd0DaZw%vOQGeZ`)QK7=*M zDiaNXs9bLsXmK?l17`G>OtDG+Q2;P>pHV;r)^Ce*Hof)4%AS-lzuh)OWq2OCUMM2 zNZ*7Qdamwz(+?BN2?UmE+p4B=tOWetXs;*KGIsO`q2+hJF}XVe1p-TnRt>q=g8txd zH5H%LQXsGtdp4pz&{1q>2(7Slx^(489c|X$+DiJd?((!f?s}ZSZ@MsoSEj)4E@?~4 zYO|ygHotcWE;aO29i`QV1Uc<`DTridPolI|sTIW z`jBorut$n);4TnYO7zs|cV2qM%c#TX_fUdL*N=2ueK4QxP_Q@{<>Jo z+dftx@O>y&VdMJXl&A3k1Hsg=yz$2Hb6D)hK~L)u;lsK30vI?W{%# z1Y388#}Ohx@Fg`jOV%ENQm9+XI|PptaXb&dW7*qU^4eM3lJ;u`b=&JNpS$)y^P?}~ z67YHnc^$FD|J=->Z6Q|c? zcrJ@GZzo~=!c8Es6!S{F+9LdlPWM+>hf50AOP0q?q-S>BQCoEVS|D()&UA1K3CWr{ zk=8$yuMUq}EfBZ{fN7@}y$CxR>}+~v;&iz(W~hg$s&QR z5_Q}=6+u7UHeBs|zN(-DzZX|5;QrP3ZD@Gdb+yOOO#}i zp0}Y}=5{y5j|dV7ykCjC!Ec|mptqN@E{XHg)wA2`q&zBxL33WO|H5o6@tsmttDAR$8w9!~CMmbv=6J^%=Ie8#5nf zV*k#=XioB~u-jfI1Oo51jNmlfp)Z?ESEM~ReO=lv5cs{XN(3vmO)cc^Z!dw4{l{YH z!xr03y|$O7*ebj`V|{RI@@y>qacg<$dfie2f!~Xx59d0c9egD0W>raIK7-jif6o-X z7S3BMwu4pAfv~)f;H_l@ucSLOmK#7^eUA<<#dPx;xwFbS4r+OHsz$?jw`eZ91PSlJ6%0)eIQ-VXO(e;Fp7 z>Fgsd3;skP(20_u4{ot`=pd~x{(s?+uaT06b zRR1*8OW3G!0!y*aUDXeC*FYe!6wccSNrCL{9AtMR)~yu?EX8PUp|j=7p|5^Vy`x7m z0RtDC;a@4xBQjniVJ&ynGFZK2H00;k;rx#EE+?=Q`<&;A&KT|roZCgi`5h*(l<0lf zDH)tvhQX<&Kwv3Ga|{1Hi8H18%+b%)@@{N2vz!y@pqLg2{p^ktSPIc_O2#}j^U}<} zvu`-TTK=Al6>2i9ub7v<_8x*)Sdb1l$3ukPa;^hO>6y1H+eTIi1ha}uVG9Y_ej|+T zTG3j1z0jYoxay}2`>e5?d%U88cQQ6hT=f!099-U7s<22TuoT`!;Y2YfhA!QF-}HE@ zyPyN_yI3C~^?}IQc;8fUnn>XHVjAkATVm<7Bh@7`s3d*vS63PE!yq{@pp?)Kyk8MA z>*qG~M8z4>=~lG`g0+KJ4MeNT4hy9}{pl`^KNp}~Ug4)q*xFdWkY34w{UGWE@YLJB z?@mXS_|}yApqxPTFWOr9V!X}VqR&k`rV07zVKTikBFgma;dgp<(Af3um|!Ew^8`YU zEK8y#)n4k^oj(Z#lj6P|dvND$XLkVDT>v(h9#!pVhTp3R>m1K~Cjl!q>=OL@BACEZ z>~o&UIOpyS$Z^0s=s6D7!KIjmt{jKW_RHXRS3>O->%da%b8(%sHO|h^**8XfrMH9Y zz!nOzk3e84_9lMvE5vZRRa^(NijNI@c8v#X2V3K?*54tx6w|>iH2TUJ!wCeogz4a; z`L9(hP80|%g)M|%vOf5bjvRYHIy$u!J^HqxQhEO*dD`S>GM?>pVtqv(oFU)8Ocbc; z9}A~f;|@zn*NePE82gey6B6nkN9jPbG~|9Ufxz!=`KYO~=TVA$I`Rg@aD7L%qrW8{ zlIC|1b>K*kJ-gz>fpBi{_o%~C-dFDuT#B`cTj=a7Bioixzv~eI-^0-ef>pZTb&lXW z1drRtzMbt+#!NI}9asv_G0@R)C|z1QUHYfVE-7$I3xzJ|DSvtCik=m5t8gz6 z;ts#(tXMim$||={Ah1_s?cg*a2}R@SH><};2k&1H2>f1gJf?fbQS(WY)Yi8+#a3Y{ zJem+$diA4IQx>aH_g`99f73|Wy}6gIwz-4@dmN_E6LDSUPd z{~F23E;M;ZpnCX>w?JSi9A(03_?>9lyY`~c1CKle0!v{F;eJWm7@B>5k?FwWa@ygs zEtHu*&Z0rppV+aK=&64OBKW}~(~bfJmcm|}kkm6tblTNo2Nx#%Y{fe8O2zsJ84bjS z7sU=PDL~-&Vj6xKRw|ATUoJ^^YZTX(b!etsa}1YXeR186E4O0pb!N#p>ffcYv}mWB zwgF~hr`bJa_e)poIKCERYX3iDX-V2tsyRa>uoTuu$fojf)D~uvwzViO=)h9gTByDL zFNyBH)mfSwvEPcVLNi>j5bm(7kEch9j+JV5I4=-Io|KwVC-6eE!9=7bjuF?E=AU=TeO3nT*q488LMj`v&XaQlh_N9?po{1p-T9 z3n6#jZKfGF*GO8wDzy3bx=Qn#N%G-qB^2yG@a_ZE^LZw^DSfe&(b`uauoRB%2$_E` zmhSg&C6)WYO(3xE!umkRU$OM_%>mMumm-1Ri#;lwE|rd>m%a;>hL0BsEQR&Koubj9 zv}wCR(nGDTc4LE|5;wSs+^%0G2OekECVoN#zjp>=O@~3!&H@CM!Z|LSF7=P4A7+=8 z$`>mw=)iLf>w|xT4v0>fWu>SBgz#Q8rwM5{HJT=*u9U{qd@Y@bZ>+@joFuQibzes7 zL&mX$b0!)woW64!QJ+3{`Mg3a%Ghg-I8h+56q{E@v}EkHMl7n&M682L;aMrfy8?lw z#PxBpeKKA9=9MXbm1e#DJXonSw~V}H*&l+(VHWZ=PskM@y1aa4s`t4_2vS1tMy`mZ zLCq^lBa=&MSO*?KVQfeu5OT|kQvCu1mcm{eX5!#DdUE}zQq+mZQu$v4m7@>R<=}vP zVFdBW5+YZLqeo}7llCSSqnN-_;+Xqajicj2!leh3ifQ$J4O05jvGSXzx9r&OiaSnS zAcnRHmo5|_u+;QXflAEC4Ea^VyWpt@?&(S0duB+(I^DBk9asv@N+3o9ap~g>i54KR z6t)mzQLi|fF)v&?kWox~U~8n*&7CCY9DQiVIk zvGh{y|4B=to(cq(!ukkV>m5gb93L(n$|y!Bo(WR2Eo0@I7jMaUY{c#tbTE?|0^$b5_il?v(9j z#vIVYaGp8maOND|?q$cVTJ_%ddGD`z@cWsn?&;~SuIkx~Y}weWdtBeR0i6cLb@l3; zuKC8U<+I?I_OrfFU^OvguL zrW2C=qnqJbwx$NVf8qCpDo8)ho-F@vTqdV_^fH82T&oBhfAlV6=ZVcjLVC@8C+BeV zGPJ)^91+6CxdM4jCB8gYF8-O%;^7#Vr~Hm@mKBtJ!knr3_Aq8`t;$=giC$QG`$&3V zh0dDzdzRO=`1Rjaa>#e*Z4UYOWHJMNg;bc{Jw2H{Jv&A6ZTVVCJ=9f;-SNWcwX3wT zTeo;EeX{;`dH5HHdtstk>Ku z*DGB9Qnt79)vjiKFc!Zq+S7{@g*nmPj({r1%nSVaq?p2-TsYC`w{EO#odR;(Z)fBj z&#PGOOFITDU2U1Q92pQd2CXPpE_vhF}Q*0{pUoBC)<51A)1f^Ra^|F#i51~2|cOk_ogxB zOueozQ1KXpBW825vmt-=dIsh55=5A{Wj*H+m7dzstHTP&D?0niYl?n<=3<0fp1F18 zYe!yI<|8x3q;0OrduGYIf^yr2&hp9|n1CY#kA?TcN65?nT`Kpj(u+Bgtg)Lpv<$!3 z_wj0HqsOUr@@m&(vcF&ZABfb~hn4QfJrGSujnyuOvHTs(*t0{L>74Zr9zWfRkDu@T z!`lGgsETj%8gfQfGejT0FN5B-dnat~3L$iqvte1ydWK{7mmmV#!*5hZpo^g|e}dZ+ zdLjaP1!+QZo>(WBayurc`nBh?!x59UwI=w^i@)nL5g}(?pUUm#6*bHs=8p)W(%*AT zCq(q51KzsQh*m?`s%J^6+Hi7u-YLzrKc*ixgp?hovUgG1+`B#19fqFj-=)KNPaj<$ zV6JvQlQx!mFrj+Z>!IrZKa)1~&|0P0=pE{(y)CrcX|okWn6QQF`!&yBrnjYs!|_6RxL&W!~m9Fs;pY0UO{{bTXH`;(%Y zN1a@n-*87|=R{v^d8wYoB_(G|r8=X*VZUY|)9W zUXxP}{_UX*2{=>38I_PawT-Ol#QRd&IlhL8)hlTi*gNAtpK_Ss%!z1HSW957`sbDZ z8Ms{TF)m#2U6eAo)&jZ8-DrwtBZqe&zm~ zswTKzym|t@Q#%hgb_EN<4 zKhL{sB3csmcx0*Z$da#cF+m08-hn-t(LqCmQ1SRd!34V z2jdUlx5NzAHA96lgO#>KAB4D#eJ7{ADP@@Rs<+bBQ~51lqZ$wQM})Pn zEbBR>2`N1|k9>LHWIE%!rWP!8Nqt?XI$B@hx=Tn0PVD#z0ab7fCgfm?^K^g0QCiQb1+pPVdxRHL z1MZd3=Ipts-i#Qo_R18|ZSvs+^QAq@LxRSRVx-f2W6hR@(jVOKq`{RMueG@*=Qhu~ zKUs=1VFIea*yT2=*Iw|aQY<~><5NsP6|_glpf)AbUI*qke>p#jUCr~{xMa`i^g=1v zD?!`#B0V^fROLqks$NbmrZ~;!D|UAgGmL$mpMH}I)8jmPg*KoH_B0`LIProLN9_ox z!tE%OkdHcTG?_m&O14BxVty^PJXV8!g^AD6Cc3vyc3M3s2@y~Q?eV?ArVg}AvIE_E zd?+HI3dVMXy+#kBL`eHF~d{BNa94Oqe6fzseP-iUxI5gCXcY0~E?k57)y31p{hUzM&lsL4ij z%44~2@YLrjj9wtkR~$}ca$>(70aegLLS7XOXFJqY(ueMEbBKWVg|QtW26GZyMBU}?5oPI@4|TPhmj;^7?i`m6 zV@4Qp5K=xSiKR9wCeKN(gb3&frajx8ql-`FX9G{wVq!M<*uqhp{e)O%A2<{3jd9nS ze-LqE8BWaQ#2`BY&LwajBjirYimdaL3(}5G!EEKD!kU(mP1$#~ga)4ne42zjD^QGm zzI9AGxHcRSPz57dJ}2gXPm6RoA{Cq7(b5iU#G=92w{MRF>d+jHjD9oncKkEiiJi%F zP&z)TH6q}BAx%g>qX(N-_(Iz2pvH(u9sNQrvGQ2@(EL?VoA|i;?9Se>2x;x#n1H zxSA_|?uiJff*ukw(zh4$Y#k|uZ#XK8_&m?coJPm_21Q(p=U=031C*cPyCTm7*6mR) zd6)AVM8JIlj`Z_RNMaPW;1(+I9p~!EsE8f1SQ8{Bdr1%SdcPj12u4$$?7ptF}Rw)%nfkDhk{c3&NJI9m8F~ha2v= zNa;_V_Zg2oi#EZ%EZpM~a<_XT-L&zXRP*T&L_n2KbR#wFagwn@p-4Uw$KTyc|7@BW z^7L$9!<4TR)a{!Sjdh}$nBYG1&$X@9XRnITS&v(AVypKNI{xoNQtafOh=4XAO-M&; z+WTvIgzl>jrB>Zj|iv|v@zI6yLhf7CoTnhu;AtI({5L6 zYQ=1vOv$GU>k`4Mx2SJtQP_bAb7Jhck3q=^loJ z>r<7kh3BdV7eygYpocv78vC31`Pc*W0qOk%Va-`0nvihbyQe&dvO3-lvha6;W1MBb zEUtY!cFdy{@}zi;aGK z?z2=gG*Pt_*Ss!b&9H6QaZ@_g&w*_p(#~+V>Ukx?_qMuyR$UX!$q9Sb+62E-dG(%@ z;Fg=^yWbiSP_-$0?jW&^n3&x1|594eq$-K5>drCB<0ZeT#d1Yk zYF@T17tC4qUX)v&&?bgnOCE{{F|PEyD9)Frz8qtIJ@EjIb?S`>I2(v-z4Av$$q*OW zm(L8lkA<78&t5bL3KQSCr)(b#9=!E=93^zh|7Q`tib+f($3>9?4P-z z+8v)4#sf!=ARCY-C9qxL_ihHOcA0^3TKVHZ%9w~U;?VJS7Mjy;=RRe zT5;1XBJW;P9;Wlt6qbtOxJxC}N5*_A+_4fOh?yyE%^PB}Q%FFS_B3_t@@{Y7Q(tGx7g5CkS65Zl^$$Uu|VmO$7w{sycnGAc+9|hujZ61QRf;hG`MO5HgzAaQKJp41XjT_ESwnqvr&>&RZKC7JL1zq z;x9iVpbFRSenmhPuHF5LfGT)KBTN4?ub>KMBY#am70z=0$}6aX8R%czfGSwC_%#7l zaGw7)0ab8bA>@zXWHzcz5&7V)dm*1rbk$6$FN|w$7DeY7;JiY}eoiEE;_^S3fT~Re z<21Jag|SV&(i;gWv3DfPHtC>r_}hJC1FG=cUXl~7CmxhGI6XiFRN*rd%Lk zlRn7cUJCHUlC8CR%lA}$_@2|cAGG9stb0I9Rz=T1f&Cz#TP!X24QHR;o;M2{sb**G zU{6;|j}9MKO)IR0SiExC;bPtC59RGx5a`NQUP!d`l}?Cu9E>}zhK)L%4!q?pzr*`# zWmAdmI=ciBPzBm#C021_ryT)R;#&8RpGXOPMH6n_PD?1$iN!y=rw+sxCOy=Z+qO;9DSb()ZdJWjlSvJ~xoH(dtN ztEI-Gw+VX%B1;QljaV&&UOf?avPQN1{RrbWM(|kl06F~wp|@7p(CIAV2=}V5)hpeG zy@xuDVrpaqdV*&-5Vs=&s-Qhy%~-oPtxQ6sHW8LG7a!ZHD1ga zk*;}kM(5V}j-^DP`AP8&QjU8g5dlten7}ClJ~KpZ+(_U49Vs=f*xwLTv7!3vc3I=x z`H?1=d&l|qzWcn`oa!0o^ab?|9fuLEe5(qoR~dg3%yNroE_zp-{URjzsTW&u_q5rk zD<+^yT^ZrOrMIV;8zp%%$7NxL z-s>V1&+fijfu3F{(=7JR`uxbxq(+>l)gq440)<)_F15-~dnFH0-AN5ghF%}Xcowbl z?E_uDL!vb!+93kA9QFtyr{6rGPnz;wSG8Ef@c!4;KKHw(dp4_$`YPz%4z=pR#_F4? z2HuWryT4M0^=s2sWbcRxkgW&v6(?k$ysT)h&SpdJ)`);A=piA?hU}-0qU)u3RqJb5 zUUq`IvXK4)Ap$ul{VwmcAIUf-+-BA^P^69^g8;4FPzHr_leEglh2Rp;NS zs&V+MbgweuydD2en@MSeH&u%bKm=5Q91tg7g!iPwJzQzNjzbUuRUlu&iH+y?)6z-J z=)=D8hV7oS)ynsCsc|bCncy>kG$D`USJ1HYm8eTlKSV$k^pKzNI&+J5>hQ^YD5?u0 z;PZ#}`1^790#!yXGhYwwjtF>P*l&bLo37CdM^2lw7l=ayR6%=uF7ba7JfLJIosrVR z@bBrh%GXUPYTTAc6RhdrH!32+PkQ(A9L+s59uZK5^P-;RoaM$lchh}~dm{p?zGuJq z^Y~lIEk|vRq({mmTE5`1X3~&XB5PzjnJK<}@y`141rb8q0;LH;_rGzfRIME3Kk+n?^-J{$Q~i3 zY}F-1!23d)pAoit^`}N<;E4h}v|Q_zEkZyw!xC9qeMc%m+h);T+=jJc@&lo(gl#=W zHh~JT@W_fN{r^+%>Vmg?24~5`7^Nm-FoW&zie3BVIizG(h1R$+~tcCOEBMZ4GgE& zo>5*rcGV_VsbI3NtJ=nK&EUP~I0+iQRo(%do`zvEuf7NiBA} z7itG=A3rbZ<1XjxQ-js`Ux1;y-xX!`jq;k$9XHEZ(q{&2WBP^%QplAc*63U{L_ihv zkdOyzVR@cQSGIr270U?-?;?tJ(ks&tD&j z);hP?ZBOMnpVvJ1BlecBV)m#F`!uv1Y*=@x+^d-A60F&kIp!&a8vQ`%Dx8y9eDf_WFgJh>{WlsBPz9^Y zgoNBE#jfRCNKJp#VmG#YQP;$DQfn_PZ}CcR2kZqx7Uf8xJvnQtpZfs1gyG?c{(U!k;D6CUyi=L3@Nu z*^@!XEMj!#n^tVi8dY5^#i??UI_T6r{vIbKF`b@2yMdNW?SKe)UuchzcV8)uJieQr zN{B`TREcZb>75C8-qMO21L)ePn1JIL+9M=7^%H%4s1fz{ZHsI`-yu!NjI&jxo~8}d zV?uuxR%W^qwqTw*@L3xTo^8OV6F!}*DkXEm#g2d~{6*E0^oC}`$K$lx_MXTFREbfk z$G$vUt2Q(j<3xxZ0aegLKEpjo3^}>&n|Z~%WTs`-Py(}+QSYsd)!61! zbVN-$ZTWCSKoz#}s%8iC(vQQbA03Jas1hF9&SkjzjWieiw+|gMA`uZ#1wG{X-P*2l zYJr<{%cah&W#Q9G=@qxsR$J<6@cTHhw)6RF+O)lrG4>5TKQ;yta0h|uMtn8cUu`5k zv}UbkHF!Q@o?7P5sh0IaUk&gqDu_dzIQSDnKb?SA0}H{`lvCnfx(#uyuZe=tX&z

)L*S@t!@LVpuMbYt@T>~Dy&;iU0Yf%<}3b%!cR_F zSid(wgnhQwdY+oEgSGwpvwr=v%ZpN$Awt;GRq*@-&n>m-#TLi4kX{@(f(WP*wC*7x zt9d0ZC$Gf$_Bd%CnX{{wci{`8dfO)*R{LO8j*yj{$i<1Rb_7)6nqFOAyYpXhKc&1wuMi>TT0Q3=u5CMde@?XFLYUb!qNU}q9X1=FqWA-$tHkrSM$6m=sB=oR;j9(6KR@vSzXEit@4#g1g*#FkVZBndmH+F0l~czarb(UKP$lU1 zF_K!V?O|gUAx`M=bt+B#%U>_sSVp2fp+EnuGj}Q0D%i~0FM zU_BiY&>m_BBA`mpw)I>@03u!x5rDl7T?Iy{nl;*c-A$)r-w6q*64(0Ml|}GcEj{%U zLRY~y@h?Dg>@v@+y-eCJjWmdP(7H=8!MZB0j2>Tb*4%gTO6jk&$%ud|_~jF?-OcSn zXEuuo**z->5wNZbYi#_yXj~6EJoB(QyJI3EpbA##2#I|XMX%qw8RG3W3=z;1_-z*7 zfAsG}uX*eYdAuHb1y#^PzDr#fOUrb3pb0C6A{)>X5XthHp>Cld8n-+f_W{_ge8l(JXq@SXkS3((=>9ae_YobA(5UTEA?TsO^ zktW!qu&4Q#NdAfR>8VUf{Wt^>P=&vVJMd{0t(AA7H0^1BM7&hGsB6p2G9KF29NFVF zVgGIPNQI+PNkc!wro^G@(~wEVo_U&~Uoe9eenP62+DIdgcb4AQ=#L1ff^Fi}B?k|- zCt*8%JiL~nM9?Qyxf`$Mx>z2a{ebg4KY`sc(7bV37ZzIop*(4Okg`46s5L)GEH!$) z1|@bcwlAs*{#BK>coE8O_bO({>G;VwN~x`Rj&ZUOdUZ*R5}oF|J9WA=sh|s+-?o{d z_{9xM;TIlS_T7Fam=Od!BtCY%OXiZIz1`TYK}`_>Rq%T}LiWACB28LVmHCEMLj=rU zLVG+~lB<}PZ|2_=J!@k4GNhgIXg9wGOI)IV;fU+!<=>{$%O&?v*B9*&0Z(<{NM?(3IxVt- z=VYX4L_n3e*6k5eYS9Z?xT6pK=VJ#%Ku_=~i}XtG>4On<=&fwn22?>0`T9{TpIkCv zJ{{^jz;JW^Qf2s!6{=50D-*2OiyVNhj&t;M9(hT~WEygJAR?d&R`~gRwS0w?D|#!f zait$3pbFdj%^}KM&~Gwz`#RXL%)O;hyZm1MDzW*?R!otDh<{zKzUU3y&hq?wtfN1YenFj(H{t11wBMxfFc5`puI&7 z#pL{}1KICQs~h6W-&aZ(Dy_ZVSi%HrEW$&*LPN+3PCQ!`$ky5sPz5VOgq*sOLq0tv zfMv9)iEKa>t`&K6;vOf`?FgvC9?HJ%a`OiDS%D2D4Xt{fRCcuw&<@utY=Sc!^pJmL zy53E8n=Z3k+kFuMRdAl?Yi%_qJ$+PznMYMY1XRJ5h>#Hxe@F#e)MPz_FacF~-rb=t zlib(TW>3onARADH+f*!H5xM-j*34^mPJ`3s<;o(*V6CH1F3Z>C`ud71TZVzf%yLK-5CK(iE#dVK9%U36v7Kg1 zs>R}B-mA;<^;1`c`&mx>>Sw{l-cYZe@ZJqB&SL%6(^iKu0adW}!hhG`cqw+~a|znM zP(8N)4$(Gd)KoVVu7GMqID1~H*;mS{G^4MaqYwdAF!xS~&x2*ONX-*cyIcd<%IHY- zT%GAg|2!=;SZ~2KmUi#gQ2+7Mq(VFTvyaU~)r8D2qcS2=gLM^Hq2b?Jwpl}G-I*)R z+J_0Kg7ygcvrR9$bygQ?t2q(bfHfUxkB~NggJ`FXe@oda3}s8FO--K>|J?ZaXj}B_ zl#nK5z$!o5_1g>S_L^aAcJ=41db6Fz;63d%sKPC8zrvmNoBdvTP3hv7vtDkOXoIP zaN-&#-qgSZRKf2f3AsG!xb*IU6H5zdjch;_h%&j2Yn(X3iOY5bRACQA_S~8ax8!}S zxp2$rXqW@C<$XZD-EzuXCt!v}?6&pO*!-*--_fglN6%{q$OhQ=TQVWGTn4BD{6Od` zu)F6OFF{yq6NrGG2zz?AC5y1uCJ+Ht&_k5Dv*h8dnF6D*@sqqC_ez{r=O@)gX2N0v z5_<0n8+x0vY>4kBR$oX&gy>zEjns2;S(!V2s-N-t_78-v!hI!9l3TMlmfVsx*JFg9 z!2Ar#Erke`PC%9TyPk8(%CPj|EzjUBhlKD%?*(WNWut!ZO204c=`0)kj6UUO^$`J8 z&>pW;FL0or>$%W(zQYYSa+Fg}Of980ejRIq83Y(*5;87ds`Gt&P{z)}Po98EwLIhMn5Bd3^Lo4X&HtQsBzX68Wu~F&= zHq%&qUW5r|5O5BlY3xc``RHn?qbnw04gk_T_nKn`4R+onT@S_tyl=X1gnA`vs?k*z zzoZksU@1K_;e=F0!UR;oFEt6N|9l0FN*x4Vo1FE2he5O9XoYuLpNgAgNFm#&M zSZ%xRH=}223lp>fJtU-a;2iqg^OV$R+dxD>6|~2H2_bwD?Hzwo`lMnTPzCMr8GPe9 zT5;$xX%I~?G`-bR_41o;JmuWn1bv4zk1{r|qZ@`ClfIfU0aY;b!ZThg*U;W{m)-qhK{Y`y)tDQP$MphO_SAoch&xykJcXaJRIfc=BiCr*<{8mr8yU%y@u3Cw~V|l`Bsd{MCRpP4z?sRKZLbpGz99O&ixO zjGfq691&0jvu*rr)Q~=D)wefddzY0!1XMu}`CO9Sy#E8=JI}sZ%J3wjhjJ~%sGY5m z%>;8mc0`W0Y3VZ>u_H%IAOfnOJwke1Eu5B`*`CFZ%7zH25^<2ed*Q!d(mK%mIjIZt zJNJ+-s!>tt=3~@$ekB@EShEt%ih+-&ZbKa{C4)wS*E`FP~@eP3hQ zZQIU3hx&d<>-(Pn^4HZSEEl)_q(MpT^MG<1Jn;>qGyeTYfe&c|IMLsZfU59}MM}dD z#kJv+%X8a{+h&*IbGWgQQ<}18UsfvvmwIY>qy03ff;9g{pfT&ExMM}x#(K>V0af@H zHoW%jm8QnlWY@}8K}5%^rG5 z1o!8l-}ubXw6%wv?YciJaiBILpz288$4YEo5AE=+GJLexcX5$3s#avde_{fv@EO>b z?VRQ0s{Dj$PE0@*_Rw*nr+nd7dFInA#L#l^9mO==P1}629Jl`cnJbXy)$j%`a=33r z7S7uN38;b|@?XcFG(BVst;>czDPxc}Pg5?WOIp8x94Ide-xVGw-k%!0G`#_fj`BtX zRKYim|3;&CG3i>fHq6&I44Q>rtNDuvHCDdc zg7?+_^~>qdSDU5l^|1}8g7*0LYVB6gJD)a4|EoHH1%D1z7tM_~hBb&pUO}3Fy*z9M zJv?@UG%^4aaNmz@IBi);UBgyNb)7K*a}JQ^aiY^O8a?}*6nJ(B@(Q*b<_36mXO{X0>Jn2$6#KxKh>+Qp9M~bpu5`h(mWY5V z9Qzc#?ZCdQkEbUpV*;vh3^yP(AN@0_DXS1v#4yv@K{@w(ur_W^P7{nWM4N1txNfy> znvaZ(WSK+rBLb?xyjERJkI z73>86TeR%b4ZK=aS!&=9@PJRc4b`)jJ8X^htjP7 zw;Oi48;qyf3sz$imwXLlVZcVKqNHvD>*@DW_K$ zwPx!GY6n=Oc&wG;cqZ-U#~3zf!8-~GsDiN_|G)N3TT{n7E|eXb>V<5;HsN+mA|CSi z(ydtY;kg;eW~=rQpe^bHUyN8PCf4siP;3Z2B;-ENx8K~?ntkh^6WM?&Z10JOyWDqf zeOA6fNtV(0pyKZmq{U|z)L=vgVia!s-A#A-%8bS=z|92_P=#&mEVop8lwO;aEy(LE zzy^#gu{~prM9Jq+FzeF15+Y#i3u*p~avz6C^=^?snHGTboN#(x=LPlW#4S&r5d8Ot>&mf8?dJdapJ^TPIRy%pbC$YPpgVbC*CNm zalqS7%=c-aw91wAB0*_TW1>=?j~?ybqX`aM>vjwq>J*yp9S?QmZy z6joZhFsKCjT|M4cRrAaJmRDjcj@Cj1jPBtt|M8eQxR@MwI)I&ZuYm|SN}xS{-lwX& zJU6mBbKV%p4lcZ+eBM}In_bu)c?D_yt3x~82xZ~IwEc-uI z5CK(i@59eJ*SjnIPYPn6$5clIRKZ>#WK_;al3Fl`t(=DmsKPCu)WuC6uKKee$2x{l zJs&8ICcA6*C;FOT)Q=)Cu{YdqYJswnGb5>#k^pyhb@w&nN zl#pQq>N10|tRap^^cgQhw15JRCRoSARkEZjDIv=^;bKQX72KEbFYo_YB?Wo3W@E49 zK{lWYyeoWncYOaU$)6J=?FguX9`aK!#j~?Ifj#Mz=aH;L&`b64lA&trr4=+-$HS3+ z*IfnKvS~Z$srE)hz+DQY`Cctsc2@a9585qPOGD_mH>$E}pxWVzp9w}zIFcEk=*lWg z+fKK%3q}M~0ed_yF&1@VFYcw%Rp;v=0;-@rzQfL5HZ4~eYgnNKvH?{%W*9bWcG|zi!&tHWn1CwSCVrBm z*-Z0?uhGnBZ8mnWri*eTMb`RlbI>3m+GNWuT}otTdWF9q9!`jWs>zW~%6(r+n?ETB zkH{KGkIeVhwqTb>6=1oJ5T%`Gu;$^FOM@y%^DiwXpGlj>03{?D-usDiyf$n!e~)AAJxXORam0aegLLUtc@V68gF zQ}=o;*@D%N)UO_VkF%K^xFR{@QQl#<}#R4K~|9@ug%s)5Ta8CD}HJ9E0oB#cq zb#%dq_N67|CDSJSuB5nq(eK-jESdhB5fh5o|M@xvxNhC2C2Aio@Vj3~=Q%l3s>;6a zQuXoPr`?GY4+M-ARxy^JkDt$Ndl|lCjBU)%@n@cE<$s^K%VDg%%6qaAzGD&#eB3(c59ICT+J zTZ%?ofmBXZDqD7n20d1#Lf~nrla0pD{`BjSe&3H;bL9gOamu3NnMNgJDoQ*OCBi;5 zG7ya?OB>?f(7K9yJr*^VMtTt?K8Y*EgHnmOLJ1Wwh^u-LNP%yn6ChNScqB?hRz)QY z(Tu&`vW++5aEV{Iey_7(?@5uV%QLUer}jZ~n9Y(05dZ0hBRuNmdXe*^h4CDtr1P@WW7<;hi5^qr3;k@G; zjd`~l&w)Q?#Lmnq6O|K@SVL^I(wq~`W2m{(Lm-d`SRuAMbJ!Zjl;)ghE)Y}_8(lJH ziPx;yBoUFQB!utrwe!uMyhZB)7GmQKA8547O|(LlL9~n@ zC>7<$7|~o*QScz@0p}ZSi5~Dd(cD7VRN5aP6(Z117%6xzS{5UP*h*-QegW;_bCe2w zfze12$iq<4jx!kQ?mJL-^8v|NP4bcMe-4HP?cppPOYlsqDAX%{5A=>S(G6^b%83a2 zTc%tqPqCLDO2^No`1X9tt6yq7I9Ao<~T*;ek%kpY#M**THIcZ1Zpv~H@@J$9tfUkby*&r?~ z%H>^$&P{v+e{DofQUF-b2pT_ClO-T@WC$wdbD>lCEKjKqftrU@$_f~}a1zdLft>n8 zcUE&Ed}Him+f7YmI9XZ3dyfj(NXXfQ5N|T4{Af(I~y96z&C{#Dm zr_gIk637i&YqcIA^%dKTdAFv%v+uS)it4k!<6*Z&(;fn0sv1S#`%DQ>oAx(n-K%jM zVO2F+6Nh&!;`ar#bGnj=elT-1^vEqR}P(=&)AUZ_whHTA90S2 z+nlfvKt&}q{o~n#6ZyM~YMtf7@2rE+=UV8|S^0d#e>(BO>_;%Y8mW#KZ2|42H!TU- zkXIajbaocMYh;?}IQ8fe*l5+Gys$@M55zZ~t0xX=w?OtN>^Rspp?msBWe~z^7>(dH zf)0DFPkOE9fgM!#SBl1pfYkxJ0iK0BX4aYJk;wvUNjPy}cjkb2yADEl5P7&N-qeJn zeC`pSOCHkCf%G#)e+LzMapU%W?$s{~sV=^fQMG1F5IL73-hpoLWpIN(_Ry(12(%Ms zt}RugXLI@JK~4RIHyw!}w50_45TUWPhU*;w=FxO{fyl}og3a1seEMcdg+6a z{`di{>mXDtLDteJNrj+Pc8sab3-=uGx!$&gB%xIJdAND&%?o!a3xQO0H!x_%;t=KG z%kV%1Zh7IJ5TcPXHNr@uPjVYZg!_lhuOS{N5$=aXC&>AR5OkX~{2D?iZQ)#Pg-h_j z$pujgffEiqH^f6(SMV?sazhA1r8neDNQHA2@=>-@5;nxc++PR}Ds)2##Y6bRpc_Ic ze+bQ$-7cYrq0&+TKeb0C$R3p>n^%A}3%i}!sno9KkzGw9tU5@0t=c~vvVXYY{(%!8 zWD>|ur*O4@ma~ho#!XtS`fWZ5MMpo#*u?EN7PK8>X(QA8lS6;SUu*JKf+8qCTdGg<()>xqW4O1dtHpy#MbV6XOd6&7o7F4_2)n7dOm`nRKn*NF<_aJyni{#YX$D- zNubI>q%%elR1e!CNLe3(ZjCm-R0tXw6fNoN<3VGLq8mVv8)%A7jiB1vK2N0wrJ}jQ z*xVDvJl3w-D{nqlY{KBFKzgbsY4!v?S%L@uv7(gsTQT3eb>J!+Vbu>(SJ+KUi+M)J zP2R*C7TO4i5;fz(xs+dG?h@x{S&_eoZT4oZ*a=aBzqlrSdu}s317mwCPdmGojrX4) zm2Dv~mdq4JH?PCjo_4C+PVh?#UrJCOvdhT*%$|L>%vk8PS^R+i^D^!Y?sY~>rK$nm zA=6)F;QRM(EcYI*DEIIFYEB(QC>5Q98RNC3{Afw5ii^!YfyokIxw>=0ji>Irrq?=v zc)alOj^9QRU{Os4zA^Wu&D%}n1vg*jRJ^`VbOYQmu}+~6XiqeK@V@@VeCYZ@=hM0G z*$C-#)h%ha!<`fNP1rj{kD@$iPc(h-A|Ni`G|DOcYmW$m-V_oE8FsZP3+6asSA$r> zyKoUpnujGJgUC{Sdk7%wCLJx6sWcOfY zU5{8-^8iU?r?#?7dC(&sln9H8-d|y@+JB@+uc;^2uE(e<$~c0xJy5%$yqN;DzR>}i zIG=v%y-sBduj>#+P%7Oe!ph*>f|UVYC;KdNXXb7d{?L}T{DHNk?~3`(kSGGEOwSNi zLV5P8r5Byeo%-`pW#@p0?v^g?40iwcZ)GkYw!b@1+&0caknZf#UIH`2sy2Mcw7$IW zyiFE@QrY}eAM{8c48qPyD=JRP@nM(3`l7I=qhruz3b@9d;E z!J97m3s&^E33ZnN|9?ZHM;3TLw0+Qj*BP0h2wJab9YdetOYWT%L4Ql5{3LyS2zrA+ z(Ww!%)>3q81g+W>of<*=2SukwQ2W@GT4L(jic(R2NFV1%*b9|+&1kg||8-z;MsVNS z&qNNwZ)x(L5`1pzJR&~ol2tKiz`WH_1f|klLhxuYc2UQ)Zqq`9D|jH>?j`whhf`AZ zB2r0<fa&v-!18^>at`bJ@3JSTQl9Xr7x4#wp|GcGXT9P8k#d=Nc+HS*rU)+;eP% zyz5c3A>k)BFWjNXou!h>R0+E>sC!Y-r!1*t4&vMnI#D#*s<`^;-gEDcy^8jHbpBQs zs$A$n`D-ZXWNy+CasQ*gyngC)rz@feN~P;D5XJc&pH8{{=!%1#5b@2q1o8k$?1|ji z4G~AD$9whrets_tVOf{fV?_M(T&z>(@b^3A_MTM%k?5|>IV5=Kstsr}0U%<}J>|U) zZl9WMAt)6*>pdC-5&ffr^bf3Xfzm_QN9ZN0!XW~BR3+(A5&`FGDtHFFsoPIPtUgq< z@spY@n9f) z4sh_Ame7_8qU2Q)B@#hphi9GhaFXy~CGj94LVswTY&{@KR+A`^h={h(ou#D(kGF?B zdHuRE&x^{i?#JugldrE6njTLn5l+z!Ai};Y*sJ}jK^{>cgy?2ITfSI$ygd)B7-b6s@y$`)NDT06%Q9%Uh?d%L&#X%84 zM6qB21w;f95ta5|D<@}oBmcE^QxTZUYDne$Z)IRE+gASv z0(05^_&*SsYg>=;oo@e;_ay zX~Z+?zxPL~R!%M&>DzkTF8@Dj#g*qiPt9e~X4bOE$Uknkr1g`uOw-CsvomLi+lFh; za(6tsELi#6uEgO7pHoS(tAn53`@KGY3y~%6Y2Ez$W8Q?qs}c}#D`{yEQ|^F4AXcxqwwFVWtp6O9R>NPP>8GoPFM4wRZAU9R#z>1Ts$j`k!51rXtB6*G3boT` z>gADL1`a-qxhjnv8T1-o&E#?sIg3=+LmJkV2S4uTSos3A%c;`9p_{Zg&_ z$(^?!I9l-t;a=pL4|z0w;BTI5wJLn_9sf#>5i-rE1rB4b?o;+3sgilA$>k!tttssP z*=ULk6?-X!HZjOIIyv^(YJ=F-Yt50<)mPXuPLF9F`en;>x%|XChY<1cQ^OD69vDF& zT8QS$ius>>HCcA+y(fgSP(zd?#LA9I-uI`+%R|%JALLOOt?d^V_9wQf5UI!2?Xii6 z!bxdpCqBSRP6eVpMWJ z*(}c`uVndeLzu#?%=+`Vy7K7))qT}fGlPYgyP>yyvEEjU4b-wqo z9wwKqhsot4xUF8U_m_W%+RC;`z;bO{1uWOr+?MfJypnH(%j(?^``jRGpBn_Cg%}y> zLB9g^Aj-meVA(?0QKEU2V2T|jraU`(OnGG6cNCGMo@u5tJsi6xmmRw%my59TLzkxc zVdsHC*!f`)cC_0vdeJ<;bb7qL{BWKdgq`Om7osDxwqUmYdJ@fAl!f)cvW2jgK_4N@ zfGOw=Sc_q`nnf1w>Xzwx1z9-EWi6b^OpGH<3y@OU9 zOu>3kOS4yNB&DuuI+0d2OyL~--#qf|YG=#fwRUjBx_TR}wU}a8OOp#F2~mL7^Dpb= z(On;|=SHqw&kX`4k=?ERv|jc7F@Nkszr@U1>z9~$XFUL`)wPJ1;U|!nfhkxI?n!P5 zu2ZTf<9|q=jFSSMjP-DmBeul)SN?-{az=e0lVUw2qm?5`ymNcHX4}_v?99Vtuc+4i zZ;SE5_>1MbWw1xql4?GYYL0TT=586*Thi^Qb+P8yy4VUrSl>q%q;ZA4hU3cZLFp#7zcD}JFG1n)# zNVC}|8_K+C#(Rt?IN(Kf=6GhsDVVEWxjibj+F64pua6MfEdq0487|^Zw_5T-Y>F59 zR~e5z|F*jEResVUC9&L`7u1U%w>IBosR{8DAv{80O1d6P)$&S>jfSYL5LLJD@%GfH zD`N?9Xj+`QUt^`o^+KAaDyR3dk()C|LG}E!ZMKX@39*|H@r1yXJAeF^xMA}v291(< zT($D%?|4FTTYdd^I@O@^P9tk|rGbf$esaisH+sBX;=)l|4Vt`+3gtqR)3%az2$8sK zaq^nF+e`}Ps(GpJjTdf|cSS~chA}|-0;Uc!2|2y3Fr{@1rM(p3~lAk>iHge^K zX-CF&J!s2FCPW)Ta6K?(+{JB29{>4uqakW5#Ai<|^Q#O`G-ceH<{xQ%eV>uFuxq)X z_G-2SDT$5WFBF{FzuwloY~8Q?LpiERNo5r2S3U?-B-dN(1_hnu8iT0NsY5Wi`~r)3 zx6W7oc|z1C1j@oPP?8Y!B4y~fhh+qyNx|@wJH#qgQg73g=M&izsNFNj7{;m2dxD#WmwB#zOBWuW&A`4RXfG!{=i((2; z=j&>6xd^t2_r!P~?3Iyg?Ug}T3wMOan-H@IktfY~QwFA3`*?&$B5Er{Te8%ve%~DC zwz8Jf%6e$ESB_#^B}BwhPp&gS4uA7NDBSRZhbd@-8yw!KhP^o>vGm)Dkk5bLO@_NH z@HP?xbD`x-xU*9InC`ws?0vS09QOLR-abNLF0{Lem1e8lcjHu~j6bt~=(YT#rQAjc zw3cW^2k-eVF)-k>5dvo|<T@k3`yP1&#Lo zT^9I<2!Xk94%+!)5z}c#je7Gyn8z;W!r4_kGy4ugM9P@cZj8+K?$OZdXP0}Jg7a?S z{nhHzwc`?H;R%HNw(StvI?GD$1wvphoOe0*FIGzz->``82Rg}nJ+65#69RMLyqnl_ zvRd*-RTU|tQ>(LH`6)f*0z%kURID$~yDtuYmUwdQGK;8Dcbr$$A1YrY1m?ndcO$88 z;`JWSSwze9PlN_E94ntC1m?ndceUDtsqZe_Xp;}d1vck5!0#Wk0y`OtQF?Md1u?oB3e-E_G>s+bAMni zoOiZAETR_mU~zw_UQ7tgh4aq#xka?6QBr0~4^t1!h4b$8gA(eUn=>q;2aUuBJ+ArO zR(AB6wz8wr%pyB>k3`z)yU1wwd46CnoOgD9ScIKX;WdQ7TsXV#6<=rOV5E$1F`&}Wr>=`95v{>sE8+|c^xp3a$u9)J9g!qCG=?Q_kFgEQX>JRQE zm;LmocagM01kP04Qw#BN_V2w@eFn&eREBML#Wlp4iaTT>zREJ)`?LNy`5l#kvlDm4 zxQ`a%1w#Boh?Z0areGN;Nr+9QTZLk>Pm?7Hfhjn*apx^WYeLi{L={3{E*mF%^^f4 zLSTw5&!AmOVm&h>~`WFr^j#xCM}>cP)POxE1zh(N1` z@i|^V&A8IvQW?=Ce;@)aCq@nFbcrm((x3kHGg2AW8kp8a%ZV{SiXoHr$=q_Sf0Wt^ zttH0&FjAOm;e57mn1W@XBq6qv6@BIVkHg%9n1UA7i7kqoUOJh#es-BBp@QsoX{P#R z&jPZ_DT!4N%v4?GEKv2UA4@z%-&bZYP`j!fqg_$|d&PB`?&;*#Mfsz!` zb%Tk){d0@e?$aj|(;pchG|93=U0d}jY4uE#-1^q#vU11);UESznh|8Ywb0Zl!|J4< z`t5}(f9{V6QT||I{eDnGHoX0Thq;y=ogEarJkKC{oShkbG;D!7TZn7E_d!nm>&S}o zVuO1grl4GuB*dMBbh`PnN9BqJMJ49KdSHtP@kakNdSTB(vgh?;5^IQU8cj}lq*u9}VH%98ImTD|>Pv*4|Y zlU2hLN>$ZOf=NY&t8PbnlUBE$udH=)RrycT4R*Dv_gQ7VYjZu>qWHy7$v%UE z3sas@yw+mmwp*UQ!I~~D)Z_6psf?+utLjJE*OlMIU5K7XDLz*j^+WfdSf$qL@Xh(k zMLbq0Ru69zBTs#Q#6g^|+&PHZ(oS7jyTm~Y(Jw=7{m_6{3ZB?AvO3LQHKrzG49n*QJ3e?SmCp zJF4>ysUB3|02DIh?eVH2b*KNt3}BR6r$<0uT~Y^uz5YX_vMQr%vC(LU9fFm zXLYX5l7Ar{-Cjjs*;H2+JNa7(b79ThGW;*9>V)fY^8MWzJ!}&kB`%_T={UV*`vq_N z?JRQ9zQw`vCe2lujJeg{Q&t48WazGR_*!D&4^{-PO=_>sZ2p@p!^A~pb+t}^cE)F{mK+__uU)P)qI!A#d8KRK@$X&4Z)#Og;$|BaZ2Ud3V5U_;%b~5*%j<6w z;?2Aj^`mh&y`}r}N=(U}>DeGYM+^0I&$J557NT=ZdA+F7uimS1g(Q}aWw?mhD@*9F z4`r5Z?mZ$=cWec+>j7D7YugXkuBPvFO)u*`pU!Ek{gvhi$GUb_oyjt|h=J+K=!ri) z@RmN7Ph!f750?fbTl7^=Ub&u#Webt>S}DD4avGWSpS%tt`^m*Y$1a0Z+HO}95iP`D zPgT{8bvpS}qYM%?!Fq&y%nzEp-c0q$R+KEmx>IfS$i5f6-`XGW7T=j1e7~)UO4z5= zk&2UpHbt7Lr^#NCZ4Agp8v7{3@(Bg>uEurckjD>rn1XUqk`V7yucf=K$VKt?Zydyp zTyuh6No`cNvc(mmg_u63ix$0;y$SJwhnm#wJvn&rLK9W$bOTlYrbfuzqFxx zbgI!*UtjdOclE?&2Z5R(T8LqD`{<9VJm<|wA9yHhd$!@h$mAw!@-MxeRuCd@)sU{# zy|_G|ewtVJ{lP(*3yoBAjdjub`Q-~u$9kB8WuPP> zHlNO~pWX9>JpOb)M=Q*QXzKGVZS>BB-17Y0>(NtvW83lU?#v_8gGs*?BaN6*x4&gO zeKb=}`Phk!9_E@+Vq7pbrHb<3S*%>drp_&Ot+NH>gqMywmik_%VZld*>Z!UZ^A)1W zCU$S5OJ>L|Jukh7DOes_A|a|CYpIi~6p#()9COO(HEeJ&sijh5i_B739@Tt`)Y)Gu zCEqL%=V2erdv9>?{@0CEFIp23EkwINdg%;hZh0+}&xbGtH9<*2gnk&J(>!;~+xq6f z(4vjAf*%U!F|9c0rDeez^>>qfTB`8OQ;1fC*uUnO_sEukA0(05#7tKn!kC$VA! zY1QlFmi~`abChfAbcD-5_Jt5$q^T*$aUjt1=}EaDA9U<#IDTir+^n|Q02 z?p^YhpMiSN_LSLw*d8=YmqZ#d@3vGy1sX9z-00Rur_YdEH*J{S!(4VG8pNP7(>}=A$9ZW#>e|a}et%L^qmIQ>qluPtH9S!d%!sF5)>_ zqbB_Lz)zty%C1ELulh|tS{h7h);HKhYm{BPg2*1{r!mEKgCW^;t}QvEYm`Yz_%xmzZQx}#Pu;!tco{YTyJ{Xb+TM=LA?B?&Pp;`{jQ z`(O>R9&Q;II+O19M>?l)>a3Gmec_kB@K$u?40zRl`Pa!o!rM)P_B)h9NkW{> z8q)bMq|?`uzxC`I9`G7&y#XT^%M+r~(h551m0Y^f^*bJ>pzbJ%PO7Qqb*Sb8spgmq zYwjX4e%?Y49h*Z}|7BQobq;uS-uC9uVEy*S!CQKevTJYyvOu&0XAqr7Fro`0N6KOw)DOd(d65{;CX8N_pkLU}Xr$&7S)4KPQpA4FmZXSFP zHzB$cwrv$3*=_6QwA-d#BJZkA3TlNTMu=&&+s@U#uIAk~BJ6HE;N3Q&iJd^Z?GbHa z^ry7j#$0y49Pn=2Mf9QF_T9NP^^dgM#$0y49Pn=2MeuI>(H1efFzvQ67q**=u#pMP zkqJCq!ZBte7C|JI;nQxrcee(5>BHT&X{~$$*P!^tAW7$IV`7Wn^@JdC! zGxNP@jEq+LltdfL3OJHR(ZPVCgFz%Zn0PV$h$U|by)0uPJ>+chXspl3wehlmBZ4SNi0Tx- z+A}^uw|E%8GAHgfeid;1%0?jVdd^YKvfa~Zj&foO)&tv(EHyu;rTzk9Cga*UPlXZJyKKfR39Y?F(cc3 zZ`Px<-d@fxQ7-0sJnI|;-ZS;yMc}GDvIx#-V~zT z)CXxMX7OWBdh=ZnQAnRzHPOR@u*Z3-!-F>{QdVc%lYqA*B!q5+rtzr&qlnh zR()Ehms3wy*2CV-$kEzVS*R7Fg$Szs>K!d!S?~QQuTu}|!BpL`MTB^Ec@}wYYMgF2 zpV%V6jlkCBSOBl->`Mr7Zf_$pjbF#FY@M?YSmCxxR>zd=PZ0mV7IP!OE)$5~ffy&4c`(5pd$a6QF>LaI?gfIo! z*eHq4?zZNUFZFApAOB>6hnmoerg&xJRgKmyv$91zfVg=@N1^Xo~;-yT9a>t%BI?wbULzoNE$Xpkq;A~G`NGYe2ucz}ch2yU5kFY0$ zl4$IHks!~UE3b=<%IhFF;>?}~doqZov!XP$IAX4i@nU7U!nO3_{8K}i3+v$`Hq}ays}B~{oe#Jy3p^|2vk&$HB0fXQ zX^mu>vIX_u=SF#$i=*@GH?Ys(BIwGcsSEt}jl<+1t6)}sv#+63A71MtKEo%c zm3;k9c718ib_c;HGVC|7&)}d%)&13EgZ_DSjtLh$K0%7gLiQH2NQ6kUrJ9`GK9|nc z{TC0}n0)faYdZT3e45C9L&RsOe8048+c~3tt9wp~2=WmWujA||AXLwovqctxUYoujyXMl_E0xsk=^sO+1thJ237zDdL{IexpE?6EPI z{OZup9;VoSHfOZ1R(boClt-?mlgnr4m6!{)auN4$7nO~2-t#seDI!r{Y%3SB?A>az zTF1Py>qKHr0wWgNidJT`dPY{~VjsuK%)N5TyV=ii3?Mbd&LYKg5G4sQxloK86aTa~(|hD2sOT9j*>V*< zeMK}y&&i6uRhc;98&j>Q;xl1d{S|uw>;c%7Q$;+0v60nTCe!MSDah->b`xUv*aRtK zE67?RzlR9a5Ye;_KBzBWe!GmkKkZTo^~GF>rkZz5kOj(CkdxOI^02npJ}8OUZE0)C zO;5(kcc+ZxeQjzhVt?2*%Ji%d*7uR@`&b{xw3YQdSKPx~ z^ZxgvE`^2bcY1)cbW)(d@cM-MsXObV!s3(sV{MISM`t8Ot&}yn4@-k|W7v8>H zBYCOtI}UnFsB$gW7XrCky7eeAx*SZcfX zF*aBTH9wPF|1#a+neo8GT(mMPUSoN6b`fQ7|Kok7E6Jxu=Zx-(j9j}bGHV8+g=kRy zSMS~8mE~;ON6|{DqO2f9VA&LbjOmaVLxDL9j+6-E2C(~Lxht^v3eQ>SCwVnFoYJJ&vb}^l)Qzs9-RO`tE?8#W4 z!Fg-!LMD4EGd08uJzH!G&2c&Q1k(+4meE!4)XGf2FXLl#Oi^f$v zMGewX)BvLq7&UNX0DCDiv6dne2PiUuu_cU5U?hZ2`=+FmZ8vArttswR$rF?Kwy5#pr_ zEp)}2+4SwUGdw(3!SfauF{ySZ-T&ez{@J{Tql^?2PvV#l^`eRUxMyBPiHq~{3jv_JUns5a~!NwDs#ZkMa%&_4aZYDOtLHT=cZhaB-0PVO!Vu zD->_9SVO1WPa~h|lujbsh$D_s7Lq+(H0&*kc*WM%9}mCi<#{A)^n};&-jI2Q%&OF} zD|zhN5oee{sEHlZ#v@NXkCJ>I#dCvK9rhqG7ozEujLukk5u;k_cymhMzH z&mcRt%PM2*RFKG_X3C%9=T(pFHjkn3-2`G&4tuECYtY<;B5!In}PQ! zQty9gzW;%DGw}S>wbXq7V=mno;WF@M2;O6HZ>8|f7rL7v`ECZ@W5N3|wjOrY+M3I1 zR0ih4`#5;(hSqax-B`N8bB@Zun>u)}$o7XV!`_>ab*T)zSA_SK?Cl7P2xydiPPd)- zMiu75y_)MM+L7q-eH`5V;vFo!X%)FQk*Vcc?|rHV-p<0?V0M1kyOw;HtS;Rp<8g(# zaCYI12qE~sTIP3;hF8&jHB7;Ihxgco_=fJpbdx6-|BpYCmA z3eG#c&n?78x*Prq-3{MB2+W1^4)2T$v4ifPC(-@${e-|=IPcuO+COy1y&2tc=X>|H#uG=1ja0I-r2EhwOT`?{RMjW z<1isG7tT9;4}`2J&8WBOZIQPKfw^#Y;j0Mz&Rt76jovTeS5+_t=bihmiG4TfKi){e zT!^MSarAP_kM!0Hzr%trwBS1|?yRjGc?C+x5CY$gL4JuFH7I)0yy;|K(!tq@^A2CX z5#l1ey@N05U@k;cxWv8)#IN<>J3jbYk2`CR(W^t%>D3{A*$8JR&O3aKNQe{kdeT?) zvJt=5gD)6iE<_7a*S^riTH($F=biiB()*-UC3*#l-`>GoIPdUvC_1C3nzy2trWk=Q zO<^uX(`pcDUGvfuzH^1IS-G>e2=(ARdXbY|l=i=hwZTdbpo^}i5!=LdKCv^Ss!z_|?nUkJQigLi=_ zvR&~;Y!yO0)u&SkWuaE6E!`RY$FId&Rqov>gtGAVk&F1F;rv>x)pxx*g)kS^!$ojK zxQwcVz&7Dr(K~T2;`YpG+*W$b! zS8qMs<;gaB!J2#$W3PA%MqPY5*!GMH^4;MZ(oOnh3O~QLjb2nCpXoum+h;~Q=0bF& z9((Ig(CgAp^0@RU0!InPdWCp>bX@J2DHHUMO~-kdf@PqjNEwBu4APUjeePlDoQv+= znL9r&V*8q133uvD(3K}o^iVFAhb}uUS90reO7uP_=CXA%Wz${#s~N&qeriMS?(Z2P8#jB~ z)I7Ro;97!rts{uHve7%HcVkU|MDJ%~F1%k&dz@l##s4|4pnSJOD~TzrN%THAe@7*m zGQ{vJH9}>B>86b6opVIseQp46us)vR? zH>)L7c!& zX5sV=a>~xXEL1&)PYP~V_?R9wU8Jt(pB${Xe5h#LI`uy77mDb-^B1a6@1$UF9oDMM zj<>v7tuOdhXLpd8f;?1|L^s@amiIp|Ho!0c&seACh{p1S_-$v6OHQm=0_p?jsYb!v{9Aa_)VMJspv%PPF%Ut7`3X|MQznRr#wd3>p^X*8RC^QutCMVrO=5Dlr$;T2bvy&0WMJ3+Hty~GPeX|_XQ7giSNg&@$DA{ zuYP(W(M9CTbIiLge(<`VY$a*_DQbH&2eD3$ByqKJCb=)m41eDG*8Cz+>b(-I6QYHv zRx7<+*LbY|%7k`KTVZ)9iG0?tw|GIpKfG?$+c-Ult$=8n=U$m`jjcmvyOLoKYe*wR z(MU0)1krSttp0c2$R11l$&I>8Ym)?QSMqtio;~P2GUaJ!lwkWHnm9$XJNaEk z(94k8ugv~QP>A=>t>HBEpxmVC-=R)(5ut2 zhnjJ9e(=KC^y;6RJyfv{3xb<-GAOrZSCSXEJ~5J$AmgH!@>ewdR9aLHC$q zN_S|hHrJXR{JN!>qapp4#e!#K++Uf!lrj4}l!clgnoa?_l5e&5FMssd^zzeEZPn?w zW(Skg6?g6{AzO%;vf1Nh@uHXfb0yMAOu_O{k`PC0Op>o%&gTt!si?Ournx#u_rvF2 zucvma<|_X5lweJRc&APjRjWCUZl#TPc~IQ#|;b8tnBS*C`5%Z zBjxoIEB)W6l=n~;YJzC`WuVXN$eB%x>kS9icr{BkRqwwwEGYACZ|80ovbShgG%{X} z+gDU?d3%+IDOes#qCS6ZqCC8!pWpR|tcS65tkaKQv`~45^$9ZO;XP-bO?~Bc^{cOj z9}1x?M33LwLS^0BCn#2&5fc~Jk*}t$q06zM!68enJS#Ky=N4t<{)K-GdjtV}$BdTPBpLp%W|I;5W9IH*GXQbc1HCRloPT z2f@#bSXs7>Y?d~^e)>|u!zc?i>GxqfH7Q5uAni=%>GyrDfs8+1T32dRJcP0k-8Q+M zT3o1e@a6(WJbtRSoN=v&K0bR(Xyu-EDnqHxLCY0O4C6j}iwbX7k?*sOc(s4mr2Ec0 zott`C9!jE`cktx5H7n^f)wacB>8ShAFWaj(&UFkH6yrPYoj$HBPn@i#oBvkA(F)N| zf7V`YIo~n(x-26`=Z%#)9>nMtLsmQYyik+OpR`x)E_Dnl(eJVd@$$7eSuuM}-QZJ^ zfU;1N#4kFiexG*;yjF~;HMF)Y*fvIweW^qUWg)sKA>s)!p(7(!2estvKDBhlq061S zWQcy}^A74mx*xZlei?(fQ4MR#g73u9iw;8))?DbQmYr@NETS5sTvw}ELt^BMO>67- z%2WxVEJUCrA;$HpCEq(*OaFFcnRD+BZ@8f(Ar^M6EJwwJ^x`6i6K22AS$*2NT~NEi z5`}VCeA`j2Iom#{YkDwmmFlu=r@Feuk1CXSxudFZqJ8jnm8A{>B@v5tdyM>&?hjTd zxGID<3-M+kN)qD8uu}5qmksr*!r4MC?{`za)s^n;f^H>vv~Mn5 zNgnzrq<6&+4^7?LSzS==f}Ay$I0%#^M8m-~<>HRD^_aO^ox7H(AxfebNt@-7=X6^= z|CvyTte7H;U@RHRE&E+J)%TB8z7&b@>jtPtLZ}J(q>6k~i z>XO&0aJ(**EuBOJ`JRgWIOBgJpPu5>8^87{t@QLu_tQ$uWm*1)d+Z`|uj!~qkIk$f z+<(MF-Jh?uNHuxksbF=JD~YepU!>k2JSdRauhQ=BuS~7|HiO#ey1lYFWuWdZ;_2K+ zz2>i1)+6s1ckXkdR;aBIJ>MCldmZoQXWY`tLrrkEjk|E7^_|v!!KsDyi5j(>C{9ZG z#cK2`gMtj=*MHTc?6LLUZ&QlsEt%pStq|eH02Vas?`7>?OutmTzEcLq7Vy3*d6qw> z(b;q4(djyrk=Q1vyIV%4EPZsxg|GW7lJ+`r21H|v(B9zh&0Yq2Ddd7E;q(XA!_{iq zoGpI(@0#luLunkX5aIU6utRbB>!zi3qy7s$)CBt+M-R=xi+_3dI@i+e`lgr8h=beG zIHu_rJ$GdF`=ozHXa4AbhjLL97cr#cIluhxz4e(aeH;YNZJe9LB)^4iUX zEQ2E#G^BXR%}+vu?vB+nf1Tx_Ttv8*;rm1R{FQN&bmh3B4g#$Y+A$%H$>K8K**bdA zmuozE`)Wu@thNZE3^VuDaw}f)h7K#VU?Rh6vYND!Gn+=dNih{luWM zhtO9;4bcxG_Rc>sa#!|P{qb9C9nTWwqIX6<^~+V|k?ZyJvt1txp>K!?*Rz~(x4itj zMSVT}k?r-+uSE?}68)xLpIUNxP)mPBo<91{C>K3hipeyKk;6yV){SqJ2%#U12$V!` zd1tFB6X~t6(hD*r;2r=qL`f89I9f|i>Qzf8BrkKcLQfyxxDcXt%i8kSfie31{8d7@ zgFsDi_aemox8h`prZsi<*M>M+AsTl`^iFDgtbFg=7~SX5mCim2HNm$!=pNqXIn0t#1o?uWTBc>^uk{^C*Y0_(YTuwV%3~jx#jT~ogBZ*+1KLDIo#vY zZhKrvHX2n)?@T{AgtAZ*7xBZl4P>T8rFDV(MMAjyMKtc!>F!dGI60|$b)C}gsgT}kugIm z=|7HyJdC8^>p&RYq0_!s+sJcOa_O8KvUw;AHE|J1AM}?otA6sooBwtQ<1mQEsF4s= zzKxeh6N~DcQ{4C!-dDs}7QI#cR6m(7(`SCR(LFqrg_^jC*hi+z*9UJ4g*LZKz}Oqc z7BTuI#Gwpzqo1PKl9Q)KG}{d7eDC^lLwJ0XLG0H#IS;O252#<0+YY$koGDs-N|+4AjI$yu3@v z7mJpW>o=_pVHB8l5~)#c)KG|jHdK~5GaU6>#wry_LqbXC!p^f^;r4rZtB2A z>a|&e1OBFa^yjDRlbhlXpK0;aVNAjO2TGzFZdvQ=y-!pyzg4}p;cS)Z{kBFHmJ$8t zGYk4Hh*Q`62_yUI3hAfDqn8@>4OtVEM0ZT4dpcXXO8Wa-%MYO}M7xM4+x`xhFF4I; z^;zLzs>GD0Mk_2M`pvO^It8dV#@o4Jf<8A{)I%>U>ie)(D2Z;2ymT}CO4VsP*U0n- zQ5K?I#AlzDm(P!^udB6tx9(|*>CvCj3VjA#sp&0?s*lQ>MOy0N$I`|l0(~Du3-L+M z+_KYwcBbZtz73LN5M6i7((|v*=2l1y?D%vbuk6kM3h83md-6@sqYKv8?An+ zhq+KI7eVbLsl7~Fp}x^??sFIMpyo6=ZOZSVxr2%xq%ozae@zdfJ$J1rjY3JIF~pn> zOo@JT87PT(04*lSOLC&m2-GC{&Ao=@(RtLBit^9Zo=iS5{}9bTMRUPug_g4pSX4Tj zc%p)&nJc*rOo@K8Rw#*1ms$*vb>Fz;5g-Y5kACwk!tyBJ=J{_LEPY zy5_atIwBrx7_A2*+(`HrwH2z(b$`Gr<(Xg#4D1_DZ-J#e4;2@1pCHtibBLG(w0*c5T{64 zP7(LNVon(`JObhrsZ>r;h&V;sa*9%O*_tb6Q@IG@6#2v{@-3%`-mhG&ET@QjO)(S9 zwv{Q5R-A9H_{1slET<^-x5#V{nirF7-x##v6orXXq%Eh2XO3bv9qPvSfH*}e zl~WW?oFZ*GMX9-nQxp)VNLfx1Ac#}s6Q{_xoFblsig|s+jY+K&mPaqjRnDY|Q{-7r z5zj&MDiiTG`;(g)GWm8Olw6Iv*nnXNpnRpN0FJC)C$Zmv-Kb=>M=XhT2W?&nHI%d zh&EQ#V|FGpGpXH~6=vFM=W$ znVFb^uVqQz`mh-sboQ!oyk^|EhvpsV@0{|S%0>o zY(beT7qOyjL7AP&RupqtPO7Q7i(m`N>`b#x2ZN6eS747L?hUY(??) zPJGo9(L%5VWp*Z8QG23fW)9YgEht%1Yem_DGCPy4DCS}d%Ir+GqAr3hD6=!!irSMZ zGY7FwD2eXfkp*RTCR`bI%_tDJGWM(F@GR;1KnVH1OG~7pKX1ettR;FflCNnd!O)wXtDU#Z~ zzsKxMW@h56u-FGENeE(PYG!9LGt>IcigzjY98WPb(=CHonLe{KnVCtfOvUjYW@ch8 zM3e6m-s~|ulbM;Q6{77~p^7jwiIwRyJCm82#L6`LGG=BHE7LF;nVIR9L99%l*_q7D zL|K>%(LxX_(_?lfGc$>msW`^R%uIZ%7T?vQ-*zf`$zygVGcz#-%R@;*5G&JXb|y13 z?OsOlKGUA#DQ0H6S`jNV#OzFFW}+<2g=is&l_{B>$;?dD9nto5QAL=U#LD!Toyp8h zVr81WI5RVem1)?S%*=GlAXcWw>`Z26qAbjXXyPF^EiRdz$;?b*Wh#y~Gcyxk@5Ofx ziLte>sAP5~Gcz#-%R@;*5G&JTb|y13v2?7H-E*o)q=;CV9Q1ao z#c`nihM7sMOv&s_W@cg;h$dF1;?s=?Gm}`ElG&Ne%tTEPO{`4CCnynSCb2Rlvoo2Q ziLy`=Vr43hR7IGX#LAS+&SYjL%0e`;G8LZ$MVOh1MPuZ=xv?^BmtFk(IH~U;BbwNn zicg!Eu_**`EG2U-nP-WzP!r-O_@teAmWV(}bjI>hth|*oM*i~T4hKP8NX6^{=0oE9vO+9g z5-S%JkCFP|ju7U;m!Mq)u`(sIGntubPZ5nJLrsX4sW>(sVP+C5Q!+b~nVDDyB2W^Y zA`g#~%+6$HrahN6Rt>d6NkR}SQ!+b~nVH1ORLl%vW+uwD(MW5liIpjtoyp8hdwyzc zEh117?QzP~k<89yW+t&R6?0dZnTan1<9okC5GzwMJCm82n1bb@Bs$H=IbAY4lbM;s z%2XWbWM-y~y_&V%o@Sc0omk$}`blPIGBXopq3$k%SecU9nas>YggqHGYdF4iOx&n% z;w7^)nVE^X?CERtO~}+Yw}l{9ret;|Gc!?lVr43h#WFLKSeb_57-41-D^oH%lbM-V z2I}r2h?Oasoyp8heAgMZLP>P4c7)zqB6cP-Gf@*83pakLJ^wU*Dc!Yvb&zCsCNndM zm8qE9#mr39#6=J*Q!+b~nVE>NXQ{^j#FwXuIk1x6>?d|6Gcz%lJ+F1su+Ov&s_W@e&Rh(Jkn zkEMGt$?QyKW?~A)7Elts378{~WOgPqGqH5k9VH1ttW1yDnas?@T!_XNp;P2-wIs7M znVE^Li1l!_B37nkb|y13Q7$4-k`Tnol+4a#W+o!A&vEonyrgq2$?QyKX5tvd*@a`8 z;)&^>k<89yW+uu-O`Z26 zqFh9vB)TOOH%T%(lbM-_Kqus2GBXpcC9Vc&UCAasGg2};lbM+)7d3Ga z#LAS+&SYjLBG9(uDnW6d-|I+bXEHMrR~%eLarL3Q8Hf5xW@j=p6Xl{NE`nH@lG&Ne z%)~VnH9<*qH^ZwfnVreZOkB57E^0`>WVWWIWOgPqGjT;m1WFQuSecU9nas>Y{{uBd zNz~^ZYs+}LnUZ_n))4wQ=+B|wMX}d4N-{f>nVIOlpe8PYSecU9nas>Y?+!IYNmTRf zv69)D%*;d&66KYS%}7cv=GF~l+4a#W+v{J5siCw{$=ax^qWp`l9`z(3pK%L0^LNKUR*Le zlbM+)3(**JplI#bM<9gMQh1NF~YaOlD?c>;+>>7^|UIHml^4%+6$H zCdxuhTm-Q)J!WSzGZW)5h{mW9?I072N@iy=GZW)i_{$y`%c3`Z26VkFhxD>6PcMpcC%R%QaTGntu*WuPW5f>@cF*_q7D z#3(RExluzQh?VIvJCm82C=0d1_%$)fe`xD7JCm82SO%go%1!SfCwJ7$&SYjLM$GX< z05zml?S=Iovoo2QiLrZ>>uN=;OrP1A%*@0x5P_12t-gDVW_BhsGx2l*&sb1HA&8af zF*}o)ndm!5Jyt&3wtOaYLPP((DL#SOnas?@6x@HHq*RWVVF+2KlaYmGM86}@c7*_pu1G+Lq0fGf2S#LAS+&ID$rL7?x0Xo_V- z*oMq*6PEpD5Ll1scO>3UtW3%5OlD?c3YLMA=r`Qf-|?883Czq$Js|##_LzQ~!m?ORTcN(uZ|-v! zL9EO$voo2QX<4_X9%#=GM!0b%&O~=cBOGB<2Bt*6xeSyf1hFzbW@l0dCZQ(LZ|*fL zPY7aVYG!996Eo8?l#NzsIbC~Y`P4=$Oo@K8Rw#+spKo09nVrew3U!Zu^DM&h=v{*g z(>1d*nVE@p3GJ0-e;aM-2G5|On%S9L25J)hX8VDX=(p%r4cE-hWM(GHiXylkE`nH@ zKC?5KnTa)w)`JmlJ&2XboNdX>Ozf#>e=x%B4`O9XW@j=p6X!FIc6VG6D^oH%lWUIl z1LtG(o6Dn!*PsEC*_n($JBXGj`W->*NJd;P2?{69YNgBbMNq=JPZ6L z^Tx^g-wsyuhb&aR^BhY&S7(TNmVQ~4f0ry@^J%JRV}2zhg|sRifBJC#Oq2Xu6(&eb zS&@Fa`nt#hRrh>KB1)n@FY~t7`QTIf=A@b4x%EBNu6J10@x))(4_5z_B;Evl<4Q!Q z;RBPrYhPB>=V!*q?|bwlPRV?u70N|4{ZdosaOjg8ll_zjxP42jM(N~jadUN(RSKEJ?Y_viR-F2|r z$P#jCgDrkN(yDTimTJx9$wn*G5YcpYmwT8uEZ?2*r=-=P^sUwC^OKBLs3D?hFzp&E z8;!UT&O2?UmoGyz^=HXpMl00N9f^0!#>yYl?hMx;t?Er~t}4|XX0$>L5ly3H#T;*M z{dD2|q*aGWE!CXPTt-SFYKUlx$vibedKI7X>QP%|?ATJZ-rUD%g&Ml6a|c;NUMp7B z`;*4iJ(L$s>Q^*S~ z?&<9zt+<_78`cUnM6?hssrNciF9u{8cuaBIvsS1f+F&~Qq2Al>)sUM=D;`ta_N*0Z zh-mUG`zM8b>O~$`Jf^tkSS!>J(R6!&M*096@%g9+dH(S@Wvx&{TqT6~okn`rau^VEZE z*V+EDR;VGa!9qMm7W5mkq?Ji4w(D&FSS!>J(Zoo(*wk-Hmh=m1E4J%wJy|Q%5YhB% z1g$n-(5kbNY&)+oyjHMQs3H0f^nw7bHaDJ3^0Javyaw`G!CIk)h^Aj_rqyOXtvYPm zd8Oo)hP6Ts5l!c6vuf+Jy8NN+R7Up!3st##<4qY@9%@S#?%BEirXv#$@~U=d&;oVo z>v5(GEDzE2yJYtU`-`{D2;bg0!6}1RW?rFrb>_94S8mppZVyZ^tlRcW^!+xC9mJHX z3)Dw>r>oV)k0m0SUZ$8jUf-M&o3P>VvC+d^$UH=jANf@4E9-C05AfGiujSMO(Z~=a4(IpMAWQ<1KMJF^b#DWiH=poyo7dyO>U(-v`88$oO>; zTi+-XPJFkMzI!99L>~tkxVTprB9ygSc<@iR{SOZGb`U5R(X{8J-s4{69z<#t|EYcJ!_QY9FL55=>~i~j5zWEEUrsp4 zYc0+-%!O!LYiXYUwxj%^b~Mj%RHG({rn|3XOV(Ihf;I!o!#PiWBH62ZWUqc8PX_H0 zmWOCMgCv_6kWG9*mKtpz&RRs%lN{u^9w58R77pzzYKYcOh-qZo|0LVa9x~c+)DY41 zG6k(40j(d|$Wr4vff^#3B9P>{X38_nWA7E$BGeF92D$-C>tHWh2jfXAT<=grL{mKJ z`bGaFt+lPl1Hd&EHAFO>(I=)0|3m9Jdl|THqlUPO3h^=d40p*(W)B&C1Jn@F)K^+lJ`QS#9)}RU$-nAGUh+RQuF#J{4G}FwKl0%e z`EYfptW$zVzXVefqS^C8((r5;0){3-3{~R?$H1V%UqpGA?n7nY@ z1E7Y8rn>;td(Fv%JwRIFJ_9vGub(V6dB^WQUe$Y%w8Fg%YKUk$ai`uJLB04sSq9uM zp@xX2-yfureu6yMBcv7X$xuVwA<@}3dBflaGTRa$kHkZniL0yRW5oir3# zAI{dTw9e7Cfy8(cdQPY<-6k*cdH9v@JNsKcncyHWGSxNBY}NAI9P97iT5~X5_>=A7 zq`On)?KyK*+TUj>tx^&nX+B%^Qgc;KFD21Mtgd_~yzZrhaLtdV%DA5M)#)FT)Q8Wf zBqBOb;kl~BmPm9*h{ov$`o*4J74HAu1joxjKN=+oQSOWU`iCcn`?ZoAOZ1A+Tgr8D zzUokHhMHgXL-N~yy`5V>m$JYwzPqub6_$aLgxLS{yMC{}?fj8z2Rb!JO$KzDuiE6D zsVcsDjLMjH;zj?P-Rb=s*GEW98GC20Ixc3b?2zB?rEwBd zum`bkgjljHogdZ<{OR4tIHLp+Tpz9%*NN_!OzG&SJo}uV@8w|_cIQEMq)o>f4Hr? zxKcVj{@4(I=r`>p_A`zvcO+i#ALqCJ=K1jcqLZCbGUm;BYW3PAGgHw!7vhJnYxudo z+8zF(;ADw&4G~x#y`}ePa`>CP`@*xom@08TBigOUM^BUve|hRoc-faO0^7%J-S-N< z=zVi;v-kYU0rGD09JTY;xkmTBgXXAwOXjNIGaXAjHEy2DICQr9tr7S6iIY3M!=LW- zETFp~l)7ffr*<*<)iTslGSHmNF>%_J2shZou3p-4e*zP!DT*P|n3;tV9{efet*yVYO`-EdX zZtHI7`h?&5rOevj)-L)h80OwCS|7AZ#FXun$$Pc!SK;H+=?tJyj zXkMe<$$iEXzwGh8Y}85OJ!-rm{ra4l>Q03PYFrkcn5nMJ zUZ8eWJC<0LzPrp>pz2rW8MWkza{lqm2mG;Vo|afT>W(9ZBEoe`d42YK@h1*Uamqln z+vf-J9X|Z~`6~XF+Ebj7h&_nf(&{|2lfH>EZNIS{D>mLJVPh*`d34(MeX_Ur%X40-b!{cyoyR&MntrVy?Ow0Sub+AMn|5;A3U7U*B)V_# z`Ps0pmeFh4d5TjHy!DM}dQYZLWuq_qtz#2W zcdQdd&%b>TU*zX9Ud|0u9J`C{gJ|OK?%M4a|GSi*;r`Q(w}kzHXg-;b{!5axYE4rM z@A3(+yXU~&OEfqCf0D%W>{UaaQX53XTk;o% zDuO-8Ip@=7CS?&8ZyGi$27-{ek=C|EReIB}q&{gc}3E zGO$fBe&I$~{*8#XC`N~{4O8$DMT~4>tGft{U}H;T-xx$v z1eYW+7oxFm+%m8gv8}KT-7>IEFzWa}*Bnz2foYbc>z099;m!*+bP?DlI7)Dgxd^m4Xo>#kGEft=a4us1vJtv;(d~wR zg*C($efZ5foqq7Z|7llG!-qqC5&iI+5hqX9@Ol=RVh}h=5dH9*5sMycDBoOC+90r} z5dH9*5vA`=H@TO6QR6UDOOLKH z|1K|L=Q&r2Q#HJ9MWz@8_8Oueely|*weHuudKv`w6rvw~GvXcU!4^fg8$R5_o=QnX z^uzCeBQWJ5T8M|=yh}x`uyjN}{AL8!9BYW^hu@6A)_vHb*wXmT2-}0E=Gaq+e)!D@ z99OJWWVOWp$8Sd9*kyeqwmqUr6#Y;VBXE9jn?%-EArSrWn-Mq%AGSMj5CHw~n-R=S zyr1V@0`n8?d1k=83~M<9_5iF^GT%ZlH<37s3CvH#6dM-}m;r&3gkWwWaTI;#C)%?{ zl65@Mo`#xldrC^*%*qtOI4w5Oz2E9NHN?|sAP(^q?*X|zHO5lv^QbizvzmNh&exDrc3K7!GxF zGjyk8m@>w5*sRqj5HY^DfvZ#$-okSusOKF8Z9ek z=uSx;E3r+4jiMI&M0cKPSusOKL(Kyxys%M><%HMGMJy{f?%HQY2Z7io!bVY(eWGQ> z4BaWIV{j+eFwX#$uo7&ND3&X2@vtmN?;sjUwBF8Z9ek=uSx;E3r+4jbbRLukJk4vSNme#vU0?cwwWMk#Eq=^eq!+$mk#t+eFwX zTKhzI)@WHVLw8E*Scz>SY!sE)C%W@Y%ZeE?8dj`0;f0N&wNG>_I?IX~GCByvHW4<8 zO6(KeS*m5l4BaWIV5Y!hLl7|N(7wuxAm*)%vkMx&L$HW4<8q1Y#K8tz=hj?Qic zU}J)H0&Ejuqo~9_krD39%ZSY#qv7ur7J9JM%ZQa8kE!kq$|6`79qkGhda%?B#Y&Gu zxxFQ;8}1{-LJyXD8L`sik)9RIokg0fL9x(-rCvs?^ccbMGCH-=Q(~pZU@Lwu6jtXA`zQ7###+HwgPdCANdC zlFn#mh?8pA4Z?mz`#x^%jE28g^t-T8w5+&)Wrp0_ z;T9eGcGxH?nIUr@&I}n1Rv15EqiF3Dd7NN|jK=ML*e1e8F(b2A9*dYEj|@12#5f2W z#Zc@MdAwtWjK&%SV=ZhHL$OcfF_jrI8frJN*n*9s9XWa2W`;b927%Zn!bUM8Gi06{ zFhfQ|4GQxT*eGViK9T1i%#hLW=zzHoY!u66_R4b{X2>%RoS48i5jKjk*eCKliWxE* zH|H>igN-0?bt8S<BCnU2 zA){esk-uFNi+v)m$(SLpkZ_M4>p|EkYOzn`bssZiG<+MvHW4<8TI>^fZOIH79Ry;V z2pdIPR=j>?hP;}@?Ha6|VWX&JhRkbZX2@vtiCCY*Mp27>BCo@lA*12n2eyf@QMC4n zyw+!iyz&kLu}y@HVl4KFyq~}f84Yc6>}9}4(b^~So&_^xGcVl4KFJianRMx(W3-v>5|vDhc_7|skC4a))8Cc;KBBld~BpTu)UW(yAj zuuX)GVn*x}8NoYKVw;H5IDG%I<0ZCGY!hJzWyC&_(PEp3y>XX@*e1e8F%Jk>qo~9_k!M~!BNN+1 zoIRVoeWKVV!bVYveIm!jX>d#!2Vt8C8^uuU6PY`s#WoRVt0r%sD7J~PQ4GaCk>5Cb z4nbDmiDH`w`yZ3HPZZlk z*eHf#pU7{x205l65Zgr9D28I6$gPAC&Yr>M2`vRSeXvms#XgZkiESb*pN!Zi`UtU2 zgpFb-_KDnHIh5EY!fwXo?Gwc|5jKjU*eCKEUKMdnm?y$E5jKjU*e7zl9E$T71Y(;A z8^uuU6S=H7ADlnb2W%5zqZo>PBG)t5hhMs4n+O|4CH9G2&s_h0OBCBg*eHf#pU9!a zHW8;y_ABD=25U~SP2Aox6#GQ}))>JtVI2kAMA#^1#6FR~XGZ(^5Zgr9C}zYykr7-z ze(8#R7wo)3vGH=Y5k|BbxCXgqG2+0!3wB+z}6Yxvy7N%!KO+R^G7I zg4I?m7F!$_GvV6A9d}r3!D=fb7F%3vjOO-+)($IKSj)y@DJxd8utm&&MX-{EC8H5b zS!cs$@|Lnc!_SQ^4+%!suivto1*h@~Mc4r8%4WCSy0G`t(b(hwGhu~-|5r6DZYj943TJ{TPY zVrdAA!%(aZojs-P&pA&#K0>({mWHr648_`zL-7pBM~I~%EDk%1wV|`}wBrZoiDSYY z#ldffL#90*pSs^!9>Q6b+Og#Pf6b4kELdb7Xe0e@N&H?|r>coRY|u~f8%~4M4uU7% z-x0pPqo;;#B5V|6 zu}|chVkXQm2*frKHi{d>K9SoGGh{SIHP|M?MllroL~f&8gNzodiR34>5VGF{uT0&k zzWx6swEUggk=ZxA?st|0e}mvX3*J=`dj{CB{SAW8%y|vyEC>Du!EYGhuWMaSa%A0R z2N=muYG-NR@Xn^B4I7;TA`bvUY6^Ct z_6^Tid0v{2JP%3j`YeLW?VrnvYl=(ZpL5O#u5&ICmxVkz#bv@}G885IOm*0=3aOf1eb2%+fFS3Z5oA`1o1cai8d6Y3(tb!b|rD;d$_z!V!rQaTOD!c+R!Lv!e;-o1`7bJOpO~NvF-aQE!qk3)g>uiAXo4=pBna7E!7ht(x9CLo z)y}Cg>q~W!Wk(IGWVfp(yDQjb$+%l|sg5(|hACQhSFo0LJ1nxhf?XE7!-83Hs_BgR zXNs2H6|C3Y4vXxrV3)=2uy9<=1hYYd^`YBO#GSYpcj7j?+=8g*$OE?!?9JPMpDxgxz7`P?!fB+>x@Yd+gAUGcoSO z#qLgA`UYzpgY`4&9DdxePm{!C@5IHp6BoNXaVZmym(xQG*9<7dow(55iA&3bbIYXw zB~0wDV3)=2uy9<=gzL%PiHotz(%IdKOY4@=T$}bzTn4)=p}P~8wjXA~Ee7@sRql+# z26xA!7u&nY25VSbKC%mf6|mi5!8+O`yI;6Xe(3tL-RHKAFa5~wMx}4C8)1@NF4?C^ zVzPIUGuUOZJ1iWp?0sWZZ}-1tPaHcVc3(UQo|(`)+}*ND*m}?mxr>~>!A^lmcI!AM zczb*1lxjr~OdlxyzUF6u^MNV_hY4`~J;2&iNJXS5NgmeN||w&WvZ zw@ZE-VaJQxl63}Q(YQzLWYyFjPv4QFsrw3 zgdI+?EJKdTdht*=DGQw!4}(($Yi)-8b|WK#XvND38TJRn%Iql_b7v-ULWUK-J0+77GMtpzQ!;+TUlhk=y?7{`l!eZVN6L!1b4=EY zM~IU$drHP}@i)({(t7a-aZ+Ya$@mS|Ajf3Ac!W49v!`TI{z)rg1b>g#i${o)GJ8tK zq4-^tg zD9)et;t}Gc%$|~QS#dr%f0)VOgbXKT_LPk4nd`$ZT{$7cNm=N;c%*HV+m+uE<%A3; zWf|wiBW)#eLWUKk{Z{1bO}-oJ#UsQ?S;l$sNWV2kaC+8@M+PTl_LPjjXZ}+Ce8>qI zPRi^l86&uS{L+;bH(4v{UN)vHFB zWNnBwj=}9y*ZUMOIkD_Ff|8!|;-2G7vU*{3A-u4{+R|XvYY}3Vi`@zP%nU6em&fH4 z^W~g#iTG(SU#$BL_AqQ3oIfAIe6c%ZODCAfr=6PRfeQM4l4_mtl&)gOA`A&SmH$gpn|l+)61Vt9!{uvOnh|xXz_yrG)=n z|2~4tgb`eZK7z{x`+Ej^N;VBHLyO4eaXIm%la9jjT_>aSUs_3u;84;crBsuA{C&>3 zOc=psnCFwQk`^Mllz6#Sa!LCLE)&iHN9= zEdrtCC#RS%BRGHgu=zi8a+fS^?c83u9jAz#q``6VSIgy=BJhw?TpwJ|T(drcdjS5< z`TO@*+njS|Qh1gW4#mODOYTN4vto4NSr9+s-s|A>MsA^RXLR9N5ZB`F>)q}~F4ryR zyznfDWXEgPyDdw(+!>AC1lP9KnWDMlBb1;IOBg__FuaLK4vi0RJ=ep5i(y*?TT znH8tb=)$w?$#Bj&hm0;f3xZ3xP@=*lDQSKdgsZ`1uP?1BMi-t1!R<=oO?JE_RI=k$ zcoqb=UE!PTSuwisEC~KSq)d`MD@GTd1;IOBTnCIUJPSf@>aIjH22hg z&mgyPaVs};iXrKk!Lu;j1xRDEiXky>itJ3u4QP88X@`hQzp)YwtAh_`wVrjV~RR(YTeH zaf%@Zme7_J?Eh1SxEEkxm+V-{ZCu>Swf7BR!Eaz~ZCT-tLCTQPRxu>Ttz3Jjfk!fC z$Y`q=qH!xXc8VbeR^yfx?Eh1SxEEkx!|hnfZCu>Sjh$kMfn~a7#S9s36+>d&%C&bI zcpPMgjJAp)8n<$j8@UD+_Lddw|5Jvz7hquT?pVofT-?fy-HluWD}KugcMMX7jJAp) zF>d81H*(XNH#20kRSeO%m1}S0N;ye<@(l{Rgdy$)82QbAgK`@ew{o>p3^5X)+|?I$ z2}4F(#gG`ca_yZ4p6~LUfzehmB*v{=?G!_dl)bQGhEh&aUU^n>8yB~7wNnf+Que}1 zYBFKSXsZ}fhFiJGP49H(%?ufB6+<$(m8+d%h>>NE+{(3O#q(&MUo+Y&hA7<1)lM? zR-TpI#>K7N*eQk>>HmZkGi0qK}Y!$heQJoMK2i$ARXD!Hr_`Q(ztjQ=FhL>-Yf3EDyJBd=8!}A^DDXWi<`e0rx=o!F7KXmNn6Dbg`2;j zQw&M#mTQe`(<+82-2BZr#gMdJaVzl=avK-7ax+dbB;C#AT{XYX|$(N-}e#I0Q0mvEoK-!^~qRxw23R&MMRL(*Q2(_^$%3{kk1 z8#~32wD04umeE!*B*d-U*eQmj;|DY3-p(q9DBQ}mK5MuS=bn?%Rxw23R<3r6A?Y~5 zy)&b&Vn_zJa;-lZ9*cMc;E};9hJ?74tDRykMYdvwo`>qH!xXc8VeC zN{CkwjJAp)8n<#|rx=p1mzW`=tv{Ivg5L(;V+ujm+U6+>d&%C+h$ynf|XBd;d08;V{5w{oq|8eSvw%9PPoF+}55 zZs-(4(sekmei>~QLt@;@4V_|0x>LXmdF5>tLt@;@RZcM^-Hl*|jJAp)8n<$lQw&M> zEO@7Y(N-~}47YMarx=pXWOz4%cPXr5NQ_&#$|;7VvkczxV6;^XiE%4eImM84e@ABB z$*u~ctzt+9w{n$J3`x&~d4A>3GDa;a4xf9fIJ51cY2taG8|;W{G!W0}Fe5n}aPN7>(V*Q?4!Rx8U^nj0Qe}tsxj41ot(4IUf7V`|;jS zdW-L91G|5Fn}cm87;Sw=hq%#^alWI`N^;injPu0j_11TEh#MUl=Q}#hIiKYF2)W6D z8y&Ip9c{!$Np1sjDR6q&_xb3V7`~%p=R4Yn9n@imyqM)YG1~f$j^R5xcD|$2(#4Il zG(Fr`OJlOWqcgal5j)?}X+FgEE-3{@Ti?+N_cKE0J32kv=9wj<(fcge7#~#it@x}y z{X82M=FWKvf=@f%TH5N1!{Y5N=XiE9Tt1ApzN16j&#-qhxW#dOFggfkeRrrn;uTy@ znb$y7tA4FnvuTPs@T-@zzwan9eY(yxkH7wEwtMBpru?(h&7K=y!)oH#ClA$?KKUcw zGNhs6H#2WrVm4HnVlF6pBg-*i_q_38`p2b#ZnC7l;!uokQ?%H$S~%5|-}e^MxV+SA`to41E+YS$vC!OKdAeRE8Vf}gEI8{AtnCVxqEaV*W z{sp7u&gkNJSeFmu+1&=qo$9n#WA2f`ahZwSZ^WOZX zFE?$^IX2?i632wy+Wnj9W%EMy(GS;d;J6s=BO2G5tGhq&OGa4n+>p~qo)>=G39KHy zb%x&9X==PZ0Fx zt+76_-@iNZ?EcHa{mhnY&o+aOTO8f|&Y9-A4+fZy$1VY@eaD=xd$l-HPuQ|w5hG69 z-N!WgaFCgG*P@8g@P6@hKfU$5L+tGVMsPlo=L$9EBaH`sJWoGZ{f~G>-F-#;hST7f zf}s71|HVW8Gej>64(QBpzPxO(d3bIgbN-uGMah~fpT_P7Tk7J|I_OjHTl5$sM&M*2 z`*wd5_FfXL-7&z7d-qJU$maZ<=}q;#-$Gq7b!A6>GwZ;!&4?HJnf>N3jyNXRQ-5@X z?sE3&dT;NqI&mmwK`Fn++!@Vj0!EP|ON&r+hC9!`;O3RTB1o9bs? zxoQLNM%=vVaxS6C@e_vBOqb?2$aUtLwU^6;&lcidlW);Ah&ez^LB>~oJ6 zn{Le~n1^23p5?T$L;nf9EL6zF*KGPF!@2#UOR*VPb)=a&twjGPj1sg9mz4v^9d@Ox?ifZ!k&GDB9uFCKm&Uu2C znhk>56)sihz1pGlnu}Y9TvI#_`m8QSzdj%R`4Vc^6i{cTogIm{1eI(C$#20T(RJHDSy=+$B)n4fyzN^^0 z(Q>L;zU-~6Kg-CD`#t=w)$X|a#TjpY#i1CDeYnHM#r;CLZrzVqV360`T- zsb-@7V)!|M-Tmtf8L z+~?tg-7Dy7OFJk|oza|L5VY+*S^evwc5(gt7KO~6TRxWvJkX4s6ECe-UAKR~hnI6^ z;?G5QKDRe~>HgjEuj}GOU!_CMwxd(>SbJKLujJ zw%&1@Yk!SzTXv4()R{ZS1WWRo+ry6+9-=qzY^^wTM*C@uJ8zo0zwhXH@~{>mBUU|C zY}A`$&4P-b{An~8x%l(2>X2so+K&%cFE=YO-;bJL`rYx7$DQ+py^Os|ZThx?)~~!2 za=grhW5Stm=~VUjo?Kk5&QakV+ltM1JI9-D8$QhPn870vYVe}RGefFn^jY=kmY!fFeT=tF%!%sUw?$sz4z=^>VU70(Zk<~y)+oXF$F<~%~REyjdSDL z73+jNMlma98wBTFeL}o+Ru}z5^ZM$GN{h|iQzn`gtv|@_ZoSyNb?7AXQt|uQnz<75 z(W#S6^R4oopE3C;)$*KXde8wMgp+m_o0lq0G@p0ck!2=6qROVp>X;jIal@IXggja@ zLyjp3+HJl(j_+!(PmdcaX2N|5_Y$xjTv%T9d#jw$jGT<6?+p!#;fWHoN#HSz9M$9Zj+!d4uUy<+@4u7{pGR%-;f~~=QBh;dUH^en+-r%v~Ss(X& zK`^>})qO3yz+j*CMv8mIc_uZeG8+eTk? z!f}d6WJcHfe38k0f37+AKL=oa{$`~Q!cLoq>Z5lK4SDXorp*GQ`}Z~9tUK0Yi1qo; zmBJp2#_G*ep9(oHX2NLfY(M#PJbPdpJ!M*X_4@q_%xm@gn%Vo;jrLZ*!VJlsVX8K& z8~v-Y`3BhRmJOR~64O zhy32t+_$I*`DnYTMg06lv-Ah!_GNgT@kRUb=FSUym~uA^^%!C&^_3gqCQ~Qr|6JNQ zx+Atuba=0et+gd z)4joIW>fnaK+GB2Oz*DULD$)s3Hi;uI%CXlriZC^(&&iO#`)k~O?8#M9rVa9okNay zP>tc{=5uN%;^`}f>1Wq8D`LK!TiyeLQta|t`pHL6*H<;3k>NBLJ@xLv zrqxA#%kfUtM@zSvCQO;2b*J? z^)aRUu8J6aK>f4L4Nvqlr(Y+C4_Y4VR{D-T?RD4Jg3cTlGvU=eENl9<)@{bM)6-TRm*Kb=U4*^G+Sps1F+kE-FszNf z$+XcG#$B7a?W+N%=aw_gjJ8W6M!)c8fAa`X51lKBT935XJ5O$(Pr%Yem%f62CM2| z@+*FKoxddFnBY~Vbw*!3@C03QOljxW`t&mkZa>?!YqB`vczIVO2pXN$Q6Jj;B;D(i zDAVMXGfj5)0JFXM5)Z*K!SDG+ZT0yNwbo5)-I%G{wx4<6sk33px;SEn98(Z%eD`Gi z?D+cn#-plcF4@+{oc{YD)AfNx5y$KAQ*U@Nqt`TOrXMSskl7XWGjr}c+Z@z#v4`N8 z;1h5_JALw~R(k5f`!c7m=wsHj9c+r9SrjotjtPn(y04zxvxdHEY$hYUn0(*TlX1Mf z%Z(HFHr;gPpO4cEXWp4v|5P8-`sl&t=O-6=2#yJNh9qJLjPy^^J4heJ z3^^vOakiYVuV46Sd|dU1GHWjAVOn+{Z%RiFjX2(9H!9y#-?{V*-MD{sUDT*bDE+MT zI?~rNf@4C@(6EE9IlP(v^5;z0pk5DiR@r#-)6$_)3*Ft!I%a|y^z6{6Ys1q_-DfW} z`*)C@y7S@=dcki^^)1~pA;01DI40Ox9yCv1wf2Eb&-!O~=3TX9Urfe!8P{c8l(8LW z6LUxC{^z|B-~8x6j}>$G5uGL!>E|D*t;@FE=pkhMma$OA@CT3XY3|49d9ocjUwXet zcPOf@x88nZ$f0UY>S=zeGuPC4^3RCA_m0=M-1}5m`i{ylci#7F+M};2-+X~tvh`Tx zKZ4GjqhH%%u9p0`-sykchHY+uC9;&`jzmZskr4``3iG?&$pC2{S+;tUpT&l_5(itPq&_7q~6LuU@ z)k}l9`-s!-IYEy(WMe$(_qwWmi;-r)izTM?v9GhtirM1y^`$}ad5=t071s3*nF*hB z$_csbtjZ}lMuRy==?1Us@RgQrl$>kJE}fihPr)wQ=Ef!FfZ&^~&+5BNkI{{`tccfD zEb>?}f@8u?(cokCqMql+tLk>~(hyq@*+&$656)i@R6DSSuJ=hfwSWJHic@Fqei{R= zz9+6&d6>E`_hiVS7|kUT1P46OM$i6bO}r~O&Z`g3htI0~ho|YeSF8(HX3BZ27~$8) z_8txN_zmq|WpLptq>HdgQw|humB8XyEtleaBAH z{RiFrh3AqoxKr-fr1W!}iiOnk)WPtMc}&KVw;pK@R+kEzUr8Nwjtjp`3E!Pu^l&Am$cQvv90x* zcOLd;OB^rHIN-n*FLPaWB41JBi%APnK6P?uef2kMI`fK-(Y%_(&fT7ty3V$C`mF`)yfr5?;q@-mfhRZ9!!OC`N6XL7 za9qrUSH-YZDsG@Z{-CQq{P$xry!vG{ue?!%C!M7CKexT!-0y2|ea=jHZvc0f=GE1e zhM$5}%iS4{i<$5a0_@199ju$JKT~%c*CxX|1&rohiXdn_x|!}iXKd&d>+lS~cXjn2C>QedDKbZqxbt!>b<5@U9A@dDjT*!E9~a{DUHW(53$V zmCV3p&MUKU-pj%mRq>7Z`-?~Ds#DGlIWA`6BkmdXK&I`%^K@oSzs|h(#(Rsr`vtvJ zU0rWDpo5-MW2?7w$E!0`9REUZegBLD6{o>y z-sOfTgx?3K$KI}}pICZu$UEk|^Un;$wgS7URm*k$>9=`$`LgHDqN0mUg(vRJ%JaOL z=a{R%yED7z_*>KGJfg$VEp+h%MHX@1fs;+G%}-iHf^N6*<}@bkGngAUbZIqDzq9L( zjKrJRP_vD&Z%-|$%osaQ_d9!086)I5N$>9I*Qd`xa7Xsh(wp9!sTY5BUd(Se4UQ=Y zw(J{NS~~eOecHgImApyL&-vtsPlWP0|MZ@2y6oY49)jcbZMHwSx=PvbCL{Gj2fiKh z8$KE3v~kh^RvW>p6IgL5K3DY-^?n^#`oxsebh&em_D)~J%^jSzx+1)%ca+uI}aFablD!P?z)fbu%X)dm&W^! zoZ%t3g)WcnCgeVsySf&R_jmd^fzeGG9I!V{{(zMWu4_iXY}E z<}2ugJI9nq99HWnJ#~C9?|hKc_$y-NsWWxk!$*bOs=59Jk$eUDG}_~fx*A^;e>vQa z1(CG;JVL(OpYhf5*U4x>B;R8mk-Oxc_=2w{X?b(UTm4MSWp~@JcH-32%?Tf_%HI9v zN|QY25&x}uSXkO^jzuKB0i!ReaeEq*kKi}VP|!(CdBkOo6{pT27$qF1QcN)^2{kNuC*v`PJ$R z8=yYaK`5(`ZmtT?+|79SFZ487*K^!4*hH%amt=a zdd7%*V$);c27bfbIZv>^YBpI<-EWPxnq(%0=d`3FVH*T4jqqKh;o`DyTpD-|f&yCp z<7c_-Y-(ejhfJpN7qojVYfG=|$zM<+$8e8wIZ} zSj%lp5NQvWlTg@gN}0&>{>#>_WweK|eIj}T8}FafOJcIDa!AM82>WT=L+Rz8?>l?7 z?L}=m4pDfMpc7VJ8a5%xkLwd%K5Q@Q<*85~fCw`n?vYW(g<@8P5^>SnzXVZuBk3_Z zc}@{74Mr4dli3O)tq+tgGw~T>yo!>t@)60K1TCSG=OpKhc;3wVPEL20M8f37BRWML zH(zC+8}8~B9sApKyz^N-Z;B4=WyYMhpA7}HNzh459s=#kPXp*EK_@YJ2;|%%(s+|l z^8a9E{@<)Pjnl{Vj_z3TlkKnkoF{R)oSP))NuK`7Dp`LBBAFq{Gtc2{8aZHX&XZD< zP|WIY%gW|F=|u&>{T1?I{yra=6-P3o7X;>?5v}whSttHA9~_F&$X_J($$v#8Ido~H ztI4E9{)$NWx}2viCduDl5lQMc=T)Xea)+1m^jAbO+jasOxtnN^aygi2b5JXb!j zfAq~c-~LU`xegG@NGON?|ELel;Uk*EM>2>1Yd%oAwx%Rrw5v!~^zxk4&0i6`65@42 z(klP&2+mV7*G>^Rd2%_lUyeL;xh3CYijW73NcuiOUqNxbr$)PIV|$&P$V2j- zgViuwKFMrZ5DDAAMW96U2u?34bq|q~xRO@QOyoIX=pihtp=ySgjH#c6O% zk`HE8KnV9FUU^Q+Eswz3Ii|I<{qEdK*gm^8uKj}Z2&{xdTA$lD9Eus{5m?b%1ixV> z@|?7Mi^wIcI9?7V&&hWKo7B-2^@c73b>(MPcDj9XWAjI!b!b=6)Ev>+m`I*CXYXG& z(wwDkw$DMZ_1r`B@Zx^DYRhV6{ASC@%gnmk;!78OL%)De{>5--L^wt+^mvI^#iqSYL0;{!P)f}w&4YT5yP;%oJh7W#wiN0?6 zi>2Qm)js>eZTZxHD6JKJ(egpdWcx4sM_o^N)H1{u-7gnzeR;Zm@!<1I`OQtuF3KLc zRZ4ermSe(6+|-Z5VOuZM!&l7f%<&#{V6ABR+y^XzW5Uk%4;56OUITTuRsAwX{90jJ z^jJsnQ~~DYdPE0>cQ{t14;-TwkLsyAwOG)ZL)ED=H5z>LwKkNGcq3@5@T-3;8C1#$ zRvl&)-yrC6XG?Woe^_lTuTaWw27Nw1`s#^AHVuv`2r}KfsiI@+>wa4rmmc@c?NQaN zs7K&jeea6smzo1D0^T;FM2{y3R=hS;)tUZtd`H_OIy2(!a#VMt%Fg`>f>Y z=;aSad*3_E<_UH(?Wd|A!e#NaJ8tdFq52*FMAY`gcYxTO^%2iLG*_M5a%)+yH&1Sa zm2h-tt8>;#yz*S(rfpbhZO)!`%=+l=Uzb`m?5Ug0QMr!~jc*@Oxs2a%dVWj}5ekCe zIE0<+xR~%Pezq$kAO8!Ng_I8)%H_j`@(~+QgAZQvbGWKdgOTLI)gYeJoZIKLbi>C` zx~@#@8)oH7-Nux!^Q!kYQBvpp#?_h)|MPYrtU|x-6E@}}x_u&&7=+VE~TW@>g zaBWr|QOa*P4Ne<(0nRyD*EzU>{`{H)$~ay=E8>`7{kb)xyFJrPubI+adWO_j6rYST z8mGwR+iLmkx#o}!oCfR9aZI>Bh|(Q?L{>K}l&;OWD_uNq&dR7MsC-YIq|pg!@EcBp z(++|c-plB_9&e_vnbonB`En?ql}kfWJ|d|>(PosMjab=doC)XCP*)%g7ngnG(y(Zk zw%rNIm+r~WG*kaV>GB&_x)#kbrKPKyA?N&tS#f%4D^c&DmGH`hR}-$z-JZ-<$DgIA zcde#&9e?0@M({d;R{)s%ptYa((ZT9xw03^OX>d$wYgY@=+BtRR?jx$9?bbcGf!c+( z%LpzvMyKscHA1^`t;Cinf3-fs2KA2zS=hUhVMrR%e zd35G6F`d2Ixew11c<$rR8DxI-Bj#7rF;C>V56`c79t8Wu{5;W~tNAmp!aR}Zc0o`n zKZmn(QJyFAT-2X4x;b3@0OoK!OXXR(%ZICTH4@M?=!lWwGTtlW66WjyCqBZp#iI&$g?XuG`n<@LF1yDkkk4(em^Me+Ka zdusPZIfQ&8u=i17ogljd$^I^Xwfr?pcxzKsD%J^tSmbsfITZIRc?9e-Lb1yb1n<@+ zyLHZ9!|iwt-2QRtQCBZ1JG%S4#FE3lx$cD}W>T-=(S@)`;h2J;>&YE91UFt9zIFHv z#i5){NhDr8e8l|9C2dBo{Vd!Gixdv!Y)T^W_2DD7!`^2^lacCv*!%DsXUP+hS4X=8 z4ZpQb2bDIRahht)f(SgxWaA`cK^dKNk`xD|r_=9+4%EYJx z{6R38GhP&OBQ2n+ouF z@x_=4Q87GTaQ?6ZihQ&Jt7E{5Loq8K;ViaP2`skc4eViTnefQTZ7iRUxa&-{?3_`y zbQ6TLtg&c)(6y%PrYTXE?_Nee?(TKthKeocshLCX%=`sARWJo|7*vpN4$3 zVx`C59fy+VBv06lf`4E5`HjWLulVrBtWHuSe9FEcO6$bylgQorvi;rKY_8pCE@luxaBwE7o+8bTf z;sxYG{QGXd{DoM2{BkH!1BPGOsOeo>vOYrm`@+v}srdMH8sw4q_~krtOz`Rm|Gx0^ z8;Xx#r*j^Ok6+FcqoK_K|GsVZdomOszx;;N7@eEf3iTndba&wlv# z9X_m*79YQyL#LY&iS{z1gFyWI!q0CgK7P5}nIY#X2*kfH{QPznAHUp|m?5JvBZGh6 z36DJ-;a z&~P7e)a7NO&?&U*A+w=G#8AsX(`axc50#7~3kgJZ%N1r7HNglM=!%e}1Ci*uA{xI-^G zdSUtIETcuk9U8_i4bgCimU}EZ?oOG|zH$14mLbOkooZ;fAOH4YT6ElZ92cj-G2xaeG~A)(9#2|&k(YBub1wm({m^iSmV3PS+lh+b@E66U zfIHRDaIaCjq81%@j+eP}Oz`Lc4foZb-x%*5Kh|T#Uof{y>@GvY{m^x%#Qj!XqWBHh zpwCJ)+!tT7e>`vSRIimVg1<+Mi`U;0*1dEj_RLYrX$ILE ztT-Q>Khy^_+@a+jSC}x?8$Y-{{L&Q-cWAk5(Q)T`=KA+rqG-57%RLqy zcMc^Q?ohP0-wJ;>L0~o9x3`Q%$DO}5MsQ4MyU=i-e&jP{3*Mfi_d*@ZXI}P96!)6@tSRCOI(9ov+!Bd_r1*avnqyXcE2?7%x&jB&Y!wP z5Bv93rcsD7K2 zPdz@KR&I>qxR?pI9-MRjE8I}EWBu@zr!Q3;7o+|0<3Br_hfmimEnU~{Qg2k_(STz@ zOFZ+L_?y`~!d|cSRbMVxWVSs$KYHxMEm;o5;|e^bU%5JNG0udQKRM4Ead>p*nBX1% zmz8nHM>mHfFF#K)6ONbDgSY8!r-z%b8PK`f=2_ks#ku8Dz^bUlGjYoYcZ7pp?(3Bm zGjV?JZ9Ty^ZiPLar>{RF+lv5{x0oQ<^=d8M zct9n!VcAiMzJdLUmS3>Vgv0 z1zxN13fuV_jq*ATzg9a`e^}{%;b|`)pZI%?#A^VrAbDj8RT8L2Ed1n;ur|~q_zkD$ ze3;spQuPSc6zUP2I)`F3ZnFMdL$_~NPPMI?Dpc6GIOohT2o5{9p1$pi8fx*K<-NAc zEzw7;nc824xt^KwT@O;ChzD)ENL2B3SZuyMY<6_r@2@1@bfdgShig9kDxCJp72#zK z1}5HgBk}0qyy@CdjD|<+GiJu`kN+jS|FN^Y(sdqNEqcLw2He)9qdI-n8S%rr8!HaQdGZnGzJFzSWJ&d~tjScx zsWaMdyVu-&d%XOv_rjlM;S`HnAEW*6qv6B%$Cvln6}DK=-|I!Wy>d+Ob^d7M@U3Gn z2pj)*nwN8qm(zoK-O|HV_NyIbs~erJIEUP~`}x>+{*rij&p-{?+}F!FGvQVl1jRQz z9$wSrk#Ns-L%h;uCS05Fg>=+N^;@g$WhZ{~YT|#_whZTg7vKD=S*{y+bf~c?go1Xd zsAoI1y+~9;omQXiC3v=s)(+)tC}@|8dN#k|v5#XyUjhZC-y1#{ih8zF!b7|-Wt~=^ zeRiI?Ekm3GLZt}`+M%dtJGDK_isNN8&d;F)b?ez>8POSaihhe-eRGh}oSh;sI`#pi{h=;;*w zEGuTnXzVjUN$`m4s;Lb#=Z8)S&$42M&JVp~CCb@Q&<;gC+o|nYR!$GlJ~JBUoX{WK z@698^C&0=n`dL=YkkRlt0M*6Qn~n`dJ=-baSys%@`5AGnL^&G@+M%dtJGDK_gc&j# z=U-5dta^TqRoN{oX2|Fu5asN(6Ze*hdbU%-v#gk*(@JryL^&G@+GV1i?bP-xD`v>( zy#C;*F8h~>dbU&av#gxvpnYaEZhAw_^VB_`#iE|=l<+JoX6QWWI98&Z4F&DECRjPO zJ#>ejJ=-baSys%@sogkMqMQu{Z7u5A zPHoS!Vup-{#yS*SFZry8RnK;cewGz8WHj`=pb}ee{l!|;vz@-LWyK7ghbG5Ll(V6r ztwlZC>GN4u%#hLW&j7XC$M?>*+Oj)3j5Zi)EGuTn=pYc~Y$#}JQO_1dW+>>|G&ntG zi{1yy*(YDWFqTp6^X-=ysPx)2I6X$Al|VWBtKUY&qMprZ@V<|~b{6GqC}?X@&t?R# z$r+t$FKf|WX1-2?$(E?|P3B5hl(V6rtwlYX--vQHG=&lBr7Xt;@83|)hJv;h^=u9$ z%Gpr4!ucR(tWeH|o>Y`q&lcruC}?X@&*pqET9mV)Miu4Nvqd=@3ffxKv-u6@oMXZa z8Oqs%Zd_6(>e)P-;2jp84dRP}ayAsSV^PoMP&`lc5u%(81?@6X&*nJ}&)axD7X+f5 z4F&BoQO{-s$IIwc|Gcx*AjieCFpdcdt5D8{f_9mxXLGz9ic2I2L^&G@+FI1JxpaBY zl1m!CMWCGB|L_a6sAqHCGMZ}>`G9hEFSHU-&*pZ;t;9!&ayAsSV^PoM?|{E9zs^ND z8w%R7jJ5o&aVSP(Z2;x$Bk-MzdN#LeX2NLf+@UXd!}TTHXK;G_&BLP{`m68IUx|7) z_e-1}qp@FtK5-cOL{ZP?zK_3JMnks`{qC`!_pm)2_pi*5dpl@5p>LmyzFlU>+=nwm zMuQc`j~N(0L_M3w31-M>_(Fnm_8~R@S0=Mp9*dYEj||w^#yB_+-yWxXlcC6b%AV&VCtl2ALuA+<+M}8rD0Qm&_Qy zw@lQtdH%r+84dqenEUJ=k;};JmFGCjkY^n5DGTLnC}@YGp3U24&)U)lF!3-H41frZ>6Z72z!HVa# z%#hJo*FrfP3fgw|%5!IC$TL~^%fP(-f0(z6dN$9`c~;D5j0RB7J_BomGR(qx4ZsW; z4bLr5&VCB(kEc;qyv|^TJnM(8GnBJ8ge{e*XY*Qy88SKuL^-=J)={FK&Fdv*$Y`7b zV6FBL)@q`j&1*7d$SWkMJ7PUp`S`X<)U$cr#|#;by$mR4kHMN#)U$bQ$qX3{`*tX2 zhlh^0WyR}PX2`2a?6+g>3dN%JTFhfQMfhcFckG%|0&*nV~X2@uGLco5>W!Ntf^=uxu znIZ2|V1|Z0nVlErLQ&7=QJ)zy8m%4sKDS}tXEFMAo>?$MMngLj%GpmIv!YDYvw1&> zXHLvk&giG8Mi1W{{tr5F9Iw;nh(saJdFYDr%5t-zkT+`jwD15Z=&*z-hR+LvP6ph1I8<)#0gT^7haY{XrXdH4(d5y!ZXO75p zgvKFP_=!`nAl~G=qRCGqOXP>TqfzBu+oWI6M)K3|W zoz%R}sLeSeI3LM#-s5}6yuzv~fx;@k;WRj=yo&3(>VJf*pyJAJocGp9lwy;SI-iEq zQB;p?+0}*-&Yx){nyk*BX_Qx^b^5hR^lSNz^Tis8el5q8*RMUT#gR(%YdI9N@)1tI z)|M6XO`c`H-A9NH@BCH!$_{}JFVB#ikKagCe3SWHzFj$WVCxHs-z3kH2FDZxPC?Ro zHex2pvy>>OhdYYUEM7h@)L%fenCH08Uvwmj#~t$i(4+h}=#-Q-PM~xACV3WC91~__ zd6i1*3yHZW&yrhC4>9ERowevYJ1^gnC_?i}k5@0yaLemj3afybB+ul_-NuxvPHRz} z=C~4sO&BIeK-YTwdu=6kMZ}+t=(@| zPKVdFMD9QMdrY1sy;LLDBDf!1pI1AIq&|}8Ji@8C+IGcbD)*?#a~@F}emUzeK0zH0 zznpC4?fh~^qi{`znl|Z=&i&rr}MuVi5{f$%V|S7f1OcYN#KpVUrzNe_~lGe zmwIM~&R=IV89I@;sRuQvQ>qoI_n`*mypTqsAH``nm8dAMAN79T>!}j2ryPp&;UoU| zs7iRt4`Wn?1J{Slm(iRybQ<9GboFDAS_`kITpye#jw$aUcKrbz)O>h|b)H}&(Y|sX zVk7cf8|C$*N^8ARc4u&jTKVhci7(bj6uFp*^A_t67r;Yot*geX2jL+$X${gcn4$CP zYGcBUDyTtSJgG?C2Q?_?4>xKE{V0ytsYFG2{V3;uR~-!hyBv!1;UgN2x*@(`+$6PS zX4AyeZ6vB4jOMgq{h9Z_tImM`UH(2ePtIqqjVTBgLk;S^+8xx1P=n&QoZsR|)S#S7 zRFv0`Iv(DQ``7KD&V+YkMmX=rktk;|8vaC}Q8mA$gE|`;RUDV|ZXAhj3daQN&m+Ex zkG*%eTG6#E<2(;XqWZ<57>!dI_(Pt%>3p>V{*W2r{2@ojLSrWB8S-Q8-5ce{zSY4xi+GCU;i*f4!zNGjTr2BT=&AQ3C#b;lF*;#x`mh{I@d` z=f6E7rKTvaA9Zc7)_TsQcIvrTk4rqI+jyCY^X2Xk&VRdVaM$QW2g@Ry|Mp0fta!Z2 z`?|k!SR3^-eBC>r_L1mEInVWx=sfvp9N(v%{^Wwz>TPILal9Og(NG40ulo*FTdBL@ z>)!dak3Uv*j=Iy)C#i}nyCxp^ zZ5kYk(U@8G>Z0fV+E~3_?V(Q2|9>PpSUk&QhC#3r8VY~ZX|0N(q2ROiU^VD zJo#x1*pbog55jHPUXv2F0-FYhVl+HDKttj1Wwq237dG19v=SoG!Q%NYGsHYGuQ#Dy zhu(zKm9Ra7Q;)Fym7hlcuHE$951_@;{q98B!KT5X7>zy=dK1s}_%WP#-@x@wSHkvD z$!tmbC}xN|CQyUA;B;82_=A2E6L z8M@{1)m4ohRYPXQXigh96rkp@=$zr<^2rC5I@OLyl(TrI$9ckyTqvJBr|PN;p?tz| zIpvc`bg-NvN|e`+DuUwFzaOcsN})K#Z=CXp9m6>$+|{2xLSJ3>df5Mlb3K4SH|hbM4}(%RAM60dGgb^sC2Ae-hOnr zvUEkF;9}$AP>jZ|8gykUm)4ByLsur5dCRB}+t>N7>hC0KH#T(+#b~UGpxQHZ zz>atuRC{>Uz}%hwkDKrA4~3)YzpM#Ag~E|jGKxe$%IOtFqV43TF+J#`Kl)eS_>k5I zDvpaoF&fH?P&gX1p}jsC3P&Ai-N$IBd=%w%utW`NNze1cJD>)|tehH@wV-s`PS)}; zuLf2BlX6C6~7GS zERL7UhuPw^56W3hwyX$6Ig8&gf=dK?sd<$#{WDa?I1OgPr4EIPV^4?b+r9B22mcXr zyo~0$fz3o-Wh@*Il`*bor!r<&UOua#&~Uq_dPDslG~75YX2LBLcT8>>t1sDHDc;%o zsgToPG`Hg*IN^p+_q=U;xDtwN{6#Sd!LH$gWes-#Z377$6d1Km*~E4 zyp}otr1^=mob7QK&Amhr^nl*oQ=6-+CeXX%9>?k3*>x265-44$2~J)6Kv@=Qf*cn! z;l2_(sZ%ED$@+$H>I;p%G#Jf2DlBXA+JI^sv;nzqXI9J>XY|l&ylUa6VHR4AJhJe3 z<)=~f8g+}U)(@yZx;82W)7Y}HF_8iqp&4C6e&%$_?$qcb}&g-Qr zb98BEo)7X&)=y*f?oRrWbuCo;E06Nh;82W4-wwUhVGp%d?V*>-Ggh9FGeh`igtqLb zC%00EeUmCR+5J|Yk^5;hpU_VK+`F}^_v~?A8XStzxFHR-DXd!5dC->S**&jVm?7?Y zL5KIQJ?+(pTZ2SD%Ch2>5U-FhXBgXB-*aj^wFeqioCY)T5m!K&>t@qNeL6N(=d!CG zUKR2BDhNJ;W^tGPp}MEp14Yb)SB<=egO{7fPtu2P@1TzAl1Wsp?7EMc_=w8TES`2~ zTQwP)#mt0Pkh~U!9RT#5OB$V_DnZ|wneYmm*Sqj|QqoK}7@kqr?wgUQTG=%+Gw~5c z(09IOVO#ag*^hY$UTyQb9X%Yhu&1sVrk;ZqHZ$Sf2;NP=Wv5%}>LboPMFq?6OjNDx zegZS`5gBMQsY+D_VyDwUfyAYZS8(z z<9U0>sv%pJd3$|~@b?oBf3>o{txu>jonG`1yl2U~pF!|Rr4Pckn}@2}JBNCEuN*J$ zU%~=nNV&4NZy%}dYxHKw@iM~Sd;RRmpW_(=+o-A2$}8UaWhNXGtkt)*SBF+_pj5fy zL_f;zM{~Tq*Nbz`$Jd2lzu8Mo?)it858ln@J#tvkoxdi&ZEYL1@Pt$c%dS#56z{{s zcj%0vszJ>i;g%UAL*6mx^V+o~#irDZj6P{8yXPOCyCr=2z|QK5;sX^k;ZXhSm6#`f z8yQtmqLF)9&&%WYKT~RBn`68^eGbLGI)dPb`$nim2X6>#)Vv|&c$pQSE(bxAmT!l* z4y~i^+S5dFyo_G;6jXcP92+gDD1KOGJzTyls@O=?cqmfr9fZ;E{#I<(bs86KsPZWg zP2*fRzFZBp<;3oa->?@KjtL$eHceH*=3F@Xnj^zIwiTQ2c8-s_ZTK+DO#FOITGvI@ zT(+Ou+7x#>DRoA0Ot2Ptd1dC;A$`<}jWyNF%}UJoqb5ZC?)WHMf&9rZL+mqLFju*Cdy{lsW$lMk}&vxXT4!I#x0ss;;h3Y$FFC1m@8m-ZB!>Mu=R#ICUE2QAh8k5pG2YWMOIbKJT~(Lt@=&-!UB zZ*g2a?C|Pp#`-?$Q}Rv3p%@(mk8HX;K4@)wwd(1Hir?^EOO6TW9}CN?e$Q1_HBM=& zI9}$?Y=dCu0~6JweW!-A>&y%}6xR)x2Pl!L9+eM9QQr}C1nQ*DYAHa3{tFfJ1 zspoqHiql|*TsPQ(+%#F$xiJ?unt4jd^~~*<8A9{E!xNb?2W8aq+RZ%gN!*V8G=|)F zl)AE06ZOrjySy|w6r*w0ym_ixy>V_>yJ8*hJ7*goW{4Hbm7j+@hBQ;}?L6G`0>$6F zpT-6F2E#cAt9jc#_R`=`jD{+E=~VUDo?KY9&QT%vGR%s?XTf&%g*uo zMDCrre++_qo{ZEJ4{Qpnepp^{AH__3#JKaOsfYTG4yO)l;jv;g_u61}>f*TGPl1}d zq_5}GiAORX;eue(4bO(7e>_aRyP&-{8gM8cyU@4K9;%kN-WY!U?JeGj!=ZS5#0qlc zoOoHi>Z<+wJ-qw1e9QR7g(YV1y;GwpcfO6jWY=?h!)qkyP>1g-HgB|? z3XPVxfGBD`RXsXOXQr3CK4gn6w(;T{z!(k2T@jaEcevX6dspwiGxrSKV+28)=ROY~ z>|Q}tTiQV}6AtC~3~hT)R!=?DF06mwBCk(mhJHRC(c{%8ZK7~qtJ^|;!}0okiJtv^ z_(SIk>YG_@yk3;i%r*#q`f67E&S^)e?|jqZEZ%tH3-tl^7cHhPCNn?esYTK@%hHU#XZNF9yKoe8wB57xN-DMb8C>Zq5c`c{xbLm@LB6} zX2tcF6w=7$ndQ`tqlcIqM^ChG*xuZ?i06E84mszXzcf73$tmW`Ip_SP2s{X@LT=gb z2j|Zs5WoE7yqm>rvnw%u^ZKyA$vN8_vqiM9z47581%ypN(qL%Zkg;M{t?&H^`;n zBe=zJd;RB}bNk^u{cS#SQdZ20x&P&ha@2B)<7I~bT)NDi>;IqYoLe~O$?tvsbJ0H28I%4L$4KmZe-DjPBX?GS?pqq9+(lc&(+)Ifp7dBaDZ*7Od`G+&~Lj zQcuQ=Kc|-;4J6c$$ob%7F0}~BVKNpmy6`NBLs7afJ$9Z&a1AoL@GOW&P=mc{KV&UT z3pKSl%jm-MpAr0~fR_9f#x9=~r_SiYvy9H1bIu{73(tb!(k+xImoz^M!quS7IoA}U z3(tb!b|tLxeIiz5X}`5ta!1;P zE<6jO@RQT8EXU2>Cg)9fJ@y+aG7xFa;c{XJmfTck7vK|QUX#E99o`pn#+Vsl*^D&e(7>4{B2p; zG`NLxC`S8f2qI}eTt5GtbIu{Rb}o@Ljhy71%ZEMUOAC=wNkhAboM!IauKu~KxMgr| znIWf>)0{fz$!7~pE|1G;ZoAxKxE=dx{5iMfo*C3cLU7tXg86bj{7Nm+4`)Q ziTloNyzcuiq~T!c_+j5LL)U}<4TAZ)ap^B;pB3kp>%)DUg*0+`T-ulXC0^Gm{|3Q1 zsAO)pD6|N&j=sIfq2c*to{+CVOCnJ}8mEk#&XTt2Ks!X=U-Y#Q7$_*>y}^AVgnYk@FZAK}+jL6MIc zrih&6oJ*0J{Bv1xZ^=E*Klh1l?rcjJEyEy9`;0m_h^^2Pg_>oBuhSrI`$qnjf6GfZ zr!F86T7Gg`;*t2|UlPBhBhP}soVtLJ|HMyDb6m`j)6R#L;DTT#oE~y6tJJ?qgPBMg zm?8f^Sh4PkTZLH!qf=HwOh&adbv{QslgWs@nl3T0&P0qR8nIV^( zp9aV4)`m9Te@=tjl3UTG2+aB&tNC}n+^E6xUqhiX2PK+kp$J^h{IRlR?Zl_rE9zMNv@jqE`&XfOHTv z?>Xc^Ks3omZxJlPfLsEIC?OO-R0I+%fHdj7NKp_G@AsZfjwrndgbRuh3m_;qP$?q+ zT65-1)-mCE{yb0Mz}_>n%j`1q&YJz|iB~?h)00>JXREa5IwB!sloUE9swFy4DgDo% z&s*yoUpUozu02#4IwB?m{P|}zv#o41|4YZ}`Re9o^3_)?<}}bA>iFo0kX!d>H0$_i z+f^&O+WfcOOJdK^m8vVaPoX{6TB;X9d?_zvgPoySY-vmdS*R?Fvn5o*Ns z-Tc=}C)|4D#iUT_J_?|CX>Dz-N*V3-!)G((b)Jwuh3|b<%lE`+)#Cj=+FKn3?O$Jp zpQ$cmp}$N=p-F>UyX%_}XLTr-8}PvC->>X@u{}2m-}SAQ?-Gkp14Z|{H(vIK_uW2@GIR~<4EB5e zr_GwRCNA-o%SfT^^*yRe_kYFqE6yhS7yZD;Xx6rCpR~1o3ia=)-%tD0r_lY?_uYxC z;rp?D_bL2jvGLJbN)3PX-W#kv_RRJ^g9~R(bxB90FGJg_z19BpDO9@h)zd^LIef_c@f8#55_fh>(y;6D6DwClnz1M13!&__L zL4l9(k=Z=~t*WF|@-Dj5jFLhep5P;GE$P0$ebyVH zTaVp;e6i_6UoZ-vbE~D)-FHjTwraGaU`ra7c&m(B&vx$xen-XEsFrl{lsZ~fcddeS z`oE2@%ILmZ3iLd8Jx34u+eFuopzb&=N}(kkHEVU>Z67dJ(JGa$)ZKU2YyP_(tHt%4 zr8)}z`2a7o0oW3))qRt?Kj%8PO5J_86dUb4E`NRUHa3H*uiZE0`RQXb3rzJJHXA&j z?HAb5u7te0Z&GykYkmV8zVv1#|Dw`pS3-*Jo3%Qdv!x(^${|HpLW=I2wK{vSrC=Y} z7uM=Z^qaMGL{d@;E$P0Mn%^l&t3rmhgmtPDfZkkRdpkJjo&x~0$= z>`Ex3`(~|fHd_j=4XzRXm+qEctK$FfzR3v@bl4TB@hs6@RH?h~mZH;ip_s=Kr|xz; z*@J~*l(o8ju#>0My;j+;`Yzqp`G3mb8fhuK=Zk2&Qg`2rQfNsxqO8?@v#&8$)~c>0 ztfkc5cS|8XUz`ny@n1OVZL4%XoEPFLV|4Ml>ca0Of$M~ z%INNlZL55JFppQaK8!+Zx#nAIV||z=b|s|lzRA}$-zj{37)4h?itd{fuK7;k>%%Cz z5>j;Eq|gybNhn6Or2AHCe#f5Jlc6nPovwxa?)SVa(cZF7HwyfY-N#0^DFZ`geZ*sCTisztFV4cNXM5(*)mZFt3 z+EL8I8nKz;D&;rJ`!^Y-(2`Cb`F7OND&Azee(>ZpzFjSH?7mwHzbzSsj)|X^M%{fc zN}(kkHEVU>Z4dl@wMfsEy8CV^+JClVwYZ+MTt}flAK=CNPB*$XH*8f$(Q^0OQrGjC zTcz&4TMDd?61#&@U`<3sO7~3}SX~xH(vB5Y?GU?zQFJBb)qS%TR)NK9v=q26Wd3EX zu0+3C3z~278Z8C+Qx0o&CHl=;(0q&0XernS_Jy^&68&bazP2lcmUQ1r&2L+^U8_br z8QK!o(bn3|(Di(@DlQMkl(R0^!lN_WgQ)n{^)ikr0Bj$(Ty~}?ashG zG2^q_uWU@TRyUhQApfx6gd6slGPpxfJNP|rx3!xmHaye5g#hcF>x^2*T0i{!1``ka z@YVKR@3YpGpSk*)#ZYv6Eh$E(eYD#A?vtz*WK@fn0SdONaf${M_U)~*?`YL1SC+Q@ zuXm;9PanCklkpn;Pzv;EUe~9$zvpu9l91QJ_WqW37tw9IdLl zRw;E`xBcg6)-gc~gIdS1PtnaS$I2yi&TK|6kz3X6oEQUfySLZ`Vy5A4qqbkn1@8|Z-)x^H={|Ch=N7v7ZIFZ>h z*5Zntarkd9?@@p>;*hPqT(MZW_U$t4yD!6gYtpeM=5;%R>OxSM3?D_K@Nu*6*PcNg zcb!3<*}e>&18P6;*6!>GmpIdw@N0DosE#voM=VK8Hog3~c z?Bk;I;k9hmII`>uYrXaib|<~G%KGFojM_S2onSw7Zk4(_6Qfn5EnR=r>YS@CgbaMd z`C%;q1fH1xbQE;kXz`Llf}KnN-$Op#>&23-eM@UAG$uYPyJTud~9|0l=(-BeRB`) zQ=l&q>0~87ANK8|Yir(Gh1&dMdm?qzYWZy1x9UP$xBaKBsF*38bJc}Dg|D23ql*!3 zpo#Xan%}4J-N#zuv(~lBygTI7r*IioYmE!0G|!H2wOvQLPoZo3u3INJQ{L9@SIQ|U zMmbhGx2}CAPjw+E@G+WuGxfmM&5vj8Z4^4QeG1<*td`E8&P|^}R}oJeo*^8c*IrRd z;oqhiyuW?tcUNEenxosW1nZ;0`mk@E&1lsqd+z#bwXi-KtPlIf7&cfR_8k=XFbev@ ztOT=GVSU&))<=c)u^5WZYGkW?4y+bNy~6rf42A9t+z;7)QtK|!Z>eXVk#QLFH zvefh`)v{Z(Yg;v@FGF_#)fip#uT9~jTiM+F=gu(N(#5K^dDb~!tX_c%F~Xt^s#mH# z{Z?`I*k-nbv&Xf^Z_Xb3$nQP{b~lTTW{FaB_Bawjffn&k?9^6*`KYkY?OQdbt=s-{ zH0zmx*{rb6jl$<+F)~y~eV(nB>U3X5Pvaigy23g)3f0g)g=!*C8?Gw$R<*KE!Ly?q zU7j|acT(`QVT)s|oGg$p6-#*9aE$oP(}t^RQ406(Sc%KCZ=N>nV^EB?LM)Peq0hVR zxz+L!Sx6DB(lw!H?f>8U@VPO*s`<{|{?*rZ*WE=lzfYleHNX2b?5&@J_T8sY9p!u{ z?C+#do$gbp_NneJqKQssCr<2^7`Fy{iOEo{?90&IQneDA6T9ncQ(#1SlQ9`e9TcNn zgRZ+3d&_f{ec`w2SWw_&H0v48bCx6FquW2v!N0XqRjYNa=ql*TP#xtti}^4as?&W6 z)lnZGqwrO0-+c<7+pbpJ&MsMdYJX}N65jH8`)1Ew$6lMF@zHH~>iFo!j@oaP z>MM6Qo>@M+VVCqNbVpV_);;*ODX1ac?xWOw3cur6OSm?=JrSeM+iUy(g=93VhU+ck z|4-Zf+%>+c$0CBKTKgMa*Q(g5IeVN%j$5C?^~XwFuk73PZ7~$8;krI_-SlOsw)4Kg zk?AV_`p>3=yVsWAU|8aTHXK z`!c*AR?FLN-`*%JKL+9M*z-sCI_bK$O_1(E5Up;sG6uu6u zmX3msbe}@UM@RRy$Er6baz-t7eLz@$efXYeJ$Jpb?|!RP6S-HBial4YG>XxdZZzwS zRjn|!+xjx}Oy$YUvGdWT*Jv@VQr*>&USxEmReHPgdA5G|sxAGTV~?lr;JvUAK%8l zk#A|2kJPuGad~m^Ne7m?8z}V?`;S%!k8ER{Qu<)^uKL_Z_A6If_s&8~l#g>w zR=#qQ%UFJ^iwFChn~S5qa$xBz%48_@p-b;mJ+#^+m$5dow{G@oRqnmiorRVt->;oK zQt>axEv5NuPb-$)|Ds|?$Z&l%8A`qNxRHu~IqE4*0{@L6XF15w66MQ2P-ZLRTi}24 zI@5~xLxyU*QnL?~*~(ZRc^%?hu5>w^NXPI)OIaVzB(c)U53^4^@;DQ-+-QLZ04t4sqI?Q<171P zN{>KGR)v=Af)%B+rqnwBh|`27{uvriZSR!`U)4}VIzijlg|_blO;qhuYSrVEu7IYW z06FVJhL$K_U1=$84*pw1&hn6t8K1@%ryft)6}E zglgZtR+y-okN1Svx}^9<+M%BINPk5s1@BqBr?z*W?|yaP@_@NJ*0-E_PocF`-h%T- zs^5L@#OmB9xbMDc=Dy{5CyvwyoOExYB`a((QeF7IIn_aXuh45D;;$YXD;_)Mn&EPP zKd@98N}>KT#64cPf4Tfy9~vC=y8DVl9vZ2pt~sZ=@b}A1y!fjl)x6nrt6BKo{4Z0h z=k}djeFF0E7TwXe6mLFkgTa>nJh0RfT150bvbTL1>p#6yx$V#HDn`F~Z?XSlQ>t6O zbW%0Ih${6T--i?D=X0y8t>O?3^X}r_SMDvembR)-ar>j!7UMtszT&&TIIvV1 z`b(v@5P9ylTdN$m+FIqC{(fh%>$IuW65l_FS zbp1VrmMDd`7VlzKA*3xmCSVc`2QF!T#k@|9)_=^osZOW>6_q-%`5z6T{-w3$Gro^2@#qT}7(X zK&)@EZ@G81W4-Cp_x09?@>O}jj83?;_{^_H>i@g)z*70@IoMz4^;O%J$8Ps>z0o~) z7FwcbqOM@X)~-ITyy~E}%O%der})BUCsnuYKec)sdiBR6PO9$y{S@0vs8gKX_H#|5fKy|9W7=_L58AHK+Q)<|DqBeCf#52M_=6Eye24D=kqwp)X^% z<@T!Ia^LiF<|+3U|9bj_>SGsAwY@~CAIA>5!-XThm+X1>w0ixsr?Ork*h{oTPcoHXhdF*T?Edo|#@QJ?EZ6M^X9qDgM3x>Vu7LzNNSU zbFOo%dZqGk>)W{=90I+%_4W7lW>6_q-%@(rmTMMs?z*nH|FOOdT}7(Xh!OtYZN+1E z>|DMAEz$L%d{rLa0Db6$;yoXnTg<~=qI~st3SG@9?YZ8XWiHn)@4D;GLQ8ns@YLb$ zURN;gS5sz}*KDK(ADE!E z^v?Lyw?``eZ7IgBxl1{G&x++K-+6F?mMCB4loD&d7gTFq{on+>C$bf!B46c{(uJGs zT8u|uR(|@S33}_h6t>w-%Tz|8)G4vo?ESvzxt6Fr<%BH%o2*x_JL#zMnc4SG`1olD zSKn~HT1#((DSfG0I)Cb&)5`Z;Tu-=l>S(pppSQ7=Xf0jAcmwn^OXq2S->ckX)(aD~ zWEa?GOFcftsFhPn%Z{#Bzj<&}x#A^HPEfvDOIw@LUf@qT%R&ZQ#F`vY@~0er>*E6xSygcM2*ZO6!RggLreqViNj5$BJQ znb0-xcJM;GkNQ4xN>=JYwVB4`=xZjFJ7u&owRLv$j|RCu&x`qO$PPE zCD&;VzUNH80gSyguKwVq*A~x0hL$K_k9&4&;?fzn*R#>{mmuTD$?G(0zvV33Ka~1_ z9hPVw`pbnbW8D+}GW_$&Hx+liZDy$@%GcvaUB*Kzol^oGPFebdVH$O*lzue>SJciC}%>(X>Yo2-s@Mp z(qt(0hT}J!cg2fWyNoSP`tjHux7|`a3>jLYd^J)Y?>m2K=5W2W4k(xWzq^ZS)`s(T z-1Zuiq0~!^U;D}xK7Oss*!83zPj~_{?uQI5QNA8+>irmgY35*W$XEyc`17%AU%AuO z*P0BahP;Uj`?25SCl5}+Sj}(y5hcnO;}#eS;BnU9sQ4tt>P5&vKPE~)f*RvCap8Py zd%|A^OP_L6aeF%-QKEbqiH#^R@5kLMol<-NbADDk9}{Ihf*SK*E!3;EUmjOn4c(m& z-PIE1>+zQ^Uzu8Lhc)<2yFQ{s`KlF`(wtws zR6L6{IKN#Vm8_4TR{ILxC{Uzrw=F*l3N2B45GyS>rSxgEY9rqnRJv04`*9U|J_|j6 z88Wm)`C_HTh@^DGOXG?OzB6cVm0CwVrH3(t-Ky0R<%^XTGmBUFpe297&Tu!hL}yK@ z`+Bt#H1TL?;(^c-Em6Lzp())2ZU4RR461!f-CrNuV@0it74>h(&=TdVD-Hd?s=d>9 z23ZA?$FUz*zmW?MIX-U)}jq z`aE{glQCA@;dED1z8E*zckjba%~gA5J0DS^e02v$KX4j!JA>}d$`|u5=f}x7aXt>+ zJshi6OO&skL@B-N<#F}3(A@{IYW0*+YUr_?gI~wV$yNJsyFQ{s`Ra*^I~-2u?Xd>` z02z8(DqlUdVHKe^&U8D^^%k!8c8wiQiDx;^^n&NP-qn?wdllDYYti#8$C+;Dxt1tj z?zvoTt#^=TInMNg=Q;N(?g+F8l$v`k*JLY$XF1OF0nc+SQNAAWZ*glWaaX{ZUhq8U zp35D9GL)KU2iIgPgJ(I;^a0OvEm6MsrIAP*m%+0fXL`Z&oM#7j1jwkUJOjBSP=-?TET6E)W0$uwc$VW#ALDthCCb<3&1>g_ zXF1OFAPeIm&vKmUcAo1gqtvd)E`zHUXL`Z&TuYR%o~SAD zEaz>X=eeGiO0DNE-b6ZR?M$CL{q69zH}s&<-wt1ULmwZ1yX)To;A^kxbEm&uOO%4~ zuk`A*yC{6^nLc;=+qIU;gRi}z=dk_l4!-tGpF92SS^{5tLq8&ayHifc*Z869YWm#i zZ`Tr~U_>B&rfsX>YtQt#)87tXdqZC({q69zH}r1vw>$XS8+udQ-|paRujzBAzg z{JQj6IIiGxr@viGw1vtEzXJSrQl`(H{&p=<3T-WJuX~Nv^tqeAUE*GK+>{#e49`r@ z^tsdDuA``Y`xNlC*Yvs5->!43dZqG^*Ase0pF92STA~!HZ?LxSx~`_ro&I)}p{q!B z8abWr*g4bZPJg?u59O=!Qi89&rq7-JcIB&nI9<(nh^|~a)8|fqyOyX0p({A08Ec(C z99y+0=S?1;)jnIQ-eBH=Gp;tj=pEnr=Da1Ixyrubr=D?A{l8OoEBD&%Z}pNNSfZJH z(}h-|R*_m^DNTLwxcc+Iomx&<{dHMOl&^Ba8@b<@IQaJiMY+tD&`-)b$$^hH7T|Qg=&V*GdML}3sZXA1Iy*7w%eop&Punz zvpu=#`k}h3Rx!NiYYgiL(ev-2=USqCl~YQ8{MY^U@#y(m(Q~b()Y@7^?>w+v$yR+4 ztTX{Xp;tBa>SpMbt|DDss>dlY z)(0^^nejf1^}#Rr4dZvR2grZ&7Y_;0ChO)%C6F+UdXqa{kgSRX_cxW&R)AH@7* z#`|b3mB&~gMD{f8oq@4Fi22Ek_t6r@`XG*>;hjM_VHZWL4`P05#`|cAQfPEMB7_j@ zgP5Ppcpt|4AXcJbyboi25M9&o&cIk7L~}Iloq@4Fi211*@1rG(GVIG>tPf&-GUI(1 z>w{R5hIa;~W~>ilPn!15z*rx|{A9-aXf173pMtSIi211*@1rslg{v(@#4lof5c886 z@55LhM7uPM_fdOLEj`!bNO&N{sbE%ui;#kB*}9?Ncz;2Qfc2<9&2)Rj*VYVm}b; zgP5PpcpoiM3e`7w)e!50n4g;QJ}N_3k?J&hj#wYW{A9-a==xB;Di4{%5bJ}OAB*=< zz8+;^D^*uB;$9K!gP5PpcpokCUwh4Kper~fo=>jI%JY!t7r#^D zeu#TR!8-#_P40gzQOip$J$Qt1U%_XXS=3f>vCmQrhL+g9P;ka=g&@zH%(M?Ka@%{zn6vyP9BTS~6G zL*5y5o>h1In&^5}@XnyCNLQEYaZ13KWa3PSF;VMIZBE2CG>r0S@1nq$)Wn%E>R#)tHHGyq?ci8CR_ zL`#$};(Z#%O|&wAFR6($Vbnb$?IUlDQX|&AVVrntZ3ADDi8CR_L`#$}Vl*1YX|ytc zFR6($Vbr}NeXSo#jac`F@$Rh*;7c-bCXO+Q66K3NG>lzpWdL7Ne+yCfjxh z8piFnGJr3si8G-LEm6Lhi-r*+tqkBxhQyf=V}eNgK$a>s=At3~pp^l9NkN>+L5PUg z66Fh>Y8W@u$^gD(&_&%V21}`-Qw?zxtqkBx3gS!{5w9i67bjf9IGt7o@FfLtCd8O1 zwo9pTJ~q(hZmd8-oC&pEOK{c(-c>o_wuDv@XF`mLN>^%?2aL%NzdRt$gxanp%2!7O zaeWitRS;)FjEVMEsde1oZ^sN0XF_e)66LEin-cIPHE|}ynCPr2wa$M^z?am-nNZuc zMEL>>5*iBcIkcTP6JktM`;=PsI3?gqYT`^BV-oA5$5+tO=s8v`aVCy2iPfombv@!m zFzgJ(nGj>rD-piBW59yM?n9gjF($ejD7Ee@xB*~?BhG{v6D?7`y7S@I_vn6^I1^$_ zbXQYq-5(LNedgsgaVEr=Xo>RG9XuuAOEPgLTv56^E4A+Pc7BvNKMFrTh|X%bIz2Y7 z;kx4*r0e%e{(P+RDKBQQ-U- z`1ui;JCrZ?D(Z48gZM<8AGMz!QKEdg=Tb{s8N?^z{22QA5qXuAFZW#Paw~)QM4TVl z&yOfkz8>S}GKf#a`BD4%5jh!@FV7C@aw~)QM4TU4Fp5^9e9;GDEnNoji8w!MKR+t2 zBzoeNFZw{NrOO~b5$A`=&=Tc~xgciLWe}f;^P~3jgBeInhEiiLD(Z6E58@MXeq=vC zqD1*Zr-*%Z8N?@YRdGc*Qp;p0U+5IEuP%f5M4TVl&yOfkzG@-irjONx^TRNTj?^+4 z$`?9Jq;5A>puqWIw1#byYL#c_#}Ma7?dM1IL;326*!fZ8 z{K$TO#3(9X9XC5a1~@-zKR;qVl&@p(Y((t*C~$scKR-enl&{XeogW3x57TxnQNE5P zbQ#1a;{3>deuP#lwd%2*9|g{jS}=+>Q$4;dCemdPpNR7#3r5lAL;31@wDY6D`7!kK zBi6a2bB!C|}*d?ffWleiVLw#ICQ@y3d=>vLH^;eU=STNA9z1t_M!heU@?~ zgU_-cPLUWzo)_fDJp*2qpnz8-@<9M=Id{i`I7RnaMlEQlgHSrez| zKFg4yIb^hj=CjPiDZ0{9RuMhp8g;IqucDZ0-xWGDrEi_u#1S=PiUy3aD^0G`4aH>Eb8Wlfx- z`z&MJm2aN{KFc9-ite)v{ZYMAdFHbm5~t`s%V>#Gz_%FsWmtLbak1} zvLH^;eU`C4l&{J&pJhRuA~A}}SM4ZW&E~T#h*NZ*Wvp|xsdNP!x~3+&hPWcNSk$rr z>Za+?JchK$L|PD6q_x!A1_GlY3WNSKLkVSKiyT)JCCXPhr36e-Cbo#UBDD?BiiQ{< z^6kq2nj;g`D1Qma z7vhS5aA`UOkJeJJQA)rRWnzAaE7B5Rewq&Rqnr%$lLhk=UMH;uoKCdXuuCPeMZ^`M zMGdhx98vIZI_#2ajA54w!7had0wd5614L@&1Wnvx_nO!u;)+zSFc%FGHl$E$Lv0m; z+6umEt1Bl%ZI#3p5m%(`Rf>MAfGNtv77;Z_q{ zL|l<-xc0o?4`PH7x0F3@sY2XR<8ezB;+E_;Nbc+0d)u2nF~W#jsy%KgN)TBQ6o`z7 z?4&6XBaFDE+T)g@7BR`4JYs|qx8%P;5+jVbrP||`q6D!R72=lcH%OIdaZ3f_mTHe% z3K>d)n2^Y_idX|+IT5!s^th!8aZ8QIEmeqHvfm&PcTyp4$$x_+Mi_BRLyudE5@sW1 zh9FvDeHp|EBW|hixTOklOZFS2@+C$XaZCOiBr(E>TPi$mDP$12+_kDtL5wismIfZT z6f!h_rnb=HmP*7e6&|-#A#SPhxFzOyvDMAh!MtlUi*1YjI+s5Ez#KwRD2ekuu-VCtHuOkJ^OhcD@S|Y?+0*2HL=1(54gQ# z=eAp3w$2gJ+z_SI#_s}Gl!+B~ToElgn-8T%+;c-LQ+opduBawfnCJm5QND=GjyE(? z0UtqkCbYGQ>QR}>}67ZK+1euE(tGO@yrD{2@sMj6T% zap(=PWvvY0ifUqo9aj`3$`=v;@eV;sz!ha;g&kMaFt&>_lrQ4x8)D>I8Ne0Q#0opE zC`y#CW=1qzQ6^T{aYYSd#wbJi0vFIcyYe+xwlaV#s)-eLTv3!LUzg|jDBy}RvBHik zY6k0Gb0uXcUzg`t0N{#hVuc-7#C}+b^7V0Z8Nd}~Vuc-7#C}Yaei*fno67)tpe9z> zaYdXDD^b2a|5dBIKqzElg&kMK`7jyE*XO@##|pTjnpk1S6;ZFOMESZNyA0rpGO@yr zE23Ui?1%DoJ$4zu71cx!IIf5*$4Zp1dO}hHLLn0??6@MX50jyM``!=WiZZdnjw=f9 zhx%j?=MbC>S5y-#?6{)v!zf>sXSkwFtgz#Xq94i^(GW2rhAXOx6?R+^cNrT+<*Vb? zu3BP+9aj|dp?nby5i@JJqMBG?#}#pxF&WBN=ihKenOI@R6@^|YUqo4ih8nJ@CRW&S zMcidftCeqmeE?UKi4}HSQLGQ;i`b7?X@)DRi4}G{4tJRjj}z3o9t~HNi4}HSQLJ<2 z>+)>JFkDehtgz#X;!PCgtNRM#cd=@T6?R-v>{rUy$IWE`S5y-#Ed7|r)v0`a+~&1w zkgJwhVaFB4zN>tF{%r?0Tv1J|u;Yqi*H^wi|4l0cxS~v~u;Ys2{7}BG$1Vf7qMBG? z;)L~-QNFInE`zI+PO95@ohyMT{`dbkF+{CCb+k`7VPPVV>!p_k-C8OosC1 z&dRZCWe_9GGu`ukM2YfsM83-)Mi^M(%$>pGv`vQc`SI5orelS~)ty(QnzB;p(_hSgGaP4_NLK~D? zwFjA1p^3l>XV3c)nxTAELoM&e5LjW`8C3g}Z-0FdBg`}1^L~VeD_>n{miJ=}SYg{4 zbQLLIU5}RcV*sqMty(QnzPvSeJ4RyOj|spE+s>f7fl}+fk`gh(Jkvez$HZ<2P`=M2YfM?-#rVIGuT>d)|+D z-BJ1KxodejGqJ*+m$M=A&+~FN#3u6h^ZpHhzII}TJufG3`nG4#JKs?NBis;;*zR!j zwG%7sc{!sNeeIn*`r3(jY=1weubo(7&&wGl^tHo}X#RGUmzbBcCRW( z+KCnRyqqCJDd=nOT5EYZ2gC|{Ue1^U9XF-6yqpEG!k(8i#$EaLDd=k_R@n1$hW@Bt zsXWWeIV4ut^KyokCEAm%P0d`FcOBCEjyup<#Y9vBHk| z3GaZ`QtFtGLDOP>IPS(*d#j^hn4e6nuw#Dk3-4rW6)-IgFhBO~)?~%|ykUMavBHk| z3Ezv>Qffo+WMYLK^Amh^6ny?&22etoSYgNfgeO(!*=3ma7`i4CD@>d)P&Dj^m8kA| z3;p&A%ugm(*fBrh5mvs+$uK{eSYgNfupcHv`Klhbts+*~F+br8^Hy1JU51TxtdGJm zKjC%K@zHTJ%nx;U;Fuq3qRqMLZeJ6D`JrCbj`@kzsq0Sl*xm)mzzP@sEHBKQH#jsu2p>sVuTrY=kEf93}oYv7t^(c_AWpMR@iXD#0WFu%-;nFdr&RC zl!y@qR@iXDTB5e0%CmO?YG8#8C#)qzN_V56oa|kI%(y#$7a*)urO?*ey8tz?!iE#p z9_p+qwY>|FffcU(U4R&O<=dwqMwoGT{w_f1kLs1mvv&b9u);%s7a(R(DOBI=U4R-` z;eo#k5HfTX^|hTCVPJ&|e-|Luhw@c<_AWpTtgyx0DPPBY*sZU>&WRBQR=DtY0b-qd z^p@?lx`HE@MfThxVOx5R1KUw~Zt-MmPiJC;ffdf4TZ9=ltVAs@we%tTO@3K<*S@5w@3l3aQ56H zAzk^Z9$Rh^W;`*Ru#S)V;ds00Mm=)xWX~-!kLNghuH&QQ7I|^9=N1XAR^9DuBJZKp zE6*(wt5esV>M`=3BdVWRVSkG*tUHfYv=(}-qJ7(2bOo`({uUk4lD6Zh)d;)^@tl6k zAjXSWVSkG*N|dih8@dc)ynyvG0&hZmt@nc%FJgs>^U@OK>oJ!ugBUMjg^BZWw4}*UYGS(5s@< zoC}U!D}xv>VugwG(h}wC5ymcq7%yUliF|Riq{&cf>J)XLl|hUbvBE^9Xo>RG6AlrL zz<3cW>~GP~GOETuI!olv?NC z-lD6C6{fcLN`$ZDd3~&i@gi2(-=b@{k|;x|Rgdj0x|&#F!3mo-C|_M^_7+_xR#duD~ z2djx#VSkIR;Y#9IDYfp8_7+`1tgydD7yGXARZpS4MOP3j%oU}(v+~t_9{m8O0SJZK z-+T!z(Y?fx3wCNpw7SJ|YAxO295>+=5U=&(QN4-T45TD_1z7Pdr z6k1D9>J~Rae1^aI5`JUHO&B#JLOV`@o9N;!iJLIJ(prv!Flu}Ah4>G{W{?kS+C93( zf7o|_-vus%_>V4Ll=u&m!4c@Fe!{2;~8B{IN*$gC77t2X(hK-MEyK0QR`9hRX?QgyiOJo$< z^L{_J{=uyLk+Tl22mkesfo9o!$BiS+`>#K-x_tQZR%>jFtf$C3`oxdv-<|c7-SgnY z<@3gGePsgu_VBY?MpCWy>0eK2R{Q?()jMG)AmaD_-Sdk_ET5;m^Q8$|;^S6vCsIx+ zedG2b&;RE5yyW!{_b3!4q||sndCq?MrqdrS_WSxO1A5`%HMb10nsM{q2_wx?znEM7 z5PeGN@ma^@_5Oa};Ey}Lcc2+tmHICHhBFbIuKy7!w*2xj`D?$tXRyZ&s}Ho~cTbKq zCm{>%&rwS`rSxu$?h{`>xPJ6wtM+6lg^qMeYc-gU2M?-`8uyNYmgwB{Wz0Ex^L+VU zo0PjxTVlXp-r&EttiWzf*yuiZ&gAB=czf$zHXoNRu}VH^w~_L;OCO$~wcO^YxE}iy zZ#;g#{N1x2Ex!Jv)do7ED(@}FOl{^u_MxUF*I&6`{>ED#Esi{Ym4TM%94IGPsW)$) z4_srD@&gNV(cFyN>DjoC*7ECNgLpeacH)y#b^9Bu4jB_{NLSZ(b$;-zP@O z*S)&yn3iatlv7HRU;20P_zQcN`A0ibMr87YjH;8d0qol6e|WyhL$u-CbBh^Y|6IAk zPj(w~%hYB~YdwZsYrp-$g-&q*D82`Z1()qOb{c#yw>*87mAJpesNIgXZ^V9p;%rdt z{L!7qv_$zTC;S@z-uZ*io_zeEv2@e583l4cG`VROSI=YBGC4^=hhtEy?5T3^D(cR4~%Zp&6->E zK33a;;sQ{tzT?iEbNWlHL~AKEehmi&wdBvY?lz_+(2}OpCFPXTnlJskuAzxn++lhZ zGL%9!KcziD@faxPL3g!8HM}q5f6yvw;&(3Ek$M$*gmrFoL=g4z-uXjn$>jI$#5s?d z(ppN5UuD*qKi~{L4J}d4P>t!&$9B+mj_yIwcGYmzd|hdH9T=tMxR`qW_k&%I}$CHnTV%EnH;`;2mbjPA=*(E;FmGWeu4WAk&`yMxJ6Y9?^n1jl@IxCNozR<%XW!A z#T1P0-XEV{AF%A(2RfoE@7R%%>Sf42#I)qk2OLp8ddl?rlKSlfEzvnpPWa{L)IG}0 zw^=Tqd*Z)%hl}x8;bN9yUjuUq+F1~(;v5USxsoEHrM^d~VwLXSg{Kl<6-nc|Yhl#Vx6Sv*H`0x@t zjA~9Es)>>@_J?LeI5?y=K2it(;PN86!IzBYf18BV$^NqsiX$ zzU#O1jYWK*b;NDCDbEo4XKqAEEcqC8d|k7 z=3Mz|Ep2T|oITDWXHa{t{peG0KAysSd>b>UBdX)0^90WwYCj9Ak6;FM*0h%DTS}aZ zi!dkOAMP-w`lDLXr#J?^J`24+7W1Lnr&_7208x_|*>M=*`!OH7CbX8WP27F3V!3j; zYPnN#h0+@3isj1Xs@1u{O$NKdHrO4m#Ll24I-ANVCECrfpG(@#d=&(igPpasn_;_| z?M%BFmWJETw3}f+m$aQ}H^c5Q+gWS%WzcSh{an&^))Jls-0NvOE2orbH}gcG?W`2q z52Z%rGVEs9&n0bV+Rd<;%y!n-p=me6#`3e4b~EhflD0G7Ux7txxrvmTb~7w7x1DJ> z!+tJlJ8KE;W>~{!J1eJ@Xg9-tE@?Y!iBjlDV?JOv!+tJlJ8Ox~jdDtfb~Ef}vz=)- z!@e}z8PPlOPBm|4ytA~nGwo*B&t^MoE&Ntj@ixP~q)$P+8TNBY+gV3c<^%?mlEw}*v}TkHZI@xrVo^dKQntwYw;%JQf>yMsVJ+b;r zTWKw&PHCkr9xXNo#dG(aF{UNjC*_1VvX}1}eBkn9$|LqYe{3VHgG(gX?dDVz<*z8`F}X zVPARoq>*Z+_q?=~&J#|Y`wy<4oj{Z@g9NnYPom#08Yw**9 z>toULHPH`kul7U7Fr`~xyl1ch=HtNcpWho@)fk;8yr|=PbIBd}g@Z<8!N@?Ko0>cJ&vx`s8f9e1S|iUwHB6t!{yB_5STgs>5Hn8SCS$ z$v+>gx7jh}=a1WAs3nJ7cVe~foh`L;N@?5Q{JJ>u#(m4(7F^SlamxI;)wbtMtu|iz zM?HDC>HlFteL5`F`t-l{=3Hg00NdlcH)3tB_9L|FxVg*ZM;_a=eE<1h7~c22_@%xT=flc;h&jSPkGZ3GR`q4fIDElywb{!Sn@v0_ zD~0k^%}?nUXKhg5aa>W}KXJ`cOH?bB6Yx>nZ!$Riw)=}WANiTAqo}o1$FTb>d0uhr z``%yPvGKa4mZ(-LC&Zqgzd`*4wCexRD&?!K(tQP|!QER7cH8fX;<;1y&03=Jlv7I6 zmpHF@7OlD+ty1aQD%E`G)v+rU*Z=OR!QA_f%vz#rMLDJPr@w7lzV(1j%QvUlL#_4K zQ@>Wd@uiR2{NH)aN!9YVO{p$iom%qOyH_v2^11EH3FkdErX|W(IU!2#_KnMTp0s(n z?7>I%Wb{^-$isd2@n09egSMXxZC4qp?J5tsslK>uzHGZa%PXG#{7^Mc^;mT*r4Q~u zt^O2rcOG92%$dq~f=_rprOxAUZh_8mPR(zEStw-V*6oZ8WaU%#eLU-@b+AN8hf6}`du z?V#rG20rIjLT@mAyfT~i-D(MZqc#1aKF?O7e3cV^qlYHKH(Jv#s(iJUYo)h}zkT30 zkea`LXo>5w$x}|PCgS&rn!inGOSFYLB3QMU4|s)#^a$&S>PYL%roc*o-XN^7bAs!uU-&JpElcTKOq_|`MW)c2-7xw+SmRQuvS`iR{{ zj{(KZ+ospMfkI1^LR*X1pg?iJkEho+EPqC?A4g6dss4zQ|8d;Nl@m}9JK&e4m7f|s zf7FA!_Uqrx4m;gG3UK!j=lfjsnwqFd9Q+7 zv3d&CC!5kcL9x=k3yMu9pFXBOUFCcBV5GVU7RCP7^W_emQ67B9g5vxyoH3>)%2zq1 z^rIU#EBF7%rseYEj~>&OXbWi(@tkU{qQgM(8&JHwVD^}ns3%=HA?_766m2QmQA(k| zAt*IGEa>_F+_j*10sYXnYoD}*$Y_oEI1%&l;bYGq)A7;Xs`jL`6y|*U2d3A1Z+J#e zOLPYN6z_(%ue|4S`IX0x7*icpE$Qpk-(K0JSnEx*%Pl{*)9~&8wNG{2j+5-3pdPQj zkL>HOys13?&pVed9NMRt4o&1=-ZItuh4>OsoCJ#X58G*|B`QN@BR>OblWG%Cuth8- zU-gSACuC?sAAXF!eDHJQL7FYW%a%cGWo5_P&--3#pCN zL~XD3qp$7HZF@|)#PpvHmU(KQAuUGURB3ZAyWL22%Sv;q!(emfG*Z1||GCu>W^+Eg z!7=61AO88^H?QtC)Dl{&yi1c>IUz^<8)ud4A2qW+-k?ID>qs^)EkZW5qJ8Nn+3Dz)e&c2NK*Z$w&A6qY9)LR{ul|uRU_uZ|3wPCs6b(aiBh@GU`ie+}JzX_xQy)}ZQce?HtBl^N-z_jdP2 zHT0Of9o@9CQSR}|^mu8B-t?6dvcurlcEmJf#xpRMftW|eGcc9`_mqb542)&K{ikW; z85qlen1;-F27UKaYiSD+TZ>o*#582aGiZtX_Z$AkqMQ()h+hE^(~ud@pcLA6rA~>l z42WsSjAvjh0}*;endd z)mPO%9ce`4!WKO2qCN5@-=96EEzuVG{h{G+o+;6?gN2uA-Dyj-g|zIjt2V85N6QWt zUZ!=YB}$>PfgXTm2MaILy3-O`cG!m-T6f9`UQSpNu<$aiJ8cy$JDdm&tvgzFI4PRe zx}#+W3op~Uqh*J)u%UIQYadI_fFWPJ_LcX{+f>>3sAlE{7)W3r##^!4YGsaXRO!3&@x8IAT~{_rP$~ z@2_8M`1Wh6A8o(kJl?O=C)4-hO!(xXj)XJE=_ZQ)DUcb;19R=kS{V3QE^)0D4%KK+6 zOliS~jwrABPFcKd$z^M8yVg?bn2!PHLrc{ArJPdw)rEVN?;H1W@zz5(D%4M<{;QRq zKeO8NuWQ@Q8Nb~Ns-EnmOND)}~ym6quKq4L_XTJ^a{>NyxI<*V|v ze?XtL{V2!K4;@jRoBn+G8Z2JG8dP1<5!I1~Mc=NE!Esn0s!O^)`r7WgTT^#+rRoaS zwE}E7qIVG6XK{Uc_UWC$ZEBxEj}WrBJ}uF`OF5VmigJ>h)0gjN4@Lfq3-9j&0#Y)w9l1ON;}Mc za&YDON9WJI@0^|tJxi1mV(u=PS-)wAS@}zEIBlrs2W@j$Ee-8+m6y`Wznorw{K;8) zXs5&c|>2 z?V-+;j&6TGZhY^iWwpU(`I|?K4prk+GgM=6FG2Ji;!-UpRkdB$hesj$uQH5BMOnTfF127xs@C#&NaO2~jxK}osEA9om{j-g8DFjC5ynozcvQrtT1={zxF6Q2l@ns4 z&?>~G7K}+%zFJFL8&SnIXHa{t{peFL9+mUKm{c869Uu2hS__f69`UG%OU)9KYCY6i zstZ8Hw=u$*F{!FQswI62#-k!GH8UnvwNJHDR{?TaU_~J=)nZb0O=vA$Y50Y=**w1v zF>yPeHhWA_ZTKZ7(0TAJ3YH9UYMJqBj8#LNTEn;r#;PHjtzo1EBia=ChWpj6`(?(& zF&<8Fa9T^LTM9-yG15s(5VO`W{)2IA$|)s8wq-`RF}h7_A+oJu^a!Kd6yXRQrX@;&$hL+NDs6NdBHJ<}+!)=aC5UWm7-_@kHbwA3OXknYjBsOgo0cewQaK^_ z&O^KBNr-T}1JP|tp)%l;Yq-C+w(}97$cS+J-xH1)(-Qoy8hBUbgp3a82jkTktESSm zRXQTT6=8H4uf|w4Ezvp9QBMi6iJ38qj8D{gRvlCA!JPq`_*2BIZSadDdl*HnrPO#O z=5-GYXs^*WfSopxw=Y^kil|~d2ybirog2B3?mn;JU6Hn$BC24gRlF;b8g|-5-s$)a z`~0eN3fgP5akNDFDyNiSrwwVZ(N?=@^(WWjEt0%wNlFU?F^2j06p9AZ zJ^}LsTaYqnt7(ajf^xEc)LlQ&-oW!IUX2#&!k)uUt9j?;eOKGAwUpZCW7y4ymY{{v zTjhj%$+(wm+H17c6sf1!KG(Wr^-l$_c-p!}g%PMq7>c zcsI|=SLLMyJFTX@M$1b}blj9vO0d(4jzV=wH3OUkEekuXq@6=sO_6iz3#Wy;u;;XC zX|K^%(-P&YoDky$o0j$(Z8a^?--=Wo-ol1W%dw)ZrhHYN_7AZius7Kc+G;wYIye3K zps$2$khYrYl8&g3w5^XJ*9UDi)g@gYeQl?Yq0?Pmsk(x7t-un#-4IoV&G3j6^Zfen zALggjI|_1n1D64OhG8?bL~k|932(jtIRJb{;du?>6+YrJ5GUMtUV{p;$W7!mD1px~ zYzA=|h-4HbYAsgJ+&?<&>D$paed{uo+6B{ZMMlYfu88QF~s4 zc+n5o`FN3!xD3RlcfT6|mjQgn(DNF^i;hHfAfn&$VH1~u=;bEz8kE3i3_Y(wl;HHK z5J%m3UW4Fdc@0Y7GYZdZ5G6{XBW-yNO5igJ&ub8KK+FttU-LH|qDX+xu#B5{u@JZn z;4`x4HHcR{9Vcp|>oF|$OH)e3WdNU%J+DE$O5!L}yEFDFh|2&zqxQT8F`~qQ054%# z(}~MK+;$Ur4NBlMYR_vBB{~N>Ha6K( zT3&+^_>98y8ic;8_UTC58q6K45t6)|hjACWIQYg&EMo4+~K5|yW%fDNB|ME=4_)9PPcbk-12?+xQ?8Tqc%Di0ZZKYVmv z@2-CgR#^YCq29chwVrYGjGI1ho9~K+cq&pu+?g})hgI(joWG!Y_-O1wOGw&d6lr$YPZ#5-_^YY za}(4p1#Gq2ZM7)DoL8{b8n@Mgli6w|Y_*}=YEcVgRl!zk+*XTy-fXoJwp!t~T9haS zM!kZq)`YEA!d5HXR*MphZUtMdaa%2RC9~B^*lLB_YEhzRMqdVOwGy^k>9$%>s0_V7 zqy$^7gsoP(twyZ2-7NIn)wA7fwGy^k;kH`zLtCXMoY`t6Y_*}=YB5&2Q|sKAtyaQT ztKC)$ZP3#It01(;Y_$@$T6SBF*&$5hw3bpM3lyTY=Do5@y%iz>J(jQGz1`!w>|4Dp zi2iKj6Z4-C73Ps(R!coBeF~2w%Nrx2QA<>Ya)OLD&eABf#AC-yUf(D493s!wdDHBC z5F*b!+RSRHPo__C3nn?+U)>6KG3i#VI^FX-2J!HU>%B+RP7oK$HrgItaw`b-ZaDRKl zQDsZC7ATpU&MDA`%sde8Z*Mp!q|jRE19SHY1%GXDe|wam*A3^I)EJH6Wd8QdJP_`0 zk6IW_X8SX~m<#43bQ$osXXb%m4hYOeLwzD&t)+KgL{ou+c_5erLQC|vteni>o|y;2 z{p}%LYiXa%-=4cH9y%u4k3I$b?KU6oZ;x@;@xdI$Jej{eGY^FO+hcCE7Un2)!Tjx} ziSBO?jZ-b@Q^4O|Fb{34+3e4YLG7kiEK^CYP5((Ezw(_axxpIgpE_WjZ?wKY23zPbiD1Nx_7}!U2|3m8>es^CvHf3 z-yuE~Hje)$3>&9}jZ?Ud6D7E@hCIConT=Dz#wpy!sbJ$YZsP>C$}=0MgpD(F8z=6G z#0bO2Y23yMPG;kjuyKZN<3x$x6Z>}`*f=F@oZ4-ixV;i13>(LO6IOX<mH)BR%>KWBvQSca)T~-w>;oX{A&R0S^_}w9Ml6m}Y zP#|iqAA$0ez#;!GUg*w>B?8-S^RFn zoMaxq8*{5O*q;x?@7Byo=JC6sud2s7(w6(P2L3gB?$3Dh!TtDlM)~g|_HDU8nbk3S z?oZ}uYOWNF)R?B}+a0(!>nKLsJQ~mp5{&+-#S&6<-;kh)uRmATC$D2K?W4vjh ze3cV0KW!e!Ol-K8fMOyd(M+D_hjba9Uo?BR(0BzyYbmv5r(_P(?Aa-Uum2WeGKh5t zR@h|_L(kFm+@Ji-)N1)JSoZCCC!K;gec<)8=l+a0MzoevTkcP0h|Qk+lbK+Rum93y z-=3+`We|r9JaYEjpCLmj^yXx_KMUj?$e#O?xoVBC-jMn-mq-H1jlj6$qti_=u;q0zeJpV>2dmTZ__#NYYC9WnaE;ds^Q;j1ic&< zcHictcZGOo_a`>=rqBba7NpvrxR-!}9zypg249s2F2TuA*qOL$Vye-ihMq^tP&-rQ zr38OsO;3*d6B|L{hQCCqQ-VLSrZ?67iDB`oJa`I&llc=1qJG_<7<{!Byi^UnVQj7W z6HDT%iK(W=NbeR)bT`nuc1rLkmc&&PQ>`V+S2>wKu_UgVm};d^+gYj2pO}fOCZ<}w z5$el8OXGJuysmQTv`kzzG1Xdvo;LK$u}{j${E4|kFRT7&Eu}VpVkWNI{fWUBGuhB% zOBu?^{E3;kYGSIj?XXtjcSmil`4fu{>8)d;W2IgS^K57O!yQu{o)pzr)fhwf=MLSk z?bUv$=0{d}^GxW;0xO8IgZ7Iu_A15>`tMPmx!$}VTB0{gJ30ezS$OW~c+nHKK)jGhoF&i2$Q_-LJ9_B3ql1DtOYWYYJG$XM9J!-2@Rmc* z9UUdG)8c(jVmxUd&`z}6(HVHl+H*%oE#fyjzBykpyKD6+h_j@<=DDL|L{%PfmOMiu zcXS5cvhdu|QKEC8b7Q%qGw_yXtEqJ5tMV*&bOzqC@Z8Zcw>pFU`5?}c_L}F84t-Va z(~-99d%4TLr=9}60rc+-^gebO{2MuylHIbVtBR7@h{?uB2I@|B{eF`F%fnY8? zH&yJ;x|a~S%=wAjR2c~7!gEtaiBjmkV!5d@5X^<=riy+Lxy(87+*HBIa#Lj>n1{5A zbjKlbnY!hEH_m~ zZmR6Lse(f9C`xU)sWLFnwdbaayNLEyTWGndGBD3W&rKEMqrKI6vfNY|nCHTCQ^nls z4E8CIn<^tWRq45@LaS9v`g(OCu+E6t&K^V02=#{hx%#jAUNw*3%^pJ^o(YfNHENIR zweN^M&mKe17;`I8zUsxZ7<$IHXU5R4xyOgcBZl56JZ9Iv`yMZ1oe?9PiFZ~C^}}eN zEQX$O`q^XX=XJg}k5D%m$|a}sm*<Kw~AP2#L#Dtp=S;uE1_SZyQ}xTYQ#DtE{{3$hTdfm zZ-5y3>@oCFqI{K;#n5NO&>P-aOLS*Yc@{%Yyg~LD`e?65$6HIZf7TCT0kX%?S6zGc z*S`LIIF2QI3_bBG9p9K69qGWBWRIZ_kFc(fzP3C5!*o|ys;+HaD=E?M%D0z1-z#sE zHs^kuw0k>$8KB>?js2j96Mp2{^Swq1@@F>mbg~vbpVR@~OD)T0hOfHze6I~##uBZi z)RvJn^L;1J_ZocZ`=-y8GU)B@I9b-y44?bZ^Swqb`g!TGB?Wg2?k8=l_zM91`a{q6 z+C2NpqgSy+Ybmv5Z_WI*!SlTa-@o7&hfV(d=v9=#UmrS7K{4=ruTi2DE@L98En8^j zYi6GBmHn_1@2zEu@D_U32xPit&j+6Gl|8f)RxTM2gv?jbUp_6>gtDEJnZ=X<3#Sc&p=y>c1!gYzvc&-WU9wN~H8;qP61 z^Um|V#xJgF6=@4wP2_uYp6``MSo3_Zv2wia4M(@X2KoC6-&pf}udxP|!bicV?Y*Lm+y?d=z21=3 zK6k&CQ{eY`M)n)JMoaWgt(@Q&-S(J_e0@XD*ViClU*q}u8ro}~udktf5c&Et^7RdW z)8^}o666PKkgw0Ek&i4mS-!rEe0_!I>x&ZR0-&Yh`T9bhmai`(Utj6@ z`a*`TD3xdV`ZDtM6`rpzWT>{QJj>UYk*_a%zP`{nz3-@wS-!rEe0{a&>x(t0y4#-* z_ePmVSnmnCR z?htwJxI1F*_@=PGiPQkIWVk!6<-d};&ytuszA5Z)A~9~sN<7xYkYPmcb)4)?Bu1oI zMmgo>5h)E%OQp6qk!rpv>~A79d`I>I_;K;>PQ!O=8Sg{P9r4z!51E)dzA5Z)A~k%a zmk~R}+;!B%+!4p!;_isK`U*qCl^`Z9>QHdA=!3+@01^&FE7Q zbH_J@{Y|78QI$u`9dHefyCdd~ZwmXHNKvA5pmSqyB4xfQOx&GHSH3FG-bAYTrm(+> z6mzSyrn6~pA{Bg7*xy77tyb+Ly0IH+dmAt#7mLM(>*=iLxknhAR@&QunX%#iHX!4W z?WEUQ9{uYSjHhO7xW5g^-%^dje`&IBj~#Xj#Dp`d*s^$NE#=#%U=9|>hWp!qA;V*~ zjju<1yA0<1U~IU=gw|`PT>*p+200a9I}=8?{!A) zzwp|(y$x6(7fbfH0r`8am3TzFQG2wp%U})`#)kXbfQ(Q!3azF4N=nSZ!q{+s8<6q; z#>;<+HEREL(ObnFEXc)@{cS*^1dKv!X`k$EKt}dkCLJ9U?MI)2^TF6~e;bg|{3b)k z$A3TfRxt+)a6k5xF)prWc9&)kN{x%@v^o>Hbq))*dEQ}5Jw*eWOZxpJP z{`;`YU=9}KVzIbzT@zYMSDL*I$S79J{H3RX``FFvtaD>;1D3?U`rCj+bC`6UXXRvX zpJlv#mi_Is*spXaq8F8Cdc1v>k+J+JKTvw|67{Oz+i`;>xcLqx1Q;*e-VW{B~(&!U8AL&Q59;!y7o_V!u93^D%p zS?tt$TJ~k&?XwbZpJjjhEGSe4f63roG2T8a@%CBvx6h(PHKX4u{`P_QIqYo?<)xaa z)Ifj&pU9jt{`Oh)T>H@AZ&+tspKT7W=sp*@ezn9;Z zGcz-%41M8RqI}hZV0k$+bIN$`&t}}auIX}rvW4@ch4Wf(l=;DtQ^s?D28H?-v`?)J z=9KZ=pW*k>QJ@dLlO6rA9H#1fQ_qC=&su1?KQn!bp8GS}uC1Ti*4tFesJcL@!X&MJ=;ojhf`a`@>yo)l=0l3oM)p@zADc$ zd1mI6@!X&EM%hlSw~H(!E6Wq8b;QxNM6%(KNOs+U8(AN~6kvCfQ9^fzCaL&RF8e3g^E`I3Qow)jNl zrFS@`wl`l&V4f{LQE$b1Z}W%??+3BYj8XJAUl?a;B_88v-^wW>0S#HK`lGd!I-)cJ&S;HyMzg;&8YRRIGD8S`$iymk^6)#(9~KmNXEggeqj4is8ANOX7iXwV zduO!7JEPg(84WGb`Our1y)#*Kz>#o-@pndR{m$qx|ITP52S>$SX8fJe zTE8{Lbi5zcV__zcbpjkS_Vf z-x(e1cSeW#cSai?-20GU{GHKSzcV__zcbqKptX}<{GHLBerI%;e`mC@YQ_)RSp1#Q zO20EY%)c|*_#kb!J0HJZXX9$)z0a=?SZDTdr$^>b?r`^(ldn7DvZ;^meEj4~ZrNgT z?X@qOy5YHl$*E`bktTz~$`Ma@t zMe$$@=}uj6;N&~M-pf3epSn`D{}Z!@S8Q`<&4^6&m%nh}nt43*wR6VqIdNgV z!@Fk>*+RN&Z98-FiNiL`JQhsr*Ehd;ui>^U-dQsa68+ByW=>8YZj^a!d+rYP*KRqx z-bFmvLb~_-v3X(cfHrb{7w} zkgjDg&&1=2?MH`S6rb(hbZ5;KfN0BLo{7hE($fpl*Vf{}7Si=xSa*rX?3MQ#E;qej zA1XPxvJmaLu~tX}({rd4EQ8&fN>qwkg{{;!*E& ze*KO0Hm=?v9&909+pujp@mNcCd*LllRyT+T*IJ_O0k-AD<3b_+EyUMk?QG$Ghm`a! zfV^q>bvLeNYgFV;H2LYPElK_=Np5Rr3+YlLx=~Kvw4JoOf_P9`qN%qKZkMIMOcuYR zteq{S%bC@Al&s`lS;>yF63!aYoc|EsBugL45^e2lAzfOiV!Nz;ds(|Ziq=Oo?Kp&Q zivI6q@!QMV*+RPXv=FuseS6ie;z2JWn*JEV7p14q$l?!@9Bd(7MvM^tS9-En*`pW@ zh-O>~A!xpL(Y)K**+ROEeEM#C-NDGw@~X`|=ZKa>Gd_lJxa@XB_WKj@U<>Iof`{;k zyy-G|)$7HB(V1w*`Jf-zdb&D%w~dGM5C2uoUD2#(j-Qd1fXF&u9C z>zXZRzk9*tkH0g0@}h$;n@UQ$@#I72k8FL>59_b~cJ`1hMEr5B1(W~1MTzZOUi90s z6+SU*xY2s|*S@u(?1Z^vefyp#PVTq!^vRbT;@E!d^XrX0dHuEZfe+0dvgPAzojCcQ z%O<*A9&^|KdHwS*%orZL?XT<4eg34$&ulbpa+jkon@TkI5BlChKG%dB^YqouRXZ2#!|wgPvnzdq@eXH=;v$<2JX}3s0Xh zJhcC-npz~?F5>>zuRr#9eQkZ>?`ID=x3nwrQ@on}+p#aqnl)T*T6YGCpuH(yGXL8n zZ@BVD^^?*SdC-e!)3WxLZ&rQl%XixFh?^URw{palwuCeuw_5W-sz%#f836 z+;i*UUoN}8{vX8>w!Chy>62T0^u)2`U%=2d$P$6mC3b@}$cu8)4h^vRb#e0+>0M6;en)t}$qefY0qcB*Er zc7M%Y990+b?|=QU9xijm$T5l~5>jtOhw#j_J%-~e?_8arSVAq5ZWnRwI~LZr-LT@= ze8m#ZE$xc@LRjU&S;L>~JT~^zExR*F1no@~TjAn*k9Vw6|6IBv4|)-8+IzUIhF^Qz zjrEJyzrW)jq)UDwJay~w^@nahuD)m5>>=rTCGd)1Po+1j+Hl>~hDYr1j^TS0OW49{ zDtfSPvpRpH;bB`nSC78zp3Z8(HHtZMMW4&gsek{6&Fh6fm_6jW#I|M~9EjyRlyOKkup8Lb}YP>t>4kE~>w^!7BAn#N)X)oH4oSKUR;@5`Em{ww z-WO#aBQKsgJoe{bs8@Q?JvCcMm#09w7w4N-)dybi#MpPQo<01{TfQ~<#04SpAbPp8 zzc+c~7cQMhQS{$?>@__9+%@aTa8Jz^((RrV{p#C4u1`Jw)UkubW9~EGot*OEB@>=C zqWAi#?qhj=&CFxw3i}S{AGrV6`y>ZjNVj`#@TyD3>SOj9UpQYpPG8~T$pbf8Gx8vM zpDCA4e&iLGT#)3rUOfJC;Qk|XUbwqv3+Z-G8n(N5tiEaQ@sC_69%~+P$>jOJy!Zmk zL3HLfns_`ZU48A`HLKUOa>N$W<;jNXmZYl>9e?V`f>w@E^B~=E`+G=abPhuc~jk@QIN*?R-QYq?_lzpX3mQK^ z>1Kb-JnXd(2w|^fOZMQ1&Yl*Z^^0tZ3?JX>xvHngK<-47pZ3&}{47asuVoAAQX|T8 zO1sa`yRmX)ptM9&Zy~HDul>>mPmFv|GsqUw&7Kx#RwpL1k`rVljtrbNqB;K|+$T#s zQkM8>@n8$-W>3pJ92w4*wU5gZX?;Y~jzd^hUc2Hx;~zOrJlI0I^fc`(<+aPs*?;8y zl7n7EH2pCId+ly}k1w>>vW0XRF+#XbJU%mL|1n1fMgyWVzlr1@_S!WR;ZAJjh%Kbc z$QQyB($#5-qOWS@h-ay!oAs7?RPx$qFMML`Q|)}j7Shf0KWR@>zFl*EhE{{`xAPHs zkZzv;$t1@V+3q~8IQCk$kS~-Qu_#YexpIGDK%P&OA1g51y)((_YIK(&dV( zZ;=%lel+8`+L3{)CDB}Wb>FKz)@!=gbL{~7ZncCypSKq~4)TjSeMhgT;OOAUpq)h@ zJBtRbwY+bhNmp9SE3fJHTDFj`D^skM6nC|jS6n`!oT3&fg zx7V_Tboqs&ehWfT!E3tLbFJll&zyM>t+jmAHjsE|EwAjkUeDP=x~|W$w3i&x ziHFwmF|X+rHV{c1xXf3b3raLltj|jVJ=z6c)`iIu?+H1PKmMx^q9l0{8iV9xS z9T~jWg?}`3xt|X~YkA#xE#CF{Za_*QXf3b3rh7dnchco(L(p1Ydri03vW0Z1kr1?& z*Iv^d87M8$)OrY7%g4N?dp&0h>2hXO@hdCwn(oNJStFX(6N1+AF|X-f&)Gt{w9pW= zme-C9Ue9TLMAHjG&|1FGYr5BSwvaA8O*;UsvyKd2&*?=((;q|7TKMhxAJ ztNnu4bVmk81ER$b@k(p?h`rY9Ia^4VkxwUailScAy`D3w5iPwT?rJR`@tW@SoGqlw z2(D9Ptp;Axy`D2V6Rr8j`k}SF@|te1Wee$YB~m_7yL_+djtpF7h?X5=9n@N0c}=(1 zvW0ZHqN?6UyL_+djtpEaiRP-UN)F}ul<(^~*T-8&oaZ}dhiQH1`nV(4X}I!y%J)^y z^|6Hr=lPUT=sV`?D^un9l<(^~*T-Ju*S$%{c|PU)dd~H+#d$vEF#68*k&=FuM0q~t z`zq)9*g}N!e9EQdQ8~}2d|%JGKHkv6n{=G#QzoaM&JCRBQ@*cqu8%Fw^C{O9>2`TI z&!>D}&$&M5`IJZM``m!&?tL=O^C{ogbFPoQII1qfc|PU)D(Cvh!+Abs+2W`;Lfz4* zJfHG?J?Hv(vrWzj_q{IVOmRQ$0G#JjzAxtb*pjo(kq7xH!=gN&@_jMa#}%JV7T*K@9qS|r^r!g)UB`zq)9IJdMb z@(aOvKIQv*&h@c{2-;f+&hshXS2@>59`qvGv~qpQ^C{ogbFPp6LAvCpiWKGfl<%vY z>myyhpVOOlAF}d%%J=o0>thSw)#<@H=iF`Mp3fnD2FV-Ib^h4*xrfgnmBsCQc9UJ{ z{IT*mq|YGPLWIsA`#$MNu|(&OJ)cAR43fRbuY1eC&L4X|hx8dFTXg=|_t}ciAW10% zoj+DShx8dFTZqv4W8Y^yX;eCY?D-thXOO%-p11Dn{ITy7rW8wb{#f}O(r1ut(fMQF zXJDq=<)QP(p3fnD2C4JMzR$NDONj2?b+7Zsp3fnD2FYF=RTrW2$I9oBK7%9=oj>+{ z`sYz`gu3_R%2j(lhx8dFZ{6qnV0XpQ`D5jCNS{Hng)15PX(zMCyvpa0K7(WnM@UK` z==`zgb4Z^-vV{naR$tf5x}fqoq|YEJA@xSI>Htok(epW^&mgHq((NL2{#f}O(r1vI zTiO-*Nsd{wdOnBr86;bXpuL5l^T*2PkUoPX4|)-8T2*0R-lOMpNS{H{KS-DS^bOXG zZ|gp%%`2ZllCDmE`lZH)-mE?KDI52E4(T&Uw&--J`85xEunz#|y!?A^QbHz>O;aWJ=#8s|`%T+;<2hq7MC-ZRij%wm6 zSMRWebaTZ`=HXg6)x`B&A(X3vA`hZ-T~6lVS~ykjRH%oGEu@<(ZZZ$o!l@>%hkCfk zgLHFUPUhiSI92aduHIn_>E?=?%)_;Cs)_5l9xhh}MIJ=wx}40zwQ#D5t6UGq7ShcX zH<^cP;ZzgXbA?c@3W_|4&UHDNhil$x5-R|Q2LL~~CR zf@|Sa6W4P+99y`DBPHE#tXeqL#Kn3zawnSnLU1jdYT|mfcD9f%HKL5Lw5yu9%Jp!R zmT2lN1lPi;Ca&jtIJS^3XI5V|%1TrdSGgXJvqm)MU*Fxy5>*oyt(`5To9ou1)Czwdwyjz?)x=eB>NL^ICE^`ml4wd<+5;&6=;rM|5+?cub3^juS&*NY)%sDnraG@5O$+HtBYj(G;-U4U=bGxge)R20e%m5l>8)>DPCT@JRIaJc z>qpZrww!p_(p^)X*N>)!bQS0Oj`fL$){mZR zs`L8MwB^4#w&lb_>qq74&%Ay#EuNQ=Qk3zCFo2NLM!1w=E|gT0d&nRJ)#&KXDs`L8MXpwZOx43>(uBp!JM>8L!E9-1#Hm)BduBp!JM`I17%lVJ%N6$6Ywsy9V zuB@}M(71k7-j&&-XnjP}j^p~#b4_(#KN|laU0G-2X>t9iTvMIbkH$Mmm;M;nkDhC) z^ZL>FIqAwen}`wDkIFUGdHraj4Cyki#Py@+n(DlMH1UdbWt~mri|a?_n(DlMG|`fD z86V^N(Q{38UO$?+OS*isi0en?nrhcmGdhzl<9y6z43*2Mb1tL#jdi^{O)8hs&$*1| zy+kvpT59DoVm-C}%zj~CBSLRWlgefElh?YITDgom=Q0|){%TGYnejK>{iT~KL-P&e zuBBEkqt3aErbX{(lgefEb1tKy6muE1av5Vem(jEkq4&f|U_r1v=E{Eb>H=>X;eC68F5W@K4a;-7S%Uh>NKP8 z>Sf=6sT_IV)w0bQ%ZO{L^BGIiqWpf}^}MFr<)Jf{+BMbrjHT~d-F(KU9^u1j2H za{WYJ)m%%h`m0{9zjB30Y$4rT8IgIomRj{!u`)APZ}crK>E`;0%)_#tm~6I)0(S4LzWuBBG}Rh8?n zT<;TkkZ!J@$UIz2ttyLNuD^2SQEVaIYgT?_byYiN9aQ{n*HWwgs^=;TwvcYFjL1A(ORY+d%Jo;@pZD16s=tanh|cvBnTKnsRe#mX^;fRg zC~~+yEz-@E5t)Z;sa45Q<@zhvkrg=_bgrMsJX}ky`m0{9zjDP!Y$4rT8IgIomRj{! zRj$8sJzSZO2A%6CG7r~MtNyB&>#tm~5nD(%S4LzWuBBG}RjjAZ)fE`;0%)_p>Y$){uyO-ix;s#5(` zFV|nW8Z&YyUGj_dSC#6oqSvy8bg7Y8e^sgeDn#s&se^urBt7bk(H`nDv znPUA_rTVKF88~aC+qEm#Qmg)|%Jo-`Wsq*JFUmYzOYO*z>#zLV15sC`+w~9EQmg)| z%Jo-`g_ABlE!JPTGP9TKuNp5RUHW6JzjD=N^jfx%uJ|<(Bi3Jyss1WP21Wy-8CUch zZmDXr%Jo-Gydquct%-cG{;F2}RWH|Hxym!@igXztLvSs%>aVI?f7QfY($)Mo5j@sk z)vCYh<@zgEd6xNT(3<~dmC$`MT5(i=6}^@%q|22k)?d}CzlxE8s|?Yy<7TzfubHa` zQuSBSYuQ4&Tv22FRjvA~7#X-)63ultejn9yO?Cc0$~%ArrMR6suk@!B6vL~ z+L6^hnRs|DcTKg|bGDGKXVtMj@$g#inrg4-UdtU3%!6pJ5cbK$!yfCJ>im6F(?Yto zPOpWDhu3n~ROj!b`i==1^Kk&QF;tht%aw;mgrrPVd z*FZ-E^B`TX<&%Hgto=T!=bCD-=WHR}%rAab5WlpjTvP4!+-v#H@7lb4AJx#!{PH&q zUdvrmoxhK=9I=ITv)(cfujQ_(_IjS>n1CD+o%NP^crABLb^boe^ATG}H_!iMnh&q# zuBp!7M|nOX57N!^KbhvkYq@Kxy`Hm$bh9029$w2`Q=Pw$vRzHWt|HxR$C-!Ma@SOQ zJ!cE)a!0N&krWkNQ=Pw$vVTM#M0a=kUdvrmoxhK2cKUob$etD{#qXnfuBp!7M>X#Q zq)UGB`>4t_)%IGpkZ$(0%)@KBYpNX?C@s;{di*}Ba!qyqKFSdwYLRrkODi)QzmMv< zrrME#vqrj{|M-1W<(lgJeNCMS&T~lqZWee#tV#M#GdakKT}JTueN@ji)%p9VChC)J zp8tO0;kDc~)%p9VW@RB=u0-+ssGe)89T~XFkZ!i)%)@KBYpV12QOycTy4fH5ju`R# zsGe)89T~VpS0sir#CQ*$Il zxR%@%XcUAokw!6k7(uj`p({^T%T*Ho$t$cCp6qSsxHE{)Xw+iyAv87uBCRC&7gi1BlG1tcy zSCkhmba}XzS~b;mzB{4eL4>lB&1mD@36*N9$MW3?%^Xm>M8~@mda9|e^W6!J-buHM za4og-efjQ$#(rp5wEQ?@p*xQyuH6X+QKL+H|}-p{JVa zD&L*Z_y_5dU%We^QcZQNrzTy#pYzQ--ks2MzAxXM(D*qs1@z!}r&H~k>U^hD-xZP% zE0*~DQRg1<3^M0;vt9Z8(KXfiPABJgV+#>Jf7D4w_FA7mx~4kc>D18m`D5Yd^G8>P zrdZU^hD!^7u~u4MM8IKp_RQ_nTk`A(<4tBHN8$M?bR zisSP~*Hq^_otigDu4LpF?{unMQ=RX0YDVHy*rJ6l51&7}raIs0)bJp}=Z|Hy@lL18 zHP!h}r)CbQU83WiPL*q_^PNtO-buHM@cE-_s`H&rjs4KB$S>aMG~$}-e5X@0gGBiJ zvDjO@(`n2#)%i}Rh6lZ95o_1^qid@3olcE^kS_VfJDqCRROdUL8t=>}Kha9Me(v)} z*Hq^_of<#Sr%Q3gp$F@xTh&slraIQckrsL6`l9TEuBCQOT)tn_RY8$1(YY=sM<3Tx zyCyE*FY0=q*h0FwPAc4Mhij=_6PNE7b-hn)A>CYYlXvA#=*HV}2PqvV5u3O7ITubemI9CYes-Vb&=v+doT*HXJC4)t)62kGXzoXo?u)UJth^$uG|H`ftn9?P_ls7lsgCt<)c9HdKsjQ5LHs;Tbf`$b(z8hMazt|QEHxR$znp}=TBx{NEq_lwr5 zsg7R{u!VFP`BaOeT58o)SNVQX*C$3fh-Q3@_lwr5sqVQRjxD6il_B0QTC1iy*26J6 z6U{g;IhwzL?^SEw4Y=RsKDgnfT>lrRI(Zj+gHVl&|e?IXGT^UBxfPx(HTZ~I$vYWJ!C z{f|bw)N~gy9DT{~m|KsCw1{TZj)+0Rb?u7pxU{h@f_mqdfwZwiz3`ykSx3Zq>LRFj zfAMJz=Y4xKPhEs1KVq$qN6A;%XW>W)bK*1C#4h6WZ}cW_dU)%Yp|f^xsWy#>wdS8S z{?TR1TTzSY`Ufiv=__r2&!F_~TfQS*_Tq`z(h*NR@QsNwo3j?4Gf`xUh(W>)hO{N} zH>&yp|MYiU2!DDADwg9x7hIdAD1^of)6i;H_ywx8JIvoB`|-D@#R z%!~%Ux3+o5;hviB3Efd0{;z%evyMJH&bjCRpmpw_Y96$OE@Iw`KieRP=H9o9=wyNa zwxGYvhjxhkK77dh{;Y?O$r<4mGbkrNvE?gIJ~q5&UgF;11Y`(i;uRI?S-HyqKyhg>AC1lShno(ug!1n<(wQ8)5V+`){VBGb$ z&h{$PWekppLBhpRP1?#A?IoLPZhLHa2sQBcQO*8}`yfV)E`kw&h^1QzTkMY|emGK> zxYF>@L-N|vi)hdNe{Fr*60C#~M|1AmLi^SN<4TvuBGI6!VPI`TgBW;Jj7vUEDqc%U z4MGotAy+TPtED3tGZ=jsmAX7ctJ#IK7voA7!C1nG!?@B#FlI1k#Te5?FamHt$A}RT zgM{n)`3h^E)DPipah~TQN_2TJ8kp{awGJQgoG%s`3>$bp7QA8W{{46D9;4dBw|}gO zAEXp{sJH(Ho%`Xkexi3VN~FH&-)JR{;jx$LuJ*w3@j1^^eC{IBihNjXNzZ%7=j@wH zKrs5`Gp`tN^4Zk?4}vk6v8y|(yk!;Im(_WR(I+ApKjgJd^jUgj;QoXAUHW_yAdPL{8?Br3A^Q9h_Y84V^k-&hxqnF1 z^>0Mbx9xWyd;BZWYZvqL3>yr&(i2UqYklyKCM)7m{{L&HH#f*EdZ87x!h!`YX z*K2d+j0k#g7eRk!FM4yLUU*~)qo>kq>CIgPeUQFQf9xW(%V=(X%03wVLvI`*4`j!)j7h&)nMtiOB>~` zkF%-qq`!ejMT=uRr-c@P|2r7cerPeYw=RPA!}|b;?jjhSX;)eDC0HW8$g?Th@miJLFi%7x$9mQ(){w?VwNcS{u>OnQ=0Jj z?X}6q((YAy!|&at-issj{m`W5XUymj_Qvzl5cCi4t&858{sWJSyD+}DEw&?5?_}+? zS6biFZI|yEjJrfPqcR)+%2@MNJgsl(c18Qi?^IFKOXorRv451Tiv6Z!Te_p7{bcNRECgS=;m&;M_BCGTo}ZIL$CNRp27Is<)N79tW#{E#pGDB1O$5#O&ja-pq0?BXfa&`Th{%+ z7n)exwVsR_*lW2fsa~DLSV-Ltgb`ue=**5t&hZEAlrnv4s{xbnYDgGwA%TWsbWM zO&eF>cw^$k|C`h+#%)NK;Jwx zLf?xMpBp(08j>#gaW~LKc%3Nur2LK(<=}nT4Psy(9&fP*_M-K45!OlJL0h7YH3&V# z9I|(laU|RU(B8TTt}?W%B}Sitd1T*?TIAl>dMi<>%Y#wI@<^^2yBJrx2+l37gmcqH z&}+HAc4xN5q+CYPF7phW&9=WKr{3vNoTn~=-pO7>cM)l((yB)7=IGkm?jYd?LwYB* zORYCNgo-ohyR;&$yu!uj#iD424TiKn+VRqDmlj9KsgY(>dWbtR?^5GPG&=u!a(t#n zx(HevV;3#7i=f|84tjGJ!HAqkHR)KAMwRy0U4-@q&cj3t&-t17Y~Pn2<8wp|5^fOV zNbw2wBD%|i64EkgFS{A)E!kCN#ag4`RU8BeTVhe zuYYdjn|tk_^9;#G?Sr-s+wRjpKWXCXM`z?w&HU;C_3(~!tILI8FUH-|4w^pk&JFt+ zVX2QEy{WoF2=-#serUyq##_YazIs6QfOvdQ2=?OJ)@ROGVZ0sHDHt6-<`Q7Vl z_M)_(e`d>xRrcF3BP{tUGY{xZ6N0@c?Xt^1GTtIS`Q$RahsC2O1bb21%Rl(;@pe=v z+`N15QpxchA=r!3(iZeBaz>me1Y1a#ltS1~qxzjjwSy4s#j$g=mODwlr4Z~z{ZJ#S zXq0w;E*=*P!CssLYCVKnGx&E&e)xB;ui0zmu`}Xq+V42Cx^qBQvazh>0$B<5LuqL} zA#5N^TqsMtQV8~1iSSd7okZs%-7- zMQOV$&OMTRx$B=BvmA^WT*)loYOg##d+onYKcM>39p}~yg)7kaVEGRC%_*&) z4@O6Cs)s_bm!&NT%hw{_C&@1qkE?}XFH2kYT9&UJl_j4dIW7@`y^^#kq9!dImPd7p zto@qhzE~e8yJGC4w6^JKm(R~$d$_FqZyWT6zm{FG7p1jLAGpOSt)CA@XC5$IC^ zTHADs*i+X23-PeEvlpecO}C@^iLCuP$zf|}FG`y%|FAr&Swh?>#E2psTS%9bLO4aE z`in+&P4=k5onz-{leJHkb3m5;8(~tJj^WKwwX3Xy* z*h1}+QV1uX_zBSs;b&8B>8zZLyREUDVIjdgbxtkY~E_=P|6ALER z`sVz|TVEW`e&cYPSI!u&{HL22(o@;%H)n4-@z8rt$p~xq(#MY+-uCRx3+aRGRgFI~ z-Xg@Kx3zezEd)K4y-vUEz2ohu-Ztygy@w>no=@GpkUq#>T`O5xh-ZYj|F1W9ERl9a zO4^HRR8uvoUrKV)WiO7_a))qvmYic}FKR@0c}u(Ni^tcWzj-0`!(P<7?kd&{zI~0e z>gj*Ec_HV3y*RU~eoDHkek;l8QS?E}ch*m~$}_m4B;WCsGkV*JhovpMJNB}CAHHzI z?wt3YmK>J0>>%08^0kOJN%HN*;{*RpR#Fh`W%=4sy*1fxRcX#GZ5b7N(ejh7R#@Y# zYB^auTj(pKq)!?&s!F4};?GIDg*$tBZpvuWoL~0%kx_DvoxP}$5I!L7ZY&-@(5R>% z_M+CK*Y=)#&so*3PbW((qhc@4tZq+A5pLkOyC>H9Lfn6T{cAh*((_@HetzMmuf!Ph zl9f+WjIL4?9lUSNTk6!Z_oQ3ci&3IM1S8l&O_NeHs`$=Hy6nZ#>K$8qhI6#1zE^84 zdyxm{Upr*&8E(_QeTsG&e>nK~iLH;=I?BOboToH{<*n%Ew{J1A-t8Mj1bcCwbO(g? z3{Q#2$26*a7d|>(5bQ-?3E}hFGn^qgo)F^Jtv)hdM#WzA$GFzkFVA~w>V#ULd?Ebd z^aJWI>)pWX`S7V@CboL}HgTTWi}EGOkI=ip_l5Z4rJGFrdN=s#bE zcY}XOa!b3z==_LaFU!~NGA#Q`^=|N6@vyWHfA!>uU@yzpBDRv`4~oZmLRi{@U@yzp zj!LE-(%BOvaEb$^);)Swy+7f$F zz9f0EcG@d@Q9j*~B9FR7JZ{#g=o9Qk`ShKX;?;SQW5pbOiXX5S?Kp&ebJqDo+Lur# zjO~nex@{q6wjWkzo3z-Av9gO`3u6f>bw@?I?8VV0?JDO!biUp1X?g?hr7ZbjliG>( zQjUFZJR75&d+i;W5qeL~wMs&_$Oz}!JuxY zpE44$y3M0f4k9C*Ygf*_c4mUTEK{p#YQed7<=lJDx4W0##p8G>t=}-T^B+yK>0G;V z?lIraUX<4F1={&%gm;ye-1&C)qO?Y6=RY;^aIRfB_o4Ic>_urkD((C;!nt0bwrf4kwJYadd-uv-l$I76 zf^+Sb+}6%sl$Kr)f^+T4xyO7vdr?|?n(pP49LhXbws!WiOvR4s-4fcfOsy{H$DMj4MX8k-@ok<=o@GoxOOr z=~1=O$GLV(?tD9YS*BLn!=MG{+O@A9I^WJnO=+E1ZavDmcIDh-zMZ`&t+T|f*E-j3 z$(?U!FG_1f8yTEySI#|JJ9|-DkE)G6&b2G&9<80dEK@t@hr#llYgf*_=X|?+6`vs8 zE+yyMm2>Yo-_BkfJ4dU1Ns@fvd^>wlKh#JFiX}tk++)6-y*LNddI-+7E9X9RzMZ`+ zQ;A)iS;bpfiE{3hcYV|krR`debM4BxSI)Py7p0|zhTvSgrhH&)XD>=iFVH)Vcqr!{ z^X=?KY3XTtyOSKsxyMzFy}Hsax&u(oedv6OCB`e-aTmcB`Z*(<5$&kRooMni!siptw|i9DiH{~- z9oBj7%F!aoqr2j?l$>i<&b{Y+dsind5AT|_r_a2dYj-}}`F8psd-)Ajd-{xUuHCXY z-%cN7FF$KfKQ+ncT)Xr7&bQMC*~|R&E}aq1wJVQ2biSQF*zI)~?9I7$<=ltPw_Ebo zep(wNCB+hrN;&tKZzo;$;%HN@y-3cnvllg@Y8UZP&b{Y+JN3g})Vj_;lxtVcz2|&8 z=b+n*wjfDTUx%yK?R^-%h&h z#nI~b?jSkG&R*1rc75WZocqxEcIt<{sPzz>YxhZ+^X;62ZZAeu=ctvd?m16w$@L~b zn)2$cekh;3Rr_7#s$-to*_z!>lc#tnS3Pu|+6cYL zPxYwSi}LB$3M7Ye)kEj0Ju1D)M?|+*YsWgN)?U=-!rqHoa%FEuouQ=`C|?N9Q7cy+ z^VH4;D|-_W>_z!PaE{v6?mV?K&dT0I1bb0F-8L;A%2n6ig&U#l%~X$yy(nJ@&QU8@ z9e2ncm9jSx(e1VOq;dkiG_%f8D_0$PSlYH_?@46~dgez;dMD7Rl&g;QC8Wz<9Bo%} zj-9=zkr14tR<1hcsi`0KqSixjj#|0u%6V$eLAMuY);VhLshzF0Y?-0v?cbUd?7eT?KyXzn)b?GluuPi;-Or1%u~}R*o*S%S7IcGa@9TOsp)s!Ui4;< zNI9(9`75t#WuC1CKDV|IWl*Nb`70yZmR46?9SSi})+-~Z-R>&dQZk|)73q>6N9$4P zjIc`CD9-I+@ZiG`$BfV!Vb7<19&a1r*sI;uxIYnWX=7rSk`e8wNSFLLTAvv>mys;7 zD{Zk#?j=I-nSss@;<}BB_29E==t2hh!UyU zi+hO>d}iP}NS_;cRAn{j_M#4bW}vf!+UEvcOKi13`9koSfzA%%xq)-)CBm^6<4|`GTA^6Nd zX9w}^j&soMMX&XlfzA$kJ~y!B?R!S61?UfGNCh2S#- zogKt;1NsDeQ9f0eN)DYJ41I1uzw7pD?N}MF6ZaXeGGo>H=#zg|zv}GMCw{luo_*(v zQw7zW_^kId)iccLr%dYK_Z_d_b@lwQpPqBTkas<#Dy{T|3ek!@XKpcEX6480FP`$V z`u$%#Vd87|?hxsc-^x3GdEy(V?wNU9y!Hk45xZ|#-yVf|zEa;J9{eVs{D=)tvt5x#9f1}GLHr4zqCH;jBD!a#e=upkRL~D&j^FjmG>Wh zO1c_-_Pp4^BMtzAZBkBYwR5bx{u9o_j^1Wj;AC+`<>L=G8FLO?QH_y9tyw%lF?>)S# zG#``V!5c`(k7(V2edZRu_sgzskR0!L&FRBpyX4pVaDTj=^BdQ`pt?nNb+dTzJ|glX zTE7~)V4vRe(^sv>#UoW?CZ8a`DZBo7*xK$x`;J%Z%0GTC9;s%t{T8|0Q$%zKH;czV zr>|OFoaK1yeRHE-k)QHPT8)YiJ}VymtLKl{2lQR zGD~uNK|CA*imu4de%|sJD3*Lpa@ao{Kgvy)%O3k`HC?aq|fo-E0!Me-wBIRMSz zZkoYs#e*|Ne$;eYIj71>4%Q6P8px065a!Af=gShks?p-ej~1hyjI8~?W$nw!YiZTw zM|AQ*dz7t&oRdz+>M|AYT>OAepJmo?XFOFo`=mW}{LSLDZ?tX2cX zlHDc8Dbf{p+vG>IeiKPCaYfC?&!j6yvNGr7=Xh1_vz4`L<@|!?N}_0xsW3v;>cfpY2qc{-Ls$0yng?(xx=?iu2ny| z_MHpai|b&j#ha56e-h$=iM8sd-+O2NdLXrsE-C4Es$YFs{o%vs3{PD1&V`(3&c_GW z*>_@vg_wTboiTr6vzvF!h@lWS3$exf?_9_h(j_I;i@y4@ z>O&gUerw&ikX}SstW|wU2(AE()XFQycbsHb8BzaQ2=-#!?aJ|}c-$zvIzW@YV`UX;na|GDGbjQEdl z&FsBNh!;|ZBZw#44|vR##4+%tGK|N5=@ z8F8X)_XCH|=^Y{-Y$09p3*kHRj|Zfy>pqY?s_4r8QRv!lT3yYT*RCTTCulw>hwZqG zo#^D}@~GZi@nDPnuJ9uzMd}oNs%NBKMjXeF@;>0W($2?Iig3GWJ~lQ2y&M_JYgzaJKP5WV^#^Cn)r{xO-yW!lNi*W1ML+GVhXbm?jO zeNOF`R@EDecb5CDdDO(rt&fg8hW=*X0=J}b&NA5bOzDRFH&!6$3dD8wvaA;C4_hC4RUq8LEa}G$6ooL4G*GU*#D~W zR#$)3PXA%e$3e;(u!VH#n>rm^VeK=lpMfA_6Z#&-3`IdTPc}6)I z=g8PXy7XXG{OYafU9zh&@wnjFL&nRT6TR*=j|^Mey<0iU<@9#L%^w-F;SXMeB$MTS%AD zRlj#9+g)34UcZzawySS^VB5%pXxs5M=T7VTV0^n{3+XZjCm;N)&L*xC5BtZgk8c%u z5N&^Kd5r7rP8pWrv66!=r0cj+V!nRwPH&K3lpN+^KQBCpc3f$7^>4+*A8J0HkPotj zbh$Ew@DjzuA7A*D`Zwb7#5%iA6kQSR_}I?*Zi?-@%C1h79Bd(7u0;CXaJ@lZBfE0G z-Ep_fInj>u#X|LEnAWJXbT+ZK{G2VM%k@h6#QnzWGvy!O7Z0x=#deA2dZoK8w5t8; zs^n2@;R;7eA&hHO&uUcvBgx5~Xz~l;Wm?rfw#SCGPXX9My3|MrTT8oZNxOd*4@yfk z^`?xMX7HbyL2H*Sq|2EN;W=5!ak7%D#e=g(H0M8r8M4Gz%MyPp9&909TBvfbvi9R; z?IG%_wQ8bi$6b$N3+d9+62d2nUe)MDMAIL2$AluoiP@vrLb{9?vRy@=10=_x=7Bd} zq8V58-Gn0CpEMuNg|mfp8TqtEDT;nu^RcOTFsc#F_^7P2BK6(!D6a-=AziOT#S2od zZ!_7IbC!(GL^IB-qERc(rt&E7`q)CcT!})sSF4)xqV-|o!BvK6u2*SQ^J$;+iEJTV zuBdvO5RVtMd-cl6)skrQYuEFkbaiPy?PCk+a%Z437_FQ~X!p8emZQ935pBJ-`;rSZ z=Lc$Mc}<>=(n7l2;e_yj=6q}ImVT@V$K4C*dj8w})f;8IKi1CjDe+(n>2jwg?aFq) zuU+5jS`D}hBieS{-HRTUcb04+UG6v=AB;Oo?k0)0Kejw(Dwe!0?=0Cux{fPlHyFa% ziY2op$8nku?uv?&GjnHVET8^*&)B{hd&vA?9hYbu14(>BfmbPJU1ZS5R1JiBZJXzod1a> zAUJmF>VICg^~C*~rnkO^fgW@dG^}BnmDiZKapK5GcZrCB5wus4XvR)-mj`>%qv*k1 z1ogvMLXC70A?zMcc>V6oS))d}2ues@Q6pUhC8S3!qLBtP7;>g4)6(VODkDM@*S+K8 zaXv_?VW5XJA7%II5q_xJy;w$r?jk55<)C~GVqhMeDb5FFY7lzpN>1BdM7{)yJoMO% zm+QH;TjWdKGpMtt_H4f6n)FV!h!z^qptF0WmC$;c?t182J8f5ujpZ+nDC4zu%k$Dl z#TFtwPvxDV%Y)L|cFV5c*52+*EI`7g87#f1U9~q_Pkr_8z>-rZ;I7yH@YFfIRad^OGNwzbMYN-xG8)2fUU;GU-IX(YMo_y%x6ekr z^^Udbo!>k+A_Qu5LUj9V#N3rO8jhX(j)+*qI~#OM$%v#?|5p_-SOJJ`pTR?O5&s&C zTNItv637t|9&d@~!Z+yl*@&#Gh~Rt>-98(U=Ob3+wtC;GM|AtVD5Bd^X3)LLv%gm1 zsK}k@_SuL$gHaAjNOb#bM4rKjXf^7Q6kYMzh(%{Gt-@1AiEf|4BVtWA#q)$9x?Rs{ zi5_o?=V>Gb-BL0STDx_U;^34~qT6R9=uxfSr;HNaJ}1d7z5g5;-ZtTCs;_@7A=1tw z@k{m=N1M7wM5}jd)Xy!YwtLocw%4w9myT%l-qr46h(Y4SHEL1qE;6bHA!IXytwxt3 zhdK{b!Q9SZtI_`p(d|`y;{QS{I)i0Cx|07(yVsTV2Kf{1!VkNA%l@m@{8hZIV}}Da zkH7ln`t5_hwMBeRHQNs;i?f>EQg71^nZM4(UqK*RH>zkC?&^dS^fvLw^|tAsal#Ri z2l+kyi)sD4=H8$0%eYEA{nPZe{R{EnuYQpq(K=&MhUIv@(a+E>e2w*H_FsSAlRb}} z{H|Vg+x`xJKQ{9?AXjquZJWQ4M}9=>+*xl$yC^f^+VfLCw_ksFRxk1(zaQN`v%l`L zugE<1*PGW?%6>Rg#9!VcKcb@z4%StMyl7E;7f8&n) zhz{X?@z_}BAKQwDTaMUwn^D^?`E9ah;+=eOoBhVC1N4@9b(W+2(iiy=tuMHgVfkO3 z<2)=LmhiUegUEyYEXS88w$695+$~*QtSpY}cdeiD%VL(J@FQB^0%*=p)*JmNH6Na- z@&7t4@*qFY$6ZGsk$KG3oNtsX8u{y&#eaM~@*qFk)eiqY zCG$96w)+ibKYRws->D@(qN5KsHQV-_!h`(mAM2d^)y%_~dzHoUob&gb$d729{3w>} zDLKBW`EUd%x*|XOdCS8!+lNRF^Wg79kss0eK1wms^RbC^nD{Qu zhbx!)YhvU_v~FisY#)9r7bOW*~>pD8q85 zbj6j0{Jeg&wmYUZ>c#R8#}ckfOo0PEs`J6Asne0>}QYSOpzZotzDn28IvMbkxGa{28BWlcx##4Qt_A%;{AJHNFMXTD;@(=HpxU!HRR|ZwFYE|1q z{_!oz!PSfWh}Mn0TGejT%6V0mqwGb=k1L$KRy<~Db>2oixC)aW(IGr6U0srQ0G6=q zMLm+jk1KTupVZ3vUhQ7z<@qQ(Nb)0ExBF?%-=hC9RzEv|D;! zJh&_3?uFt6h)y1Lmv)w(b9+wVL4Mo; zCPdl2a+gYeM2GN2#gf^1XXyw~bVYvL$!bTYSh9`exJ`0!w@rRThww_p#Q)9bgN|fn z&dHBEa^2XXnCKe%qs4=74dh3(PJR^IFVA-6h+J%m{P<>}Tbi|UzD9QSCHWxVe#npL z5QbW#-YfsOQ}e-HXz5 zcp%?8^oZ&cS5VFN1FF(vFY?RMp`Pq}7$6Cv0_x}+4s zi&P`Lx@K@FIT)iDOa6T4yhaQ9x<<8}*I9DaK(ZHQn*Xw+8cplY0U>S?Vy=0hg>*?N z*4Fk^*Nayo>m3+va*sRWF?ei_h*l9tgnku{cdmh{Ph4^$b*!0 zuYu&aO;xP-<{2zIVUNA+SS`~7znGiv@p1+B+f=`Mqx^%tD3eF{)Sg>sgz80msu!(x zm#)}Cx}=n%sH<^*ldYt@19;B&S?Q~hu5F<_hp?S2QQtK5R#`+2&&{p#Pl*Vk^*$)X z210yJqhgC~sqpjs7mY++4Xvvc#lwD3^ke@hz3exIpT5f`Aa}+@qT|;C{$iweyR=JbIjSxX+ledte=7vFNbPbq zRUss6zf(L`Rn0c7k5D@Fr)ZPy29$`bwM z%fGWFmKe^s!bp@>10$Zuk{1M{D5JLa?V7<;G^!iLgR2Zz18cYJ?ev9$R?e^Ko%0~A z&M#VNTFm>nl9aPaTL|F|svI~_J7mAtE_irGMEKm9=xf)V(SQBejC||ZD%t_`^mccq zc(8?ZIsf|3OVw?zt##gKjk~w*&wG4}c*hpef7)of{u_Syxy<8#w3AW2Xz$0`0kDO1 zX>TEXMY|<^aTwoNw%B)v{=*9niadxu^5k9npO|w}=JAAfWJl?(=y|;fvxRhNp&_iK zUEiDa=JkN&xZ&yD`ak>n{K$joTmQ0O|4Tpqa^_)c_uHK-&)7n`jAQPvd$yF5ac%AY z9Po+$x*t9@@*w&HuQ>!f?$i!>H_72jC$^9-eMN69+J)~dIh-|k%a;yrco04HM+4~U zaqaZ4)O>tEJlI0I^i937sAl_mRo1u?@XVJD8eI{+VCFo``JQ@X*;97qI|tZ8y7XY( zhpe}vef0+E`M7V3W1BfAdevFS!*;)`H?JA;kAr2qY$07n46QhNySqUCak+Tx|6lVP z+a-E%&RAK76SIhD2yZ#vOpd(%D?H8w>lzBX*IlowM6C-&(N(<>S z+Nn}jbN;yASbmk~W6j6D9(j)TP%C29#48@YqNDgOM?B|6C(T*!cBO&}lG4VXjM_)YHLb_ZTLinI! z;!~Orzj--c6|Mu0Q3g=(E5m`9owIhN7>rhLb~*{ zgeYE1FCv=$sNY0VWH>12WY|Kwj2O!GDf(4@PIA8RtVd zRIA!+OQr^9C_d>Mizuk*&BHMk9c4Yp#hApJaotkb|mF*s`UEe#iU6uD& zqHV|By{LDVu7F?*>2k-Je9*T*&B^{z-fM}rKejv^OLmYP=D`-y<<2>T3l&Rz3)ETS z!Cf)Yjw`LMZdc9rO_~q;2U|#&Zvgs@T-9v*7N}qN%nR@OL_0pVbAFpvwdb|7bS|7N zq{}y%_$|Qj!?LT{l7nw4L_5wG3k_kmRyBVO=v9p^q|5axgrl@Z-LBp1%kuhBY?o-R zS7`?I@4(eNoM%OV{xb*c5Z^4uHkjRi-(Ef6(-x2p(OGj|Lw5zUs?YLay)sB}QMGtQKTXIUvSVH+0M-&Me zMa`p?FJlIaYL`67JN8#^|E2jTw7B9}zM{9(H~pLDyzDHkw_iLp5w*K?1Xuk{>plDL z_|cytqKj_13_3e9Rc|$KFGRQfEe9>!y*|0>X4x`YbQeM2=KOcjEhf!inGb4oi8DCx zsHhWa*LGEO*m5v}I^j-+I_x5-6Yk--XY3-VQAPvmu#2Eh7_X?qE`kzL4$9X>aJ(E9 zN83e^JH3{(xj3S{u~1jkVHd#&KtHGdcM;SgbwwR21F4$rUar~ha;LqPXID4=Lp9sK z$~D{6BGK)$5qI9cRz0(+*>3%r==Rx&BUH2fqg=Dyjg~FCwP_=gl_w3*Cx~vJjbK$V zwYVrctqevyDmgy(=DG4FRq}LJmNo{rl#F;EZJ{v(RG2OII zBm~hVR(37X<4tQu8c9L7l+1(HZk?nxW6CJe?XwZ|s5WLy86~=XPLf-C|2b06$#b3% zY0eYBw3G2@+rJd4+ZJlKrPTBvBpz+AR->l7Gz5G3xoCGWgy{Q^Yt*9JU4+LV0y=9{ zSG$YxNPx~7)z$9O5v|@ms^Sw%kvz)5UPhPsSRxO};u-Az7Jw+k9l%Xj9yR&YjoU0? zpQv2OWa(uzpY`?A5)tIVoBc^CD=N#;_Tn#89C*eq-BC#f{|!377;@-Ow^y&V<46`m zBtS-#yY7v6-3MP45k%+C@jup8_xB%kzd+oPna3&z-JADwEhcHV^h$b5h%O}}cw0T^ z;QDVI+sM@Rx8z+3snJ%4T?8fMFNW~L@OMo9FUhGZ-fwSASSlfTm8KkvyZW_eE z2-4yR$-9f7EDDXp2}X`*(|-&e@n!194yaX zmuUH21Y628(SAO5{j=%=5B;?0gg{*_>b1#sjksu~8N;JMC3)$Nry%pAUO^?^wXJ7k#?sZ(e3l1h;B~=!qeQpQ zY0uD=Jo&+tQKH*t@DMl7M?w(YdK71{owYQo6hHW!MrG=Q$b*RX*}drV?%yKVQl5*h z9O3*tbN#cbgY$eaUUhA^*s&2mTxmw{?Vo#N)Gqyw==Rx&c0?i2JBeyD$mw*mOPHC9m$kYqTA;*gJt%Tds(0YiU#k-BL=U@|^h3R&UQq*3epb*N#))^lulD(B6@Cy{n68b&}*L zvqqU3#K5C!y|e3s9BqTpgGWUhEz!X9+{)KQkbA42?re4uU0TI5%!9l$X0Z6ES_C!H z<-w7V?$QySwW3k$t;CYlRKBqe%(sP$bYDoz5@ETiqSo+0zq`M3fB0U$n{(iJPw_FB8 z{jSqQ8M}OAq8IsJH(HL(a4H<2{z=*}Uzai_f{oTP(wK zP_*C?E*U{9Nm@u2Lv$KX`gbto+)_VFlswA8@p5h`UzZ1^HQgflVsZ>Psv<45(3P*{ z;+WXl53Q2+*7o;&kUK|3eoIGC3zV-x49tU;$oW`Qj&|j2dpXwHj!Rr=ZQ48dZ|-Kp0_muR;rqV46Dg66YV1HVbMqbhN5$|%w8b6!6NX}+l|BZw}~nMb2t zYLWVBpN-%Qa;AuGpVO$)Tu4_MUGWb~Tb|vk8?PFKKx`?`MEhC$>7Mu1>aIC&W7Oid zYdbbV`{|x{mkH5EGNRjOBhp{8cxf>-~E=7)F)r=*cbMMH&L%>B5#WIrQMbiz3K|+vLi{LzU5nU}3%@H=3 zsH@gWNVlu2-|O7&PMt{^xyk|C_D_BAIK5TR9xcxwxnhUWpRX~!f8vo3O!c$scfYk; z@6$g!w>tRZg>|=O%f4#H^d8ls{jBfq{_&^k;uWU%eknwu>y`_K`}KDnoThA~d+pla zd5vW=j}e_e`qaduVz2U?Mnc4P(^ji@-Src_8^ojZN_3Bkbp5=;)I%b_gcgsw@KCi$ z)2lqYR~I2&4U4W;eC+tB6VolvM*R7vc~OUn$0w(+H+<9cZ|eP9qw2P_{0cgab|;-C zzDGA&N$`PNJ~VafsL}GA=%#P5((`Zs;a^Y=VdYB}3e~odZb2s=`)gFoJ^!ZRNGSDpNh;jub_^{A|$(yKhXR~O+CB}-2;`1e1Y9_e~+{A`4^ zTb}hRN}9plcKyV#mae)jEx&?Jay%%zx_pJ{!&~y47aq1Tk3IF;HIBBCqnG7~)?RuQ zMCwI^=A)PAL-Mp1UY?Dx7kHi$`ab!`oS&Ur@263*rSM3jBBejb2XB1g1SP+gS3854H;pbP{DEj%5{G*J@ks%?hBiU6%&^wFI8&RGc9=*bYQN|i|v@@bS zH*)lf97~FDX;hrSG^#kVA!lmg&3p8BUFWE1iBEoH=l-?J?3b-FBL?=7GHd4kj@Rwq zf6X)g(q{H3(JhDMRc-v(Xr0gZU)bf4sGk#lcXa=l$1dsUDvgRdF^|veHZ}IT|H;oZ z&yj~lS{C4a}g}ZkcCF zyOgnIXkmIEmy66@&7*eB@gYv2Wd(W)@e)Y_e8>&zD`j1YJ z(yo5;KBGjCQV8d4vE}fU%fGfd`b9n?OqS^AO!SI>+^YYbji!y7lD_6xZ$W+X8E>s_ z6%V$ME^R@(m+!7U{PID!RU3;3S7)OC^Sj&kzx;-SGmp2ucUpbYF`udK6c4tLE~Bfy zUE1-b!-pPyOK-M#6pOPQM4$7S-TF7oI3e@+!S?r!&3o=E)i1<@Eu_o1qVH=TIk|rH z&;8zL)K$A@Ao>lXpXjgr-qSJ<&)`94oE_z03+Z+}*ofl}n$epn9wm}l4x;~59}FIo z+ut{GisZOMa>U(ww= zJHE8{;>X^Sb(MBSmV@ZI7axl`|K55Fs(oZvcZ&yGNSD5;JITMhcJC9itB*+z?yrdc z>xuJWyJKsdS-trOGe@i|wvaCUQC}f#v1M;9`Nw+VQ6hllAbPhG(>IvOKi>M@Gpld^ zVCLAQc(8?Z>HpCOd;falYwP5L?fVDO=6BH{4^K@zYU%3JXS}s8a+DU*WmMAd4@y_( z9&}s1c9x^OjgqeQ_M3aZl6h2`^Y0wt-IW*x|mBtDn>NYU05b((SInPs?`i{&Ro0y?B)PTI{OOwH;5X{-ob0aJ=&0 zSI#)Q{<(Otg>)C+$;bzXyNCyO$VA&8TOR*ZEV)E-+$HoY=LyAF6}b~le!3k-k{=<-*A)-8kS;Y6 z!jIC*8NHU$5>35@@IKAp6Pm#};=z_K-F9XbcV#8_%SvvM9Go?xIsYO2Tb6j2EOAHi z=(euApZrJdz=c|J-@mu|bm3E_z~rd6kEw{%aQ zkMbT)x}N`bFZ!ZCoLv2nc4U3==(e zCLi?f)sdRJNuuqKEf1~EwS2JWRgEoOy6w(c`x333-o4tcxGN^wai!JOh+^U^w6nCX zx-BhTz5#^re#OM=^X`?qd!ij5%glywx?=lAva3VIgDs@XH<=KwQ*1v%c4ayEmO`}S ze6djd)|S?&arwuG#Dgtey6t-9%;uT(%~#DFF%Q0N5zX}~o!uRh&xF7FqW6tIch6Rn zDP}nDuy^O#*_IIgODA#T`E2{<@Q3l&UbkWFMRa*ih-4?G7s6MM+;XBIh%V0wv7F91 z3y+`o7EF{;5nY}WVvf#Ik8aMk{j2P0>_nI6#Sz_>gigI$O8R{@jEdZeF3(Aa5_sVE ze@jjYi7w9xLG4nDM3?7;@ab!r!NkkwXR}9%F3)9DX+$1XLii-kbDQRz&r3tlG7f{4 z6iRtMVxHPMIrhu*b1!SOAkuT$ zH8}1XvHcCtk00=l&Exa7D{nYap4*9-MSlB6W+gO|`w!bF#!GYFEI)kQ(LKm#!;D9HWcg zsKa(l=0Q2Ew_@Q$H;91|9B)@z%9k+_LGH9fj&?~rk`_5Cjy57h-+xJ0MOxBb43Pkf z$iewAqIf~1tyoz8EMbWslr}w=^&_pC3B#6zPQB7|vYrKJf3sfg)SE~4nsrcb?vyV^ z9*)%1G;LZr%QHsnbv`_=+FyugPMA0Gl9N9gV>^4%deT^)xb(crJobKM(}{cM|93>N z7yVHu4QGs2|1BP~gn0MbPmUJ^d(l@y*yZeRRx3#kk7|d@w;3;^VlR4{zAQd-li{t` z992Dj+Uup|RzK7Nt|?AiLkTi)HfSco!H)+l>Xz9ji^4{hChP>AA1Mz9y<)6J1% z&sNuo$NfSSUo(QeC|?M7ow-TxX~}W5d0?l{UR)FP{*e)5LUdc&wU(5052QwQmqvA& z5Twgq9Bq<(UY49=XD@0bgw>?oYsBMW@t}U#i(1$1-d$lvGn{;F) zZ;_SkD=VQjPz#h#?@_YERb+{u6oR(IUX-u3cH1uPmAxpR?#7iz%@mK13qhY?FUqG| z<>j^OOO8E-px?0x;B#6_H#?S+`^M0g1x%2{ccIVvv}+wgrzMA_F@c9lD}VaSaM5SM#Wy;mEl%d z`=75lsvgQp9IeYvpIV@NA&kn}AGqb+!%Kv)g_rjM_M&`^pAYTlWtAyjTV$eq`h7-O z`%paoXdc*~vlr#l@9)UkACVmPb6a>B6?>&QPcy6ED-z-{A9Q9`+xYqLw?c62>_v?zCnN1%D<1a=K`pWuwXU3{X7F#4;|D@;4!XVCnN|Ii z{NsJH68j*nfm)z^A)F>l?8y@M6N0wHUX-u3cJrXUvKQqG;Szb&=Hjup5cCQ5qI|ju zT3-7q$>CLve#c(4W8G)D&zZHywzl4iC^^^jZe&=0r|I$u#YVk(Q9s>YjG{zvyj#k#LO2E&mQg(k;0w%it<;B^f*S>T9#Ov;3eFRE^7C<=MTuh&xpSd4XzcpA(PL%RF{|(FZ5~H7KA zTg}b7vJcM5Ja$n<<2}0LN2WDkukxHmLWJd5RkgMEWF9Tu%g4_@eSRay-%dLw^Z2o9 zAboF*d00QCS9vaSv~g<4vbVSHgqRHJnf5=2Nv1VI!gdJ*gm5ou!?qrzCAMCss&plLKZUbN?^ zQ_vrqA}}Io3@J^5tS}hb`)qHz2*m*@LZhreshAMGs3h`v*89Et{jGBjdEqQr>v{jL z^{#!sXMa1;X5(HM>}dI3t8(mBBjPXO);=?FYdMqpjL325zCrurkqx)D?9C_`k>fzz zrfPp^LhKdYu)QL!w}q;9|1(+T8qM6Yu5uhYrb_I8!;0KTje1p{A2|-hR9ACX$+!<< zccoRigT2oG#iuXsPJ8RKBt5TlWy*Qi!BfT&&7GR#uxiR+_hUTCBAa0qGaFWQ%U1O8 z+~=;|{^4bZdL_mUFe;|jJ5J0kv-ZZ**R0?2@q4B^w%dVQbRD^Ct>crA-Pu>&`230O zgKs}ph)GfYjV!b?YqWM+-2d^;trPAa*FL#@`i6rW9S44O?H)Sl$Nqgs)@jMJpS^dT z7H)Jb>^Z%?<VT5|q}N=(pD zCA5SUGg@Ws>4zhobw!^>1hvyATDw6k(({T*<(axS2n}Kn=6%OG&x)aiBZBdvC3{xl zE*;(zc`{Jns3UuZYbow+v4e^3h(+MUryllNol(1LcR-{iUX@Xx?u`ziVt-`T7|{_O z7Wx09RrF(r4sdJZ#(L|A>ThJ_d7ULE^@R7i^WQYPTTggXmQQD*pLpNb*Y7!SSC^#U zOVv~4BYKMLC+?hK+_>k1h4iSNRKH6)*qwWTZgdg5-jNM_1@5WV%@&#Yg(>iDGNH+ri7u%7ChN5&b-<(}8C1B*FuM$7>} z4R;^RTM^Med*$NwYcK!uq{F%Urq~H)I&p?_$Ngx;r^SFcAsuANNTIZ!$!`=D}0j6{{=65PC}aunx{p?zo%93Y+g!K0elC z6}KY$LG;$GH*HtW9~A554%OAu&Ie{Fm;FjCJuz#(sJgmHI(WY#`sA_mwySpkCWg>q zv3JaYKH<2teQTvwc-T=pyN59zo|OeeE< zyw~%S3DMT~+n-!N)zzOAtB1sHQ=gi2 zoTHroS}Z;DcR543V~?6C=P!$SX5K6BqC`9YZ@cEINyn3_-Rs3}GYg3`l*^u|Uq4mt z{#6XRkMvm89hYd=@r#E)fjuaO(9%48&QR{|&iO4d0bRSiArtNWSUUc!v*fGt!>kw1 zQ0~|VPwOoCqx`s1IhPEOp~ai%_hP*QMfe<$vsnak8pH1+A%3gr1hJL=uCiZhhUh_v=| zMfaGZ+qr7Ey%5c~wRWL0ct#n#Q93v?%H>~iE>e{|tSWIOGHXOL|9bC(D)H~C#1Bfx zI8$<2p?d$Ws{QlRu4VNR&0XN0raq`0b-8qKhH|;n0`WQRTE~jJh-mJ|)?U)d@T~l} zLOM7z%B>TlwRP|lyAGZPMDtu}ZLSmUf6B*x=@@59E>FJJ{w<#6x0MfnV}z#~(L5i6 zTYHD<>Y($16Pa>(g6lWE)eXL&x-wssr!&!G|M;ak&SC8jbDcRe%B@b+nmgx~cC9-O zyA09nSL)8vakDz7yV^KYa@kR%a~@T9cIRZbB-;9_pMOtX?YM3L?rNN&T;2@yJ0^gE_?LIKwUU>_nT-Wh<7tNa`XDF99&e($|rrRrTlSF$zmX5QY|Jw3L z^5Ywd6=z1db#vAeUY#XBp8Vjgm}s9X6_Ncq6JM` zd!l_lW@cM^L}&YLswE-=o|+kZmdx)M(BB3e@g+;IW8Sy1L~fuZ$!u{J+s>&i1s)T=GBS~*b!mx z{T)Gcj&~!*8GC#GBsazp1$&-Wr5~0>bdCeD({snl2%>XbIx@PJ<$NT9=#2W9L1v2R z9H&)|YqD#Y+Ze|xzu__S@AZY?OpGI2quM8<^Z90$TWGP;(P)xHy*k?zsm@h;Yg3DG$Y9okVF#5luPF^04%EwL=3 zbDSB>?1ksK4~WijAQ)ZCaz3oXtBB61>zjJWU}i0?N_0v}t2&c)X%?$1Q5|}E*}`e&6pCvwXQ-+>4~ z|7^}xW6mogx!gMP1h5W|v--?=)wA_I-WtJGw9rgbJzL)c;S82`+D>aHtGee|akk1# znvzRNM6gQo49>Xe6Vo2=fZ!_ok#%K1#9S!EBJ_;0a(u*A=&N=iCc_ph#)J`N3^!g# zkMExJurkPqY!DhOR-DOwXV1-~+?BzNj_NW;AJ6zW(u3!dqVS_;4s8&O;b;}TWvp0l zBZBra=k#xbSfuBfHQH`TnVStl14oy(m*->k6ebW^yUZplzt&p^Pc>RX|3(CDx3}rj zE~^%STdXLHIj8PX2Wyno{{QolQKa0_!n7# zsq7RamSS-NrizQ^fj~T3DA9Vy*u`2bAL-A^DnK^f6$%=i{5nRQZ zZq2+}@oSgnEg2#9QU6XpSFvKmNtGYs*Dlj4v5z`pT*dRzyjt;V=fSNVW0g^$f32BU zD}L?F+}g~ubHG*fPw&bQyVRbWbC=a%1Xs~NeN#_5#IIeNTbn0YA~Firm;ULuo#co3 zwJUS(a_6K~wTeB_2=QxI=GHpr)tw!MxCc>^_`9-7{Mw~Ccht^Rv{uYacuo(wiV@M% zCFu~qc4lrZqy22`6t@yQbb8DG{aTPObUak1GOEXOEd7eIu0{zoF6IF@g*DlSi zWi4?P{i|ws?Xq6EivH>C_|hSMZRgfWSFf9pcx{%&j#dPX?~y z2`*-){7BDjRh~ZMDs~_9YQ?Wz1-CZ3zW0YaKvq8e(=Ydm`6+(w(%jnYkVbG7{pzgjEBPUQ?cDo3`$SrmQLs;WcIhv7LWo~G zw~le9`UfTHeKNA@fUNR9r*^KQwSAv=&&{o+hg`*o=x=1wA%5-B+*-zms~Gjx%&Qf@ zc4clYb1<%AX3eX0SMwgU=Xncb6zHG+zN<4oKE{^hEUquvyqV8@RA1k5h*`Ebm@RMj{wRlkJDk$XFkjA_{6YHP z9i0C6@&0clV_#<)^pEG>@x%AtYKYjlmsxCxgTY_rxf}1&5rqnUAw=I<20e-pZ|}a< zumm|!5@QQQ2Yp!Gn}*arIrKVpidi1cnJly9_#vC;%9PF#68TjkA7ir{j?-UFNHauE zNHZhC_P0$dQ@5-p!(`X=zpwVpWMZuL^TB$T2laTnGYJ}&AO}ifto)5|J)u%NzHVfI zhU}=jikMuZxL(O&E3Y-GzK*S!3?cBdCa-J%GkyBK{R8T3g6SR z4e%1;w1cjnE#kfVT7qn_{-?w~M-3TkuzG~n{)e}i-lvR$5cgwsL-|;FH}bWDX3QnH zufaXmTg;hVO+kD%eNHNuCssb6|5_rNv79RpXa~F35zg@?l#z(-X5QkI^6Y4WbS=fm z^6o?X8nR9I5^J|s*Q+&g^7(dqzI>;@mdG)?>N)=QW`Zm>=O@kcT>sqXbuLsBcj5}_ zmV32*e3KI7fmX~^XJ)vMZ4L&^cq2sHu4!eGJ6qUbF`k2C(G$rf_x~6vCo;S z@QM4pMVD=rbY#a`h-NI$$`j_h-@QcHmsNGt9s33)G4{~+FJ5y=VX=R4HNEq!zCI-q z6J(u3%oG*B(r4Gu1UYkVCey2!H|cg9diM|6@sHU<#7!zBu5QsaEa^Y?MtZH%0iPsF zV(jLzf}&xrG9vbNCLL?VPTi7@IQI12Z-`Q<54b5yHSxy1kdC#mbybdHF{MSD+0LSC z9Y-B?|J&udPuHvo@^EaH-|Q%qt-siiCy8fC4c0bYdf+qtal8y@;$S*jzp&BPgJrg7 zHf{JTd-~srC%%*A)1M6%Tc7XXXG4yg5s@5LG`&_X2Nlg&;g3DVku`ZN)~1 zTYT5<{TlWG%0)iL&RjUd|G83AwEtODnNir!*#C^>`*7O)Wk>_jeQQl+p5xrckE8lP9|gyP%LpQC?dY-Q8tVoB}CJX^IiZPy`Y zwC^%-VaUw2mpP}W!^j(J0zAwS~fuoYK9vi|%vj3Bsr#P!k-XjLoRtQ>;xX%xjf>ri@+WKyJp~?1&bFJ@Xn$dFC~vzBpc0#OmhF z#XmJ4bN5PViibl@P(#K(PXAob^K4yxrB^-M9xlUj^v>9uw7=T-cAtq5v4p7A=7UeR z8hd?)jq@@g!Y1iMqoT%7lk1abaNIt={<$-Cbw}@d%KCwtAUExnUQXTXLmY9$fh#id z5h7#9$yidq`}MpCvHUkXP!rUU_S6l>??3aORwxU1ddSV#p3$%NwIYt`|8iLD7PdXL zB4x+p(LOb~!L)XCa>|T$(|vl~_a@74CtuiK^ITnhUBmR&%|I+(=&m0wD}462aZ`&3 zuax;KTKc?wYaqn^rV|f7a;c}k`%pK1Pi^OjFb?o3<=V-o+7W|keC7T=2_riCY&d2^ zEWKA~e7eO3>#DV&5-uNe9cBX;PPb0UjAAl(DI@sebaeVmA4zyfF)GxbnpOH8g5(0Hc z%T+s~GtF*L^i*B_Ag`yRCfFY;N4LOv2Yg7YII^5djCKpFy~u2gpQ-umukB@0IXb_d zpFR?okya?n_P5;={f6*$-dBU{*hmN*Keb+Dwk-LN10^xmB3G3D_WF7Ai=^2GENPrr z*s^(bDdV}04NYI>6t(z&t7)uTx*?5{wWlNW!}WS=AF8ca5Eq8zx3rG<<}>I-LldIO zCw>UlXSY759ccF=897iZzTClb+i=w9j|yJIQJWCL|D3kJ_lsmKK@OC}*x{sTy;eB~ z^W?G)2GrM9D@%lrvFa1g-$u#P!Q;gIxu?xj=A5?Kkl5EHH@xp#sx0Tp?&Gz@VLA_-0vF_=6A3NXwBCr;s?PpvC zG2SNEUSj`yTZ7W+9Ck?xg4t@>*=>K@N2Tp=J0D{;*F}q?3kw<6(tniOZejuBh0y{(c*S&JMZNV zk?F0A{b9F!xFNrB{Bbw=b|fzml%1}6m{1a9n;MT63s3GgtSr@$qrPYdN@6Uu({uje)+t{5WpjaY zTjq2&ev68fIj;ZCF?Y{1o+amLe#p6nKz5fb&c*@Jks7i#L~<<-*6z0apvkcX<1s;G-HpG@%W%P88Wk~ zY4HgcB?AGdx(_I<=nv z^?fYIzQtY(b1q<9^lq6f!)$%tc5(;NV`~<1OKZrnWauLoH9Yz1f(-q58Pq`R_sx6n7$c`O#^BbG=UoKBM z*(`tI`jF?C)KQF`wTxp)YFa*{L-XZwjOlmFPmX-ebBydL+{dUK>uO zF}9`cGv4Xd6TVHFlzEP`7JHVl@T^vY-e z7NS)|hvMW#59H<79(yU{3Oy%!RK^ayf5ttIJ>iZeO$rBkBJ{3|-MiRPEcq0}jYa*jnw{m31(XJxuE~eFaZfS$Vm5K&L;0lLmidlL*=6)Za@*mY3 z3G4&3L*%5yM#U&$m4BOb1cA{B(}92uBId zO~yR84iuNij^U9#R&kuq=vP#&t~I>DqwnVuvtB;uBG>ir7&lL~LKYmb;7`z|kY4pGQ85cs01gYh2}G)G8*> z>!YVu5z+o3BCf|C{@kN3NAH6zihPXiceu~X?eG_kPiv}YfO(Fq4`aNgZHK(r;M>)) zF78s7I=UJ^`mdB@(u$kTl`LS~9Z7y=aXIoOK7>dj#N^Abb|GTkH5cRf_?2>eQ&$tB zX(!VnT0FbB*f4iw{st%u{h;dM5{Tnz$YMihmqYup1bre(`qvH%X=OVl*tN1nWiiT$ z8qyAcIIRC6u*8nGpFiy9l7B6KO^6G{_wPY=)C$pzZA-bsuQ~S>UpKroTn^7?Jm9`U zvYq8jE4sKCV?QjHwKkM9IhdS{JI}3@8!i>6)?GS2SnQdd%Jt{o2CRjAYU`Fw%fZ_= z3>V>LXK?4g@)@6xUM`!wD{sPCi$0&RKeOHEx4Lu}vr~p~qSGy9p1k z;R*+?04Rx~YH7jZ?fTQ)Fkz(ub;nxj%GqZBTRyFCXW`j&u%Z?E67(^Q~Z1y+;u>ZNLUr=jqHdxwl=OhPXzt{0{%@EtYbD2*@L+X}jaVc@Of-qiM>=XEBf?RqslSy`|=JWDH0^O_H zZbmC~i8YjN6)h%v&sPvE(*>X8z6sLrP!3nUu{X+EwEP%f>y#+Z zls-xhRSH z{4_IExfCtRmxxvDK&@27r5^(fdq}G+EmW}IO z8GU21&lSc_kFI z)9U#SmLfE+&JVYZE60=s^ES6=;jn#|HA88*gS{9D;Moo}IMP&Ux zz-${OoJI-Cr9QCOJ`jLCpM9ubdG(?n}b~UAhZ-O+LvzXLd%h9P-^k+Y7 zi)8~RX;=&MJye9l@@VbL)^JhOvy_5BO|WMf^AFCU-@EQ1j=p}VpW18Y{7vr@0A??M@Gp{tarukCJzDbaqIWys%uzJJW z=F?J*rTU8rIle2oILL>R7+amQuzB{%F{1XB1_}pig7cB~iB;E_mly9W2DoO^QPz0< z6yNBOC_9|}Db<_m%X`+ElSXtFE@QLmSPQc^R73~gu?ExYG2&6LD%#}tHGM8VN|1Ue zGa*{l>RS7pJb*ZA#${IWOAvvQ=(ev_0d5@=DN61wpe=M=?$dm2g1odblL>2~&u45} z+%Eond~-~ zEN)6!NR-`#wbV80XVI^`&CMoaK;xqtYJv!qL_3+v%XluoFmX0D!Cd@LM`Q6L@$#=g zN0U+uyae4^8jWJ@Iu~)`Qi6sE%%8w)2s#M|))14sR~H3F&sDNTkOL(#7Ap_)n?Zxb zp(l%zac_XN6hFqEKWihp+{-W4q;9i$pN#Ac)C$pzo%+&W9B-D&zwLgmSdM%siLuoA z_jnWXiS@2!G9x>#)QD!x<5gwxb8{WBx7B3Da?BjTR-p6w#eKZ(s8I3b)EzVKMUYRm zBa-J5S9aAG0S9kuC<{4oEKp3b#du!+Y`8c#rl_WjALwV4L}#4g>-gdGZN-c5zm>6T zfebMm$24|(l;v6OM+nc(?i$V<hW`3L|mzOB_|a#gm4X}s9LV&TJ~yTB5-fK8COe` zt0MBV0R7yt{Gx+to3aBy4%|zSFX??)>mE2rwD4G*jQa$Xi#v|=Gmd6IkPPa{IX!TM_vX zO?#iE!TK{g(LbRRJ)PVw5bMe44?3}Cv@~OMqSx#vdOEpV?2#hmLv0y5`8Zf#WI4&3 z9IcD9_z!=fPI7L^a!L55y*@lq^P6C7N@kuEGZgkvF8L(23?D2 zUG80M$g^T$eJsH~N51s9s1A|Tbh)-jDsrgvgJQ_~5sHgmYm&Jx%0inE{jVLi7;-|< ztGlok%2g2*t<`PO+N?!gw_`2z26n{1*|?O$qT8auwtuz~dsc|;Z+qT>9bs!XTfP5( z1mu@wJ4m-Dkuw}hu^qT!|drSX9P+o?=|Ae;c8{}VM2R_a%L;eX zfT=E)h=4eGt&}Z?h4M@E!&Lhb{l^kJ$A6LS3=Pw>Mf9yy+xQztm&4AMfTZbi|E}65 zT9wtQpi)b{pkfG0N)egGBve@%W5Y1Q(vZEX2uN)%| zwBu4sS4))h5?Otin=&f@G{J72`oXmD2cIkd$VbO zjH#ke`06EcFRQGt39M{vme<#W*@l>f$XKE!ir2kXUN2VPQ()F)ys?YVt4Z~Y4c|2~ zmH5(E6mW7gR(J9xt%7FxbFX}r^&;6l1(u*(ltgc^UX>E9x@Xb(rh*Cwwj1&>w*BQJ zE&7|YzV&$xff=8e2|9J&1^s00D#nQ1Hm!DO%e2OiE9oy?YY8kF{B1-^%XSTnFP}Fu zp(I+PYE(4exm#7=G}s`peX!k75@X-DX4AfvuBNw-Y^ZRcRw#*bQoBCZ#%(UFhhM2I zFwYV-IX7`Z%Ej{17=GE-=jX0<)pLxWuU#@;=k+fhOj&Wajd8%PMkdT|#C%A`3ao0N z7w+&>)8}LrSb}^giLuCcS@jcX`Se)F@&ehh7NRM$KX|CVZ0i7R^tVa2`H|s~TW$E7 zQaWIQv9F<#sgGk`i`$l!#*14_WJhw^Fuh54cP;y;x%~dV4=F#YMj1;qZKPy;VwNUj z&TO=vP0lnQpWR16V3wwuFZyIyD}D5W&)W8@TNDIph1$|QZ#_oOd@!q*wSY;n136Gz zI^E^#spsy#Ok2Os!ckxB4;4}G{y06QoVVGr^algB3HcHWWVdCsA!XKF@X*w?GyBU>+fGrs537kruRT zrV9EHC-My7$#ACP45s|6n32NwRFwJ8?^8H>HT1ja^XVkK{knF@GqZTyU5HJO@>rg? z9wW{7DDUxEZc9>w8Pfk-ZPVm`@>@RVpCJ!Duw_#j<_*-B-5Xb2?kD7aJpe zk9jDy)OB!P{0;43Oet}yS0&;0BEKbN>>PRagu8+W`a8EJ_oEr|>_!{MfwniaZ8J*= z*YTAEvZGciBI5Eu{ngXiymQk991+N;uIJ4xH?_&(4a6wNT#8or9_F^(*f>Y#{mb37 zKQWJG_F&4C?PSYt8@Kr{t-!1L;;%V51(rNG>SRef6ep!mRTJ_tHuU{KeahNIe!J>u zjwOh|b)NQZmG5g6+O-g^W~A{AOY&OA99|+@E_O3T#W-8u%vd6a&2lp#n#NVn5WQ;5 zc7DjomtzScaA&~Sgf-8!njVL_mf25W4^qyI1#%!Qzj7d_yiU`eG=9bpJ!)#pbjm2f z5rdK#n>pmMcHjL7PyVcOP%e(eo|%b!^twjA(X5jL#N`&NZMVo7ryo3jpiPY38k|G> zUE{K|D>Utt+m+ z)e4sg5boJmD;#*H!jmP9_Sqr&lH2?F7>CjvWub;DBH(?9-pIWH>~((L1BBWbEpKTiPFPrNoX>l?3`%^ogog&Y1`5+Vvqk zbL2*ja&g3{eI7shqIS)cMI>+aQG7erQv2iZtA6IhX5++%pV>LyfMTRbjWc-Gu4s-* z8Y`ynDZ#PC(f#el6Vq475tJ>2k{B!Kxi`7u-T}h5z$Kog@W+i~cg4vM1FM-3@mmij z_BU_*G(xbqGdb46XbXBG#x76mWQRdupTZ)fGiwG>i^$L5FzB%xDUGlr4CNXD21%V|tbaAIya`M*NCX~e3=s&WU zo8|eN$IR#>zDB>@Sp9BfdKNtP8qO}-S@wIAeC)xQxGT@^K2QLT;IX) zqBXtt{@zy%zO;-VI{B~Vn9Yy5yo}{I>S8!u`zKE}cULlgkpm@BzUcX%-Z74u#lpaD z0%f5lDk5ZWHbY$2qQa+jON9e-IkBY~dtRcyA?&rMsNbWeVmW5VW0of6^_AG~eXX!b z99~yJUq?~}oS8Zs8J zp_?IzET3^VkJ5u^Ikq(IcZ>HoM*qf0*t4fvW*}YPGG_I9}kq z@`RJy)Ww01E%ZYbNJEFY7 z!q-PCM%{f^}4OOGm6u`57_AxO;XZ6OAj2eO&34vRf(-jyFE~X^X?fOsZp!J%7s3 zZA_GcNb3D2k)&+5+$&tM9D!Z%XWGj zJLK^-Avf(yQr;#tet+6fdvBD$T64FQO!;o9YaCeocf^kJ%``)Bci!z%xTx%UI>p0! zGre`muUPCJ2W_HEr;9!%jy0iVVSEJ00B5@Y9U<)%d6fqZP|hD;2>CjZYrY zCI|nvew@sUckZi*j02tT+J9;)z@^`(ap!NzlX6!5nE*Y(9_Nh^UTS{4a?Y@(dz3(S zM5~AxYZgPO(?tGmq&m;B-PAQIIR0<%uQ8MOloq1|mY`=)`#kL7mn8AC7tgkBw1Pn2 zj%c!D)?IJyKYxX*KKd&aG0SJTVZUn+KL}Ioz_!Aj0b_MXcjeV*cjLnzhS_Fq#)!jOh^EtBi&@^ICgk9E*NhW5 zGO(7~x=SjyYv@e#;}FdcoOd`sRK!sSqq*tkZ-x(+aRR+1`b6|A^fjxB&9oPx-8mzF zg+2;BgX-JU&b?0F<~o6=t{f$>1QDuMud3foJ`iH%qYkKR6s}9S+R-cQ=jVC;j^hnK zUk?zto4}UFkxx<1?fr!3gZ<{!HLh{o?;v{lsLaMnrkTc6lWo@CPD$W?2fCYcUK}p4 z1m)sPW9-}ZGUEN5N!ottCA{V)`}Anh!PxzDBNN_W;_U!s#DAzJ7Cl(1LGZl1=#>^8r9X4eiw zkImUNSADG5dcCJ;=u^d5xT3EKYvBl`o6(3}hC#->nsxeEfwfQ*6;WeBD}H9`XRY(G z&I$+K%HVwqMIc9X;5FVm=m~|}2`oWA)RwZ_>h($2(z)w(EJ z;fYlCMKUqeC`d6LR1h%$Ozx5cfokMT9@r z9^QDO9Ujt1LEz0F-s91C2m9a9%DCUuTnDvK?rV_)xhY=qeuDP1R}r)C;89}C>Q5;T z-%c zhN{&D+I*tLelkTq^!fDdg#JDCY(Z7LS9bo$kpmGZi8vgB^?FNldr$aw(RPB&;J}j? zN}}wx<`=YE-!2w`6)9@@-OKLUIY}^^HoDGmq?T@d+E^FJmr)p8> zS}S80Z>@10(>`&w(5|<;WB&8$Xyr74<5ktlZ`nBQaY$xeehN_LIm$&o#xC7XHBY>k zO{+I(tg>&%nTlxox^c(s<_Q%X^jd|wDw#FtsnMg-9evZl_fdUG z)8n0a)1_JUA(3qr-;THM=;!Ink+B;L>xcd@mnpCAme5nHTK)C%GB3RMtX8Lpzp_Rl z2d>ogB6mw|-sj3*^Pya01g>PL39h1yWnbAqXsgz1&Mk{8>p5mn;o8pFMaLQ3>qbg) z;G&Vrz8&SNh|KYAMELh==En1!m3;|v;0}i}2lRbB>Ry7OsNZ1aG=Xwy4rau%=xe%Z z=e0@{@rt8}7sXyI_DCAeRNM_xTkSco9r`csgSBv;tBB4i=d~*r{P@k2>5-z0(=YBB zk(=^G%U;lIvA*>b>!Y}s#r`cMtc4K-y64PsLHk6prTP?G!de(xP!SX((}z)vtR}_C z(5sm!xD`3pd|Woi$}12l45;P z6zfB|SPQjfOmn=THKa(Y%fC^zjOY;Vqmi3V+iTBj|J?NB{V8UNeSmF++=R$>QL}%c z31uM%W-U-o5#0&fztDuWFlMbHn#s}0yBGHr$Gbk#@NOF;ccTJbEHTX@Wu+9`ccTXU zV@xvgKDyhXXBeUQ#TdSq?1*Oz|dFvJ? zL@FV$B;FxhHcD(HS1pXATE8UO@{k#OPql6TvDW+R!(@$X&1JQS*#8g2JF0E_kF_Q= z3X$VQYnjD2=Kq4gT30Rv%7q2}<>+hkenV8>6}|U0$^S(EvDUh29ptIzEo67`yHSJfQx}~=quGv}?+p7Gil)br# z;|8IAua$7dQ-1iq>^H>WAX9xi!Y0dJ3wu!I$Xv~lH+C2(Mm9RkFBIr3V_temzxMyi z-CEyMYCD#vbJ!)(j%@HszSP)TJe{^jbJ*8OIxX^+VgG5;<(Q{D*O$IELfpU5ZcBIa z3q6{P5%n{P4JQKR>;)!yX5u1=e5!r#TKkDNZwiUn=`+mpYX?ZTs77)?j>QuB5Y1R- zw-fyIqk`(=J(Tu%`=B2Wf}wUPH?=Sk$lu|U4vIk#}wI$dj4sD+s57bs6&36P6# z&XdT8XvP+wsce3mEr~C69xSRp4v~{)_{)oqF%tQ3gwjh3zhrIxGbws)$}ar+50$I$ zddovMmdfHGBjlWKjby8{aS~@5-9a|1tgX*HKm?H0#cHJ^=;cS|*v;YZ@+f_@|9&aqA8{VfZL z<6TN${Y>?9Jkh0zf@ttzgp54qDKG~QES3HnF1&*xnnqpj{)MKtMGS3wN&3X=yvHJ3i?VL3$b+r zwKjJ%iH(EX3-qE`>)@cF(&ee2JkfbRX?0>Ey)_8?%p*FqS3GrPeYpHOx`kX48Y@*q z^R++CJr@@gGiSC`MmyFzU>qVRmTfI_pR@V-ue~m6o4%X9V+sZfESWwyRIc0VFAMjK zkvMNCgRbpC^OleEwUdp)m063mytjqOWljNdyRdOgZ|Y9|h6LZIF!H*+%LY^gJZrKRu)2>xYmozOvaPe@w7tde@xo`i32afUg+0sI2kOC+;h%YL>OmYC*n`;r zj4gV$SPS1=PV`$^PvAVjQHkT2?guS>_3hQpahHNkIL<+wA1b2fgsaJ2$TNH<&!Bn$ zTxEWF4DyLxYbVE$_sRDC2v@z#uQd_961`;Idq`_Grkj{HY_ob9QB(BO1AB*GH?tQCbaF(`tZTAA1dZld&qa;zVwl zt_`OZ2UivxOE|_T@0C`y#lTRO7v4Frf z!9KX*5h(9n>Pb6h+Zy$5TBHbBmRH1t=v%TN)yh+_|N z+$9byK?HKstF2obIip*jUDYcqcHlk;+mNCkdrTs7;wzr7_J?8ptYw1^w^%Vq;c3kb~+qhYa z>d%Wb6j>uSYS>mWr-sRQX?`-2`k+_vNcnPeV;M2VHb2hmj(XQ+O~kfwo3t~1N6Cby>hZ(vTeyD2aYIV-tND zrg330a?55jvMcC^{_>CHVRFP++p1RRorl=`cWp7=@+?_|`^z$Z!==y6t@0B^DGXji z<*=Zg5+yPAYE7gFeB#F!yZ!WL3){#X3x>+vOV&%&1U)KaA>RjyszWV2bnj$u3$P;s zB{9~&en&BASx)iCm&)E7cl%4XoWrH}Bx)-_H;HT`dH!KC|D5$?M^lG}!u?K7Vac-6 ztH(=!dEo9ad29H3i8i4m`Udu^QNro$^yKe@qWGUd?c|6*LSj`1KOe&HJ~LGx%V+=E*9uqjW_f z_Wh_VT3;z;*m<+9EZ1m=jM}(LqD?4?e7muOI6I)Oc50o2`1?Vi>@uR4Y`1oiL``tL zqA$Lu4iG>59vEttKEsh65h#hinw_t=h^ujukGn8|XKBz*{&9A&w4Pig5k0<5Px-;C zw;Vjlwnjy6Gl_&l<-~$gYYl6P_mr6y^^x6Q#!0jZB~hfvt(|$#;Ocs(OJ2&#iL0fY zH%K;H86Zncx1Ca-c$5}*s>Yj7ZEq}YgoaAj0c~Z6aWN7#QSET2Gr_ltF?>SJoFd^{ zsEnXkWs!0*a$HbP+4E;_dCa&-K~w%!s}>^C;wm1L_26g+B2bboQq)T1Uz<(zIXs3IxTv~7-O(nL#8}IEXL*OfJ=)Gjos>Su_CYk= z*Dl(~zphEs@;>M!uokut?r`Y0&qN#HxIV9#vA=-Q=V-ZV$IzAiMfq>ldFOA(INE^- zwa?47Z7JFnjn$R)g1{N6`o)0-1deLd9c`k0Vy(tvS#%i@@7h+G zgQy9PO7d{-A)?F5gS`LtV#@qLggOTwnk$A>At1a-$b&)D*vgT(H|(OTE; z3pjcivlMqgu(tSg$wRza8=}~OD<|#@=nis)x9HupqKIzoqpatsJMJIoyB`5k>~(h*rE?}~ zxay{tD5!pQAqaEi9^js4uRLIiT#}P1<@n2{ZI$DK1{7o75o;oX{wqgAFW`&~ri{+hmRSmg%)z*^E>(RB^kQFq+K z(>q8uho6dVEPQ)9>A3SoG@cU}8)MVE%P$PZ9q1iiYfn#xoWDX0dfua@K7fMUT`R%K048cy6QLoQx&*tLv}>t8JDu|y9VhU z)@BJh3viqHrORJ*1U*m#L%yPrr+Ljh4>$8q3Pl8uCG5{x>dB=T3+N{gDVzQSeV zLjzh{VN!%#^rMN4uDDQ^zcxw^8qrif8ECutDHZg=kX&`BDBgS>N8QnK718t7X)R!} zzZiMqGDqDJ-SP8Cd16XaSuerHQSYxN`lF3E`Iyy@ImX-3CX_^9Q2tp(6du%2j4D=w zZ$CalwhCz>H{Y8tpZSlFi}$sV`|8I2W=HUdIXpR~qo^_QIY)NX9ns{k>Q>NtMhKCX zR$lBVFjAhY+EhC4UnmjXbbYuyd9a1dpMJw%Wtc@9Gr5p>?&~3{{v9SujcOq`CB{m; zb-+6W`li!IrW+iyi%nf?C^uNhhmsgub*ze*Q?tH!;?_>Fe09n&xvZ7H?D}e+JkxcU zoE+*eTX(bVsbd~p;fFi=2)B2c1nP^{s)z^LCd2o(l||q=uGoR-w|j@mR4;$|WQUET zeFw9)Xa7NNJ=8@(lz%@&E;`&=dR>qC?UroKjd|Ma`EU5>x9ydC9K4lLE&n7gYs1Fu z;Mq!a6et&O%!5X+9#6uB=?;Au~W$jp%ea?SL4QeQSiCJzXZFS5t{)>akn zKIgpyN{S9E$_lg)+XvB<{ki>zA)7J>)kjj*RT6JE9ruvsLoFPn@~a9}$XHi2nR%sBB)Ttt>UfW=H58 zvlg@^O1o7$NI2XbB**j#kQ<_7B;MVjO^iL5WY!j0qO@*hR0Q54BAULlP2=`xP$3ce zJdWdO3(rof9kb@-5nZmw^MapzmGdB;om4ygyh`(R#u?_Rrm@PI6VFs=AAQUFPBraC z*ca_q-mU_5$6AP{2;|YlT4w(=?E>$noYn9ojFRYEVcJCAVB;tA%K0Od)#PbKPqTZQ#9Bbhi!&YZZo@lBC#kSJwZ5*N8*Wx(F zR-l{eIsS%zmivZxE>VhBSPRi~cJBFpGs1@3Tqmtf?E^jDyZzv;*b)Lp? zgyWn?o9HWolft!bHL~(6T}CQ5?&w!kt)f4^O&T1d^TPc?l^KP#5KX_YmUxW2JuEJ2 zy{#!wE7Tpm1ie`QR9nQ&sV-_98^F=ypl?T;$hVUh{fE40H}azBIdR2Nz3A)EO6Ijc ziVOL=nd0G4cNNj};4a?(fe?c~=M$(E>W(V|eJ|rh4N)Pso(LaPOR)o299*^OTw64^ zKKA@eKJig4WgW!b0IrGjD`O3sBqvmDD%#I2rL1bGyNYPNYCpfcv7IpexW-Wv)E(D$ z`r`Y!ieg)+L1g_{h2uT}cT1`rr4uXbZ;lriN6j~ty$@=FHZeA=ewdcuud~>9{*AIP zL4>;Z@tob8-!Tsq$9`;7v_jo+uSGXlS}{@HyQvs=Fo%M`Jsj=^DLP0y%WDS@@J#1D zIPNBKPp$4O_btw&KM<|O+J4Ox%dr;jgXz~czui6fJ@+`#@=H-=XNk3NugzEy?j$A| z14J{Qa0BX&wQxUAyVqV}qNiIt|J&h?cb!Uca_Vr4(IwLhnKkbU+3!=Q^uK3)StjG- zCma9rIZLbB&Z@)2$7P%Of^dItEa|g9PWCNnHNLu|Nt8slnPFj~T-|u?wbkEy$g$b- zZ6jA{Hk5^X#7dOJ*zf^vV#H)0vAlX^!{lC`^68W4bPkLGU|fUV8~E22 zdAHXW8}ffWP-1wX%w_DGj=MivzDg<6X@)mwUF3G$&Nno$EAi}mx%h|AT# zd858~YQ$49-5XpVB-Uh2;%CQQFrc;A&xoe4S-JEOPFsKQfc1yHumt%~67^t&L0ETH z6*c^t8ju|=M>MU2HyVqm8fAo&OP}OZRYK&KyB+1MQIjNkYSlAbz0yP6t^a{{?f=A# zC8!BXq8HNdeZ)y`H&L(Kj)Pc&E3&$(84nvpm|rE4-K$6vmf)I!lIWWpolN3QSOw9s z)5avMg?6Zj6$`tI34Px3eC;b~Xb1X4w28hoxxbgFll2A9JL#YqYoW(c5iQMLVo;76 zBBI_@FN{Z{<*HT}BdUnqDO`NpSbc&V6Vtc9^@6=8^R6Yi6I#ID#c z$yf_pK}9S%7bLzHzso1)d6tYVit|Hl-F@VJ@{TSj7X1^~5N9Wja2)ycQjdI9VA0kh zTi@qi4kPo)M>Xc9dj@PPRjbBTp`KI|aS)ERi zlslMunUC%^K%^9_>y0Hh3LY^|Z@5He?p8yhB*rYw_i1|?3=u;QFZZGni=AW2*+Uj% z`^9o@MR(~MRLEMj&>Z>aAB~73@}Giw2Xia&WB5{=9ag&?SnKsSPiso=@iI174?<`W z1@-3CUIU$Gcwq@yZnb+}hShp^rS>beANrWVPo9q{d?PMwclXV+t;Th^qT{liOBqM_6 ziq(FvifDSTR=AR$c+e=W`nZ@8K{LtmTb-V}2 z+Y3k1DA{gpsNXG6Q$#&om4qeaudHxCn88PO^vR}Qxz|}Nx;Wj7d`X6d*dNG8UvJ&n zPA|Rc1--voso}WVmUD!4cKenx>)`paPS`N(s7?N|?p51ckQUBe^*XP<@vWmuD2UL| z2&;F|rgCYXg%Z*9)$GxI^)>Gv@#|rZNytII#A?qFsxfD@HPfcX@>G4>o$%b{z4Qs+ zUh`Fk8fGl<7o)ANd7H><4dWzAVr-?>LwD@?nP-aIWyV^lm5K;H*-4)vK)bMXKX0K+vbNACPys?CKuU7kR870yCs8a*9l6!MBd3htOjEp{zKIqE{MveNOY$|2 z9TETUij($LJnxby8?+xluM`Sx8r45h9$GVyIBfqqeu@?~%1rUblJ7~iHrdfA$@Z(d zEqVWQks^~zJ#SoDaK)+KeX-A@l8N$EqfW#T*ggyYkvvZ98k*C9B~gb$efBp@lnH*l zep{oKpZdK#`(oQBS@2t z6Qo2*baxlN)o}J`l*r}O#DJPihPFccD9$jU3SSUJ-&%Sw(i=Gv57+Z)`e3N%RGpf|t#kUyKtj^A?yD$&7Lj)thhW zTz!S?KC+_Cj+9?^)Sdgz{NM_G`NB8AOuDDoTNG;{nz2e9vS^>F&-V?s;3r{GFtTYSm}kba3_P3(g*u^ z`)H?8ZLyDV9PKy@D8Ic(y!NSim~b3g+>Dx_T$DsBPNpfzwmDde<{-*Kw2By!*h34x zGg{2@zedT}zuE*_8f{|CtNk=>`t!je@mU1NcE?(Xw*6W`HuJaI(PE%+fo&va^ev7U z91D!SEE3N@kmU|!IeGxHJY!#qbA^62)F({O;}Xv|ov3a=e??J)3?GG_kAA(bKx@5g zctP=W^>}aewdgs~gHs;Bx?p|4Kd1OEe$asXHe74b&(n>&N4yq2Doku%u_p<4thoQg z-lUUPU^!7Eo3ALCXPr0h&vAc^J95U>o+vKb8k>ucrLKEpbO6sgv_@q_6BrwnZMfKS zbscZ$IY^%w7p=AFwZN7emBEg>Pn^@nI+ikJ-RYeMjrRQ!dhQd$ z4f?5pw*0FMc0^ZN*v9%->`=LAu?>-TLWn-(`Jenyw?ejDwG4Jd4~uMLElByIOJ>^; z&b1orM=2}paq+gcJj;w7J)#|C8*3rT*nA#sL+l$LtuLMKZO-#zLX(Gz|2teTsM zId#Ab&oYRnJSnR^gO=`Cwhz}gUGC2_7Z0-KMrE+0?mug{wXO{xBCqGOWiB`H>aP!* za*{8h-^fLFM6W2{*1BXHy;Ce_Lj)gds|O6qBSHt9HzPZukLPJ?y?K9#9Mr&uaK6_- z-$hwrb+_g);|>|oA72JoLtTc-I<0JoQWlf$RqrETx9)~5r^ss0N=HppJI;=jdN~(o zk>zNDhU|zyN%YcUpSOOyc102Qm(Y+M(Uikv{gvN-Kd!dU(mcelln`59c*YqS_wXo* zvXJgM>IFBri_wq1YVLyqt!d^y@=eN4iJDLbl-2(Jhh95PE25wJ<{<{wIAF`a%3wzX zN}?}1cvsX@!yAem-vVvmyVDwzaNr^_qGC$_f*d6^3VWvYPp_St&}%2u9c@BM6eH6eMNfKBwUu5}p@rB!h^Ad1edqoaz1qq`uePujqOsM} zUn1#!=q1tzdWnQRg_f&!+>DOZ4v+3Bwx2$t*ntR?M0sSz-x|Uiwh@y9^DAQ)TLH%y zebsRZ#eC@1R&9EV0r?`Aznc}Yyfs!bfvx1|(wOK9kWWVa$QFrvgG}_r^ zP0*{YtJ~ak^!jKM`bWCw+*wC|Ii{Z2|9Z9=R~FO+y*7QPh+@dTp5;aD9j%o00}&{R zq6WvM-pxIqC^>Y4veu&RxF%AhXtzl(pZz5-y5)g}t1#Mx>lI_w-h1fFp4Jv&tDhw! zJFc9#GoZ|YH!bz@{}d9XmaI1;JEC#_K)>}nq=!Da)O&ufa&`?@eMI9Pg_bayij-CsnHj$TXxj5h2<1Sri`$?kILBH zAsY8{v~uPR)t5X;;d!qg@N(Hd<(&c95smw6#=?4p>yA$b@{LC%M|MQx9-g9VFGuOg z=Vl}?8xzHG=Z$DQC(v)vZ8PbK^b)BJy+lHG)E!SUbo0Y|>2-ZiaclAv<@|wYJnv9U zzh8g7)xc+lGp{ZvXB^ZWPh|9U7-I)LS8!eJ7`@uUlMw2T=Qg^jZq-5`Lobo;(@P{g zDWWE-9kmLz&~2}sqUf~~vLgZ|(F-?^(z@+M)d_l0h3tsNGcIG-Dz!80qgPw)>D3mV zmnm1xYX6=Ho>=LOvySV{-xm{+Q)bz+^fK-|Fp|Ej#1QMPw*hid7F+J%R_3I;jZWc3 zbuU|%UdCw~YgHIG*xGPJfIQL5hB$C-fY$e`qalCA(aMP)YgODDYTa_AjdZ0KW7LCr zYw)OsYqX#lgB3fl)~&w>Sx*;gBM1B05FOs{Z;Tt^+EnWNBZ_hzSE`WQ|}#2`Vyko4F(AfSALY#fUks0%i=T zm=GhFbB-&_z0B1$=bXcuS6y>XfAz@Be9imc^Bnff+3v5Zy1Tl%y83oCwiZtvcIO+c zM;{DRYS-sHhP}L`=D3!NH7^vzP!lpf1D zk9@7p$tP<2T84D$!>+y^p#L4wOewZMUcojYCAxj)Sxsy7!k;A?gJhH)&xf`w9HtLg z+*rA<&*8oM?|yY)hak2s(t{y)lwCv|Sbfg$t&KZtuqvE2SvOEm$Q7m>KOC!{V*UZJLKpmo8;~lx-cw3en^Sd+5;6d|DFbR_IgzrTZ`vWgAb3?*UhT0c(mYO zt6%E6PYwIof=xbhQ$~5QwIU*K`KE^T?dq`$^Sp$1Ao|{u5&FU9^_9_6Igg~}pXK3F zW;V8Hpn%AqV}yRbZhfWOiup=h*J1ki+zphpBRqT3-mKYJ$20%Pzn!niu$EWb;d-ql z^%S?njEKm{6xn5G0hZ%=ZHBbM^dWlt=tjzq-g6bPuUx8oYIO?MWj+t`$ar?wXwWEq z|B8Cb!+r}CvE?(1cUPBh?Z-Y$TrFb@u@<7~M6vKN+3l~6Z1Uy@GPVQJADPwC9-D~&=JtVlE(snUN%-dQ}>k-_Hl`g*Bh^Lk>mW#aC<%%v)xS-zS>ERu!$w)WW#o>v5KVU!Juk>RQ|Mj5neAodj_9nzM(W=?)>9fc z3)=*_(V1nXvZMa^gQ(a}=bl#4g z+q<&qe;<)opA`|`z7N-X?F>~4))moo68EpW)|kGas~5G;fV(Z+JBjV+Rox|}Wnv5~ z?-RjqzBu-SxOWoU;e9?YJGVESoqM{0-+XcGIdM;g?IT;#w>K-c;-WnAV_yr(jL22o`zK$+z zdA%^^rOcC2Dy)TQNs5UtVaf5wX!fOLHyNcuG-@Tii8Q^acFemmE1Z3b5j7m=Jhq9V zQGXlRvhXMJr90mQZO1m@+@urt{afY7gBvl=2@*r@C_BzzN&3?JH}x;~zO3qZRYs{0 zjaGtQ+jJ|fWjkSJBd5MMqQybmj%}iEipVCql1+T}tTsbCh%1h06GM(B=hG7+I zvfFw)84>6+p!dP0>LDMQG1FN6#VEn|K}oPp^fvjJ^Oo!>m*wV>edG1}#g zqf^Zje={NiB|$WK`VT!co{5cTv!bk3x;@`3(iQh=Yy0gs@@!VuD4P{(A7!)B?U`If zgbVQ)mY(emOAvv)DX&57A6kFP_V$^wy`dyn3)^SQ-KN=dw_$6s7LF6$?vHt9uxCjl z%i_=_)JjpWJV(c_>9%Su1POv=%inQ}Bzoh|2Y$dB?h z>h|o`^a{q_gK`k%fgDA7AW?SYhiJNg-Y8XGMp+%}Q&vaHTdCV~?jk?R@TfbpW~ZF; zF&?F?jw>juBV|_9?RkVLlcR3W_e&Wbb!T?#)h&mp_0n@RQl3QJp4}MHl&?{DX1Dgs zpGzA-c_0T;&KJ}r)I>y6ETiHvwG8EGY)&~EDNmwq&(e(iC|{%Q%!mDSc5iJ8<$>Hm zc_2~ykRPHcLcd^#YM~sB+bBmPnN?8N*!x$GMu#pTKg!prJ9BR57`RNWNqHcb{>lUCm>5a}=SkJ=ndGq+?!qa)dtrmTofTy-*45^j zhaHljUn(NnSMMoznCs0V-_#UlE!Gmf@Qw@Wu>PB_$_44v9ZS$}$N5j$tdg5Do^84` zWt&E8fVD)M7|^gCD_%G=TYNPe&mHZsCAdEm5xuw2`wTnMp9L3 z5iw`LGIa%6hL^FsRnY>7Yn0tPqsVrp>}o@@K4U1KzG!7|B}23n)MvefmhndSME>mDsK@var0n>(3ZwR+R?-(j>1;9l>eYYvBlrJd)3bYmW24kH!8Q8}j|`a-~vE zvvPIW)Q~GtNlHUkvl7(hGgJB}DHX>BQd~6OTc$;xzar<2&%}Z*WD0p+Fj@KYbAV6_ z(d4%uo3G~i6v>t}>@DLr?fC6EQljzh9HZUYKFheVZE_0ILJ8gW$A*~uCMhdY+K^Od zUFvIvs7MPXc@@?wBrG*aS=puwAwtu#X!oy%v3?#C zRiuUJ@w+>OTysfQwlCm_65|V~vz4*zc%cIpyorG5XEl3-+^UkSw0p)8RafTFUT-MF zV)o?LkQPd!<@}rN%bKhV$kmGw)8jX)m)CV-i~Afcsy5P_6hr*5A$igl=qcp z?{`EXCHmH&lxN->R&i}lv(Fr)d!>1+v}UC3 zGi=&k_4#%AK|~i;IiQ<*zgCYluA?T>QA8jmx+T=D7Np^Qm*ZedmbnuQlh?k z)0uV4^GUAKCh-7ShBUj4Lb@~`)0~!}xkn+^JAWA4vwu`7&7w5>d`1LPqP@YsDss+- zW7*q|B@f{J2$T>h(a!57zOyVqK?}&h(Jp8hV-%dGPk>lWOuOy zZ+0Lh%DMcOu_&_bxyiO;pP=kWi9F=9;cR&N`hm3&E%pf6U76e6S7djw7qK0pRMGqD zu|DO!SVXlM!AKVoNXfQ-Fus0lp!EZ_0VP37^rh_h0`e@fyE@rj)HtMz<4^Cz4bI9A z=4j4(xkU@}0})7x-ealSkQJi!V|u7X#hHT=qE?cJ{CI~^A-g*)+jk4jPNa)-g);oH z&GPtjo!G$q`vqHq2&5!Qrd2tZb$uCjmDUfmGAJR=U}|}j8wPH7H<8^%ONMmOuFx&) zMYoNq>w2>xhSMtAC`2G7YI*rUnXexPT0hVtql8F_zC+%3DwW&aUSxNX7TR50B`DAK zrW2MARr<3{H&qqwIig8ISk(q)s;JhW^`kVcA1D=~Nh(-5r?r@8;db{c*Pi`J=XIBhZ+zmPta$GAQ$!vgF1JvhT*=MyL^c)tc0`=0Uwq?_ElEm+0k(Uo zwL7U@8u(h~t{=^?q+)~O8#lQnDNj24E3KOS%L=H=mG&-tZ?MQcRt+^zSL5?UGAzM1 zAtlQ7;=bN!2#;icw@eY*foqhw;*6@?Njd)dCKY(E^T+cQUn#Y`|cBs@291m)TL$7dbD60yc+1Yy+rNUao+c67hSLD9l!bk8v zjUblb?oO0y#y>Hv@#M3H(5)3yHV&JV*6R=Y_GW3Qa(nrdv_BdzQ8IrDR&b@JufnSN zvsaa}Ft;_|)D3>uwdTdeIW-4#FqZV3Jv||*x^UbThDp{1x{5QXb2;_%odVBew7_AYFN6fGB2(ga` z(iN>w_+fv^XFidtLG}8$2BCo`{`()Jo9HCwsh|SVSZq15iLoB?!?RG&$nZv*ZnO|$~P|Uk$VEY zgi%L9et%24mO0-%W&DN)#ACyh@~mj)U^eDjOBGv){ex&iJUuPf$yR|q@+`~RdQV8p zo3dERQ6^YHelw=^OKXrXL3z90OgwU5jAX8V#L2TmqGjwKq^et7DUtY~dm zwMLJ%^`(|8m)iwUo>V74x9$VernFnEM0o@gk9GUk84tAnOMcOyAG3yiUB7zEa^;@U zUqSS>ofox+qn0V}t_BdoGi9CSPK&?f@eTWN9?Z@I(Nj;A+i>m6GUdVrzH&B9N>DvW zsx~AQNfKgjIiiUNbMgp#bXq+`eKn+1Sw<}kv5yC$sU0ECcDP-P)bdkbB~f4DoWL1{ zXgbxu8?SbtG2gr9Z?0F&u2;y9#v{Zz9tl&*YepLLURPTR)(80^n#TO>LdzD?-J!$( zl2PN3AL$iy>Q#YbfogBk-OzmpRMc0T+lVI1FyB|Z`?{vOZfbzgyV!EHN|F@ayo~m- z^%hI7*JgUB+G($FJjA{VAKO!{xxKm?Gj6!Ba^iZ9<4+s?+fC%?+&9&$ZM$-W!<#_8 z5)osYmtoIIsy-wYad*rQM2ME5=DS{U@q1U*SFv3LZAX40;>vtq_JI0o4fPe4;Os)) zl>K{bPdOmHyTCkuz# zfI5cSLuV7`7h0~9Ce9=)iW-NO6VVi5A#E>2+TNWk9BMW4L#-qa;7+{iPcv!&Sy7xh z$Pdvr3#VnHSsO>Q7Bvp};q0Q*~IH)6VZ|(S{#ojmUYH!WD`e|O+;&nXw(JTZ6_tjg~=v{kyL1r5iM$d zPFfA}P+u*hzM>X7)+p3h)MH7i@#wU?lKN^H^%eDxV`V{ph^BXCXjKcQG4D(kjz-F{ z)*?S#eP}0qH(u^fV?K?nD6Wvm57G28DXq@^NOv2Ng+q-)ez=O#2$Bb|o^&^stSIU$ z@E4M{-HmPnA0p#=~T^{N2`aj^HKsS~!9tqIb6# zrtYtAe52L3@SHAj$H$xQ%{Zlq`CXiOUL8^v<8s3_B)%5%tg?a!w~u3V#FJ{in2 z^9zxwWktDUctsUUkRMW#q$67*nEYd@eCqpBfd|hV`g&w*Wr{vQ5p!m8gpm-Z34ygR z*QkhS`@Rm_6#7`EKLNpW@4Q$rMJao(sd5~$lS&dtd?Q3VLSQY-)*~VkLvyo|A3WHh z_Z}J|cqXo6BNCN9c`GTHX^dWjBE*CD9{f+kT9~^_M7-)WSg!KSm(ibw*|!jZl;|Yx z-&|_##{Mj&k-x@sI<*?LL}{6;oPznC#0*VY2vL|2w+MkHoL`f~B&Em65;nA*675(n zzEv+)F2%Z6E~OQu9G?}s#VOlsnT33xm_v%1YFH<@NZ1m$$n%LKJ!IT}BwJ%=;fADuxG!ZU1| zv3uAw3zi@cky0v2b+~bu>`GE0cWgQKh$LmAzB)&}OMgNJOdJm!Ct3$-1Y6PwE}=2U zk>cZT&m)VvKwl1!UY#RN?DqfYl|2U?>X;q<-Rlr z-~8h%%v!94bCdd$=D9anhMhFeaXzChL5o4(c#-vaPu8a;Ss%1AXyMTEQDmEJVlJ|Y z^rxcjLrX2%U01U0HNq;&4O{=GrM72aN2^U)hiLscuhlpD{aK%Di6cK4|83VR5s}H0 z?S7dhQ2R)KXqRx*#PPTpTx9oSs{NDxumpP-DbYRQMF;#ikI(dny@QCPkY5WiS9W@;JNzyUzIgWPx8LOIpOj@9;R+IVNA9q8t>|3H+ zuh%i>%2d^Ay}wxZ8eGRr`QaAt-~Ev2OIZW8ALFX&4a-i}yUhtQpZIf$QZ>s3>tCJS z&G|nrP)hCa)F*H9B*YZ=(f;&plt%uQ&~lVelxpp*DtpdT?Lx!@>BcS^rh7f;qKDS< zHP0V9TVEMaL+=|`mUv`q*DT;NA@UPqb-O#(_h07fe~t|??>}5d`P_V}E_(-?v3+Dq zMo$eaLbcCu6v#U$e5$hLa6SF`D{nKlkM5XM&$o+f2yYAOC|VrsX^LN6$`e37oc5mn zupLMj+eGKirK|e8l2o?|f&Gqc65FvoAUH4^A?^|aW&eDC)AAQ%k)We`&lFQXEh^T)P-MC zaox?w5#aBlRHC#`3a$$HKnQM6kS_8Q5f9&W^8ZA&`FP-{AwrbO`%{e8Pxen;Qp?}K zYqk2Pr}bI>Y}6;XB4Z!kFve)%)=rj7M>`pjN16CV`k1xftc4pCHc#ucRKKk+uqO4- zNtA99!krMsk99I)2}*^ONJ|JYC#{p^Bq6Yb|89QTRliiBm>K!e$!M2h+QV6G)Y$WF zWJI)oIbWAv7uP3l_cRymus}bVqnJLd2DevJ2@$=mjcVN2Mn-MtzZV@3(4RgkYeqEP zf*?erU2W7%yV}TDg8YyY#q^cz+PVBqG&y^`iY52sC+dSAHPi2Isbp?aZJO>js*Yao zyf;bp{C+3xcHW(;SCO4EmK1ZFrGE*lrH?yWE`v>6_}Hu&>OWP#TzDd*m8ny4qW)%X zn4bAsB{TA)Z_jVLXqAUI)t--EqGAb3h?MC2M3O4M`%ZOK;hl0uN$h=vXv%r^(5w}r zcMcooc`8W7=@$Bf?vu^+HKT-d+IO$KmO0c_I}+;3aBk=F57b|}Ow@w{gUp7J{q=MG zdg#Gts!?BUB*b6!U9|@$SB51hJ5r)==>IOSm8eIV-V~7suT^*8B>nNTAT#olq%6&| zXeVbC*DRfi2~wdY+LHF(I^plx`qVXyq` zH1R7QO6_=8cVTLan*+4NZ}!Pp@@2e-_4>5MdiBp4J(=I*)}(&>9-w{y6u^)!|NYZt ziC#A_)Qptq22a+3^6o_c zyT!|tv&Uk+@uNC|uO&%!-^a=BIjU;4vQ%YAm;e5BX1;DNp_q{p`MVdc$ZM8#(t>wS zlySZDeq3B>GisVXaFD^=eCm6X$EMl(>1kXO=eXx#e)BxEtcyGtBKYrjOJjA*gkUqG zC8_kXSMs2Wvi6R$W+5$<5Gj#Vu`lJSBf4sBw=c9{33>xB=eAbb4jQU=j1M5G;&N1B z`+8>8f49|zxyp*-6?LEB(q=@{_i%DC=F_aURxov)iX|vJQle}N&xW$0r#h%@4t0>R zg#Y%aS5kM&R>~Y0H(z->r;Kh*^dhNT-1@S-M~er8QBA!rY{O2PprUu1S zG+-@6i(V#2#6?$3eKxA1K`e3ZqmdGQCqq(gT9L(4d1)3Sa>w4qUZzx|DzaSqyT3C>4J`g>Ig zcC=z%trdMckk9cLA1kZLz5KM;0e&pwN@ibc#g#Kxk&|k0_VU_ksXW7#9(@K}cO~gt>nvK4 zkHxeXuZuDCKhXCPy`?PVEnTeZs`WMhr+;Pl;n3G2AC5fagEGLRzFuO@c~jlXC1?&N4IZt9%MtR0lQmPywOy>c%xi5c!CHu>xM=U8TDvOC<-b<# z6J9>ScL9(Rd9U<}QdW9J$#Cp(?a0o3^}o_uDx5pMgCxES&}w8et^b!o?Ce61U@R## zI##dgQ`&|`O7to_@!+osj)?Ua5ZDWdCWK2LZTjX5^4sd?_=|;(S7I7vouQkj=eO|? z5kCfcXvVzF*pnAK49fl7dfA;bZME?20rBmcgjrRz1a|`~wCtkr;*`3vqrNAis||fC z+MpLM9Ao=UcX&s7Xw~VJvAUB!r(g-v#eS2ddNr4;o}-4cJLOuW;7b(v3c~2~iPkTz z7N_$t?%ASVJ3EMV)YaO%OJ~>L(oH5l9#{*}bSourxjJn4PW+#uom{4h#(#^=W&{NP>Euf3g2cR-j3HQBq?gLEC>BDhAmmVT6iBP z#%ebGe7V%#CX=(})K@a^t1Hx3)LKUg(#6*?=u5yoTV&o>BdM>j7NSvF+Xyl~g5flR zG*XTiB=N-v8d=3T<_Wj6u+X#ZnMpgCLj9xI^$Ketn!NCV9*k?^-=v9Hf_;UQ=xy?m z%~)jmjG~#N*ykW=xMH7CG}9cfa8lHOUVM8`Gb)y56xPCbEJVaa%Ko&DwB6&EwmVu* z+OF8O9eLX<1LKyVI9Udyh5aTX$oepDeGZfLAuFTU?G?VELH5e=#wo3wE`8Won&S@y2#-Vwf~KI2B8xTbM(Bd`VIQCj3ywtPBk~^EpW|&-_6r ze?3me8j8B?G zvw%7mE%*-7+UQ5}y^_hwoAB=nO86^Ud!F)Z-EO@ELbHX)KyE;dLB$tR+%I-qA62h zrY)9Lg<@FAsdo<`kB`UIw2AYRluVUe%!sD%eSFSZN^Oj0E#BwmWA2d3y-j9otb3Bu zty&gywL&gdYtba-{LjoZ=4;EJwfGQ1ev#XNCCCFQNm8L$SzR49hV@=Clk2Y4zRJ)@ zS$7{@mcG7vS)IDu?WvDy*LGgZUV?N*O1(b0sx?+bvB`;3$?J0>@)ay$tsl2sNqvxm zYl)+MlGJj+XA8?0&DPc(YQS39auLBtefZ;O*0qtvf+L0FEF#`}Ur8OlDw<{ectSv+ zULl%dud%Xh?<;Bt%x5o?y{~ZoQ`EWZXl)o-xW{DS&}N`FDOw-0aLjJuL~H5X-Jw0U z`MZq!yI08HMSG5R9xbZPPh>M_{dhy`2d;y-eu%5V0$K;T*T>gET*Gl4#1+owEivvb z$W?y+H!Yh0f9P(Xxg!ieXJhv%d4HaQJu9O>|)ySXPiqHQ;_lgwa`+Fh;Xk+*5>^%b(6;et|eBxUZG7yTS?zj)4pI;)2`}=>YW4x z(#2JRPTU`bvcY>-sS`tTF)TqI$eX@=GHSS3%Q>6ro1z{)SisqEIp*dmxmEGG%CIrsruTg-o5!?Xr1ZV*Yuf5v z*1W3ET*ddx8QX73>eQzd8-K?t?mw4$UHQ8*8*RomQ4Y5${nI%3raPuAR2nQj)7R2@1hb(`0>A+Xk@A3@61Lu1kr z#hbsCPqnMhHWR`#sJb$!)F2xIYpraPRXK5cW;!A~SCU*ax+9xUh_vEAOvM|;+7MW) z>4^l>mF9`*h~3Q%tl)(za4sAxfIZ zDfznZvmvk+_J|~{N-n{Chy5*=B1E~szDlhNxfIR=YhjPj4l;jc_9c5B=0=Er7dBMZ z%&KKWU@hzsI;l=ND);d#$BGi-%FEJ9`wG9?5LgR)gz}M(+Ho@ zHU!qXxplTl3YlZ;LpsO#F@hER+FkBjJFkqIfqEsb=Vb^{j1c_@fwge&BqD|!k6=wU zoReE-;DJ5^dIRKJ5h9cjH3)$vsEH^oz55#3gcTiMkQE^W)zaWFdNt^y(3lfq5h20}fhDNzC@q~w zNt@*dLk6(oguq(p2Vt~@-ua1?P8-v(C|q~fyMdGO!i4VNfwuX78x>p+lv;I~Ltv*-q! z@8c|S(iQpL*rUiBmXemV_hxF*Nha^q$+j7V5^^5uoLS1$0DcDP`>C)z;bKRYeep-3 z9lX{<_xZ}Www0-tm&x3BuF~>6KOc;0<0A)-uftwX_GDs-ldj0mB{9D|%Ox8tk*$p& z6-O5?GD-P(nV+9}nf9wu%D9m==yxOQIb)SHZ$`(1|A8o3aH_JsfWHmlM6YR)N6y+U zJA2x?wM{BJt?-81cXoTt$%*~UTjEnKM)P2ZQiabuOcsG6XZc6iB7*$)t*+yLMF*<| zl2n-=xUo~=d5qg@v=%%7=66gyZr%GkockBETyE~4p64wC8$Nfo@NkBsu7R3eYw)bh#H@*~u8 z>|Ja*_6U6^Lz-B9L~dgmX(DO~j-WUm{-o`(r0qvY+fl2}=If(;iC$;ZeAG&MX@h3e z$lrU*e`T0ah(JoT{h)asN%Ne~D4gdwYsER3NY>{pS)Vh6Kr4f`M6?VG$tE@+o57p|W(UZpk4lh!C+%ekg{ne1zn zxEj3YYwe|uEIi?(Z9RAT2F|rsTsf~Sh>_cP4`Zo`m23#7kK^b1M}4M!R1repP6%s>x@)1mnh)*O_|6M=TUbk+A5CaK zScLY2UWC9M9o7=(-~rlmW}-c30Yc!e5o?K-A%ym|0kp4OPy1TbCG0os5n2an?|ho} z&U`0~`h&HwM@SQCe;!Wz^R0wH{lQw;Bb0xaVgRiv2Ecdps7qK2dxWx6Qk-EJ#Tj_i z0QCoJVUN&@QxwY>O0kRsgh2hlTB6-;nkz~5OYbY{AFF-;O8sWF@B67obZ6AStNB~? ze0pC||5zbv;HX7CqB|oK)K?mhWo#j-sDE^bOgL&$kLb?mN6>qt);zthsDE^bemH7T zkLb<_OOHOSw8_+0i--sH54}_Eh_E^`tqNn>3N;ofUR0j()=)k)*3hN7Vr|2lEkv=A9Ly29AEi9--5|{F${k>2r|g zoeq%+N55f@NYakv5?WoFgWNLEywf52;pjK)5lL$P(O1h(bI_9zH1BkXusHgSG{(^* zbl0-EK`TsiFg=Q+LlnnRi}Xsj$Id8vemjRYKYewk^;Ng8$TVvmXqvUUJ%VKOcU8N; zi&7zi{9xVbA&)=uQyoC-`5{_4u@>?Z5mB4&tL@VLcI+$UN9(-q^z=s&VgMod>WsC> z1JLb$yNDnUK(%`S$b&op-M*V3&p>zXSZI%<+V?nEg5!^r=#AVnbJTj|GaM$Vuon3Y zx_ysBzJ%4e^GYHF-+A%98kV3|A|<*@mL#hsX$P6US99nt?bWRI{UGfut-_vDg*~UE z1m_C!Bmb(ryL!$)J3G?Kwy$-}DDqyc_MI^KE7o4;qm>h3e7Aj9J!JX)$aDGZ>aHwf zExYd{A{r{?)cJ1$*_isi!mQ=Ba_^X~G^^@IbiJ%8O=c@oj`7_@z}`caS!+GmkcmzH z1F@^(RHa67+m0U5X(qMr=Gv@3#WIinjcMDsNJgcU_Ex6=4+J0)*^ya3M{cu z8Iz?VNp)(hc=cGq~eI$lvnM2@v>&};ox++%-hTAoCjT4_>?|8 z8U-az1V{HUEK{0w;X9Vtq7BsQo`0~Mi#Hg>5-+Ro!DUM2(2^N=oQ#pxY{SN|GsdH~ zb7y-kj)wDE;9W-AtlmraEU{1UJd%7y$MI)*_E_H$`zM_M+S4KFF_fxA8Xg2wU9e5+M?r=P{lk1eQ>w$X1I-ijWe$srSH5 zYfq7)_+ODCM>~4-i?t#6nGRC2#g?>d>9HlGMZ0(%Vp$GKbc(z(M0@eYY-~n-g)KxL z*d|HpPUA7;cBHXem(w!#JN6a!Aw``@OBiX1od`v*jMl*>v<~uG&XwM|4vOnz!+nP=!RtKOiwR9^2&ezyWwm<%;(G47UsiikgnknF zSLhX?k0K(L{1=Z5{VUO1T2FqWJ+h5{B6@wI4@Z%0)gIYKFBN@J(X*sDwQ7%3qwkFV zF8aZ=cP3ANEP49JspUA=aMq$nE=hEXtbIFQh4Ro*)Bx-iqS2q1q&Bo;`Hglg=`jGu zo&#%%Qf;AKQ9;@j{YE@+_k*>>mh+ugrX0Uck#UEGwZz`NNxQp<^iyQq#bGUR1gp>v zvMB8!-AO9kDPk>AOH|sWM$s-ciuSc=GqB&py;>LA2}jaSc;BxWfMYLgvuom`+E&8GH=*LDvpv}Nq*dr97r>Ma(iW=}30NM#YYoVAiPPW$!s692E4X=gw&)2i|OEXB(d`?H+Vq%6OY>1CQ!pn|fpApiZp5cX3! zj&Ppc0b-m;%Ncv+|KG_w9YM7v8v=GIaEkc`*@nq-eYdT^a7mv&9>_unPS!`cM9?p^SGX1FPqqu#LZ6oOH!;Czf zEfo9eKgNTE;{U|n#ZzQwFJzR;NlR>pvlspsVrrcFuw#xiPU#&$US-5EU>rOk+N z_PaAe|6dWdmOJ$azlXveAs)2;+5b7eRU^8Ny&C`R+}-^zgnb9e5zbZne*(`Kv0K?2;6Nuy^o9tXP@A{A1P%- zpj0rLj$JVyIdKG?ed1*WJ%;xEF9hf=pfe(zed1-s-gQcw5#j6;F(&ih5l)R0;|%{D z;T&5pD{9GqM__~nNASNRFrI{3;zXzg|CEnj+GsSTL<(p0cm~<*c1b0V-yqYj5`2x? z^v8ZVI5o+bgWlo6l5O+LE7f{058<`MbIu~!RQYxbt6|ovNQSlWlwCwD8?;{b{HMI^ zT515pv&}CH+>}8Ntu{%Jw0P3iY-lPs}^36C}(X2N!LW&rQq&`bXRxIsQo>b zsK2L6h1^jpq-2|eYDoGV#C;9TF5Nx{MINI`s=FlB&|mYz!5yU%cSU3w)YD`cLdY^8 zEv$vSC24+}?sCs-b&SWFj%LRvt~ZsaQ#T}ta>(GE7iXVC7~I~=>bZ2e4S_m_T1hvH?^aXY(xoCER^Z{#7#vxO=|_gCS<+ih?XW^S z9NLGyPWGxzceO3`?r~~4^_3O+$}yTa{*v@&fs4E(ZkJqTMx^k~o%k&Vda^6~hsrBP zZjeWf?$6^44j&io2ig@ngUq|c=(qHM{C!a*KmTxiFUZlb);cIrmYdIQWMA)m@~agi z8TGCSde>nGEwf6QUhG|KGU?ne%^#54Sm6F1k1~`wZfkPbt|&ZtCYI&+IVLhOpN{Nkqh}z#{UH+isSoE>V=BqU=T<)15vp z)Qmc&+_(^u>0({eKM(3qJ67D=V@&d&YpmQVnqjT4RdSnp9f~#u45?#Q3;qn*U8;{M zaXClK`Dc&ucCop}#)QBUq>Gd!>GI%sWBYk0jJ*nrJg}$#u3yyT-*Azs*$>{k$?sMh z`yYL0Olc9tumq(Nd9orIgFVG9Wlrmc$BP_D`e!JVkXz1 zQ1gJPd)Nhk4^uZ2=do*pf2|oSKNuSRElL$uC|6L|DjueRRBLJTU0T)(9;OjC#PGku zEoIKkGsG+x5qUcmN?TzqYPwN7)I2`HoYv(~Dbqq*J0=^qras|r*;3?%Cz-x z9rHiWex|)1*V~jknd_BuyrAk^>qqK*Z;=N|vemFNt?sj$rhP8FcUQd5q?SMa^}yAK zQ4C9v2TDt~g!*o=^xVD0m`qY3cWj4Ntt2OUaS!(x+6WB)drMf9gH z?bMzwdF8S3BN>(;Kcpl{4f=l4*Ee{D(4R1x4cU%0c1sgk`)z8oI4hb z+|qeep7+MPce=crHR;{633N6XupPjOty8d}N z!y-Z;-8`lWwp!c^7ZF8@EV1nPyHjwaIfi=~4j$fq8?4+0bN}H+%oN-2xFD|WUkBec zTr2Zf_6+YK_$8?Ab%(l|IQlEiVAA#{MdhA8>(!a??$7wwytHSACFq+JvE_rRgjWQU?UHXc5~W;3EG z4`j=(a%tZg#(JKk8J3`bB}z4Eb(&o7nZa`JL4Vh|&-a^cnY zEvI`A5Zd9NP~KL{b)#$+5s$a-l)oR{W2k?5Aj1;;W*c{Ulp&UQlqVk7hzIrw@<0jc zHsFh*@_Op4@zhrmi~;tQ*z&Y;ODwUj9fHG1OHdnd%u#zNAKCK=bn`o zkq6L-JOK0!&;t+==d3x5S85+IxRaNG9t(OIB4TjnbH=)!XHufclR+;GJsA-(u={L7 z-b7b<#wyXjqP}wYzFTUQF#R?!$rM1V59JWrG25_av#We+WfVjI6Kf&brX?285{D;D zV-EX%JZYfy!*VBm{U9v?|J+$iM87(cXer%rlHq)a==>YS@`kkMbV=WH;@%Q#VZTYz2-?>!p`9@2 zf%{jig)^AG#i70P3PKzu1lbJ7{tUHG?A=DRKX*-+3U}C8OYGf1iUGK!?}Tv|kF~_! zjiorlru5#$NCDQuv7uYo*;KV`%U=;lj9H-fg5yMM)S&h1Zxn&dNfAgK5A10%CPVQ= z^;>#85o=*ji;<$66kGb49_zz66~>kjP1$rQ;#EC8;)T&OjChH*og#O#J#vTh8Anr$ z^(9YfD;G(R!(lBPO)&yVF*2FAqbbG6F#d@#OGMN6yA(<7o*wbSs4PZOQ5Pg>6vcPX zr^l}_HjVLJ)CIcxx~?O8dFzrqz05q7uY>l}1>Aq&zJ&IiD@L)GRs7^53(E@#^!jmq zq_3k1vC7v^_FYt7#S&Z-k+&p0xfR29UN~SFbKyX$SmNBJAV11sN<8*d^^?aWmRFH3 zwnL;eX!AKa;Y2MKeKwEAGaeZFYztYpA=r%TF78Dosd!a-&oWycc6n=d0fDZ|b#3(5U! zhZuupVc(A{wIp>7=zbtm69d~YpbAH%*%9bJpf|wJqbP0}Vqn$BR?)Bo`5`5GYH?VI zTq&17yB=Fj;DP&o^id><4Gxi865;_Numq(Nc`RvUmHj`JW49C^fd`Hn@}r&C?g0lz z`5RcL>0&$355hJ{(urnywDNJD?CQ(he9TRDEx|YpdNmXmB}7j`JR<~_pdW;kBq_&~ zIMtg*FfGFfqOXPgD3eY<5AB$5Vb*9#ZVgM2uGo&l5hJwRj~dC9RvP%Mb$sc7@hgmL z(F=Kmc=NcCoUqEEVhQ?JNJ*0ZB}C5$jpPl<1{G_ecP1i|h7HxOZEGWMI@U{&3fqAZ zJ&N2-4%eFdyqC|mU#4OSwnOBx`FxC)uh$jBnTRW?86|;uiK9m($>+~{T7wF=Wy_zB zR2((rhZ55FyYX>qiGh{bo-Mu_&NUoCaXg|%dNAo~KGrv9K@Ig4HJo@jtP;iaDT`p= zwe4iD%RN=JA7U-11-DJwarfv|xvcaa9j|52q{C&m|K?KJvjhD?@OJ@^5(*K#NA0Jf zh_)dldNYI3t39^8n!Oew9BYX<9vs7^;;;Q7ciwWlBqHx2^<4KpAVelYAYG2O+b%AZ zeQwfAW?kKDHmBMN=~CHOHBQ%Fi}SOif3>63|KD;rWq0<14Ka@1m0`RsNDHMxX@BwX zCB!~Li1Iq;<9{NccR@!{68zR+=Jol;s8SuuZVHcKZ;H>|Siao?E04F|KQVn{LGNNZ z|GjY61XC&ctv2IvpS`;#7!N(`o4S6eh}a%A*%U_T)&uL9h3JlS@nLCse&LgbE9=KH ztc5WL5fS!fk367(hb6J-K=!j!7NukR1=iIeCUXy?i_)DW$^Tb~ITw?aHa^94_OUie zHE-kZ@`!oArJnm|w7>&pM>JWV?a6Y%KEbJ;xrPcndL1zR3T4j7(vC zhTeVspvdKF%rWe#JBDEi_OvKfy;1k%szH-1ujQVCR7V%YD2IA3upV6>Amj$1mQy}} zse1z~UPW6otc7>DF)~FbSeF~JD=wKWIX@L=wSD81g1r}59~ATzZuEw7Qlj_IpXOrcl4@B}`?eAgc$*y2loPP$U^de|uR8s}VmVj%Vx>j51=jxF zUgpB`0_CrW1=f&)-eztRR}E!NT=Q6(Rb47$EkxrDdAj-HKbplKSQOEJMycOO)EbFR;G3S6ImLin(7U=`-d1{OD2B5`1E#5lgV;NQv@a<%!fj z)O}^~`Ews{xo+>>N3|04ffbACUT-~l@9NIpB_0~*QJZ)WE!{2^qVZ;jBo%EMrPZIC z$5P`;UV#VR><|%?nzz=5e_Up9UzU^im2Mwr(j~oEx>n-70P@IIhiF-+$(Afty!m)I zYT?}j5pm#KAMHr)>Xy#2r@59mc;MXwyh%WD>e}SVbenFu`E-elCD?MLMDHS>s;I?z zCR&U%KTs;taQ#^Nti>A4Uf$m%l>g}Cii9hi&C27=utWgerv@%$otJ>XHJitfXfR7(X?Y72YM|FLK#m=R!)fgY58GJ^ao`?LM&sLmlmQe1zVdRvGoB zUxv4~#<$<2KJ@z2Qnvm8Mjne}9w1tLIqQgP7VXr|Y=(W!hzGpkh3`!uB}p<}o}`Y? zxh5q`@JNR90N=O3ccmyYQ6xb<5bqv5C2g31z*jI3O>v)5zpK@!Rgkdd|N<@@>vt1r+j5JL18^on@ z__g>N6uvz|FKrxYDqsD5UaH5oKLiB68HH%dj=%Pk+~aB2)PB~^d;}dH>wb6*3SUH# zr0Ne+_&$6c8wh_F5 zJL9WO_~sLxV7X>x=Ng~2Eb?h5AW(Kh(@EUH0c>n!4tZYkCO)GaeiXh}gfG-k>~-e= zHaqVmOWk~X1q8lbglKv*tPkBl+T*8|pPq#w4}8Z4Uss}-Oyi!cJ*%i1%3qMN1m8qL zO7uR?{eEoos;8FDR}Rk--!8(JkLc|hpJ>W*bJen= za8Ch2)<>~>ONf@F4OydD*1m@=*$cno-jc(IL%R4%5Z%E#5W|)|{3msO^#a_s+s>MK zrhP=?8$*&5L5PK2pQY}fUO;$#2;V3|N@Nr7R$_N|`KmYKYYA_L#e_{%;`{jMeWRwz+XF)w8!J!&>;RkoY=R@qyJ?gWwu!y)*s-0$(yiv?NX5 zRfN3`&!iT*(@;R5h9jC@+BnbH>(2&t#@W&gxo_JsSxLxTRWGVnHlwt3o4iCRwyj?u zHU2hZWX~15J;&B+BgZJNHHzp-C3*gVq`DHyE5VLih9Ue zpZ?y5XI>cf{EM9V_gZRD>-G#wkO$f^(%qsEAdOK4_#L0Yj zz*?{z>kWIX^V;(f{PS!@HrqA9@*vH~umpGU z*e1$CyUB+YvqW2%D-#eX6{5*|-I0fxXWq4J+ZrxN<<})z+5di<^?knpGfF5)cUHD% z`rZQSw+BCk6$kgxL-WNcZ>r?hPnN1g?RfZSOZFnDfSPlGtFYTfNft#-Q&L*JvMw)G zl@NV%HfL_`Uo5u<RbvSwg&D%4NfY{Pw zx>B;Szkai|j~UUDG$g(et9mF%Jz1)tfIzw^E%`pFE!c&xl$m==W`-;B!PYaB*$LJ4 zUWdHR$dCNQt*x1B*=FjGF)jk)bly1S*dSm1b60OOq9v(BTzfVuq^5eT#~0!Cx*a>? zlq!8H>i;(OHaF@Lr;NH;MR%*i^D}HN*nxeH_f^%$pM^0uKa5lAZ7!#mnBi?kGC-ry5D5pyNR{hvutfEs1+Ohkg)`LWbhg0 zcVM0){nWilA7$i@{U#!s&TGfI-ZQA#|NJIn3q4xLDXwL!>gDQsXLzM@$b_~mu9#Wf zU+t%iwXk=QADz)RXv0=~XR7wnh2cn{j){ophns4%N*L~letbI6TC=d6>f3DD1;n#Lar*QTx%Kg+`G}@d%USKTI(mR(exJf#`any&GY@oe#%&aQ5B>lNk3PY)0AoNQYX2Zg$PUB z#tAw*x!)S{*3bOVeVo3lMydXGbI@XWB?TVqreLPLRKO{hN_``#1UY#kSS? zpVD8|EN$AUFFUmr5TUh3=u^Ju(!Xx&P$)v6YDCd!~PO?!u@*;(gVi5wpJPu zXhyUoEim3xFSlB5i8VzCJZSB6M5aDz1NB#*&spP&alhn9wwG#B$ahO@#V!m>kO#I; zl3wS%tR5_S)biNBmk{x?rViG<7o=J56|Z4NN|cS{@jW$Vor`7QLR<9QAxYTG5&G1v zJFQ(;1)7r^4AYM(`>f+1@@%?O&)!hmevY@O(Gd(wkO#Jja+v{o(xNnE>fcL811fg?R?*IW`CH#qjJY+ zy+@ht)+c=f%rBOY)eDu`X1$)uwcUSiPObE=OP1#etr(V|R3eXENp-Z_-GkNnMN6{c zGbig+M^x31J*;dV^5pjy{6WAVzAo!W+jHNmg8&YNQp92#QJK7 z6YHw4m--8DlV>VBUS|`_=!HM}njhAgsLyEZqyI65Tb~D;YiQZ0w^f&at;nzh>EbKr zbYmn(Iju|yf3^HXS>Sm6kzV?ZT%9%Q7 z3t#xEjf#Acv1H-%I6c$pGWwh?w(}1MZ?cIe+G*JmL)Aw0zX&|?6^qlO>ig=3-)(EH zgCD(q`n|c<v!=nZx}E`AJVb9et9o% z$6b|dyJAxFHT^1M3AP+5QIvCT8?C%&OZD!D9|8iULNuKfU2mdwx>H*neK{Yi-g=tu zn&?kXU`6il=yq>O|$VQX_d|v+ePE#nBw$eb&#ovxR?Zq9uk! zZS5Me);LQK96&dN0D=67$K(^ni(irr_qIk0Jn-FLq$Ek}=eik{jVn?spNe6~9c34J zv^qc2xUfNs)WF{B1+C>Lxz)%fY>AHoa77#&1PbnCZz zCZk*Dy_TNWqZvx_{-5D=XMB!6kWSpO*CpwaHK+XZW6#uV%c2<4Ws6sZq@_;OJ9P*( zi#+Bgt~buEF*EqJ7e#X*%9+$?PDp{-f9Maohnf*hd01+N8OxO0W(Zv>B6_{a7xHm+ zq&|;E?bG_!A*XH()+-F=BiNn392j~<3GPZ?4j>Qwa^Oe)ZfuxKKRqgjBMx|GGqzvh zYP_^BhG7ZvKuUCLt4FNy#;68{P5ojRa>sUvh`&qckc%9jnwoP*6vGx`zln&5ITeHb zd!_6@`ZI>1>{0)&+{IS6cNR49$QclK}A87P{Ho*20J*jIb-)@cXxN!H{1WK&o#e~wOH${wdcBH z@2NZHp6hL8grNI3qBP!^d z^VgnpITa^(e3mcGKkGA|7wD?>cL*k$~B}nN|X>N6{3Y6BgW+IbjvjjD3~PO z(2ZlF?WA>DtufR1i{Edz-p`t*5>Z~J%&AEfpNKJ^|7XULrSkjS(zIpdYnP2)r7H=oMfs7cxW_;e%Ub&`G1>`x==2c=F1$Xvx{UPj%$C>(_Hp{`0$&_!9Be@VyByPXFTUQq`{e?ra`Iu@!zz z8FA6YC9nN-$3`Q+CsFK6qk0}Lq7uN}eM0Q=|V{#5vD)qPr@W zW4FitBItoaUxs+Qf1@>GX878iRtPW8s?V-O(Qk;pEFs}vKcmPScNxp4bvOkQX zKN|gTLi4}*MIr-xf+cP2YQva!JBt2q^!1{5SVT-bYEbt&PHb@>m7*slUM8pJRDHtWe=!w|%y&glauH0`r zUuV4mBQe+tBSMODrq5`4wQmi!hV(UHga;!(a+EC8UBshWc`(PIodlmCLjHo44u2se zsT%XW+gXar;JcE2;e%T5AUm!zQ^$s)a!aKK>bl#>d|~ZIQl6b0QJg-sE4h4-w_J9e)vw4&pz$0R?~vL z>uRf-9cP#!fSChwK1225T{O%2gG@^b6x8quBIN9Z8-5>Nzxv-dXm?+(J_B~f(Xp;5OL>S$tFF|v`2!R!-AQh^0~W%i6&-MuSwo2ks*W` zDVQOIJ_q4RebJAdS-sycLu9>RJ`85P$T=(`C-t{fdQK|#23%!OLPcr!bq5N-)(v%)+woaem&-_5VVK<}_mXsxd3Hr)p82PpBAAngnP>9)Au<8A zl_C@HqsRorOgZcs*kgWYO=?*pYcf-0P2xB}y0TO;A_sD}$bpCWyQOp)#S6U?W?97rMI-@MM>`H57|PjnIai8x#0 zEGkP?@_{9tF7jT>h`d+KD#g54c~yI}XDgX}qm^G3k@1Tev6%5I#>d}yq_|n`SxwSJ zWJfO%+0mH4i`mhlC;rW?7CV4fHA$A|^S$pyjxgpPV~()s?SHeT#ck#fR5IazId?dR zV=I|Qv1Ut&B69A+Ma~_r6DT{P#my(_-$dPZMX|k;B%SWZ`9mJH!8?-;YyOv|hwB7N zA|tBxtVnCz38ptKlh~P=cKNlMXYpDaf{ZzhZ1bBxhoV>RyAtwgIBgZm5ypvUe7L z-CpO>;f#pg9j!qh9XxCrx42LK)Bclr<847kTbthbQQaoD3(ZaPtE^so$-lR4 z3@=+$M?@FzL0xCfV!??A3ARGnWyH*dHgw$P4s1_$Fh%Z&M&81=bk&!1skPW-XO$>f z^oaIYJ0ibGfjFKld_W>hNtq`p!N3&84{caXu5&gzUJ{d%}=*+cd;|B3H!s98v zM~(~07*bVxXVZittb)GaK&y-)yiwm^qpU}4Yg;yJ_jX464wCf1 zR)|&Zz*IJLlj*?7F%*5e=<7vFVyAE0Rh#wJmd$bgNY;4G3aG55 zaKGxoMxWGQ@PE4dY-Mb*>Da5nCXqoJs8f)xKiPdZXklt+#|wep@1 ziRaF0Y})9QfZZR``OCZ@WAjqY1NQHp!YgbEG8Rc`8gP5X6rNB-?4eJKz0>w|$?}49;@vg@voBBKO~Zs#AiIp%_$G|G zR!brU17j#gtuR)EloaJ$tT?0JyCrR0eFhV|RQhL^igZyz;Uio8nMFSgpyQtY-n|C= z*}XoBC>&6^bT;27W(hKF5RPUwU0cL;Jvoe(W5_Kqm29o-&6jq7JJ)G(^_FRGQu=1ax*K(wd_ zuzv_s&ZH5)E<>g7ffAxlisEvriqlar_x`t1VQ_R@kPT|~%z*Z8i7_OIi6@-;Tc9}ze{ zaHI);V&gRC-LbKueo~w?&XF#T6>+L@Zd1*ojwP8ix++Dwh>*wmTV;&4bGHrI7;w`c zXCIUVDT!Oz+q7eoU$!uXxg-S&R+LvRpPBEJsjO>oxU_yCLSCbGH8N-~ zZ7#A5m!cF`NL+DnEfLX-78_0eF&|7z4P&JB9O>ekC{BhgUCJH~%4M}edr5l+M9Ay; zT`zIxOXCt+k7aHYcM~WfuI-9)zEnd~$2)~tZic*vL%O(s5Sf`j-C5-M1I&*6Lvi=YZUEjB8ZXssADDM+7HidgeamK{e_2Gk_oj(td7+IXOLeT7X4qvoX4=1GjAVJC zBxom!Su}Pdd3j?BE7Yx@WDlYwXibW0B+D#m^B-5)k%?qp$Xl=_eDnNw(k2u=1&Bt!hOiAb4W#b|6)`lff0&>*0@3I@ z5jop4qDVJUv+wlJk&=f6C6Qy>r~K;C<+G=daj8xeX`v+O0}>I%!$axzzH7+U0}4TJ z6#9LTlE}HM*^4~1>p(W187_IFP!jZ=iQ8yr*P@O`OVGVJmK1$fC<%Jl#Mve5Alhta zWm;@dEJJS{dLz-pCZew`RkCW#baHsuFp9KL67(~Q`%+66p=A&G(7Rt>5afYq^hSz2 z8FAXF@c~N1r~lqr{`G%~{gw7-e}xi?4D3y>4I^tUCM6d~OI}XQVR-7WSnGT@n;#Gv zP@)3=Z9;21k(1F$=CQScjbZz{l5UT(x!YM?^OIwTn^GF)l8D@)QdZc-A(v>s zv}|5e0&EHi#ai1084ojPkTLVXhQCYb~t{L)@hv0E0oc{ zpp#<7E~)Ft(Z@ri3_9H1%RI_t9%Zd+htf9PZt4E^zZL}U?qwdX7Qfhlo9*b~^ed2*b3({aTj*?4~A}Ew~(k|L!`L` zTgfx^vDf9a!zbF%mBnWn!lq0Nn7?E)w|uV}u_vOvt0*fMdTB$;dC|dM6nf0B_l$Y?3)Qwrtl=z9D` zptiVk7P-!g>d?4=g4)hND``)SJdlz&aac2&u3xZ@7{huR#COjB(-UzIhkHBy9OOUL zb<-TyaNI0{2$UW7s3N-bPZD)YyzXzkG0A{WkOxu{nVH1{XxEPw=`HI;OpJ;AKcg1+ zZSrpEMEPFy?$cGoZrdgafwCi7@OWK~7UfOp+|iHnkQUBY$Xf)?-zL!m`xoaq%zoyF zbg`AJM`~z2`f5i3t=DEnvL>*V{5=F0rDTq`78K?y*=pEI{Qf(d#W;6f#3qQ|o-BGh zj%V!cGUD5hky@F#9;`-=FTwc($F`90@2sRKckM=L^GJ1)VdWWINBMuVh&JVSFgR{j+lptgNaJ%*EzGm}6n~|KV<8+%rVyLI3bT zexIsy?dO41e*e6F^QQjyV9hahu+l(jhQnThXtC3Ol+BhNxJ%rQM(Xb>;Lp24eu4-6 zk4L8^b+n}$!dbW1jVbm9>`RCiw)4|dtbuoJ`b2yW@fHLAd_m+V-c`VV?<(x#U~TKm zv1C=1$prfk@?0tw9 z{fhqAuTsK2Xsf;T>D#>x8TJP3B{)k6PpVZdTDDdYZ7^rE37=r!MM@%*JkFXVRv$yF zcD&*Lf28_5R&YP3D2L>CT2JsIrx6?y@~bw#VNK~%%UsBsKwEV{1B}u&lcCwYKR%G zlbGRf20(r|f)(Y&yKFXK+g-BucqGMH2KgcS|IKjs#SC{y%y2l9AwQgnej~>H^S@aX zXG`RVXyLzFQirw>Gn|i@;RN@;>j(0~8CCT52ic^$m_@gUSrlh|^23!uQT9DOMeM~aYWc1X#nlV>AzD;o>pz>Mh+a}^(L=po{aqmujl4y* z1+hBM6g|--=0xm$h?e{AgUaW8EJUT-dwSJgv2I5d%H*>~1RAj?Vvi9uuMA#{*m8+m#WKN0N7R z|DPV%3g51bxO(c`PW@fo6)0?lZ&yZmwp4vrh}J>6=I{meR)2O#GU8y2x@)CC7zF}b z;rEac!!2WJ{Msn;;cP=P)|A0*=DG6b&m4`HuV(N`Ij%e|z{z+cH-mq)aN|xyKlSVS zqZ;+PQH`8EZKT*Ls7oeKf8xqXyp!>kcP4+^z>T*MzeRR*rL+EB+dS~Q^f-zBx}M2X zGu`;o1i2NW73G~nRqe;ULhM_$5Q?Xw5uH$EGB4s%m)nifd6SB-d=#GHMoQx5d8ry-MhibZX{@rIKT(Pca``Af^v{2|fLRM&o1T??+2 z&MrJ_Ow)2QdCjY(xJ4sZsn!Rc5)+ZQ!6MmhN(M8DC^9}len?3~;*O}at?NlPb!|b4 z@=oiK!Si>N;tM{y7!$6i^HcAN@EwnIskZjdA^8cPSh2#bDawoJCG|3Rm%2rHNZGmq zF=(6Y2Rind!=w4lfx(I+km6Ldn2iMG} z4|^D~`U#$V6L~U+?6f|!CbD(KiF76o`5`4m`Jk>RL8t7s)mIu&loz$F>o$?!I(^C9 zzq+T8s#o4@(ooC}OFQ~gd~&JwM6L`uZypuzX+%n*iePaU|5LoQ=AIZ%QA2EnXhoUQ zV<{`L=qj7*6e($r=&jKcc`1wY=3z;?RA*Y-Xs>sTVy#1rQgs;AcH*9i+`7*>bMZtS zQ97zWDPixSh4=EJ$ovgWPY~XKJ$|2dJVcGF+)uK;;c1wW^0Pv z5$))k%u`qGHE;Q#Ba*LdVs5_I*si`26uBdMSg&M0sLEdR<1ad5czQ)mZP|zYIM!6E zS%c_F>B-zWagW*RH{!?cpQb@YJhV*fh7`G@>?NX;__;pY%rlDX)kqp|oyKZRE~zDW zG^5BJ(J8Bw_=Klh%^_uV#Po;P*@Y_yS;3q(6uBe1@TDYvrTbR1tF?|;+Nrd5^J*A# zt|e-1K@}iG&sE0pqepVhc9nI+_emRB$Sr$qd0+$D`Jd6e>wz3|`<(hll%#6vSYB%X zR&$AlI-*nRTDE#bEsa(7rq~L#l@WEypJ!2z6>W))N>N@!BX9ApT76*_EqActQ7tLT zi|8Loqd5=A5kWg$D!XbWwQZ#coByN@4V^xkZ`!`ae15N75e84Siu+z3TWa^liYm&& zAC6CuA5s!0y?ei93vO1_3XXP?-qn*9qdD`>HCu@~^hYL);x}jHnpJzfl8(dC0^0a5 z&zNO=V~X;kw&f>};%{q<@8P5)a;Fy6>X%u=zKsZx^gwjasiU}YQ;xZpr;a$^vxN4c zhkNNGH$Q{w$&&Kg{ueX`kPSO!KN|e*K^_k6vMFvsij_5D>ar|1wHuL)FI^w=_ z3GH}AZ+7NJ7{v-bh(5h8j_LrR*>6@KYb%}lY>3bd%i9)`4|SSt!^NFgOrku;;X z*0*dMmJo85d|WY%hZQ<&ZgE9a?*u*WPLAP;{mkYImvkQIl~&q;ttvaxw=6~Oh(Jn; zqILAt;+xlD3$N9uiwnf?ndkD&rOWsj5xsWMFuu9yS##reI*-KrrL;1;E!fEkVH9g= zp-xCiQ98F7sk!FQ%v<&(Mbe`UAI9m|Gv=3h4UGTzMDu0Ko|?y1)_EMO;BEJg=q11-%zbwn{_6ml@o1IZ5VeF zZ?}7KA0wjodWrfd=UKRdzoo%A|6W`aO9-Tf@-;RschSaeoKJ(`g_TA`h+ZEH(SK>h8@fB)I4t^N>X-g9KW&Al0PY;^SJP8h*seG4w8K(+<@E>fs{ln zmG#w*PjDqe-~LN{cg6AL(@OGYQ|cKJ{bWcyU$?0Y_kW@9OWaI8+JNpprZvyJDORUL zosg2Elo(fEn^~b6b$+&)%`Q5g-``b(I}h|Qq9orE;`y6_R(yB|ok#j&Kka#Q8yeAd zm85yx)scLrTN(Z?%iAa;vX}JHwk>@?Dy%7QKzWe|@)nhD+x69whj$?>DjX)=4Dp=V zTk%0Q^^AzNXgQu2saTWyEzx)37Y;Yk9Mg*D9d22JB4TjFc;3uZlaD^@VZ=IRic)Tc zzve%vtEpZ}U8!CMR>D9^B0IWtE3L##OG9iy8;W$X=9$c6uhTXbX48~j-dtEq`jFRj$=A_lCU~@Q_GTG<+t4D{N=ce8PfF%3k{x-=OKwIPQKNqq zExuC_-Km8$loxp*Z$&w@s*|=e_XEis)`|oVP2m@!oOpImcO#+?C8Y9M%j@#3Q*{f{ zcSU<`?vO@?`O`~E_4=?%9#Rr>qB?{)*fyc`w6zv8aRR@-t1f>*>KY&4p2(f-y|`tB zi}7urN&M$XPo5s5`x!15yw6VT>Q4J+HD$;hWtS0AqUKqUT9Gc@-h$+9Nab0B-S}ux zjT_OUo=xHh=6mwk?`$`Mycc#=y>LylR9Ow^*lFh;US$=L z>fE8`NJ(g({FW>{)r30doM$MzPe>ZC(8ikwH*_}k*ptSu#(HtBtIp%$z8R*D^^<7K zssg5MA?Z9n(Tg|8ayFtQvK}9Ame<}Erqp}XI&yhiIxo}Ro9FFtHV$i%&OMuY^PUzi z5?WL?8W5&g^r}goTb7in)?sZsM2nM1mhH5Q^_1B7b*#2W{Fc zJF?xrkkofkCwvQvQt@Cd?Ql&$8s{=x(gP9lH(%Ga3X89vK)YDlFq8z}0`@Vns-;^*#?;_HO!m3O-x#I_Pz*mew)9 z5lz@Sp5eNLXk2$iox6KISS@iH*RG{A?m1Bs)JeRnMN!(&?@fvA88bodh(JohvwdTr_QK*YnLKQP zAMPd*jk{%0p=o$iEoQtzw+H7l+@Is_6)A~YVJCdF7grmaEUt(f1;Cm>NpOFyC{J?x zYcC2HAj{4iBFG&PNJ-oUQ72C86+4+Un>j?XiV%&~i^wD|)LAR^BaigCyN98@ggT*R zA?g&pt)WFuJZFO05P{0i_z{}@5;REj3VfPK#LwNZ*jBS zJrS1}Rhj+z7AE;iP!jYYi1^@gXKmQefo%9-AIX=22-#n<_)MUdv1|dGSiAy7j|a+* z{uyyn&#|5My(wcc&Q~Q*5$c4LgnhoQxOS^T4K~&?T=ICKBC9z7u;d*?+0h#*R?fH9+UdckSe8>giatb?9X+1H z!!p`N^EzHo`**vYqz9tWtEwnDp(Qknr(UeX;V{XQin3#Mb5Zf+c2R9b%Z2Q0zvhy+ z7G+28u&Ao?wxBk3!gaQ?BauA9C_8$f#VqRni5(QDq>tsfQ}i37?C9kd{VLj0yT3%# zJ-;FQ+p*$5`rbvIqF+DRjHFfU*^gF|_Z(%H5u-zHGwYd;S={UIG{%atr$z*j9>vpzIi- zQIy9HJJ{|r@7U7Tt)&hF*Q90o$+F)n; zFuk%C7~YCvEDdGH$e)Oej;gHv{5G1E*=UraeJDG|ZiS7LxSka)ai0CU-cgDuqU;#K z6erwXmo|C4F0RFn>L5ieQFe@yDoTx@iKJ7Uowla%&=alv6xWAfqx5WgOddOdj zBICUx7*Q5poac+!;;i$mfNf_f!i%!Yh~QDr{U5z5s0Ci@EXAEsc8rWG%9SE}$cx>U zTHiEr-T-3p7)8eDyQ0k7P+cprV+yMn(pZYPqaK(aASxj|Ysv~dyvo{q>?uX{QFhEC z5YeSq*(C7Odv@h`xRg17vSX%#$W=S-Mfs`=>}3&aiuna7J7zI+KwL??B)u8 zDK7)-{bG)W=vTd~vG*}%HgR=-Da!(7ml1`Z?j-G94l%!lky0iH%8t1v!k@T4n2vw9 zn8my)C1t%}?uV?$sk8Q4-KpX1@}fW~dj};!okRsQn*ydz7lYX9%862*3?k(0osh>? zbo9%MrZr)0DQ454?3gVi^7LOP(%w^C40$s=31%K)E*9qgi2RZhcG}&73d=6iRMG=; ziZEwNQTp`1=2!pgTz}hlNm8a0%8r>;in6F^9lA2jl2qSGDduuvCKyU9{64kf>7KM^ zWb9XKf~{uG&fq0Wx$$w29F3@x(4(eZ~D)TgIW%JIUxAkODz@*-L8e7d;jN$hvG ztukFM@ei4o5HIDCVXMcsnf%KSH{Lg0N3?HdLFdqeB&A=FqzAToG%JJ0oO9#zJLrh- zL&e=ri{Fr64cifXvcGc%Us1!Ir&>B0D~`(G+8j4NyH zpq`QRSk5mJZj-^+CV22qtDKC8uCpnfKWOE}KSb(Y&Lo39ZPY_#4eXd{Ks^xM#W9_q zb`}U{9Z~+8s-;`IkV;9_C7&hw5M`-sE1YC*9}V=~g5nfgp$}1(>UsIXLPTmM<~5@C6(b5M5K&K<7I8U`RXdV9z>k!vzZk{&wXev`7F^REF&`4 zl%~yG!e~(OUnYD~>}VRVdE86f{O)8#-eOfd=;v>9DuE_FZb|S7YK!`bGt~(nSa@e2 zn&V?Zu@$~ie22nUh(d%sYU`gE#F95XAcG5Zm83%1ah4Ew zZ7~n6%y43;x4#j^83$)-)JdGYFVUMS&F>MHG8WRDh^qn4k0MviP>c?}^NG|u=_Soq z*a}x7MY+c!OtG7mknz`Jq&X2=$*Y>TV=ZldnrB|)z+g!aY$dOpbIWcdZ(V)pwzqcL zzBS3b+}#E|zp9HAB}31x$SMvwNET1)NZ0Pp6Ss~1hrlr?#|F_XiAp_f0g1m z=#@uGiZU>zqG8K!U#b-I*2J6R+nzSyFYH~6*b05i;_l3stJqRcSNgWKtA-xhYH#BC zH~)G(akxHz{6|Sq4jAo;TGW?@Ww}d!YDCM3Ce}uFuTcOEy<0=#fu2;EAN|%z^9#!- zjTY==b^$T`<3LyLm*i-~R_K!z9+ribw5_XaQ}+p<89qTTCsGoXLP}FDXN3jr)%`NV zR_ITZ5l^Rf*Pe9WO|;@`B~L1P?qo#Mm(kket6f>kyaaN6!wB9grY1id;9x`_8Ty$- z?dX_9jUN1Ny7$ORLLgoA8j6fxmZT*#dhh?Xdocq(K_19kWLf0fXj6w-YHKf5r0yTb z^6Ag2@*1~l8PRKm9t&}hmHB8%p)c7y5%NO>`j!wavJE@DU?D53YCcxACGQ7%4Um$U z6VKRc7rU3zT0ANz@j%%zlS^1EHQQYwr6ca z$)ZQ8WIeiV>`M2&OkoGdT_YWyrSeLf?fAhmwT)=wV8*|=rPBRAdHU2|8)xr85rNvG z^{Oa!&)21;mKV@MBZ^CQE!u`iNt{w5f-}Ma46nO^9=Hpd>PnE{(>R9mav>BPTI@@9u&s}_7WLU zKCHbqxi)8B-%m>Zb{rEpRzw|PkwI4?%-Jx1+x9%1qi~kMc|}pG|2V}Oe{-Z?>}pA| zJDgE*4i=|tUb~TXUJdB2bPp+81XmeceH5k2iXQ&!$_%1mUk{SH%aeJr7$1I&|G!nH zXMzvEf8hW99(un4Pa3HIKIl~3Fm&Z$`eKnuS~=xaCYk?-Ua;GpOq?1;!z&*lbDO2{ ztQ>DXRM;}eug0uoe&BioKBK?RW8>#FN|zZ&Y!4SOApi1s=n@<9Ia z=Bbl)tH{6iNwU_bHVuw)r0dIO@aqW<{O1G*BcktQrt_~o-T9pi-5$(bGmE?__m~u$ z(ScSxmdax-t8tenwTy_KGccVWQ0wq=DGma$r@R~8ewVP_V|=7hi#-w1Vi&%@m|@6? zy(F^U5GwA9<58jZyw=`YM&ws%bSgjHp*rtathV6sveIJ1tkOqV_L%|Fe1&}%(ZXvm zDW0u+eu=DH-JQO5i{%a1)Z(^Q4o2ixKQ)QpSYM4-xlv2-2-{vpt8jDz8|c}LVjsmG zj%Y=(5S51))U8ZQ|5J~eFUIg4;*QLCKSv|-``Rsz@0wYgPpPE8E5APdwbpCOkc0aU z671E;57CN}adr!H9n^x}a#84))}wfzd-ZsYYT}M<;P>8l1YeLkLR;0x zme#qu(1hav`5{`wYqwjl^Y#Pi{4NKG-e3RpQRG+HHG!Lx>+y2u^nSH**F3iLR4+RD z({_eE9Qh$yQO4IBOy{f{K^E_uNw7CyFTvSPQDP5ur~jJQl7?${5`2Pv7bz*q)x%}! zo~BJ`?{AZ(5rqiZ{^&5fIeqMFOJ{^%Fkmb68pw#cR&Mm*M1Q(-*%^O)g0>otN0D>a zy(g`D=OLLp-I^c|^tK>BannX9BO!KCw0CA#hO+_E#T~iGhjX$O^%6@CnX?$XodOYTDA-YnsqvF#!yN$Q8v%5 zGW8X63CHd z7vFr#EMi;oG07Bb6s|?c57A;S>3@>EYEYY2=;ugry+gD-mt;O&LrxrTLEAJaNO4U? zwA^=ZFn7{FJBkLCK0W?? zGxeVyj{FcUJlmHlG>8`Gsbj^tYMsZ8DK7lttU5;QyV%EsRaDHh?KG^ zMBGEm`g(}gy96I>h2LC8Y#?Disz9t12yBI4P)1}r4%zN05W58eTj3X!5tloa_pK*d zZxtwPgW<9r7{gYdZ z=pzl&)#wB-9=|}}y*dqTO9zd0B2BDH>3(YU&;8ek?!G)-J>1osFZ{jNUiM}U3ov!0 zFQ#5(R$C^j%PxEJ31h`w*!3r=8yk7@ZS!3uoy4ie*wWkb+Ifj1k2vjSJmr+Ax-GWm(+2Bz z-q)S(O6T@*qvN|QU??x5ckx8^S)Mg_nWrOcOZKMw({GWeX|@EpBRZ$}Xmz1YC0^!) zj&Lg;LT~=MlxJR8P15|#%S83?(n@^tH!maJ4JsnM!-8qSOQlWScGRTUN*kG|7Wb*l zm)Lp#A4I?@N4mPDHN9H@9Yc9h+sJ|OYIcehAJ9!d^D}p?A1(j29A&1x44-`66t9kJ zY{geC^fn?Tk$*Lz2kn#bh8UafHKB&s3ek#^;x>Su>6=2@nwJpN1JOUv$E$^>34SMa zss350(pz^U^W2-&5wY$6v_j=B~b!gg)O{Ua3fpq`LX!X*xujZE}8W_v9jaGdvzL^`< zZeYY)V?`G0{l+xAZDG^Ye0PdZkRMVKHLx$n)4V$!Nt=tOO(-vF%i^Nd$M$c{|J>1~ zDzGqyJm;xMKQgKufRAG}3Or|HrC@Bs~!A&^20Z!rz*! zxa$b3j&UjBO}^l7+j$&8c@d4g zMP$^qBaMAn(X{tWF^cjcdXV2R^^@Nf^QgcR%b2T!BbO05r?CyFz% z!h3Gfk7m5EW2=XqCCDAoK}Vw19Pfi>_t!e2;lLp3Q>h}W`k)#`?ucGJD_R{``k;AT zAs>Nw5o}GrRxZdAx3r`^l835Ukyp(7EqsiKz8@Z~&bfQQ>}{_?Q>VM>C-qt z?kM|#@ZstNG(AZML~3eny0Gat zR&k*eBz7KE-7``^vCV!x;3$CaD(mUDp~_0qOWv`S3j4^ zH7EDd5v}eOrQR=!X)T*O(Q-8t)g7yI%vNGXMoDBn=EYgk?Cgtd=G#UTxg!E8iJF=3 zEa`WzxvYNQ5Q^LpUBfd`&2`K%JH689-N0kT>9#y~X4|Ztbkq3hmhmc`o?{OCr-2bE zDT-=3PtJ_6()uj(q2;5-s_M~Pb6nf{MwG<6OrmB67*t^|!-qq3KS+fr;*{peWrQ@I@T_WvIu_lGz$@u`yL zG&7Li9W-7&J!Y3VzEeFT%3daUtXgQV`@GfC_oYpuF>p!BXn{l=tGA)Z9T7-L?Av{AksJ2=*z@!-dVcG8wP5&8^Fbjm zqHkAEQTwHt%q{2W`zwonR&-#cNH(HXOBy~rMZH)r&m1w;+lV?LC6V!4vuR$LrnZ__ zP)kXV9eK&>&{$^vm?ln>*PN*K&ADt|UQw?Iq#T~kDrP!q^IW_sKDnw)QfEB5Zcg0q zVU+clKcywngrz$FXaq%hu@$1lE<7q4?z%3W*C=4E5rX742R zgWCi11se||N^&4~qFVXqb@SHEI*;?2lk#F4S!yoFA}Df41X2=p4el=?11ztwaw{Y0 z>{XN0m9MXv?;Y|mBKlUvG`0H8`{sXZ={&6bZRrYex~(=3q|LUcsnf>ZGaE{H7*Qvr zB<8CJ*O`6s!dmDNe>!zbhU&Ph6o2R8YD7r}M@>@ayFM@p*SPSR5IPi}GqLA+kD6RNdeq^tr7qbWV+ftMlwUrTLthXAvSZrc8PlifTA$piOQ@wuF zf!}62k5eu%gK$jOL0AzFCox7*T* zIX3Kkn-GdmM6TLjen?4V{N~%6;!_%#;xdyca!1(_Eh=-jx6?*<-f8HyCPdGU{;MIP z@r{TR>)x?i;?ag=f_+~-%lq$J#8&v$MF#f9DzsyGN0#)^D1CF(3EzUKXW2R@?^JG6 zrWQ$*^gx9C&0U_>(%MGln>x7|r7wtjU>_5Hh8iQZx9q8Zv8Z_jWyijYqd@ooF4)mV zMN`=7g+$T=dm@fB!Q)z(f9UOX?E0u^X?&pUI39&Xf3uR7wIhQSE~`?M1ZBrDFDfB; z^wxS+tj!h%-yn#sp?_NYn^A*Z2 zBN}AAV;|m~VFP@cO6v#8j=IPTc7E#g@(u9miVr3zT*;C<*GMD9u8X_tWrc_;HZW30(; zlsKa}sJ*l!L)mfXB=SXPo@VtdY_zpyyeRI~P$%5g2%pUKN_28`e^%s!gil?(au$M zllIi86H*d9T3gYYD~1}Hn)BEq+{uCZZw*}7U+PXk5k2dxR*^^3a)0!z_%^IEgBPO`0rlA!e>GK97~ zAm1nEv(r;UB|8ccvaL4%+iFsVh4cMFUpSo0CCIl@t9VIUj`y%e@UI?CFrMsJM2MkU&-%-vZH@SRCR1$l%`BAtz{LcP0=HS zI-&1G^pct-=mcwbmM^MiA$RoRpqEPIM$M^6i@9d8qrxYH+!2kwERiSE*PgyRbAT1? z<3Z5_g=qAb2|Xfe)A98_u?nLrOL`z0eRATA;`b8Nc4Kw++`FCRheO%XYbfr{^sPq6 z{u9S8?I)724`oN+qL>-hdQy+sE7^T<1`D~P?C8G~C&TIzdYv6*{+T5xdL0psK2k+l z_)ke%yj)rK_M_=1Z}xx|(t zca$Cd$-?*AKAbk}IGck2%VY5dq;fXflBIQta66M~t8!AJG_f5LRlO zHT{)+-c&29l@w_}*)c96d;sF4`rc84P2K0!q{tm*$LNXJ!?lj0hL)A`+&f;AA|{B& z2#ttsmrSI)+uZQKKe`FQm=MNTWIf{4nzXm$2GgD^K~m%gWyi>t$lom#L95iv^bd(D zNs&9sj`1&XBlN%#^m3&ahF*S?3C5rhjWIUi>zkTDBP+Hc)vn*o!#EeBF^(rjZ2>>} zx%Pv+k(=d+qNQ`Zx?@~f-q*IC5u=NW^08+}TCDqY!|>@vDRM{IWyG<)(R9ZC?qo)- z(FD088l$8l;$CkUooKz8^glP=gpo=_V@vdTVLMv4PZ@f)dvO!SqoN=^h3L1Bv~y&G3N#)L7l|CGFzQ!;<$QrZnsQ=+!2A4gdgridy?QWirOwT zn=qRO(U>hHvZD{2V~xKA(Yy7(Fw8u{TrAA}5m`vQ4V|CoNM2VhE$M+dMVK=sA|@|O z(#^4f^y#u41i7Q^m{}!!03AO2H@TfeQ_DQqhf*OLv$sS9Yx_6m=hu{Gl{liG$o-oM zCh~>VKQ$UrCs8lsWfMBFaaq#)dsQjNYf~TLTWnd6UypD$8a*=9rMBL@M3nBcEFb%p zBo-BS$_yx?pGE$gM~1EX>`7Pm2YPWg;h7ZKBAce<727+CR$S0SKa2b~R}EX0sGqJb zuHwa$Yv~BjJ*BnS6=C$_lRGASvgl%(T6(t^zw^w==rJZuO|9h3ul_!ZTv1okF%!xf z=83nvxS}UtAMIpB&5@GGdb#OIle&f(=)#5+Wj|GBvU+rw2mjL3$@pbmrg|;MokwKp zJVqG@6T4E6$gV{q3INQTJ=X~WtQlSuXHu@t$Z?1&bAAFFTd{eWv^OR!3jJEAWN&!lZ@ zQJ>-WJwKg_cGm_!dqciQ6(g}Z8S19$ZoGA%lQDHvhI((F8?P;DGBjwHp?(N-=MSuO zJysR!u0?%%LrzD^h*MKC)JFksJoCAugciH-jOw(;&N$O;QC$^%tmr+J_1H1@vVZ*c zj>M;Gf?k>8uZI@Bs%=5nEv&!?!M?$cuVvFPohrKhBLN_-(PrptK@C(W;=?qO(KxtxT+*bSmZ zO^)#+wN2fskmDo6Bm~YSh!!V!qKas7tF1MUC_DXBqx$FcGWw9w534AfzBJaN8$D;& zUn>#nEiD^1!!%@dOd)Tos`$uC3U&-r?-dd!jC?mEx`d^vksg3Q~ zh+-@Bi^>S+Vx8&pKFe5Yxpoax>3KgZo{=#&&rM1>$qP?UC`uflZC@SO4cc4vP zS!mtvmyx_`=$S&^;_T85jhvoeTf6kbMdE>eQRF9fmR<&O>8QK5?_+%lf!<+6i(9AT zR61zu6;}S!H-eI&=CV``!;)yNr!x)Ht~K!!=eg8B^%>CnfnE_sDKM`GT{CM9TeoqW zUZ3GF0^cb5gA`>#WIVMDv17#|10+uo@<2*rjq<8X3wTwet_e@{>KE#t>KAA`V@|rF z6b%)&vpDE={ft>cpa%ib0^uD)zs!v%jhA(n5a>HWw1_Bn9!p<8-D${nn`%O-@ckfK zQC9bz%%*p%N1HEo(yNiEf2xt7&55?C$g-GF(X=4hm+qt9l9eh>YN>xJtRN+k2XHv` z|0C==;JYZA_R&EQr1vT!HT0g`k&6mQM~Z*~(m{GBfh1A{sR9P1N|PcTMJc)4l_R zH-^)*nGEIU43aF11hH;g;X(#u!f4d^Jz+jr+A@ale*(G^nqP z{{7pH`oVV_8M!NJ@{YTy?zl5Q+(a`|?uOSj8yVYizxMH&g#jC6evHPO9DnT9d*JSC zXWV_o{Zmuj)n|UViD;(WakskmHVWZ>ZBN{<q2qeOXPxA2SyR0^ z!2ED`(M-9kpZrBOV<7I=PR0FN9$V(eXq>H0%xEPZ-=UYn-B;W{HPzb*%n!F6&6GC> zCgfdgO~d`#TDV`!+Q9r6jUD$53HG;{FY1SJ_Z2r*P4%J!^TYi}Gv)1sR5>e%T_<(> zacm8P^@sT}8nasO1NLUzmhFz)vbf`Fs&^)sA8u5dDQ`fWzqrb-fR`z@R84K*j;pEO zvS2iBRGKO8O#GS@W|zQi*<9K7$QL$D^}+_Daih{qdCTILPdX>&#@*K(-rd)bhBF#B zD$SJlGQKLE$r_9MwUfO2wIScmK8n$rHnXi`Z^Etk?6?)rC5&Ki=ib$~7{OGWlL@XrroI1yi2Cd`W5cZ(f$RtOF4u%#AfEV|=#;mp zvFFThfxHi|)fkPJzd95WFQ;W6jF;y%>0z2!4m{h*0gp@~6l zU|*XOeP~+4qVFUwhqgDy3p7EkW`EA;<6Fb*Rd`RP1KyKi%VBho_m&5%?1cS|umRAlhMI;WbAstzK{20(&9ZC_5h3y_SJZJpV;4Y`&YaU!(N8RfX4=>^j0U>r*mG^ zH_d7*Z+eG38S`T_&MoCxY^}lTFf;Kw40}uF$KDPvg?yFKI{DoWeKcO6VUNuG7!ALR z*`OL;hxq`n!?4$9e(be1EmPb`Jquo->A0$sycHjsS(qQAvA5l=xA8e%hj|~b!|?3I z{CM`k`S#0ub%7UX&i1S-@9KwUNan|Atb{Q;%hzEV;B^?Dg_$4EqR3O@b=b{#{h}OR zpy8RG`7s*rcp=JIgeYU2_c~0-Q!_t~1~l!ht!Z=zFVGzDUZ4p@EXkS`%H z73)M-~9zg_NDfm*oQt&iYO8l8JPPoE|F+%mzRc&sGk zf95+qdZe$1SN4<2tX$xJzuxao(niPo`!&m+BuO&)$3p~4lIFRH(|aB!aZMh*LTE%) zI#w z8htG3i^dDx@1;F1Bn5e2Y87U@xU!;%OFzzjA5iT94bG=PJ3{^D@l#z z-zBkxs!eWBYhO>>q5sjeqDc2)aq;cR`L0xLD(p#O2^o!>NXA`#e5PnS*W)&#{m)XX z|1ff0+MUD_G8!kgGDTSrA=T?qlkNHQ=DAYc$@)VQOUSx_`vwWA?9Py?!uFaXcFa6i zs+(!{C$WT##yYBhdHeGW(e}CMp`z*#X%l}K-~F*Ki6vw-c4Z2*wa-ARJh9d6$KQYK zO4Xs%FG(yR>ooSAFJ%>fHK{1h|9IUlJ^y1@s!e~LPGSiIXl-ISUHtGuwB2l0QE~YF zk6o#9k3F5l5;9uTX7rqDuZ2|7;+0gNp1hf)zNLf#+te0Mts_=7ujnF_RL!5im88C< zgp9^6!0WBVvh3L;BA%(#w?y~o;Ylm~7~KT=CplE^lxcDTMv`}{&yQ5@~4ee}An`XuAyRLRVb(YSY4UKf{BN87*6 zDr%@6oj)~oGE2p1#Bk3=S=S-e(x}P0(x2{OsgqekHRi4l)?S7tc7rCC+g{U9`qTPS znq-zRfYu5QD36<&(e}aUp@!1F;ZxEkvxJPsE3`eb=-)%C9$`atWos{uyC1R-DWS3t zZ~hoLeTV)cq+0f2aYNbK+q)iy>_bY(?ZfF$Sna#8+B}cj7|K#p&3hEG4=EwH55M($ zZJd4+QVq?S6v0v{|Ka*X@|CdKZ6D~-9fyhSnVksuB51oe53*0>n(%9zuT?T;+zJ!- zJB-xX4|1D=i1O9?7zrgu*>65vp+8RW{NUOv7ed}gwu#Yr)v-<=BdOphyTVT^0zBA@ za!q(C1Uxnr8D-acv_j{)Si&IUcKu4m^qXN~U+0m55#*LL8aFM*j@OUAHbQK!7`Bu9 zisuYQYud*tem9_rEFq69&T>LaZbD0bno-ltZ_W%jK&B; z+tk*`?536PCWC@v+tPfG4BqjL`uvYO{Y;{z}da zN?Pf)@tb-nzCB(^C1(Kj?RrsvCX!y;n?F8-RIYFLV?!C~v4o69o&kOJDZJ>I*+m0$ zEla`@;%wB#tRfPg`qAO*f%#n3>&{U$KWf_ff^F^Xkm_b!HCv6Kj1!eqQbI=Kog(N} z)N|4H=a|oxHpsX{je(2?)CkIX9eH3l-`U^LE)A};w0Qq4kK zqIAiPSSj9RG<*qcus6JDZp1#ya%2q05-M$%F_EU-h7IO}R8tXODa(;@B1_04AH@*GY7jBnmnv~uNjF-OJXEyA{AA=T zdE?Bs-}3f_M!S)Wq*9TLLaTPjngYG+Mj4VyMHvdM`byS>UqqNO&>g|cg*GBi^u}C{ zv(gfYR^uVRae8OyAmjMe4Lig0eWr5>YX;X8l#01Cn)wA=&MjoL{8nv3zMXnkje+b% zM$2#2Z-Eiid88PvM%Eh-)+<%7)I^1lTA~p08?O$L?kd@(wli8u<#|!I57j@?QW>pU z?s+)2bG9|ML9R*DX8k^1-&}aOh>O@6@yZ_yoq5x<>Eo(iNP52NBH2F?f91cBG-jr& z3lSa8rGl2+M|`yt@zt!3BlT<>7CKnC=(S(Fki_WKZM>TLx7C2C*`T*kLyNXMA6%o) zE$1Ot^nD!AtDu%N+uqlBZhu4j-q$Mwn#laPCcHa{xcwJ+>QNPj=**pE&v4h(l8Cvl zW`b1pXY9}`Vm4@xxSi`_^ybU+-5!~EF+C6q>)q9FV0JeBxLxXxv;#)}d1k)bBXcXH z17bI3wVxqXp;spBTo+5yqm-+O5xc*TJnnv!$}aECoCep$=mU-Cxl(OfBCWPFX6G;b zs84Bwv}ZNU@ms(isTKzx_4t(~^ga8Y|qHJ$5XNn-w)>yH1(-Ty#$M`eYBl%wznQsw#Mj~As@R^eQ-^BxUSu%+C?FihCf^v zOQOCf)jkQtPc!O>>WC91g6m?m`u_gsQ$XA>MvB8(qun_~S*NsTMyu};*`?KXKwo8r zRHsH)v$-yoMD^RyISvq)&{u;Y)j?z?xGqMkep_nq24VpED&hHPd#9h7kbNb62BTHK zt=hX6h`%;Yvl?t1E?QL?Z*yG%Ns#@N7JOiTA`tU_f6i)_BSze~`id>HXR1W$)vYim ziEG09aL~jEjCo7MaLk>l7_DiApoyz7<~RMkk8FqZWQdNL3$Jdk*%|p~4WG z>r(b{Xs8wPJ`L;c2Vy8Oq$KPgv7$#laU}AIJrKijU5sY`h#0PQFXQZ)X!{1@ zL^a<@-_B_Ec9?4sS!TT*ZD(J&!R8Y7^IQ}5SRhqJNVOAEF?U8YKb-4B%jcox4}ST^ z;ubQR+k{)c=-or`i9-;Db6qTn@=D$ub=J?9j7JpCbupU92Dv_8OPWAScnlcL-_D+s(dyfqKUTvheg&U66j=kVizQM0=Eb|m&{w@7 zRqo^0b*_uis^7eMu)FWu#pr6fl1k2Zj8^^T&9#+%4|f9@7OsmWQ99+=93o4uizNvnx||=c&qnl`Ro@w*JcEo<8O^>+^Z&%V>l`%?$~BJaX*q{0 zUGSm|58@%XM18vvl0Tz*8Tx-iNGip{jr9H#!BpJSEN!42@l3_N@ZSigVn6>3A|BDb z+gD7b(C&=R%8{<@dBDS6(b_fQQCZ3hl1X zyp})9Lt`q{4tFK=p9rQ>y+FGAFFcq^^)A`RzaW_Ezvt{;-(Z27py~r}si)4&uh-A1fmPGZst7BR?R;gi4D;gaUEpc6p_IS(<_A~N6W+Z0*4lK6h!_M-5`m~k#t9B!OP?v?9eNz}-C_TjHm4VmBNx)|-x zSGKpt$%~ouLHcO@Dk3s}Ua~0)cO~)XMB7{AY{KlEq0(@p1R@!(izNw+zcw8az|AHV zjp~S&xGqNfbGz-W2fsm-u?AA5LB8Fe!);ozxRUtsgYB&cmzAhtr@9j3`b1Tij9ApS ztd}(uzwX#+yj?%t2*duOj>S|gdl2ETYh519ozd#si1A>DVwE}!_E8k^71zaRrIlW^)EAn#31fZ@F`OE6 z89_2y>9iM-MSHQ2u^F)s*Ts@33-)qkafq){H>+rDKzzk@FNxzT&zV&At-vupkeY zVShti=HVE@9?p;LkW-PT6a1)84@1<)RO}yv2tPZh%j_VRDBndHHrs3YKWN7`wBrQY z!SXUcmKJBWk>%WizPcQ~GlKhs(cBB6b*+wdt;!C%+*vB+$Gk}Y3dX!7G%+6eM6Qb^ zVO_vk9O%`r(Ds4QD;_mQv&P8Z$0={`%n+@gf$nl$ED7thcY3EZq=Khbk-jbMfYGe^ zcoi7uGLW-0iXdmn8qSiibs;Xnx^^-w%7&eDT`URPKX#YkOA0|M1HOdoVl?|0>{?taciJ<13NRtp=<2EV%t*+H(0(aIjZi0pOP zAWohcZz3X7+Abq6Mk{;tqP`o*+>JjIt=~i*j_YDc*xTVvKtz_K5m|nK$dc<~H2W^> zJKr0tk3{rpA_J*BgN#xc&AtnFMyC%n+F#yK_ciR@DM_T~WRL3a$_aT!=h>Y&X zhtcvIdyvA*8t@*Z(hNCss_~G1P<~5<=M$gaiIY5J1i)zdEfHQ8hxSr+WfKx1za^FY z_IK#8I+HVwzh8@0gQjtbLQC6L-x7`cAG9Z|B$2kJs1!o-^E|`Tdv~%O(heA{+TmI4 z(|dOkq4w?+TJ@D@QM`Z7`Xj%kBywdD96{dgQzIpLFoJ6eo&(?#HRck{HF@U%?sZsE z_YBSfFn87~t|_2bZlo_|mo4OanO|^clzWl;N9mZ?S3H7BGvr7yn#U%v!>i8wxcb9r z9{=DjvZ`0=s6r^MR5~5psaCQ}J7Bbu%F}kz5_J;LwKYbomU|ZU*)Z>v#cAxg^LVJ< zm6ob{*RxvxB%rYkCjtFaAxZK?qkq;UNuG}OPrc#4(xUwHaK@nuVLO@1KWmcYp7Qq2 z6#9s44JsLH5s|%th|E8$BIFrJ{{)Pn^VB}S-Zmq4HqP~NI~c(=;jEf>+EACL z4Y`C{&NZP;-U)02C$QBC(whJKVOvOoiHtfx%M5*wK##T&h-g- z8rMIo3L()vuY}GH>NtU|&YlZNr96Z5 zL_tImoWQowyB%=mPW6dA1E(aRljKS6T@Y;xPGA>lUeS2<=yhB5i9Bb=QZZW7Dtjle z^o+!KPDe*)XU z32b!|P|!(0AtmJYg-&4WIDzfv$fP7{c2*K{`!uaL@`=+Bkrg`ojm18ZB~-q|yUk&| z5oV-YjWtfXaq1+X>j#xLkPPs=+NnC=@SE5!V+?uLZ_n* zoQ_uKMcr{`2^k$a9c|!rv^p=EB(;GhWHfRB@QG{T6Hh}ES>t$|)x7IP8R?+yU7_t^ z(00~p)+I)VPDdL!9j(sRCea-%S3*W>nAUWWHhZ*w30BM2$r7?PV?5w@f53Y1#QBo!Rdyza;&u z`lfTpuCEN8j`sYncRJej;VdDeaV{KvwFsH*kvLPNT1dB2+}TI@U@y|ohSSmY;6*bW zxgMBnRlRg(+eL>?M;kaDtOPmJIO#0<*!xv_yif^tSyBPe5u(CKI$r=!)a6gMJc z36-{ck)?k++Q8{(yvyORHy$nmJJcEolLw98ic~^$xT9%N}utE1v%8nxL$|T81m_3|Ad%hij zc>K@RT`o~$Lw7CRnn3UV@elzjvO&4qr+5buJPRvLbS?Nl5lp4N>0WA*7wNN90V>j~ z|6eMpeX32aR{ob%>Xxai8LHptKIgMi#RsT(&GBD6&?NV^lUo;$V6YtzpTvnrPpa;S z96DjU7N6h@yI6Adf&HbNJ8=o}Y@8*(AL4sRj#<{Uv88ZM@i7n+jDkDTPbjmUOP+u# zRjZ;_jdwvsHEEj5BUQmVL#>wsJS3vUv?38jfsi$AxI8mrq{~C@IVa_6T08HVq16I) zq27u~54Qc%rIf>HpU0D`bt12gccoHw`Rzbf@@c6gk0(ac?M-qH`{HTY6^{UKPf6T= z$BU1i)0~?5C!&u^IXhqI?c8fz*ZnRx>3!!+&(!WW0l-Uao$1usKOtEnt{r&Um=r5} zxRf()Lws`2Co}&A(IHnFC!*u~rli{Y$-AbRqn7(!C2peGVe`XC`S(E{j3_?w{m4h3 z&2$m?dsEfqHNeBgi>IhU{P6e53LWIZEx%^eb}nq`=!(N+Zjx998)%^LZCYtZJe&Buw z5iAMI{@+q@UEEjyEfv>=Z|C1eGbk0?GuO+b=_2AiT)bc&?0uMDkO%u(d_xO8zsvm= z;sHMKf;|B9<9-YBVA+}9Gdv{B<-zs(Qn_B#M|&QXnBdG0dwp0F%_X5W5diIwHm9f< z{R|ICm!z{5_(`fNSTRaRPxZWNe+>`RwlmeR( zQ~L-_BDlo=j*wJ7+U1S4K{}U*HoNR&i@7t8AY#>u!6M_9x%%%9Z@35*fADBB+Km7V zL^5^!NG7CLK*(`+^%cBL)D#hlWDG-5i5QJf~hzb3B&IuefZ@Z zA5r-9HZ87NAi9Zbcu=vT+nnc1^U^bw85 zK4-kMt&ONuHO68pp7kf5#Z#A!d;5sI&($>AHLM~kf(KLaJh(NYzd3h(EgzBR_4Y>Y zgK5P~Aef40(IjV*S+vWeWN*xuj2vvFuCdf!2n18{oDn->w%MZCC?BzOEv;g42bhUFjavIlbyH~=^aTGM6_SuN__HR zdhyRw2-dzAZ$&%3@>F)w*bN0@0ube+>)K3JW%)p7f0sy?Du@_fp|W_8SVi=B3c>oC zXf}5)M8D(n7y^W5RT1rhV5-kwF`U~i2fI{3#Hr0`MVphYU8xws8vf0wLeAOS<9r_9 z1JMbHwBW&16RW0mejYu=r3xYz-dSefEZkqzcnZNbarTR^liz-Orq5#n5O;xi9tfuT z?)3QNE!G^DDu`HH?2z?cvuJS<Q8}y~(krjwpK->X>OSoRH3H!B; z*6Q}kzM=x8V(UDZBa^wH>10>-esS9)ufH+NZ%11oEFfe%xP6>*59pn>;1guskjL~kI#Up4n#5V;1aHvYtpp88&osm=T{VYC4xM_%|}Db zqa`BTdcR!S*xWd!yU*h;5OF|c0D?=nUakqRK&5JH3_X}y)C7Wk###LG$z74kt#?}Y zk>=R*)qNf%ffxitQ6RX4>*boT|8cm#acR$DTegF}%*hLL%-reUbNxrhwNuRul^^=P zWE>DTfv64ymvFsY6K+ldab@>nJKs}0zD+;ZJn&+iTQBp&EB{4ejRPBwSw)7%SX>wT z#K26gg*S{ghQE8*8nLFXjR?t&Ii*))9$XVLcM+q+>Rx&5j~`YEM3(GP&!wL06duvn zZ+Y_b(c;JZzgfM;1pV&HL35leFHLr-f{0RPj5yOduibXaJ&Wt*n2KX9yvzCP7||{M zg0-(kjKw7!KX6T&W)B=K9+mpTYPjvb#oRe&WPW&IV?>ORYE^c7W754q?}EzhHyO!t zAL6$lfJg&G10cBH84>K=u^97v|Dq+VyR0#I?-jZm1KrK@l zTbP|+0)ppMp3ixn$M1h20$7L$Kt>rn({q%;(FfXrxFiqalE*-B{J|C#)b>vhEj_8e z)cyp~5^Egm5=T+^9V|p-`4Ew{0D`GlmpD?x&0<7-tq}Fy0)nYnmpB^4JE@2)dm^$d z4FprME^)+(6GDhy+ar2ij(C@;SeH1e)ilG8kk13bRIE!JIpfzn5QQH>6y5^}rea;< z=p4UqfJpy!MEc#(4yIyV;uV0V{fyPb*H}$_03J-my2PstywZ#nOJ1y4WZceFtV_I- z!7qkjRdfTZqT-0#nTmCZS4)~!4J)s`Sb1H7R7}OX#2!`CzHTwts8V#9ey4nl#W@+y z0i~Wl$=sjxIMR#T-}tqi@h~=>(XIldqFgcOLg!BDXAYlL+w>3#ku{7qd8!)yfnX}m zCobO_VHS++<0F1*l*xEEuB~B)#aK+m*~nWjr8U18KG8>f_VH(W!_xzeSnyyf&bMCt zWMX8dpJw@petj-Pym)4e(Etdh;%u#UFzxEh+vfO)zI`rOC4krn1XFRY7d(?`AhVblhRk{T_Jn74G>Jld032xlQJF{K_N%5 zAP`K&S!ay7lQQPe5+Su@4iHSmS;y#pvz>(b(Y}_Po7c}Ma%ZvrNt2c~N=#M4x>Ws# zY3AwUw<5i@+SzJv89xlXqgUNs%4Vvi6Q`IhGo>~qRS+?!Zfm2~s?^5*C+!0W*1kTg zV$7untGH;q!!ka?2pjscQQ%?`o2iQT8f+e`AK_935o_{SF)nEpjlx&o2_RTszZlfq zJpNTzpT~^ad5oS`BjdZT^Vv)_aY&^3%dY+|RS>ZyReED$>y}1DzMcUDYxsv(3Ys}< zPw;u{uX#`}ez}M7?c2F*rW(C5y*WPhWS1(4INoWc-s6ux#)?UO0tmK=l|Lm#zPfCd z&*SZ^t@Y1$jxaK8&u%l-wu+M@XU$4*se%ac@!5z}u_KHZ>-7yF*oq2_PaT;rcAn2e zrcv|s8)J+<{({X^PvUm2QdB|2ds$oCTT-M7*&3uuR#E|xtk9YUsVpT`poDBYXtnEV z9<zorLRtOT50$6dzVYN-k_bw)XpP@LreC0S`xBnXo;h=1S9CA zj5)MKC@tXkaynU#q<( zj>BrJcvc(o8L(PMSuHHeNwGm#t&mo`7goz9TyN0(e0X7?n3pd>Z}Mg(=}SUhrqefb zoI+XSUH<{k;H3Bxcpp&|-e(EC50`MgT$85F-7?bnd+!VS>wlSYRpjP$<$8d9*QB9y z&9W`~`~GUgg@Hz7{sg^&CsoM9K`K*86-1mF5@WQD;`D4Y} z+doFE8W1B9p_a4X^;b(i;*V3K#idTWBfcvBAdqk8>^Y=zQrdx*3)ONiVSbR%ky&nc z&q71Xg=~3!w44z<9*o9sP7a9?ZPD@_XgSNv^#&1WxglG=8ZGBO;TQ#oP_JtmT5hP8 zbHDp5I<;>Q8dd4rciEy?k8%DAb}naweXw)3D7JI9 zE=_}Px0P>aJ7@31Hjj7u;1i{%P7hDb-iLi6dm`y|Q~WObME1Mvk8zs=vw`xv?2&mk z;8_B{y^J|Zc~PDxc#h(^3$III=9E71Tl5vrUOaR1jH+qyaE9`5Jg4$}&hxyc!Cx8D zUsZ#@;+dYK430kVdtR_}>3teQ+d2MVI}d82gJ>xN(b8SS)U4I4OB_Yv*U}J?-S=Z^ zrea;T|#8p6OmX zoU(IBJb1oxcaaV3B3u40a%g{$cSC~+>>?Z3Mb`aYWGR*9?;^Y3^5hXq=%%Uxi|}`mL;b^O=7;z5Rtz?8nciADB}pC4IF6)|?cxwq(e zmnw*`R=sH?97-cj?#yf#?H^}O|E;zo>*BmPXCv|ZA4fYFjix`byPf{i;*!CYJ~X>l zOXZ@uCcJ+Y*}<50_OV@RUy#Swk7Lc3me+ZPA96DB)s2DsDv8DQbJ(J7OY@z>@48f+ zzvPT3ZV&VbH{N-!oG8%hjKw9)gKNV1_Pv>m?(t4t_`uYcMz04b9-f*2hHhq6l zc3(dG*j*>`?+SBVD$c5M9u~iAS$)5L>8;*k_gnidE@2*A6MpaR>^^cQHxxuICIOnUQH|0tg&8r=_pa~?_Cy` z1b9$QxD_9jE%Ew~h+uCeTg+n^wo1np_xN#kSkszpI$}-gJVtchx!2;1FjFxa=W8ox zO&oP;wD_$>5t~bXd5SY-d?UGoEPUzI&PUZ$tP|$YAl|#`^MrDu9s`l zwCx`oV&nOj#jm&bT3nL0Y@Bmvspq>m_l~!B8nzLQ5;BO<6S4&I?M%gJO*_$37h_J9 z65s!t*XEK8Mc#An6|3R4i8J@OW!kBuSW)(_9dY}R#Z(QO%yhPg-*x>i=l3;j`St#y zO6}G5hXpiBZ+c;YQzUkm~0$fnUo!rwnyUq{@v?mk)M&b4y> z;2DQ^7ZG1&9c0vtT4Jx=`N(1_p09$4RlkfDpOoHZ{Z{gU#ZrNvBclPy&tI|nr^0ff z9Z4(CTL#*}CEO0K2`|2{A8kzQf7FV(ecxj4JnM7&H0_mFhlnemB-l$^pSHLcx!z!3 zWxm{6+AcHFZLaC|k0q&0dW?C;Lk5zWVdWVay-w zoq7IXpO3qJb=K(xZ}t3!aTSp%+B3)@qL}rh5&-=WvXcran8IgwO!sA4+(pWMVD4Q zIDf_bQV3uj)$q396X3G45*}#yq!FNC~74r)siULu))*QVH5SW)t zH7{}Qoq1zzfW3($*qcaI=7B_nW-{JG@MAkSTMrxjX|&Ps&D{|ub~BiVAGbyLaiWY- zeFS(IiiaQRxg{(W*W~gLiU)J|V^Nm}OY6?HhMJwZPq^M-%hj0gKwt4lv5v7WxU-s} zW;ND6&T_L(<4h4OO3pY5;K4S*w!*gQ&L6s*KL!B7_ROA$J%;Psb?Ms|1HnFu{UdwS z6fZg-2=>VA&x2kRKGDwZdr_VNcxK?4$n{sY@>e{o@odR69P(F~Yo+&*F$2%Y95bMI zL$QSG8HDl-94B!6!10P}wW7IiwH*6!OvP~!P68q#s|kzh45>I)WBUkd;toH{`A2j2 zu1qK|%9_u%qG^oa68~GRyh1g}5%lkDfQ2nG0DSS1N!y4-x9&AFr2^ov74xtC5L_Gqmw$9tgbo7dFA5QxKrXv6{-pQU0=Q- zmef39r%q?Ue- z_8)26*<3HLCb=g3-bD3!qS=7b;?3fdqTyptg z@+$mtpxY*{2_9~0PF>5>TRa@PTedt>wVV;bRcfoSCi=e3(V~uhGn`9!Wy&>S?L0n9 z;`F~qiIe}lWpllpjpUjTxxRcr|7cJjac=v$M6Qc-y1{jA%#TO(^*Nf0t@jVeNx*^rR|Ieu7txTMi^aQC@%^;9~sUiy!z#uFoH+28@X=3 zEt{9&xo zZu$xLHAF5^{K&(BM*75d;E@eH#()R6gLyD-ylCD0ZR6@PO`Jks@fdJl1zSD=k~jm}{u8vFZIHE{tpKZ{H687`u=5MB zbM^*o=im|YN_Z;_-sd-XpEK}2?BUq^pdBG^huZ`2qK)81qu@o^JF^!>Uxj==_6^{v z+xwoH=MVPO?7`)%rvAhmK6g`&t=~WH_k&q6rQwO(Z$&Nt8*eaoZf&ryQZPXt{-`~} zFNI$6V5xjvij)%iTJkSaaSM5zeSVIoyD40P?eO`zRNST%dMOo4!V>yD@-I@cyuKtZ z6{ABu;{BF~ypNA|rQ-I55cr5UxV22>OXZ@22p(I%wf~P)Jhsg586IeZ{NwhOj9%PP zQxTFJ1MWkQ*86v;cb|!OxJ^NX&)t>Xr*irIE01_7)l)qh@{j+`gX{IWsXv_uAexf=hVS=#P_I6V6QFCepU=XX_sfe@o43ZoRx><(hCxZ-rr0 zXkEs5{rB237L_rBTNmdwf@{vOMJ0_Xhf5kg+Z@%ogsqlq(zJfNkLd^RwJ_?`*rOsc zmj@#_YlPcQy$GKgR?g@=4|Vv;u5!nSH)ZtR*<#Y z>c1J$MxNF2Dk5_coM8*DYlrm9p)3~_nd!0+3@)9!Q^rZsARtWYVjNnzV)IZ$l zNFHUB`o6QxRJ>k(3eo$py#al-zvYB*=7GKnWru?+;lCr>+V7;aT+YI(<)NG|qumj- z)d+H3?46l6_Hh=K6jPxkU7#h<20076JQxvNZI_G8B?hL9pq%Ml1V%8FZx141A41wk z4D5q>z&=9z6v5SYL*or0Z7>Qp$R+H%xF$_Y^Qj>+rr1ZQ9h?tfey(Q_HQ*VV!ZWb< zVIIL1{no?%#Zg%8WY20tvjMC&wA&Lzz+VaFuee0<^J7uz?R*cn13b2a$3*bpmNO5Q z(De*LdWL-P4BYSB@?c-V28Fc2d9Xp&5*|Swf7b@>-=T?VVS}vIoC6B#725~fAlnDq z4Q?+-w$-J!=LHY;A8hB~K~@V*G?XT?hhtyDzRT4TLuyGw^c8z&_M+&kkaxw-4?MLT z^XV85oxcG?`mcb+InV zZ_by75b=IC%GEe|O3$aVtLWp>UU@9eHnZy_W2ZE_oFSM&s{eK{sO7-sj{`LMB!XE=kwWGm?)w1OW8o%-^ z0u6J=Bc7?i1F_sS=U;h*5KILL9f|nYcBCMP3ccVW{|l>d#2!K@^#4Yv)-t-_%F$xO;;MDi6@3Z6tCS)MOBm#B$B%K_k#~Jod*aV? zoqS7fBp1<&wqDq%X&=mQ*jVSmd<+^Kw#?zkday z3|<2|IOcZZ(IpvtsrI;aF;$TF!y4_x!Xl}xsPGJe<^6Wx6em-LCQgnfOU#b%#yUpf zIA=_$>EJQ^c3%-TwPxLy_9O>-ms`$g+>iPqzc{#bzx7k$MuPSArFE}3+m?Rj*r(q% zSCy{qtj8Or!v?kikAq=vh}vm?uG?hO3jqX6GP(a?r_a$TPM^pLKzvaMx1)1*NId_0 zHNhp!gL!LO$GHdWVQ}f@NnkY-y`*9~itbvC!}s!B%wk;`-$G5)L_adc0)5+3I*wmFg#*%Iyk( zN4rJa>@;un4u3VNe*nRfFj~_-O)6@4&NtVxOOF;@*HhNzdQ{K4epy~rKhblI)$)NW zRcN+kL|npikux`*aDFdP5K_f0ZLLr3U1R6Qx1$A@d{Q(i^5ljeoHZ|FuBCZb({2to z!tBjw1CcNWF4- zNT1lbPjfTV&&!>*>w21ZM~^W}lpX7AHm9QeyjI;Pe(23`{5ODL30rKtoIv-*NdmZbvh2ZC@spB%J=Od3H!8(GpnYGcLpDk zG0N)49gW)yrzYlW@xbPip8IE*Z>+B7oGZS@S?PMsH%naImV7Di zUevYN#N7L`=W%58;du81-c*I=qU|bC|zG#sqjlm^n zAC2{>au$!`nh@P@>t{qCEAeH6N0!d@8hCqG);nZm&M2-4w;;Cnlj9NJ`C$;@q4zkl z9gNnr8vS(R{P6^Qi%VXaC@=?9o$>@8JGii23wBzCp-Q_WKLRo|5 z^}hEwvKJVQyJY998Mo%S$4n#l_*VpcGBjg~WV&!6X$MrQ|D)bZ& z)Pg^I+$bD~Wcls!fK>JiO+Bf&1pGkdMd2*1+gEnoT%T>d?6usHRI;^Qlw85=Q>Jrxr?Q!`@ zt#ox)knV=KLtkAgsjorA<4eWei0s(wuSvZMA-r#I%o*+4pdcIc5U?WHoy$YoHZ02h zmiFk{xv1HsrEBNh4%oSefSog1)8I>l@+DjXs}1qvnlx?T^$u=3y1>34%Al3&Pchj_dG%0)F#_+|Cg)N6y&QfA^yO zOZ8siC3AKYydF@xBQPB@68zA2LI(%3R5X<_gcOsZ#OZp%1?ER47_Ob zYKy6qMR~p3IO_-zGxj%Ymo@}iFD=y@HC|`(+ECL9t{!RhnLX8N`(kgq)rEOxSlV^T zKi%79@;LKo;&sZehZ+l~WwAy+{3sAvX1hAgyfXG>=a=5gO|D7PZtomvq^)ww%JJHp z0UnHSUY}+rtt#Mbe{~Ub?ZWht#;$kU+Y<)-Vzo=0XI=^WB>C3^j>%LKJ+f0)r{oE# z!&0hfNHhqNN$&S!XC+VnSeQ&D+tIhYlic=`RY0UJGQ@bV(-J#2-Oe3MCG~i~_0-P5 zS3fj^hKxF z(;_;)Zj|4X!;T%0Pwf2WRkK2xInKQTZ<^c=wtxHr@n@}#-@lq}cdv6R(7TMjR@5|q zjrhPB{*{S#ZEh`7NpzijW1LgvW!7NMu2+o)r;CdUl?PZ{BG-eb z-|y!XAN9Pu=2UIM&EidEjcQSa?Rs141lqwXNcKdydB3}ukrfhd?%!m#qaA{J!++F~l{gTp@m zz?nT@OJooc{pO!~Sl2A}mi(Oqo|^q`>kR87r~I|U`D}h6wBzRI7xiDNyl#Kmp(Ac? zrIc{X+2_MPcBD6~qnGWQjcN*}Vsz2BS4O5wv&Jb?Aq{xk=#|9HX*?-mM{$VPK zex>n3r}jb{Ex!t>q(nbMGHxyRLJ;v>yFc}rX!V{hS!^zmv(K&xbDXqo+D6J=_`T8` z=lbLJ;L$7fSiN{yb-Qc-A%QuH^Dy_P{$1~0ddJDPI6K-=>-tA}_s8kQ&m9{F`iiO2 z54&8i;x`+dwXNlPYF5jcdc%E=@ zJGUu_sI_)X_{x~(c8dkkf+gX0@GOdZ^f!Bir=8u*c2-9VE~z!sPRh{VaejL8g2^@E z_15VhhTqtoRlGg0Re%R08lTykG&#>k$H;OG?PxM-YPdeAl~@84x0b0SdR_iyPQwjL zfOzRvkMM6G(ScdbY;GY_NohBki=00HWC7wyi!tGcH${u@PdBxhO6L7i^;_h$e=&1p z5E1oBYy0A?*7p1bLj~sz>l9g-++%p6Gcvq@$!*fKI{U}k1$sRv`c`TpxP%eA{zynZ z9r>9vdZPv{nYJg^?l!s!ev9Qf!L4N~iS8JK)7ewEp&h5Ju6D*c!^GJmwQVWYm_Oz^ zJBl@kCV=cwa{0^E|e9Yk0~Nr*+*>dAEuJ%ZJozC zg}W98LQ3@!Bq|8WxP?q5+aa7-XG>Svy9uL9r2FVGR7=hrKeLd zy04RVdoQ%(eXXg;o$Zl*tov%4Tgy}uUG;1`r?35nM68Y!qwbdwF~!S>JnzO)&^{Lbr>oXA2Iol%)*L#oKOJ;dP;w%bRpjkLM7OeN8eY8Q7F zuA2hHv{qfjdkL59-GzRzxJ2$KWt*4F$(?7syB}5Ok6O;{+%n(387*IhR-EQu(Vz`x z5b;ap7%}M8LE-m)f5m3md3DFTi`X$KgWoWDet~s%oaORR{gZ$0BBzmcDyizNUrcM( zB4^%=eMu{B{0ym1JQpjfzx1^=Wz!OiTgy}uy{N~Iq}_j>2I94U#)#5m&smjM4iB`0 zsiaivUimC3`SMRdj8BRar!Q2t!WUks%O#AEt5>zJiW4apK&{0onRid6@XBX}o=POnO%nl^rk@+YRQys9~Z&-AwkFE$`VZJ5vR% zwjJ!_57@?a*a&+7*7jgK4#0~(ga<7RPs-khy)%0voPliJLv)d-#t6cTeh&{i9-fqaID5EY%i}Q*F2x*p3UeXL&NC;^ zsMxh!-c;zPQ;A2@=ex6kn!T8cXFHq&sMSOqYP85s*C35x*_n#xV8lL{2Pa?-9ErJ* z=Ou1!5K#`X&&P;+9wYwYnV#b-jwNt*?d|d+!YL;D9{Dyf*D@8yE7*5_t*qENe4pK< zbP2(-GgUBJnu@q29b%I6h)p>1;wU57j&z7#Ga_s7ab72rbXmh77;AR&Ky|=TV4t4j|Fn= zfi(z6^eh#(2^sC-W9_2vNIL0WU!9H z`oqTBBOTTtT*Bukc%7hWe{L8P-V*E0$yj&t3QMjzOJ~6uoaWggc@2kqsRm9Sd5^ZJ}u`gqf6?o54E_e`Q`$3}sb zFjGl%N>1iBasU~xwYK{p55O&CD$c6o_gIkkkvX48t+DK85Yjf;QZBrw8qx9x9#%@)dRTr+yp~or7eYfnwRYO?cS|xxPr` z`Kln_$C)k84sz~H(?0sAx{>EmZZWvww>HbpRGgo~Nse_@jrUgVv$HSED_C}>3T6ij zAP@I3a&R&i$C*aXiv?R=54qP-$h)>e{*^Pdoa_PS(WmGE?ZvVC`ox2O5 z_BnWGgZD)=EqnG+#&b_H*=1YQ3+w_gRd81(74|=7KiaWlBKAOdhlh7Cf-V1P;us@5 zTNeA!fUV((okM4pSSoH4=JPypM%gvXt?x6QPGrQ>Ql+$9BEAN7WuO?rvNIa_D@gUp zz^&mOAQ>Zg2aC~|4L^JFaS<6W`vB*^`P3-S2w?(_#1ZCE5-55TTP! z678OJ3ht6uITdFV|6qDz-pkkAzEV8i%&^F82Y#(@ri%g(Q}Xk8%v_saT<_l6deW@1 zA#zo94m?h9F0HH?b@93G&gF**&XdS6d3wj?=bhdu*hCjS%dN7e-!5Y?74M}75&I7p z7w@LYWc3Sk_nkv^d3%uFzBBXIv_84LzDg*z-tQ}~f4CP`yt%-+{3O9yaYLTJx+i*y z=oWdc{+mwd|HQoStcUCs!%9Tm_-wY58dQ^V<$CJOMB0)4#1B;>tj>EaovHW~0iUJ7 zedjr&#p#>1tzqel>CBzSz}p%1_POzPLa~wJNaY5J2RFp{Cm_5M=EpT5tM+|uk?Yr$ z*3i>ofzt`x(_c-GcG{tRXD63N%fBwCi~UJoSzV5mF}TFruMM51a(mr7_0q3W2l4Z? z)z1Sje7D5vL&T!G%@njlq|5#n00CDto9 zq62-!E$5mL=_7)P%Dp;qaNni@9&8iAzWS?AZ_!~vU3*UX!~kN(x(}Qa4@Nmzs=OFA zW7BN3yn$0!D~!H6y`-ned7`|%x7;3`sn)cb=2HFLq2yDDoionaY5(qF=|#F5U622r zyau}T&s;r<^_9fNsPw0_#r zReGNg50-@axfW#{f<^rRi-Ia1Am#S&S-(Dv@9P09X zJGY6?&me!*c(frJero+XC7;ed{EO~$fo|Zu*)X@X$58t;t#js)#?(w}t@rx&mmV%u z!U))hi}viJcf;;RmVWu|6+M5{xrAlsny~Vk9%r2SZdPK#EO%CO>yoF!SVC?Sc9H*x zGmc%dcdo4Yb6}1-IDe7ZXH~A`rm3{3L75ks<_FW0A5F{%t4;e)oIFz$f8){g07CW~ z&P2H zR$=-(hJCDs-6ir=KuaQW%{H%QE9)GsQ#|VLs?*JL>uNe#mX!pL!OlSA=KL&nrAnU! z5G)C!5sOZJ%ea$Mvk(3CK!Id}m#=$1fM9-%#(B}=C5$h2 zN7z@})su5=$cO(hZj|}pS_fy&mI_e=D)lovz0%FO@vS`T{Cq?etc1Gj*&3|e4 zG}mK?BuRVn_cDK$Ti~8O&pEYda-PTYoZq%e9#yjxvkP3SVC`ItzM>L7H7i@B+Jqh6 zG8gT&h-4OfkxVEeMmz7d*$0Xtn(Y)Q}@YA8(6BPLq;Vh-ks}I{alXuu%or@s<)0M=2;VC za0&AWO0{(TIeYH@2y1D0_rS`Fqs%PN-%EaV(+ubSbR9gJq&sbwPIbbnJ{z+%m3&mT zv{Rw=`_6!~wF7afrWGzT&pz?_nZybehDvP@^;LeWSqY4t5t>8@@QXhEsX-SZ821=}VIKJ}-9FC}rQx+QQ(HyJOoqrREKCN))ad zSWV(>^%=FqlxZ*6OEy*rtXO!B^F;6GBz5TK>^>m9=-Da7#j=t0?A7b)8C=qO=LqLm z%eS4WnZsmEO{=00^kyQ>CokFy7rqeSF&1YFuAgn@wAolTidO)L+lSW^$6xMbFK%Ac z;1WiddnP(RKB@2g@TFXNl}KzQ7Cj8J$4jMs5i(X|wAOgKGvw=<&em0OuB~|K zEwQ2Udv?9jXLK&9^vj3N`>iWGHL^UtD*AH4a8WgDW;=i8elliodB|vz`K_Hh$Em6p zbb7omV}?Q5;zZ;`D>2W$)iRQC5i+0f^{expsdpbFU#^}fs>zB4PRCdGB##r>fVfv@ zv>5edtrhj28@+}Q%r76%71BIRHfqXfY1BUKbFSWQrMgj6=Mv_@ym14xTAXOm^aX3w ziyuZHrgBuqgC$vWb)nPs_}t`gHfI8l{J+PEp}Q;W*nG>)mq4mLZcc{Lh##HoEiV`I zB1^=gLV6<^iv~-0kCwALt*^(4gAG32c`3&i;mn=U%nv@XWt?c7DIxLamLEp2>`WDG zd6m^MqILH5R+}xQbRH@0H|}XotDe+P{PSC8`}NpOI%@`_dHgl4Z|*kY?u6&X&m@+uIMiUz$sRR0 zfAlUp&pusv)6T=M24@_mVl>WWOsZ=)td!H59v>5!2YD{x*#~z4vW8aT)IF91jCx}?zbA>*1jJ{(e zA~KHKI3f!o7WB<;{5flpwcpzUQ^@D#KPf5-$&2c%iwo;CB#&`BE!kd`lF43ZB|+9C*{+5ea2M5_2A}T5`2=ox zuy@nt#ook?^@$xmjR|BXm|w6R$c4L7`8UJR?|U5YmYI~w%Y}PVsT?`-yN1l~c0zua zb26Ow3Fb18-!)DmzdIE9UCsz`9)=~vY4s+$@h)=VGms1Cj2GwLSS#^%^o(`vF4p#-eIQ$F$ZYLAWTQBT$l0i1@7_R!{3YysA|hnYO>%?`9-(Lux9F~p5Q`Rl zX^m;xKM-Z`oDs~{o(dZ+5@I%4H%8?P>LdEB$YW=0Wd$+}2(%u^%RCv1%Q2;}-W6VEw)jJcySg?Qy3x$vL-TpwrqITz0S+>Doy z8Lv6WctIONdk{~x7O{k~j~{YgwA=exPTuq2u?fyN*ei0iUG5bH?Lca~s@K(ge-8=y zM4|GDydS|5!ag9CvJdPP3AtC42YW>W2Jh!_HSD(`8*~HWwvK zZOPPf()QZ_RK&#JCx`xCLgH_OTK*$fKhml;wG4A#icsHynq0&qP+xuuk#=}CWYwmc zv5oPf1J>sX?Mf9-QiZrPzh`)8|G~piJeZ%y;}Rr#BBjEuUulPht9NkUmQdgSj(7|N zN<#HA`dP$7P+!46g$H+X@Q-Qqjxptb)wj%rD}J6-H$naPQwT{RDQ`~yFo4#yUwWmk zA=_{P|8OkIaZqqQ2rlstKrN+W*;&G%R6Un1`|>2Hv!x62;P{I9A!{%o^H=+TDEJhD zV>piOf-OgD9o1Snda_s7Zu!*hC-wKpcxBI2Lqq+t2=|TB|M)>ww_Mn`3H@weee99Uj!k48%`B{9j?$9vfv5#P_N^Ed8S(7!;!@ z0W2t>?VW_X-Uk(^MlniI12(}|V|W!TX?R#gR0JeQERhh2u?R>?#2TSjEbX^&7zqeI zLa-VTf)*qyB1ph0K7Ov&@N$TXM(e3=7c@{ z2cKwaY%lT#=7*hXf-7OR0_NSTBeA`!!(Q9eB9CptmS!8K`XTWlvk%(`UXrw4!XAS; zY)m9l4m&Lbg7xJcT6gcYrm8g38;H-d5WFYH`(-#8z4ynk^((eJ=j|+8skf(nA1Qzg zA2QgYJRUBhs>g~u?*O79ODnFUxW2-8R4m_?1M1^IIX+6&onvV+ubJD=0wrs$%*rd? zY&N&f*zc}&-zY2(=Y#)OSz2)p&z8pX!Qr`$t3W*-D7Ft<*X{Y%Da%ZppAfBRcZlZ_ z7cqF`X9=0xWkq27FqP|x((_zsBvH#f-+f?B$ulP&7-pERKXC!$92#6nh+3FU$#di%e?RdJ@z!zjF)MRPLVsUu{=6P62gwmR4Ndan*+# zn#P41mjO`*1ba2_4zp~W1=#R<;uH|=_;75qrT=SPS)oRZBcSR~eT?G`kaCOI3A5Q&l$xS3cEn~t~WZz{@cx!S=GBN?wHCZya66OjS zd#~N*hb05}ISau%^gK2=U)!{=;TWhpK@QKzJh!`AiSHf-qAL*a*QE8=MeT2uT)48q zlV`W=$4b3ZTT#>sMD}{l)uj7e_3+93@J-fz!y6C**r0Vwux9uF6> zdi0QV&)JIn+{i_gO&SpC1^x#hhy9hU>mp=|6Q4Q^1bZLb&9zn8*4^v2fqE!V{M;GV zOnz8?gHdKN`MT@MsX=cm1FX`Bsz{08G!D}i7i<++48;WzIeo){Sf87)9?JhLad z2=Nk`d4>R$rF;4*J9`XH>OD7Ti_H_+8@RWwj6KI5E4%<1lFe`n?`!aLZv1lZ_^L=8 z8f^rE$C+n1=A_hSj7JCv$@*B6EDh6r!jtN0=eF(wb$_7PUs)?xMp>kHV(=AVZ+mCV zaP;h-N6?Cl%{c)#SY1$y$@95rT&~! zpmVY__~a2ItpY`{49IU5Or6GQia6jIiH>$}3&N;oXlzd;EX;O!IoSc5Sh| zM21rvQiZJ4!el4CX6z&*gAw+-)Srx2>iU6w{rP*Vz3a-}#|X+F*&(RiVJl(z?$+nC z@@D!YPR&ip2&6MYYIPUUt-iLnJ-ooX|GkUvvW%=ffXv>2>NBu!T(s&9t+)=C91&w; zG;}zrO5AJ|y7npCb5qF$TBQ*dEgCA-^U$8SShu@amv#pv%a>fi>>32Mvv9)OxQKE2 zh-8eKsh5omqJpKV+J={SSHMe3;U(N6wYhwxR%cF_+R+E;i^!0kie@5%sqA<07`(YW zyUY`BpAT>67S4B=lTwH%&qkDtx5T-~;B|>(Ua5ZANiE0iOrjMdn6LdVv0`QhZ&olf za0|;|PPmC}UzK<2p4a^Lyt6Wwq_yJrwE3NM>}lb4%6i;PnXQ#YOJ2fgoD;@xTFk5a z)Box@=>+J#TS;Kcfw?q2tCN=Ix-%Mgo;~+ae9Pqd`q7+gwg(Yq zWbnx#J~4z_#acg&A2~Qxw|$ZyWdv)&X#9@JksISn9;w!|mM&~zUPEi{!QIiaS83)h ziFxxK)x_x={Ry+H^}+S!66ZT@3nTaj37o0c#s0omp49~#S2S}ApEzSqN=^P|RP6Nk z3-r&U55<@-pZQ`=K+HJlhk8Awzf5>y-J~54=F2Delc`TU}BJ|_)IL`?7wQFKC`roE}ZszGq>=mU*?3T z;V)L}BbYCrIL58n11k01E7tps z6Cy3#!ZMgs>Spe9=2mVzJ#o&Na~77-7KjVe^*@a}{bSpPMY*>uk2S>U8vMq{;nn$i z@$xUCJhp5%wzN`1=3b?*|Lqaoee=aA`x1|{>sNb+f8@_xU!gy)8yVx6V6S99#(Vl- zjf(w(`1lF&!BNZc!EuB4maqmM#+}Z2mHAPg4Zt@Y+t4aKk14e_6!!4ZuiiX5#&Z-? zq35z{2Q$MjxSR1Y+!)%aVE+i7YnckxO|KHTU-av0@A%NZ{CWXkYuWga6PkQd;gY@J_+NAd>1o9p~ox=s0Wx!WvZ9^4! zVt_z4rfo)MTLRr>Mm1FUui5KQ$pC+C^DEmD*e6XDM3l+9Ozxv??qgemF_5_{pyH@a z^-BKc-x;ah!Cn%KM>3_AkP5vZxP^T;)h>UVF((95aeVv_f}+TcJBtZq1pjT8AR;RSB(*1C$IvTZXt#}T%nZVrn{=Tx~6rTrbT;1#zgiD>mM0W)G@edv&i_U zreO~D|M_=6FJt<{skJ7riI!=yAJ-V`rf+>0ZYGxXvj4QWvo2#CW(yy0d)1Du_3A9# zT)*GT&RA@zKX$iR8!e+ek8Aj3*vIC2?er1msA3k?kCqrK!_Mt)Oo%arKq_C4Hu|eH zk!H@xp8r8)zF5EdU_z|(IIba;wk1@L8Wm|?;QvMJ^6~t60U>+{fmBZ%QF^bYk!JO7 z|3z$^ccx~hbU%pz4-N}A6Gr^E z=Qktf)tXKS8%c#!E8}|T<7YX{ji3ID*vqT#l{6pOeU5AYrP>zhFxTbs{?AxV%D8OL zAwuLJgf;GNDx5)eKFVkL!zPUqvQ{-+dgz_?wL=`{jf&sfT^;K%&1&C&$FFmk;oSP| zv2(I*Y2p6zpS*L$wAjviHj?CX!S7UKIyua_#s7=$vn4G*JkwX!Z|^5>W@)8YDG+Y9 zJnLmge(x)H)>kDtOh;`Cy?5I#?Y>u(+}5F&2;b96KlRmNrZ>Ip$Pdws1#RfbPaK!x z7%MG8ng{E)IuWK`%FB-YdLC`5*KQkbX1ijIbWnJ49`ci2t~+toR=s?4{k|8?b8#;_ z@VNVE1BPdoBMG-HLgJ=DIen`vv;G@K{&4b|)3jx>u`^t2t;sn;$A!Jnltg5uL)Wi!vi3`0X=M`obQOW~mVBIq*X?W4-2NkW>Gc zL2ihvzze?XtA8CEVa8qav?CgMGd3u=sQ7JHoSYRkTUa{k)}@4VJ@n0!9HuR!w|!2n zD80@qhxyT^`I{y+clN(IL|&>Eq-Z<7D~M+7Y*1zKB)Gjy-jjyoTZ`{JO32umxz(Jt z=e3YSzxZ;b!gU2lfw8JtF4(SZYbC#Z_Tor|YZuN9V?`30Yr8Lm$|_SIDJvYVkEk(> zHJI5(o432S4C=Q^Sw(RTMm=V%(9h3pw-W}*x^F_1l^RzDe7hKHR&S?&UcX;t$<9F< zQsKIS^TgQWn>Jao?4E;X7nfJ`YD-K{{leo&GorPpz4en=eQL%?^Wqgtul`J|Df50R zDnj2?;`n6I(O5lxZ-n`rG)C2u9GjcV1%DM0&vYM-RJAh3=~1^M%yYC-SI8cx2b_;E zuimnF{5&UzT(a^f*=G7p4K=a5U!2}>T7-G|g{S@cr&#?{r3mwwul3fh$Xi6d_wbVe zGao4k=YK8m3HBUYV(eUp3BqHcLk6ri1isI;Nv|escbMz5dfPL! z>8Y>U;V}DqSo_DPFGWS7=O7st9;hJ#We><6tsgcVX0a#MoR2xVR@8ePBTMDUFYpQS zz?K*bPq-@vFR3Fl-A^xZT|!Bw&X3Y3A8?q>@>x=?_2?*miY*|W?*pav=D7FQIV?&) zf7W4U@bk8}d)PxSa?xQXmaq_2AFL35Nfl*zSytgOxm}dr@vy@jTZq;~Kr=S;d^a(u zOHEmMbvda%0e;FVnt5<%@!Nr7a?=V;s@%KjKX&~eXvUi6S}6{0tteOQE-SHzic|`Z zM&9eh_|wty%)kx;#|Otv9o@l;(uvR)33B`KXboo#sZhrli>NfmX@4CpALlhSe4kOn zQS%wg(Ydo+vVN7g@%u>)*9?4v@ttQZZgF#YWMvUiJk&>7uW8C>F)kTjqq{4j(_bakXcK&JWBU;I!54{vi2KPSP?P%u=s_tC(YYX{T!JLX+g8M7( zsEh^Xsw}FuZ7;hfrBSR5oHbnSXx*LJ+?nOp5E)ZCNO{lIed&iC%-HPKMTPg)IC*pa zY=PQ`@1u&IJwJmy@+pHX*{_1KtKmGOgp9Qg%OXDaxGsMCHA1oBa3{l2pdDvfkl3F8 zhVA{D!5l3w+&K}=*oXrww3jm;iMAixaJ25w3d6Z!?D^J*+N^~$ZDYx@L<=|!?|TE-wYhBROE*m!&u*M;XL%>Yv;1vw=}ebksqQNyAV~J7q4iS?~~5j(Aq|R zsG*E~S<{pEx-Lbj7o`MR^vDm!qQ!LON^x}mznn}kR*ED43a22BCsXKy2i!xB%f^J zLhw|9BZ}z8pIhh`$H$s|8~e~6wc|+y@42h1xRv?1z$c5-2J5Fi;?32yeC*f~W4WR_ z^0wDYYL)MPRkY;itik%!u?c3_YH$011ugZ33lhxNf!02FF@6aDW7lZg-Y$(4L|9T& z{ZWqr=GXV$c0@B4)nSWPt>PMOcLRr_?L(J_=m#SPnAa|O*$rE$zIb%JId8mW0qprH zKfga`o>usnO+la}h-U2XC(T5j8V9wcxG3eV#dgc>?5WQ<-P=5z(c;ngQIJe58>3y! zo=4d~@I6-%lkPVY9cv!c4iXQ1f(U$r8G9f7O7rNqUK?GmB}Yk+3g1WageUdk52s|% z7N6U$VQ-O2ox$O2hVsm7mpjLF_7OPGI3FtFOPS34a=|2VnluqL4mAdKjIm8^x{Hoc zyM=H0DCPY?8wFcpEJLAseE&O}xE@)Y$1Uoww=Y9p>UB?h(r^9s(PtvelD9qWncu|g zH~xt*7d^A=_H^l|X!BaN7mahp@;jH}^^<;)=FrC~RnYBzy8TInS@D&HSdlnILs1Pu`4bF1{5n#_uT5T#ROm;khy_KP@lBUz zi4P?*a_nv4)A4$)>*3~+oL=@lA=L9s5oY@Q);sv|oT=4_$R~GsRp%%#_Etsw9(>>V z=gV3$?as=IRETb|te+lKI>P*|fW;&3*iJDsv9=sGI*)=la4b&mSR=w5n9u7!KIe%= zt@+9JvqiSd@3pv#G5XUH4l~amUiRtZWAyNC4)fP@|LsR&h0HvDV;Q-wVrGuqQFcT# zwr^ZMZIanV>aAaBC<&r7r;E`){OK@95O2m#O-cD?yC3E%T95aYbcVc_Pod8V*F*ZqSE)$BMp0qRETD5{(~*ryq#nrUpb)k z9MLBh_ttyta+pEyt+C1)z2Die<1cbhk8%oP@|9?P>~V*A@a2Df=Ne5KiPqBx%9-0r zYDk6tC;C1V#p&3RFRQ*+%>Q;ztK-pIKhxe}{#nY~p7Ct7-hU4DyqLE#3XHuyRE(Fb zUR_=(xK=}XvA2jO`yuOMt!kk-`RcikA{C+sl#kX&3y1lK%dgF}ce!X66)OkV^A`U! z?WLDH;V`4Jd)v`>#y&B2r*?a8TP;NJi^JM^TeN&ce>u$Cr7bHXsoFBJ;6_JT zfBFT{abi!s>@|vb6!x~GkBi&nABX_YrItY zf#~U(d+EF1I83j~R?nLrpDNCDuPH}dC?SVs>#3K1NzsUs-gflpaTFMon?GMA-i1xp#*FEuXV~d5YXy7TW2g4g6K*@q0(82d_Tz1S8^1ZA zqelRY}kZIk+)htIqjic;uEw>a1_YOn082;>?|YO>@KB@F3OJ5Qp77u zecotJ9$BbV4}nxTJ~$$b9sJUh-$-062G1I=Ar#81#(B(RmA9j^72geo5pVrBkGADO_16fI_pXL}2JXAqC&s#* ze0lKBk^yqVq-jdz4lMw6KR>ghxt3;qFF7*wH)W4P*;T}}mOk8TSY>(c-V;SClpS|! z#+LfF;e)@<7Jp=VtKqJXwifn@&L*A>7k?!6lIQj>RqPUsEuxJ=`^WNW8mrb?9<2OX zu`*D0716m`KE5O_zijm;BS)!FcC^k&Dq9PlbJ%hbckPpgmLA%>*eAxexA2zZ!>Y;U zasMcBQM9Si)~0^+*=@VEy`G%-&&jwFUe7M zq(YyXv63HxWcn&G+WxP(IZA^4z=#E7*W;Fp217ly19rrl{$s4Mvb781dxmxud28h3*jto6WA83{+EejnPC8v=Z2G$;T2hxJ?brzi zNA4)Q8u4n{JUw5yAg31pC4?h)M0-CB(bxVmz}$Dy;&Hl9CH{+Ty0gZ}IvlwpdO@-F z`l?w2%xZsHh)rD@@nKu1iCU*U_|64g^pXF>n?(nE*%6(#VS7D#(*QG$vPei1_vGTO zzpmD7Gc=CeQFe@LG3L49C%(Gi3!CFw4UXIqU1nQLea+ScbFC`^8MY~qmsymqw6CT9KQqBRrdu|3$ce^$puR{9UyzB{?$BOON*-XYIq79bw0%!YJ>8WAvul8b zINrMhUri^LJJ}ZvxufiAl=FYjJMkG+ruol!k(MKOL|;u8tmm1ZVEU}JctmXo;kQ2* z6=$BOa_<9FzbEswxc9!KdLV6%S)eq01+z~xhpHB@iH&Z;BvCdhW^M*sWhycHL8d80(-c+|Q7+@~V^j}1mokMxm48=uY3+X@1 zH(0-uE8bkA`Pfl*jFB>yKFa`Juv(;e=_Yu;|BZv-J0>g z1I~$rQ#VBGGoAI`<9nK&()!p@5{y988GWrDyyK%&;`Q~y0=XjsTVl-FCYn!fdr$;S z_SVk*)KY&*^7fAOu_Jm+aHxKETu-x*m(`CY7rXJV{%gfn=MJs#FQNLwAw4N>=wolv zBvh{-(bMc+#>bves;$1aNQ_y(orQSyTPRQ8ewp~E=Wz|6AU|x0@~_VC&_2%flD}@O zr+BF-yBa;OIkXZ#)HH{z_vMj5Zxm%mG-H?YhVk^RUy3x5lbz^|q9llBY)ILj{878* z;&Ji>4H4*>jvCli&(b8yoJQ{>#gLcw;DfGC69pcu((noLz?Mj_M0fu5&SbH{f0Kg1 z(M2?4SMN3DvF$R;)lVl2lov-q<&n9^InBA)M;01XOX8SdJOI&*E#Ldjd9MB$k=d@E z-C@)K(PT5s?#PD+EfRk$|4W&3)O?(O#>y^@;$M#cAr@`fmGuhIxUMkv#2&^gln)W>{jMq}SlB0g=NbEI zwC0iTHj5Dt?kVdoN`fm9V-J?ZaE~2hM8na;HRO&6b=|$4c_@$DR!M9!O4@McL^Q7R zbYgPg7ryP&SZA{-6$S1rxH@A?Bvni^zItMkShw_phWnkqtC?Q#_XM-`25&p=sEn- zXtbOdt6#ViPt=~-_M}b2u^)&=>x{8&`x^5K>oswvGNld@a&gr3T=Nr z#p*-Z(aL0OXgiH(x|?)xZT|8cxufi8$uc%Dt};)`m`zJtwiZYG6VYfb)2U2`CcNA4 z3&pvxOp1k!vZFmuR(Q>y`PRc;Vo0ev*j}EER6H+~9X&nEV+qnW7P4u6+Y^*ieUu%&NyauV)p*661;o7G zr4+vwy?FF-8LPJ7nU?R$1ZVAn4#i7F*;RyhOWjtst-tMj?5~O^jIyJz&e&gV4~fD* z=hu$q?WN>1pzIhApuF%arEUCBtlWHRv(|S>WaXPLCYkwHPt^v7O65$yX!&>o@^l+8$nuQLTm__rsbL1 zCBQ;#JK||aDxTdhz~XTCW(Qq3yV z--XDzI1?d$$-Y$!B!qPdDC^E=E<{g{%yy)5|9-VKBO!)m-zor+Z1sGxmeE2aTfMcY z+`qr`n45Nku;yb9Nku$dh!h?!ghfRXx_*D}N10*^h1HL#)N|^G3z5=~R4N(;*YEFR zRkX=S5lo2ZSGrqc8^#g^cXdiu>(Q%wQmF4$=lo0@{a9G1Xzg0)3Ym7sG(#ho?WVC zA|Bat-q+5}Smr{USmR?yD%4O~sr7T(Q{r*Ju}|xsbjO8QM0b9W3N@6mXA|FRX^F@9 zCnL1ojXiZssuwm-J5r&BGS+)xWNc9vV(#m#cBDcLWvuz}Y&;zyEZx;& z%DE6rVl&&3%Kh8YP!~c1!my-@x|+d4xMtI$a{sn8l=4OQW|C=$M?sQ`c(@QLJX{Ei z3N@5+aVEYO*$EL#J*R%S5Gnm|AuK&c4Q0$%KPN1yrqSrqSh)}>W933vdW;%MzS`NP z;sMP^Cz?T;k7TPKDf8h%SbB^aN^5&ieUX89TqP}`Id>sa=G=v_^cXdiEP&%V=hFYjJ|fHLJg&}yTMs`3qm+M zzSUm0^wKRJS1M<>BNb{W#Y@ik@s@;G_-d0@ZABFqqUK>QJ5r&BTG_bOcr`*a&GVBs ze{(|@qS}LOcBDcLrLkI8O*SD!O+s|{YHL_h^)WNsQO8hw=!U`>KUtCx21!LcT!<7N zsXB(*!&s@oS*6wUgVb~ChYOL?k5nB)?V-3&rSqZ{Au7`7(pb3=DPxtYW2ilh6|6o= zbR)#aj}@%>NVfWsG9RfrhT22XkBIHgf`ph!T0(Q~LZr-js*d5xN2g1pF4&INPb>dt zc68}gm23me>=Sdl^vdFA=@@DcW08#(YrzfD%A%gZJkp2`un;ry1sYrWtxAxGP*Za2eEg@PH zqRz1Xh9y-Z%VI|zL+xR#MX^BnfDk50MLb-H6dtKMhT6ke_tz!lDMCb12SL`pwW zbquwK)~l|c#Ct;Qq0yzWav@U2Dpki&dl*~QXt6jzh*+9InvZ0wA1U*Zs$-}<6nhOuX6NtotFCeMB+o`n~CK zZrau64c)2b4!GgeU-#ko1V;h;$5_TbW%w%Iz_~HJp4AWC-H#Fnf6^@;Rk!)tCl|=) z`dvD6F5iPKZJx?7g z>Upxe=PH7FF5ErGcB$tsv^D=UA};jzv8pk$zvvX<@4VMykfkN5RIK`N7uEdk|3!@Y zvz*$*Es#AUJ6pb|8aY~9U8t%v~`JA=O$Q<>*ip~qOEAI!z+YR@* z!LtEPjm)RrCk_9!sUkb}TPUK8G7196jbdbmJK{}wmSbzn+IfeInw?81nurooq}cco zL*94EUv5d~5GyOCZCcmN7*aakOiyPBsQHYgSzB2a zSbb7t4J^o!3VW_1y2M1uZ2K3AyIW^#?@tVLjc(oyo_1Wj$lEsDXSZa%=IJ8e?%pgK z7CoS>aO9sG?z2J_5&f*CTu}G2(61a-5NSKNHyEAD4W&~#L|aj{AbI~<8hLJqsURpO zW4O=15KZfDW1FmV=B4?0bEQ{SYSbm3M@8^7k6VahXHHx5 z;aVB2`M{HLHTpp_$URbK5T76qY>6>@o-W)ygNVQg3!)kO<4H@tw%%ni?dnktsW7&r zBEohD@%;DF$hzB14XLoVDq^K>2oOx2%9~Mv$*jtPgQ=Fk%8D6scS8;k~c8*Vwhbq;}(+zq2x#6O!mXuq*Pt4>* zsu6oz8^Kw>Q>lmzt^N_O|6MH(HgCt>JS;C2sn%BxGDeLboxq&cIU-GKjQ(WyXslPCJ?e_1#=~SlmZE<&0sLZ{8fKb}a_Aq&J@+21m(PU*5 zN)jKp^pzVo{$j%?$PZg03%Pj%arb6(`Qe&}bjOf(AJ1Taw5d(eVjvor)0kejpNxKDUjmlPK#}9Cy$id$XiMH1P}gAr#%ZH~U4 z+|rWbq$Q*cI>bv-B_!?9f9Tc8*0;6iH0K$<&v`19mhEAHd(Krva+aLjNxGZnyY8m) zAl=p7x=Y%w|IqeuS%*){U-|!u`=EsMuINABL3(Ss_14DITZ>QVeN6S8+-NJhLnpjP zgZb~j<(BWhzqP4U^w#R`x0Y50{l{8Ds}HwUp9{45;1gO`bnwDbTcS5=Y&0L?I4&-J zUwu-kX!X(Et55m;!}SPfjCskmUj5cLmd{wTO_bQ&%O9VF*hlHX|MW6{x}M37{3vSB zHJZ=Sj*F}BN;|RL;`@f{p(4hm;n)(bq7D1-OBWZ2#i8A`L2pLtSLtNEog<4KcVu-R z%)L2|*I74L*w^K?e9qK<1g9CLx85CPuJX%b$Cjve!qG1L=G{BuQ($|=WGgNcELS%wJl?Gw zqJK-{Fo)&#wByMJovS(fa^Jk^#Kv;#G^E08Ocjw~eII^f{32)j;Qa~$b8FR{)b}I1 z^L*8Wv(D@*nszTv-#4_YIbo)k9W!tdO*X?92d`6Nm6O+eq#!W&7}1Qi3<~A_(q(r( z>diRv;B&g_g|c)uUoZ5rs~Ol8%7yXZgh|f#`ClrxgpdceL>7QEltnz;in}+RT zhPujQPl*ov-t$D~inSRzW^Z6_KDI>Bs2c70Y5QU4+iMwlf_E4F@`X<3{(U}nv<5K4 zgR#8xoAcn^*PWegz8s$*KWvGzsruI9TMLJaY{6wYaz`peQ(nfaj{M7zmd=Q@={d@d zJ;# zS5^G;;UydD2k*8wlltedXZg^;<)0e^bI=>LU26Q*XTy2@OBn@$ql=@!*f`$+Ug6F& z=c9flmH9v(Xl0Vs_tK&D7(2rm`e6_!f7um*u>9pY2UgZwxw?~C^9ga8A8rJo94qrHgBX^8`AV0bpRyCJ4y-gMIvHM^JvE}dX^;*^LZk9Qg$F88+ zlwpr;Pv0#Qu|4CIm?g%RE-ZM$?}S8|gLYW`IM*SacCPS3(d%KH60^j1&kcIPt57`X zt_zWFe<^KG{3P-3;eH&SV7thVv43ZW*shdcB7*Jl9I4ja_o>_UeUw>XOCFbvV(nK} zgq5*?Q>Dc8-jhV7BmI=98lk0I_R|Aj$RARj%oE~lU2ci^LOd*c$K6(ztRHq&B_4%{ z2cqc)&#=c%Yph~utndj&xv(WV!Afg7V^ijwwB(RmmuSupx#xV~^E9sb%y%uJIT!9Z z$H)yvbVwHt{m{f=FCC(1itgeQDB8G+2<$Ofi4=9p(&JFppSzn?NlUOL zIzNxgAZni&Cb}8}6a9I`9`!);kKy&7-4`X}7%o5Rcg=i`1x+u`A6KpiXhd`z`I z^7`~i&I}Pw4WD4U*b>!e*wII>2wCdv|74%S!*5)FqeRaLa}!k)Kz?-JU{#E)diW3L z*NaICV*a-NM*YJPX4QW@?TB_+OVVvEA$N?hk?mu+DWmJS5@T7&v@jdR78i%8} zkKw*6p(4Dx#meSOvWvxG%QbwmXjOlsP~J#0fhsQ`Z#u7?-d8pq^wk-jZi9wY*bfyk zBuAv|wm~=(rrcCU7v~&DnodkMhsv-C>7DDRe$#NyQLk|RY3D4~PrggBMR9z{7B$?q zDA}mS59>AEx1O?InRm|TAxD*%CCZLy+M}BHkw+TO7g;{^w5)K$ZG~f$f~;^?)X+Mu zaoO$ia*ExKPf$W^i81mfip_v~2JULOi!wHNWM$_=|0N$ zpw)RcOyoW^fTO*G76;lWt{sPONZE1F=ESoi)lU42V#wB7lAYEP^sq37O!JW%Tc#6} zZ#}tAZ`3n-qtFMWH!9V;QxWt=arYaA{wrxls>e$6pX%>2M%vEZ+KwJJ`n8Cridp2* zTk*slHQFM@7 z(ZQ?~VZqo7Mp#q?MeejaDUmyj4q+4rqg0F;O&e&dZZ(%BC=Q3QC5%QSjiph zWAU-J$Al>Klg)`w5V2+K4ZdD;BU(?5wOt}abXl7dpCBS)yiaAb2_T$q1U^9owIqM= zAgP>|RE0?@e1Zs)_Rx=hP|uxK&udc8@d+YmL=L&*m!wy{W1Uu%^8rOUG5(2Eh-QqU zoKAO?6Qid{MKkEirn91-E-evmEx`yaQmHXyigF5floOvI0;9u>Q3O(05y-R@fyBr* z>27M&S&bo61X8*qkQi6T=sCR~uAG_gZ&akLBi#{5dhb%B{Yd5hof=P+Cn=uzmg0$c zqJXCWcsjrsog(uiDW}MI&Vg|a^wk;rb!=^3lTLVR&PiXK=$938#t<%1uv{K`lDO!E%&iVdRW%+6DNwMfb0gmU6)UL~Zurf!~6W&*+ z8_IquCqH;jj%U!gi_%?yUeCm?lne+wy~jKNJneVoGsrb5`3#sLfL@WhJ5#QKE6c*l zHNboZ%(B4T2J#0-_Sf8*1DIuju?2PKJY9B+$Vs^$vnlrj_ifzI|I-i3FNq*T=9dkX zJQ<`?`;mrnSQZf?Eg|s44K+jU$C0vIv?xN1BdIXc1*z12bWObAJWJU-9*4hYY`Jr8 ztd+qX55WFWrS!&&MG$50-17)lvcix`&66okIYm}h*h|VO!rURGQuQi<@|Io`qB`X* zVSW-)p;nUrLAg;@#@0*9jlvu#q(WPpA}o}D^^_13DgO%dtdL5zMITd+mzA+Kh7h>Z zqn&{E3R(J;M|PhO4@oM_1VbwItsO(TYSw({)N{->Ln_n-ii=V{oHbTgX>>884XIEU z7<<@wv37(I9W#G@ePa$?RVQla)xRTat?tx1T>lrM^Tp-83fA7d#ewE-bc5W;QU zS$h%c7-|pQeLd^P%M!w$q{7Tqq(bd+_1u+PYxNwnW04BAhvK`H&udnOX$cx#%)mt| z)E>s#R2!vP^HGLo5VL%d3bltZpB~$7#R)Nnv;^~wkqR}2vHmB=I&)BVbc>X%dv~V2 zMdj8p)E>G8LHX2-5cesc8uO-+3blu-a#7BBPu&ty<;S|F8b$pjzImYPHFwxg^p zc%*Xw{%$Q1A~jDRy#}{dT2$`e->s#QbQi$7J+O+TawAfBxXy2D*v78)hv+f)8B2C159!P~+N!3U$mv#ow9TWF$Co5aPy5VF|x%C(|l;Z6V z-Z|}rSVi|(@V*LCska9*n?a%>AqLW28N3sNRO$_d>y1YWi$}R@-8H;-gH))Yj8&jJ zKNgQRbms@}_8^sd(_$*!E3$6alv=UY=Jp4y`$I^D8cKH>;O>&!Ysg8rkC4j!`}>U% zLZsf0!rTbAR;Jt-apgIDzcI3k?qFH-QHP{*BT{&zQlW-2_7mOnvTi$tP|v9!u1t=U zez*`RH%45)t-By}$E5K{*X^@Ube9ZogP|UyhB8*v4082j63rmqI72GbP{yJkyt7&J zF_p9gZ?z#6YAEGwUoLI4ZicO(+fI0M4yjNp>Gr^f@PoG-CCY3`k8Rcyx9*}=TK{)v z+|WwBxwO+l_<8vo^v4v z9PDI6D%469F?7;B7s71$k3UkOR;q}AUQeC3sONOqX*g23e_Od&Dq?7JxJUCOXb#l6>`j8$LmP*b;r6tNakzGN7(=XoWT!Qeo^}J^vWAB363WtmD6B7Q?` z?cL#j6&`p#q@Mh|Zr)55X!O`NJXdZ$t87E#*Q@Q#i}5+^XBKod?*Ffo=|h<{80)9| z=fTb7sXdQu$MWaqNQLdHh$-EgNxi_owsyC2Ddz@w`ii_M`Y|y~hJGAnEBW?cD;FpA zWEA<~7}B}(%2@ekZC(GMrCXKrLF~DTh^R0`zI$HB*`-7qE8d=Z&V?h5GfStIq$PI~ zFFJ#kOtqoL;hd|8bf15bPo|U-4SP;@qV}OK;aflzFsWM4#)ALa+R|9jnCR~Lz>E|c z-PFt>swvyN8PD3}v28ZZAU>h7(%mzNEs+g3F^pIKG|IM?Mi;4Qq*Jr0XxvgWxu|Z` z%2>W-SzZ5fG`cj3x?6XV3ePDhaV(G9l>LwLS_>o^|E`h0sVt2HoyY!}t<q}#_=Ge=cdw7wl52(I zEog-+ODh~of;?2jp7KL@1zN9W(RziwMcHxGDb}|NDJHDy>>b>!}tJ)jTrX zm6;Ju)q#v3)vP`(=^;l_g{JCMp$QRGb;xj6w!$-3SA{0|m?|`_rwUC-h0$RZaeTyM zQJSg_J)^2aC@=PwD)$&azDnXKqRZFs&xmu+DHaFvBAV*^81Bkul*y5yr~G*FjM)3r zekV$WXsRb<{HRCv=C@G!zmR3(236%k1l1`r+*QCZ%I&J@B(0iGm#C%_QsM0?6|tc~ zn4FtFL|iU*)v9ciDlhhSL7HIWif6nzo4&L{zH{Dqd8PLhap6QBtAbgoyom0ZBiMMK zJKmf{wdoj3d$F%98MjKbZIeTh3emBdgN@OJ4dUlpQ_z$ zW)vwAZ*HcVZjAMjzsTz6$2yDDs3?#-%1*U@4ENVu$jbP6sC@pUtSFVgf(^MNnkoVr z?&^Y6YjSUld=@fVMEQ--kUOHO0+I2fCSc6j*0S@1&EnPJdm7$XLo`)6GTik6>6mql=$7MG?mI7(L-M~Gx|}D#<{Kf0loeK@lg!Vb+0K7pRt+J;T^kc+ zS9{)Ja3?urR6b{uzUes1iwJCqu{j0W$q~~6MfOSQIC4ic)hsf8RN4GAxrxmFWQ(}A z*j1e}^>!Zi99yE>XVH~qj&E7D7L{x9)sI7rw?hV)GpJT6NC0;m zmN;M5s<)KN9TC_P<+oREC_j1B6h&X;wW@3y?i!zn4lL2$cr|l?>E)_=nr(k$`EuO` z;YU@V@Ma<248)eGQsLiEMcGMBHNPUERt+J;T{{*f`QP#oBO86~Xcv9$h_SG31!ZDT zZkt}WF-Pu*z?P_%MdsS_<-2U+T69G&8n-w0ZyaDYrkbmWrkX{@k1DiVGdGbLZ!8pD zLNZy^TT^djVxO=jik`0z5=m6qs3cW3qAEa!yZSFmLKSI^A75&^!0w9eqPFeSlL)Kc zQYv>uU`wRC9ZSoxKDV6Xe&be6C&OI>7tvI+$oNr5n5sa@TT}&V2UUT>lTqvww&bd8 zq!mi3Y(y1|4EL9MP!g&TZ2b5dRKAwFvvNxHB&w2RxW6TYk|3I*Y73r;98{sH4pnHP zN=%0Pdqq^C$#7RXMl@sQW?lBA>c+>Zx-n8A8c%y&b)%%aZWK~sj-QGc{8M9jiE1vN zrJBq51jh||Q}q1eXmL5Et~1Juqkz0!wWBq6?Pwem9BD*TrH~InJR{Yo-b3}Naonjs zwc-8(EutCoZx_{lepTwRGs}zyIK{qQuPNB*b?1DYIVmc zMs?A$2M$uS9nq+jR9mFP4DAk8n+~ID)A$}>pKwH|NX6F%3u>uDY3jY5R_))t9PCu z!Z(<1VV`I$i*{Zl{AXrTR#B7$*A>Q=)eDquHym-!+wG^UaEMS>(T``U$YFV(*{aH# z%5H$N=Ul2^u_eaP38LN^&;XrQ+73!1lM`S^u!SP z%vMZPtCC*XaS);IYNfYyk~!W?@;}}+ow7Tl?6`|k4rIR$a(eGTZNsC_8t&WJC*0xa zYvx&-%Q~@JL}CTiX29G1Xg^SnSDP@oGQ6+2JmgOexufhV;_lhL^1!|)&e=6KXlN%O z8toveXx(R!Jiw;cJzR01(ho$VtwlMh1)Iy*8r#LyVXqYX3j2Z9Ae|4cjFba>=8A6J zHz+n7%8oW8eTVmHe|dXVFL7~6EyYem+0ibguRHD9#)?^wdI+@c5skhGV~a0#lV7MF@)oLxjNT9WgXmvT4&;trGG??CugZ8^ z6=G9;9F$!}FpuuiD--1cv@W9fQHVxQkFlH-xw}qhwxg(aGc;W`RX6@f z)s4}A#d{3sAyaLtykXLVDkytU1!d%pva5)SLo3N-s?ywssx%{aM5C`xx3L7Mh6g$@c^pW+a^-(cB~VQ;tQ=WHKpG9z#RJCS)z@udmQG`>Xwh=UBV_C zjxQ_2r+>35L8nFykg9uBFC&h=sFkg(g~(N6uc&ajfn0Z$ZumoF0;%#2>S=8M+hMjV zVjZjmyq~m07e=7qMq?Te-98YVjrNo^o#jZ(5vg z)Q5aghgqI(+K^5Cz+0{_Sznf`F-Jprv9~JXb3jRvrp8d|xvP&2r9yPQ9ledFyB+42 zHx`fmwdUL8w?z5B#eq<b7@5B-2;smj3HypIk25I7xG!_mK+`-&*eQo-M8)e6QRX z89BY5F?M6PIoIZ8SEUM%&L&&GE-#=CVQL z3UQ$8XAN&0ZF9sM{$3I0)jVEywdXzF`^vC8Ipn5EIXU(asSr(HYYzKGh%EKxnyI-s zaz}Klb^VN^73rI-^i@py{@@(Css6HqT)N#Kf7hE)+}|1Z{;XhQd9 z=l2d)krNi()rP%@GjgnnFbj|*P5t7GJu_)O=w=x9i9Gtk0rK;T8RBUFJREOPWqTWM z?7tdehCcVSt5U5yo+Pf1yD6>@Y{QW|QX!hL0gp>+udjU;r@nUNC>5g9-s@+ayc=O& zc6}rFM*W}p&u<=4z3>dY#h-CTyPFZFPLkMj#u?tHBFv0*U#)+!I3syMgjt6E&sgOT ze*E;}vtrkqQXHQkKWvHi+T;GR$k8y-tFIr&yJU-Q#2e}IMVgD~E52$!Hk_R%PP|DJ zjj196%8OKprafxx1g*n`4kF8lSfw9`e(CII)bourN73BSJ^H=P_|n$F;(Dkz7pvop z>zU~ZeXTcF#yDf>?FjSF8|o;K$CBKP|NAIdj1E*03tq<>p@7ZRC=4p5>7=r61NX!Cr#X7hjS{KY56`chMBWCHzV z>>tH<3pC_i=Va6DX9{qX9jOpaHDyb+;N{a92eUoMX?;H`HC}@LIkrUA#rCe!I?g!e zzj;VMWpq(?l$NTh^c^YAcjjDfl;WAHmU$N+0Nsd&gV>s%R!xB=L z?_Y4gJem3I(VAABDv>%PD!Eqbt*^laByd81Hv z6*2SuEK&dC7hybVsYr#g$CK4Zj!eYrTUQMhVjpJ+bLAJn>zuPM8(&&zSO z#5GuzYQOD{ZTg&g(l?-#vL+%GqUlC1GsT{}h2@uil@+N_c3kJFrtGGs(tF=5(corA zj(Y~~yVxi4alFpk9*zu`e;m83;eLk}0Pd)aRc-sq`E^oTS?PWjWsgGHRm7{8>131c zeo_z1p-6?Y<4#Tfpm%GzCgUtIWZOp#cYVD3jD4cYcpv*{Pp9;iIZusK>=Lxw&_{>$Q@-@5tT3HmtVaLO0Np(I7)?Rw9XiNv#5pKQeuTTUgM*NmLA%> z*eCL~k1W$Z<%y$O#Y~{=Xj7w&N;!8^r-*5RedPnMNDaB8>?-1Y%|bG%5XGYQ3q>kK zqqR(4YQdKB^|(Dk>-9iEpcRhZ3w?QU{vhfguWo@7+69>Nf3?x4&9IrXfKacIwV>(GZh5-QRtD;spZCrTGN@8 zg*C}*#Zq^M=JEG=`{R)Gp%#YgWAEkD4ruc)L2)hyZND#r+rIIPvgSlNHe0f zryXOxl*tkON@VM|UK>-cB_A-gm63H`q{2Hx!Q-=~m#+W6x zL^(w#2g{hHm2Ba6I%)U>BZU~HB5z`F2dN*`wSV7yRuC9ZL^NaaWrU2H-&HhydrVyW z*v!~6IKn(#!OM6hO}L7*gvCjX;MW_hV#k~noUNcKG1(x}}w z+{|{x%Z}}0RD`h&ZMtinqIL`4@~$s6rN&E8ugFU=;@3IMaQY4&#jmzpar$OID~eBw zqI}LDPu^GVY^+Lhn2y@sc9loka+zh%0!gA5Nrg`kfzr|~?6`Qj-6xy45Ij|hMj;iB zA$^HvQXko1D%}G(w_U^WK`NYCx-n8bzpT4#p7!rKn-ZbN8B`H}J!z)psc}$CBHcwD zMeReaq%Une3gW}c#%LF_=TQ)-?Pvj#RAEK6$y?&&l=-to!nq#C=1C6ImeCsbZpN5S z4s&kt@4r{aI!u$k8&6*#o}Yma|CB+F=~sc@J`-gu>=9{}3h}fTeAn0bIyS(kp&5_FxDRc3jef0-Nb+lHkMXo4KSWcFlyBj(-G$fAv3qW5Apvw9Vlm(1KUB4-9(y?k@yKKcFSi+kCTAEHUG*7lT_u1V4TX(@3tODm&FfpD`W zoe3j9)G>;YMHQD#E81n)=Cii&J*|vWUma$8)60(h5KT4DeoHHV9px)!xS#aUI~!|< z(AVDS3l+!@HJ`DIYj=rszESdj)q06(v7L=tqSprGoBy zYu);T{P2AwkABx=XO6=CW&4721!^DiLo`{hU3VV*tHdud-_Jpsh1f|=AIcKQf&R55j=t*??a7tcOQ;bwD$=~bRjnjntzdQAUx_Vb<-$2RQay1{w66vCHcPX`}F_vX; zXKmYoVsg_8O__6x%DtYe>wG|4ht_LUHCb&;MTt-5)QU3dta6wiX*MmiTYDILd3=Ia z?oK6H@pn2?1uBd{qpd}!WW&~Ig^%`?qxxo5RyedQ(c+|-OvepcEvk0AtxAZ3Kz?Z3 z(J5KfMD4?vFxmIoQN`**9_s2^aQFl*Yu*q(sOn3B@kESS_Prfr1c!y22_vjgPj>qA z=RUZ2lFjcsmAyg5V$RQtY1xos+x z1m9pf|IjOIGPu3$us4mO?P&Yp3Qiu&(Q39Eb6ZIBi?3plp(TU61m$x2UT{wOt(A0s z@>1+8v`cU&qNu@u=Hm08p)%WyM;cP0m4Uk*^9YQSQ03 z)WAV9)9Vlosc;X+U7Iv<^v;7Ge!s|qor5%_Qun1FmI3{L?_}p}vNEpaohwvp0(Tj- zeH|~(I^P&29aPp?$8RuF{Fs_`kwN@2`Q?kFRgfYXz3xEEdBn4<>dXjWuR{c z#imAnIJ1o1Vi9ua=GV?iJ8mgnDq5_Fru!coSBRwtABjgV+9z-iW3hCp?QbFzmXhG$KM-chS1XcZKe;tPIi`Cf=~ct{%*B9YlVJX6(qE z41D(gGRV-l3d%~2D<{6eG*$scwX?h8WbNqLE_>H)z=Na!zm9DA%Fu!pN}yH7G#XSyCp@8ES^wf!GpdQ+*jE&SfqlE9}xFK0!qBZXXWS4<>YGi^rn8gT=82g=P0MnnbEz z(>#)&)|+IuDsw$hMKsDbOY}Y2Q;vN-OL%P`oSbRvM6<~1zXK5+n9(D-VT(!TV}FZ> zZ{{=N(Z{^9>!hFL^e2Op_ph30j#&J6Ao4&oMYcbk6oY-jXvW{V z5s3V}3l2_>*fG(3w)Jn~Q7$H{ygSrWrVS}B5pjF};^Y^FCYtT9+z4FNeo}IY9uv(E zeq}LBhCm zzkirudiA(TJeoIrB7FTi%0hv|m44)DxHx%V#ffH<$2S61#PUuBW%1UT<77m`^_6417EKcyc}e31+n4ZIbF|TUl9jXj+-+ zjfd36>`4A=!vr(O)0=_V?!9ZrlPlMpU_Q@pAL@Couj-i(bm8p!*(3(9q|UJ8$4uS*;DNu$l!%1;B| z4z6WPdN$I$`{iHaQL$(<>DkOz7Q0_s;FED_1B{TTBg_(wUInT=b_YeswV`XolCCQi z9*8KFwU$x$#Yi*x4~xg^!x1v;!DS+#${K-GO|k_Tf8HBm-U@mZs3KN}hsdpSGRn{0 znRx!Bt&un^(M+EIArR4b9@jJ8z8qox-Sidl_?ok~oY-)tFk;7uGOyYitNJCHW#)be zL>`DHzqWq3?C5n@)T;l?i9D)ZYiqO`muN0q^da!9EzD?>_7}5{{6ah;Z*`ZuJD=0BOg1!7B#m6_E~w(S)rX4(1(q{_UchjHucAoEtnZ-LY6bux;b z9cs24^ND!q9{psuU2(!UDN^7QY!_RiYCTcC<=1Wp#o)a+ocQG0lpe+rufe8Awr_zG zCMFmgN5-2gj;E!4aLu~`GOBcQalVu;P!dEJoRMJIhQ^zhk6DP$MdM}cv$^7n{+AP< zV7s^{(icN650XLW%L!4Xtk^Is!I(23-pogBAsY8!x`kbRusqFp7K@sBcj{8yoz4o45~b?e(5b+&mAkgt4~ti zC~Oz`(P_qxE^<|q=b~fI(gNQc)OJKuCg7%Ux%BZSG5hgSfo~_SSL({}Zd(gk{(y(P zd$f+SmLNa%9V|boovh@2Qp~-1NLk?~yvkyPydG%&tFdN{7P(I z@j=rW>8r1z4z zTOyDDBkQZwg3mbSQCakrv{0;Pf#xNvbV?q0gd=~>*} z-MP3sytBQ(_WR_%=dbhmB+twwnM@|h>;%_&x=ZbqS$t~JLgZXKN#cQM^akjRY;RFf z$B{+c&*Leu1nHu`LXqV8-txf7twsH-F&upy^h=NueOFXChp_nN5xxawj|_cA^v>v8 zGV?ipI8!H4DAQby{vi5S=sD3lysOXfCW#)RLfcxBzl(H{ANkZD7VsL8;Ud@bRUG|V zz%tv>qpd(-TbPU$}PFVC8>%eeQ^vc9Z zKk7O7xflN8b)WnKeRb@g65U&-1n;38z(>Q=|6E=X)>oyp%UwE3p8oQH_>>F2ar)6B zcWg4^ui*9k)~s9gzUxB-mY`I~o1#VXPvXn`X7DM)2MDZ%Ete7ZN}0ve4O{r&>Ujlv zmS;CzNm;cdMj!s@zRmvnc*^H5F?w(=!xz0fyQC<^d-FQCOk!o%1t~wX#p#9O?$}Vn zQS&Jx-i`eB)xAvvdpD7MYNU&l=)65Tw@BD_oxj=cBkezshm45-;vx>Tn!sb*(;vfqO2L6 zZcV1?g)%<2p?y@8tY3me;_ql)u!4)gT4*_CMCOYou|3xV{<38TX*>`yY}JpH&2y*e zo5LQ_c=)wxCT8!5;QPID39NYnesd zi1u|J6j6G+-EVA%zIi#D)S9Zlef8XiE1aU-KT%(}o-H8q?ue4sD6EBO`YMID65W=V zc*k6s1eRb=qd%`Ghq`wcy>r%A2hX`Id9NS6+B=tY8>a^i{%-4drIGWHbD}=5`$y`l zI;@viG)Uv_VVyXZpua1703W^Ei4=GWsfonT4yVHGMXkvoI1A7{M3Ce4bW0a^g@om7n-c$MV$O+CbiG%dd z`!d^^=Md+nYV?Kthzxf0&ghMi0b@k=f=9FxpXzb+4SzZ&I$u}^>g!@%>_|ybevgb0 z1N-^&vWrSdz9^z)#IUZzM45txO_6^u^DIe~M9Uaxy$5p~!8&EIY*AkdPbg_Gxb;VgMXmlu(I>#!!$8ike< zEhbrLRuY(j?%VxJ#*qs8?M2M;(KSjczZ8eE4=Z6hP{ZrOBsRE zbD_~qgHH}&>Stpu|K7u~q}jzN=h!LXdO)EZcBDjS8Ls2RI#Wy2ORq{Q)}kCj=~>w* zBT#xaGb1}?7O`eyC<`eZ!m%Xh`ytMe89M71r{=aJC5phdbQhU6l~=a}-cqp^=I)}5 zKXtcE3psyCvygxcuUd*`zwCCd1ICs6dt)?Qsc$yLf=hB?R( zP5BuH3>7^d-Ze#RS|nv+L#bpQFCRvV`>*aCyiogj0QN5SmE7{h3yX<`O=hdrX4YdD z-O4#T6=|urXji~~Z(2F$@xNN?r#cs~pM6-!d1-N&e&T%r+6iCln_c8Hm1f@t=VDm0 z)RfOzF*#JPSkc{%lxR0WQ3>A16Vw7bYBHpYwN83ebLP6&QXlgqKk?Xn$VXK04pJS9 zE3tuD0-T=;wbtiX$#2hl!0fD%t&JY_CZGM*m^#kzr>*qBg$APLj~Zgjj*V)U%%vHY zAYG(HV;*D@+5MNRo39j)`EI!~@_ zr88%KJMyDcjsYg|e(G{{_l<%K>E>x|b)Kl*MsIrgzdXV=RTLQu_ErDH`!J-1Jg^TH z#S}V+TTP!;XZ0|)rRtuPDm7c^<3D=XecSC$xpE{}uk+Ny{>uAc%Ak9}dhu&UzVHJh zI3IgwgWC3WM}{Q{B@dR z@t^<8PCS2-L(GTV0+1><-oEj&Ucc?)GsJyEeqCdpZO$EI}T~n{KLS zW*2oj7GpO>K8AERtjXsrmc2g-W*Jbb4z)3I!OO{*m$vUY@3%_<^r|YC-%H|EWd{OOS^wmA5mI$JF|wh87NHNY{1T?vx7ETIdZvd)Sc@ef8Tai|V{u zg~dPiV_VAKH|N_Oq*uA@X)p8Zq4{~6Abmggr0b-?<~9|B^yJicEnSs0rX%e)soot2 zGc3s)YB8^#8>H8M=4nSt<7r1Ub(PEYq}WPt z)fOJz7}i>Izp5i=nIQf8ZBKiF7ZZigj3C|RrO{WfGknyJw=c;acegXFg(Fz`*9ynd z6+!xfdj?`doLvjMwoJX6dlGd&!gTQDfFkX7s5`v|GpvQOqqLN{<<~WB*r-bE zaM=Kcl03Nj#1V2JNH1`~(~i99ZoBGCHR(e|*2`IgEf~Ge5_KV155DJNe}1gJrRLrs z{pd7L`{gFnER%)@>q-x!9lIVTs2k>$WJR|6F)Zs^<4O1(hu<2)Lw zmM@p6#`o^auom_LN=sS(rx#{bCx2F>H727srShDAyi}h!tP~A1j-Hwzfhfwk__3gL>b+cCp z%Q@+j<*aXr{xFw^edO^smW>lb^t07G?1-k7^FStc_}4A9{ALrw66A-J$cm1?q^>`b zi`75jC-Im){-DM60gd@pT5%p-uoOAdLO=7ju^L#T538SxFIJnlcV>Q5_E`q2E%ZjO zAtGZI3I?!nolcdJx6}xCGrzx#MGGuSh+Su+0B>P z8ESalhlQ+1$(uY+-Xx;QCf0RhldI%n)yI2Dh~Z;BtgSkQ>F+(;^ptgK2q;CncyW^AM9PZuUgJKtkzp_MlI1TjG=YLd57~+QSy0wHrdGTem*0w z=V*7)9xF=s_t&&2TBBak8il?Ou2HylkzX=1k-x0_MV($MSn_w#%Rujg?hU4A7qR5S zt#;&-b}Z<_p>IciiNzu`mt5-Va%C9ii^f-cH#MwTIY~7R{?( zarI_cGPjS-IizD7ebS+PcBDjK*Bq=P+P5#Px|FCc?QwADB_o2%RTC*WywvT}d>HOh za2Hl?WF2R|53O|HMTUi2)T4svA5%uX-Zenl45Q}aBp zox!f27}0~_ZVPu|_CEJhzSauSpM@K%^R=-DdCog_wQqqw(u_j%p>{l_<=_^&^@f2c z5^<0#QyZ%J-}RPwEG&2^CHIULdhl@%yNtM3cP%fqwt;%I!T{EA-~5z1JXjC0c}n{M zoWY8c9I}?rJl;f&eA%C2NtJSYQW{!Y=tDkv*pU)_OZF$4hi3~^her)zxJ$u3hm832 zEQm)BXrU&Q9>H*bhUlbrgHqau1nZw@Per#Gb4u_5_7L?>;3&ynA-X|e^^|&lg7hD$ zugi~*xUW6v5Tbf~h+us_u5kR>5u{JKFMHl-?Z{FG-`AGR2~(F}j*xiVj&e(>a5qSQ zam3SJu|bBEUYCM&^|T??{6Y7%9Gybd#g8KxmLOfUu5>fH+M?y@5vINLN(F}Jf zSZhX+`{pi(gY+U-3`E`?in^qHi28eUgye1HWFiNaPq`d*w%5I-#sW~-Rf0w$C8diS3y7z7))f78O+DBon z3Yilv!M}p_QpF4&*Y|B!+m>mh7Ucb;eH7M;EwjgBp}8`W=8B^H;Z8N*U7NaKbuY<7 z#`U~sb8e|Jw1r;tx`F7r!>MjAY*Wu}@5PW7)M)+Mf*djENdw8z0(`&;I>Zm1Qe=l3@dWe(?Oevc}vzSEj9 zENRUPTEEN-(|6EXf}Rt_^@I{J8PeSZ;Sb>6Y2E^BZyuX?;|C27Zk zwSxNCtgXo7h$fGNzG^JVScYq^>edzI818GZ7QT2*U$Ux0b>Y?3qAnrou(cx@+HmvH@% z5o7AFG#x!2rgmI7T3Xd`jlva`-qd500#+YxscsG(!*G4YT6k(mar*HVZAWydy0_XG z$uGh6Tt>VZdS7cZFjU?CD1xD9fgXqKGfbOag2%jSq3#VG#n3B4Pe%4j*r6c4=5e6< zpy3FHo)@Cg*P>{{=h566)l^MdH$?I*5sm&F-G8vP+<$Qswefq|v&1_O^fGBzH0U5- z?`Btblv2JkQ<6tXA65gQ2&L9y0pZgn0Clw+r=GQz~_0=+Pq@eRw)& zxSdHf>RDSIqP3FtABe_%0%-~Daf)QBrJe~1WVkcIdpvoMQ=1nROPiHdiNx{TJ7>TWT;Y%s-Nbc&p&Iwj4d~vP?tZOl_t|*X zBfnkq;!YszNB7Rl=-wG?p;R*B%YdOQjP9LB)4enDz!!DoH+bmAoxzQJ`ddqM*KAF@ z)kjK{7w2IlyGS?HXX&O|ss*no(G7O`>q@DS0}LVu(n}~>z?v5If|OFD6WA+?PAEyy z2}p~g6VhKeLUd}Z0b50}2G1$h09%Of70En?Sh}A%B>mqSN#94U`)`!Rl$nRL_I_vi!qdH_7)XrEKuUB!Sm&}& z^xA%`WZq+ZrCT4%y_s?P&cNF?L|}vm-TZ81d+Q|jW6yIP*WNy4m;6Uek}Q zcb9o!ObJHsk?!WG?vs;vY|JeqP@1wIU$zhkfp+yON`hwUTCCMhY;S>S4eAhu~0LPX4-#6xw*x*uiZNGVzSAI z3hP}hJ_X|SSp{y{T(>5gD^irr$F)Wj>-Mq3_LU(XKGauu#+s#CC2LBCDf$8JrEOWu zV%8Crrt0C!KZMvjY~EgPLX`Lq;(J6>Yy5zTdiBbmY`SfzQIEg;fe^DwXZP_X z#C>W9@;JA%t94D#7(MC!Putm#ZLAlojMtw}{6>gZ0dxIE5W+#dTO?wTwc^PU`tL#+ z?06r68be=N3>{m?pAc7x2hzopW<0G|ln1A>?|VVIYtD0wJb|MY)6W>)l!eUS+T=XOQ5z&} zhnc1*FWBCFnb-GYU0jZF99z^9)E@d$FH6b&;neaZnzcQ>FIZ~nG5Y-2`!?(a(){!| zDMe{zZ{lkrshs~A!42O2)-L0t^xeU4ZKyF6RUGtaZ+SvgCN06SMJ+*HP?TKW!}r!A z#2ey)a}CE|9`pCxcc$uY9pZswi#JWE3v_0=rPIC=#G^hTumtbx@II1mOlr6De?}wt zheA0`DW_JNi@oM(#U9BY5gR zx{I-u)Q9O&nsjEFso>sX#G?hZ9JLxFC2{-}rTCmUpFV{6Kywha8e>vr#7mE(KD!7p zn{*dTFv1X{bSb*6(JY@~gg9zgQP66PD#p1&u~E%;`TknfkLB_@#&KmqD~gn8A9XyB zk6{_EQSYK8GYkH0Ip7kfpGml5tGjHp<=4nK{Y$j*?W^%Kv_0iN49Wklfbw^d(~p@29qf z%`;f5w40_Ey=6psuS*QxTbU5~Xw1(>fcZIMPVywCysYPsfdWhtnJ!MOGA7ebil96Yn%^U%LSDh$0@SiAWc< zl6H{0Ciw&qLjO-+VeFV3-IlylnRzj1Z`OWNXtSOl3sF zOp34J!#yPg`Ua?pvR*kJx%(MXWg`UIS6rQCE!jDC*B(DY+#v*7OVkoss+g;H_ZWJ0 zlMq;fceHXGS*3N2_EaZ?LgRr}4LtxH8`=*#mhLs|?m4o%Xftq}abzjV;_msq<%mZO z;(=1(Jur?Y`P5Tx?Ym1nCJ_%D1GFVbiL}JyOsa*uLM_MD5_=S9u%f*0Ie(wA8nh&- zuupKsk$D8%%CK(*Nwvo97)Or7s<> zy^iU_+GnYw9*NNS_+#PLG4)65fjfWOa6E9F==%?SG&@o0tTrgDq2&9}cN5mM3>zOj zMp_@P8>aW&V0O>yCUhBEh;8P$r)0* z*3}xXjnVsl{%J!5`l$3WDfQLG!x>E_53iQIR~$j4q$tyB4rZ6%_0+C7wn|bVUF1ji z&Ve1+kRk23*QuA16?N7wW*ymis?Od1v0Yf|VIBWxs=jvqGg{AUJ!{M+_kLnJexR_x z612N$k4Y2r1h7x>f2q3;7nKkpbv&%cvPSDJlb_iTO>a9Tc3~U3ztV*NYe_2f?iUUy zYrU8}MgKhe1xdC0ac5?|5z609y2r5u+aXI8n$U?|eshjrUOAJ84)eDL?u^n)bbo6@ zH1ebDd#`#jecPd_ZJ&6FP~m~@~!*=YxO+(#}d7Anm#M( zkxfPvIUmfdhi38zjtrt`t=!h-YohgTZclB9KuVO!^M{??$-~qYor?+_DfL5c>#M(_ z^%Aw7+K>`O=~c9`>f@~H?Jo4i1^9!AmJu6#%xv+g>ilNy(gNk(eBhd;%aIs8ca{e> z>=DXI-sZB}d0=LBluHwV+_A4@ zM6ugNSi>c>`u|m3LSVlknsNvonxuBwa-27-+D&X*ooHS_-%;zsCV1mwr!tK*YYxZyuMGg3 zjy`<98lEEf_M~BlDbV|t4bh4+w@Q@SXU%C|s%}?-C5XWGDaxMn57eGf z-u(6Ct^zd!+aXJJ^M(&w&A0OPeTzz#0p|yfKb_irwzDUhnCc8KD$v&Ati}0Ad$p+U zY~i*i2k-9wM_LEbs-d-`eEMGovp()80>1UyEO{BYF5!BWnw5*CW#vLYf%0luduRjo zEAvzHcv=6K$BVLZv9zpQSc`IiSUd88y5;{vP_8hRmMe_1gQU|!Uj%tmPT9EDyE9YX z0k=DS1fE$L|I^N?-}T?%zbigoAG_H&vowB{2$78tSc2!fNQq8A0^8Mg`9B{2MWpdS zG@VTBJ+0NRUQ#6Z)K5J#};V@VdF4W34a8LLJ9v z#_La$<=kYnH>k2pE4_HIIGAk%$E;bcdS2r92LG#z;<u6l0Be~e`!&_c74$|Ce&>IzcDzQ zvcW%Se!OnmbJHgCxcKovz@+s<#M;?14@4j(MOiQ=Dd26&5b^BSI*ug?7emd5|8E3Q zT3TznW)GN9r?hD6TVK*d>?@>1ipviq$CFg6Nh)k1N+t7Hhtk6PY zdU+|Y9t>;*ReI>ViZimyR-OWmh6D8^kq>Ht%-zX>G!_jKVe~O96 z2USTE(YAY8b6I9JiPyK(G*%q%LN!!3%J5h2_-c+ku-4=K_smYp33xU&C!qB~4YmA- z0b<62M2@wV+;O$^35wV6skdx0;(Xy9s@ucDB67a3KuK_g`xaQ&(vj|4_U$yJYU2^9 zmR;CaJny|i;(@jDUi7#0E)=hKr>x0z({S~+dhm~j=sdKlz*@)y*DK0vP~why!fDEI~watwEN)hvW1)Qw$%j)s#=_ z_?r1encWqol@oofr(=g&Ob6q1_o)Wr^{HKIhH5=T#$$6h(#2Yxo(-|gCJBGdG7#~M zUUul6N2p)RNIo2TGPefKu?%k&r#~KQ_=!*c98vS->mrJ`o6C_d*1F&|$C9%{oSu8U zfw*DvWLv&v6aD@!EP0mbYvt^**%Ej?R`*_Hczt~$AFG~z?ZmT-u^j1Qt&q)$7PoJ) zdU&{j_|ox-T6tw#(amEz$69N1Z?=@V8>>%Ueb*)Ed!e;sm@d^q$Iw=8g4 z#&(F+mpTm3a{h6JDRo0d)pe649$4#?*=dRF7OOWsZXj%hDzmq(74c$dPJwjMFMXe) zTSm2{mY+8e=Z?BCy+7-8;jj4YQ@=U-ZMfelUH+9NIUq)7y^P)6{=%N@!ngWj@B987>0+&R7hYQa zSY!0{0}VvuH8vLP_mE#&{Dvc4+}$l$PkY0S)ASF*IHC8fT7vbO&&1H?T{+UlTHRXx zv0U3eO}}!)K)h|)jLoQjncq5hha+9w(VZ)k+gfc)wBFp^$Zhy?R7H0DoS%qp9LSL_ z)|%kRYJFC6nm*Fg$e*}!SS5C#f{%!u-Iimmaldm}r|yc@`xSX=lM%%}hOoK*r+M73 zQ(Q0aVJ+Ymt#6w4%!X+6eHEq0+YqKKKFw=yIwkSIcF2g38@1S=;?;!pN+St@{90%7 zuy*%|);rEH&PyU^wPbZl9_0ti9^>eR93im3a?B((!; z{pjam&6_(~|GdILm_N2=Rm-RFfm?Nsbn)~fV+A_V=`~d^?rz+l7qQl5U!GPFuLher z(#2YvU5Z)v44A49Dr_Lc`SxtX=l#5A*(8p1@w{YN*Rt05LsRsEe;H>o2`*-qbflCh zQ@1Whx>zg3Qr4PuVv6pz$Utn{-;K>0wUvL3rCiuR3whvPgkqiNc4wK(ujT!RCQ7F` ztOT>(FCC>1KJw0nl*m#KY{rh9%P#`ms!BW%@oIvvwe4#<5Bg!`v&?M{V(OaQ!ncZv zW3BI5nRR-_DBX18olQo(n$({?$REQyW}G4Iqwwsl$LcWamg^Jr%9XzokBDO(S?00t z_{qi&vSjE42r?yu$EI~<-66M%B9>K;xt;COws%T`uOy8wqE$jt4nfTg| zy;#V3LYX@n(#77zUZ>UI>PP90(WvFzqJFD1b6>oKJon%XpF7i{9vKAA2eY>2v;9Z3yU9_BN z`4q(x(VngBn9S>S*)LfitcBK_i- z>@L>ARf68sJ5Yx$`&>nI+;8GY7gsV|;mD_+(vnSXbCe%0a!gu3uokX%wA=nso%Q}) zQ~df>mm^(V&vB)u*pH^6tcTYL-e>a}j;k=zMShAhQZL71$^?k487&-r1N2_d`=IY8 zlAE%D;s#&3?WVMzV=eS>=qsVxUMx#7n<#Ll1xLE*g`pQkS?rtI*dg;1p8M)6$@jrp z=&8{QVD1Ijj(&|r`5_%R(nW6)y+Im5pL*<2!*~4Ph@X-Vhqch-RFr)mv$Gs)gGAX2 zy*biFKN`JS^2pxSVCRZ`5X zrLKBk%{sP&INUah<9-Qubhsm%%DU;`pUFvM#9^&+_IUMQY4jXsKl<9WlC-p!; zeoI7V`zm)j#KYiRYc?a-@rA3%Jv#-9+#mHSV*Z|3IDR-Q^$OU*TZ-`ZYRo_g9nKSi6} z2z`>iwM9yb;ySCT_&h;qqq-GhMRUfP-@k98SNlgsASH^FEznfVD1Di}$}Pn9Oj~Hq zxT(GV@uR1`WXT!k>#y4A3GY4aNJ&vnW}eKSolZ`E)oT!Wzg?d!?j14psH4z4nXhMKl|=2cN% z?4P|ZQ_Qw;-StW*jJ{gq3=re^uX+bxRF>L-=r;SOnLT5=>sK!th>d~Wc%ji1wGTr^ zOH!fik>97A|N5)DF0LDh)3K_EDcD9W>r;v$EtI78lpyoB4B>i=W*}BHddn@BmzwU@ z=*o~5qEm{tGPlnku20ns#HwxIwBGY(YR^ZGXV-qsG4ET|UH?P*p%7iBd?#~wxp3N_ z8;DH#GmG1mR;n*PHf2Z)B^mJaBI}y3xBh9Hfmj!^f+t+dpuTxOm?14hzpZ|govF~9 z&Jzv9Z>NuTeE%iwar+4p!nN*0*1_Cce@fqjpO1LUsyFMcKT7>JJo2c&*16C%EhKOP z!&;XXzF-eq_tqo+Kg7Jj-uzO<9cq&<{TXsc*%RAlthaefZ++krJ`STh~(&TYNm#)_$|p zyf=p$Qi-%aLAtV3_4}_kt*d>&lu%#-Lt2PHN@N-SnHO;W$`x&De5zC;t$(uT_`0X& zm)^P;NrIFVWx|jH0eiysY1y91Jg6NaZ9J%b>68>DF4Ix9ct@LhCncO+v$t{-$``KB zB8@{ysHesMwB&ZJ&T2>oyU89u+UVVMx`;qZ6h~HKr75WNN-cMv3G8NYCr8<`;re~j z(e~MUIdb@g>ot#h+E0&qEB>b?vo86V_9tJ`PLW<=3Gzcqiqd?T7n}Jums)sl17i+4 z(&jTt(sNUggDc_s%+xv9+B-=d{w|j(Tkt?hDnuY9%BnJcqv`0}om$pX6O1|NNSlM$ z4q2*{TTR&Ve}V({dKG14aU5xu8tIaiaQx3+jmY^^ec!J}^1*YR49nn1voeT4N_6{r z>5VBQI7G|wWV~Uo9BEb*B}7Ve;^jJ)J;|Swt08Wx=o0PdOsmWST5*srSyadWR-FA~ z$FXN_f3#6`?`T*;Ym_5xjY3Kkd;X{{J6HU;wzgCi=Gi9JaqdGKoxSk1lNEKOttH5h z?pUt%Wp{@?)}j-1!?vgQ)s_y^9MitE(TCHjhLq@yk#*hGQeSQ)--;Z~w)LCk=tnC~ z;>dUxx7adXYRe{X;FO|8mmFNB=dUBaKzK9cJH019VwBY*rBGXT$q%6CD%BK z2dz<#v^5I((SERbaTe-3Px~F)P-;2yK;D!w>qcMJdDLSqVwx_E2eur0L{YW`c2kWt z>JzO|IJQVvmTKM305&URn7_MHMbbn>ASJqK$TyyO(^|Wk)>_n29DiA=Ut7PK-Y3k| z-qRX|^8o3hR?>=Nf2ZDgHp_H2e^+VNA_6HX%HtU-yZNNG8d0Yd!}*L7;#^Ub`nUW| zn@e2NylKTjTY`2F?Fzk#l(bS^AO77`@Xlb#CZZ%VB41!;_OU-b^qbO@p|wN_(XJ@U z#DRMQ8f3VtO`1A^p*>&w#I0Uuvh79wKifWN(FxP2ge+?7$>XFI2PKhLg9=5w)e-g` zYPrt+8LmYrAzE!Z>-#z{Ioji@wmD8-KTs-MA1O+&$5!p($FA4Hi7M{UxsR@kY{FCqIrC>45Y z6#G#DR4LPs|m&wM#Wq?NvH0ltkWtgf|;2HcZaMvkr4paX)~P z$h#tkeH`0Ty@ly`#d7MQ4r3fkhqThe2YcA#-_3ArG`G}$mrmVz!8&;Oa~U?(H$k0q zst$90JuEW$x7I&=cef)NEfGZr?PIKcrgm!K^(BnHN?+;GG9V?gS3@guk-SYkwXMIz z<3BSvT|;T*EMHT-dN*11)%r*Xoacz9bLve@gqClomfTgsK(MrSppN0lD#{fX7vXks zl^T_?sf56}f@pdr#y(E$^=@J6TOqY~&1t=hba9;M44}mb5iuzv@A)f=(-@dx4AOVM zxGSbR`pLb;sU4xbt2v2diRt}7^S9Zp^dIEOBBfLWOGDr|6T*>(K(B^ge$U#G#hqBp zKjb`PNR_S`!@N~T9W_k%po_s5 zmA)kPyd-PJUM$AZh|idCNG)+;pd(>sE4|)h%9;$GrR=@l{}ayaq7nZTBO}oNL^Per z zTqMspwr}B7$AJN@DDQddc}co2ifB4Xoz{lkytR-I-gcj3|Df)A#QHdzG!4_;Pa8Yo zGw*t_Sv3;*m2B~9gA0C+vJJxYJ$F6r*l%+02IMcxHr4LVz0`W_O+C9~cJ(lQ?JG|^ z_5z~mOIF{8>V_JfwdwoEu*#Ri9DnkL=^k{Rgl$4JW$W?juO44GNt>1sA@wfuLrQe# zHLEsj>pFy&salC4cWe`)DHdnmAQn?TkLgZ9+7?8rp0KyI;8pfB1rq zrC@i5QXyJVj^~eHM;rIx+X`LRuoj|mrYVYBr5dbTb$8L!{f5-?^JRP;=F(w$IAt+k zy0V6&KyJ$S>@f5ysX`6bu%^4%>M0{o6A?{cjFh&qg|ABr+cZ~66S1d5E>v;kE*7Sr zIcM+~?&Z#MtbEU1@>Y~I5l7AQa&^bPd|~=S+D%e6-8p9U!?R+%T!RQn6HznTruaK1 zzX{cSUmJ+u$pzV(UrogN+P}1^E`=Pv*F*I)be6HZeL;tEKU5!2S^Z?GmV9wx6)T2_ zKcD-k$Q^4Tnk@AZhw9(2uqddI4g+^Y@2FG6;eI+)SILgi?Na00ri>}g`3^RkeRy2o zkz0i7ZZxA1{q|l7N8qYZeefFtVI8?y?Y?cW_@`nE&ExI~@n9k4)~0!mlDw^z&Ea=6 zRPUa8lB&0#t(w~n6Sj;l9BW}O$Os-2rFI?~F1(KIR#9F=BX311Im26x{8~~pS!`h_ zFQPvlIxR9x2-U50eogU-&-0i(cnBBm$FN!7%R4Ie3)TOomLq!cv-4s}NT|M??6IOW zd2`kj_HnFOJgb0;+!yUVF1oD@)nA_Xv@g06DYDKA)$3g~5c8X@HSr0pg>_9fhTIX| zFKME9KPgnd|G+?OneAihQ!=-xu{4Y!cSNr%9!2l%h3aEd^XdOSFsn}GF4g#M-*IgD z+$*9;@lgHN2TuwH`k(AKo=z5d>V@iSseP1dGPYs8FT=ce=*MvkOAei%Dq80Z)hE%) zfRt!Qf2f1WZ$}34r%?xn+!2lZ=yvJYVbi|xjm6V1MHsda(by(M$$4K~#eFr)8f+=Q7HU91L7)f_gcAT4JMZa+M zQNOIhyNrz?ca$AxFl9V>=*k`*H;YdT_NzFH5RF!X?xSKdv4p41#0+}R6fF)~XPm+G z5{=VOjeD1gKV30evOXxgyw?6K>&_CMo#Ix{It;m^>}XL*svCjq>f#*Y=Jf$8N`+{& z+KLi(wHaIFnpsTRy@aFeh{lzHG9lzB&6=<6&($UYtW0tZt8rRab6b8pW=6!EhqQhq zlw_Cxn#0%3pf?l%fw`#=O}AtY5B9QDCH`e#6A2+@MwGHsmZI#GAGXZbdKNTG*$}4} zDU>Q<`E2fXWIN2iR4-uz1S znSV6tIq$~ieEe!L`l{YncRSXS^KxEvDy(Op$=agC4pPQN%%zBw=o`g=JnSk-_3~3F zL%JxH%)@2eD|Pti658}R-Poj(B2}tQ|9IGuE@on+7xF4!R&Tn@3Yf9Cx0It1GcF<} zMLG5{NgeyRgsEN8fedS5zD5}_t@v7X*3pcnw^fHqQelo)%*06fWDX5i>wXz`@X*`{ zDMzDHdtz#v{toxF%RGwxNK%KARE3KSlz5<2$WKuYis7njorcNNXGO3vuQR05E%}hv z3E+Xb8x>`1rq1fBo2!#YoF2`v7UqPM5r@u~S7Xj+Fiq<{PRav`Ssf+bO6lJpO}Trx zn@0Z{&#)Heg!~WU&~TooN4a{g^CAqXQVdNr`e)SZ45|N(HeqH&%2ar{ATQK1o5}ar zIEJ+_x$KJe@oo`Q-(C|W1ZH(aH2Lkl7jjXkgtjc(a7il6t&N!xDGOAIar|KB z70EGq<#u3>Mnu#5A4$Xc!(X!l>c>Seq(z#M+Hynlu}3Jj_V6yA^3KEbc=8|#f%zIG zw9@$RSG;(mlgU%Iq|WnHy2d=mT9|!NQ3gaF|QNKRQpG>?M-6dh@PoeMu_J9Emw0=>?Z- zr9?!$A0OprmU2zvn+DiE8uM+X#LxcYxE@?j$~B33AZ3ILy{g-5%^aR#x*x+@v~s5Q zn~_CQMr`YtWSSQ0ZfbjIf@H7IGSE)goOZ@RJC@)Tre*_bn+koIAmx-LU&IV22!M!E z|1y1T)ZA3%kBk_+C(vB!8D+{QKN``BGNj8p)B6P@4j%HEz_1odC1*K5Q;!?~IQwM9XDW`v=lzAA@ zs0)fRIE-npx>q!{niwhVwz1`MJNlitq-{>@8jxeb1gWoZ#XI_@{V?OT{Yjt>jaq9YhN!+mh97Zu244 zs%Z!2(Wx!G^MR`Yt`dq8Q_#XUvwO+5ps`YxW?Y@+wRTMY>1vUfOUZl7jFfyh^p?n>#&M~@XfS;|j6rX(8?=FO9{TBU64xSODsr|uJsm55@5>sRNs zS9KBdYd==6Y|3K3>j>5VP)yo*mr3mC=urJ8opRAGoc-@Cqgt5c>ZIGB2HaZz=ts9xeyns%>{7!n>WyJFK>v->^R^r~b-GxaHy<-rvOd@g*oTzut#LK6 zw_j~>&RyjX{A-zq`-JIEdglWrdD*;_`RMadJ^YZtBlAcPQKhh-_bHG9vAeHDEIhJWMR}2jj2IPnmS4)9Ra`H|*!DTz=A@)h{Rf?YBKq3L zI_AHt(z_6;uR9Lyl9iv_RGP0JI7V7I(TXA^in@0V5Qh_8MA3h4^8&B@%x%ks>CY%K z3-7#WM{oY$-9#?$&VrqN#-IOF*EkV2r`=7UByu~(}M_(f76OzM~Bbm+o2M3V>)j19;esuXvl8CoG9zSc3eJlA=6a zRZKjKy2$@r@n*;!+k|M!hPW|^IkmPSZpj%~tTppzo{f;BQCoA^;=>@`toJ6hv=KfPb8DJqlTmG*d|JAkYSQGC@z?<^co}0T9gE}lA^pTCGaX|3yb(^ zDnsswkY{ay**EyZvu#9!pj9f)B1EH=pqsdFM|hjWaN#r&@XG0qs=ez0l93??CMIjBT&HvulO`K6~sc7}lCL)@i zcYa@;n+lH;8NMt^#+3!_E}~O!$;4B-C9~2k8Qq4Z-^ATb_qs7?`eRx*K zfn>T3OOMURm=am4NJ1Rh*oXh>pOlOxh`^YA`eMD?5V3n%BYyQ!tcoQlJ5r)=Gs;&I zn}+7*nKIQgZbsAPMT8tDGyY*C5qPKwuY5`V762prkrJJeO$+4laj%l|t{fxza9B%@ z-kE%B5?|aTuNF2^{uTheKJ*6Z3+Zl?`0u0&+Q3nx7)pY4kssX~d~PV(p03IZq!eP< zSJ+zYh1AFakrp|Cy@*CyY`yu*iY;^-UW9JLkvpPM$5LmD4iEi9cDnz3mr{3y|8+5Bbh;H?9PTXGrhD<3AI34Pg}Y)IF?;8j2OXl%q--k=<2lj%@!}qFx^7)IK`8V?0krw*xh^7;-fg_Sfzv&@L{COm; zA1IaF^8Q1+2ehA>QGBo2LAtd>Es>?#d8er9SLczU?zUJJwGVq2wTI$l#%@>3)ax(K zcB`(g?LE$M`*N5*IG?9|Wq4`FL^}8JUq)KFt%jo!-RdXpFtoki=RU0YpV|D&gL&$w zJVPBd3bxYo_4lyf35a#He;1}7D3lsUmLB^>Ik1NvSMxM&AW2{~NLO$es|e^HZe3gQf96escVkfhprzT{J&Wn(nflrSU+1h*p#qKMRVg z4dXN?y%R^=&1rpw{4hd{qIXVC<~Jtz3w1+jMzWjJ`U?3Wnj(b0_Yo^!%;x29%~Pot z&1qwR{4j2fR_7ka`S`#VB3t9D#+aMa#vJ(}n%=<*+0Ngv{kQYOEBgRZ7`j%gxJIh%8~l(L|=|2qn>3)+EREqRuMYK42mSYLtS|cU$UPElm$fTR$WM4zC(k%|w zBJD|!Hl=TVTGwW=Pm7C$>6?u)Pq$E?FO} zCF}0vp~rawtp)`eUNzQ_beo8C8|@19)#pCq#jn{s`0+d=_B=gK7i|fm6=mnv$$VM7 zznH$Fv}D_nA6h$lLDP|k_A^P9-BW*Q6tB=+ht#&G6qOs!apcMyK z7F+=kO<#;0nXIPJYS4LOX=D9JUu%&cu0G`T{VvE78pmnPqnj~YA(0=VNw0bySNGFu z(2&LhwHo>1DoU|9-}|uV|IFqG@61ziP9Q%-(>Yv=?doxJe=%iFbrm%n`Jp#JJNlkg zv;sa6qV=PZlHEmZm%XKYPpWDj<03@eZbQ`>3Dw!g*`fLuiciB@=m#lEx!R?Yn}rP) zJA$^WSmK?lyjD9ZR3Ag%3?n7_%Jh?mX;xH(P`?e8JpGd=nHVuARDVpdm58R-PhIMm zb~KL=>@Fg3&p?r9_9~{v)be2uMoK);Qpcl4q2k=#l~T(Qfs`nJ$r^vn);mJvEr*Gh$4^P@Cm!WKrlO9bRg=g3 zs#<^lkG1{87eb)Tz*!{E+WIwu{GJn{NuFbp_lo+8ycOl|Ar<$3Bt%g{AT6{w$eW_{ zw(ENvP&?-5N^M8F*N0<(Z6Z&mgk^suA);Mn1ooBOyI*%dG2Vg@*NF#m#~#IAptJDF z-u~~`^b?oz%REr8P(rez0UV2lKbj(?$0Lw4&z1keap2sy?&a5+-9ZbC&mmCn5BX|vQ{^S_Z@Mc|2C6^Q2vO(MLJheuZLr9axN}Bon`DI7 z!cFR%p@YSX*aaHaLNsPup%ePg1Js175u)j|6&jXgymY{_+W%i3NQut+TnDN>8bpYD zOa$F4mAP=C8qgIYu7gEox-m!6IqpN(q4yVm2DexY*=~ zn&{n63|P2A!xGG2gS_cX|IB%{^48vBf&VfMYoSy!Vp}&?HnB@f5nMJ-Q*%DEOi!Wg z#*`@=a~5HaBzjloOa>PJpuKo|dya&_3`B^g3{A>AwQK&a;zs@j5(4`N(Td{U?x|XG zaCb4j#aa!yuc_c}4M>bll@O(+?>W14WT&402FG0#)b*rToWuh5-YlylR-o4Jpxg!qxhTCG-~L zwc&jY9?mo#gm9+iB#(_7>D(AKOka7-$Xb_lrLS0b;wZh|yV7WfGp!wnzB!|p^KkCb zx@*oqluNH$g-&8$+3)=G+5;MvoHccIhEc}70ph0(DbY98?Vs|kL%NH;Yu6a#k&-s% z)Vt2K-d%eI zrgs;oX8vtxdrI28!&;xF97{0=#OnP@-zOeNGoI#S5B3oWvzKdFGB)?Fl+_1f^%p{xMQ7T}3w0eRnr~aFVXb8w6H`upjn#Aa`Y+T||?o z|9t=-?H3_FO3s|2#~zZ!%lMk~~F6r}Wqr zr@z{I+lG|ri;+wN`Ak!U*xO{0X3OH5(kM7y|0m#^y&H^((pQG zSD61~pRPCkX5_}*|DlM%7KO+k!R&%pTV1`q`1j{16jb zn9AIqAch@ZsbLB7z;#|xvbYR3mD)E!lq;C1ZHd0a)~o+|06k*ds_9Mt{a-nz!okB` zrt23v8@X}4OAa>W)+UHmhgQ>@K>w5EubGF<{$BqgOpzna$yNXTPqAum2ANbsO;iL!W<9IWLcsn-14@^tPbyCbcykRQFM z^L&tIwA_taj8c7_B4H=;8RI+{+J+o{7luW^f~C+Xr?2n z#&kXC$zz+$?SVovmRlno*9l`6wf@ zo%kzxe6>j7^>CSnB`6j40-dm2SQ5~Xq&oFJ6_Gx3(0fIVp}V`j3ryG7PY_!s%{F+X zBXFK0n!b>}aX;CWEJLNXQ#5>O0p~f+f6Cpq`Gt1o_IQyycz|Jj(p!tY@OO?x$0>Rj zpk(U10No}fXj{)s5bL6+Xjp>$kP@8;Z@Q9vm81$QF;%iYSPRkg%JHJI>_VtjWcT?? zTVJidb#lyJ$H}0OlsxrT9bw!&_8#F9ogKAp~ zU!S5^-u%;slqh>r!Sc+bs6~wVHA_PeDPxOrR-XaU`lm@hZAghSe=RP{wvkj<>ii|~ zK&g-t?I7<^KFbk}M8M0n5)bswy7wz#U3r!GrF^G$WFy3ILioH|t6|Chhb67IPf<>4 z@xvzb2+UTJb;!^_Shg?MuokvMMtGg~VtgaN1 z@}evoQ{E~(zfPABm@^g8bWYu_D9cr`i71>rKtf;!R76t@8b< z<};n8oPO-8&fUWv_n8XykNM zjT+X%@yA}E445WAmTgjXv9S9(4JAPdG50ThM_8* zyELqY?T`_fi&$C2p0c9n%jFvO;*)U}>zwXUdP3so|6~|w^I`=uP%C>5fq9U1G1(=-R&cdj>Plrzm)$o=HRE%zRvhpQTn5w zMppU5Q|pR6xvPpYjtv@?jQ>#HX^)?x53cson6>GY=r-e8QE_m6W8rF>tYNJ+$=RJ< zGfvZa*C+o$T*_NQJl)zr^q93y+TGEtb*9<#*V#%rzf6zTQ(}xa?}yASC9eEs7X^oH z(y)Z)yfe)*;69PQ9=Piz+6`|c_WhH(ex&a+Z#^vOyz&3|dh58VmhXN17#P?Iil|^< zfRYBBGXwjG9oT_|VvDWV2)20b?(V)eoIS9&-Q8Zh^IBm4)pK7(nd zX@BNmmUV%`KBF)f&53k0)`?j6`5OwuG8`t$fGMaumPDTZp~j;1v%I3b!vVuGq?d~) z9(WRBGHLC@MERiwMP!(x4O7ToX?9zSCDC^+y&H+*ra~fU@=BZE&E{H@iKF%9i&L#- z>eSJ;limH$JJqmu>1g_<_pJtE+s49TbkWTc;=%J^?c=|(`tADftY?OWYA0^Q>Z{5a zD^8a7jl|(n1%%g!S2j%97hPK`7ZaVeh{OQNWL%`h=^X+bgfY!+i3OmBDWO}QSl zeu(e1e!Ts)8l;a=93^s}zby1cE!)0>c%HptB3e$gA81#o9%Y00>`7kYc+=&Qmw_uM zdN|bQ7prmmJV);yS07vx$!D1V(z5=>D4}JIvf)Vz?wxQ?Wis7uyj!hyyN~GdWUdWQ zw(w*M&$3LW;>rir(X*o{-(sN+&-d_54o~su+so^_h$)rsr~@75*zhzHPb2aClD?69 zz9)Zp_^A5g;c6S6x8mt3uA;O*ANGWeoz_`wpEcix=fbmy@`MavlqIa&`LVv=wD_iNyFmJwCd(IBlrXp z^@b->t%xq&Aw-*WGETqo-q=UI-cvwWa@Q7LJqD^cMseh0Nn{z4j<6-Zo74-AZ3Rll zI=y!H)1nTK(_NyCJ*UbFSpHd1Sg>;q1xiP>(=-i> za#yq^r{eUj8NXT)UH`S8R_Dq%Ju==vWYf!vDrc*UzD+u*u|fXY3fjwFTJ+6|D;e5+ zid2V{5Thu*kA1|%^mhtp5w}Hr6F}K*$ZV7@Ctaha#eY>i?flwZo z6g{23s1YBE3Y3oM&9P;*imfK-`MMg2T6Zf5Q~%9Vh6E`xpoj zT2b5>P*rSvSw}@L1JRG7%4*BHkv})oK-B2lLUevHN$q{>y^7LN_vq2?+T67h^!?in zPyayu#^SEHrDp1-t0*1O4;w1&|T}FFhRe& z*FfxjT3NWH1c-Cbi>T=DAo_X4=`2Qc`o(sOGw185X_w z5xweH5#KHyH%?g6J!JG)u_Tjeqt6KO-cnFqG9n|(y~ABQ*m;6}YuRTjYU1YQrUk91 zK0ji}SXipBsPX1+b(?RD1*IbbOQI96&n<+hZ)PYj$FAS?r0OS=iI6P85L_RKv*kNz$;Td9jI$AGe0=(X{BtyQU3 z)MVUBcdbg(33}ujLq_VOp5jfr>1yJb84RT(0!yOXncG{7L0Se;{B~Y;sw1^k>;!%6 zjL%j?pB+_J>+*cO{?~kCHQ0Wts`yyRSG@7hl8E~c+#z8}^pfW)ZxOe}C&5;~I9IGEInPT-m%CvkQaeCvMpRCnlxmGPWPM`hEIFnf)c2b>lcC0#a zTm+Br9IVxE8K*lu_+&**9xrLJ^(i<)8YS4Gh$fG0-8S2u6~3137e;f; zg)NHxM84?O8lp&CNm08(W@(h5?pP;^TDET>3M}2M`o90hupWqzM~P=(1);P&Xl~}p zrFtM5M={;k{Rb3YJ%gK-dt`FAyVt! zRMk6;8A?Y4mP98L&b`Do&jM<*vx$=RK{Q$kT5H?171@rKVzyo>4DAxu31_g$)H^9q zOh~LG9yRv2q3uIW(5}#(xbmIEanCpE;@45{)bCP%&O@r$*IyY(YDSXtdho zCte;Q9^Y?h@rn0lxK3c5uq3h!m;FTXcK)J6-7_{^i%=7^^Ymu_q84KPpseE2!YnFE zM+BBcob7&n#M}uR)LlhONUJlVaTTT8PW6ThwbgT5$xwe4*KMp5u5i@4e|w45i>rw) z_3}uoGp@DhOVCT{rxa1{Ungoi{g>RrZIkckWEurq{+mRQ(y`s2#z(dR|v`g~HPD8f`Wks7WI zb?#L~qw8g*T@j*j-$pO7b)K9!V4$nWcD9bdy%Xw=dqZlgWEWv>YZd1Uc98b9s0r4I zd^l?dHNrDOTp4{$Md^r;_qEMeG-2O1go%^u9Ho6NqH!NhC&G_g@eLm1)q*8oskn3B zdLvXD*(6qXJC|z3T`|39+5KO(yMLj?S84>m^(9zyFBYeJXG)R0mnq&{3v-Rr;~yHH z%+U3@_{(LbY)`*8lh#`FePl$*BhGBF{*PKMth40%;7X0MiJ6&svHIz6A91#lhvfU< zs?RTnXdArZ^qZdzt&&HV6LX^i#hR&BhTaQ$7OR&jn$0&(|44opF*6_EWG=Q8wUwWh zFJGc)?@q+(C7PvJmHJj~$embyXwwv{tW}NR`mCI1Wf4BZkE3+Vg=n(7ZDZ6j1zL*! zi#{=wj_92wYG^s1$Lg2s7`|xcGVWs9Vyjqs@{0ve8WCORX$`Hz(^$P#bpvr*%g?LM zauW%f125)KQ;VG%t8=GRsU9A$t=f`RvAWma2IA7w{5&|?O)Nd&z)@dp1sPG;%ffnh z?;y(be8Ny)M5An)QF}+J=AbCCZ08Jy`XYMs)WwjIUwA z6JbPmJXT9fo)N3(&T1h3*<$5Inidd`>Bfjpi%@NTbgVwZIn^3?H&hF28>>GYk!pQ7 zs-_k||37rNfq3dVnssT^Po#Vu#85iwE+cx`TBz;(hKkCoGcc5n=qvqdX_Lmq>c@wq z?O1*k7ljtp7Bh;+CgMpmoajLM#*`A> z_`fkXRF?{^Y?y*`9!sJV$b9Enj=SAOt?`R(XfsfE8L@rCIopB}qr~yBLpHQa8R>+6 z+ZYc%!?!G88P)^Q zI4a4@@Gj3+{_8Kgl#i7VINEXE5Dy@}l*qcKhB(v3+k(<@?Bd)cOPvy@#ysjR#?Y7F zP&%S<1{2FWq#9drsDt>K=?Ozk5RF!XZr7~N&v);46W#YZaI{OPJC;QA+`GJ}7R$t* zS4S);9d$?RN-r)h+osMP(OkrO{3BU7M57I+$Y@k!%fJ2>;s36pWJOVTwDT03=;p*T zWZ$WVj|`O7THpG?TAoaCdb{tRtZ0L2RqIhn%=xQ|s2x&XT0c;CTy5}u6 zTyT-rDAXO-L^{8!y*Vh)llN+oLb3;dy5qV_cf)hNV9h$#QwwgP?|^`Bfc3yNk@n7G z?yC=Nn_2Cb&G@jDWwoW*1Lvz18 zMjw*$*^0Svhh#EU_a7$AnVr+*4sm#Kno9tY(bAr>?IXE-(eXW%M}d%^I&f zqQ#A^>f8k(5(4)Lh^CtsKQ^;FRg+Y&((MG@_18|$7^4qd@WqPd%3j|_WhX1vURQT? z3zs54qxW&`){!xK-Xg|X=%12^71p>T-&`O}Ex+fEigpkYvWzLC4<_#OIj3$o(?il~ zas@vv%gizQgZZ+CbW-GgL9LooRlf%|m%MO9U>nj)x1(E#Mg4lJHTQj&_Ji0~GUE2$ z5yJOcgk{4OAL(QQdlUPgUYd%zuf`{CW?5e~lg|2ZjNzyx&Rx~NnA4p7Y=%puguu~` z-ZI_J9Jq!}DpFb8+2SE`HRIa!)noKpUyO5He=W4{7`^}C|Mth*ow?ZEv7^Mt5iQJ* zdNS?%@-h0}i@y-h2=TSXFT@{otKhxNdrD8ya*>&(ys>KG?y>r!6{%K4%d(eQ4zpY{ zn~E1f7g)k+MT;6At5@8YVny`&W}#XWpIAL?i{Y1K%DJ5NSrj62_9(z#f3av`mt*y> zUp`q8owG;{E%(w`efT!R7rpoWjisK8k8tW*g?HZRt5q|_>CfkWvLd?v4W_+*AFE%x zXZY=F+h0)YpBbB2J-i2hlix#Iax+#h>5^h~pW~~|c8}9vlP$rProD65Dr%GYej;S8 zH%~2APJ6G$>YFR4SWzCLXQ*P=pW_2pV+rLUnr<)aTN9r>q}TU8d#BBF`-nq%ID@G_4rNXB zNsSSc+cY;DBiue-Q68enTPhdEtqU^?Khq=?$0%AKv`QvZ{i`+ktZ7BW^Sw1Bdxhf_ zOQQQYmu9dPN85=Whb}N2qliF{gTCnLUxi;e*54H5G&GuH3R(k{O|Jsa%F5qs8*P8Pw&JKe%0SsB)4muFUNmc8by#7>*@^OScG2x+vJ9n5d5VB2cgf2@d5ESyucNBLmAi@k{o6`5 z5#^zkpfltV;i7-lPwKdrK`L4@v^a>Sw_Y5Q)!p%RL`AZqXf4sIp|vBQfh_gk6~fhH zWU0|2qdY{@7mh|$Q76yv6BjpmOCu5Gq1C1@thT+NuJRq1ID=Lk97`w<(e%aJyKgM3 zJ$=N@=2fJzi=z)$AM(PTmb1}wLd4pr0vzWWjy_xy>Ey2VVdgchsTgLtAlVW`tiF*LhFGqw)rr#utL$IjOB~B`O!8#p+Wskt z&fy#{?{lCV>&NNM0n8=0C?a+zkKI@8_g#I=CHER4c4TQ(wHzVbNe1SU#}XpqoQhTD zgg8j|=rNZ(!V&R#T=A;I2(g~t9Kc-iyhB8X6?67!)VkU79+P|q*%}~1?|7iPFUj~o zTKzZI9~*^;vrqQz^&`YbLg0FiJ%~M<7O%B@{2i~QeV<~FpHpm8v2z0GbXfTlKd(_j zVJ9gj97Qo<+Knpq_&Mf6G{x?Ma`Ju@cWzH{XWH>9_V_uXDH5yv;Q>%=n=ho;_9TjJ zQ&d;6N7*S3oPN_rW;6!7Shxp8+}$bSjwvV)OQO>chtsSHMR*5MgctS2R-m1Q@`nLY zY*|I#tjtFzHMzWA?FJrGT?TjdXvBjeT@+?Ar? zbtxK-wME@2KCIZe6m*+>Qa4`eau;^%&;cVRoGu-8r#+SOhgmb=#$fvH>l)kgzb6@S z=XB|arWmAR=Ni#nOB%D>YaXT z2hkK)RqPxc8j1CW^X%czZSRBpjaX{Bbkx1&Xm`b6Y;8+pY^`YChnJ|iL3P^bZp3TT zr6am?A9v*uF}7Z(F}8BfYQgnRS%ve$Z1ke%AL)o5+R$Aw7+V+97+dWx`|-{cMSf8A zjC7X_(Ys5yD+XgLFpaTQ$+rdX89zgP8v52?o+)4?CR=nOf+lkW`m5HZd>jhL`v z=kFnUcNob|XEff3sK9Uf1PU>@qKY>Qu})YLy%e%%H_Jtl(Z?w@jToe2XOf~OFCTj< zJ<^$(bB2Cldm@U9mK|LMN=F2iM5ndBPJG1)Z;>zIviiP{my(0{l-G$*iD-&>Dt|bs zu_w#%aEc<&USHQ>W~Se-#5!R~^a4%i$>w1c8O=nIQHp>nc3v=QLg!4%A8u`tz2h0H z7$92bDQ7TD)1@Nn)Xg5u7#DDI58C`PN;Z+6IttB+fWtrSbmMX^*m*;4H6X!80Mdn}cr z0LmYBbng{S)E^YDJx=jjiYO>{b~NfP*Ico7V4Wx?e34?p6tz(7>}b>w(Zo+orgL42 zJD;GqGwO~AEGdmo%?&>FE8?`HNiU3-nnBg-eS0?Xwc=W!GK7gQHYRdExUMzjjEeZyx3S(vOb7L zD?xsHL=QIp{5f?*%T5CA64nW4FuiVEyCUD+tEyP)U01TAs0rE?VxG0H!1Fnk5XUxO zR8cx2WGi|$e@UKj=Bql=)kRtj5RF!wSQe#o^NM{psRLcD2D2u8oxnPwMWtBklgd0t zYJgb!x`?!@p(beODQf9kgJ;iBNTigFHyA?c>m4HGRc*glW8UHWE!Dh9msV#)<0?w= z+I}tg*k_Z}fj8c(xNc*eaD}7zc~M{9u}l?l(e;E4rQ=#l%rm&Le)4)4Uos-EcwZue zP2cpq)GMP3%@Z)oD z2Z%8XOBzhTbYBg1N8gUV0QRmq-@PY?C{k#+!P!pt$PkSlpvg4rO)nnqyH|ZZy*NYZ zh(<4yz9u+-FfY=un0lk|K!XXG?$;t3Jz2W{(IbeTAXf1~Viluw)E#|olPP>-L*AkG zPgUQtQu2@yjUG9D<#=#izJJjKHE={Oj?z(g^!n+$eXG3rjtxEuNyNZLUmel7voM*6 zBg_qsa2MhT;~od^dEtJCzUI-=owp?B@>yaoqjc0=Mi4ui%_4U6cw$GRbVTF6jac3b zB2@q13~by3(z%~vXJF%=iq?Smw>F=cno3!^)fBQY?e0?g8b0q{sPdy} ztX?^dWzlF+FTs3|skxW>B;p!{9)OH+TAE8#>C;Sv{5{WLS)_Xah(_6T$0RCjf0?PH z#mk%54VFc^2Y~2)Lux5WV`KHM^NbkFbKkuDT%jhSQlZ1rt$0N5oKjo4MjVaQ*#_d# z06%f|A8+x#YyfLHIaK*hvDDRmsn**8HI?!d(~0p-waQx6J91O~*{qXrDQsaV9djX? zc>4SHTR!NcM9S+!7L<h zXDn?X5;GJR*}s+$Pm(?`l#X>;^V6z)UKy(o*l9$Uih30i9h@tOzH{F&Oex@4Lpecw zFV|ryQY+9~dSRW^LK!=WzLhR9)EDI;+GKj@*o%$m*H3)eAIDH%L|?yEL;3e&tp2{Q zp;gu0^i`|Snqu|g92R^#0beP=l4zb6E+oPeAFI#&y!fHkR%PJ6SbgE}6l<^CA&M*A zul-Rl#hREHqFl}vr@wbHWGpza#-{FSByySya+Hp`%ZQ%=YgoyZ9mLUr2`q7KsPg$- zte!n0#fs>Ga}-5$iqqY58#0vg<+$ZL7eD4Lx8S=ESSKurUYgpLUo_5NLfx04AxGVR z*5%5fqH+2WVi-30!IgObI9+>VMEf=znqZsstfc4`S(Br5)Lllri{HUc^r%JiBMTqa z-l`O!a`RFQ648OTgO%huar(z)dESF#3fe9#$zTYXgS-!JS5FP-C!Khq?lNN7 z&vUHOp5kIfd`0QRYuU;W#YQZPgtMQlh^D)*U%dH~F216{_%zmJ`imFX3W%l`lxYO6 zUlJfPmaWS$1?@Sm48##Gyq9JCT3XDjDN|jU0e+iO{~ctW%!ZZOf*g@&#-T?PS^^>rkb#jbz)|bJkLd{2O_W} z+Icm~qc*$nQ>}EhjZ_b81ss+1p5?}i>WGvn>f15xB?OLkoHr)Z@GS1U%c>gU^p7JJ zoNK5Fj$>MJZjWca9ovc7lWsDUjtDG?VvxD~)d#Lj9P3?%qb7((D?wixZ~ahRaVn2^ z-N{!%p!GpJM*eO=cV6UksPKM}&4RWMH9@;V5v=F2toNn9V#>H745cFiOQL%dd;QdG zhr5cXB_|kaf@rkbG)n%?BN9t`iH<=Zr1b-J$CBv%5*JrK<82*b{+!K*($Ti#YDZcf z_h-kZj}W7-ce9{$MB|!BZ$NZgpe}P5ApUuoRayrTjq5JG%Nf~3bZMGJG!N{|a1B56 zDpXn9B39o^uRGu>O1Jy}F2o&9HV~of|FNNT)E!R{=%vD_IhN4=BZX41h>Fq?jXny! z89hQrG2J&QL?lU_#ilU*4o!5uCWG|e!QEK7e+$glp6jxP% z378%cB9`8m`|J^M2Wt^`5X(XY%1+}Ba(}8vXW|Z`CYX!j!|C-)V*>IK!~|?bOhBwH z=E7DtnMRe%!zBAu6D>&l4jKQ^m&mL85c?0J%d5ET$hiA6uD~LI8g_r{ry;tl!GL(n?Pu`M4 zGAlf_j(BkTvk|XV>^w4*hiIDT?JlrYRmLUuB<29c{uMhv4dvmeq`Mi>Raj19CrsV! zZSdg~J0A|^A)0PM9D8HS=H(;a5!Zks)ry^ShiH^d-fPk2>M`OP%<5f$Q#4$$^ZF1? zyaVMA=PqBJ!|EvF8jL3cuVS@-@GME!S=zDh$Gy(wt9X`b8+=#CWFb5-X@4Z|G{K>(>zQR zuTg+M6dNp6!)-0(UHk zrk7is?yJ6Ds%`k7NC|x**#>93vzUGPsrt|Lc?qaH%0Sul-K8b>RsD==Yu`B1 zV7DpuQ!eZe91FCM+Lue+LG$ApafD^*@@nwM&b#+pqkbSBa_y}i0(FcuUx~h(;?xF)zpE>ehuJqI=H*(nv%!S|U1= z$@|t8R?J82j;tctU2Gq;cC>Q#s=_S95za;&VYII}x6z^!PoHdi`025UoyfMM4M$so zXnGeXPcl169N`n^J{t_W^i>Vzp`ACGR?-@Ef_TU;X^q0Q2<0J~zD(LcW&4RE91+!) z;d+PiaJ`~^?dWj6-1C$A;B%1VC!#z=(-#q{muDYnJ$Kbs8jQwtF9YS_x@$5$uAsBM z#6ylJ9y0m{xP~LzWLj}Nm-!2^CL@=mafH)X1C)pUgUPgd)F$(1;vw()lEy<$_w-R7 zqG>a6W=>T*H_8~{cIFwDE7zmYs^a?${?!KJUtx;eqJK)FJWV_WdF_e$3`LIP{#uY46fR5=2^N2fIWykOWdfM zokZ5@H`IWgR<-kinZZS#$LskW9$KpuA0FJI#8kcEmq*sodUUX2nyPO)@rX_b!*{e3 zL3N+18+)}>F<0q#1A}#ksd~!C{~{D~AyM*tU2$khHFdjhT(IgrRd1I0u_Oa!((Oj5}Z}lNc=q-RQ^gMRe2~`kG`;(=@tUP& z!@;6tu1S(sh$gL)?DeA?RZlzdnoAvQxuahiJ(#WuYDhhp^rr{w9;w2|Y$__Q`0Qa= z7NV*Dlk8)fUYhb9&RF(n5!hQddNBQsctleVCfUaVt%KR3dB%2OYO87GjroyY7HXnS z8l5!fXS{ykv@t)H4G-WaMpYJ%9+y|KEJO!%ic9)gWU5~Jyn*O=sx|YC9x9$Uej>fV zkLUr1CMJEYI8}dl-9XfuR-Ahm)73!-Dhn(NH96*ZLj3fds@MN%e4(O9gNy9eTrLt{ zW)@f$q7zG>6Ax-m)n7Xr-%+QM4Yl!8_S_M6@**+wN z39Uwcfn`YuD2dqW&Ic2ZevB4Zrj9bSO8-g-eis5uBE;xd>d}cg#mo%8l2+7K+}>-8 zTQv(lP;jdLPZOgDJNlOpOF}a7&l8;lrl1YR`jLkmxLJ*^6ebSde6LdbaC=W-E=1EC z*xMX!7V>2Jye=yt(AMJjP3Z2@hqpH8TEoPy*|j9wj+Rl_5(CQ z+eNqHFI8YMrV(Pd*JT@)g__{^P00G3a^|Iu)DbD$i>O!@qR|G^2}_MmymiOBYE)kj z6>Tk|(axv&49xB`U|FaMu0+I6I8~B=DqKZ$o3N5$S%}8<%48~kFPzsV-zOvaKDaI+ z8rMXViF^i&;WG>-p8?B4P0*L1NJG!rtkHNEQFEMyV_AsCwLQ)EVM*lsWFy}Py$SSv zaBZiPiH+B6Ey!nZC7*%HP4|7UTv@B+eGApXRr82}$3i6;h`^HQOn>bGwbF0j2eqO) zrTdKNsnMIuzQa|+X9yynf%+ibPsDQ3*D{$L-2#M{zl&)0tT)siS<%|j zS1JqnviZeMt6Du7ftCp8Kiz^j;lt8pfR95mM7j)+O?MP0mgcuVu25Is@D)-nK;vvC zFQdRnKI7&_Tb#42YI-;dkzoRnKNL&%wu) z=D9R$t%pjnmgB03ibpGnyO&jwwbo?4?TSa%jy1bgzF&Q^-a?Qqkq}CqNtR4KV#KJz zt<09u+r{FVll6!JkF2c&x>cSKI9b0tO-54>E^y|lyo8AOltFke?w|C4zAZXYeP~5_ zay_bd7|Tws9U>Z-ms%E9YM-Pno2>6!_0Wp)5KS*G9_zt(E<2}YVi^)@cbJ@%Tz!f@ zDe{38J1@;B-cY_A8(Lo}Ve&Tb%46J%9Aa_v4G?1D^mw? z|JXc6{Tyr`S11qBCe!o<&LWh??q?diG~&2@exN+G!Q_{;AFJM{v8yUeEi_)aeSV-k z32pkQmr~uwR}pQGR1!GvP@Zf>2REB!bEG*q{Y`T-&O4NcXj*IAOtRhS9wP?Qti=?R zhb5Uzl}M`&WEuR(GN5#{28gB;FRJ+^s(D_TwOB)xhZ@rRyVSaGsCC1rb+Hvu9-`^a zPsnk#!q4`?Q=iAMr%)cYH0@Z9^$>NIpHq8_3<=U`fK>+3^tQ;m9qRF7HH4$hQJNnp z4@V4|)hDs_VM zlE*|PvvZ81$Q68dAri@jNGp`ICM7g8$81+>8`hoJ$ zqEd|INDuC@{+v2<^-&(8DH`5xEPGC4_h!ga3yrw+br9v@%0Mpy(W=I2>^`Eg zE3ICzh9jEZvWT2yc|>#Yq)Q7k&K#77D;&L3q?KZ&$TIXK%YgF^9} zE78sSm9!dU%rr%xw)cUwa?1616V`X{c|s)7O9+^PEs7=47uifvRjyI|;5m|LwQX;q9OahMBjt>gZti|N0(0TWkP&olK!3*YU;i3^ztxPt zht=0ZjNi>`%u|Nhsw>8C^ST)N_t&3a2u%5v`d0h(e@3ofCH)5cmVvp9vW;B7Wc@FM zoNHMc;$ZD<9>2={f61T|{`6dcPX6Br%mo^1{~Lk1pcVcP1m=R){l5@@`ar8Zt4{e} zExPRgKwvJCK{Zb6!T*gIgSkjU%9+;B{}%#sQ7fb&ej)!y501fH)Y88YY1;iSgq+K$ z@mp>6R(0e5?hoqo^jv_ZG5jAHW9*|HbAg7+|3+XgXsiDNfw`ci|1ZR!UV~i5csBn0 zzel@0Wtjrw>OY8V*GBRzPestK$|Y5*Ii;q}I~pN>=1N_$l>Wbsp7GylNfd*gG?GvI z86V{R(nH0RV2=f9xmGmalq{FD?s^QLTsJTwYH1D&mOH5buX4j?x+G#rv`bwb#oec~ zgfrb$Nvp?+bJJuD7^o$0h>lPD9THPeBdrQY@+;9L&GY&^RWXJ7hH|A@pER5Gr+&LK z1@H+!-UiXXg8CyZm(i1muubomCL`%deUh>HVr4$?x+&;$-avsV+ds3kTxNa5Z!2e? zE3Y>;jJlJAys#kc8nb@$yj^y;Rd5z zV_p)1#+hBli%KQc+P}5J6qq0Xv3579uSZkOqp9XFql|Tf%KcRjY7x@EjsB~xoPt)X zMm@Sj@qsv!}TRv{tvD7 zRu^0e@%kFQ=t%Y|~@mlkaUb>%S zIR(-5g}ecs#OFR zYZWr*o>!4$3Th?GIPdsW{W`dxrQYt&9Bh=~M{9;{+s!5!*AC_t z9o|()a4+AKV=io;o43kpUDrA4dA%kOBJ=y7>WyKW&6(D>rbJ$WHy*@6hYU!F|}oI$11LFQ?VR82@Qr#ktX)Lj3QhXwCaCRyv1n2&obHO-rq3 z_(Si!hFfa<^sy|f74v&9W%z2#lo7YS^6%X~XanCbReBG97`!m(qZZx9Xe+W7IPkn$C-cXhZH$pfQh$xtQzu=N+8wj$ZHG*zm*qT^Es2i$KRJz& zSnldOw(@L6i(~N!2~o6a2BpSqKL)(W~i588PaNQ}i*OqZ=N;ui5ifGfoXc^Da>mCbrNI*9oP1bS@ObbIn_3 z$(G`1!4z8C6}z7xmo(0M1n=E%h}q>!4Z|-U`cdO`1(j* zyE{AB*}J5KK-~wIo2Rrq8LICpXN>K0PlxdN5!o%B-6t?iK^Z7J&G+GvzkMInoqV6P zRxo@YxgL#^2l5-6gAZmNw1i>bqCC`)-YGiPkY_qrF=60~!W>69_6_zXoxPsV$6rT| zOeor;2}hfOqY}rl$rMlXyfn@8A4dmqw68eNasHDP4W5^H`?pO*+m1F-wxY#o{m4M; zM=e@EaP7nOgJdMzZ9d)L$s8c6S1Ffpn&u#`$fUbww~tiwwBNt#^Vm63Gw`LJtv(nP_&HpoVXjsJtyvW=?&8$`tm8s7(x3%+&kmG7RD9HpuHMj{d=#5 z`+nS?!`LMR?Y#K>-#afnnZPpum>-0oT@f$!dsl>~DtP(z~(cCK>$TaIwwNjqyzx7^ajOFk4IVtfRO3mO;UiOr~o83=_{? zH(SDYHIQnKx%MQ^)+{e;=o1S+BpJKf4iO{X&NR=xJw>Vq=E9jqEF|j?5#?3DT>EG| z!(6!EkrAbb4;CMN+OhIcX0|9kUaMW1>5;B(lJ4Ex&ekGx*3q|Y&ZtlC|yR){ViG*z3KCrH2Wy&xeLm+31;Bwa8!uD+LH3hum6Lz8KOh!XG2%bD+qhOAa< ztoHs+fWG5LsDd(l%TCocc!cOXZhDc7#;2l$GItAGo!6CNO23q`TB)Ewy;sp@3YJ7( z-=IFie{)@SCTxjRbIg_Re4KV{pO4-nXBCq1@=X^}@4AoW`R6+fQ*dXBb)r}0$8{AS zCLLx|7B^sd7mU)_BtL!KfG|mu6Ai{{vo=@P+xfL58J9kE7meHXXMr2GNi|3Gs&+A2 zT>i>>u`Zkt5#>6HB7PGs+rE5Yn1VZO)R6qEqz>ZI*;`C2)rDyTx@(g)Prc0LJ_^b> z9x+DS5?@u{n4vSt$osyN=z2V!y$umkJrLcqTTd;nvxn|DstqA}4{j;m`~PLRSUfw& z6x@H}xqTl?tC&%`Ou zZ?@N3&-2pvME*ruH9Q$6oGWGLTgG=_n36GLW9`=ZvieK&cm?ZZGDW{`DF)5j!0I-< zF3SMKv)oO!uH8%Ot1}HG84iQ$ipsNhTM~1)a7@A7HnsxY7zt3sv$xK?WWn)ldwf-` znc}7|nKx5Gtun^7)G}_asQa9pMKTh->WU#x4ztX6-ZRXF=w%D4Yp1-5>T9};BSa^^ zAn{M0JC>A=o*Yx~%mFo|vy5Q@A}Pg#kBS?|`hN7*SoV^7T=zK&%9t~SYrYf9>T}wx zBpLnw<)Yoot8CxIj2v?zI_8J3mQ!=q>)$bUUduN7h>#~)SWe#njwyKhff~}AnYn$% zrnwb)+yq&xBQ>gPds>#!w;oudbjVUkt3ITZ-pgqd$*5biyy!C7k6&y%iD62#pR*SK z%|#z_ZmEJA(mJRFh@&l^v37+WIi?^&aVx5wb110ScA8Eyx-2UrmNm-Ber65kn1bgT z=y%aO!ZY23d$2d#vphud$gmZ#B$~C|3yIjNA-w$d`Rq!k@5y(UI_tx1YZcV$U^_Rh zbSpPKoBIyZYSKA3ar96I9`0C}V=hGB=xfr>WY4Q-{$%V@Ck@Rno^^I-SAR6%n1ZJ* zSSLEmIQmuX$HMrNEX!GwL&uZnzbT~qxNT8T#*|{&v}aFT^|Id&kc{SMGmAle8u5HH z;~A#(n)W)mxKlBGeHEc#NyGzq<0x(v%gy(OyKyWRbM3I5O5S@Zr#^k4aVE2M-e+}g zQZ;sQR~wEg=q+QN$XW6~uC9n{%bT8A!`cKbNVa}2pwGLsL((L0>CNPM`CN2w4~=Ae zu6|$r`NEk8wy4Na6GU%Vuqb)JFh_mupyh-p+RCQR%HNLFZrM%J3Ui?kPv0?dKB4Y( zpfxbI3&&h|IwT{`usQ0Ek6rjZ^G5cdNWs&Ui=(WAmVlDF2)reAhnO^Ak@I;hHs-t6W60UT5C@cqMj4xJVbV44!urmTbIO{vlahum&Zm29-Agjw z)hnr1|5%>S^b6vs3FeyoVoFl~saf@15o-vsWP3){TMTD!a}43A32G=KvS+=S*yKk) zKE-Pb!*Wrp(ZyE>z9~{zFFWoW$p~+BC{ZocpKm_AnPJMh3s?D!G5Pe@Z}$GD9z*Xu zN?cIhlTT}E;V1(UOM2hrd3t5lCoeSW;purW@#M(i>@Sa@9QDOq@*X$1(W%7lbbE43 zxuG0$;R&RSC|Y-p#kFTYek)}&a~O3q_*1LGdb`tSm76|?f?L?~=@nY_hnz8UOhLqt{zrqO_GZ<)yBPIQ92Z&U?u%yb>*Nzi)C#qwbB0b{>}{ne9-U_k zOZ>Za$TIGvn|w|yiNYE(FD}2{X25PqL-MJ!)nS*1mgD0J1=5@Me{@Gg;}wa;>f<$A^q2>EM)lfJC-DW%f= zl_5_Oob~As4a<-x+hR7B5U2lxz&at?WE$wOnk}}v^QHs+Im)=ljMiWLPfhzGAK(veZ;m zUmSRtWc)Sw0vp=Jg%2rKi6f%)?p-10J`~j7j@+iO?t4N~*5=S(4lz#MA}?-dX9K&i zabtRL)E9H%i4J{tX_}2)o7SGy3h2f$7oOb8h($}@vw$Ye`2@Ea3^hUBz1O@BIh3!M zzAaRcR)MDwir%q5#z_c9iOYx$p#IfzMn(lW*5_s zowX^0#}`&M94VpCTE3fPw5;mP|GJume~okDh!|8pm(r+jQ9X9xO2xq;k223Ezg{ZX z@OLvd&dft^hOwlp^!;`KN#&K73Ft!*WrR0NqWQ*v(DP@o78B_xe72sv#%xu(;dK@*uTzG0o z-#+VAfgcjSeBy}-EYlG`CBt7O^`X^fD=6drH!tP>uu^)@T!!~ry^%MM{8pKZPrVrC zLfvJ=p1xK1fT54sRW&7HEUg=#OvB zA+5YkwRz)9$JqO&sS=|0`Uc9KyJd8*j1!gBdm1UL$Cl9j%NViL>J_T;g1y~XBXcE5 zE6jzl5Zc%BMtt8*M_%M{7v_<%tI|BLr@l9}zk)K_UTCj$S?Hy&Z)@xzBZf5LyQ*a8 zlP1<+mIR)rtM$}Qxos3l; zT=v!zDi|@AF{Rt_T|YF-&syIZreKT(&-ZB`RlgOlmS43rx|v0a%3wXPBsz_n(u?=% zv6~gMRA!g1PEkxT7QI0E(h6$z?de!$XK z6z_Do0n2l6xr9J@&hhcen>vAd;sGa;QU739?vuLDQugOHspgnVj$qx*GME>>8OvG+ z<&o;qD<)nUHaVEQS0Ckh&e_VC4Yl<}Co_|bS33sr>xJ^MO*h9%h@h9Vl<-+K^+#c; zA#HojR>t;%0${AA1ca{0dtsxEdnbS{@48IJ+`Tb~5wxY0%K;02dZvti?#*0l*Enb1GB^h^W z&R232Y@lm3MM(Lj^Odz*>*)(B?IszAL!x=VPA--f=CKS@FoK1VCOW5HJ(!Oj{?1%4 za=H}r!kS}A6z$70ir1`o#A43=)`FT~ZEcqqD<%84)ZhQxl(d@UF_I^^23UH$s=yF& z`_W=0yi`lQPmV?*9X~Htrd@8K&o5V(5H{NgexP*@%hA16qy`$}`_ zi&P7ii<;00z4GUT{#5cP-Zd$k+2>mph6p;XSL|o{RVW_m{IRv}@xb6Mojf>-S58U^ zin)=Mp(dCMqkwcZ{QD?=@3M9vbAFS-TS|{@A_8ND^p=IgXg>LD#=v&vepoOUY9%8E z{20akGv7bZ;r>qx=EB;_h=}k}yu#D02_=*AOIl%zV*Tii6l$w)m9v_!=g-PeE6jy$ zNOv=+t!#zg2Q|2sm7yl6p^Uiqb{L=L9g=WjKs$z-;MkQ%Vhit){N>R=OX|V$Qh#7B z9B=flTECHeNzq8lg2<8#M+RylBkJ}a%&+#EXucRaQ<@)W4REedY&+*L{*N`;^0a3w zY3yPyv=}B+@_}LeoqHix<4HM&vj{bj5yxlr;VB=knk!d7AVrbUa-tohFPZHe#G?lm zU{RIEGSmcfq17e^ME=1%{&Xic$dfU&QK*TGIQu!0Pn}fNviIx*hMM52Ca+P&Hb?P; zY8abdV7X*>F&C~x^d@<+zI%c+E|-+f3)B7rKYRI ztU>=1eLIt>Q1KQ#`|&Mobm`j+HNjlyanko7=QrmMa%A8$21hdVInnErwHozLHNMXI zk)=U$C61b)-;Vw~eWzh@Eq*fT1mjIp8ES&LaA!ep{O;lW_8}LZFmM7xuNZZg5iK^A z<&AGYTb3O^+wTOeItj;cZ`j`v%KE!e8?Z;zER^Zdtk7KxB!u^M= z)vou>yhtNAcCL0EiTi>3Ox*R+xGLqrzs&l^{w`BM+DBn7+*uM+*42gI3}$>m*i42y zI@Dc8)UTPHM_2S@^OBl!)CBkBxI-om2WKeJ3vKdFFh{h5zGGNjm+&TzG;+ zyruI8SoDVud|ccUdg&`aOaad`b(!# zh{n@4I*02zja@p|m3LUMk>R-*Y9b?oJC|k^_YY&UuMOgOZiq7QOwMGwTE7;1wY?ng zmmyH92cq#TlUOevoaJvB#T#~6$1nv?Zt-lNl@aAsZ@Eu9FX3_S5PnU)^j zZ0Ra&d7eQvGkbSkGF2RiD62%XaDj?c?;`3mz`5kLyFxEKb5%M zYXm#uJe1>kG_tqw#GAg;kn|w2b7@chx|Kz$2j;?4bz*FtxsmwBxj&CzAfM2qR;VpS zMmy(LyN?{m_B#)e&f8Hdj3?0E;7)OM{N3_gv<{LG7-_(m1@-y)?5fk8K72_hInsc+ zFfKyhN=a&B{ry?mbmc|xBVmpMzAmzMz2Ot zT+=Q50EV&qS*hr^}U>IsK7?9H)oiFJ?hVU$N_;guXk&g{AQnEdWi zoD&fk$E7bjoXadSP)xYP^mvAGVAN2qN6@oe;#T20?0wEg((M6^nWH>ng_UpL zBGO$MWFDbBvT*ZSiYT`YY)*!o3{wyxbBen8H52DHX5q0{6q$tt93QzJ$%Vp2T*P6^ zoMIUzZWMC7kS9f7qWQa%=n)#vj-O6qs0rpmz8Ag3wz{JjBp$MN6MY%7zmQEO*CUAD zk~v;tpXCKhVaPB;ZXC*^ccV^r7av#jXFqyxm$+((K>i(l3A0moF`nz}TqZw;OgYq0 zu7_ml?A0ka>vm=-rP7eT3Gy4x7Arsl@9;1TqgzrZdDgTrztLGv#z; z$S_0=<$4Tq?Jw4ipJXY%e1mlR3|X2ekK$3L!Q%AGT&!&8IEgih2;`2MOjm{u7LN;! zVoM(7X2{t@KBQa^v1_O}x4)#tHmtA2*+!-;GHA(XI5SK%Td={hqf;Y^VT!qsHB09V z2ZoDs`P|sTof#OiV^Kr79(__q3N7fCxtLm1x}!+vWt#mA5#`Yff8R!m=pA>>Ps$aQ zn6ikV^Rje?F>z9Dqr|EwlP!;LKC>X-7`eQ1J?I2dJiVYDaG(=NItA2>yBWr<1e77O zis=MWOraCVj&uTv2-F18w1fOHN>ri~$kucMi3rpX(G*L4F_?Q^?XJd7D5b8szgQ_; zw5#qM@>kNQmh+VCFZ$~DUkt1$09Uz2Ch_!^k6f74@qMcXHrhEb+0%zqBm~wl6RGPdcBkO9&T&KJG zgji090776cyw@%x+;TP*X9=PFl9AR{zw43K|3*Csk@nlTmz<`RnDkpKOd)w`XhSQ~ zHoc^@nhTu}>wdLWdJ6Up-fy6LMgR5|qY2TQ5SR<^AIk{pK{1RFMh{{xL{o33$u>q0 zv0e)F7Y=(jsPzNmEjSviJ?ChH4)sqP`Q5HA&}#SZmG+ygPrxvdA-0FgcFZ?p3YLo{ zQB;PF77m_|Y&R1eEuOg-X#u&rrj>;wU%m_CF?zJ9b7Pk+W81OP4QZ5tB@tt5^k{BJ zP>S;ZvGvtqRW0B9+eEQN<=TZ;Q4teS&)x&)U?(O97>FVmAc_HkMOfI4c@?`Ai@ito zw!2$UY{hP`@muGh_w$aw?;q!R&hyN?Yptm@Gb?8Q=7Dop%qx0RGMaVRo~T}~pHIeG z`0j&#0 zV_^P02G!UM^TzCvwtgEiYL+?m#werZhd3I+E>HWjar-i~P5I+wEI|p8k|gbU8_tf_ z?y9Y7;H06>K*WVLsGTt9mHlN z&(~&$&Csv}=^`aMS!T3m4U0_CHl4Q@bV`cbuoD{i6tPa_n#AZ@xu3_*Bl$ z`nTLBbFs7ijHfL|6C$KRP1d<=qPk{~NkE|PLNsOSoyfs<#Jia8kLW3631QAp{|(j6 zVLpA0Xy?hqqwRod%+BSodV(>I+_4s-CCTAnc2-@_rj^^(onr~+7$GHEgF99$YPTf$ z`_)h(+X-`*mMXhEE8X@r^bQM2DwprKl)yGqP3h$a@}oSv`OC`QM*l@KbgYGF$}C>H zQfWP{fmY-6P>v;-D}|IO2C_mPC3jVeCjS^MNY(#ztmnI#zQ%xei}Wpy*EVFV?`1eV zT}D!6&woeF?>HqTbCfM>i)LEZiy)Y_B_bBAU8%MDB^7bkf42kk%1BxpCF_eGH0BlZ zXn9B~Q&4@4jNgK zChHX!$|dtVsSRK6rXAQaz&fvNCDwOJuuU{$^#9GP@+Wfe-!luk62u)b4*QlYex)bfTiU+`;1VF|4X{r8GON^}<8P?P)K-I_A|g~_^V|J#uf zL915(->Tg>t2O`9a=PXmVbcu%?aqj%HLw3qGm!S-3BR-t?ysbM^xs;Iw37Zmef1-w zHE&GXCooI<{Ktc|kN#WxAe!Pb)&=p3q(z&N7R3_eC!R9$uQt@ypNH_vZIZ3J{lAmm zaLY`6Skd9eGHF#RX=?p{x}A0de)!jJfF-2o|2rEZCEJd}fA2VWPCx|h4Eq1}D7RAq z+}!w{mVPHa1xu>7ovzRQlC`VR4yXU#;po-V6`|a^4_>2v5D{1ldE53V{(FzYb|4xh zl%#`O4R!L@A-uasvWESGtrbV`asF7%m-eVo+M}=p5jZxs9fvpgwd3IY!7&#{kaisY zd&j{!ifEjbw*7-!_m8!-f8Y$qTH^Yk-GJx$wHx3{#TASz&8Dd}|6iIKH4bVb)DmQ; zCJmSCm)=Efi5gDSSEP64yub7=B2e#Q7A?IIPrCiL7R5aSb-Rcl4X6CpaMarWc1YYa za4#X1*ryirCVf?a^cD5VfBQD>gLt!$ByB@Y){C@HC}|%&8{i&JV`H}7$gKASimjd1 zntl4Eeeh&~weapkFFMdkrpYf|g6ADP$%qJ=?Xq>Y_n_I1rzM)Z=HK^0S_S6cT7tf> zw%U+?>k>TOVJ$>U60LLAg4X#nTIYCTrFCxpz0PSp!s(UnAIy6HXifJIJPG586;GVD z+XTz`>o$SsbGl8Kf8W*dd`&*#lF{6oPWtERq>uLu%tgnWg(T6roj3S(ZpS+g-Z@0X zN4j}g@6I{tYaUpFJn%+lyF1$u*1I#_;xOM`)C_d5<;#hO^ok|W6Xyx<^vUD4X1AH z%`>kyFfTh1Z;ZJ$nGi#h{&GtuM2$aMj;j`Xfxh5UBVWT*LVPN-O~d^IcR1Xy=vGui zaSxjn!Yh^(`wAt*exoy7*;)^?6{00+z?aay;e?o7PHZ`j4fX>0Yn@6r znl(Fw|12twIchuX1xZR?(QaQh;!(KbHVs>ddoA_|zG&n1CcqlV(OyH35M=<%zQtR zrS9L8V2pTU&6VjJJ8JI^LbUh;for8{@^($3b@OA=NkV+c(YxVWLOh`n#C71f*Spd0 z)rDh2-q)#D_SPfBm-5>*oTE6~#W63?Z+C;8gzzG%aCL6W9&RprXQE+Durs5ClGLsM-WGr^wq>&4XnLemk`+R@u&LgTcsG| zV~m^m4@C9>wiWe`RuqG&V*n2=I@-&*Qjd(v>I$wI#E^lZ9*hEcB10kb%QUX|DH z-bg%#5f2{yhJ}rmt!e0#_%VI7EF_#WJDcdE&8xdKYQo`3lcnq<4Lqx*a4$ zG2(%zRMc?ddACPcpM3#@ctY9-YvC;nH3mh{4Ly{+h7hxf2hI#!=QtNAiuGrDgWZH^ zNC=z_lbcl1S2#^I3Z~BeV?5j|RBUM7)k+cqXTvV%lc}eb8OGP^d;UOVcC52+10li) zf#Zy`M3gE%YFxwXgc$ut@8Zc4Pn?t=^`YV3MTEFWJh0#KB#YxDNge7=NM1pRjfBA7 z#j(Mg1)ajzXC^Ntgh2>g&p2vGiL#fYChgfyhz^9n7Sde$?`DekL^@L+9_qH25LPXU zV}N=WDM?bqjD7X3BiNV_s9$l_iip7j_as|&dlDhA7fJU2ESq9qdG2@oKlgLIi{Q+c zqU=W1rA^{LgA2wxjE}c6-+mVl1@-XCG=f z5ixygl5KrVCj`z6oL6GYi*Cqa8$qk4#uB`%;T?`*Yx8_;VAZ0Ye<1Kai1$Q#z4d&d zvbWk)n+10J$>v-0rBYWaUwS?pcpP1Zq5!?Lzx z03mSK$6Bc8=@r3)a~kX?L{)3c!Lo^xpoHWlQ^WYI<+GLiCmzaE_Q&X>ezd2TnXjAM zo}H*4DBarjAHB5KeK6>Q0s4)#pVeqH|OUw{4R9XA_~8{QptJ$G%}e|-0c z@^RL5;USrM*}VLjGSWo}krMgnPqpR^uRF5CE+1v2g=i5GTHcj+UDuFR$!VvcBp4fo z5lQp~$$bv|{M~l!Xo0u#i&c&F3q_o5vd4K<)o&(NvHi!lY-mMIcjwcdxU#LU_sK}N zuWuWDz&;lnVr*fi`!%U<`!7lNr@HgBr>?BcyL~d2AU~ueNek_|@ek+i*)-3MCM>}= zAwSYShs*JGxtg<{v#-i1FQSnjec$=5J5OCvi-iR}ma$JTdJFkUQnMum_@m(++2_vo z3ic01>0xXfy@x!e80RnAv(e`9@?h5-`r{hqZGFf z#C4f6(nWqqiQalC`dBNQ)Q|N$@jymeh!zo+KI^q3e}}NN2R`t`pec@j88>0Ar2;KlgdQV-fN9 zgpR3ew$VEpq`@iLu!o2C%zG?zd#K7-f)T$+iN1-H=%Y4$7tZFnPNoFt|IsRTNs<#j zmax&q_fp7u{`HGmqEjS0_WY%cCCCFQk!Q5wv6KP*#;^}>0u-c+FRUOXiVL^&RPQ|; z!)EvCCLqopWgah2XGw(--xLq$JyQ-I7QrrTsVlsAg0&D$FMq9fRVL0F$vS)uP#$^> z_4L=W#sDMj#rXEHWdTZ!fuq>*cuC-~FZ)4{PiwNILQ0hNd!@IU+a;Q{Ya1dXcSMLh z@`O%TdKCy|+uk=9q{8<^P(q4yS{SP&J_=)(UzS#8FWul-vq34_s9}BsqUp3WHc4rF zIfVIkIU)}kXm}>S&q83H2BOJ-KB2#IsBSoWoLNc8n?Qa@iQZhEcU4(-FMzf5%d0G# z_QZ4c%&e7)?{gqO@|eVZQQG{)C*rCB>i^V~6&Y%Ryk z7vyJsXFEGvSF8tHz4nKU89azUN@TN~^jYZ=?#n8#%O>!+-o(j#wxyGeA5x;1(g&4i z&KsMtJab3c-?1nD9rikY}xpC#R_&m#KQ zkx>$?g=l)wVPF;Z;w@t*iWXJA_HAeGe5saAcFgla3F!qI`f}th`mqP6WGq1*NJ)}z zlyA-opDf2Fwmv7%d)Lu?@RO^J2j<{m<{Q0bVeiJOC)Z)araq9d1f@bsk|cL*!}8@V z!J@JkQu1n{X1iBerzOnoLw@w4gQ*u=67oaY^zey{2+X3y+(qgupU$jTn|!QT`D{W~ zBl18>bRYB>#7dY>DG?bN0uRg|MSk?+N$L7*>RZw@FweYCQ0jN zhp{j1<|yBTp2-DbCz}0!o$fJn7IRc3sX*Wu_PB9#B`o}@fWS8Z5KVa#0fB73=Xs^G z-vv3pDbl<-(bG19NEh2g@8V?ovKDtfEBUr($XJ5?GicCAbJ}dhMv1IAgcx}1vvO{m zh`?INn>-CIquA!#h2;Rpd-9n4appC@ZY-Gfjk(s=c0{qahgO@4xQGb!c_CVow!e*J zhSLN2*2)`llijiApt7B9@*-W#oTeS8^BC4Rv!!w);Gw+X>tyr&fDSeU*212aq(OWX z3wsx!ES&aK#u6M&q(onkJUfcz`Wc|y@O>yFU95%D((e2wlJTGS)m2V6t+9ju#r0v! z)1BkYCqDN4H6FM2N3x@5?yD^`p2}~xPc(Oa8)z#*?;=v7zS=XEeLh%IJ01N%;IZNS zWOI(={cLEYBuO8;MzNwEFHN;7+_T2-(n%#NMi@s^lq%&xf3~4qx@PpfB%^P$;g0d< zi+re!NBi92=81Dh{Ax%4vLUR2{d(^F++H@dTp?Q`(QtukelWMrdI^Od}#Y_g->mv)22CYE-- zI=8I2D|i0d+Z>q@ZL1Y=+1p(D;RM@%(Q07-u0NaMlCI4heO5+V$O9>nFZGF;HQHI3 z_jJ4^BP~RWh?%Li+0P|zd~3gtGD?De3eme%ae6N1bkT>GDSJ^am{!wl_cPWe`vy}r zbL$>)w*TnapjREQnpl7P8a!gyF&XJ1KmU~WW=GeFHZ*qPWx!8w(K77c&k23o1u;oaJzT#^4Q+aiuC$H1_n~by&Eh3ZxN0igCLEPopLm4GO zPXl@&C`WN%tWw-@1kZKMQTgn!-7{h9bersp%MJBBuwjPnzv!FTnjEWiTswl_inddb zZj)ozJU9K!YB^G(Nb06(cCqlf`TRJaYaft%bm2dMFdY-Yf;)x zDrp)pI*Tq^?$Dw~UxYr^hh}C3KfKPOU^+E$|*$?-p#AvE-CXqttbcvUngR(mp$!wV3l`d9?CKMlS%? zLNs|AF3!{1*9zm!?mUyR#HHuZ)UkWB<}OmAm%r>@sfo`cX||t}QFd%CN=xt7uAiw6 ziyF&KNzD|jg`PigJSNu}t4)3}k{4ih3QB_B3{k3a=VG+JUSa&hXcwjSvxljz7iX;^ z^i3g}zKbkv)b<}7#&7I;ETi855lD$%<#Nx@XP)W8H#}`EV~KO4XQ{;pXYoTy^xo3u z%UaCbf!z4(u*_RLOAQUqs)fD@5#bb-pZl%q!dta%B_mx#i-^4wUTF1Pd-L&SD=OoT zRMk&Atg!Le4`JKpdP+R+UpzKJAGNk|Y<_*3U;v+X+kyl#!>$NkyucENk-MYt~cWf0;UThWjsr$Mxm}z4gt(Hr}L54h-at`(4mF zKenCW{)@WBo*uF*O0T$L*e}HRMjb5ANyrORB>+BYDT?_f_+*yE2xb zR|X^Y=*;jTf|rV36Pg~vkf681DoNcX|>5q!sxLfXyL z$1=7SYayCqSWXY*J3}vMtM@;aac1C{m8Z+Jtq(d1`s`W@n^nxcR@g%df`4?s7d0$?ja)ylOK|E#R>5RrhDaKU0_PlJ@OTy_D zPs@0cB}>sR3)7ZY;+yl+Z5!h3@MeK$c#0%{(2qs+OVivZJ1KbQz!)aHEz#?gbNaJo zXVbL79bO2xJG|qFh~0EcJw&(EQ*=wkyCvRI#d~c+IEj9P4yE5MU@rI2zR+@?b zj$-Aj4^Wb8UYF5Eg7yo%-BUEKzaPuf?~CH=zfZ9HpsfdOCz5pccs(|UemAbal+oUX zmLjy5(U%v!J}U=hUskY3Ug1R`w4{nw&ZR&4DfwoOU`s766toqiH5+ZcbS|lOEG39+ z`tQi5k2ZF+>7%Wm>~LxET1?0YcHm@A;WZNUv7l#z_Na(Qnsl!p+qyhmMt=?ZjnLmh zFJSJh!2LdXvD}uoGWxdA$A-QsvP@iV$s1NI&0b%*E~76EJ(!|j?dKD$$LZLDuW4J3wR$p7 z?dDTjf8t!vCKXDUH_k$DZo2>CA*%tr(t>p5&eZWjJ6_yqp*w$XY^!x}hD9If^&9bd zVPk%yPAzsMbBT&2NEi7@l51K?em1E!^YdP&_9}HXb&Gv(+Y$`;KC72096Eu(k3V)Im6M8sw1#=O3RE31(pBFyFf)|-Ud?8X*EQ{>r*f3<#5 ze(Yzd5J9SKEpDd1{$%r0Sejm3pBkIxNwHA&^8J0<*C#{R^#jXPEGf{rRjO}-ldVnI zK8mL%9({<%w?B9+c>Eys``*88twnyM+v{}Grd}Sy`ril z*>G{zf3i&EX{7AP5y4_+FH^C^t@~8Z7U@-NQXwTtnm%)#5;rWAE$S5_AWk*v>v?v6 zR?87hAxQPsDPNw4uRA7r+a;K{W|q+2&6>c$n7-|W)Od^gSJ1+pL|`i_ZLG+Vv@t?A^f1l9FucXL_yzBZ{A z-3&H=tk&1oj?47_W%aE8^hKTUXy%)Gv`Lx!lLQ1xa?2^m?056`9(BtS&F&R`Z`w#a zumpJ^Z%NAAE1DIm`rfpmh1gdP{|+)Ajr6ujg_Ou&OW%|6beW?4d>JoD)v|^)OFc{W z&~d%Yk#C3E(30d-JDd%uAFmZEAFpDG&+3+D)7fFRUJ#{98`71YL+8dJ2%-{Szqy&K46ykrEQqFWjBIydA@!T^-H9_*q;+8Lzn%*wOtMLZyy^RD?Vl+9 zBK`U6I#blq?`L{`c@t}^B_I-RdPZlnS&%G}^x$Q>;y5*chnAh8Vy&uq?9Ahb#n@!; zDgF_!MPn%|Dt>q z>$wdj%q+q*w_Q_zNtJeg{(*+R(Y&TSOK8WGn)m9-ziNqyO*cy^COVZZ4T}~KmZM!g zRu0didsL5-J^tenIO5QO3dCb{(^)E(AP`CU@&t5I13g}+9Gx1?<7+h0i!6w;jqSF4 zX1#ZOmNw{;T1OwTd%W@R>op5~-(X*qTHi;&1Vac6irS)?^Y@RU-QlfW?7FFgA zI(c#TBcUqFjtHbANw>>0eyfo)ubQz~#gciK>g&B+$JknqlqlZkx(g3$--OT9MII-O z(t3-ZSyCZCI{Ost$UlV@;oGl83p}vp$d6tapXJBPx_{L&eCDh9zqQvlZ40(Z5?9er zZ&1i)d$WYee)`GmS^p_oWSt-Xvhl0-b3~Miv{*5-K67$b?;@IBtt;K1FAsmHT?(D6 zVhQp?O7wk$E@OB?4qt7QQ-a#2VNcy@k*`gvo%4e9^(C_QkE<^S>%E5g{aUr>294q6 ziuq~_BPR>(aQM($zgBdJtrnu`#rH8|`Px;@wH|$@t5|~kP(peyyg@Wy{j#LmvC0fJ zTh1Z+&kSE1UA*1lt&iSr3mC^OPx31Z6bIq1b}oNwU0T`N_;zElrE0!Tw!5MAKSf8o z266WNjPk9CgLscxUQeIePO%{nO}c%53x0fgITn#5BJfu9v2k(Tb4Ps}n#R0QDc-Yu z8#c}4Alz6UY(A6v;zbQxEfL}0aliI3d?>5Z*g?1(H1;*8W~~3)hCnoBBI$?JxSdff zR2C6<@^(lr<}tigm0wbw9??i~UL3(zkW_fCE%$h`=d{eKwpt=0W?zQl-aUX#qrSp3 zZjF!^o^SisvLO&nC$fKPu(`=HTSihL0?(qkPgXQvEbsnHD!()z#`oH>DTKgUcust} z%)>k`#OoJg@Sc&ZQCx!ZhNQw%*zg-2%t1pt+G>f2VV9#Bvp?44ChlRjpfG(fwge&8{XFJQMzl~FGQfvV6|dkG~cwzLD<#i7AulE;ajY&mWXK7JyH96 zaTs@|HHf<Y>$gx{=+C60@1Xq&FIhlpFY&?Q17DdLyaS!Zmx%Z5Beq5t4Cw`na|C&puP@* zPHelNqy9Y1*H%kJIPHk$*X!7+d~PuTfjUamKBvZytxZxO_w7Co!PUE5|#xYtnclO)>^h!*u#m2)llmTl$ODWB~E;st0p zQTwE|EXC_LXv6B0RQqRKOs#vhx{XKCBY)}p&epU27ZGg0eytgOZDS5e75JrDYSqvx zwpxf5_0^z@ht$1iqS)*kA_6s>sC~LmX{2QCieQgOs-gwsJ)=_ow(-a#|K$;2?_~Qg zB1)XkP)>&iu=ZECnQj+(=jqtp#a0W^qQ3gMrv|%yQf8^d0}-g{i8N zP3(yWB2dGL`pRodIGZ~rUaNC+o9T;lSM!*XeQk8HmZ*J7tnI(85!RER(g zC+aIpk>*Off)U({S{^@phG*KOSQ`(lC2F5M!v?DpCq?rmzS~WaF~w3_FNw1u8b593 zk@I8Le-UwGP@-09R~UatJP?5zPSif%_Y~l-Ds|knY}af{n-Q!3R@KU1Dti zMMTvVjBnlO%*V>xP1P^gp|5?9w$(zksIT6y?a!05J<|5lcpw5boTz>FW{co;3%1b8 z?NAfZyS4XA@?%?Cvnm@F%Y&mHq=sMk+s32Ui7NW$8MSTyMZ~V> z`?Ruehp_qU7Rzxjx}~O&h1M!NqEUBA(xFa=)XPp$tUd8S1Zq3fL}Y<1*hnc}Ac75~ zzB;^iu4j9{N;V$*8&vTK3@vZ_FCxk{&QLbr=+Dk4EtVhO&ta}S&DmB9(Wtv9cF?N^ z%hpzA9wZeaPYzuER*L=^M*5X`FL%nbp!_mnmh0A zYom*`P!m!10A)ag?99n06T)Y419SbN(Kf_Q*KXz^O+#(}MZ}VoF04)ECcGs{HQqb7 z`DV@-TP;MR?vkWQE>DyXJ^c9y;(-X%U8t2LsmzRKO6I_^yfN{ZuxhdApzZNC9#{)C z5qYpK2dg!1MDb^(m&heuDyAl+O|c<9-0J30(md7nUqsBwo~XqX3F8?g6(Ue~p(dip zexCw-_uS5WCrLG9L}|U&>xnkHTK`k2Qed3zzlc~!cjx_dcec;AL@xNRhyJm7gsm2$ zQFqaM83p_Em_ZM<&cp)|sJl=Tk=3B*SROQ`xmNPrV!6w^LHds?zBV40KKkm?-NCm1 zB7#+j=AWMAR+kl6Dj-nXiQ4DNl?Z+_Z+<0u&Py3}6lx#Q2RSL{2!8$eY{k9Pc|pTr zzN?4`Cxpw1*-EuP5SUYoXqqKjATPP^w6bg7OMwUKNA$5uQm6M__}lXKZ0^zXf=)#5 ztB9yah-ww=S>PWC%w9z_MTM&?BJpdfd^_)(Tlvdt~)o+b!8rr=`z;Bj8idZ zbnyHxT*}DH%3psiV+qnlO7!OPH3wcaUwif_+XI0Idcegj)6ba>{GfAtcG=^Gup3}T zCZetHq?Y8VcCA_dhv_nwpd`36NRp+)dhJ7@5Vm~DLxBf+@-feozVkC|y;j&1!Wg?Q z>>rq4iD>$YQtN$Mq|*>~G5EfWB`68*M3iH4oU3~Wk7K?KZwNea#}VThT#x&yJO3TW zvQeZHmSFCq$ipXZZ#AQAGT` z&x*rIUzR@qnSj8E6wLXf7v-vdq3=`qu^HR02)i@Jtst6SZyk3}8D6SC8|rsY#u98f z?(_7P#kqPc_r-dw{E_DZk0Ow@huL)$50||@J5ImNcdiL10F28)GrvEFuHl(o69%6Lw|s343MBCr1PZfw`9+{|gvV;M`3E>fcJR1*)E zJYSTpfAGK@EaXSI$T{n?5!vdq;%V0e9vFp${OGO8un}zh=^4tGxLZOy@KhtlMzz{M zie+R5D9tU;g?u%PrV`t6F2`v0r0xJ^`K&9#X$kYAL>^C?N3mSDk2G;wktrbXOBJEd!vsO3ltV+X}{{PVshdpD>tU+R@9NQEa^F-yp9S}xZ0 zybnKc=%R4m#YjmJabij?R`!AqFZ>4r^L!9ZtG35uWy17+{QUGs0uMYbi?N(9YQ-tr zqet>C9WDuHYRsq+^KlZ|=3+lWeE7zBZ)Ge&y2y{d>HRTQ2`V#^kL&YV#*;T@qKGl6 zmk;}=Y*-w{dwsqnATaX<(G)ZBqN#FX`53+}Pr8uvgOVU`+SN4wl%Ro8Jm-uI;iQi_ zA7X6n+As4obH6ZN#P61Xzp?C_k5; zcH)2KN*8$GjYW)gJ~=-h4>;eM*CeU11f!!x9<^uZ<6n+<=A(M03->6@l|V}LEz@}l z*R^WgeZ>s{fj1w3)HBKg1NrpT7c`frS7oG&c>yAi<0m6{^Poan^T4M90wdxv zQeKk$9U^&|xrH>R$jid*4x{`LO}WVNWB9at&9r$L_hc+V3Grr0Uu%9H!7D}=(&AIo zg!>@o0w6!KOpK1=8xwM??TcLzvImeZ-YjVZsjrT$x}Y_nzQPt_U!jB)Yd~XOmd1Q0 zjX911j=4A)qd9JJ#*)q_cfVK>@2T;`gyDoe(Sy%>;g$3;wXkkH%4)GvM zQ7^I-Ig_Obtu<&VLdz7rEplia&vAC4Jh10o;blD3SEBauARAey$GO#+WFtdc7}i4F zMbU<2hwDyuxQb+lLwg%q)kH*Zvh@ukTc6d+i3rqcqP|){_QV5ZPqZU@BH9hnIw&Fv zk}k9|+WHqP`k(Ay{=K+v@_dy`qg3EvX{Hne4mI z$-e7JJP?6eP1IN2$c8NS^yg->)}j>{Yl-^mFxjcAk)8SmAZ z5NPv8w5Z`Y+1tC4y?yK-2-Iq#zA8vI{RgX#Ht9+&N2@&667|(C@*AX+-{3s?4bVS; zUH}oXkbD!}$v5FnJP?6eP1INQ$^TK9{2#-q9q7TpTB5!>(I`XF$;UF7d@SfoL63=u z=tF*-zsQfnNGkN#AX?OL`8pp`FOjdvpQJ(rYBf<`^(B8)P4Y**q`pGG6MC0K#4_@E zrIF8T6!Adc7NSKBCzD?-d$V$^8~N1`fm%(}S2M_W*NuF4`$;PF(V-_!L|FZUAILwL zbJJo$`yg7>aB1X&w0PO6`^X20zDCqtsEO!IO@7Y5$wo6v`io@xH%w^CZcm9#bpFiTt-ofXTbOijIt0BzhgfVC~^Q1 zsJl=rNm8-o8teqcm!y$Y7$JhSP!n0-D$Y=nD2C-Fw#jxoT2!urWAh_OCyNd z2hpgz$ZtR~Ub!3Csjn!;3lXS&Frt-C`V>d@j^fCgQXCm-AB;Q`5s4J5)`()&A}Ll4 z5vYAIhK*kMqjYa@z#MeT!;vLd1>#nwKe*xDx65ri08 z)I=C_OSW)|-%XYJrd^>z9t-AXi25qM z|6Of7<+0?aJQmEmISY9#sO`w!UZ{-bPWdZ^r!N-5O=QxCNr<)!8iXSpf2ulTEY6*D9;<51La)~v>= zl-0PAvKldm6SEpceYKDBId@P#XJ^Xi#9UO&=R|EMNyl!rWm146t3r9Hm{W^+siKB! zK>4-4lwW&>@@p}J81rjIeYKA=i?2~;@d3&##*AgmEEe?@Yd=>0D>vzP%BjZ8Ys{%e zZAb5(x9+C>eQ68}q1@j0q)K@c|8}lg2yst}{_xJ_? zX5OQ=qnDuR&4Cnpb0CA>9Kg2>@XY~HUwPBo7`mjSGJ)Psz?U2F?F3O@eMq%%@BNke z`t((TW~gwuo*uq^qOoJvOUvu4ZS?1JqK#?;KTrmbdu3O?KCuxWRA;q{Ib)cq)j5Zg z{-WGuBe2eMLL7ST#|wP@s=atrT1C33iI9>cWvVs#BCQGk(0hZ5v=A*K+71ig!A81P zYwl7Z2P=dH>W_zvGOGRjVF@T7rnepwW_-Ss&5QgWBmDTj(68DAzF0t@PW+VQt)F*_ zG6t0RMD6IB(w)C~m6P9Gwo%0rMSYHXKJEM{{rIR*BQSdoYKLq2G5qU=UYf<>0^wN~^dbw^x3@s!VA&jGA z_|YofS~+dCiX~+`#^^Qs_p{Z)j4_HFcszucy|+)Ro3va-?ubTyl5~f7T&(P^RU{rr z*EKXo|4{P(;<3GYG=KZJq`=k|Lh2ew|NB3-O??cGHEZvKwOk#E*nQjHw=r>*Oc#OI5o}bh5SgjJ4f?5{xK=7I;jLeM`HAcdN-rthMZnbQ89X`+|7vUl9Spox867|eGgU_|FGAv1f>#rys=P} zY=vfOo`J%t$UQEK8oBV29qxj*{vijxeK7og~9II;;eT-F>TwchJ zUShiy#fN@vtlpzHAduEj-&p-tULV_RM>ORq&Kt{vJDQbTpAv=lWClH+sCRzvZB%`m z&Fg8dar#)d*2W&UAEX(2EFQ-v2HchR*Ip;+U7Rt9rmv+bkvwQnNhQ#X8SB3FvMHVYbH)g6R@1-%J`k)nF#)Pe(Ey$0&uj_+&p{geo zugeRBmLp>DwxRlzeilPsW7Ua1u>st@Z@RMb;ZhY#aK93H6j%_ze-2AmOv~q~xmJ4X zwI~`!4dMQ~3MxA9esjI)9(OoeD2fedg zU*1P=)kZdW>|2s*d5&P7rNF<7HQ$N^r~-a8C^#`vW!?)QUB~;(Rw*UaevYz5;}l z=q9YS<&OtAvd{Bkg_8{SblZC#`j1ZajQLfb5sy_HtoD*>EMMoPDwd#BI5xDaWxUj$ zM)zR>PoArIrYe5=N$TU)RSeewX_h77>8Y_NoQ%0&?hub@ZNF+m$M~|I0S{Fy!FPj@ z66Gki&%@8Ac4NsmR;uhy9zDlj)r_=*cP+>R&vx{kpW?3kR8k`*Jy@+`|6sq3=vzj2 z>{i3LJp4XMwe(0?zItE_=D2d3iY3SoDUmJ-r5Lg>7Tl@Tm@sC<4uw(@1E^ijeEmb+X6k+H8WCD)9zI= zI{V+YAOc@*lB9pKz0@ME_F)zJKUA?tv8R!eBt6{zRqKDjmmLc{CP;;75wZC4aCw-= zD7Myhg4SY9r^b3*IpfBW>lQr2<2y`}lvc5W_G4KniyIW9VF{kwS9W}VsOI}}hF<;# zwcP%F4=wll;q1WEP;Eoo4yhH-mp2++y~{#?MtZEOT`g#B4=L z4q;_0d1_dKJdiiNO%+j`^={pco$7o-c>gN<&3`?w#{O;i4oSC|HxxCmUh8bE%acJo zYOHi*amVO=s)T+j-pTQ<-fKX*=f9_&jK|-sePvhQk^QXSmVJ4tsz?`K$wEpL!xEW| zZT-}PT^svQMOug!5!L6cQ&Pi1S?!D@ixfs`bvT|Y;*CbTX4;k{b0OrTV=)>kyQ z?O)S)VA}_eeQnELjB#WSBHO5G(SMtrn!6asiaxa9yIN@1Ano&|Evpbgh)Hc!EI~^M zQlfXAPdc%oB`hqs?MxN9V=Y9}9VfCO+g7qRQyM)JqzdWkY<9loVw_75C6uHnH^wT3 z(z~W*535*fMhn?|e_&nXc<-k|o5;H~a{wFM^`=s6&nDsJuc^m-n`{4TGOn55TAbNH zbI&)-sB`E&jd>fgd_*7ptc3Pc1w{DZ_U0}j4UPIsURV%Ki0N&aTXjd);eL`}Tf*M0 zyr+$M&^9;2>9h3=C*2QaE-RB1r#i({q>C?#p=F9r$Qhw*4k11h0!z@Ag_P)fkk8w) zrJG8yEd`TQOO0SvhnV_6(`@#DwZG*wCK?rDRraS zxS#J#dCQX30A4M_T9qD*H+Nsy&R7*I(Os>KV>IjZ;GLmOX&7AQnfljj@WV&*av-n)$b-U_r%L^WT+yj3VW7c_AgzqAGnQ zrnX7Fw~AgW1X_p|5l;S5?DcB1dgabJfk(+tG3NETeTzkT1mT zQ1KPHkztd~nLj%lm(4l6j#rH_=Zo!X9QbIp$&{wvb$pc7yNJNv#eO4icv2)QSv{9R zpKcPyBdx(C^Msg=My6|aFQi1@CA&3_l^(9iDFJ&`tc6mEh$_{i*~ig0Qu>xlR8d~+ zD-p53`Z(5>bZ!~@{2C&zZ;dhUTH4LXo{-ZE(d21(HIDIK?bQZ(U#eIOdsjqM3J+)c z|F%Ss3T^Mmn@&rG!r9@PQ#6;dab&#=G*>W> zG8WYRX~7rw(7sQ4w{mwjqE2ppFKwxcwGdtIn74UyttjJ(y;U=WH0#Q8FR3Jpy@32A$!l3xcIdP{pS2)Rt+uD0Ir~n^UY_w%c%u(J z8x&=+-I+BxqVN;_=BxOUAELd#S2oWsJK0FAZ?y>LrdI^}&?|zMoENBAg0KA{CGs?k zZ_4h)Rpc&Z*9ktBW-Z#Ai@l06idFk)$#=b;IcV!dWB&Y?#G_FS6Vozl@W%zYiX|u& z_8WaI?R9t7;ZRP#GuJ-?5A12=M{k%Gd9Rc!--oYRvRXy|P=k(7J^$VmXY9F>VR@Ny z&vU`OIAcN=>-p;Qh;*fNfdH=9>nfI@Zwe{V{XDz%Q?nhpL%jonKPupAF>{{C7~}KT z#}?#A7RckyY{zDW8`T#G2<&M@OH$8$>B`(z0sMW$2KD)_6`m7=rx-)_qzSJRqQ^{< z>PN*X>X>l8r9vO!r9wpao*v+Nxa3shLn-Syamese%E{I3{8#S--6;hTq&^dac0 zGW)YHuks>Q@ZDj*RVsDIGc9|(QPIxYyCbq)QD%=E$cH%}Q?Uf4!k(s`)1{R1ba(_W zzwDv#QXzU2+xKws=$$^*7~b+0@o2H<(1EAP(R@#9Pt~{8tj0rcO*Qs*yk)_+4e`xG zTIaW_Dl?ai^F++ud_hT96FBgHhoeNfwCi-P8s#)DAOv8;AL_ff>by*C?Vxk-z}y6yLv3& zwX*Y-SDZ#8g|=)ZziJeR+0wW7t=;P9m^+_&Zl9?z@_nr+^$SDy7aweK}z)U z@PT$IM|MW@Tko0R6ULrKG`&HWt+e*==2$+$E|-QS$Pc~C^bLgv^AEhC5j;U7h$T3J z$d7W7*(Ghy$$`9$<+O@#F;?xoBDKSiDTcBm&GL2W_0$6uC`tK~Hfg;#59L$t*lSozkPtll zlof9&%g66+!AD))qoPmn{fQ#_xP39kw84)pA!m!|PV~RWkjErdfuDcz!gpI!u8b-m zqFNTv^@6cR$5oFk&jSnSq4{GCp7e+ip~FjYhfA$^@uUMPmLL!0P50V&W%;Q(E%@0D zyH(^~zkCV3aK9L%s{0d*i1_)S1n=+HmKP1w1*s06$)nfl8*7wKe`rAoX?=8c;65kY z^UwmP1;pqoIdzX+vBuG|4=q#Xd28edG; zymOJ|dA2IVW#B9swe()a#n(r%hw?~e`sVp6-jVS(i8ofV))pSh7T?;dbT_S5(E@?D zV!TI7(&g`MS-Y7f*vLmoDq1}7c8@j(Nit3Rn`Q6k$#(0jRkVeneFm*Yq(vj%Dy_cu zVKv(fRncyU7AUk#(aWmYrYeQ^hp{Cd#Wb|Bq7@JAe%9}8=T}pMi#f2{kpbZ%< zo^&oL-$|QQY9#A*tDS~+W3(rWHhsTFU$qK>zU=3{XM&Ffy$OuuEAF=JaB;!-G-4B7=u7Bp7;#m zq4`s^3e^^=7~_Gp5KS{NqZ_Z$Bo9}sEKxDK1!FNVMuUt|?W4IKJ5L>5th$NT!GAFf zCCkR>BLeyvThj7)CEttHKQ!)U9H?wZx6~>L(R^5iAhlWbpcE{LPmR^b1a>o8xaYRs zo&TdmaeaNFd1Rg`>d3JxOh|Y4#aMk8(JeOF?hhVs-$n6^e<;Rs%LW+{g`dUf-h|k4 zFOL_ZC8@GsG|$_kiJGr#4;3XrZ@4Jcr@>?So9*6O*UHOJ}OsCTz! zhw6o?mizsJUhhAL=(E#(jib{GdSz}1&^K1>W%Qj}hwGa-_bJ5U*e6_v&zdoE|{`rzcz6@p@J$ zZ|-nK&HZ?#g0-+sC?Q25%?{$v6YWxJ<~^fe$(A~yx=eIO%qZxEl*m7LB8)pyUo9^% zS3&OBSICdPOq$<~_x|vYX5XZO(DH4Uo9fev$Kvp!UV&fQ=_TlY==mblj^v{)d30t? zEyn~$h9#9=_SUmE>1GrfSon|Lt-rGepGm!2l6n_wVeewE(rYl~O9~nS%X} zEyo_Ad;?m8_h}9OyKRGvvk%vxI1|+m;rz_NqVnOy7zNh>&O{OMDkPjYNSLZEOn=q{ zR}t32wMp%u+hgO?-de3SubSX`##)G`)9bc2{7(6erf=&@3cY(Kt(~5CX&0l&xguWk zTlngh#4g7DrG;rcJ`tkqoeid$guoK)X&fiYu36oaPxjqt>J*rR`CaI(M-i>GfWltG zIt;b(aLp*_g<~U0;S z?H@5gym;-6rV824C^*ho>sjAXdJ-Yx*A^f|5Pe12xUj+W_Qz=jOK?pfCE9W7hVZaq z8%_OBY!}uCBF6Yf>W_(s7p-7PnwoDU|FmVJ$>ro+F50(29z%Oy85;A68)PgwF`srd zl7x|NM@p2<@i3Y{8L-h5=(WOx`yJLAbw1WM-!|KJ=TncO`DvHUrbdnCrQkk@JN1lH zvHI1dE=B>#x}SR!;&sc7rZ#gH3;Q|J6%o(9qIvrpsV3L!bJW1CvHIT+x)@Ju=Jwj! zE>_PM-p%j{$mKPrORWBmcQXnGTO%{;hD7s#ZWT<8%EStY#a^+xOGa1Ye)n8ng<4V{ z*6e1i=xs&Z^^N9}Cr&Y4K0Qsv66Arr>8{o{n)^L zP4plt8A=G$CCP0SeR@z=qwJfaglPJg2mju9qbYx7XNI*ED9_Kg|V!Zx9_lJq3Tm6s$$dv9tvv=D0{ntVkb(R@^DPT79U z454@Ne1$ztBX~cWw}{_s`YUls3eF!K0}&BKvpq3vqp3j06(*d0ICpUs&`p?Dl;hfs zrmhFY6@_aaSC=F`qji2KFRiHjOu_YxwGd6whNOLbCvP+rIwNWyJPn{GqFk9eA-tyd zMpO9d?F#BXtc7T6v|$iGeRzYZ>rYYdA{sTSB(102V7#%>G;zQ)1@$>WT1tBq?ku>g;oc=lRd=@GDb+Wc64r|QAl5=OAzE+RyJ=l8&t-R9L3=COfY5eA zw~1v<_7);UW?m727AUkD(N{1^Rc=%zF_<@#k1JS$JdiiVElr%`)}MHE%X3^oiwD}1 zMT@ZVpmM{~>x22{oT5}{Z9$tXjmL+K2Dy`hxlvF=phX95i)4XxUDmipuV7wo&Lpu<$GQT?l@?VGrB?dZ-Z*lggx8x50p=aQPTmJDH#J*t6V_9vBwZTO zXs_GKVD4O9Y&qJ1uoon$@08+hwcJOouMiKFcwkln-fPiIO5ahOQP#cSieSFj^|;cbz+KPA zMhByR(-K}4_S8u&n9$CU=Qw)R8xxe;_Ha9+>u^WvtKAWC?zNT%^BbNbB3s@39tB<7 z897fndO3ZcaHw6ScEY4k3H!Gkpn0|Bn1Z#QwGa1f{j{C2xtF8YyA~}yb1rCS z?4Dsogy*@xfBo@bZVo;sNVO?vvS%)%y%BM{gcqXeYt5;1-KNoaV*o-&_1<>Gc24Y{=jxtSgm|6rxPo>{ zwAP7!HSevF4QG&4KMRWp9DmU|c<0=%y_MGl^YxC$6;U1+?PQ>2=ii`tF3dPEwiN zCz^j-2hcu)Gn7u2?)H1{5aP1^aqF$f{M$N!J2md}6u%o%bzfuBJ_AVmAfnv8LVD|| z9gQ)KihE6rE2cj>*U<LHg4vZbiO)G=c_e0YM7JPbT$Tjv!1UqKb=dSK!_>%k1IGwQNtl6vKpK^l{}OX z*9d_n*l)YqMw&kt?Pm;du--oo=lQzlGR@uOLgL&-U%KcGFVyYQPAB5gklKMW1O3jT zox0qzXAQUi6U>j76cOm*#nnaM47*f#?{nfYmu3mB9Q5`gZ+h)*jGbF~T2cFHMd6x2 zO)ajE-Fy7^<{`bCop|7^#`Pg0POG!sB1x*n)VpX;#C$c3xS*L>&13i9gs4S*h3f-t zmbg|Z3u4?Ew+l2LI*kX88lFFKtw_?275y8wBZN!Q;|i_=Jhvky@>+hl;-0pObYdlu z2hN!FPmiRQFV?}>u(<@yk_Q8GH(J_}^zMQa3hMCDoi2IUySFp89(MG?wIWHrj~yGz zG#<5RJdp0W*m7odPAB8=vSMDiR_Fzq$_3o-kW{@%DnvZE+|V3hbTKA%a`3{nLT@J& zJlpU+@i^;nT)|n5x*aJ|=F6=^d!A5Vb@^kqW9&ywi0Yv;+{?}G-?U)NiEo7t?sb?(+A1kN9{Ordp{_NdbR-BPJ{3(`J_2(-P4 zRyFz3#^gleAyGSUzT#|0O7w-*=Xuy8YXIg6JiVjAn9wod)L|?m>$t!mR z^AgvODX5WApNq33H7w`eXT)O;X$Cx5;7k+|9V(7<>raS+G=iutabAgIK0fp7-Yzst z!f2M@X&c8GPXlzXJrcjC8u9plbbWPPRm=DGu~0+=MNw?UL_sVB*?SM1b8G>zuv<(_ z6jV5<2sUDOcL%ndJ#e<7*xlXT?N#5kxj((n-0yq+$Ma#`)FQ+ik_vkYS0Ayh$RF3xkq~tVfhBlnNq>hseW!e@cj<`gguuSVTVSk-dT_z; zy$=boomv-r4fk^qQ7CBVp5uh5KqoTXA#p7c`@^u}$WBi}I8j^SSq=9nu|E!Z&)S`b z5C;i?a{?v7b~6}GbX!^H8jbcjw3eW@|7xp0Cme&pq3@Eqg{aThl{l*4X&Yt7QAs!S zMO^o05RbRS19use9p^tqZMFB06xVBI4t@ z0d>z1A|Le!u9heXN=Ps2w2otq;|)@^YcuuxE938*ExPeC{=V^YPf9d;S0mrrTl$R` z3y5RYh7XpWuUcSro|9;_FWyFD&vWUwYR2EUYFHC_x7CSb>3jA`HL5JMCT&PGcAi4E zn{QcnZ^qwuZ-}PYB`J z-y&NfWmO?W<|4YGCj?UMJw*tjO8+0ktgEA0_q-dW{oy`J-bV4p14QL}JFgiLzOe~L znfSeGW=}lk5hBik?v@CFRLD<66x}wQc_(g^ykn*-z3avso#;Ms)vdhdka&x+Gu1mQ zIiERrWSp@r@m@hzIfEgV5R*xdE+eNaNY#3^#n_an>dyE#qT1m>tVYL;(!;_j3Q{5Z zPVy*Y6XLzYPqzZhOX$O@UfCesd3jMuI6ly*TdMr8eF3IXbda z)PrXZXJ_tP1{!s{O0CQJ%`u0$ET@Y2vUdR+ zCHFHmn0a2)tP%Itsh~hLBe{XGCn4Or>WItk3S06cN@jaJ7?$AIJ=R3GwM#wOw?}oY z3o`s!#?`t;-O_N8&W5-<!CZc`!R2ZCCCqJqEq+=KlapbqMQ*?U62aV zC?VyorTn7VAJ?_+Jmk+%60BD|z1GcPVh(#ZN|Uq-3|kSk#eO3D2le0^nuCw12eGHH zKSV?+8YOMW9yOCj363}%$2dZ1rKZtdl&oZ*UtLsiR3jCl2|+XJ{=kh=Ak8R5;QYXu zM*coDYacAwD8wjep*@) zm}J{g`0e)t9`UUh0`bmY=Zjx5MX3Z{uxNlpU#dyrXP1yTi0NipQcG z$Ws=+aOMfA$yL>gIYdx)5m9Whh4<>d%HQ$v1*`L=1lz>JZM5~rbDB}AB|j2ud(XAe zPJGjOG}vz8-In`H3sO!Bnj<>>RDvygu`sPxnvR&QTDTIwMpBz+SW$MQVwnlHsDWYH zzFk?GAErLT=G1%9A(NXVVjGC9b#D;>PAQqg2Mt z3ASuYTWj)iokz0>3m@x0MylHPj-WZBmyJ!ZwQJZ$i-^z>&!$`W@*&qH&z)zjC_7T! z89`$qrHvNcPDj}7w(vbW3d@$^+=?Zb7YFm@(B0C_Snj;Nom4d_hk8I8Z!4IyrS|4j z4l_!1a7BXc&cN1M;vAjF0w)WfwQ8+&q|_Hdb3`{>HQv_rKugVetsddlyPbs>R?Enf zu3ojG>_`=tG~O06xRsV8R!7uGwD5ep`^iD%;f5vXTZuYRH2LiqzBgsQv?Q{WpvT$Q z<8AwcT4;+u=P*aMA8#As)Lh#?L+7!wIc44}5-uesR8z5JiX3n2)i+r4JeJ*zI#H&n z(y=`Ib|?Aa(Lw?bM3ne7&h~nKh{nfd*Lf_D<*sakT*LLf6}3gGZuiF7B91iIcGlAo zrH{w*_SbE4V&pz6mSFB3Yz2Bz=U6Ncx?__Ij201?hX>JgzPdepI)khx=$Jta^0jfQy59M7Koc z$E6M`%8pbyyLGXRO01_Y`A>FiY1r@2(trGpPL5qjmFK&l}80t zEWuX5nrK`t>A^pkH_9UhJyKoDcD9vE^41oX{%S%!p570)^;qVqWhUwU@n$mJYTvA< z)ETiuXe&ggMs={wEm%h@?5JzrrNRI{_0D|dK*}f;wMDAj!5wXD+xuxNFX|Zt+Fb9; z18N^p)VTLnEWs>C*a{TecfJ$ewfZ-;P*9NVXyq!Jr^hD~O0}|NcUyzq9@>W` z`Y6fXw;ONqGey2*c_nCm)vu>5{Yh1Ap5ePmM4TKK&il4$p$uwqNI)RJGA|n2qLzAT z&vw5j9(TTn^P4xfDWUxnRMZx!+IMSe`?#T&X3F`N5PqY(^OrjxE5Y(ZE0$nRCu{|> z_8kc2jZE2g5(+n_q&L_GHpaLb#o5#rGY~%`zu= zsHg{0VMZt#iJ#i=pJQ{gnbW^mkqR?HiHNtpMqa|lMcKKb9RC_#(YCR93GIg0TNCP$ zel^hc*Q8>a(`bE0z3kG6?`&;Qo;jBg+A7-?v+eB4;+px~N0W#szp^ygFzt2F0V{N5`S>upxCeUPeuY@6PJk#ZIMq z^J&G)C_d+Fb1b>`rJyZkKoMgSj>NkJg8jwAaN19*B6k=Uw_j`x4rz zntGp?{^ZR)nigeia-CDLeUPe>?Q8l+KXE5AA?-L>X*Rk{Ix8j|&n=vm;DAkkl`D{n)+H12s^m$%mV`)C1_BG`+uf&lG z(TgmZ=}kS{v<<0G2+?9(NuFznY$%tsrv83k0Yv~`aXV=~tUzxBb`YH;y=O*K8CGKi1p{cMO6*~+Wog62qt8Pf=1pN-$S z9>%-}F%_vWGn$CVw;)x0e{-O6xO+IgTsSuUd;7dv!QIaUZNn#~r$?+aXb&k5kHL^p z^{zTTdp4FDtO%`(=ohPoraSu<)^6?B<7@YyzpiexW9*lboujr$HF=gLy>s!B+NwZ3 z-ubP=c{Q|G4>oU7h>9hcQ4V#YTZ8mz>h?j=%Gq24xh11cdi?1;TKO8!OeodU<#W^f zjQeiO%k_*vQ4c7bdKUe7sg|R=Z5e!}iZ_AhZ=y zc|=x8PjxM%@d~=;XH(Xx6E8MoCmQ78s4Y^R+E_FFtxE}QM${cbOj)r)eV8zSZEe*_ z#S)Cc!&V?Ky`?ME#)$*if;J)oGrS?1BEuRsS9kXts#NkB#^051lYX<#XIn~%7bcIe z?`aRaeXyB#J~v&Taz5?$ncUj4n@>rqD?56tUJdiJ37O4=) zl(O7=1V`CFZ(EkudhC0fdB$^74g18j%j0ru@*!Q1U6mZwU)2k+q}w4JWk;&d)1%X7 zRdLb2Z_@RsBj-`20io=m?8H%aq_W=-pEj#raV_$suE*8E53J1|jbMG64_7f?AIdHw zMy7jO9XgFse$0vDf+V2Fh>7{ra`?WtjZM^d&cR7;)=bAS%KR-+97_r=vSW=xa%%}G zPyeO)mvVvD^1L8>)Gt)vfrw%=zbd_Rxo900=$cO}T+iy0y(McA_SQlp86XR0rB@dQ6%^9Pl zw~68%z8((vb?&{b<&x*7(rwlTR9==_vz&ZtLY?St>GfPWcy>V+lqZy92_j}RUl?GK zU9^xry5@F~Gvtm5E!cnrXO7w;RlA5)0gsy%*Ye!ZHD4SvO%BZ)%?yo)37HB}57dvm zare|x_^9DZ#^6YflAumEi&hP6a^jfNoqdrUOG=G&4}6o5N3(N# zCbRq6Rt*}5L)xJ62x1&!Dp zo|mKSNTq#@2yA<`gto#--*I~7PEh{pIEb0cMyaSFQekF9%IS1wj*_?8Kz6ZoR~1Vz z3L9&pRrF}O(mT41BA*WDC_A=7#FKr2JF*$H*M0T9cI@>_%C>Pi*u0rcK-leG9#}C) zKCNs0=cZ#(^8)V=ch!1#)K3{3>8tB{24mr2xj1TzR1>|H24?p!rS&SNpE6d~-J_K3 z(wm*^F-%2mkxI-pS@Zi7rB%g7%G&VG93|QPZhznpSA%98{L*ye=EcD2EwXE`-SqR- z)jUs?55*cOdwPfn)E3dy=RpQ`wd)t9;gGrlkEYKL2C8X}T7lcoO~-%k2)uBth?Xy} zezJ5A`L49fUzb(6_ESY|k*ZA5{ek%hme$t%&^7ljd{gP%z6*O~>ZhW%NQDvkbk}#p zj;VcXDdWGk;wTAf>y|5<(P539meTVz@$juuh;@_bRkk=!0ny<0qrgnp0$P=PFHKb< zZUk=aQ%uWAxfCgvg;sz~|5BCJT>MT&*^$a`<^8|{8D+IfJ01{XWoCBv&c7A=b)t`o zvLh8{!z9aSMF-}8FO=19_qkkJD5aOg-LJ9d70^0}Cv|jbD!Y)OhQ(WWA2t3AE^B6C96xMntyfU4e znZp>ov!v$kps$I;M^|DIlS;Dg#qO%uK1j9vvz_r+N_lP0VSQx?^>SmWJ?pdV-#V+< zK1hXm8w`e>sh(^=IXk6QHb0J%ptjB2J&g7T3TQXd^lxW}?f$Iu)`QBWRRsmag`*{n zt`5bt=Plou?!7K*{IsvE*0HEQ&wsV4$4b9#o2))6mSFBr%sD}xvP-M6nJzxeaadCoOHgyHi8R0C%Sv_0p;XG|#ZmSynI6Wk zbW?DEZVLV~cpB3-7u0$>==WDGZu+vL{c|W4bBYLTA4JnV+-5TyQ*?_mw6cT1qvMq_ z#tj#WY3rB0F}XRHF!t$IPHQ(%Z>uj`P3+jWTrB^oG!@$isS1B6MfprCYwjEMwrViL zhrQ3`$)q?%Xe*?`+@|!7;)wt@H~o@4+*FaHB&%xHF+SZ}Sex?KdsE?pfyUcqifLcl z={H5&3E`t%k|+HOf$f86S{d#Ju{&PNm291|2|QM;_AzEJQC6#!^S$ZKu$so!+be0k zE9f(-mtPP&n*2c-l53xe+9K8Ul-kDVsh(PyyZSdyrRpZO+)#?yzBEu#TcpCgCiE8F zxe#{x%|))lA0;(BITQO;q@+H@F725}?R(0rLR1JRGjs^N%_|@2M?9JkP%6+$Lg62piX46gK zz1XWB;c|%Kj*5~D>fOUwv{zNF&ZTdrb$j|59elhsTezNuw&Sz`Z1x~urT2!-0-{G! zFJtqLwY7SizL`qPJ&f1;`D)vb>20N!ieT4E%~XaIi&0T_qzXON!?-L+(!x*anwM(Q zmwkvoqzv6vR7Kg53bXi-_s-w}tiKd5cSuZEC(MmB=2gY2=c8Sl zqFZIg{OZq+k1HrQN;<3}6>2LYI{6P}*RQ%NLr2XL5Xf(l-7w?S1p(TN0zZhy^D9Hy z#L2ytE33P!s4Y?@6&+@rm|)VPmgp9f*e1hRo^Hv?$=!A;mSDzS%vnSklm-w?izcI zV4WH~lLMQ^35f8w(Z=RC0yN8oU#1yLqm1KYP1@GEdh4EhJc8vp<*$6*X;e{Lq%zKo zGF~p&Kzk9Qw^eQO*z$Q7r&Jr4L(m+lFxL}V;wTsEp)M1oUtN<_lmunJdTXq4%hiTj z`|`Slw`Kj2YS!}N2+!Q#~Ay)Y^J%r(c3C|*GQJXVjZQ)VmlROM=H!yMRuGTqgagwGo_Qo+p5ba z#T&2J3(+=w&TdAja*rHm{GQraTNtJ5(Vh@T|EeGjTGm!YD%4g)EdEaK$_Dh4x4-ca z5Xf(L^LS%wtLEB_-8zrWy<=GR!aHOssGy44BGr-F@kSmIs(l=)BT^D#nA5oTa&7k~ zR@4@$#9YM_f5xzSGp@;lUfi}K6=oq85r^8uu!RrL`o|BdCbU)L?RewlGQnB}zZ~Yh zcgGt83$)M@Ug*9C_QA1i_U9tM#{=e=x zsVE7`K5IaN@xbU-TJ`R_@5ihkv8;BLrzq(=x%>?`JD*aKoJDd@R9eH@3C5 zxSEcbT;0N!uPH7&E`4N0*^z36cY<+ljyBq^0y;uzV`2SThRA01j1^@^D$L$YXSk9U zmfb0z|IOTAtSAY}UhQ;(v0$w>n(464V;SYZ&SO7Wn%4QQfHEr^wGT-ohFOoRt>ZU$Ua?NVOq_^av#1^F=x$atFQPKDL^?|MWp2cQne5 zI+0)BbPH48<@WbFb;XL3pzPt<$UFW<8?DbToyXHn7IvaXBdN)aQvxE_j|AhTieZ}R zYfkgkuL;HxL&7w-_d259J_~btv_$ehaMX&jBh_un9qyDGroDKfBMu+4umR6LNlWjg zS~2f6=ED{>&m=_TiCX^4R%BRF5|sUA$wcE&`!H>*yY6#$;|#sWn$1hfKUEVD-HGaU zNSM~NTrTq&`rT}9nD(%Yj+k_gTK9aC)cbXs6=g@Nx}_71`)`D4v88oHsq+@raO@fB zIat^7k^KidM8Q+~fq)Yd$0-|lD zM59ZKFl`}GJ+GW-tWUn2X;}!%O$$pjPLrB;uv$@eq>8MXXdFzwoDZ@P=Pp_pV;Pc* znkwX>N1a5?eZE+jU#paf?w6HY}HKdS7DMI86N`+|hBYS0G zOMcCejFEe-$Q=VE@^*Sx?L(&&#Lk#iUy-= zFb5??LA%yS!kEg=je4U>Jj1)$0}?N^IyMpyA@jz zW0w$3cNv!~%*#7d`r0j3Xe*Rme664qjS}yU(Cf$*& zR-{5S&SpBj(#o)>hliByl2w==NQG+*S+MTY*v;41|82A?=z-dbi27$OZ2i6rX@RU- zaV0~kaFw7qVOkTrrp=Vrw@ni?M>MXk^pY8^)GzOtsw12F(uv@(p zslLM*VgEoX+=F$GMhh#Qw%z~7hf7x6$xwC?;knqtKIC+e>qKW-ai>SAa2KVljW8u;6`qOcX2RdXN-ZoXS?0aA;>iMK7ZHty zSy=3*5wg8^s_@bVo+k06Mqb4YY4!P4MV{5|rl2`e;c1YvEVUm+Eq zILT*XEuBR-w3EK2+N*fdL)k?{xd*YV$gI6`WcWcV%8n;}`~sj;pBl@iREw4SK6x#i zMUe_m=LUm^cP#Tem0zAx*hNLzkqW>!tZvvFKHFUn%F|*rW3}h_$`atiinYwMle=)oRT)+ zf{+Os?@Pqnk6s<3*qE}iqP(vwe4ir~-dNE2>e6s_bL>;Oc>8g}9RO0{9T45=j~>ca ze0t zL|>_shp>k83MiV-0^v>usqiL@yk5cvu|-4T<#$_ls(2TMH$|czcN_F$&8uc8*DpR2 z@@(U+Bi`td9Vg#Fwr0^xB_U>jin1dW-WnPVRj%}BEo%8HC#G!|Zq<+q?=s0I9MX#g zecL9VXmwk~`#scFM1(f%##VNHp*U`QU`5&S4jJ#3DH3T=Z?>k*Hl^Cfal)M?QsFHw zWnz2ZlgVS-E08Wr}jZ|nIpxg845Z3L5 zo${beL5?@(sI7?Dx~@KZW>=au53^TMcC_7~m4mz{6GPbMTOXCiQ#J{91EfMriovkO zxf%P`YnifVNKTHjBNbYN=yjC>j77SXQt}?Gz|l&AvWtj?`4u+ec12dXTPYP~N86of zi7WD~0UI5kgRL_jP*HZILR%PlC%iYZdr8}rfRp(+%8pcM(<95z!DgFuXxf;gtr=w(5hk+g zmm;hFl7_x2TJq6{0sR9g%YP+T<``F%Y5AWD)^Mak9|ZFEnOJ~zX!JxGx4k+?*^vr8 zBj}5zoPph`(?O}Mw&7^|N7+Tha`~-Np;AXSJ)@C|vZEIY`fC^rMS5muiMf4Poc9;O z0|KegCxmW_`h8b!mHet4`R>b6cBDez7TO0tTv0+(dMNjgcID{rfwGGTpPxsSXO>>< z!mt*?yRYaigdR5(`Lg<&;y#$Mv+mhB%8pd%)nhPZzB#KD9hrk2`4GTScBDdIBZ`pz zv{SjzaEP+0d>@YfHz>P^u$-Kuv?Wg`?{Zy*mtyhl3DMJOUjJ3fkO_@gSW+I2vLhAx zWs%QBvBk>Kk$KtdO^pP%FS0JVB`Xtm_f|UWA1HW*Rd)ysbO`@sGyZ&TLeDC) z0<>^fI(~>`kM=~X=#z$0p-yDAOm3!>^$cN2{Tw+`AsYSU42HE+jmr47PApOm7Cg_8 z3jO`a@AX@4<;S=frS$7zf?pr%A!=@8!{iAcqgY;3l;AaqQlbAH zpPSITk@97fDsJuGE1K2a6se+LC`u)If41IV-@5c#3$|*lGe;^!qpzyLP;$7x)$LkA zR=HEC;LC|r=yOXwxYg6@ULsD(*e?3kq8_5=WhUfQTdy9$M%NlF=z)H(=m|{UYO9>p zd^tkdqLxk^Wk(-j^fsn1`r7vD&H)8jBzZ2Q>_~+k&17Tgd)Hbk(V~>|GUK_rumAcA`Jg_~-I3LtW)O>ty zCmuDs8N2A&L&b;$J?$c%T7JKFGTPl0;8ZPyV#tPd?~%^>Hnh=N7<1I zBdur-RxQYXjIX3Tc^||vIt$~NM9t4Fb?1BQ%k-*MTNNX~Frp46B;Uck24IJp+U&I@C$jeCqo;e8a+O ztV=|Yicx= zRgApFSY(Xtr99hByYTT94l7aJ7pf>bQepfsMK3#aCRUbzpdCtS5Yx`8Y9b5LONMq?8C>cU!{z6nJ7drBLd^O z>4l2Y;e3lrXXV5bn-C$5R2Yj+Z%&@*#LssdBi~>1L&Z3A)JfF5+REO1LgAB2m4_}W zM!#c3KT1gN{B(-oNx`#}PLqbKSb_+Q$fxhxy#0BmUw|@k$4(()9jP!k0Of!%_TtOz z#>n%N?y8t60OROI%`2LQaP{?KWyOO$LY4x|&wv>VDC5cZA>7<*nDWH6mx{6@73Nf+ zECsIz@xDJRDz!3}2ssCk3iCFQ#biNW{-|dKId}gvD&~4XokY#uHjLnxM)p-sOmtE) zp9E&xKnV?o(s_W|2_i7Z1-;MNX#_vq>9y?YH(JOVfmC9KjSOn5PC@BX z#=5maP7c&b)co73(Oi3Kr`UPsP%$G2=1V~d>E37mXzo4on7nI92^C8afmuonhV*Bn z_+Q25$jS{#$l`%im+5d-T#Vkpf`3WVY z+mG3#xq4pm+;c|Aw}c4H+(bEq`dN65E#sw>&v%4eNJxb_qzs0GiiMY`wb1`W&DU1U zD1|zSnqNt?@D-=>$+0!9R+I#F!Yo(x%}JV<2;C)RxSSLanEwhhX_1HNBnv+?wZF7u z%@rXx6;feNFN5J;XA93?p^pE~ttbh~KJ9ISZMC7T zmU3J7Rg+2cQ}-50PW3Yc1m+{d%x2_4x6Q(@-7`x;TTTkO!jKActdUK4k%d1v>ErKF z_o5XuuAxq%=9y&)^&5=|YlqD^t zw)9vNbGIQC=Df@Dnc#I^HTSQ%`6jfWUlxnEB6OxJd|0*Q(OHqY3jdkip`1{2~j6e zb2mcFT6|dYZJ#RSfkdf9J(4Noq7V7|_Oei;$V`H0~__g7NK1C>qfK9#=6!-$w!fDBp7qKbk{!88^V|mTg+QKb%TZ77*f=F zBgG~o0(00R+F)qfc{mGvbjLc!mMBPtFJfR#lwl)d1oMc#B9)prL68a&V#fEvxuaOU zhKcIT9!2$cktqhNyQU7#WyX3jYretob-*b0aC@kFw{Knx+sZ=NJ$>S zzO_$O5C0e0{*9Tk#aUa&Hj@3w$ds-$@1h=DI@Z|dZ2>J;N_O+-Di$NXRci|j z%whh1bZpjdzeD;-W?P?Fwyu~(+CR)$#gf4T6O1v0zM9w0j5QeyeQI}ME!H{8W!%20 zYR;j?V4~`7_+{E@4Kr4v-_h=0O;7r@%HlEVww_UL-L-biG~ki6CcutkNy%M(v#5@H z|1x1s6d~;x!QPjCC*|3nCh+K(5s`&h<7+TqE;K6Zw|z-H9%s?)q3q4PwNf6_Diupm zc9BQqSQEQy@RYwjEzePQ&lYuzcBIE%`wylg0X|tg9HaF}y%Wg+>~eW`xpCLZ97`tO zYmr6uX!Ag_!R0>0dlTPXzHjpYqFne-+{WhXQT7 zBwf~jG}TY;X46~OF7J0!xqQuRdT$nv{7Oxz{$S>XY$m$k2G3K1xoW$ziVccuW?eiAzp%$@mdjziSTDBf~D+EWFhFWzw;F zhpmX{U2bd^)rl@S1vJG+RgK~`6Sqlgu8mi*t_8QEZHd| z^zdAqU>iY_T=C3p?nv2G^%i|`#LkR5kyr7XIPUOsp)??&ri6$kFaJgipCzIVhT`vI z`GZXhrEEuj$q$x~v+1*_t_Cz{fJ(_tKh6g4SkMYJL=Hu5R0(Cu(Ww@H#Y`z$v{~p{#e;aUhzT8S& zo`KS=)L4ckWoP6M(9!R96ft8>lr_6%AwICf4e9ps=B#m<{I*F%l~|#$d3aKuEU8@1 z7BWBVT{G+VppW|71Nmw-Vn7%H{pY!`lDNIjQ=NIEG`% zw6Rdu=sTelF{6a^McDYp^%w3Et-Y4uT_Y6q-R^J1bdB@zLpy*%qT?PX>ue`m#S$6{SCLnO|mol3aS*_ zsH4E6l;@Q!s@@k1n?*$65P$ai>=Q|<<0WYBvt7=TZbz?Z%k!k_F7(+LAm4jGHyh(cL>c+4H z-!#FR$ckLXmtFt%%|G-?4M7il!3Ez?A$zU8iS21nTvAVpud5(Gl#t$0wC~LlYP6Cn z47j1-$UsT(6%>P^c~T#C!{*G+HmiPYSj%OFzDh6H#!kQ?9 z!2aPZVL=h8Z2WXVDtxa9UqPWvh3%u+Vb8A8*lf|lD@r(yMX6ftk7G%%J4sz>wBy)C zg!uAF?8DK_IU$EsBEm7!nbt*Rkx=%{VFdd4mvFgt0jyVopj7 zyOGjTGK9Jd5j+_AA|m1=V%gYNC8YQf&cgQ~_8PvMV=#>Nj$?%%@08BWT`at)gKZ`9 z2pKVeonBE^F66EWJTPto<0&ZDWZ)*4-69!7|nB4$Yrs9(QvlCV-KmEU$PJ@ zgYhP!R1u?wupC3kGi~AqAu0u>5)s+G+Orp>>&rgva&i1p#CQXYLm+ELa9P~U^+4J@;jIvxfjp2mMOwU3*aW9E`O~?|!dEJK;EVZ|u3T%) z5@+m{IxNg5AW(LUL!j8c;|}KW$TUByd9z2idP{dx{DkjXlmvb2 z=>+i7fgQd&K#srBns-}RC~Kz=v3oD%QWLYJ^}h2%IZ(B8E8^658tX$nYRb^j3g~(m3GRG41r^lKox@LD7_Uu@9x%{C9 zg4aEIu8WBFJLv^X|0#0MTm87>-kVux!wW6m2$=)LoPeSCw=19H=E-$p2XQPhXY9#B zrw({+!kXy4JMER?RcorO9qGogeb5gbeYwdGU}!$(957NY7S&onU`r#Kax_*htZcrv zRW8>uh8v4d&5~sG;8!N}-^F~L6ie1lQA$`=$OR9K5UVr$d32P#MhJweG z9d+i&ZASIus4cbv`f}6$QF@IMeQCa2W5y7{%NsqSu_p31yfREl*}7e>vMx%<%ZYl3 zh$(|Q$|pN4lk<`tWY_F#S>H9KBVGz#zUVbeJmR)WE9S44R~C%pSTb~qOPc-#QM%Pj z6V^oMl3t3kF#7^I{nRLd2ey^yRXqHTi?XQRO8NO1dTAY66#GC#oQ__sE-Kqr-rRMV zkVklZkHP7>R71Y}#JwOr1e62q}xT z5mA0kRkhKLrE=u_(SqjalZvfCuca;7s#+>6l4sl+#GgL8lGP>;Om9r+{fQow^o~h` z#p?TRv*hZo!+4BuW){N3_S%H?qCYHUH@@{uZBetayt_;fAu~7f!!^kz^5!PYSa5UZrpnldQGC|A>|!h`Ai+-KT%G7*qzr` z9I_By0^gZXD)b|zh>?D7ytd*ew_Myz$SRNguqJA&9@o`A5$mKJWj|EvCT?@`ToE(fnHMEmg{O(+$M`We;CJqOxhw1yuTn7OZse0 zv{ii2T6>heGR+ZSO1!u?jfZ8ITe_s(lZGKBoNVM*t+U9wvDRxjs& z**~0T^y5RjzxSW$a8hWiXWgP~YpLFeYaGo1E<>{Ve85zl$MYFIc+E1^rS5~DDOiI1 zP(r!`I2FhjrFW8c_*N3E8K~3ATftd+6gXXgczliW=Y6^sl@2ubVp!5N&fnILM#;bu zE@rf(P%^81&3KilY|@eKZh}>2PNPmX6Cv&|ayDa4l&5I;H?`7_V)DuYT?DDdO(0WBlam{42{ZWwfX#Ac}OaXKPM8{5)OEW1G=?Ues>K z`sw%WWpkI}bHXc1kGeNzSb{u6JvO$RuYR3YO^)-36s% za({(rhY#p>gUgpbtK+_Z^mjLO6%Z)9L*T9S7t5M!E!*peR|PXw-(S0>{GIwUEI}S< zp`j>7}Wk6bgX%|^7(K?Birs$UE1M>O?Yg-TLJSGk=sLYwzT)NgamSM^JMvVh=&JEUf zP5ZZ_G z2yFT^SlirDmumE^3CgR=Yo+z4MldYdlygsDE-geGeZ$p^mL|&9^Tdt~y5}KzPix1} zy3jB>oALgQ&!sd1Z-HflRwA4ml*DY9)1+p=>FGu`0xpWc`SZ{mBJAw7I=33AC z`na0>?Ywf(?~c^`MIVMG$OC!P_s8pEY>*|l#E&#($Q>;kB4R?zbIRJq8UA~F^<}6n z@GiW5@ zsK$|q3ht@6e~7!mBicFp zRru*2U5F`oX26|O+y}ip;`oY8x^*tM+KRhAo(9B|%uzaDO*EI4@*ejPVjA##B_j4` z4(7G4he-<#ZV{qV@Z^mra|S9o)S zH#!ExxB@#AFW-Lh(ey#W?I7Ny;SC#|+wcESyynNsu4*UYUKH;y#XHOL@5{24c{$avq1_poG@nd-?t?2D7H#`_DoUhu9LZ-?nDy3xd@ZS#|IJ67O$n~hZBU3grR zF6`s*_0s1W--J9xNG0CsZ(lT&h5hI(oo~2G$TWpiqHQ9KEGCbwwWP8G!c?^Opv6Q) zly4cwnv5wZjT}GAiuO9R_MjDrc22TEdXf#Y&Hx|5&WSci(W01eW)O>xb(FkIq$p^k zMO&(98SO>(+JR)RJx%snv`(YF7VX0Z!{^eztP5GHn_R8I&@PXbYSHejdqCVH4~RPC z0f8O@=m8<>QI`BmPRb{xAi7*azXkL!5v5A3*NY99uuGb{>Av7IfoM_lRpc!)>r;lb zyg^67lLNg_#GNxw*O5wD^6@%EK3?cYf<9j2KKO)qIFd(7AM!}SdeI|A+-nWwk#dVX zQpS@<3i{ljM~c|G<7+2cV@qw5%Jz(7=+}e0rMTB_uT_XIB|kEm{K(L!2>r-#Po$TD zwyse(kl)ft@>@b5DD+#xeV6iClINL`JkOHJ^9+5t(DO{(2UpG-#v2`7BrP>AQP5uu zcQSDwEKiRfu~n>O?o&W#f3}(?t|+xY~-oj<~-fnqF8X4^!Kk z5^^Q-FhxI0^e`27&W_~E*@%2OP2|go-k<2pDelf2%J}g&QT64%-Mu;bx8iPzyC|KI zkF{fup18>8>)CPiz(o&ZT!U$pkax7*kxc0qc}Js07CeR`jPvza??qHDvu8!}R~KMX@*0cl2+1ih24U1bVR|T0~$U zVBetkuZX}=f)e6b5D~ZzqE8vF!6E|dMSiH0h(PYB6QV@~N`<2YN6&vFum`bcMFeVy z2;?mw#^A{dS2$exvJhkbug}L|PocKh3IY!U?jL9wLmQib7=vwszV832hXG4)e&DJ>R2lBu#A}%h%vv%F3ucWcmD@L zu>YMOc(TOVCGx;IfivpA=Le2zoF6!*vv~ZG3dbmp_WwkT!4ZdJ7e}bb1IG`J#Q#R% z8jicce~%JeUvZ_zu^_fCuAI2;{!b5%`Q3xKl3@@2cYolTfveAdw=T|3oag`DR#<}C zir#I1_sHKP5oZy$D5Aw4#5O_MaW4@NV{k>r_Cd6OFrd7+`k;Oy0_8<2oby?TF~55d zcQ2F#B@}p!!P5)!!*&x9cq+nnLkR_h0aqNPLNw(<3Z1>T{q(`SYUyq2s-3B83ocI5 z<}F-jlr7u%Ujfs#S6jCl7kG6}JM%tCd)9fA(O{??v2D*KLd2KYreev5bunr4W0SP4 zP1hQ+Cb~UuJ7LdOLWGsvrXtnFC*{*t7EaPCU0m@m#5_~N-p7O}MLdw|>BIhO=e(Gv zy)Ll)Ux@D^33Y!Xkc!X&|9>8jCr$AAEfrFcgaQA5JxFt(-%YL`6h&Z;%t8O1cTq(6pMXH=`71qscI$cxTxBW}=%uQZnaYIuJN7QjOugGbyF5k*R0lU)aP3} zO_V3Q$vkOqRgU!{KSa|=oL7{6xNyrFzP>5t`5BUyns2&Ra^WT;@^k2Rn6FNru05-# z^YCmPuk;`*@2~T29LE*%Lo~h0exxt6J(;IAr}sGZ*FP@~`t+&F6{M-vC zr9Ie{q}@BdhIssP+o2@d4dhLq8icWnBOlRp-`;(t!n#!CmCt%Jw+UU=j(RmstJ{2; z5&5N!^h^6h@37v^SWY}X-gHo0d&lzSEy~FM8ts2(6rxG<9xK&%?JDvE7rp7Vm|6k9 z^+0~Z0@|-VQXom|etaqM*tFk4?bkP!?_69;#`%H#5KWQAGlO{QrtI7;c8Nk72K??1 zH?&@+{8G4db$Q@S$MAQ9M+jzAf&D!QPYf(ewhZ53#61DC< zS{Wu&>tZV+KSYxSt3{^Tm}c#dhw1t}|1++TAGS0_2_5Onr_svL$ZonSj0Wg6L{oHs zu^s9t8j0DS8B`o`$PY&hy#+BVh_9!Wp%|?UII58!qA4H1QwKF8JeHTQUPi{5gZyyh zQ&yF(D^(M%4C82Jz}boX5KXa`M;(-BePVeu%~~q?vtA)ToWT@5K&wyr_7(XHS{ZPa zL4JrPyK~VU%3*4&pEPSp!$0dT@*_R|tV9&sH#3NBqLtxJ%n}7xOXP=W@-{KQpXYz}59Eg{DrL0J=*tego~O3WGhM}1ANe7gGTny9D}T|fU2)Y-*awjx?hIsu zoLiK2qLpDeja^~)f?WpDlqtQ>M7br++N=Ak{(GMP*>`b=qxiwY?#ejVUe;KegE;Sy zAI*>RwE*?roYdLBhK2fb<5fbJP6Hxqp>E6 zaGOw`Z5bY;B=7LkXYHRo6?uq=?PT-%P`tKW;Y>As4*s)40{Zx;(P@!VvUaWDM%r%fA%7zBFzK-(L86$0rgenLdAQ0H(}kanf(@9>z=G>jkX%+9X`swP|sc;u$A=a znpv5Lc8F4D)b|lqQLGoyw8D9o=auF*QQVKp980JN|Jh|=ebis`*sflCxJc=ARbH>T|C5d1>l%Y#*e;)sC`8P!C?D9&AoMh<$)mxOP!= z0gaNg|JUa@8nDkrgiIsx^*>Vm8F7fl5lT60XtcllNAo|U8pkV+V~RMOSe{iK8KeBz z?kCJzVNSqYp%GwmN955&K{0 zC&OQ!1-K6@#{1fw_$T`(tV%?(Cet?{qJ7`T26XG5tSzgc&)Sw_o2f-sNAa#FORIYt zePN?$b`~;jGa`EH!tnuhEXmr0PC8;l*l1pR`)6yp7ll=<3njs^Kqs%B$TJ7M4#N+bp?$$heBYBavvy`SCS_V{ko~&)@ zvDk=cmsMjnB^qXE1#;?$6)zVnk(++1URsDQRoZV2v0hQCLFNXErDsF_dQVY?bs++4 zq7y*9_VRfeFiIyjI`fl6cJbxMI7d9s5tE&#f=fY z^wFO7d$gm3SQD+HtE#Z&^bIm8$e*XXW$=N`lC?vTTa8$+uo4-9HsoN{ZhG=NPIjDT zQQGhMj0miW&h2%}Dc81-;(1zUQ!N=cc_CUEoSezr6nW^FQQ3?08mUeBhgzrkwgJi7%S&60NQLOXdED+F&2Kl4QV~JF*>CiwGY9JY zmi8aSoxc%(s7NRFn@U6+E2*gyb1zRVv|@m;?xG~PqtfYhq*YxtXI<*dLlJs^{LvO$ zK}4Lmx>PMur7Zu@!AIBpk5q`pRh#yxm}Ay*gGO@muV58dXI!;AO}fKMQ9mv2tKZ3Z zS2$zsA2yPg?iQkA3G&05DE@qInl*RZk^HaxEd>O&6{2YlE?lIJe^r(@>gpr371k>v z`oteq1ANY<9v$9aIG5nACTdQ7IOY!Z`CaNk>?s_T#N*HC`Mb|Y|KGU67DY+^7vV=^ z*PF&JA^yxL>cKxJa_mjI%b3|j+1V?KH!f0H#d(1BqJ-qpI5QtR9_Yp+niLjzAOdTm zR~MdCV>4IvPko|F9OpAih0;>2rSDip-#J^-&WURV){8UPU~s-3$mFUO`S-T7t+*N> z0&B`T0kGdE09^Y}Lad2$vHE%`m1*Y;r=1hmSF9ITJA1?SOT2@s?Z4l_X(5`*I@D&o!wp5ch2IpbK+iv_2SN8Fw}U|UU9pr@T2p}3Ogqv zuqJxj>G>Mv@&BCwa8E@EalfJrX7$=z@6pcbM>{9hg*zwi^K|z*uCcn;)R13TQk3D2 zjA)V&&LvA=g=37`s{08lDKlT>i_iOzIU^_|m=c22AdCBZWhy>??X@Xx0j^D9^P zC|DPwsW;&a7j-0%-=P!0bvgmy2?^2EgK$oi^EFiUoimVjPOJ+h!Sf?UjC`)d`HcYH z>ribg)`e&q`EcH)69BJICxB==0pMv8(KOoOOkL8mf;uyG6rW%Ei*VjWNpRJsm#q)w zH`wRN6BfCv*(cW3SB5`dqlgw)QP*j0*v?A!e2L|pYoY}L1w6o>7d!;WXto7hcfA#wN zD7~Cq?tc&gKPxK#ru*}D?KYY2%m`Nx9QZBOmLGv?(H1jwUbKw*q(@z~>Zh6dmb4Ny zt4*ElplWU*L<-a+K;>qt@!k6VZC; zlbXb%-E>7+z0{45Ja^NCwO(y%t@c;E3EMTj@5r!sSj2fuXs zfhnYZ3$=2WXuW){4r;$vE!EQhMC%on)>ET)wo=f_({yf9&{?R^8(ciCp>X<38+2a)AdHKp=#U;f@H ztBka;9b(I8)+?_p3{!d3^qZ!A6MWPnQ)lYUD+Z{@19?l*@e@UrR-R3`?sQ*}s();4 zwdJ81y488Qij*X2??hQi?q8XY%b#LGi$i-Ab@d{kwvy|j7yp_2q6ur^h!RI_$EF|T z9H+bS_EqWoj4*FCV9iYZ>-_p^>2W303yorRUTmRyW8yFK?$dGl#>*Q?yT3k{Q})EG zyu;Uf0s>{nHqkyqp<;^9+hAU@*8>xlAP?kC-;$lmqAY&bfwwO4*tBKW8}lXCc>QCE zt?IUi+12oDvu)#i{_<+-@vpJE=gO)i)sEFUmCz+^dD)-~CahKBR1I~+%UHeD%yO!T z@MxAx`7yN(k3RX?geB&#)z#D^v3jwy9xC#dq!qmiDJ`R#@s)#e$XE+y7ZE=3uFB?I zludpuQIM)~p}J~eDOPWKpoE&Hd#Gn-$Le)n{!Q)p*r&Ym?1Gt}8vVh9UJbn+qUn1z z*X+u^7VUYC{O?Ryf?DW&(OunmF5ad$(k>xx5n>P_uq5V*N&Ry2w--f9bo*Y>>`Ina z?RkL$A`e8MwDhILg96IiaxJ;jt-U5}A@&DKNG~;A*(kf04(IU?ADK?nOEUK;JJ%-f zj5tYM-r;wji`soO_?)~gyg$8T`j22Giq{GA(x35q$^Z7MNQu5Ue6vw*-!PmW$Z14XJim*|x|~UT^b7LswS2uHuI8vKH%;pkHZ!P#t^vKkKH7@%qb6#`(GWCY~J{ zID)qubyGkfT}0FEVmCLks+Gd|k%R{(q(%Lq+4}=|OHz8+SN3IgS3We?Efdy4^!QV6 ztWxQC{bV=Wss6Q%%%@^F&+YNhge7DdnthxjB}uCCFo=8oQ;gSt_sf{iHG3q}>!1Ew z-Dgqyk~U@4`dP+n%hIRll{Y=7NT$_-c6@0KXTIk9855RlGR0|chyIRzC=Sx>aS)yS z)XvT;j%m;TY5d4kR`<|u)9Bnmqm!&%vyTrNH`<>Obz))(eyd(%9+&#egtZV&BTBQ6 zdE1EMFrpkKG>SBPB!iSBX-;|pezkl{o_v3=;Y%F)p%JCoJsk3rq{1HAxkT+qq;{aZ zh!zpwKIP)MinrktXMGa-gS?$)_le7wSJMo?yL5%&cb_-N%8Mp-;7J1>ny>_UV9!!^ z!rnr>Z@XrESzvY4S|983 zl#fqMShA*4pw?tXj6Um4WA*jZ23o|882!KpBlc{!Py7MzbvdD;d;ZHYc51X#9 z{aIg)I2feO?i!g zY-@i$bDkTY)NY#z=~Aqv*;f$eHLbO~`=a&OhQ``pXsnt4h^WAmqA!}T1o zvFO$+Jb0BKf8h4Wgce8fu4a#^MX6}5#*MXF8Ct8+noP5=?$Ez(Fzi2AzDQEN#!gzM@I66YtEVcBF)}s?k4J^W*%32 z)=fIRSWnbzCLdSDojYSkaq8JfzS;e#2}^J{5-CyEWMnJLobvQm-16I|hJ&4~7uOTr za>s?;bEG6mojzZ&e6vpAeb28Ec=YIT?Qo8LiTa0S$5o_6^I+0cOG2$k9#G(4A!fim zD{)s%cFx93b;k1+x$c{=1fvX$KImP`OIcX7-*}#Rd%A$YJw!y4UCm0j^wh@l;M0#y zU-DNy+=|b$#c*93_o#L8;qTwLmqj<}>`b@Ryg#1TzkJ(-vhR6T)>^UkZ^Vf+M-KbN z|NbpW1@@*}$`NAb{~&$^nXUi&{H}#)LhMSn)F6b{{~$bT^s^?p{6-*}-j&&wZjlKw z|B@&b>Icyj`)o+Jv?9bOLZG~;1#BPP1Rb;?bvb=+S@F(26Y2zOA)4MkD^!WSI5du@ zk60zx74`x4jZM2I(5~ZrkR83K& z@>tR?(jtwT?frq2=I$Gt_0WG?2ApSX>eJD66ynY?w}SU&HfpKuzE{E!kw84*`a zSr1O&ackC_kQVYt>~YQC?pNqugAw~pb+SbA+MRcq@T>@H4XK;tZ}*QBz1F+!S73A` zPgrx+geBzF9Or6CiEjD7{nPJra3s&_l5Rq}SPP~7eU4-IyXarh?;<~n8KiP1!?({T z-;O0HAyT5`H8*FIkvsOFsNE7tQ%#274J5ydeT$YTt_QzuOE)QG?F+~= zpoL>CMAQ9n!}eQVP=9PHvCD+>63zzHKF6sn-A>u8Jb%?k&zJkO(a$0}%&a2c-X~TbMMN@IN z*3`V2>YFD<|FK3>~5jXx*Dz5EnV+_ z5XDM2l^0YR&S$=gU}I)9RUhSz(eryLYQ<;G)y~(W^)|cfs;7svP~EOY>y~eIiAU|W z!E&2w!};`@qZpPTKcqx4^~2oCkb`YG+g@I12kskxD%M0DWs1=+1qBd~(eLsohjO&# zPjVhj!4l+w8j+;5O+oVg#>2VObFm$WSid${t*gf9Ykt%x9&4rr%I#VV=ludkF{~B$ zAXrT{$LMZl15^>w`eL9wtnF}qeD6qxCFRNls{!?6^jdrCt76NqtjVqPdf1kK4EZY+ z+krfgH|^p~Y$89cFr0s0K2p#w_MnKUJ0qWx{;4&u@Zm}dS_AIsi@J*aRzS(opcTK@ zvvVr$t9$qcsbl)b=m9SpswgeJ)%Yn^KJ#-h_qjWsVJ*w@#%iX4F?#>7hX13h@*}&* zQ@0P{)+z~tuCV1uiQcK69%s3~tq*_M=MF=MDwR8c~jollll9=DbG)N-K=&m)>N3sBE}kJ0C) zHdaL*6UXnD>qbj_PS z4Sg>E{W%jqdB#`J6}A@JM=|xKib`&};s5obMht6VZ=w$APL6veP2Wd7XH$yz;;47D z7?hCSMCuwTkM^p?n~bc^kq6d7G~G3+mr&MM3FHSpbGOWA<>8fDso!Yco*nJ3 zVy&rRE!Ax)(R%x024dru3OvZIGebdp=B*Vjes6SLG(krLgeTS`)%yzRsf&2*Mgc05bneyo++V{f!B z%`tYoKE@YhRrihI=Vn!vQ4(y2h*+9e;!S6D;&D$335aCgQhiKxw+!`E$6arso+AlY zwlH{P>z+?p6W*G?|0~LblHh6YjAE_S7OBy?Qr|cY{}N#J`#ESL-`jMO1?i$BBEor0 zU6!nm;R_?b3W)jLTB>IbN9(OV`>5O2v`{0cKU$~y5Rbdvp0XZsU3u{wZ5fsfxY9x` zupwH1I>}Q--h{Z3M~N-gmd|`)sfV)T?2NOvBsov0E0@bRlD}x)hM~L|0btxk8NUVc zC_fgr<+VH;`XK`8B3hC{3fGqRb)~l^#;Xili*zvpq`CInbxZWSA-wd(%?wLW3rLB^ zN75vDum1>sV^>8XlEGRiEqy;&xR6pftR)|M^sFDsjF@uDn`mTZVmr zwj}mP&e}cYpVvooIc>EC>7rC3;$^YSN|~h2e8<2dCPbiJp@q_05TP~sjiGY>h>1y0g8rj2+qd4>hs zR>|lM`nj}FQ^|HuN4fuxXGobom{khs&j-xgBaB+~ALz&E#gMJn9+GD?EA z&{xvg#E{C#U1rf*%{7U2xvQ#khsNl|cQjIKj`C3_c8t-VENh@HnBlJWeiyArUiG6f z*r{KLk24|qmPle1QfjGpM?~u>-)gBLp>@>(rK5GPlq%{M=Z0$MveCNBqbh{Rv194} z`}Bo$9r~Ia5jdA1Z%OJ_Z|lCwgzzby#E@3v_-5+fG12<@KDAY(MCY{=$0gS$sUnMu zJa9dL{3Jlckw@18gM6MPg!9>Dl7umcJVeCW`ffh!sU7k3bFA@j%k#dgDNIgrx>BPi$z1$_Z5npo7nWI$557Bh{Uf)5=rx=~> zJmhNmXPmoQa$>Z;y=E;H`Mq3PLv2V|Psg_!R#J8SzjDx{ZamMVIHAvxAEN1O`{Liq z`PxPJuz}f>(XV{ffO66LttORK&JMmy^V&t?1Bl*rd-&4{0P`ikx zD5KSY)RTLv@VQJ@%Fb@6_O1}Ej~Q24MSdO!ebuiGqxI@dDiM!+BTlB|8a0uZOPOjy zOGJK%rjwuc@od`l2rd^WX+gU}H1ei*mp+x?1tZ+}{z(sI^ajTdH&?qx(cZ$^TB?Y6 z`cG-j=ezK_ahZj796Qxet=>3V?=!xVij-*I=c~%gy)DnbG>SJNUG$0QD`__99Kf9t z^YQpqD`iBW??N=i)K8LGO85XidSI|Hq7aR<1f9q%*v(#92k`q9ItcRz&T6PbNqX7m zKg%y&=B@Ko;y5NSLdM9M&Qg!KS*|VW&-Y$R6FeMx14K*Gw7ah?MW4$2)^j(GV-4xz znt{F^uykamsOhZ4>u_N;f$JTlMETTz`O5>9@|NxLIF4&49I4_MtkHg$<^8j*mNDxi z1*vegg_LO2eyS>;ex8%f{5XaqEtEt=e3&xKGVaAzOB3ROvLg>fOHx9%|17SFG7k%; z6*sKIu@?3d%?8twEY)s@^UTLL3Nak|U9r#0&e_bSb_?ax%XegGqi9QLW0JJ2c>sSg zFCPy&zET)bXuBd}k{Zt{-iqKa_LQ{XSi@SPRQXz-O7R#uk^7g6GNA`RG>&;XY3Ms3 z_0p~?ywzb@K`(=&7SZ&*^U4_6d*Mi)yUveP^km2nJ&`2UB`^Acyl89kqUbG=AEGHI zb@RXS)Q8=8m&iDV9vS(eN2Ra(`wUXN<8^lVw5tWZKJr5}tx~J6m+Log#3!C{7Az6@ z;mkn0gEXr>p;_$)&1yI%kRPHYsn5x!rqpC#e&X+%!uUYT#~F^kKaVfX2aVatihcA{ zFs4G!8T+WA+ShxAK5JoFnhin@+_4l-@#Xs4>I%kGh@QWxks8o=h8`AbAWWU#%F8D< z=bIMp6jrH-ZaXkgo!e@LKJsoELfmxqw4D33ncejssvs?tq|gjs^?LeDT`?KihF@Lg z%VxS)c3M_H1!*Dr(Rp9B(3_ch+3SB1!gX>{#W%OgKlX`}5fSZFS3UoArv9V#U;mS{ z?V6*ga(RKueTT%#SPL@@F}sm6wytJZe&pTH!afBk$Q@<(zT=_p2#?jL{Z)#j%J;p5 z(tC12zJ5|}1$iLa{k4axM#kzDPL?D@Uf0sf=jru$=dCkjlmyY2A9|>BXT<6=dKicW zof<3qiZ5mlTIN)c7D}?CUrqHr<&NgAWW2jwV!FR_wsCgeZR<%HX(2kcc};a$TC868 zXE{PV*DERchu7il8+DN}YZB2XU2CeL_ha?Y69%IH*&#~khA8&)Rk-}HZFP0g%~(C} z{HiL_6{RY(shzTGkrS^oxS5Q!5P_8F+@O68rFoJMU!US4W2P+Tav~-2?ajt2Ggh`> zcTNXeHk7EL`mBl7j|F+CNO#tV>guJFv3l7VMjqMpaov?-M?SFTsTce*=dP{}q@3M# z%c=?pq$EiZJ8LQXvitClxwe@w8y6)+N^~}HrnjO!aAQx{C1#-*_wAUO`qg5pigbsS zsi6*xi`91)^f0vBsf*%S?j@^VrvqzqrMh}?U##9O&O<;TC5nB*J(Qety?L!J@9W{Y z6H17bBq__b%*uypQI^nWorIlKq+2?`TfH1IQxDe6Bvq0ReGBmRHamJRzpz^?pYT=_ z=gicn>#B-qie6*uD0x>_;uTMHVYvT^JDZrlElF9uyp@f4Yw`4uZx$>;9!QB!0Ty{G z9p2aGEyuqW5U2%2Q>6c?w30Pw3{&!&ILeEAx+0JD7h~jwIiutYI|p;r3C1FbrqiW# zRoUTRfxp^5)`EIRNl-$1V|{XO#c%OsmY9tTR)PqmME3!_4px4wXe#ghP=KTTpoG{y zIt_p0qZCYc=fx(hF`bQ-p#p7%WN`+|j+VncGS1Bd@oXjWQiV%D|N`mtWeW{oHx3Vs&Bp-R@vy8M*5}bYL zUF5;}l_i%SvWI)3OSmWhr*M8@ zu0=^i#GK(n$g`>tg=7Dt z)+Oob`#@!D*8wbiOd$b*c8qB9)PCbqO%L}ote%JE!$s`#y ziY*rr2dK{jsn54ipJU%*-(YXjIM35uwk%yMul+GdK%kZ2>?28I-sRy3DFfm$Wk6td zG@box_S_FT&C>qlOk7%%oA;qy1LtmkrD82Q|I+OF3?ica#Xx4{GaRLS2HHc^?71Jb zGojh@8R(2n`;#+qWm6EdXIWqg@G7(W4C?*?YAgW~fK?Yo$HfAFZbq_c1br9MVeC#Y**=>*P`Vp>GX_ zwMNZvsjWH`t-rnMZDa_6cAM<1#$HLIdHd>h1zlmwkrKW0v!}h>cuy$L>9vU=-NfT9 zv?05r^_J_sjf^CRrfJu?i4)&4s|z=sZ!Tor=RMU*bE3TY`i(qQk;k^~`I-OF3A|d{ zlZTK8)sVE`k zo^QL!&V+X3;YSAwnf)|dYW7oWkw?QLedJr^`|_5v4jX6Nj#@NZYW7oW4-bCJ#^wYyrt{E_f5A-N3@W5J#rnTCZAFOia&V2joA~ISAelda) z(t2=Jlw7v{aQ>}YErwQ&V-QCHWyGJ*Qo0SB$SY)-Zb2R>iHO+aoQqd3*^YPYw$Oy* z4m}Y{C`rZqtFqCJM)QO@UdEZ1!vmnl5qV@u%FUIlZFxfe5q{`#(5oSDNm@=`bngDP zyi#&Y|_+mZ&@m@nCH_Gwt3VzelU_}G%`!zZX`=>E^hNEAf zvAp{-^9y0V#%f!$XHa3SLT>}KJd~Fe_t`jCtA66HrE!xxmXFWI8!LLvojOAU`4=ieGcLAYhYozsF9;4T2 z7pU$IY^XJwNjaBajSRYv$BJ^dyG?oa=~XQ#34X^k#vG)j^o!Bc?i(kHHT(8vSFU&9 z6TW_ANEam$5#M@+Sq}AS%10F}#t|`MLu0M;fEfK`pN8tkUx8Y6$~=6S-QeNhELg6% zsu~|&*qdWX`uK)g1Iqs6X^m8*M7Li=<>hS`wBa}R>`6u0adyU8o9<%0*_qA#X9)LQ z8qZK(i~uk)ptZrhyu4J4HvDtJOR0!Jx`-w(I;j_{*eQ%JsxgmYYmqKSfOHev`spUM zL|MbMx$`Ko)7LXEsP5vW}^`v~!q07b!kqp*CX=&G>TtU9Oaw}fwRdXSd!CI(8 z$~A}zmXEHh#{F}9bL<1OC9ywt1#DpEiRoj}!IqBX8PFThnnSZ^O^Tjj)RcW}!UKtS+SgbZwO9-N80Eb#D$U1D zkontsp$sL#TIefnSr%UQEDJi}(d?NVbk3#Ovn=QYOZ$__LHP{H_Iw69)zj?RB8aAQ z9PLlG2xVD#70$@Az*;z$AU`@Qa;fZNWTY&oj1;6rXE&NXBL#WW4S&Z&lb=yu#$3wF zKpwarKz@W6veetiNb#nO6r_ct3n|gday!TQc#>2TDZd13ArBF;Dmo zo+l$B>IKBhmu^PzsM94ah(P_&d8B5~2_Rq6dVt?)I#KLICyI2cr`dBR=oC@2=Qhw< zU9;x|Q1(vz$$Hi4)bd}qC=*J8{18q1q8I<>pXo%gEuARRsh(!f{Xl-Sy4U{XOsrWE z!&=g*U5)i@2c24`oOU*HaU9l%{18nq z#hzPg$#uY&cc3#!v@1j-Z(4bMs>)7foYA8^VM2 ziFTcnLgcbz<5SYcfC5jXODXnOfz2i&SJGgejkt&YCzw5}#sB(q*qO#kJTpWi7z||H~vgH&h`7?5g zkQSmvgpZG`TqPb2D$uSotW1#yqUqa=!w2LvmjQgl)n>wq1#4kHNm2`s@}|BgDFZuq z8pD1@k1F$$~JVtJ&IS>u>r(RM||!?dNA zoV$Jb2Fkg^5rwrxsfyNF&ze#OUHS9QM$VnXUm+UDye&(QZzu0_le`al8635UmZaeI z|FTY$K{tG2979ir{LmB8x5#}5@ynE@H-@`f&|4xuMAQ0wZ4A>XgD%ta@2TjKkso?g zNoq*5!C9IO!f7@@uaEo?P1%NZPt|jx47#>_stGL-`Qgk!IrM!7_#LJ!y~UKJhhqZy zA)4-{Y7;MKyAi?Dvz4@<^&vl;;m9XmjA08h&LAhGuZW;CNX>r2D}K*Or?0$y#_228qO(oMeJLWM*6U#Y zg-$IG(WxbJN7-p#T>Enx?vdDszZfuqExMP&kO!jaL{YP!_R|hzy2_2yS5Bv|C<&tJ z1XHu0tJ6utZOWxi8(^7qVUdwJ;Gl()EE!Q7w>0_oGsnJD(Qm#Sa9y%6O9wqUi)v z`;+@I_Cg@PNm)qW?q^eGzVgtTQ+CTN%5FirqEv^nC_JQkZhko3YMiAyXdwbA(f!n0 zD)JyYeI5I}g^YIv;Vm~viSF16&(E7*e8^_^u4SAkYWCbAq`Tm@hn7OwJI`&|J6_pK z@q-Wk=6$AqlB+%R(AHAU%~#5~K?G8wD}lXBaXRAVV|av-z2mq&2_-~Iv`0342%AQy zmSyPFlFkG*d!7~2rSmWCPi|E8w)feNv$grY0{M-cBF&!Ngb1WW_eNdH$NlK^bsn9* z(n+Oe&&;B8PRBhg_BMK2niS9$bk)02A-p@9F3{Y^ap@eA1ln-~f60bbE4j)>( zi{KfME{-nBxeM^;6NY8yzkE;0I8qTIdWQF18}oi87PB)=avE6{4sVGPA|+}^yBhoi zWuAS|Tm-4m`=GC+%$h9i`OFSZ-1Bvik^ABBuP6z6R5~jDzW*ESQC5k)#t5-T6M}k1VBpq94*iG|oQsVo0;G{3B)11*{IX z;4Fh^oZ)PlXWYm<>(%YOFb|?6I0s8os7q&F;K(cXBe)MkS||z5)O26}ncn;;WzgND z3_6^V5slG+B)P@b;dv=X`v({BFDDO{1s); z4WJAF4-E5rS`i$%Zj14hn#1TyIn0&9yn`C4sV8n`O99^_Zr8@`LHcDZp zGpgVj(Atp_?a-f!o7|55Ao%T8n0k9XZ8#TjB#=OAtETVhEL7NticjQAa7e{4Yz03pd?re+ehEZd=BJI z+7Dn(5rqT~hb{&0^x7cggo3^YMMWL*hFv@yC1X>BsK9bb@XOKK4z6k$2 zHBhOx^qT*%b&2|wH^qhW!5qmx~^ zd8a59>gwZ5fA2}>5_O-uhOVaM$!?k(6vmHtIwYfhuucD{X74>W67}WGK#Z>!n7VMW zE8lgji83ck(qX&av6jfAe2(mv0dg4sw&;+I_xs@8M2M#BwmjJ_cB!xg`5`4b`56|N zI*MBEPc298$;mqo+pPrA^wn>U?50qX>MKcwJWwjsh$M}w7wETuTE3H7jyw>JdZS%u zzS)vm+m+{+nkYY)Tsv%xkE=93s;#_s*gif)sSb`gZ0SOl=t-7{C5XU#k?8xV^Fi$W zts*>nN}#~w;3Fri-AevB;$$_(U}oDG+#wfdh9zDnOGLU@OT2xr!&X-|k49~88nsx0 zk{~6zsqjY-8#Jp3|9LP_LAqEAHA3GTygzKYM5ES^MlI6CenySZc~tF9mhI#j&XH%p z66|x4hjGi+ukp$3_0KTH7!w0VkxmAjPz{9rH}1Pun>{QqAu_#kvKms&C#le`MC~rKW@A2wU6>EG z14~eENQrK`-8928gWBN~5%&KO_EC#y`UdM}*L`~u!xi=KB-yQLoLcVL1pV0AqUQJG z-&Ps6xU25IXoa>^-ecYKZ-{>9*FueM{yJa6D}@k+34tZOH&@XzH}0t~zZ#_>C0cns z+~IYa5Ig=#l9BGv&Y|k-1O4oxc6AzRs z$vRW5y)aDwI3kmV5*oHHN&5*=>wgeP_k8ReHKg81{nj&IE3H4=-S=!EL^vUCe3@?@ z6O*8qa$|xeidItS{fvD(3DN9-T7IC|8*BGRak}EUO`Yeu+uEXhg5Kr&L2CKji>3E3 zB*cyXLG-QUrrobIQ$KqwLC_n$MAN&N_c20TCtaa-2X`5-m0L1Jzh3%<`R&F|+Uv^G z^}QX9Te+Ne_S(0J5Tl6)YLs-P*>#0lpnadQeQZ`zkPxU7)GlhBvhJs^-MgK5gb;#g zX?9Ee8jxGrHwF0*~yiMlG= zx2V@XLKv2)_GqCVDju!-Wb3GsrZv0up$;X9pY`=VNr>ab1GTuUte2`ZpP?7vQL2b= zKODb*4k6zEPk&Usdfe=)#q00a>{Fvw{4(!Ih|?3pH&M%tKf~I?2!VP>kAps#_S?61 zO#VRq(V|R}jI|K`>iS4)_Qwf&U2lzexL0oNWg#B9i3jQ(tsVPGk~$Bnvu_6>IuQa( zu(jAXbc^8kX?qNxC=&uTTC3w&waMiv`u&KHWnZSg)uh{J@y64b(^m9x!fRwd{&Yjct+^VWgh1!sjT?j@3B)H}{H z*iYn33NG-zL_8)D5A+#0K9HXz4IEf$?=C_#pq8UfP`jvgT5a#|ko-3xMv`{XUQt)r zKFXOWV&1=+5Sxexw$N$aakIA`uQy5B_dnKNt45Q3j1V~pf&LXOQEW$>Q%^ki62hAh z*i+c&VmnSBtGK@+AsSFS&_^L%JP#3%Vk8xM zXOx5xV7rg^zLv+go6lTg+A1gsN@&gB)ZDvCqCTwI5wa3?f2*8r#6jk=Bt*e@2Wugk z)*rdH%F5vFtY)Ix}Q9+~SKc~z^O%=)~!@|WvS^Sh#n`rVwGigb~m zB(>S|S~fpk#mWzAtzZf24JpxAba{f5YKyzF>m>>)I8t#0*Zum->}!eBKjbvLXr>Kb zN{)U5*s`5f6s(2q2;OU_};IRImi;A|*-MRIIq7rYvXQ z7W*kk7xjjeB*~*oPsMd|C3fP>9T~?Rj>i!_ywqb8X6VCwqev>fR0rh~efPS~_q$wY zPYLylPplpnuu#QXh^Bqf;vJM9kId|8A4$OyoUf1)O*h4Zl;)R)v%44bD+QF?YMugd zdcT#cRIG()%H_-+q}(~uj}53?P{9)H8>B=lmH`8mhLOeDB|5akv5jN?#K0D6bhBvv zOT!M-@+l!bmDL4&*w69~gro`ld;6D!B}-&zNz}~ z{vXUpiB6Hfg((}R=Vq%GY!(pcwLMY?s{=1PJIQp@M|9jLfPlwsBm7J0$2fokJp zQF@b6rB$qjXi0k0bD(nlL}}JJ(IU(SsA;4`XGJ8HcR(IiF>JGpbg>=SK01}j8le;_ z@xrpeB}UMd)HqH(8WO30`dic+%^&>+Dyt8bX1B&!Wb8GR1SO;_?*ToPk3N-I^N2e# zS~&I^_9kU{R|!%kME7IWeicw~q@wkqRnonj-(8i@XV$VNz3VCHqj1!U9?rYN8`*j3 zDwdY1wSwLmeH8jGTHlNaSNyw;V7ns63%Ww>&X&ijU0tT?nN;JYzk+#sD8-6DVJ|I3 z`jAYEJ3MIS{fgEh_brT26pC< zMc{!}i8e;LwP(93No{trGKCHb-pAa=ORX?{hOShOQbit3U1X))=kmN+)p`OCM2K(E zExOoB`H=M(dlZo-SUdXN_iIb2f16|V6}61DTIiSRO6CckeDj>4$_I`f(vpbVaMl^tpMQO1%3SAUrc zACJ=?yx*vbJlugRYp zu&^S1;bIq?3b@IF6z4^nsYhN6lYO=pg=+wD0^@yRDxJJ!Nkn_g<#T2?9Wj@|$*HC;x!=;1_PvdAky>0JIMlUuwOybsbv zev-6sw3pJ{xe7Pu8ZP)m^v>uX>7LXht(D#LQrT(cn&7Xn7RD=-xm>rQQsG5WzW;uA z8R_DzCe9xNk9JkEUD(Owe+~#U4$?(_6j|PFt2~L%#DfpE6y`yk&v8zq^TF+Xm2ECd znQ!_EA+p4IP?T!#*sjXxH?P>MEPgV^1{hh0JTh$@q$m-S*@J3xWUPg;4@LvD>pZo; zlJ_iUd2Yx84}94HVNiwreyknK-6l%lfwjaae8jh5{Oqx>mLn7A$+%C2>wZFL z_7wnq$(l8S=cRae9>u#@i{f3)9`A~XqG`SP*n~1{mI|?94fG!m_E_nSqn_ zt#7xPu@<5!r|8`&;!WmuDdZFAIB?sA;4mNgoobb8n~VtkLzF3hqtgo^|!cZ>$B1#Oq7%Y$d5~K5fWn zb?wbg>@K2UEj%%q(!ZFNHZWG760w*NmnU}M^?tNw?=F3lua|MtZimj)n~qITu@<5! z%2?KcpT88$)UrQhEJ3{?C2IM}hJ4Q5VQlnJ7X|5}>?o}yEn1a}-@m$ut(X|7;9eN+ z$+Wo^+WL01(%EjZlEM=YY1uFI5 z&A0YVPSEq-wWwGN(e!H1%3QpCu_es4exQOSs0E}%H>JN|EcntEHhq0p1?l36BJSKu z(w^D5`0SEP*y`Xw1@(h;ksp0AGP*kdyYO^2ENpGpxyCBh;rq}VpqHR8?|UY* z&Xe==qdjFoSJM+mS_jct(Yy0j70=aaKQU7jJ8-=ZUzWUI#u7x}%W0IWc6BOSeyR_@ zS20<}TKIO6h!`7`je8!=&KE>hQCv^$vOWz-(BmQxs))wEp|5_6WaHHfIrBqHD=SzF z`(H#fi#)-?(>wDrZ#T)vBM#pBMG2|T8@ch&+TYl>IfVqN&| zVp_ow^!|0v#VS&w{X~~iymnJR-l*bC8EfIot@xrV?I#{B!fP*S$b+8u6W*3Zx=4xc z?4Q+|uhOloRm3HEfpcB$O4S*9T%$=U)<#jN_5=mdrhP zbJx}ERM3859?aXhlQwP8bUo>>02L*q)tzrJpWCPa@6Ec&SPS1sMF}Oz<<~&&9XOSB z`@BS$&m&#NYZGoy(fuzzHzOrU%H6yRPnrIjEvep2##;Dtb1!)7S(2KqYsdH3%fffQ zuO(v%(nU)2ebn0_{AHIZtgB_X>|>78;%LXqzp0BEYoRBiJ2|$8^LsHvS>apb1gS7a z5fRp+VchfKd{(h@FM$WXI*n~2-@d5_FTL_1d)vFHj3p=)N=uneCBk@(XY<+dg1v-@ z3_YrdX!ma`-ez7dUj2S)L08y=s5eQvbZ!8b!sf8Medh^%j(#4sKrg>9F!Q5*%kb?befmM-zSp5G~>OKnW#j_Ua{OF8j zVKzQJAREs#tf~d5gCC`pyiMk>2^O!d1xL$hG5anW;B&z&Rn9drDw8@tU?znmMU>%I3-hEVL6_wwHh zIx6$-_mHs!^JI_`om#qwDlhN6HNCubm|?BCmYHh(+(Y!ie`VHw=#$kBV?ynuwSdnnn3FCSD%dxj9E3?blUN!&y(gLzQXTy#1Ng zmMPu!pLJ#tkC+MF$?txxmOICWa;(+NcaOQQ+D&(E zxky{y-^(1-B}AX?znpj!da~H`BzU|MmQaFW3FhA*CECk)vchuBdxM5i9Jgfo_3-EB15M4)}9a5s`^%jl6U5n*qWx5;faMYr9Sncf~jc9_d80gAT zg1K=>iE_MJ?O=JR&wEjyV~!Uhs0Xz_eO~ZDc|NuIIQi5{U!w;d*?-i7n!N`_M8%X2 zJZx@d*>k*;VI_{tJhBqaZY5-)nqa#OY}ZkOxeZ9kHlmm@qUO_x!mI~G&`8t%jKP)P zNAWhFV@-GI+zV^bh|=sMN<@%nV0O=dJ1oeLJcjnimkf=Z$j?R>wK%!9Fkvn744U0D zhzRmmygT`;&g8Fz64=E--jd;c_zvsgvGMXK8s})EXeDSp^c~BPLF_Y)+Kx18apa)2i?-|h zWQFN!#u&s=i(^n6QT=XNv{QB1^>C0DU|4ha*3gcAX<9DwoKv za*$o&9ECFu^|@odqC9{_!6|${ z@1!|uf9ptn?FT=ao%2GH5vBvG6Nskl_(OiE z5&4Km`rr^t)+-_cB|$W;yoR??PV~)|8hAdhVC|un$!d|+J zTlUcx-!tNpoFmI91!^UlBCa>!I8t#07YL}Y4qnh(H$5Inh%bcLK0ML%=4u0BoFiQk zQT?=&!sOGYw{D#U9y^y-QP-X8saLHvP0KnjhuSW04}Iy41mfXNh*rvJ(*b6~v>kb*UxC=OXgk;o~`aXRJkNs~t`GyOgc<^IKl| z=kInnq9v?FQd$4BBZLsK)bcNcz!IE4a9*JZIXh$P3;!@}SR87!+!0ez%dK{elBPAg zrYSq&v=djU2S5Dob4R>`GaU7-_NULwpLOC5Hl8+_D|8m-L8L1p3XLqo?|CGe`u?_E z2M@9<&2Cp@iP|6A%|VDgWbGpefh9Oo~`zWH(rP)Up zWe5#z!-urYky@EXEyfHO0nljH{*3cC!`krCDcMp($unRrq$?si$M)sBLP9Lgmu()- z5%rNT(d@p2{FU~{!%ZfHm3-nN!zV%sMlvWZ<#NXK<$cH}mL{Kw2=Z#0-6tYil2*G6 z=TqF$EK!LI4KM154ap~JcJEAHTeEv@T7MiF!)wrN@QP*wjKVNFqgg`xGk@GBME~U_ z*`l{4joH8vr6OGs;WB(I->|neJGdn<6?xDcrP*gPn&CA23`e`?g(J8zb2g%xQ#ccZ zh?Qnk?ay3WqeujIQ=(X@@GL?sigZQ90+$GWp5}8On$NL>=5q~V2FH1%B+=~5KOb(* zwtoyvMY%RX?8}PV9Q0sxx&NwuZC%sUo_XEMp4t)vvdYYcJ-R( zL1&r=(K4{lMMUP|ZTO7=*;3n+wWC!Fwkxc0d}s`&(X93_&1yI%aID}6w#`v=7jmNM z9nDcV&T-U=2oLgC*G#|XDD*PuOGMA`&6%+)G~*PZ83%n7dN}lzbOWZ=k2RqAV-w9E z=y%bJiij`zQp-A;KSt90f&Lu5GtLrZyVj+q>@)67sWme$y4VfPmQq%Mlu)^QG`6KjdCD4Tk6o?mgtDQFj^83Jt*p%-8sba z^|u#wM35N6i4oaKm*Gk{`NY}e6EQZVG2z&a!q``mZc&6hggo3v@^Ba-W4tRO3J)Kv ztRN4UZChX}M&2~G9lL56&r>#4kqE`^uW)UEk-ms%S|Xf(h?&iLCj<*V5&f087yiN} zocpht%_eRQma!J@(2IzXCBwPt>vRn{eb*=EIBa~D;!A@Z;7PKXz7wQYzhN8;Ik z{WjSUof=)SVy!(s|M?qQ_;O|vA%be%G8rx3kz)n>x930`LW%ff#ah++jI<%<y}NH)^fgmlj=`U})8Hl09oi(gQ=)(r$ zHxGZ(sv#9=+2C;)csOd2gtp(m+wqRHdWR6TspZrTtAWU9hocs0!D{gMt*a-bRYR%= z^q+KPLuBa6QHwNf`~B9|AJvGq(SwhP7xjk?k^uz1r@MEY zvMF~KcjSlX54F5(N0)G4kJAkVT0Yt|+0~q%@&iK5tW=xL9c8j1?$`9PVlA|3Ns0=2 zAg2>zP-G&@Rjj5B@tSS3VlA|3Nt(5v*%0)fUHz}94N-LHM=RDso0g=(k%=}$bjSnN zzujB2(GK^Yt{T=to2LA$O10&OBo(!X`LEk#L-eXpOT$`d)AT*g{GleJ9Xp+}@u^>{ z*$~g76b);kP18F+q*X(^q-DPNaFt4iR1JCuXjltv+9nkx_gIc-zP*E@uL3F45>2u z!(sVo({zU^$!|y%PgX*GZbM}Bxx@0&rX^_y>B#60LuX`HHbjP9IV>M-nld1&)>ir* z^yXa`ud?{n8lg@&Hr-~sXvb)wbfbe`Wu+G(lJ5*+j|zm@5d9K+Sg{sbD4i9ZE2{J$ z#K#kqzm%zq4YAhgsugRYh0>1jtRHeWLcE;ygPnUO+Yo!27T2&AS}5Jwe}c&d58}nU z_!qMwDt-3XuohY zXhX=Q!Zoag7Ai@Rq*X(^q-FkKNta3nk9qP)4Qru=O454LY9B(7mJJ?O1ChbQVaI5p zww5z{%c&hUL`FLtc8nHE5i)7ju3gfVX7I?+mBWtFLTOKiv}*4`>JJ+tqdy#Wj2226 zbR>UIYKMi|Lw#;TWc0bij?qHNGmwr9yXrwYBfGL8GVID>$7GeZ-@iTelR0gb?uB#l zA5#unsuzn_cYKVr*)G~KS}5JO^rfiMj}S}gevy+ayVww;e%8{^#?X4`-SAxx68!&+!P^xfU(c)1rL0&WHIi+A3e4XM&9OwzCxT8|`spK{pLlMvJ% z{;ujc8$zBxQ^Q(lJ(R;jEjC(iAhI=`T*=^Ztz?3Rwa|L#+t<(WtOp?)l2pXQY9KOr zIBX29hrZR{^?(`em_RM3cGwUZ?Qqx_S`Y0^kX8*{EvNsaE6w1Mp(}@tq4h}8W0K!! z`8R6MoP-%R#O9rot=Rw6n>O_CK3{yava)aUE=K=()QTbMSlV6gTHdT-Z(=`DpO5(^ z8wls%V4k(8Vnf{AI#k12*iUrAyJ&@+LWm11dh(dBS!{@1MPoIrh5bbLg)dscwh`hI zA%6CWu^LhpAG|cxVP9gNH-Ys6+Y+f?8~EIkm%v$Y_T{)1(F4 zZ^NePH4jsJrPU&5?s6f@gyW;=iddDuiqu;caxvHcZ-iQ{+H~7*%5Ia}DFIQrcvx}^ z6PDnJLP`|xcJoxe?DFJA9?v&ntvfTq)dL59)7{pzzPhPvTn3NlBWo*@via~V!#kU> z1ZNziM7I>Y$*P1+?8tZ2jWHrJ$7%u*oiDnp8_&gO@Q@B>SAI3?z&j0@Wx`r9PfY5U zlfNYq5k>#YuJ~=}!1Ks8g*6V=+V(KJ8lG)-29J@8Hpq24gz^0zm1TR}W~_>4#7XM% z4!>)isF!5!QFd+yqFBr-Ia9u2yjX!fCM>b9ag1mZDM`|?r<>$~n}_nYUC-CEuWLU1 zd&eKqjeEwLuROE!*thI~>Ez=Hyvp7QrnS3MHw^TgZ}W+sHTs#8T;|y%`4wa~|LgPn zH{Eix@`2?jA#QFH5qqAMwN`BHKv@4Eiaxq)+3@ceKGR~B?eV!G74fjzd5~1rKT=W4 znbGnR)N*^olCgrc#neX2sZG{Dx{6)Aki9Q7oPVyFX2NJ2`H2Xxg&Wuy>W|m8ZT(@3 zcQX1zv-bz}p!TN+-D+j$qi=NJHx3LJB7KyQ`d|BFS7eFYu*6+tiCBX3k{Dl+wR6MT zGn2KWCqo2{0`1TEsFa+YS8dUOpB-$oUB`S!wyW7~S47aL<;JLupixVs)8+vTZ;AY9 zG;4pxx!lc@XWi||^Zp*S4*yD{RE=1Uwr$d_n#UxND&l2kQ+ zd!8`fnGf_{X2M#yGa(|*_v*vHw70B=77@{EWzDcoQdcZIV6ZzKXZ_+U-X^PjAQe=#*Blz^|-4_@9>VT$vcFP zW5$2<)QH9%R=OuOwK@;G)`rz=>nZHL;!Y}3qI>RoHRd0$db1qCMU8pTAr+dSx)KXB(3_hIRd6gewTtKEk6$lHcv3C>rdRF#ixU^`b=X1jvJgn1AV zxQk1X4139*_>^F&J-QiltxYOp9>m>Y5%D1R7B)C*ZI;?*u&^VH`@1*?Q|3VKE%KlY z1eKWWvor3h;vOmGupHSS@5*QgmXL(1eWpfAv|<_2N-jDsJ1grq+Gx3h2cA?SKbv+H zyLL&7HoC@qjy!N5mToHKFXe}%t0lj6<&XsTdPM};l`@#@%AM>AdEm}1?!(euNSR%f z(qtt$e_M$|DzXyC?l7Wl)~>YAuy&+{(HZil^+(Uf$|thjz~8oO<6(>_vR%jSFz)qI zhN(v%#Td0QG-_#dszzjK#EG~MOQYG5KSAGA_v)kAeF>Ie^n#Qq+i-thWq2nGyVkZJ z!xG#bMt+j?Y)pT}gS^l6zir;fCY9lLaj%y=+@I_eiM*(CD#MFn2}WcnA$>WS-dHIz zDK{VYDqdJSw>>gKUE(xZuk%*YR$UmUcFQqI|2qFO?GBD@rzmL`^KrM>eFCD!%)x4x zm6P>BAvrWe)7s!`4JEBuQJ(PNhJe6T(W;06>a@9&^?X`BiY)ivsjUQ7bKyP5r!g!+ z9=Ot%q}0QnN{1ew*{=Lqgq4@~$AN0*n2EZt-(TA9(Ee)YFO&3kD~k}1m9ce|{PXUz zn`^TPh>l-F)lDBF^_;1HX^1ANa#m8d@6N?fcFf9=7PbS|36j+Nbrogvjl4Wo{mu}9 zZ9+7CSClhY$@^C>zVJ#M`>*;0_5JvX`ojC4tY|UfnsfBLASEa^7oT-BUf3@|{U9ZJ z4eCIMGJ8TC+nI7+IL%la8KbiN!}U2iGHL&PiB|Qa!}Ri5vy!ex2J}_#PMXOqyOIP1 zo@Q(~5u-XU9-(8WK9ocam9F6bHEXXCCCF$Qm8*V^i{H7n!&1_O)^d`9a%wx zh;DOfgq|bqn-wY1twTL}DZkV;Y(ldwZ0z`GHSq38{i*)WiU_1c-xc-jrCk1*%AB3! zgi{&R?&cQL)Chfy?)2Y()Q)lEdMUZ(RCaAZ9K#aiha;H22Hea~^?*Y3_7qWZrduMhmcx~@AcisWgJhzZO&p_p@446rjeiekhQMLiV-OsI$iQBk4< zbIw^$!HnU|Y&XncI@5XPj5&MetoPOIxy#%4dp`fs$L+VPI#pL!ztuCj5{=-%Gd-2> zvxcy4)A9(2{dW@856PkW*J6dW842;~p?=}IzMvE#dQ9q~w9cNxM(ilS@fVbVHkjt_ zvwliqhv6(X@r}VXu-&WOb52t8goWz2dfO`5l;M-Rvft0xb8I2@k0>K@zDaqsemAS>P=ez~ zq5VKKF|endH^;0z!mex|Da2$j2Jq4C0q<2JOmB3^c*AsJ@q%pbmZhxv#Sp<;YFS`z zhQZ{hkhM&!kT58tfp>`heY3%)n(^9^wR-+5tG{Nvfav2pFC%i}7`@AfWg4RCD={le zGP{nuS(Va39P2`@L~kj6^;h%4=))|%%4h+Bx+9wWs}m*7vr231-QLk0OW8k>W73}h`(>~+*)Q@5Aq zbZ=9P!GN%_=5FQobf44SUvJcXwT3m(w}gUso4!}=Yj)lmEg;?{4{$%W#b5u}e6@yX zNxHV?jcG&t1M|N5lle!__3mr7kI+NHR%(bq*%VcK?I^p`Y_Iq4Y`6K;G~3;+vmI-a zq^+}C%8v)-WBcY!6l9aw z!fdWkCC)rIAe!SZ)Vmqh@epO~bYE=#xb;waFWEBYHW|%7)ySClx1T;^*lG>s(H;F( zM|15Y+5BX_I1_1JaqHYgG-a~VpIL*3n+N=7w#S%zY_`sDn(fT`Z{iyKczifuet@~s zvKWrP^uAevkDu+QU!K1DKU~fx$0nrL*fr2Rcqx5j4N9R_;%s+N7n(~fOGzJ3D+=|+ z{t*#0cg@zhi>0u4ab(GsEbPp!ULSdPn$=IlyAX_W)4kfJKKyQ{hpgZei(g`iuo!0? z@=G+UUxGE!y|Y7YZuNID@{2Kc@@lmlpIXwJ^I`ozvBBhp<1gCBk=pm97=5p)q7g~A z$o@Bmoc6LVzk97PZ{FdXaT8~W6d5-^{^J6*7&;H6(|G`EqI-keO?f*y8+50$0k)RT z2AcK!foS4|rwrh2h#6+yHq#Xm*jhT{XgOz`w|6@6VRR}w^Kll#Umj$JYj^2XRR5i% zVNH}V(o5lcE)?O{=Imuy3bhgu6TdX%cj;6VN2emx7kfcOoGvw(*T{@#&0GG(=C~wl zF(X6uMfD13!C#ZLm3pWim^Y7x>^*v)dhI|y>EHxrS1em#f6g6|q&*!Hs(%|+P{W!m zo(wlUnLXsmU<8VM5zUB980Tp6a5SsWNb~Ccue{o!(JVCO1;bxZ2G&IHg^%yT+dZ4Z z!gm!AVoT&%YF6(xUtGNQzJIu0ce&w5|SOf-L6`8za^;Dp~t-D?%@S^sR9=&~nZn6_@wt=Po>8!8KwTmZGzP z4NYepVB;?H58z3r_3XIU7J>aqry|XIj>4KOry_oVPDT0YRD{y$RAjRfC{L2ElpV%< z^`F5KpIFXnHtEP0ZMb);R%LLQ{<)DvBiPV)IPWkmmX(g&#qgIBXQpayXTtPBx4vbH z?P!=Wm_M#Piwz!m+&FXExW^~^Pt{!i4%O}cvD2_7dcn-A58n|T&+NOr6A-v2aIH{; zrMoYGe`*FR`S*E-zn~11O);_?L;2z6vl+XwgQ4!&yJ9=&Jjj>Qd9WOv2eEh2?qW|9 z&$3-VzP3#Wn-~5@VB_K{5?AdEn!7Huve{UgyJ%~1?&4aJq}~o)xHZmz`vhu&_L2A{ zbT+VhOSl)|*#P|&%jO(w-JQ|r#NAok2T6vk{Pf7s^G1(M^siRGs%uPN?>CohcqP+zG=4DjDQs#51Z%CF1g*(a}e49|dgHWXtS^EUNS z-qBuLfc9GIMOzdHV*nU)pznsK3{aZW9+kCqrYpwV5KX&*YH%qGo`dE7Lox0@yy^Y} zV||!?hH*d3ZH8jpX7r}p42)S~JW-4eX8U$l8q(cFD&0+B#1zl6WZ`TPR?EGC^8V+& z0Y+;v_9`Oi-axV58(?%9Bf?^Qmty+zLyA)$qBu21&oNGoQEp50oLQsi7{^BsS)98R z3uo3?INnX*y#d}Q&^N<=-hULJ$Tr@q;Qa@+!?KGSad=Cdnt%Ekr^Xu|ykimf4~ijk zBZhp5V#s)-gw`2XuqB4fo70$Irx-HchT#ns-hWwc^|^7YUy^S1@s1Af*hB=~(R1UD zzC7Lb;msl5_TgP2eM#UzJ}!Cvdw-7ioOlO`H<*${_vhTWKQBi2=XlGCXuMaYnB~$G zX563erTcTd$))>q+kLHw$a=Dg1=4MJ8r_ED{W7BQewf~xTzTJY+=e%x+i<$|w%uXl zO*P(C---#h){EfZ=S{%_{Z6Z#Q z!4S$vOef?HVJXojP9)xv!F0Mryd~r(VJXq>P9kp9Rzh4R1V*`V*B5Pj3h}QDrjwx+ zGN`bWxPMTK6>H0prG=%$J<8z04I&=dbK;SqB||$X+FgUAHtZ)?4Nr8~)7Xc!e-Ize zV7D23IOM%yDeObKi6hRP!JzXX&K+{=uoU&7jf+RTaMIu4!x_9db8;JGP%gBPqQlf1)av6-AhVu(UjQl7ISIuA!;5^0|N(_jfxd4=L!K_}9 zk;j6iaE2P+|G00-Pza-Z1I#PHQaD2;X+GsL7d=x@wjz*0Cv>1$9w^CqT{EXgh~%=3z;JTI#ZBcBUP;hd&heaa;> zGQ%!XE}8WVVC0NpDV)=mY(PspjC?iBOT$t)r-_S0bsH^jO|mfe4NKvirg;T>Ga0cI&S|<6hFnX`mc&vxr|GMqKl3^NqF%;~Oe}?SIwxmzGWD|cJn(bO+ZuU( zMrI(+X?jVA@=}f79Y?)vJvIECSC;dDG5bVM- zx~8g(=S=IYG?>!jsc2`{OJ>K>(LB%RQYI{Ao%sekT11>%dB=kIHn58umcrHb|02?{ zlof6Cf{3tcmG`ryuWZ?pRt=4w77+=i42xD@DEkac;p!3*+o!L!AdJ7U6s|52AuSHE zAYw@tmcrE~B0kYr8@;=mdKpXM>Jkw@26jm|5a+3vu@tVZ|3SD}5m*XWmx%aG^T|N$ zA+4|!t}YQ_w>ZRth^LlgDO_D5f_l}0FnSkD;p!3*G=dg{F@ji%MzgJv>HEK9PP4>< zFlGss!qp|ppt);7(A-VOQnv6eQt*m`N2;LzXWdDs;n#HucySW z`j3o>QJd4p*Ux4dbOVGjedK?j?S3mvwy;YisFm5NZigf2~ zAC=+w3nJ*>%!>Z^Hsex@eQc5`SU?b(S;q!%HY^C~Vh+Mq3V8?rKLUTj{y}a3m7!BR zRB8w6i&}|@%!iG6MZ3!UVHf&(-6GjN^NPQI*mafGFhq7=zS&<7TC-AfE79EjRieMX zLR(2A_~}Js-s)Q=zN5W}sNT-Qy+o$J-f8Me0ZrbLTASOeb@};(y{uwwPxmEf{q<7M zS7|73c+IBnjhFlDg~u2((LQ?;Yw5X%%^y6RBVz~AdZ9M%YOKG0)xnrolVe}ASN8pQ zz0e6V)`hyOi%Pk7>gKP%D{5IE`OdI2ueH(3(=zom3D8_(_i1e%|Mh{lb3xf zbDXVh9mtVwgy_og72G%0_t$$iGPGLrbRfGpVxsW|v&kJ+!2R&q56Ntw3NVBBc2a`kYAbu>uGE2C1pP-)R*4^OF zxxyKlG>`YwJSIzhbG2O9CyZEw0xN8@1}5j0DpwQ)xL0)Kse*eVU%QAjGAv89K<9`0zgeCNG1 zx&4Oryn(lapcNvpCOQ?p$|cuny_0pWHHIVa4H;tCKFSzr;-Q$9R^SUadB|4|x@9Du z^w+!4TZ33{|8q?;29Ql`al)|F<@{?a0sZRnPxp4p_)F&%a>j>LfBiPucC3j`UY!_ z*BLubhIPlmdgnG&GxF>qE4t8VM}>WzlpC&3S&IF6WB?)qmRI zA2wGG`ehosab}dUf7m#Q$W=r%ap(ulkk?FI&Q?DRsJd}6e?0Le4!!ovzcFqjz&WUJ>s(lNPP0RPQzeWtEZXJ!l8zUmZbGd;>5z zUQOifI`t3`C<8rNNxHi|_ko3T#`614X{_hlI_{1`{Ph>9E3`^uquj%r2k568F40P} z0q$3whUnev&!;tL{P}|rdc`!h{P*pOvUi9+@cC>Fy-ZQYkt(K^QwY(ql0`;_RR*EC z6-_cSa%7B(E!Ju;A)1m_C<9xI+EV^UzJCr3n>&{KmlF}GHLLPT_WpWBItihM|F&Ze z$;kb`TG`r!8qyosdtLV(AVi)2XobCt8q#e>qI1hlgqZLj#E6JB+{ejZpI(2Jh8kMN zqm^|$uuo__GOXi4Ew}X{y}eU(S*v9v;}4R7{f=5;AJT3x`qlndgm_*-91qf+TW6(+ z$evvF;0x;AxYB9H+_ja$c8G`8i)DDfmt}d` zi+=j#o~w=XneBumj^Nh|RS#8j*~bFuwZB=* z;+Kp*W$fpvXX=;&3Iy|G4*MAXGNfuMk1Xx4&!JU|7K0GJ!_q(1>CM0FFC?^MYFcUT z`VTS5&#%(3CP^B6PLiMfHJYb~ivAUPFQ_4X>2GP);n)k5Gs=U6mSZWje3YBfIpA=K zk#|@R`lc6_LKz~0S3lvF{Q5RK!`4H+}d4KmKowsA%cMH%hR$>vw3d-KDC3JK?0>|I0?M>t@YDeg-o|K6#EFn3Wa z)RsC`m$20a7x zivCNq-HEf^FaH*xH{W7ppDl-a;wD9Vv1YR%6zq1elf!-^kC27E&Px9pP zp8U(YqcZ-2o+bKobo+X-mh$kNGw+aiNkE{tjA+VnpU_Zl_hS<85z)$wYYqDi{YOb^ z9`mbwv2Y}pS}jk>lizpPm@K@68%ImQgpg}T~?^%WPZ1BKQsP<>zuT; z`KXd~VweZpu{V-0oE~W=O>7nb(HP^9q`E!7uv#}f__?xYW&8zW4p@_A%=sM}^RYDM zG`2STfu%6ENQ{)BjrqMI<$0m>Gsbw>w8EIBh@hFsjhR@JW+MKAHVS1M?&|@Do=d`+6X&joC|rJz+|4hD57?4luq9Xu zXDIC-vB%|hWJ^x$&N6lbn}x%bidKTYG*0%)p7xIr+CR`Pp=Cfc`96i?(f)z^1j<9S zBo!|j&sLCaPa)e*(rr5@%EP^c-s@{#h6mC9agf@9`yI+dv?To=b)3DS@%Wv_17|hL z!#$C9XWGw~(*EH{O7qeSSf5IN3UMEdk^K36e#X*mBlNuY4TNLLT6wgi zAKN^Ea>F4j79%%eOlHciNy>}C-AtdaHe*;9YEo%HT*me%WAwwG%ScB57Ou+Ux=YMY z7B%2;-Irzb-Zeu1=(SQq^o{ok87W`K=$+>qh|=~&WV@9z%ltG!KumU;p7Etnu)fy3 zOvAhx`fm94Jo1WL?O2$@M2@8}+g?Q69pkEu^=c}2T~M2&bksdhwr57(Vj=qJKqI@q z-?5kS>(V0*HwpI_WFUG@3$KiiHAD24iw(rt-F9;Qgf=XC@kEZApoU#?_sKYF3eo#+ zGZ1Tif5<&gCCM>+ygAl|nw+bAhTo&NMQ&_1{KT}+E98?$TuejehHW9q+!aHe$Y4H2j?Eb?@;ROLiyMDjHGe3vw9d!dSsz`O&e(W5%L$^?lb)hEqZHFHA z?Hs1(4Kfft?`fvLqT8EJO^>GUhv(FV=pD_24i_I9rn^iu5H96(w@N`Od(nQ9@Ja!q zU)>*fI5;*;KVm^_&M3udPxq5c+>bD{Qmie+dPS`+DO=2H@7iv=%EfT33lUfoy^ddE zQ~H((UMy{Wq@k7VWdh8P!kQ?HZitp%XOPO$Jthe}k4osuo6R0%KHaArC;Q=UwPaW? ztzh>Y>tlK)@oDZ~%x(Yv)mXLeR{Mbntch&<+!0JZ+LHM=j5Dl{yVYKieYCxbfEjg? z! z*>)$4^&*}tIC&s_~$h+Zb5C27U>JZ$Ap+m5}98IIV~6a#4B%2O9?GCvvEK$s=iauGqh z8vmPiwJ)@*;ru}jv3>Lk?QT2fGo=liMz$U2DAtP_(r#e)ig{0}pI*tyUszFyz?vv( zFvgV+@7+|MLwgjiHPjI2F}+V6x550!ht@2cY&))JtQS`oy~#0g6-)Q2ZZZ!F6RZy+ zuqL{@^ZLR3GLq!`2faDkCDahtyd<3ro}b76ZjpS%KG2>LUqNy%N%@rcuP0OZ4 z3$`6K5fSF_YHaQDIdTl`QE2s1L$r_dPSNd6ZjFPySoPl`1xt-uk$r?0fr|9nX=-$> zx?7I|F&y^{)PyvIoinLRX?b^JKl#bM2tg}ElUA@h@3HeWohD0Nge*1Ig___?LG-TL z>mYgW?vm#8a}$K!8PT}6Qx^8^6SAvML3t?cIJk$SCg?vmny5_TnZJ+u+I3-$6}iwu7HIYwieH`Dv-q zyF*Ww*1XN*q;Dvk%B5tFFTm=4=qGr6sELT69Y<+QJI*QEanLtJO~^8UPu`ALw}_8ohqnYXc^6 zKGxIp@iN&ghyvp21+5+3$`r50pE^a$`o%WFSq;%>i6qH&uN!Z5zJ=`Yq^8kVwp|!4 z1D?X@rg}n6IXrHGJbZD8AmcwP82sH5vl=nK)*Iwv6UGP#T<3@;=D7&`xR9cedPpP!9otYX#AiAssMDnGoV>a=K#aU0d7`>&0=RFB~=V zSE?Ur#uAlVLL3fH^djON$;hM;{6Hg!zaWCf#wMFi6UD13k7)!o8bQ#&gat1 z#;J1D#}L6XU@36~i!QL^FQ~7&4DKQ9Q8*qVg8GU_{_HE9aX4dej?qhn&HTBwuMmNA z7ySoGicK~to0~2&`;;Iy$I(PBdsT$)?)olsd6gus?7j#+YybPq>;}o2)0Z&4B>zS^ z4X$fn$QM%DvdrXx{Pw<^f*2Sk-c4_(|`nT8C2M`k6uB zGZDRbeUj#OIzq2s?*qx0y|F$w70zG}&sOF5h6uiXfi=2YxnzSE1dzsK8iEQN1<;L9YmqRM;lQADsqWd603h*Vjz@D?Rd}K8k<%u4@cdx7vAm**TO%<>TA6WL_UY2ptTj?xibWPOk}J1S0paKJ#EF5Zrt z9yMd*=Tzn>9nr@&1!+B}#px?I7>ETMI`HVhC)tC0Uxb&Y5Pe{6kalokoL)A`K)ea? z4@&72WoZW;`Bb74Mc@1o%qoomsqh?j~Tv_h3GQt1GSXtak~9M z1JU^0B!2OAO|$*HX3YKR2yM>&SUvlCDGfCd+ws9QlyB_g!h$`gGn9@9tchZ;%l-J< z#%r1TfV~W*BYOIuBQ%%ivHH_0#yi5SY-c{I=^d8d>bmj9ukAH7eA5eSlB7;S6M5We zAGUW&swsE>QCh9BF?zA9)h`E>))0Na&nWF>WQ;z?y8_8*n$m?|;rH3LMduj4A%tzh znk1>vFh71{`Z~6)@m~4JwqR}Gi^=+5zg5&wleWqztz1Bi9yZj-mOVRt6nET^!SXk_ zZ9?gYz?vxI&}k_Ds$F4Y-V|XaT}Em9<74!Krz>cPzIHZP3wl3UPjYu687VEidE&#n zY-HRXRy!+LJNt36zV@Dz@OBrzi)6eV-Gc{u-ena6IKy919@a$p1{>@03KQS4HPeeL z%_c=@W-US=S-q@=y2tniYr)x*^{Gx3Nvkbodhi#Qb8*+z^JUZ*5m*zwzV~$?KQZnH zt8pNo8KoooXvJvF_hf{A@@iRxCLRX)5{ z6+Wm^JvnPkw04rdJAc_+PDAvACh;1Z8?JB7DnT+ro%`~0o1d{Ei)J!>R}I^QHAzzT z2QYJ>s;HzVxN~m&LV$y%RKjN~pf`x}#Q`Cus9nsP6O3kz}+D9m8_p z?!xOlD6AxTBx?4TLUp(C1vS(}Y{!qfm3e?mJAN>4OL_6{iCV49PtV6V^mK&dlxRlj~&uXi^W8y48fM5CO9kU{(Po4uX8aEztYD?M(KzU z*I>_Y75U%>uh`(-RRvpuXk7D>G<5egb~ShfyZ%q0f>s9GgzJ&G25Y_e!K#$aWYPr- zhjt#V9o@04AHkb!zrgZMtYt>&sJn=;zde*sD!GdV`pyt`14N_MrWYN8y7HL*W0*sQ z!V2ya*e0}(q!pdfCRe!4zV65pb~V%l+eELC#Ej;DT}xvtt2SUL9TDQLR`K`*{${~Q z7I1oqusb6fcTrj&^ri8ecQkXSv>7t)+t?=D;UsC%r!G7`6L=z zL-}p{1A$l242S)IXL-Mmv(?bPs3DM})Q0~%>DDKqvqTA`)c^Udq*e3Ki z=mdGSBR{wP23x=%3GG1N2Yow9D%Q`3pB*uceYp2l@W@bi^Z+I4-Y>p>D^qrp= z`faE?dYSa*z@b5WWWrq2)fOLwb|4x(S(5R=gU|1Nl@+P?TJT;`cYM`Vk~(bi;7Yk9 zmfof$N9m|LdgQcoelqbcX$Q<>9O`nEj%f7y$s-%yh&Ro@)wIs7HAi0^(Ri|;$hM0I zFXecK{o(SRUK!6h%b@Of_94qKpc$WBDVSv}uP>Zf5RE4!x-ofEieK2>*_^+;mvAaV z-SHGgdu^3l?A^wK^8I%KT!OO`>W(Kp@~`r^@r(XxtjgC?98aV8ekPuf>HNXV@oUG! zSjzBr!U+;}7ZIC=n_1s=tIY9vf`n5l>W(LGNm}{&vbpT}L#CrK^x_+w^-*^`-BY&H z6jvU;cNcs6vXpQ>7uo@DztR`kW^&e}eH?QN86rdtP!r_4Pn&|BUR z7eU=I5<;y0!0&SV*~?5lR}JJCzd$rbTj)EZWt;O$jndiP{S|~r5o&_*Ao9XXk7Wx_ zn^~bE!-OafBE(3Md~&J$=eh)@)fpv3icoiqOwoHXT?Q*YF_lfzf4pZH3mftxN%Ol9 zrpteR$;3Dly<+|-pK_*VIX-ezIpwrVqUN}Aj405-K~-` za7`KR>t-+bKImDBh&!$oWasu{xIS!)jD8e)PAHppwXtTlMGxXP9rwARuZHN^`zQuz z4%G(@H?%5SSLN?wit`QI)(CGdBf4sxByH8YQ2m!L2I5Y}7y0&bA6~KNIQhrAMD5$s zP`%3CeA#rIHDyV<|*ajBL_Iwq^8aK5Do(L+OaV z5S64!2N8qq#4leB5;L-mXz1qe~(ctxdYna(_LRy{LH z$2L7uk~G&lp?cqq_Jp|lTUljc!*0Cz3|BM$a>+Q;9+^xpTsX4Wz#Ya?%k>04%hr?_ZV)vfaNacy{X<#HUQqwXT&@X@|ZyVQb5 zU#rJ!^_;3bnh~Z)FO)Py&pDE;y?z^}ZwfTNa5QLZ6aI458&+O(;P?_WzDbQWNm8kO zev|>Wl=&Yz%uqVE6h}k`=41bl~m7{dr0T4|wvip*fVam)K*M0oA9l`>2=Ct9eI3)BVYRa8o>iV-7%I$Hx0KRu`LaU z@R{{CxuJB_9laWQDSi1^w||dD&;B9udkmX*IV9JK;Rh{&x!Q9@%i;~k#-y8N<)Tl ziYRNdYK_x}?YfzX_2Nl}WbD}{Pkpvhu5~LwIOEhiG)3EeI$ZBG;sNciIW-Xjdt_Us z=;>ba3&+YFOJTj@X(IjP043t#GdG8Rxr94<+&{1;Nm9o)G=H9!BL6~P8AIvi$46?F zYL3&h{}kIqHgW%B=F?!IoSVMhgRMn`(CgAUPhWndx|2L-%4;F|fxRmtx(<%uDSK|2 zOWlf=aW3KbMV#Vn9@0 zD<>olFwf2k<#VS^(H;he>&JWkJ8CD6hU@)q-u%x9ChaUBZ^&}x|IDk)mz9~K?QIdR zcm4R#QfftFxIUmlw&mYBX#L|}xo*oY+++JU*5VVLu)2ono!@`SM6@XT%91SEJl&7a zoji+eU7Dy3-WRF|y~?d2dcl??ZD(kh-m0kK!z~NkENAx%=I7qqvGB7~G`)GKem1s% zhUhdkNh^FdRG%>0II;9I)s^pep3I#t<~N;QI$67SEJR<^ps-?)7mD=na*Q1wPC0}ZJeW4H)XQ6=VXX}erFNE644ik7Z+lUxfSrOn$TcFNcej0cFGOpC+1yf$c6xi!C2wX}k34NGC1Ns=n}EvsC}bmnb_ zND7uhuSP`tF+E+*EL5FO9$R0*U(nW~Y>J)_E34#Y&U{}VNkQFF2FfOa5cRINT-vNm z+$rPOV(*H5wYcv9rFf}SHpTHc!cF!B<4ys5p5sJLo|H}lk9F9+1=M%eS`U&t9F9DLNxB8bRV@VOD>)4 z$Nv~hZ!W{Wjq??EY8vzGz4Ad*7e0H_H-^>{(dZ3O9?P}@vV4?o0_N5gb^}DC$3eV| zN^9k{iw2k%lJA3lBHDID6I;FO?v`Ka9hTkn){A8w)TA%3nSKbKjHs2jZ$itPv&Ztw zRni3CM{F&vsGl_vhvmpwmspa~kKTI0QeuxH;-US?{VnM|nGxmF1m8y-HAGBWbE;(n zLaZYMmJ;U@BEH_;zF#G+wp31ISW2AXh`1uJ+5eCbHR)v|EG4cxL>z6^XI~T{hEvP2 zlxPhQF{e+tRwD`V7a{(q6!@Y!y&E&W%6=;XEtxnoP=?2+Akf~LYln};sr}=^^{g@_jGGNLhxOv{WSgnRL7BS^sbjESR4eNROCg$Wu<908&c5{I znTKW?tQXbFdO>u97V+xR+2ML;X0UgjRPU)=$e)*YT^z{pyWw>1w|!|GYoh$9zqgyK z*T2H<6E6d$W1HxlpysfUnzTum7yDJ=mGd=HP&%TC0ijxXS#%#2>7vX`smXI~NR-P= zidUbONc%dDLCRT@PP zCnPn871sQmHG@rMla6R&K&Vz`9p$*!?WMHcY0uyO=wq;{Y|;@;j0-h~ z4_Bo?Kcy9MSjG^Cg}5rV@53Xyc2=-z<;l^VS4dYStjQQQx?EuerK9dwO{3IuLt^w+ zLkwPD>Z)N%r>O00>4)hCyUivY(bM~lQfr08=zm-`5WiInRG!TGi}lW3$6&YFq$7Hu z&nWffB$Cn7;3r-<)`1M@*O@qrTW$Iu)xq%*=nvPgEAn9?E+B-QR@z zBAPf8s+FrsyzqUam5u{TfMbink%U@ogx-ZW|=wqw;AU#0cp)8#wOM?=kFU=KXsQL#I8gZ)TsN=@jtf*1>6^tx=$pk@ z6GcA;H&Q;o-(rev*P5I9hpU~5*{dDRrJ*JipHXv|ft(`m%AW zHILPx-vSKIglf%QKuwwy4p(D|*&lhskdb$88Kt*-Gjl$>?i{5f z0&9|_RXv(3lMakxQyyZ^Voj2C-S0aKytB--YxO|>#5qarw?9I^viE%^ zww7X~YEA~vh2gR0$O${ledk6S92Q#(5rH*PzVnJqx!~f7OkQWne6h6y(b?;g)TlEN zdY(E)CX#82t5W_avnFzKvg(-~p+C_rUr)BRTx`e1j)S>fXJ=D+hY!sCXrfwWO@uzb z^}9?uf2vlt2;KInIT=+amn~(Z=O!>y^HIiKs%p!q0!_qr#I+eK+aEGBR&^&^M2ztSvwr?|3y=?$u3aFNs-$?LY+9M7hWt>nnTnWw3eYstPjb{#3Po z-x+J7{J{oaP2F1UV%?m^aFmX15@oPuFPIeAmSxWr#~k|y(G+hFHF4Lxi_B~4)#F$S z`v-enl5+jxqI@m3gVi!}uwd?D%f)s~ah@x$t2LAzzb&={5m*zgk9W*!)O@O~tBdlTtKN{K&U`e- zIt~@q2kI^>%OR8yxw~^z2oX!SS-$E7TqBiX^>iU}h62UrnWaHMC^dCaj6>?k=`d z3hvR^Zpx2BYl)g*n`Y0&5}$_HRv;9i~2}vsYRQ`#I{4`z|q^8kbhOuAd`&Mydvv)3(!Nn{ZF0IGl4Q zrSw0SShLlS1-}F}!JV4oi6MQJ6NksLT2b$ftSy_*fC$kqSsFS>aevdmeBv?1e!#y% zH2Ohwm+I%MRLLqQm)-rEq34Bd!kWkfDArkd(Ebj+0)1U*2YO5B4HCO;i=R?;#ai~) z?%xF;4s}PLk^B<>P-S8DmMrn@REC}&>W+S?Bpp6CNf|n-ruop!W4lh!dU_g)!KTZqQfB;{uG?WOFcY^TbU?S#^? z9eCcQF@H5c>F=0}&pU5##WRgu8QX~-b;mdgegEUCyYkwx8ee|CmXTv( ziy9yrqZE?VF7=C?5M7ryC|%UZF|ox(5RH)#Nh)0TnW?hm$Q|GJGH!Tnu@^*Rw1qs& zF};){>EBs&zbQuUk}Xn%nuzTvS-7%Nq+2`s>OxByr6U4sqUd>YkR1843!nR_un;Li zG)AT*=}XE5wxQ{Dc5gyAgTHHwh0$GzYRwG8I1^>8_YUA4Ux%) z_MNIeGD*GNC`>OtB9~@YH(8z5Gfe;IX)aCF%KVJ8 zfxI*K;2#)D$5MzUCWoJ^JgB-S&t6iNqjW?U*_^Dd>r1_BvZE7ZnVF51o5A$$(!+K< zh1yYIS(rY!-;Yd0=c_qYjdCXqI~s_p(at>4y958_z$P45Xx)} zzs*ozM0ebqq&_+sss~)oM_Sc?-CCJoZ_j6Je$0GpB&)l(hw3lN<=5_xNmiSV57oVD z=GR_*PF8h#ORsvKJcKwjzqPV_gFXLikMZTCwCr^}EX2?NUM3C?ZKcv^-QV`nQ9I=u%-1!R-|zWZYonp z!C%nYVNJB6nwCxXEjonXPI_!)DA;ZRPb zHAGV`Kx`*v2r&Uue#|#A6l{@y>;*)VR_8sG17C`8`_+pX{(|zbCVCIx(K)$t)(GA^ zbAbt^W1A37Uby`|^DlJ*`SEopWo#k#6{3kXNsQ%IQN{U>`o)Ca#r*@(WT|J%ig%M@ ze9^?;g;|1a!d@U5-P7gb3+bKh$suNJ2O`8-(se~4cDegFe!p(4&<;f7tfY6N-hO6( zcWuwd`Ck+eINNdEQ2u$4tMZq#BVXqBm#}J46P(Ay5gxHaUNmqxf0dTNP&y*SRl8-r z6DxIYG7tMRw;44-G+GJbetehs^MCsBMkPQdDdoYmId>Z6V@=)1kq^cDfU{uJa2HL zGw*cdn6TrZ?pPC@?&4c0n`6H)cRM?d(y<-5KT48+Orm@tT;_{ooj6KIH14AGEukgx zti_AYyjVsdjyoBmai=CrEqQT|-wN{JJ$(dksqTj)wIJn{c=rFEiTf_yY~E|AtQ+=_ zWw@0PJOI=k{S|s4Ho2C(xJ5bM=7=Xp>8Lw;HImfF>kKPD&XHgDaO3EUAR0X<;;;>&Q6qX~a}VY2{^X=mKd4p~ zE21$zLoE+(X!`JzFNzTl;+Lpaz9`mY;fu;vz9=z7R4d~b5m*zwM$%}V?71dc?$j$# zh!kOD0&B9ciWMuXm>43emAQ;w2;C`@bu`v=w}NsBwB$<2N;$+2E6 zh1yz}=8*SaX3oJ?D)d%be6pk{lLBw5eGk(Q*LjbBCq?ctq_O9(Zun$ zaJHG1vyHP_oP9Z~fX-0^+wzrnddV*3D|1{qh{m--Z&`GAHuWNoS3GgNh-al*xtzwD z09Kf7r4hf~F~RK?@yNo6M@GC1)ym~G5INj2M89o&MZQ5CFM}^iJS)}8Nkw_Mx+JM} zWjDD3@yM1DkBrzNs+E(9@(@k2S6@G66>+@&+IiMsg{f96aY>LTD+{_;K3Fd#_vNL!~s+F^iXkv(|Ieco3-qC-O=*M4;n`LmL zR4XqW(Zmo_b2!@xclNUJauH|S)Er*8Yvr}9_~HTP>Hl)PZ1a_P zU8s*jE9|^Kr+ab$I&adQ_*jmx2!rdU^{a%)vGDd>az6rgH{e$a~z7n%Ei%p&3$L~bU zGB~NWd4>IhR)X%;Mr>vSe+}lpy|iQ4LPVn_lB9edb=g|V7%?5lZ?JJ~b{ElT?TmNs z3dy-C|Klm;f1rIuG+I>ZU9#j1k-JjPh{5qNp0}wZF4TtkCYW zMoyf~L&m)i(eyp9DsHj|<$v_0{14o>Q6BEQbShG>$O9) zitQNMaZO7rQx<;_dz3sU8%KERv+XSnHttqp<6%Haq@?-Hx{fE9rrD~=$JtR(#(j9UPz literal 0 HcmV?d00001 diff --git a/ros2_humble_crx_description/fanuc_crx_description/meshes/visual/j3.stl b/ros2_humble_crx_description/fanuc_crx_description/meshes/visual/j3.stl new file mode 100644 index 0000000000000000000000000000000000000000..cfcd596d2f7879a610886ff2e792fcf2cd3271f5 GIT binary patch literal 208384 zcmb5X2UHcw@;}~Y5l}G$MuHJBfs$sL86<-Q1pzUlqM{hU2ngnYVa;*Pao06tf;%m3 zj+g`Hu;#354!`c}yWgqC_x6AOob%3`wfj?{ySlonx@WFWSV&l;l$n`XH&p518yTpC z82^L+1OMOu??1na2-Qk9NSO`Gkl$*@;CD4Ge2$$wX-JLfsP?UE;j?-3N$Ja_j%qYU zK124Ll=96xs|d|)e^4sFak$s|LhS$E zT^@~LFaCV$nZ~#evF@yz*&rj2FCOt~8~2~ju1@h> zs%@*J=?qc$dlSZ^K-HKYzV{Oa1f+z}-ZN(jwpIbZ4! zB#{a2n_$Qtj*rMAgpKYvHoDW;=)y69qYFnJp-iuAX;q*^LPs{ikS^pWB2vm2BxLco zJSI1Re6>bCPfuJ{>@sA^M>k-=IVEw7tMU10u|-P8YajN!s@5!N#=C>^jKxWW_cFC` z^owoLN_c}PDpE?FHCHO!V}m_ygN-~cmZ_$?TGTeub@eZ=p1WdWe0E!MQ%M@!l0CPp zy+~T5*>K%9zfJubs^boSVb9b5Tqq5=9*fshDrH2#UiDwOs7DT;D}tC@F+sZY zB^iI}n4@vJV-AO_zh`we_S&5tq*`9+W_)(tBOd?(&VveIQ^u{FFai92dhcF+85zxIoDCzbSwia^L`j0E&gmpI;x8uC%bXp3kOE1 zDX(YjN64-Jc*rK*=2FjUK2OARP&+>iy&^F>m$w19Dv{7 z&NE7-)3WyIur5%YpEy7frOM7-C-q+Af$w~5YUGj2tUbh{w#s#~eQ2d-WLGmjH}6tk zy*3}Q=N5-MNux>z;xA8Y89kh-1xm=DbxL<{&6YYotAY2Wg$O)&uVSvJ6#Matk;lGo zSCo&9UD&hxz-dzLS=I6KnW07=dW*GB@>z3rS*2R4$YcMUe5qgV4f*QGUPc~}Zt=25 zl|w#mMR?5adq%2tYP_6(eW(#3ZIYC?JED!f^36SzD!oFC&mVGTEAU8%=|7`fwu5x*dQBz994p6+Ty=;+Qa#pU)_56A}pen!nrwD`E0_7ZUn zKWBfD4*ame-9iJ6JWM_uBDjRpOO;lSYVM3*xzsb#fI4P4dU3Q7VWP`>g&x19)V%9& zluAb&3cD|z?-z`>AFUzq;E17l_G+3l-+cT}LBAM?0Edl?n?2aZY_(qvj@BTo2REz@JU}A(W19O1+;Y;rNT1;He>kOV#B? zJ9U=RHYSx_o4=$VI}-5N*MA!kCc3ZeBG;wae&ZluD;Gvdl8+`K8e~KQBSzlIXMwRF7_5)$Hx>ayk0qh|cN_kFp9v z^?ff$tJ}11tg96pm z!qKK3K%_*&-br@uHE{K5!A2e?PYn^AlFbDxHTGRI#zT4ZQVIyHj?>$R7I(FLr!pgzDxVsn8_hq z(u61+A~?SeQ)(-hTK8l;t~S3TsU4@vzuibRN@b$Ud$~vWDQgnD8>P|_HBWDoYCV1+ zRp^z$q_XxYR;PkeDmctIJ|;Ab$XQlY<%U!##Y|3dN*8#*=pIJr2)!(OL#o0Mix~p8 zK)Rw%%foLkttkF%vR#hQZF&V;wb$9IO=PQ<_cD0{ z{%l&c9HFn~9?UbOG0(7ITcY5vIKt!^I70UrBbZNo%6#H`lECs?-PiJGlTYLb-B+Gq zes>)6yN8+I<-PQMLif8Iq5JuoZ2z#_nScY?{=pHZJ&He@_79HG_Z17a4{m4s;9Ry3 z@?QF$TA-TtL5|ROweoCt?!HkvLbsAk7Pn7l zar<5txAR`6sF**S;&zVEtz;j|CeE{L0<&y__cF!p{MnREaD;9pds$YL!Lp*pW7;w+ z(K87CY|4r_Lbnp0c^zb#*P<)My?8HER>Yr8nHNXsR&s&mgJW1eXnV?q%{k2CST^~e ze2^n_E1ARc+E|v?9%gwhN0@R>{%p!?IYPIR^(@=&$g=GjEZgS2^c>mR$CPbzgl;86 zS)HLGt21P>Is-?TGJ5`OsxxqeZY9|)3NN>Knp~Pi;k=ir&cL5dQ8-8FR>F!zm{p4Y z^JndI`+7zCYGhUB&#iqvRt%(HZ}wn&t+mg+R*`f@p);>46+ysW5dA)>1>M~GDnl1V zJYuwZ+4s%kbfHdqU85)>A^S|eUtTN95&!YK#%Db*`8Pz;>xld}7Xyums$cB6 zC_w{xyG3R73XsZ-`6L?)j~*1sM@q z?Fspnvi<)*5GK3gJal{eHy$Rt;t1W|{taQWD~{0T1|YI{i$03teCYE85Ns55>*LRn zn*yoh(8zrLytThS?e}UtdoGHAwlsWbLppoI7vp^B^Hda}kD|2?oDY4TiX!xu|I@=b zAG{{ZYoxzQ1retGoaK`6HYgvgdz8G#b{5?v6ie zob%Xr4QYba*Z(r-kcTciw3wni^tC4XE*)JIq0f{!=l>g_x9IyI9|e7XEXo5SO#2{5 z==1+?2vd!WBlOxCKxFY2eLd?t4*z$ZH$WI?P;U{}qrOWNMd))YT8utVMG^XXw)TN@ z{=X6WTC?_nK2evpC=Y$*i1YEk5qgUrW$>}mqmQCIAi@-7aD+ZL|AsI{862TUAOD6h zMHw8S*N_3iIOqCI=@9@&=+Xj&anAL%Ca&85Js-MN>lw?x^U!Tn9Nqsdm9C*4k^N5| zM$Pq|UbJ1^j}_HipIbc^{dXSF*TVVu-+JhCtH+}Ml?T&-|G_v4&KmSxOb-^jnf?mY z?u)z9-QR3Id8EIu_xb#zV*=T}#B!08N%>Pt@$hfT_RY`x)YZttbP6a)mBs1m+(kWf{fg=VW!HNZ zsJgU85xTquYRr)+dU5+mqfR2?qx0^a?^kqog&8)N5N2U|wHEL&>S4+=Il@%yvpO58ZwWR5*kBNCSjX4>+Qm zDz>M?3KsvD(PdrH_2s>O8C@Q?n=14?e*F2&d5mA`x6^E8!Y>F@Ud#2+^IfA<{$+B^ zcDMfpValC3LZ3~J7@62Qr`qbazaUKcIY;PuJ4Y1n(Kn}GP_thUupXdSwvAG8)!755 zrO&Ninc)Af*Lnehf#BT2TIjza^tpvK#D7ER+{MbBUO_4`tG>s()( z9N|=FG0jGP~jk-5T_o%&!P(=5IN*zF7UDhpAG;Dd`r&dF;5lCC54R{4Zk# z=SHtmaRk@q=bva9(3j}wq6oc3uiSB|^om|lgl-Lbb&w-;N*v*B;j(+rgB!bGi#R@d zEt5;1MW(EM;F{V!t`$e<)}Ze=BAO$5SDN5D_iUYCMz@=a>8b?}jCQrWX*=5a;ZF9< z5x1q5u1N>|enG^}wV?q|9E?_SbaW$He`@vrSV=gu#D2^Yxm3FS6sRUk{8g$p%wJhB zf5j2{KB3p)enm8ARuagpgd_C1)$57BBDgj`|KLpNl~hhioDWlf-lA9H#dR(snzB{v z%2q8$=%ZMmnpW+vQXOHVo5DtyBlOi-pqfVaS41fDyLFl0UGgy5l|0!#$u{E zb4sEf!muB>i;Y4s2DKAeZXdljfA?<4Z~ z`XiGRN5wrz+s}JB!W0#Wy>!b*C@^`6bnebU&2fAZ`A{J&3$ycZzr~ zQwyids;89SDT4eEde&yQl>e4ewVi=$!Aspq17RClR#)d3{r(9at}rWQ_@ z)pRMpUj+Ff)O_v&DJ>*}I9LC9--p$TDZk?b5uBf1%c83jq@2Z>q_*8wcizi{;Jx$= z0%ic8R(F%u1!a({lYidcG1XW(npLwYzxyLninuvL>SUWv-oCIi*1}B)&cjrvglL3Z ztOBL6mPsVm|L1)lR#&I|j*r+2Ry^A=9$grZMT|$$UM3!#pI#$v)V7Osq zdD5biyR~(3$t*{*_A#|^sn|JZKEKJspLI$tj^|4&jyY&|Gt-O+Sn)7bLd4sKPdB`g zV)vVA3599G?N7*q^VTVC?0ZU*e|v7Y`7vEUz#EMs`pVh^($>;13{|WBJcBgl1F#po z3CeDsJuD;lzni1w-tI4q6-02)r)L>w{0>T=hudl4zoi)wrt#suO#DQ|!8*ldx5_n0 z@7SMb^w6&K5rvuM^<7(~CH9ZC!Ye%lsW@GjJL|cqgUcf6QHl!*neAdkn0Ro69^=B; zcizlLQrBVuWI)}YcMVKYG1uH=?fhA%RC!;vv|)M=l7F$NwZmMtK-F`q+|uWytQ!4D z_Rynjo$D=}F7ym0eh96bGf8rYO(XMbwJx%1#Y|YwkQH^W)L>OQ>D2V+Z4pxo=V9_) zkRL)ZjZR25S~@v7>E}He=s8UYF0CHhO?$FR%B`G9EXTdhgLHW>JRtW-oakMFB z;Lmz2@#V)esr!OJ68y!6?NNFQN1Jvyky2>cjneh@jfux=$;iXhi=$1^5`WgCD5nOm zq(5wIN!Xx3BM(yxr^`)8GX=z)3-qJJ0JG_@E4zk?#$oO1(NOu;aH2?Zoip(yi zo%c>Butk(akDL%1xB7@=U%Ir`cUHP_tV~jIf5myUaf&y_KK%LT*`49rE$RA)Qko;< z0qGWJx7B&CN*?i4MBB4ysWgk0PO)f-drO^`e&zuwA+-J7E$JEK;afxx$U{WzYw|>z z;8srS_x|TtndX3xm1*2WMEBgIQsnCMTEhOHGiaJ~I0qbIntv82GQ0Z3?5ZBKE8a`D zQQfXMLbsA)v6G|>X6+}KwR42Na&&9w2-8|YXeL{OE^G~UU~7;g^!2Q-L5|Q@6kq2C zw$A5eyk@7m1**xH@MqIH=Lp?PaDQdb{MBmauXr!r_v!wMBTU{7p(@Oau4Z2JJoBO) zVe-5D*;J+A2;C>zGvEH6`F3yS+j%eD>+8OqBXm#A_mAyt|G3Qd5021xFMa>u2z~cC z|NgnOt)`v!v_u*fcSt?zH%hD5NCRF<^V6OiK8;Bi-f4hn&O_fHKLovzedjHrhfi$T z7Q-!PF&sze@t_{VafCh}9#P$-N#W_l|AalWD;PWL5i&>UR+4^Up`?CGBNp?1B1~~R zM0130iLY30u#M#g29_J}UZ!kKF~+OJ38z}nqqbYwm`a&A3|-P&6LujeaX5ib_BLS4+kkBbg<dR8c)>O~=->_1YQA!2n)? z9KaAm7y=hpa$rllKHl`7Pm`3zFMKJagwR5U7{CzC(`w|vUSAUe>16w{N>Y+i1hIl4 z`Z2_`tjSUt1A74~|R=tiqFovwr=G$?`?#}LU3vHxW0*05LH zo#wQh)oi6$^JYa5{TYIfZs3>OF0fbnz-F{pu{p-M5l5FJQW)aRv*x>CFF1oD!j)u@ zX%oNZnO!U)pWfw6r>4(Ss_pWidu*L)4wh>jL!&7*wU38AO21*i49Vz z7R{*R#yN`fSP!~%sWY8##&1Kn7SQaj^Xm4*c5W%JJ|!#SdXrsgr}DFu&D+~j$S*hF znYNj`Kq-Bk)i%%_%eEx9`d4}1f%CHaZdZCRX{M4}u`PxCAR3{wm-4j^YHhr+V{`m? zt~ae6KUo=g(~m+lnD438b&6ts)T#; zOr_;TM+*5JuiBQH?U|y~+QKWhbN`;C&D_)g@2KrcD%5nNlW$B{q9)a+kRL>|Hx6^$ z$&@AyrM>r>k=Hw$(S*x$l|I9qDdcy@!;Px_XDP>i<8Lcm_|}{lq>^|>croJU(45+s z&rwp3IaA0Fq7fSAGK$=@|CG19SF{Fg3G%Z#*o;O#o3D(Gc4j;#SLi}oZF?i{d~Tyb zTY~%`n!Wk5qYQbtG6t7i-q`@H9j+CKMrd03*V?DQX5M8uZrink275uj0_Pv0h67U!jVhL3wj2)y4akbFGH*@#$dP1(h}?i zM;gu(LhUzi(&p05vhCt-_~~75I^eG<%7zvG6t26Fliu|0*lZ>EEkDh2AF@IlI^9J+ ze>++53=g-sQoqV`l-sY`(xiRfbj*WnWzI*Aa0*$iRbL+~C+E?1^kYL@Ee~8Rx~bqxpiaGyDRi3c z6s7)1jtDF6s+GyL$5SR?3|ku8tF&6$WaUtxKZRZip^v?$YFq0M#Thv#Bshb6`ufrl zKgKI#TKZB$r2u-$Vw^%P_+DE&a-G(5(_p*__cOp2v+jX(WXxDa9imW338BLoeKq^b zgYo->!Ge`QNe=(fmX19>K}p=?%XmcBY^P=Q?17(exGcjKD3!<~eD+5}-}mWw*8cqx zv{$%O57-ex_fF4JzIK)vkIzk384}L1w=)-G9!|7{(|&4z^*4vJ-r;O-p+`;7)-7_KL3>PAfjnQXT}jQ4ukxS{QDb zSq|@5n54lLxGzE82%Q-3gBP^0$G&D~3{YOk1M)`bwf`k~d`fRzIPARywS~RJu{yQd z2UqrABON(!kD+Bi+l6z()?o9avh`j?emTE4hP@zKw8V*zZyUA^>WD}7EQ8^?gLVup zAE5wgecrnfrE&D(SPVS?T)}Y7Bh-1$YD4xvo8*Vgmq3pLeTj%LzfguezYv4BWtEno zw}ieHdROKXpM2Mx*2Upw7B({M1^qen;0X0)yTKr~8_WvG5~3xjtvFV{rKA|@u^p#a zsR0H!Q*d8`I}t*zJ~g$gormMX-W`N!3GRJxw?pUw+d2ENopZ1vPj1A zwHEUr9&c{orNLfs4~M%pLMvDVu#rUoi&+E!d%=;0`xT1-Sd`KDKT!sZCSZ&L(Fmon zNX8R=%6r2i85ps^s2HMuMoW1tTAI$HB^VV!eo$KW<|K>Aay%MJi&#VkBQMAgq7h1D zQD5Po4RDV-u0kvd`N1(ns4|NzHy8Aid$Pz9Mv#ynL?aY@#8bYALUElBRs{MC7)`>N zMQ8+lE>C}7C{q?8LyrUbK{V5xMd9mN6#jxm;n06Te$Xmel))nXs!DDAET*{-Gr)BR zEgzw;ESspqvWdzE&kH#Yj1%DMLZ~~-SPm~M<<*sCEHE>HaS24TxSeH1Q&?8ii)BU7 z8eov%Bs4#V**<`OpKueCp}TjmN`;5Hwc+E$kZ-x8g8&1JY2BEc)tjGxK0^$ zTnT&HrA<5PJGz`2QG(|mCpZ3P=x^IHFDWKdKtQ_HVxsAwuOF50ANCB<|5=PYwR%lC zzwU4XTOQSpqOsGEy0Mx)g;vQbA#dO1Ma4h!N<5NDU@s_@h?u&kCwX5YTvKYF(qPN| zjcw_&NK19%3MX3gy${7ZE!2j0nlhUV`fkHIXW3WHzQ!`9!`M5fPw4hW_ zS~i2dQ%U!n8CugZ7Y)!G4E#r-D_@mU$ELKPFaNBz zS5RAsX8x+r0J65>Ozrce(SjvHx&wM(I{O4tU0?G2d`h(;BzXG*tzSzs8MZ*%g*J`Q z#6Hf%|BShI&ely>QRh4{Em7i*(rthbHRNI%n0ii$2;i~kUC&@5PwS~wIwh{b>$hcE zx!y;`wu?+5n%%EFmqdEbpQG)*FhPcrKnWq5`9#MGr0+~8t$aZkhHD#2(z}E=Jr{CZ ziHr1OQZ;(AP)m0oXE<;m1;du+EU$^|zeK6-7(gKJ*Ucn5xi<}YgSMEQQap8KAj{Wq})jQ)O@CrAMHvZ8ljXyJ@A7+ zPsv_|Lj(kj03n*?oW-2*Us3(#j*VRio*KTZDAHBYF?P* zM{=`=YJ+^MVmP9(7n~;+S*}VZuWHTJ1{QYFp!Gppf~$b74+|%9`(c>&XGm)TEgbd| zSJaeix3odEkoKCbTIk8(sudBNE3J~7&3-0%l^IN+=Y+lsdOL&$26V-NkwmWh`$`SY z6r6*bt=iLD<7O(AI=5zXUT+S<0ooP0M;V2{mVX>N(5zlFm1b;hyXHjEs4q*Eao#Qr z@!|e0Io|!M{P24afxUJ`N7JO+OO+!lT#6uko2@hW?OrAKzBHIjk)!CdeKVBeHf^Y- zMMpYmU_ zqv@8s>B{?At?3-^7`nRe66IiZ7Yfnrz3uzGaEo_G<+f9TH8?)dc4ZPyTl5;Mw7tRe zs8#kK<>^=6%KOfFk^z53(6iBFl{YKhDI5hjh6r^tb2Ip_-Y3tpO(s3gMAFL(#wgWK zxKlU^5RDM+S%HjQTt==N6G7^0?dgdDS&AXhokE=;8llws<;eJ(73A(&9fZ+^{2(Rv z)rjimUbnjtIc?woVFsa25X~Zhd`o;L{*`>RLUX}N;P^l^`yx<69DaQEy8L(N`5Np6 z#|Mr&ua}f3l^1-HZg+_!aHgQPa1;>Ak1Ankv2mT;?CD?v?FWu1L?aYF;g0;`;(2+> zhhPG&xYKW*a8u7rLj9+bK2nzug&qxGQG4j z3&ZJvrDK#2{_Yfx0?cs{x{~ULXS&wKS;e;+U@vHiBEom#W%-NbiQ{9;1WSZy$eUFM zZ5J7)zN?Jen1u_L2xqPKmGr7|eX})F z@wD`!qEu6RO*0g0JRFCu&(a`w*bAar++O;&)-%KnKYC_HAa{uFwmghxDx;N0%e|OX z)#o)QBmE}Hqh>jgmJrz7DM2A!lr=f{y%8TN>MmEGM&d}%>yV-WGxeU3( z8VRh5AT-)0&Je^9Eek{h90iDG-^F>=TkFzmBrbcaR34+beX@L)gyb-!F zdB0YyML+!PUNsGB2zx;^i?15jA^Y+j@wSzBG^im&Cp`_IAs5Cdr)soinim#&kctld z<&XOuNLZyn>K-v#8MLb{z33NC7t`U&oVpT)ln~nS+Mr!r$G)rPa>y(1t1k_>K3;iJ z;7g$-uwIJLhTICIcE14J&3B3hxkCh`#BRNmY)Pu7l*HfSe`pTYfwalOETvQit4#yh z9s2mugH^^WTatO4IIOEDX*jjD{H0SvQg@;seJ8Q=As>GVb%K--l0I(Hj%9SgTkGtS z)4!S`@7w=cQ%di)$){2NPN3F@*fM8sDn!y0&g=okd zp>4xtQsufCemU{Dc5$H}9d~l9lKsYyLUhV37Q0WIteo5zz%=jauaMDmWqIBEx&$Tr zQ0uo7lw$!w6pjL<#3Gru(=>U1OFXf0BMiC2DjuxKv6Hxoi?o{GD&g*BeS~_ud$daB zK2w!9O#>*TgwS8F8<0IqTj0=I3uP!T>;=*6=D?0vQsXAV$8&3HV{(1yv(!n7|L=hm zqN9uZ&~5HhmFZRZcNE6;2_w;4n#&%2D=^QX(&}v{E6$(T7v8`qKuXLfKHH*MZCED1 zf71i!zENnBAzLZo6F{LPuri6z>|3E)*3ANWs9R5=W(g~hkP@q~^mixw6F$f_&wi1i zypV^8I2$#P&^bBsvMF8i9P9hg5q+j8?sbAFL|@vg()zoymB&rE=6A2e5^d{kX>LXd zk`|!S_!8O5ydJ^K!|9^{DIs)C>8UxE^N^1<8!A*%VK&j@p+arHu#+EeZdbuRDv1f3 zCPkle#Laf9)c<3)a;#w>g_4MRbay?$5n^0Spx1%KAOyj8k#PqwnTUoeF_K{P^sUR}xcoKDhrn@<{Sf&3sP=BWpz zk%RVj@`@yR&blVURRqz{OCXdTi8ZG_jyRKj=>~c-xV9lBcK%_Zk{>yP zYwRDbLGBO%DIs*fSSfN!iN*u%nhQG)L_JRY)}A{Gxc$Q>de zC4_#|EJNZvqi|42V-4C{Nk%>)Q<@Mbf z5Ey?zN#NejZdoKWA#=Bu#tu?x0=Yv3q{M16?Me_SHU#h6zEXp+2t>ok38CWEe%E>q zNWqcM8W>;<2X%s!5K2&6kaz3)%9ifU1U+DU1!Gk94LbLCTAAzi_*Qcp0=YxkVI+&t z9&3B;beBHZ^Uz@p#)c3Lqh)rgUw)=e28D|yj` z?zo`OU<1sfpdOGCLVu2`M4Aj}E8naeB4kBScCl)(>&7;NVqXmJdfJIV?of7^8?uvX z>#OqP*LJw>3kL%8Gl+)yCqf5QPrP$`W8C+>l?F3jm_b5HY}KB>qM0LKDQ#Y&P#t`E zQK8lYmMG&_22i*Yv2)H(m@MqL%BxL4BVj*>y;LWa#xV5DV>|-z`45j#j0fxmd5DN- zk)z3&K6RyI$FB(y0NgFt4OHoIR=LGlJd!zOJBT#yR?jPM>^2#;SnN=##Cpwc9Yn?5 zxxvA%q{r$FUduB+3NZuhbue3{i<6cp{igHp{r2$cOTNao_R9TwPJ=Cll~iMm?9jqs zD#i@EocfaF4b!%ISMrW?{s`g=o zFuE`zgLPkoJWpQHN?PnBGx#2e+kAc32}v=}2dVrkJ1~ zr#~wZGrZ~93o=dI{z6%q!tX{cs~$<7T$v?5TJlYUEs!6igpi@dC?a2LuDyKqS=v*~ zn||6|T8*66hC)f;xe<#K%~D9<*iqVz>wz-t1+^6s7k;FX(Jxy|)svky$Q_~~Z?*=D zg_3U$>*d^RM4+}1{qQiR9zJDMn-aVhUeI(gS6o3iFn%A=yQLv>&ZgN z{-!~Lv>-a?C0jS6&DDB`S}-2;utM5sd9sCFIdV7@(@A+{)CO^G6rwBbQ>eLxg<7e2 zONOYwwx4td?{f4D_>VOl4l-PUf z@p0s!(>dvOi4p{IhrJ*gA;%zh@*((`{GzcH`4+3ttJxN+wL?n^(b?nL(%XsU)%-L3 zByQlM0CJ{m1#Rvp8v<#;^ICY0%g!e1`Vxox73E-`It0>!Xu8gy;;8cK8RIFk#pM>H zap&{$$dlDb4W%ue@u0lg@vswx=w(a%Y56PV)iT%lxpSsReX_37Lc>6+5J(G3BAz?1 zwQEM!ZgQ6!U2`Fj7DQXM3Z|btEY&S192t**3r&dIKUd`@akgZ1U@+ZSySy3};z%zH z_oq?e6;x?ULkcM&6#9+b4X&QIZ^P7h0%<`>;29h9ySAUTH}SXfj1&%^5h-MX*1@*~hr^|Ak`}N4-ymmCX zqq%Cn(4IQnYDX*Qn5#ot+p}AsA@o5LOLf>NexKncZb0Tm70M4C>Jr!j`9VtTt&|CS zw36E=NM%|llL4$Ay?AUH)#Iieg_6LNMpiX&DNTmV93x+D5H3gs5s(tA!|k;vhrV8u zKQ*@}cj6*x$3|tsO#|COsJuAuK5hKV@8bzz!L~8HS_7u{E_a_jt8h%@= zU4D+dv{W1!UNw^5xlu-)FvCtjKuRpis8^4Cu)icHZD>FSosFi=LyM_at?Ve25K>~N zedww5a9^l=$Z{mP-Yu3sDD_k+ebSLay6{|;oi3el_R2mIFQ0usQqbcOxGf?g9^G53 zb+uh1zr2w^j>Se(sa`SFZnvGl1M)^_(XpzeYma<+(5^NDqNR5nb@h9yEScv>OLdH+ zm9-a2%pz_jz57)mFNRUM#8fu|dkuIWM;$$%D(_1bMLgU&Q~ngZOun$RkDxg`QHH1Q z?EbD}HGIAJR5^B{k8peEYuc2GdK^C8QX4san>_bPk{}iA1<}l|YSth< z8ZMVdKa$9It9Uv+lPbUe=|rI(P(OC!?pg!y9(h!bIMRy1(>F*L-Y8%-{eL>*^F7wf z*tSrEE%3Y!QbK5Oq?uHEPp-VBWU_FgIJaUaI<~<9rGs}<3i+`&k+SZ~Pg9S{jcF)> zE%0;^o=qY&=lyZRg+Hhq);Ed36L5Iu`FTtnosqR&@y%(*=DbJK5@dZsjC`?j6oD;J zDoBa#YKN+mgQGm;(6a%;St>jYhm;U{^N$&k-$uyq8b$~_;M_od2n9XZZn%5oFS+4? zfx=ipNkoM8`1|r}HdYS#p~4Kpv4UfWP?N(JSEsm*k?;hOgJU`1U3`AD5MJ|WVyk> zJ=*2aOu1Lx-hzjN2+@m1zn^1xGoq6e`+hWmJ{L%~~=pw{E5CJJM&BN-GSp<~fEQ$5_+{?m9wA zU?j`#s!ekx-=Z(c$?jG{ybC3Pu{JxK(4t7vq$YCzR;7iQ8cG5qa+c$SC6N7%j~QNB zJrHsO7=?>cnSb^mJ#L(mJH%NExdD^}W-=_wDBp{mIBO?wTX#{&SfC^@-(lxbEryei z2TvGwmma3UyawhUFsEYYIO`NrN6VF8tt&?$Ehq`h`q({yhl5F4nyq}e|6C!vgJ_r= zvRdDP(PZziBZeFrk_WR%uPOFM$ela5V(MJ+o^r<1kHS2f-6^t3 zCwj(sVl#3FzLRmtq~xn5nSh7s7S_{hd|=B^>i(?MN}ARgXzB&XwM=9Pb; z62}tGMyWoXji(SHRyl2HeUd+@d2W3#mB1EQRfCjR^g7Uyl-g{a=N0QiAYFJ;2`RCY zhOYLcl~hiOc-U4rscsk1g!(KUten5pg=Y42r{#mXD%;}Qv#|aC4uK3@Jxq! zhCgM}(cj%LF1fLAn+i$@DY2V?>>CqP`V`BX@YarawTU%a;*)1Bg*&O@jYjL2{-k@{ z;=I6uI>IehNEcE<$T`}N9Lw35cjZt$0Rhi$Ae#M#+XEkRu*L1X&FdV5dwo!I5fSmc z8TqH~-Mk5x+=V+u&`O}au~oY)mh?J))$7{&(xjblx>57V$)EE39qdbU!|N(36Kc{S z(^IH2zp~alFDla>|3|qjISPUiU&0;;L*PW|Thbcxx zR+Fs!F@6(heDqWAjw5#FKm9a`{s_9^ZFcate0Bpu8cZrjYhGnv{2?G9zeC^0(AK@a zdY5T;nIV)neMt9C#quhKUeI8#$gp&}p=DXcy5^^R5i#}HKoT{)mSp3xU4t!9Dkv>` z8?ft0^5siS4a)oE^Dy;7d(VS8;fsW2eItISIFOIV<#&(LXf)AvK(=dvg7hm_c_ zzQv6syGAz6t2ZT4gLI)(_p3~$o>Aw#b9Tot9=ms>lg$l&^H_h;UV|-=AEdUaI5^a%RtA0MQCDk4>jIUUKQo3_%ky=J&;%bz~6)uiSs zL=3-^NLL-QQ(gttQ4!j>Cy{(P(m9u|xGKY5kl*YRqiAr$a!RcI52icxztp$!Ct@2g0<-z;7E(ab}IXoNHe9}?2Cbl!%|qEruUBdA-V zw=%7=ms)vc1U+B6JbN6tXL53@$7t05z8=JLg;}1ms2PT|pj1#=gdz@LQm_8bydznSFw_u^6`W0WFQc3@IY0JZ-qFRL zxcQsbwA82`%DdrF>KrE@>a%L1vTah33ME9yOLHO)u2b{c-Sxt087kXTrzlIB1q%pB z389jwYLe2g6<0kUxv$;O; z@@$@4%!u3?)$me`aAr>vUBiC03_? zXHQO0#n8~JErzrpT15Q)yB)c;W^3M`t9=Co)E1%mGfp8@LaD)dV1HtzXQQftNbeaGBtVCXraPZT}e zfaQtAtCV$Ke^e;LoecVRaaZftX*7wU=6RRDJutxi9L6GWZ)fj}h72YbM-|K4^x+R7 zT7q#KjGS16oYI}-hAhnup87_EaV?B2VZ_Pa9!T^ht^*h6m3VF^#O*MzfiXP0t2VS0 z*?BqFE2(>&kkP|R0nCcoJ(;o>H0Q_Fw70K%5m=1?b6%t};eB+acC2knc_B?E&J`6} zd+Ai=(ItO1z(J*JzpY7=k=N}vn*vG?vmhmx`#rpkLq>^FdWRw_g{y~h05ovBJ}ef~>CmUX+35nYc- zL$f}~aGgW+`mZYeTb`E06!a)+`*G`me@*^O){{y`p*XeB}J5FH-xLyNI5|82e*z@+Ms z+@APYdC0R?l@&ZSM5m5tcW^3AR{lA~HSg!TSo{5=inms(Oj@;WOV>V~s9dNe>M{1b zN{6qXqy*mfV~B5Q^|jQv033MUnm~EsD2Rv?70k)1pmsQ}$6yW03(=4_d%NZjU$Qjb z2G{EoDnof8x@k^ZnjSV$se99(Nww~WADL3Kr`%v^H4Jw$i2nP2TUxyQ1ZB_+K31_2 z7TSWDDcGs`bPaM}!^X#*OjJIM@Kf7O4x|kn$12ArC=BsrutEDca{#uy=3;;?{!@Zz zcH9`ncA26=N-W#H|F@P_uP0u6X@Ughg}oq}oi43qzpSd&!)>P?m!Z56{p5ZS{g9TW zOsv7949{y`JX)P=9#y$4IqeXL?|xq?L+%g(DX}lN9BWFfTb0Cn9{WPmknU-UT#^3**wSfvQm2Qb@rfR0 zd60W~r5#P{oyorT<*A0=X-79K%v6GtJQyPU(|GxN>*4tND63r9(xxzsj*rYzhHdgt zAtmctv(}DITFZYQCEvr z;16%juSHE4rLb+e}AXisldj#Qa=Yg-amqN-jS~KVzDzs zpH7UReXEaAt~&D3b?)4Nl<6`=p7Fg6hVdtiOCcrxoA+M0v444@-4#wB)gG(- z_#(;{3MsLh1CcZ2SqbfM%N?aKlox6% zB5ntGYuWy`IQft-9upQxhq8B3FZT0LA$r*A2s*3eSOxFnqdQ?mb<*x)jQmFle+)Ad zI0}#wLcMOZ$DWVPaiVnzxus7yy~_N@y|-;t@bFQg#W@$%!s=YOa8p82` zXm-=-Y&TrVa9O@~C{c#JAR3N3JE^v*PO{n$mOHH#=N#$;M}gUH=j(qA}ld&DA$i-1> zVbwxOpj9#+k-uqY-?YGOLK_L|10uv#J9Sqx`CdqG+<5UR8LlEIJMH6?Ph4;fdCuV+-8tM0pIkLxku>?>sqZ zs8cote{@~K$HZ=ZeNuHCap!mS?2GTfJ->~P;@U%&WL&yaFI9oM{I zt-+lh?wpVk^X);NB*)!Vj+@#L!)O9ZBI?ojN^4RX7sJ(>e-vT{h=7#Xx57%+AZ7A= zaIfGj8AcXRb{Ge-RqLCpeU_5(S>o*lBQmHHq{K4%Q-0)GjE{_WTMK%?XbHxTtPVFa zjQFLN#(l4jmmzm3JB%`!ziQZs;8$Mw$1`&wvV>?D$+FX>gNwAS?_=;(tJ@lkonb5r zV@4KPTDB+c66(m;L(MVd4rPZm2Nubs_8~JGo|o4Roi9P|5DoJLb{n^zC;RGIIh-1D zL4&b6M8jN!Rn_*(TEp#D_-m<90`nSNRiTR~PgR~>@K<4;!1nWR@uY&)VkvX>4;gZY zvcrsw)fp~~B1hk=@;b{=2FM+vVcy1m&ufn_DdXQqUURRyAQeQz+>pIdANY=Lw|J*xE2B+v6Mc;&3k5HjKO%T;Q} z-jAYff>g+ly~E28RSg%smaP;Kch;(O3wtNZeNm7K(FjG}?M&8oDdkl%`iGD^!#W&9 zGw<`XD@mPk%CnGt83?w(Srg~{$>7msYUFyawsdU4^LS+IX;LNgn0JnTe{W4ivm4K=Qd>KmxU(8a2 zPGZ_%_*o_JLt8e3C)YcZJv*#58|O9zwmkbF)2QiBmCl0{6;eW|OXv`CI&!||*TPH# z-_;U&*#%-c4i!_kzA;AO4||Yi^|Q3*sYf)}a-Nm`tp6^qjxKapAtm;OjiiBO!Iv4@ ztb#5w_!5`U>xrjAN9{6GD>rDx^msC?AE{Mrrq*@s92vG$yXHf~Zd#~U?le^)C4|Oq zi6EITGBliA62o5a?)lKUcP!Md7mFe)UTQ(i|5UYAi&|jtg)cR=yC3a-(o((GzOg!U zP#|5K%)ao~xB-)@rLz+mBDd292e%dwP!hOki#Pd9_b++Xi2rWy6uUb+9*7lt~vivsb7)*W_8dXGYxH4W3LKvnF1p5emL#A ztc?1iy1fd~2%W23oE%K4rqxhm1w{YIP&x>kt0dJyUCO>%ctAE+pQdmgNv-E-Ud0z1 zt|g~p*aCTodVHAE2G9AnLtb3b27|Amsmoi%(oa>6DL12=s6AiC(2V%Q%C|F37>`kB z9dL~GOnGB$YXOm*9Lwr{my|{K8wzOl{zv6WatC}wy7A{w0RhLy&n1S&7d}^3+dDEI zj&;p&!SN3A*hvu>wm=?GTDG4L?vAzci{*XYb7k-aJVADFbDi-peXlRz=_DDpfbVLl zkP@p*{5@Bj@91c_u{)K(wGF+&zEp4Kweys)7+#IyU*C)S`Sm>k0jr!4jZhuO!`kLP z)DU>GAAz)fDBko&u>;EPr+$K8LFi0CMN+J{hqkzFI|6$_zXGKdzB?#GZDGzSYF=w+ z1#Gr1P}bO`M`#VOmpC7FKh8A7NIrS3Vly$EXV^=$!~oyor0R}p+OB%B7_Mh%?IL1g zR4RG>WP#>Vxr70FHRy>%57*&JXHvH56wPhsWexgT=pRMD+c_^7Utao$Jh^`{ym(|3 zb$_>1F)!(&LW_YT!hHLcAe`>KUEU}mY}PoAz8-ZxmmyT(De`(1ZobRk+q;4fGnos%!C75d=boulcg!%LNiSuO$(h-SB5=1X$q@k4U0 z$V42~z7u`f?U)ktwTYT&*^xFJzf@_x!$pOZ*jJjXl_KVGJ>@u?_KaN|b-T7r8F{jq z3QuJUV>;49@>0cYx(l=RMc>Uyhn2B%SXh|Aqg*gMsV+FG)a%nkg_PKP6Xna2FIHXT z-{;AF{A}0fqsnL z_+2#KkW~3kIeqsa3~531>9Vo(OZ*EZ)Svsr*WD|ULFrrMQ60STl(2Yen{!D?{Hvh~ z(RXh$uf6VtQrUtd_IJ7=we8hRrrSp0&i6ae-xm~D+n={nAzipO*)O;RhsxLg`6zkb z7=d9gD7%O_jAJzSo-^c5cL!p~9iky`gf0!PN=~L8kS7jqgTG9OqZ?1XP}YoeP$7C~ zaunTgySO@HtR2&%UFkaH_{yVl)4Zk_whSwbqT{NRQ2#7ur$S0BgS>#W`F|=>kH0bm z&EftE_e6xu?T=~YwW0DYH9_D3WjBPeuPGNVtG<8DrShp$i%f|tkeiHdilHP>!c!X~ zXw`0IRrA#xu{CC^_Gw{E-iNS37}A20z+Ic&5DG0pR@z0&p$<_P(t_w8^Frz8t>)^r za2^4?ylh9-KRGXN-&r4TdJ;h^Z7!?YwzN|r+UZazty0HAHLt)C>+4t$o81|P=^LUj zqy_yh^vCQzoP`BR+LLY=vP(oj*&&)mWbNyct=GNecaIeexkG;4rU%m7&n?y3wmgPo zXYFL#)a&xo)3xyCIf3*{zw)Z*+xlw7ae-91QC=;ZQ(t{JC4}~Jw^Seg&h=RSupx13 zaYc@saHC_5A3Vs0ylwTVp{FQL58BBgyV4VuYw9*WPTfGd38c{Oe6eg^}_P%yN->8 zUJ%W`M>e4)2@bp>4|A`A&Aa>14@1kV^O`uTP$x)x6?BzPCnBMAJLTxe9Lxpr<{J_>=y}rcoxu$$J z>7X2o6q<0hoZ9SiD**v1u~_u37wHssOtw$8z-#u(lq8f?8;tc-p@fhU`_8sQ8p&O8 z+7LLYkyfiOre71DDUJP971D(<3VXX|Loo)H1>+zQQMcbP@_Ac1`9;bg zd5ssQ&tH{LcbE4RctGClHtx9yV(YU+zI^MWfGFDm(>wUN^260fwbx`i@z@LH-EJSY z23J@_lK1iDgxvXun?g&DJfNI7=&y=;#EczHnsq)Qd1p3}pj5CIM6-;(Tzg{k#~^vt`4afA z3*NMPlY@$rbC3%4fRtEnVB46aJ}qx(WP{00c8qFuK2I6jBtV69VRX)_QLWQR+^`hM zb(p92Ww1iipB+%XmkksUkP@pc?d?V;RkxP2K0lJ98!EJCfxsArQ# zlYveQ zOS*@UqqVnr+SRua<^yUjj#Yzt?3d;LsVom`e_w`k3+akd1$Q4wVoyx@e`H;CR8`H_ zz91Ngfr5Y{2H0R=180VFEG+B-6R}Vf5fKqYu)DjvTMW4Oj2r`7?C$P-?N`4IylefQ z@%!(tHS^4#IkWG?j%O5px2ukAAp%<>n@sQ0;_}u+OX)|Ar5hw_2DU^wSZUqG^Y9Q> ztmPx=e~#^gWgK_1f`1T5kqUBIkS?WAd!PNkJA|vvY>nF}H9ilf{dQh^e;d+HF zk@eiVv52%wVMDg$=D6x(yVyfI@7hI+$0f%rZ|xRJdlVwDC5p?a5GyX$i_<+aGyQS* z!rcIO31Wx2<0qOYA7c|e3rTw|wu}3f$yB&hFR^Eiq5OOIt+bybLf&iF3>hef9qp{Q z>9m>QPLDmreV2T~*0n^15*OH?KaSG51lz^EonlyywGf-{=VjlHJ8?W&AVNNuM7(Y* z^6n_9cUqBOIxS%ju_Zbu@~YzO%4=-=a98Qnhwb7yh|biP>xtlhDzXALUeXy35%Q^T z*o@kumpRk2WxkJO{lHV7e1@}KSyAjedX?3GA)j|o-DznkN%mTmy&f8#eQC~XmJwg- zwrAfqbB-rg?1_x1nNd*O{`a+ca7cTpSBSMYXjb~67lzS4~zdxiD~dcmb)BRwQ&AGcs+<;>Nlps0XC)J5XpXpJ(2Bj zm17I?7JV&jdlZwbgJ|)Rd*wr~M?9z3BOY~IAlY}}1%|(3in3m)IG6K6g%neSF*ArJ zR{8(Ef+58eVf+oeBtdtBVf50**qoO(q?jU%@qzay2;o|}5%I9zWVRnZN)~#wh047; z;?;=z`QK#KUwmX(f(W$3k{`#{iVsY<%+?)KIhJ7Gu_dy%XS!G>UEaZZ42tB~Uqr|= z=-8wIJ7Z;LR|*c0thJ~m*b<#f#upNm=#?hDdK)Ps9&4e#QJj7clZbUH$twKlB55L8 zYcaN-_;(9giGv;$*kji&9D9Q8qCAsn__6xzlJ6OIz^$+Jt#GvX70CKQFX}X-7j?=k zUoFiCdL7V`P9FFFz2G8!UF^FYN9Iqj#5B!$C5EGP>^tgM&Py~?=_Q(jL>Yi{i)hs2 z|Gjq8cyea zeJ*;6-Mcm3vGq0u-b>WrB}55LS-&p+!Xb}4%W$p4&GhQ@=9M$l25#jwl!rb~vcp}q z7vbLmx!X}5oGHAJIqdhvFE(2K3<#0#D{uEWcn8obG=)iDPc z-rpvvRoZ2F`)=EI5KeV|Dkp~9iJ$kX8hz%@Q$tt#Y8~d*Hg?sUr5259_?Pc4X`Zt< z6W553*f&^*_e3?6hiH21_h-Dg_34mejQC|iT|#-X2di_9aw4Hj1HNET8+>nDLwSg% zSEut<0=jjdBTCf&I(8-9rBPS~^^G5S) zzt&3#>>*-j6@~|b7sYuFpOD4U$)ViLxz<&<*M2-qO zdGUnh)M9JCRS%Z3YcT!_TOu#O`<;54-F`N2YlL`X^;Lh-zoOd+(klQ zyND(h^U&@3{tL62)7(A++d?lp%BFYXOd0whJHa|{=_Ii4*e=SWyIS$KdhE4+#C5Mr zk$_kWzclRz$2@c=n!#rq6Qx*AoI!a$s@|K%9DSpCos>^f_5f-hY9(bN(Lc(D{!ugU ztyS=!ivK7X;YF*@Dq4M7M6|KsDuZhm?r;=4NGqJ%pF_&txL+1r$)?atk3 zcP>%o48vU*<>4-BG99w6qxamtmHE>N0C#$nhiHmtxMD9d=#)|N$ZYBCgYxh+K(95^ zN#>5VJF8N>62}t@%0o2qeq8VrMfYgDZ_qXcwE<5rc&efIis(cZz3_nIJgFtVmny}l zA)2z{>#ooT#}4C{X64yGbSE>SDZh>)3Z>JMJdWOkh$h7B)8|sK1ivV@ME@v4gcHI( zaC8dR!g>DxhyjG~%}h+eTBu7hV%2{#?gy`~g|%=skP(Xr5kWFGZgZ}UwQ$9e5fOxl zB1G{xUK?xSe?mrdBt#4$T%Cv4!dm!Gl@WsoF^mu&Ustb#wQ&9T|A?$!`L}zt4{M=j z$cS6JGWB6EMdR(aY+j;ej(lX*)y(2!QW%mW90{Gh{lX;;+Ys& zRCrw8Z&_&9n(y!~X&gF{q`qC#U&9=3%=$K&#@s6^7N6K;S^un+l;hswMIB?}n_lYA zxDFb&WHKFV=qPUgSY}B)DkCu49?`^Wu)DnQO+RB9zc_%m4sB?3Yu#FP^KYtQEkv74 zA(Y`3XrY20>4ti|yy;D)*ndtSRt8uMOb#;?VRSjFBw^G&z z3V!;BCHzhae*0QKqe-E%>YSib8X_uOb zu1_^GELeh!P{<)g*|J?m3VU-&y`WWP9ZQgPs#Do1MkW8ufYwbqq|-Y;9Y>0gmnHSz z1u9G2RKbO(7;6@12JF{6r^|?XABPLyv95Yg_aQpgLK!lnL*u8z#jz#D^#fIh=vdP3 zpNWR!!dn6BPRvTjmWUCk%TQsQbJ9BxT&!a)WC26oFyb{>KTynV?x5EikgDHS#~VJ| zUId&<*e7wGA?p}%Q)PsSBAp8AGlt%j_{flFqW-T$W6f-9b>r#h^sNqV3lp7271k$D zx~XHWbHqp2F+7iYq3ri`88O(ko5(#Yx8AM7cm4L*VaA>-MbzUD>3D~NTcS%VygQM2ZP4Z zqP-~a-bznwlV4y7^3fri9oaHYH52D!K3Y09b`{tz){>d=V(InM_G52Z#$ECf&Rv@r zyP{gC3+psCDqFf4`|DRz=iTx$WKIqx$d_JgerwTfy(LyhWlv)xp><2u?kmM)K}#mn zS}Q-XXT()Yyx}EKI<|}Q$O4(iPkd0WSPrFo2`nl4t-CRDg|~V#ri#Q5NUw~wt|anZ zNVjx|V*-1E+>bI-;jLIV(Pnd+Wl%sKQQU307 z%Z>YO1=d1&GUA+OEv|S?wXEMABFR9`RAgMG=+B)G^SR zwp$!1ehEj2wz2g?}U&503u`P}^Vo ziwE*>{6Mk$l%t+GAyry;5rHc>o%D$l&}oK?zB+NSj;lV_!d-&?=QoFoGy6*Djz02^ zgZqb!$m~B-)U55M&;MCT$Ndg>XWUWgUF6-Pgi~2}eg6r0cgFJr?$i{Ycr;!_O)f<* z#k?@%*#K)H+GHxYC0>;3UrK)>=Ghw``GDwPRJ*HyjkF>pKLM|Rm@KQ zYZ>sUfW(-EwGd4n_b-8BPxL#Blcfa5yA0k^@b*Fxjs2NuQtZCv&^h@Yg=oAXk)Jcg zN7z-qV@au5o8v7GZ5GW40<{3R^Y-fvS_i$cf&dc;~uFKQ_*F?!00ecDE2a66pqgQO*&N8V( zILDHp@h{Vp-z-&66;IT#CCVlzM4lXkfD!``2DC)G+BxdgVCt1e_i%wFFeU?AqF9_> zz1ikZGuck7A-r?_I;wujS_|niRvXlyoO&Y4N?TB9oR=DBJe?rOQOhI>!e0`K@7KGo{J>gqFDo7J_jUaIOdwRZ1GgzyjBtWsY>JMtVTKnqSq; zVEQIj>SH9W>Ied*GZYR0Fmag4ZMMz^(@r*tnK z&nGw~rRVq5)sy-}E!Xcc>6uq7YUT8anoFx8>Hpq1tiCOhh467Gub=3&OF6QB6tBen z(&uZGS^8y?hV9<5AC%rDHC-KADhqM8w}*c5)pBL;$59+huw874Zg(#S>W3EuDz(nU za_kBAF#PA*^zS$Ks0S~MCmB}#w(3i!PdzxpcPL->Y;F31g?rSvOXD@H1-eU!Vm=%7 z+`V6#uihLg{RiRypDU*^_|T?B#>O99Mvp4RzEDGpx16J;!Re zVvq&$r?oiZ#F^i|j@)C`^YqAbZ`En1Vzl?~E7F^jZ`HUh9W|M2k`v-EA!-okQz-l`ssvt zN(hGzk1SY%Y~09gN!*5oBg98SeEhaiVoFDJpVm1eZ@cj=$;d*a6Te9^Wi`W!-JJoA%g5a;9I&f?iJ-10Uw z=zSd5srmv!4EWeuOgh~!dp=q_kC$fccGWA{-)j4yUW7-_Z8ih#U2X5hC+qlBL;PKfZ9dH^-U6d9Lue1dku0YPDaqrTNG`D@1Qfi0_@s zahxece?C$xJqs~DI*1T0V^Z`MggA4^k^h*OGeU<74K+lsshX0F@C@aI$UOf^Z%K&L zufDONXSD2ZQe(fHhUjS#xr{6sBV)@G;^+AyB9IWB7p5`P21J)#QZ5@2`^Sb5aaBA; z*2q(Q2QbtIMAr`C*@)pi4w05Tb@CR?3Gs3E3I(+R(V|yGaBm!t44Qi40?TNPfGTj57eYaBL5rxW6`)vxSc&AHcCL5)Lnf^Dg6M1!>sgxHiP2XU%#9}8+6qH|UA$VQwv zkxaUK-T7Vi*VX%1(oy3OebYWi#x)Ozbb15y_7%MxjpKIMBpo#l(L=A~j6<6|oe;y; z?9LwfTZa@KH4f3`+vR+#*!rglak0_3Y()H!>pE&2qQhNIWq;lAF~12>t6pi{gL?IK z>w6tF4$;-OZ4Ml+6hBn^u=#{aEdLd}^nQfc?=qdC{vdkfi<;?Ki1WF!UZ`*m z>ZfPPcu;;2L;XSYq4i1G2>Y|E31J;LHCx8@uQeFz52BymUXzXJ*D#3?GsV(u89y7` zQBZ#no##nfHlm4FEkZo2wNCF#z1ldWn1cF)=;hI;vk}Ey4w3I}SG{%FGRF3CvY`GT z`m~;zjTlt7JZWOasioQD*nI4^1@#Bf-xG3Vl#4k?ezm;8IV0~bYUrpxh;H&VXB^8O z)J&&{_=JAhGID(zsH6TM+WBkFw<_(KM2Imxy|PChkY~D%`h)1P$8+W*dGBgMTsWO+ z$(r+`7nkX%KZt%%t5){N+kVVi+g<9kwOHoG^9C*58EOOS(pJynhc6V1*NO%>sw5+A zyG0P9d00V)+JI=$Xht?7HX^I=WDL);Q+6jVHv3{pGR|dovgMqc$MA z&A-L75p6_XLaa#5K@>Z>z>L~}=+jT!vk`9=5BH;ZxOydZGmRtROm_=v1ET$HN@OE; zG|79ItOl#?^{lV!&}**+wE@v-Q**{K;K?{byj`C2bw`(dYe8*5^vv=Rp60HHe$H8C`mH{Zj_AmQoH?J`GauQ9K`>HU>Cvwiu(T~#@jV7u57*-IiyrHPd8e8I?H40n3$VNCC| zfas{s+KKSWBxCZfRm%RSEqI}FF48!t>QnWv_-dfaY5fH?wKw1YUGPq7XRod9@}CS!~Zt!AN`V7>Cd-E zXnW#b(7*QVtK61vvtxL-^^+KuEPiVe-1u1qeRBxUTYV41cCqhG zqN}l}X9KmVKL3!6#PS_1?buLW*?%*`lF`ojl)!d_v^pz4s@M{F_4};1G`Gk2>oc1uO74_;t$O%hQk$ArH zOHqa;xDLuAw+%dLj%gIjw+)SzWP}Z~5>H1A)tcowtD-#OTk4co*S92a_5B8aYU!(c?mU|RLWcoOXsgFi!v7yfD<&;vw z`)9mX$KiAU@we~kX_?V0kuMfi6)Zs+*b?d0(OC1Xy@}kdqo0CnIM(`^=p}A#PtfX4 zn@7D`^l7gpzbTR1@q+$XQZ2u?2-%yU4Y+E{u_el69i48TZBFFh=esMo>SL{01-wNR zp+Ked%}Zs?#hqj-)!4hxD!9w;i5}I}6sTQqEhnCq$R2MRelpV~s5DXwD0{ zk50v%1#9{L_pS0y>`4f#urQ15l0@FEWup{TcY zNyfe<%hC{mG7wGgf8_gUc3Yds?K{-ATwj)Rj!LiZm_EIzmx$h+pgAXHi1a$HVoO52 zRv|PO?VPRV`smLJ#q%@ks+$pkJwY_B4EGoKe}9_54@Fz)i14jjOf0`SN}JWmIlbf4 zpSsoF80}ExGLmtpT&l%fEuK#s<)mW??(NtT>D7p-mK7mU+*Eb7bh2!$Zqw7xMQ8~N zo~Li?NN310gEZ5GPb8zc$8U4NGco)|$%)dLA>+K2IJYTM8@upQI-)5O@aqh7$$W9V zNA3^_F`|o=xZZ21_Tt|&>4+vv(c77pDB9IRx~$T%Ej;_;nCPVMFx}j|+YmmlQ;OcV z>xS&R{>T<(j3ouD^O#oQTA4n7(%tK{4A|EuR9h10WRUL0RMD+x58`1@c1j2wEutxQ zFuJKSZ*3Q@)yggKcGoiedO)AW?X|bbHH`NMORD4cHq;K6X+|=t-RiB}T+^RFJ9$Zx zapumffQ0(pv=2v08HlF)c@1lG=iS};n517imY_TwANieEZC9Gz_u_qL`bqW@N82E^ z*1igw*P3wSWO8e@#=WxI<6J|iS074@RX!}Q$8#;LE+Gof@mC)XsH1(^6k;HnY#E1p zDQmy^@rHF}n+*0UPf#uO`wL&Kd{Re}acRv)|06e5zRI26wty0pfz};5w_8nAu6}9E zC)O-2eOtM8$6w<%>2@Vzi#UyA*w7YrydPfHHUsdH1ZniwWj`> z``z}`tHn(xDSwVP;mxX)5?F#Va7>huJNuq_!JuDk;qva%w<<*5P{$l^sPXK79!!#P zr+u>W@4&p=+q$!a=tch8V>$j>1JM+hVRcwpv9u5`F{`bF2>PG5*FbcZRc*9VIzBhg zAJ9cY{45rz+GG@<49Y~KUDdkk;%C-cTF_YPRk_~Bl(U)iiqeKg5@N^uR%+-{ckRrW zD5KquAhm>#ljcz~ju4GMY*oCb6yYP!wH8={GUOTj>3l|+!yWh(wT(dOI1U-nB-llN zV=Q6E^A43P+iv7>Et}(UH4^{lOQl|wT9JqKm_JZa+aySq?P4!G@pJw!)v1Lh84=`< z?nwUVf!>n|G0E6$nfc&7Yy7mQz!J2Dqm7*240Akh@fdW1*^~>H5ZEh36Nl;07y4@t z#=c+bF4^?K8)~43pR#La%-4JGpTTz43YSJc?SKAZW61x!uQZP0&zI=8Z_Z%_clQ@q zg1#HMS5Du8b)ipSj#nZj8HZmFO3$|-U0qpXl7aFl@9v)?`tUUkSg$_)BpEmklt;b^ zqnyz0-c!02QKi??fCb9HcjHZ_CVo!Bw{8GS>Df$R3Hm?e_s>&4l@wclO=0g`6baG3 zHaDskexzplH8v1U*-jtJh=}`6oS(81XwAMnqKVO=bsQGb4ZyEnc{ZW-oQtu!E1lS{E)equ-vl>gr()3>mS+k=~CQ_J>`mUrk^M z(Fz+A&3Uv6!SxL6Em=}8+KcJ=3-jRbB?Z>PamWa_4feuGcjw973ke({em5CW>4vKi zOI`Tb7I`HEeqBUU?D-y5EP3~v+5NaKc{3gaw>3Id%B!s?QPzmO(9x*g(n@ovS(d)l zrc2et?>I-kz0rLMf$jS2X<)_IW|x^5I<_Yhka@dtx%ZU(UqTch>y*(px(A7k#%fqEg?EV!TpA@g0_5 zdYk;WLsw&ZqMSg>$3N~hp*`qc}sYc_7vg#xPgBcq*-C9DRjEFD6MmfJ%>KEHA z-Te~OMT{-dkBvS2S;rETA-@~G$iBTeK|bNF{&^%B=yyhWv>TKT6wc`u?mlAqJI zQ?OA~f2($0>}jBEdZ}q;Lvb$Ska8uktiTZh!-j#cFq%wz8Z;DFj$c>ux|fyMjqznl z`CZEjgSv?2=QumO=NCgiFvc1n;|+bQ2_41uBG;9f1@m!yHyCBe3^W_^bQ0{sI%Q|C zd=k4c%D|TBBvYlMaGo$sdDB0?G!Eq3kr8LccM1J3*o|F*3kkmn^{RF?Q7OcU_rHHn@};7m6IrLo&q>^jT{l|uEAwtjzEos>LPjWh zp<+{Gab)F1_VDCqX+Dr`7}3PUc8!UypRM`A6E_)_V6WtHRNw0(9yD;^RhHdjC>{Hb zX!88b%PUeU=HinZdr7ed=tY(p<^FukFV60;AU+Kcut-TBX6g(QYp>=m{|aeWqdVL4fhuh?QE$v}=@lxH$^En7e&KX>7N z?oN^n90$rHZ^lu29k`$qziR(o(h_6{MtQ_ikm)G8)DB>KcQ%vW6UJyEncJ{&YZq}c z%A3{kXezOVA}=Gx7tvdE8Kp&PzZvXm0bgkbkzZ7nq0OKi_g%MHO#7-50(lM*O>YTJ zT%rekp2J)%{iUcEj7Y(VG>YKK0;eS@Hjca*o9FAx%gtmXN`*_& zZ5W@1F*6id)8nG<6Bxki^$wF{;OoF}vef9tGUA2)sV8Ine0M2Q7JG$bA{n(dSr$zA zz;^0AImY;4Pvls&a&ymF8WcFe9R0$jZ-udOG9uMFL_eN6f&FtKQbJ&q9>(I)zqX!> zeq!np_P)qaDM}AzU=Qh)W8Zm7p;~s_ad$__(_qZ;RhRCu(Ow$Knh0#6*8Aw79a@(4 zBJ|?(7G>@?SN__gImZ$spp6=1@20gsAN^OPlh432O5>^yym5;*k_?QqgS!vO@K{t! z`Rr-M?~1M*OR!h6H>1al_lixDHGkz5EXlyR!RS`X6E1n*+&SqNo3pUH6!(g8gt83x z(aFllUU_*$-p*3AAx8Ylh$_twD-Kf&@lH$HN>Rl)av5=sJU`dS^Ak&+AN-=|`H>M} zZS%8%rJ2&SQ-U-O963f%noJc4G2%Z2Y8=)=G(~y;r-^?^6Y+nCnkeg4(;DSP`h{hR zPnybcje7 z_a*?rIoh;|3;I0JgMpqDdZqHEi{%h` zu+G>YF{57vYoWJ>_NbzjEurLH%FH#?jJ_MJg&raD*IIlmM+mWZ$(l6u4`D6zI+;vf zn}AO60ZVT1sB-_c)Bw+V_h7)-GSPbt;_BN8yyKt@DU z%)}{*nfT`E!Z8*DV`CmJhVpy^e8!3hb|3!$#=oIo` zQJhQ`ViLv4;J*mb7y(0>78Hwcs12w~^8SG_cc=}B#%MZXt@|&o&qQ&3s11n5h&^Il z{4aK}C&dn;HXs_K0x36x;uEvRv5(>tQ5z7Ak%zSUPz+=iA}_^2qBbBJqZ>`8M-*q7 z6+2jk;w(`c5RDO(IkB8sGDgpr_>V?r^hSu);G zOe$&vqA}XkWD0<|SJVbXV?-;(uuyDm*2vdVY%Q*qh{mW{ich5Y-Le$F8$$8Bs6Tiv zkFk=~p7e zeTvgZ{XsNF;1d_CYt9U|q+9^hA4Fr6KSdi-zCqSFyeZ!Rqu3CQnFN%<^IuMb8|5_M zE{tf*R-mu@U*1Gx%9}uqLw%J``lTp0BZx9B&Qfj$Y8;|5>w;`#l>d>H&C!qYKTzWk zjhP+f?V}u%tgMt!$}vHWL$vH&`uVVk$jbTADUSs;4$<=Mt_kJJWXVXUTp83jM9W^8 z$CQtgHS*e&kAoVAXw0;sXm!f@$;uM?mvVkk;}DJ6Jml5?FR$nzY0AMujYG6-5iU-7URm?; zf%3di;}DG*T*TZ$xnxZUv5a!b@H~iU%o3v)btqpgE5mIv<*T8_p}yiB*JK(`IdRho zF^F>FP~#9S-?pbw-rYh%WaZtV#vxk1(NCk?z7>S9ah$88HlQxamWfN0KbVzwH<$7U zQ5z7AnSu1?B;_b(Wi_s#97WUyL}T_LF(FVMgxEznqiEAZv}{%DMtP}O*|K;3%1cGx zzigBFN!hX=2vPU1{94S&mA~%mCnLp!Vw~0a@KDP7ZTn_gw*6|{uZRBf*F8>|#g|Ej z*UQIJ&L|?bx1OAh{(U5#qKY#q-+3D$+$i4}?QJ**a`v)6aQ^FE;E=tYp7J%M`Xm5sgE4DihiVvM2$vLdw(HLq9NJxpM6DD1o)|{g2VXK)WBE z;ml?9yT#`zOH0HHtcCG6GQy#Ixc=Q-Q z1C?W^Vg=Shc{0Ll$X0#D?fnN!)E_FzSp7eC2jfG@N9osFu24_b9z!ym&TiCqo<45= znlV&h33!+Oid(8o91yj`UYal5lo7xI@fYLCG~$4`o>54tQDdaQ{$j5%0*Z1o3YFL2 z2JKQ_uOB7wE2141=ZU!6h{ag7RKD+ zia{2ymvzMY%9Hiu!^%krhn#PMN-P9J_I!U~>GKY{BT0qoXb6(#a<0~=UV!POq$uwn^qqshCwx!{^RuW?` za^uQ~*)2+lW#g9mKZtHF_3CHWQbxt4Bh;35{r+O?U01+LT-$iilIvjz$6CV|yBR4y zqtxB${r^JDy4qaKdofTSSgR1%=JYds4OjL0Rd$Z-ykK^M_<_9;vHG z;h0c1y&zesmiWB$yS`Vok@$C04@VngR^?SoUCXN>n(pVD+lq*POyc7liZ}$e**#Y# z7>nXF1BzKKR{biCH}Y1$5m2b?9@;qvm#rpVI+Yfi>KtZR;?aGiQE;`jI@H5TlX<*e z{_Y~on-A&Eche>QUF6BdmdLN>)kUOyo2P#o`H*3|$i*wmD0`}dC^EON{wL1Fkrfyb z*b*_A#WfIibu4xL+@5%>6$-!oes+-1kMejO(x}g9}%>3w;uL#vc$iO zJw(~WUy{FrC^_0r+|2lK_XQk$t_2{P)~jD#MY6k`-H%<+5Pxt|yxxJ-W& zuvFss#c|;H=>IXRx>zgR#JDHNbR6N3v!jjWWxfVnY4|){Mr_>PSA4&DMt7`JMVdim zc$9mUZfK%d^`rV$m)ruGF5B!FV&tw@NG*EG!MIr@)>zicMt!g(7oC>c?5Zzb2Nn?P zH(k`RC&-40Oum$T_O795QvYB5p38ZO;}_e-mMHgiWUy!(Q&)e#?1zrEuwCq}$>g10 zOSF5kQNOvZv=}N$vl|)sWdj=Ui_kDwb@ix9nvvu>xZ) zL{m2Tt)`-a)f#=Cbsm8w_^ps%n3!9LchGaAtN6qUN<6~IVT!#azrk5ml$twA**m_x z#Mq16s7cdW8?|=SRfDYkX+DbQwH22lKIv(PYD>(+AA%Yi1OIKPzDa9j$OyZ&xkSM( zQTmR2?Iga}3Ble*i$Q(Vu&A!a&V@CM*DrdgP5XBt8CwSa)N2f~7I~i364)+sydw82 zMHRoY6H8Cs(KpqvC$I$D#g@nhkXlr{ZvIO@oLXLzfg?wG#Ew5GQ}4eduimO{KZ$p6 zQ27_>$CfTsi+Ls*m51apdIe8aM_Pu{I3|pFsu%wC#B3E8Ca?tAbdkZ3{G18T^btXd zzP(ouiQ^a1?l#4YsrQrA##JLo#+S_Zy33nwy3>Ky0>3D-5X=0#KgWF6dkk2n&mP!D zVjjkJu_dy@tt=#r6JzwqCru?8$li4gfJ0kiblXZr3Zqx3vcA<~-`coxN$Or{dSkM!{Q11ym* z!lairkSDWL4{Kxbx*6)#$ShW_x1a9o&DxrDyMw)@mo~6n8DanJh;HS1!xH-;oP%a) za95LF_8=a}m>F%_l;{EN_x>cJ~7Ca&0 zSp?50#DIA_R%{$JNH5GPO6Np8h2iPUWU4!2keJ=Ar{4J0D(P;3Cw)B0QZ(+*CZblp z!+Mp8e<=3#e=mmM$s14P&%H2HJ(gQZ?2`NWqwRBs-)~l|GH?4`t;8@1MM2b*5jM1zjnT- zbiF)Cvanz+L}zia>iXO;FBUOxfWVTSL$9ZI&9_{&?wa(M6{lpgQ~FikwSGmb3=~*v z!P5unN4_jpk98jN7b1PnE@g#7S##gKiDFanMu&HW+)}$(CK**OygJ;dcBUE|J=s7@ z2<2`2$68jE+vLA*WTL=YXoryz;XPhh9J@`n%sHGO=3XD0UTwlbwaWa72HLL>O__QN zCi*wKw_A_5iInVcC=XjAPL5Zdb<4O`=B8ERB-;|okP*jrhvfi$=?LgRAJ@4O_6p_EnwZ#3ce)X7 zxiB_P;C}+=0Oy9--kP4$w>MhrSDmyS|DCAq_;04%zDBc{d+`TKf9q&ou0HvRc45NWILPfX4jQJw$U8h!ZFE+ zb(`ZXTJh!jgmT094);On&rB9|=e&v9$?tCI3AazG`_;)B^5jzFfN?|V`ZG?q?2h5i zy;tcgrae?UoSGytK_gEty=hVUm9nqkEIsY;_B%658VAlM@<`KuermPe{=zoP>{mlM z>;M|*l2#^uQ~JCW+f-9j7K5@^y~+OR^G#w@+io07@Jq|=#upDB@-MgRiJo*YOqvg5 zI+hU?lI!XEz(P_$%s_2lXnMdWCa< zy}~h3u4QZw#b(4T7FKh(#N~}&6u)#9N8@Z3@y`wAr(ly*aD_%@pF zoYY$Vy24r;6`ibItr(;>A84cXk4)CEC3Ns{Ew}YVf;U+N;yaH1gU_o3lqBR#LWl0{fClw50uDw>Vd5h#;VJ++-y}~!VCOcAl84FuI zgkvon6Uruz_@^1{VRB10CRbm+*T-F3{iVEi>0TEtaId{KtyvjuvmUD5yy&DI?^;$% zp3Ko79J6TeFV1Yl9k= z(>_1#qM>YxNlo~~Vw&U;Y58h#Y&W9oH}&JY657ttaBb?gXO!#is{Q&MLA{C_`jd6P z_=2M06$uf(*G9X!$6dQNw6BI}VvX4Jlr{IPB$85GIkx4${-Rp%SyAo1O{9jhN!#zv zW{dJgDntI#_C6VN)FtuxwYm95Yp%n3s%xIuY92?Ds8`)vUuSLXx$xSai(|V*tW(rq zxgE4Ln^+CeCezN?=WL7FOL%^Eln}G+E~)h%J89dhL}@Yq9wT0hqV%qGG|8}je4nwT znxf;eLL5s_2Fj*aT-!fqsaihKs!kn_((!*MBQ6h4VpUVlD0W?AIF1l?3DLy3=$^%LHO4i@UJx}Kgww!>wRzzYwSK)UY{UsxwR=Bye z!fkaKCY_K`2Fj)=Jz96WoxGvAyp5K6_29pCw{K*!fwCzc?pRaSWy?xd_G5(j^53df zxo@(82w6rTt#EdXz(sotFXE$*)Fbav3j4UgB(uIR0v zSzm(q8KO1Je4|Kmo}2afQHgIG?$0p~4iQl`d#HVLm)D}I4^Eg83MmD%{kAE@bXvA9U2V4y}Vb@8UJ;;lC zH9BmT5;(FuA8_ag!xH3c#FmKvYE*S4`FUS%_vMzv>e#5nseqY>I&0d7O4^*D%>h-1 zb=A5mWl6@8bvDX~8xg$pDl@xL_6YZA(qH4-Y$YZ~%(|d6!{$x?%c3IqG6%u11lz@y zh;i{*9{;cNhw-&h%Ox4B*X~v}bRMK_kNc=%E(qO(^Sk($S~85+CjTJTLiR-&QF(h! z-*Y2}^A;3ufVB{PrPDOM>aGawPIwmAWavh>v?6z6_=6b}r92j7b(9fl!E@4@b&BP` zXU4K3J+A3vnn!9=23}Qr_zK;&T$DC>U51KTFeX#gZ!6OVb&lows91)zke5+Lto-vm zZFl~7zOQ6Wi3bu99{aZH;RlClW8bCFIQmyzn8xkm`P(iv8P-C1GUC9!f#&-Ej^>*O z>{YzpRo2~h#A%_!TB*Nzb3Mp9L0kItQ~>7x5byc)k!BMi7S!CUU@c^Llo4)wlg!mA z2TQHutswU!BCsVoS@xY^?(;H{?>o6#%3VVAw_bhq5_1x?>-kmUnw*m|(Y*0lzuTaLA$ofmSe6IWtN<8V70o{G|O95UjgIoVv7zEyIs8)-N~oC6s#Wn)WosUL}ad8fr`Sb~g;$o5EY zHBO#rp7be^_pepSoOE-r{(M)0=2|~PVsex@8pDj@=B+;y`J-`H)35~PVM~-dNz9xjTgIKD=$N`KN06prKX3Ww;J zw~I0^by%(UeLhS(_%nriRo`KFnpKfFZd)uwkKmW}CYvL*C|IBsS&Q z^djK=tM;1x`s#l%U=}e?P)1G&=6eEd1lHxcyBh zfwd-ItgW_R6`)l<9AsejI-TLB9aa+Wx8(Qyi%C3?SPRi6(<+ZtrN31WFH*gjz>;w85RuQlRpzLypiKWgfmc7B?%lWuoO@0Gk) z>hrb<-U4g6F6%+j4;8daR|ovX{aJgn6-*|1F2Wj z2yuiEVT8b1C__e!Yh}+$Tq(sD-)kreIrmcYjds-fe;O$>EquI!)znmb?e^qE1NkhG=aO#pi)SjH zOYHdNQ5_}Q656j0w&)Q#li! zn~z`6iDO&HMk6C^jykfJ+im!?!<{4<$R~sLIg(KzQ(3+?H~-_+S+d+=uTUPvWlT1) zy>G4g=9OIpexDoVI;tan=F^h4jxpdX(45ftT@YjOR+ z6@#K!*W6MTyENjF`O65bg)F_eDw#|+ndg+?k%4@Ib4h_K8P-Cy$+XS)tWvx|Q(mMb zy}J!-EuwLKq&4wShVti6OJ3%+lfd;HxlC}EpxnOLwTk1rV1CXem&AC2{L8o#nM`G? zH&INX{rTO_S9IL_aIeK3m0oIcZ|#41W+Y$!ue>{BEkx7*BQ?P9#Kmatv1-1=k%D~K zc=|Az@|X5a)ANqt>w+do=MqHV35T>KadX-bIxUq_LUcS8;n_z%UzJE7U_L{qzFQgc zsSg=e@B~QOzBAt3^fr6|3N6V1Qry!&C1u^-R4c=M9ayYX~FK17Hj zSN$d454@$yx4X8(Cz^NBE!BL*PP(NcqX*ttN!xQzGzZe%`TFP8{&+{mT8JjUnlaA2 zfnG$I+{;_K(IXmf-X_!VT*2l~zejVM3VRj2>mzFjS`$nreSTB(l03v^QL83H3k23e zG;!$-=#=)1>?O6yUV?TJ;dVlNw5&WM(*+zz3CTK6C7t`Mc zD9^w5XKd*Jt3cs@cK(qyT6wm|{yVec%4ztgQcvbZU`+4n->980iW zY>BjeU?{WOZ(%h*^p(6z?KT}#r&Vy&qW45=D32^G_lB|kAxGGfbzyu%>u0L(Dp#%X zy$B5v=+hx?k<-Ij*ww>qvV9+pwa}X-BQ8A}!*Y9^Wq&60;^@`$`uD5q*wIb9u7+zU zn;3h~O=e5$USj1=b?0ry*lX!~%V@`zhH9It{ZPm3cGJd-0UG*^Os1*lr?B@Knartn z4@m~rLNwW_%T8sdA~V@s{~jDmuvgeyvJM`Y$Ht7i$IL&wNZwbsUnRBOp%t|JX+)Fvr8WqACSsyM)l*UKd5~;{}clm+L>LNvXi}TBkL~y zqfn2D3#mmTW;=Wh^G=cfQTVULe;4KBe67v4`7UQsoriEZw`=INAam%a%V(ZRTY;~?J+OtYMwUdE~YR{-WTH3lk zT044D)o1-qZ9{k;?d7=IWYd2PBJA;Xeo^R{ZKr$e>(cF`)fMAmcf0ethD zRjk#QNlYZ|)rxiKtIZg8Bw%QRz1kAdPixipNI?BPdo=sdep)@t6SAHsrVZqscTHx| z3uiGb!CqlY6m{RJJ$HF`o24vFkr3EJMAMCaZAHGr)mhj)e9Oi?S)}>dbu+f}Q%H!JVXwXYK|@lSvlwQmW-lH~PEwT5FmYq4w2sMr$4 zy)LZF(`U|O#p;yh*zUt48?>3bdT2GYg@4KT{-Y89+2p&v`_Xx6J}QK7(dy(6)#kY- zsfeaX*_3YFr(s_9M*qUF1m(%|k&w@opFJyd-yya6ry3)*(8z|GskpoLxzb4O+FDI( z?Ojs4*(O=*(Y>+uVuTZE;)44nc)wdUgjKGi3`=mdc{db1b^>zH0zEztKUOZvM za*O$(AIFmS&n9WV`?k=k(cK?gqFhTN9QbEeYqq3JAjeuCs3#RY1GQ;ZPJbcR5Dmhn z7XG4NiyhJo-d(j=TTr``7V!A8x?;(Et?IJ&TGx;#)T`W!?0ILW#-ii;)eK9phd3sR zRjcm8dt85{*N(2jeU1#$f|fDuO%g?-z_}Spou%ko+14)4{ipBOzx=Ag zu@-)58L{)m1NJS*g9SK;a*T9oJF2?2;E|VBetRnoR|$&J3(CWtPWg)Z749-bU=NSP zwAA)DsiQq#sZg(e9(ADgwxHwLV_=GwxP@SI`0 zXO@I$ez$!!cdJ?&wnWVJPh5DfsYS)QQw61Ob-qf3mUmi!=24`AhG=@tV?_aeHZ(}@ z`#OkYPjKXNuR@F5V7}K%F%}xe@tfc}C?lp)ui8hhCsH+A}}T z794dHH4$f%tj?r~Ye*9VNE2~2KuwhOYA5~AiwAz!H#|PiaOK4Rx%{s!*P$jmU3?h} z+BihOE+fTdpmm2lylypE|HDgJROS%Lii5QS zCExC?RqcZ8wR~Gf8rTx~QYog$ieie2c8!tZWUwbFkGz&;#GGL z^=344XntDhwMLeK-v{MU1cc8Uwtbnqs8pw{XzO!H_4r*>yZ&H^f#aw_(OXt|9JKv5 zu{83-8}G9&V{3`giwX)XSw&G=`6x{_>@D%ure?C9;l-KP^u7XX!TC`u(^ALghgPMW=71CY0tM#J0TF*uik_<${9ggPXS+hoL zz=$>M-o6M)2Ao9=8Bu(38}`ic02A5(F@PI1r;oaR6zs<1q9(_ zU_h||R_t9=6crT2f?)3jtcWP~-o+009=P_h_OkZg``Y_Em)-l@$$sDe&hunGGn1TT zGMOZkjOXw5ljSAv0aqFJr{1aZCbNfBSDx6~7Pf0Yr1 zF3u2U`R9a-PYx34y_3dEn0IgBoD`+`>S?VH z@9r9x&e2>R_4dc(#BiHG#NMgBr2oO|!CQgOx1Sv@cAU=>A!YkY|AUW5{%`2b``F%M z*iN0e_pYDRcR3YD)BI5`Qp69>7V8cV(0K3Ty;AO1XUv6g57{hUPZ^}~k;8kt+;>0p z@Dk(o%SEL^vC^&#AA@`ZQ-(iUtL^@KttS0J{y*3nj{YE9t7)8ytWjHrB7*#*on^9G?mwyth*&tt>Wu z7EQB1t1X{)(>T@Z&K_9lnj4zswKRDt~>&H20}BlbkN!jN^A+S0%m`l~O~aaD9Xbn(5M|9Z|8 z99Od$78zE~FtK$i{+iheL*0Jn(`}AL=0J~(Y2!=m)bkSWg$r@>;&!+u?omGHM6Z zN8s#WYT}q{R^Qein!$L@k4iIC-iX^#7Qpwt3ZD<0V`x zuC1cfzH0|PKa~~(eS$TvFK-1I@u)#Fa4J_?tLm4oe__~!<3oDmo}bD2xBNF@TtrWd zJ~cYuCU`wo?%5qrzFbJHd$+6=JUuP6b}zD||50ycCMJ&Sh{gAu&bNqKiJR#S@iT^9 zgji!<4OV>i)-w7Zlo0mmi}Bs`_89MQEuW)lr+Tk5l)rAR*|oW^=e)Qk@*i}a5dg#E zV@3V3_8LcQ&0mLAw)eo@5$XS_N7A{v;OJjp6U%z*PgA_42E|ME3_g^{Yrba9c8sK$ zjMW@(s)zNLSSVfjM}YO}oqAs4Ls6CT6jhm#`zVidqIqz)fB`egYLQNwp7Z4`4f8kS z)04fiqjdtw7{5VEzRcYc?p-tInl}Gx&xrh%N3&ZyJ>o^NixNKwou$BvFD-x zXjO542*mg=5`Qf;*LaKaw&EHp%0~Kw%jpl!p+Cq+5&who|Ikx!|3STdE%kP8ad>a% zqd-vxpG*REWeG8I(07$bo!VC2jSKhn!}^KQftz+_V_)lN46eSE;#d6^3qM0+ zV^vOd;g4*z9}@llK`b~v7!E#JEo}Z0g7e}rGA^64K$RT^&3CR7V&wpW1VOeU*4Nj8MSgGt^OAgMTnUsV_U#hFV2hC!^Fwh3RLqG zgW<)a)k1kHq`u4l`DSXXIBF{ktEG9A4e>-0SRX7QEc<-d@e&hXqgHa?oldPgyW2W3 z>HJs;!Rx`%igGh~r)cIp2+n_X7ZLW^WI3bpyzQaDU9Waw)#lL{6Ke=u)@>Kwdf6X; zuXsrHsAt&}=4>s!N!>7m=2qSx7|S4lo%tLPT7v0$NSP7 znchL1N|xc(F$jj1D-S=rZQ(vr*;}x{K zJ&oEPeb8#?upsi5I&K!**Y$=z{%Zv<$s4g5*EsjVp2y>ZxVALcf;Uv0RSKGHcrHaI zcqCOueD%u^k$ZcLB@*Q_T_w@DA;GBR3h#{C`p-~{V<(rUz3SIAyl2ul1c z4IIJampl@pC@T-wh9UKfz~FVIftPR@oD=QJoSrWlYn|Yk**!_CQ{&d*CbcKN%3l<; zr}j#;JJuD)dKlxo+w5vW#RuQTvNG1dHQ{`RN32BGd0nw&suA&UZklMZpe@wu`c?1} z&NpvRCYC7I3GdpSCWKR#B|xKh;)cHq@E9^j_nMQ5FRyk)v#~}*L`JGu(kC1?J}eHr zg!8rUw-B=(BXRVdhlDUVnnUWh`{H+wCzPAK5Wl=?haLSMNwH8KnWFermkQ9f(qoa* z(-U|Jm&Z9N%2~>)x(h?WN>^Tz!8JKCd@g1$Y=b`6-ji0L%NL4Oqe39a!UA~7?ch|b zd#4qeefSY1%lJ0m4C?A{iy`%Wfk$gO6-U!aa^E!ZwoMSgG%MgG?VMB5(Xut#X8j0C zJva?5pNC;3trU{C^sX2ffF!ia8tB=Z$w=AktS|udBYcPCm3Wg z0>@Z{;L4RXkyF{tACEVKo8pK4#t41qv@{X))f;@CI|8TTn#hRnQ9s4jUx!6xLa2n` z^5iJz{PdsV^{~TY@03tUD;`yq5j(!m6qlaWgEFn$B*dbJi8#Ay2$oH*iCViZIFQa? z*0|Jw>M>)-Ut+1-0WoGWodp=v1vlFG&kI`&JxTq!S5M!hx6YdT>sZ zU-ai}QEagzoIUIVVV%RV@H8Lnv_M5p^`=iGmhbC_&+axPt>)jIDeP=&!GcrXl2%-I z8L`Ftp>UtDTO_S%13c!hm_FxQ`-i}aw>|OHIU^#!*hJCtMRka%8wk9F^W7ilf%DtA zW3MSK3Gu1Sc`8`#{Gmt z;zi>X;^K<#z$5=0!PdJZBY5Z<5w`cCn0F*nlEKzz$T?B;BWsOlzu}=+n->XOI$Lf3 zXZQ7u?FF&9)LIeRvoml_IA6YJL9bwVOchP{RDtLcD9PYx-fnbOt;J0-g3f+aUfo{$ zADpke$5Q9+Ea5b%2F$Wnf&Vqmm;Zm-zMc9=e2m{I9=>iP^()So_fWba-E^*4Ho_j7 z74rq&t9eh9Wn5hNM$CSwiKh?3q%p`X10RnHxvYytoV5$+qCJ6+B0fH3#F|Ur#o3z2 z#l||J(yk@nmEo3;GFtzUE^htl39g5of!jWAePkJ}^9zGj&?zy*H(0WXTn68pq#cu( z#iFlh2;KMC0k^eW6K?0}boATeuz36hu`WtT^9Se4_aiBKetEGd_b>oTe60q2mf?K) zd__Ce+e<^?HrGY-?Y`1H$ocXam3A5uGlcm$gu-DJrP-O!oU)9iZ_0!Jm?r{*WuJlX ze{uhTavQ$O5EmXcg^+wR;C=$1&t=4_TUIbU{iQgP?;`m=Tn6`|=(J&Sricq`3A?5! zz&#|+m-||D%A&h1bQ}9wET3)-yoB@R-XLXFd6p#_-;IQJUQY%0^f;RPjC7Jbwl?hC zQUsEg$lfd8`Qx4}WuZ-5BaX#%1jXt9R6SeRyG6tP=s3YwKYYc) z(KI__Q;1432dh;RBpG~F#8+hWW|&*HsCqmG+Bw#fWN;1nx{dB&^$CM*Pc5L6zLB)r z-kF+>?n%-3ywcJ@88M{69?`;TFw9FYCOB1kr))gDHX5VOWJ;?^MR6(D3Os&Rgj3BI zs(eMy*UnouXJg>~l2M^Bxe$JaGv#zT^^ zp5$ebJm1DPeq0{Optg#owpvQ{;QI3Dhpbf%=l!DRi6LN-dMtqR;xc#}D$1*W+G-8` z4=#hFc}vsEE4C$UxmpSAnkaiFYYgbRI2dB!U7}*_)kwva}NQfd$5awo=1?NrMrKt0P$=mVn zvA#GZ(mS7{>2+Z1Yyowm;Zj_jo>R?=+>XO2ex)Av%9mvn@9hKXnG)br|AiEF?whz7 z&(`XLC$7ckb58U>dTka7t9nE4W@{xG9FasZvWtJm$nxp6v<;iZx2)bU&0?*dQ$h31 z__#wKeBmCSFC!XlstvE(7Xhy|rM27Z*5QkiJ+W+^^n8w%@r(0bOC=l@od{BO_%UdIt2wm@|v=xrTHmwWBRGNct?s&9&Be#GLOs)N8R4 z%cOP1)mg^?_hj&#M!fkwpjOI9#*`Ac!>sEf3l!FNf@ z&d9{-mpkI(xu*%yI4M(%Z`u-aW-A)!%c)|cGwF0=CmiBsMD(9k0hTm*BnBpVYU{=> z#9`0d;iia3`5eLH`*aHFad{X%@rej->Zx%mu9b`!@H|88zuy$P9W|2>T%NAyLUgx_ z#A6>Gl2-LLl!hVXQ%CLg)%Z>W-@)pvrs9X|t?)%@<8EKdoP}a`QV4viXd%^uQ{_;M zY#qhOJg>bc#D}pNqUceCy!I6}PIb{X6sA1)RjNxeIMth7)9CI*7$W6lR+M4-!qBGPDe+y%dv|=d zuSdfPXcpZR2NtSK2>QDVqtHk<}CrU#~=nZgYN$I#Gv3=GF^{71Rkr)xRQz)O>NIO`3FWnKs z(Q~X1wp(Z1)!!-RidAv;(6g+s#!Gfr4X3lsKGVX@XuO1L#W~TrSO1&B!e_Jiv8lbrHQ{FhVs8tKx#Wo*9vDv!^gKIDtQ}he20N&d zR-CFwj=;?&>f^p6M#P)47ex8L)`(UEI!k8__&EUIAP<~V*&XNZX-SBtb*GAItE#|t zOVl`DPSw@c1Issc#}*kz#D+d=#Fd>7Meh@l8t2PmOaD2SF_(viM^5ID7Tn39R z8Dtq%ToT08v6k@QL1T@VaIILxi?muFb4X0`Tp=c|qtiS8-V!iy1lN`_Q@ooXT0X80 zN4x_i8N5Y#i_o3XFXzOF)b*m5TW5{)N#KTQ*ob&-jH5w3Eh0&i9mFb z{1Q&Z{W(P`e`3C9o!bdkR=KC=e7T><{YN_cQLQFyr+vIG#<0kG_Q^gb}@`d^{GfvZ0_( zCT;0V>H$<2PfP;+Okcrx1u+>xM)XKS0-jnlJ&5jLZ7rupj8BGrmCOnd|L`iHS`a!6 z*B06KA4E=gfI4B#An1HQ|9=o$e1>8X-)sr3C^shWQ*AyE1F>?6gfMFL^mjjO`bRM| zYLz{pC)QqG7%9$hTOV-$)mU(7)ym&U#s8WyL)Y0l;b25eqRel0C8zDB_lnX-sii!U z;mFfcQq7H23ExLxxk+9HTA9$a3-DrdK<4PN@Mc}2YNRriaCye>fBr1B)w~}Ws#Rhr z)NNH$GnPC!sp7|z5eA-Tf@hGRRZ;#bwOEf32>)s?A$Z0MjwUPGb+P(aqo#1YyN#5~ zf@i7VvgstplWXd(%8ejqySpUANcFBEwPeq2qt0oHyWSB-L&#@(E*toi*Ux3@o zc<@p)B?RZob8pd2y_F@@0nLU&uKy+}D;JkxM4M#O9{tBbjRuw;0eJy(77w12Lq_y0 z+$;Cmgt72&+uv5yGzN`SCTqttZ_v%+K7D z!_NzHemKsT%Ojt`)iXyuodl)xeGA&kqzTuZXJw;!`$MzbCX|gN&asQsx;!(9jHq3? zd+wa0NpL6kZ!2oDiA<9qo(Y3i+gmboyB-(|TNB+?UPGRfL(Z9*Hcy}X=*3uYA6Pno zBX~X$o&$t3N4o9LU37meT=7~Jz)QFc&WXGXzr5TDFUNxO!)rObgy#X2GoI`^qvakZ zyBpX=&Q8g-;+*J2qkqTTHWSA}$L)zyHWDM1$#Tkwkw4exR{fL$Pvhl`q`XBrn&Lhi zC@b)&9xylYqcE13<_w-MgJ;>Lb4z6>1dM>eP|iJ1%3I6xb8t?IvS7)TM&Irxf_MDX z0vV=%&a;v5EG2ZFI_j&x_wwP;m^^-7!t>S|Wtcco&YE9Max5qdZM%$-k_?{jmCK`y zK&dkVtZ&3a*M*r?~zD;kiucZn#&1THhlKKCiDTA-E=TjueN8 zXX@cse&9629XKzehX2foX#6(Grt^sd7OAIun8AfP?WIg?>>eDldo$$wd~CN}Jv5~h ztUuFU%KpvsxUqXWgm4KwsHQhI1J`=(rHm&$ql27>CI0P4byrJkI2YAa%3s3kA?NaL z>wI0Uu2h9XgIfSE;e6R0BV#@0Z&V-DbcH`_h=SHNwGYoW&N4q9#l&f`KQ1katp(X^}IkFJP+w}$os z%_Ib`Ek{%Cozqv;-PL>{?`pjQFLm`VPxQVKA@vM7Q^>AUU)1vkKPcDRy+DSk|M34| zx|L?kutKrE$p&@kXD?VXq=A$ph4Ynr;+Ckds>fPy=(5#Q%6P(VR~2~SCT%II=2T8x zZ{Q7WT6)5NsZ9AYjGptqh&uh2st=mBgLb)P3+iDS=UfxZ3g*}@wi(th??v^P&`VPv zl%fonW|mUTPj#w{-<^W7Zs7ow5nFcMRi~!}!t4RHB!p2DGbeA1^J!5~k4eA$(V=-T z$+&5ILmk4AkMwuZ<^|- zD38=dYR{lS5R{fL9_p&%_|$f&McWo=GV)YAT=dtc5WF57tteW3lCiZP?AmZ$&v+Gh;U2?>6Zq< zo|am{YCEr24~#fc)L`sa|NKD%N7L%=aISi;%OE)YS}(~kB21A2EqI62lRj>aQ z0}DUp={YafJ_YjrMXafDR~=I%2x2cdX+|p3nzL9$b$t6u#mMKGpY`x`h~QJT%pQT^{mz{ro4B!uX7i43FX};FDny7&6Pvz|o4*?$t_l)Z0$*^+-_(k#A;>Zx**i_j#@o zT2V3{Wvb7bwS%I%vKr^bTY>i;T1`wbs3~L6?X=gR@e+Q! z+gK+PCq>y$b8SnSYv&&fk?uS5yT~%)IL);~X|8n~7pie8e*aiTq?dlH?(Sv{BNLlS z^|I||pDZi}))t+lJJme%telHAc+*jJP+fCq+q<>K`En|r$yHJA zoHM8^+)Bc^{v9;Vmutd2OVTPXbFI2>UU4XSvZKaJm@jJJoM?xa;y&4D-M}u&U*j#x z<34ih&L?jv_-}7Xy0Ok%S4Jd~?{k5CpYpxkrJMJh%J^-ve6$ls<739(9zel}GTA;p zK4e4)S)V#&eG-or)%ZNYt&b65vSW(Upz|X2ZQvj%IX7Pz`I_c!lkXKAG3zVE+Y2HlBMPuTT`P^%kK&P?8-#_xZ9 zpHN!Y4yASNZ2ty=#}@dy)`<9beZG<6B{L{q;+AkVhsUgVyu^t3H-0skVoP2WTUzTR zza+q8OH2ms0@SVAGoWuq927phP0EhX<9nc(%=E{PHGZ_W46F2Gva z1=w)!@9|+86Gnt-7r==4w{<=KiO^?Jgx*MH+Ji8Dn zsZ4tw#&6TE43j~vyCX73o%M1UOkT320AcdNj8rC{QARYTeVnGWk8_9iag2OTwKaa5 z_Hme2B*V615G?p}pZKIJqusWziK&PE(Y{d-WdgFnGnDx&d1xSRK5dB?9TDR{_|Z5Y zRoES7Mfk({sJ*(#b2b=TKLE!?AaeA)wU*fYEaH+4jR>*w`Y!Ru><%z@^o4@9GOcAe z+O4J~j&ch|oBsZUh>MPbhTX4~qRt^0A7An%#H^J5 zV7PotY-;GK=TuyG8L@D&H++t+2i-+&!KHIFmreNq-fR`IWn06yr>_NHZEDf=z3-%vV1b*(;rePfP`{tUy)FO6?)J!oDVGWOMi zv*~)ld2w{-+2**RLpauH;7*9kotBHsEyH2Tq{7nbj-!)*SHP3I!!fXz5pioz1SI!7 zF6t}y#pM$glr^9gS_&8Bd~M5Hpt*B6-iR}5l{&g5xYsj?$oUTir{cQHh}NAd!Rl5u zA#87P;L4_t^r#KpitiBlM_qwS@8VPu4G&u4ct;l;6KaVs9opc-yAD+I@~W03 zgQGKwT4LtLHn`xT5pi{0f;hURDU9E10bCQV;f5`hv01gYcw?;*kr4S>%pI^&IPGl< zoEO(*UCSzXeRUgbKhvHNZI8Yd&eO8QOuKf#OLn+b!zS5nF|Mi|a!!=R{P_;CzJmpH zoG5@x=Tsa`H!VU!MgMuBVAih+aNmHhggGbL+isdFJR?&@6{{Gi*TM#4uD3;((>0Ov z&2Cu@PuaCa8-F{hNB^z^#q@q4nZ%m7@LN@U>(LIK&)Z69I?*`I zR(wfq0^cWD7kC+_Xav`gqv?H|n+{@JKw}8`S_60qmuIw(CQft*t6{vjc&r4}jBEv5 zcU~usrVQh!7l;m?@#1&W!N6;1-O2{n2eidf?`tAQQ$*OiiSRue3VqzFNdJRt$m>Ka z;Xif?tIp=ouL4L~afJLo=EGZYrQA}H;3oGHt|6}<%?8){i&>AG!?Cv&B(3;A=Y5(Y zUX`8-%ULy`LPaO3?{ZCe&!_BSaSl*q!V$4xoGb7i&U+#sU5fI%+8nWmUXPqM*9`c0 z=6)%+G4wiDLP@ZArzxA@v(4@{~)*}S}PR7~P{Kym(eb zvR7Oy9&MwW78R^u$;}=ZtYM!)J`Hajp;r;{l#4~iqa(6lKR&(@x z*5_#MqtKbuF)bmjwn2=a`%tXBZHuk1`eNHN_Q?M^?+X-3?O7P6=Xr~M^E&`Xa2w3~ zH0|B_dqIWFX(D-yi`3h>49-bWUbpQBr@oyNm)hItD<7(g)^uZi;0!n9t;<`TZqfO4 zgLCuK#p2$Smz*KE?!5O<%}c~VREzbZbm#XfFX1vcC-UJQ4}>-+GQ^k;ll7DRs^Q{o zKA7`|FLF(ItJ7VwRg`(ZLz-|1uc7f0?pbn9it@heKrQh^rY@qzNpWwj4_Apc2HQfVU^uBmoYmDDF*P;2txB6ZE(F%q1`yTg!NkMKnct!wDuWpMR-Lz~2 zJUFxkR!?;zgx8J++L~P>)J@yGftQT`RUapgYk~e_ose^)d`r5bT7!T^x=vP|fm5mV z>R^1iR(RUp?mq}WpA0cqkxwbe&>k88nnS9TWX@*uX-(vQ?DdFQENR<22RDbk`dLZ zx3AE=#a-&{TwmVXWklh2Df;P+Ch6J?9s#_4xQ4t=^g6ItD{a!SWW9Q(IPibV{|*0} z6w4@W4bIo!3dhb48t+TW7CS6k%@5PFgHY~QKON~b%8M*fu8X~n_g79O_x7#D0^xP7 zNumqo!serhQ^_?q*QTg3BNK)4WCRSY;)L5DwZU!k5&u zC(1P47T^2TMDAJ0K7&5%rMhxZV>l6P3$>%2@WK1GSZ&+iJ258jg`;Wz<5Ga$bAhLr zvT+1V98m}NUTlR6UF?u+$o~!H#aUWg@B7$C+-o*cst4~eG9sm6YhB_U1-#F8mFmG| zaM|>BP1jkfdsZ-XYTyW4eB5yFm)2<4$`*N@c#F_Ur{VYYr&^a5d2i{iSC`Qg<=D61APBxw+I4ANldd?20YJ)KPN-bEq)e9S@ zhhtVfCtCmit0Ct^tJDPzwf-09suhwwVX2uPM(k{YKU6p5e0e`s6fv%W_PtZG8hpiD zst30#GU9Zv>-tu)FT|Wap)m7v0~9sG@$x1oNd}iq_nntE(apCFgk}d_pwyp@@WRVb z47GAYUMJ3pPPg^!r(Ha;Bf#Opt^fNWwrk>voG%}nbT+C`b*)F+7ve+PS}?9r z0E&QMjN9Oehc5czqVb_vt)H8OrcEkpD-!=b_q>-`{olN35keifhRK z4c+v%jmrI4xDmu&t0(n#&X@mxMH#vxOTVDKK^$}KA@xL#kb8TD!$q`-4<_g+Z>?n8 zdEezdpVsF=393U;0Z(qbN|u51<)cecYI^7Bezv|XQU~^x>=j4ImceshNB!fDO;vax z&x70=@G(#OoF(3s?i4*Vq(Yz~Qvjq*&BitY376BT(8X^Sx;k>>A zrw%s8;dW1-pucxD4wmOd2~KrwcOx7*6VP&x59(j}V)01=or@R|#gokRFGk0}@aefi zDzWmz(+L7Q`1(om$SuM_{0n63<|*Cu0i;Do!5V46giTs_t@SUR&UA?Tn4WbN7Grg z>CLniTgPX_w(iIheOd#RHbX*sgYc42cfFw$~89c+{8bL~(}V=2{`0 zJKSpXMsOKicaEkP)3=S%4rX>2QDbb>C)540x((ux6P}1+{#c=Q5Von}iCjb4scvVd zKUl2^G$>O;vZCCo$uhk5cxyv0{}er{DUzk;R*lQ1RqDnh&Fgm=bz!8hG#m5{^~Vn0 zK{)Wchom8$h~Jc?rBp7f+62l7Zbdno_UK*XHK$V@0!qDGE_iLZCR{^`suiiDr5HYl z{y)uuQ}NpJR-m1R;pOzn!-8RZf*o)w{x{|Mqjs|>ZP1&;VvBQv;O)-;CYMc?VU(xV zU`I{xIifil0{ z1-Ag)uE;Vvj5X7{C&fUIskuU77Kd9kE}Q1_1Jl&dLl>;F+b!Q z(tVt|Rlrc^ym%Yosr9*Uhr2BsVb};nzBZ873`&WM7T|QU1>AYrSYK|99a+vsD3%8! zN6S%zcca#coKoH3<>(`#keMA$Y}N=3yF-wp<;X;a%PNugsViLWc0%wH9`WFu6eT2~ zEG&s?4bO`>>bZ1|=JF^Pl8q&}-g__J?{}6~MI6oRM5lL(PZbA>_5#P4Q&K&C|7nkr zll*YAcVi5+bHMqJ{jjSWy&9yLEx9X#|LhH~YE_lmic__qI~q$j`C(@HU_#6+^Y@w2xRo{9ED+kVD+oQfPRo;;6-ifw)MToYao8R0f@ zfQY-&3J#c;)HtG)ofC$1^Fx<`!T9l)Bih{X#S`<5^;i_9h-b}vfKu)+!8LhV#sx3l z_QfLl5S(+t87l<);mk@#tTLh!mT~}`a`>N|yd<=Y^Ur2C$WA?dX_fvit zyC2bFt}A+-@xyV+M#PX8Q&j7fJz)2ikA`BV-ITw*RSeeL3GkA+Gp> z)+6R6j55ydpQ*q6XDsZ~_t5ha-d3Cwt%`i^>vDG{L5H`M1n0}Cc>T!wgwIhs4(kpz zAAJ*CcTUCIkXA*fb9B9Dc7X$P3Tga*@V>*-BLMUu9b{9*y^IH zj_(T}7T=Uwm-j2)Luq!-D``9O&t9vat#k4HWVXji6K9r5LT5^RYbs^fgQCNkpC zpC00Icr+x|JS;eZk3l|~>CNJQEW>rO4BQ%U+b&zUDOM*%q2|57&1b4K&N-EAMFUbM zimXEY;9i@(f@{L5WJ?`(%T62Qk6@c@EBf8?M%`i+)$-0*{+%CQc_Gk}e7K=i{IT9+ zz_Ud>sVC|O6x9}r{$hQ*wh*<<4R?9^WAAKRoVn2lhYlCmr&=v3eyJ$Erasf3z26E( z+}a~bu5d&5#f@-?l|6EK98Irn7F(efUVlYwn%y64GwtxlvW6Ji(gC?VISzO5V3_`( zXFu2%a!hm@XOC794RJ-XBXW5hP1!;RSBAO0D#O?r72ruuHSF2j8}s(NA(tn|$S(S& z1voVy31g0o6lry>acH17_HlAYE{~%rx5%4dSd#1rU#42>qU%=2MN_@;=X_t}@_0;6 zQ7TnEtZq1&0*@z;&%K#$jq6FP%rd^n<#9CK$BDXf&~Zm1w75J?pFGn6AFXMKn`;Fk zM|0Vf<)#m<(azh$jB`~q-uqVQ?6K#MhS;l55Xy+=S*0P2PU-#LYpwAT9)aYXXg2UU zAXX%ngRIe@alX9g^YKWL)K`|m{<Zc!CQS9pcmX~PxKmu3TQ z^|?HbCNG?3oP3&b*3pc^dm@*|X9n8mq*-lKgZ|=5WLw~4g3IG*+To>{b2!bMMQP^b zy^qV|GaT*kc8<`8=@Y?bW_|Hjk|%a@3&0UwR2=)(6FWKu;DeIlKM}7+SJvo$t&W2( z+D5^t`1+HtSn1|{-IeP7$sJ*Payyd@V}(+n;!F*457VDGln8}~cuDo(GPs766L8FXU6#{eNcyo? zNPmj8uGH#E*r#FoUEdR7?3Sl0?+tv$k=tr*!z}&4k?}BfXS@#|Yus|meK(m9afF!s z&cT}_IA1Q0W*kCHB*e+j{r7MLw`%%nEy9YsR)BgBod?t3^du9b{vO^8H7c*mvf=KAuQ%ZPD=h$TeLE4sbB6}iQc5o5M2 z6S`i*#HhzHl;!6CPM#T9?Afvd!`1CEF=ZzeelE3d{7d9+5sIepVDDvnO}tBM0EwZpS@jfn0Uzr@IDt3`5pgyuiE zGWP7-20!<6G;qE@!>izhb#1WLRC_`!`20)s&RQiN&Wq4E71v!xbgrBu+@K=N?&_~` z=^V{v(}-H#LX>OS6y{a1()g_{j-Fe-GM2y82G0pc(rU~sC-7NwTzr_~to6HYfprpF zVOlj81LwPEcV!H`*BTRIjfe`9pNS_yHc;)pgT{Gr1m{Fi&Qb%#hzczrE4hMnr-9#U z@cIS)!<_dau^Vn5S$a8VW~Y;^jY5m4rj@TsLJMe8X_=ZlAD3wx}g2@Q8UGyx^#*a zN^6{o-zAd~rJUQs#}7Y5r^B=K4vrRhd~q}UJ+;1pYqF@61;*D2M`e&3)uZ@@)-bK= z50UX@p;YsvA{N-XPdK{ObTi0^j31R?%482Xx$mZ)YsF=7*_1&!Vzww`-I7jP6qW9) z@p^DhbS}JDC-}L!1UO&Vnag>N9%F%#6`Elu^ZJG%iY4}_9gN-Y`cge!iT-fM;+z`ih@{bE1>WhMEvi#UGYWo2_3v#~ge8)eJLV)|aR_n(i*SED_%` zTEop2-}L;}AHRdgInlkl=AkfgZfO`6xLnK~XpJ6QR7_h32F};fiBb%{KumDZvO@|M68E z`cxiROxM8q+I6+Y@qY&3kz0baioIe5-A{(W+|Yw6iyIr}6|=?{6$Lh56DXm{`Z%u> zF7BP7LZu4@w+Bo&k+_B&O)p4(-6ST}=?tG6oYC_VE{{dINvo~5YrwCsO(1&PZ%`IYer*SLP!g|*;}5CL#X$3LNWN~SacjwMyKxIn zBMQu+ccd*u-72YZtHw2v5k5UzfT7-D(L4B^p3f89igHdA_h~p>{IY8X6N+0%vl{2i zHKeQ&XFmuvwJOB=J4!PrN652Uo4u~!GjNX>aM4-gb1K)6&v1(3(I!HK8bTp8%}UaW z&zyXor`_;+Il{VbMQBC&ulS72HR0X>-9+m6i{4{dBi4HRPP=uFN9`k+!l4 zXg;)i$-E-2iP18cyeNvvJV+4d&Xk2(&S8@8!_nN=Qj}jC(nWK>xuROq0F8S{-1p)B z9K9gfbQtWhS|dJmuvgg%+rU=z|Cyt#pG3pX@RQCp5_Y^73qn(+5yks1mrdjRcsQht z(1~5cUh6p(*GfiMcif~qf4`8}S1MW3>iZo#^!>999++Lz@T|2HmU-J6b3PigG*^80 zO@-{g)XRZmBn0=uIht&ue`#2JDM(m1Z!IBsALD7R2May`E8 zsI47Xl;;0q3ur7FVQ3%ifrnd!qx*ITL;CUhxF)m(?m6v5^(d2fL%+58c3t&ZB_g6mSa63=?QJd<(aJOS3XSbb%;4>#j|9!UB>F=|( z5`x9#3>-~+!VL$*Fqf60_>wl#Jjneyt}X5AZ;saLegCF=Z*yADYsey-2Hql+2Xe#> z{iIDb^e>+D(fFU@RQ%5>%2cOzBC2h=S}13f#{U7Ql6y%|qtbBWLXfE5qP1jqc~6uP zRqMpU)itZd&M$U)ZVmWIgOa=#xpjl-96-k3=KuuTgEDXrN%nmf z|8v&hVz(1|wo@f#)!=A~xBqjV;mznHdS1fiaZbwrotb#_va#UOd7U`=?{gW4=v>B| z2v3k|`0tr*14olh+&Dy?QoB2Zul=EKQ{DwX(w=#!F2r#Dk~7-Vo_XO)A%-;CcfP#G z4;#Kl8Xr&Jebx1@mjw0cbONU;pYDuSo%}GZb+DmIsw-~4>W5;i5wU;J;oQ38;$hb8 zWqMw6iFT?DNBuB&FG})g?R24J^h%G6vqcqn>%$ z59*%0tj|q%#JEa+__}ptLzQ)om@wWCH}#h5M60{#Eoz8!3N*a3O~+;MI&n0;kk`Ct zfNQNDQ2OFGNvkGH9nmYs4@Y+mHaMg?;p}(5czK4g=6BMj=+=H}3&YaN0jIh<#t|3N zEtu>{_#Z_6?l5s=Ml_Txm#aTl!X68s_rn~s#)kDn?Xk5>BW&=MT9?&{GSH+i7JvB1 zL)@<%mCN8%98H;Y3|+*TKu2gaDFAd!>~YRzKOA)#4ZRZVvB@W2%qxKgt|6VEdox2c zf+*;kbwKLvy!Xj6I+wpK;xoEIohsv`5yg8Smrc6>+2=*Y6a^L(4VFf2$C~yyyqF)B zdKe^WNGoANR3gOk{~)*(SDeG`|Sc7{G*Jq4%Y zwdJiqH>3y770Jzd!m44%^qh+SO?jM0_E;t?<^@At@~wHh^S{YuQ&es71hKDg9IP!e zNN^dPilgcM+P3Y*=efP%^21Ad-ZS`E;TqBkvfLKkn+FMS=EfYsdo>?}eB4l59oiRA zPZMJjF?|s3~k#3ZdH6I*%EGvxQ3M5u(*}J}hKh2=Yk>CCy`=vA^J98; zp3=bQT0RFW%FBi>n)5oH7-a6EvGbG$jt+d@5Rce4#mNhde#zK@<@GO{`9rTiTs3x{ z(!kLRHu++`*G;kGCL>~;OG9m9#1~ynM-Pqj;+pVzUQyQWb<<$V#(-P*10)aNe!d4@ zwT-|}w;T+d6Wyt{dZW+XlP$I!ZK-kToQk8Vmz15an|Q((YBcoFUM!`zF}gLw_y|`6 zN4IQ7ud7n-yDM8Aj5XhSPTy+U>)e3#12oQydzP}-cfWie{qkSOM3nMI6Bn3Ho6XNgVhuxB6E*k*LqV0 zQKsb>?ZJCH{57sEo*P)x!1;2Yh&-~!M|3{VSE$)VQZ!D*b(azSUGC-#z5PJERr_jO zI!ANa^eV}|Evh{o<2-Fvn=(PyMu#VDu=~)O2991`#2)uh^t_(AaW&ELViB>*AjF1F zqojK96$JPC73Jiw(xUS@1uhTmtZ`mk6L~!t?om`c2@8ga?)KWivi8__LOZNB)5gHj z@|rU&t&oTv*cgiC)RguO_*#~8qB&|qaZxv_Bn&UyUfP@Be7QWz-(Kv8YIiG9WDiZ$ zcn!JkyiRoUK76k_b4CdKIn-XNIoE`@I_+kReCpqOeNpgu*I8;^t_lA)bPv)gQCCuF zFOJ@keQN$cWUV0IQaybP;oNn~_Qv`s*M#?JiY>iy)1R*YQydEJEcHZ=<~^TIv9{i+ zZ+Or~s5b^_yub3E$VV6LtIfTVJLOs+Jo0mq#vs>(kAKQ?b4#xu5dK~)Eg2?_bFK-u z66Ezwu+hRR?NwXlgi7{`TLxLHu^A_HgK0XL2mxR!Fo7ed^(w1MG| z)BsHR5QL{j8s95AKcuEsa&skU;#*vrKRDIG-Ts(1Gzepg84*7Q#cDMiT8oRt7D#gx zr|KH%k5MZE(XnrRLTnzNtT}k@S7&UwrsE~G0{k)ECkS1>dr0#YpOse$OG^ENm%2tc1rf!HI~n`C^iYON*C_l6LwJ$kMQuZN7-T|QDv#u5a@k&H@}dicjp>}30^W~bz2*VpIEp=rJ=v4c=jw8&5G(tP#n_s7) z;pR_2TwDoowxzTO+)7@g@{;}^8)57Xz$*Q`44f0)1^BQd;8;d?D75^C zp6kxeOc-u}ANK1eum!s*uqQTSj1184NP1&w`UR%zW?Rk@oD5r<|wa=p9%O?+& zm+)5LoD?N%b$|WyibKKvcZ#0#md&^X0y;mQ}$6 z(#|hZ`9I)&N&X+H`g!_ul~@25704mp+@*Mw8a zmU>WsGhyx-1HFFe^p^9-qkZ{7c(va6e521`%KT;gHf01;lu3slsLLP4z@9n!0z}ua z_SoI!TLHq91&pKVq-?{&;^C_y5b4Q4=a@yJLe9B#Cm_rFqLpkxQ4VRT%wXFqVEPB zUVf13!QWfwZ=ur(y5q&g=2cx`DK zo)y&GWC3{l@b}zkuKih2?9b^2)}KD;c?o|3&M3pgiQXQ_E-sM9$MIv|^qh*nOD7{P zMKu(eg@eH3jGgqFAUpkMV5jtGcCLHaLws=yfklICG+x4AtmJPI(tho9NAcGof0$FL zwj_hU!pLJMbP8#DU156*;Q3((O)B~KJfxwA^h%{~lDoM7(jPK9xJWNA@;HpdNy!Pd z74DOK;lypXf^%f1tjRo{#L5c$qGizzQgva+}t!j3$5W}Jbc(^-DGB|?Qk9Nb~)DY+GV_?jSs#a zY<=PkCavAriXa57vX@nt@NTN zAHjT`KraIw@D%rh8pEeTH8ftry<%C0Q_}__q)I51NUf%ED(WZMN?O}#rQR$!ae#QU4q7*voDQ2WJ z2Akd1@TN~BmZukbpWSUJ-En3ug7gPJHV~O>LgB^fsuF_V)s}BapTFoU63aJ-E2^cG z*MK9qY_hxdb;RUVjbZUmSu3qw7aZ8uA8TBqysV4<&5%Gh_14u98Tk<~{$K?u0}X2* zT=XyzXEzPOvdPA5R)&SPV&&yd5Y|xvUc%ZZNY1MA;N=6g1o>Cv$iLzU)A%s@R~)S< z;YnViiA5xQn_e7v3D1in%Lpm!Ax>5egVnZ`q-+bkwp=#l<-F=EUd9iEMjQ4O_`9Y& z+qGG?COPBDBa5eMsx|<&r5+c&gllNDD<)2qKQY5j_+9P{7pwo25WF57O*ckDzNt-Y zVjyqj-yX7wmyxe2Zxq*1Q5rR28u%Tn6Vv<2Wygt^+ZbGMf|GhE7dYW09uCsKOuJdtP z>sa*8KB|38$i}eG(HQ74Aa8M}Y&^3z8huY@=23Q-PFvL(6;mMK({3Fv;cv2XPBcf= zKB|5>kphQ$me1vUIo0*m^YLDw&bcy{z!oht6$~vl8wExacO_bT3@5A z7w1H`of1okT_clWx1Z4QS8f{&o{RR$u~>FPXdahGaca+Ls?D7-u%JT)Jul&J*>X;_ zclV=>y7Sd&Iyn%m=OuiN!{t#lYVIAiiIxO&$5)cx;WgS1Q>1c=SscQImDIXV zbRE@WmdQ}mfwW>&Ve}ndHXh5a8>L{It+_-okfVg+YYKVTaJMepUw5WBsOUZ z#-$I%l@nLwaZdEk&()VIBqqT`3oAXR;+n{a;Z2K)o8DvK{-}pKPPJg@91MOKi_c!q z%;T*<=c$iZ6bXcQlA+UaD&9UaVru6*>atr&Fr~e@VA6wjx8ICUd-S1qc!mY-b)Ahj ztHoj8+Y19}9d)maNDmkTRR^3^In|$4((u^2Saf+eEKo*Nt!^f^&KV8o18f8@d6zLA z4Hx1t3s(nn*@|)>{nbuRN$~4tpx`p9w%?A2KJ~>4IbK2Gf%EWwzgWs_ZBJVL_+c$Z zR~ZBGBR8nLglok)(F?2PHmDwsDe%7fZgtnIU0AhwG{(dl0@G>S9j0*?btW@#%gFiY z*di8dj2Huo(&FtR_4(Q{aO9bV;4-*Y%ew8tTQB?L?-dV8tF}Y8svnjnL)4t>Dlg&k zI43%J=BiU`olb!*YhDEy$67P82KBrL1g@tsm_=jIx3P`i_s#RsgGQ}u=SwPiGUa!v zHwULcMyXjU*O%9WbD}6t+hc0)V=2%#<%U1!#nCe2wsWr9Cp!gtSh?u9CfqV`PIUKG z%T?b!PJvRji{^4FZdYW)6Uyk&KP?3s_tgh*O?dn8c2ksYG56JSo04Go=E{QirJQY( z@!grBxP05P|MaUS-#4l|rjCI%e^n5iN_{;Zhrb$zE@LMA2eG{IDYb7-3Y_Y-yWrIY z(+k9@;YnDxZvuLxB|?odNwia)fD>1JCM)V=eM()Jn*yIBTl(`7)$ERbO;>2rS!npr1cx%b8LI44@szdot%JD37>>R9F)d6{01_l4U!eXFI>s;KgD;R((8$AT%` zmo{)V5luTk1&<4-Y0hIe_Hf20$j|yaXZ|Uwc^)D}h?Kg;hU1RCMKqn#i}4aZjSQ38 zt*)k^yx4O@(+wMWHQ{`}5UF@-aTUiM<~+Oho-;*Fb%nZ1ijP!TropZOg zRl=Mv3mOb|H=BxUX?s&2RmkQwgDO z@Oaf1tB*2C${2gDa);GAzN*%G&ppALsvqa6`hhjXoYkGR`e7ZbKNZNB*(JsPRCWF^ zcZ-UZO>70DOJ6=&cJ-dnzT6baKiFNwx;n-_K+t?F@F*|d%@{6qX#GUQ{Q<0513yAM zru~om?&G8`SAVU%a`rr|Y+GeTnHnEQU5KWPj?ls6q_ZsZz+gpR133TL# zr^@LJ3*DWNNp~l#y^*5A+siugL$txb=q7|obQ40MP+Jw=yw(woyno#k(u8gbi8k(0 zac>juQP6pW_5PCYzwR$l@d=)xM@n=5tC;r^R)g_yOaVP0wqB-oe}VFtTgsV zOO6M3_83m!(@Ao=+2|PEY!r98f`qiNPsp3jkr9t6#G?!Gz#bwG4sBRczpffna-0+x zxsN-)i>+{;3uHq6a`U+B`*0@;)c&uCU8}dUNj; zq17Uq_G{@LuN3ldO1mr-JsI*tPedn|>8`L(8!n1F$cv)4M6ZTus$V(IHC7`}edf>< z6+JTYLyt;#Y*92wq-ZdWq5*n+kRPJy9p26t)0lchJVO}Ud!$OA`&GX0u$gyesR zNd?kAay`dWT99Q@Uh;EDRbgmx+Nr+vLB%JCz%x^HA6bp6LbH;?rNUP}sQ3gj*}ry? z&(m!^<>W{rq_|#eht>F;p)lg&T#uGwh-}O>)j03hpe!TZ7P6+EQH_zXXc0leJ0T4}9gH}mu zFG6G--2#de0B^bBa#0>pv|B$Z#^;;Ze3QSp ztHd<+dQ<>Q{qR9+G&qE9Py<+6-HO_av=EkBA%GP;P=?md3+GmmiWKc2g&rv@CL9T7 z5srbZVB_i>0x8kWMsNNRU$hOBYG~C2T+8Ab7bzJGW@p+vzxYw?mH3R4$}(&k`?AlU ztuFma>v15QZ7kr=W-b;oN!w4zQuw&*qO$s{h)r+ub(@+}M zE|Mjj@neY@;h9L+^+GtyGWfHEJtpeM{3B1r)hApeuNF7NMKi+LjdlTS{J-5e1X7|3 zecf=;?&?HoRF|&;A_monWG6=XvyES7{#BD{_a8C)ouSlaL1@kP@9q zeb7OCd2+HO1=)#MJx8gK65aK}T!bqZlEo9b{G?-pW-+gIK5WmT#7v}H>Om9>-0Z_f z|2v1IsxUKN_*8tScu)1=`cZUt6iYnh!+z|WlgT53E8G>)hadYd zc`?TWdDEG@8SjNl3xcFVpXi7Q>_K3kkdnbrchDU5bovZ2e)V{+A7wktVhiVavtbA)DNF7Yt$|!D~Wyf`$+iY*3$&`{De1a=N*#COLbGNtV-Y7NUJB- zm(B&wV)kCXY~uaJTq{J=jX;evjPkRo($mCFBJMO`pO6ymrJlFd*4Jq)ZWzR*l`G~l zudd!Krhbb|q?>jjf&II30$Vs@D)pn&*emL|@a7Z^N=x@@&1U;(rfwdOq4Y=vn0@=1JMHQ%18Qp@451+0Z(pOBKlkS8-l+tjM9;994$xOP<{JNk11TXjki zknX;kiEQoR@oeqRUDS`fWti6BqrGG)^;OtBFOk(O?88>x+pi%4Dbbt7O9!f6?}Mb= zmZ}2Q@lisgM0dBn8>V(#5+ofMX(#k4G@rfs;m!6%9u~0jkCbSCuJL3gy43o;86`pVj;o1meQqCCw(NL9IGmoKy*oZo*fK9eZ8w2xt&L}d@NZIG4QU1Sn8yx18PDp~C~0yS zFo)ghG=Z(_HINWd4~l8Aqiab;6Ih;~*1d@lxokAQ84bif z{|(Ua$>+>?mR`(<4WATkLQ1r+_I#VVer|m!<#jy`xnnCt8w}qYc2wf2AJ?x8R&f^* z(T3OYtnpp)N+T0Us!MshsLLKU6-R%cq#>sfOIK6{6|(3%Qh7`RQcoL&sh!?%g5!=h2z$;1WMpu+k!u z>QKd-qJzsCG53G{HKeuf>`d0HfG@k$Ji%n~h+y{z`LO~=#tysm6QN_1LeKmo~i znkeNDKB*#iY=vmj_PbGHvH26Fq3UVH^%&*tn*&%C`x++PyTctCgQ3CmSg~~OiPC^i zR~3AM{E!m8=k>9#w7LF$aa*%>DstZ$AI40RDD&P~-Zb!82-AxMF!#@HR=-=Znly=y zTs*7UOGR3U?lmuj?b;K-{DMai;+p!8c)D7kbY$p21!YGxGlZ}j4Fg#pZ>y)iFn^e2 z_vNEFS?Hr6EtI73&JZ@OQUI$x@xOFBfAwI3^m2+>^!)kBj8AZlgOn&neVr(^9WYDW z?J`wC#HS@8Y)3H)}}KCbpM~UyC!NyhxWvoN!DOhxVH&)h{tQ0};3q z!u?3H+LKGf;M#%GrDN_!Y=!G6+?%BPGFBys?QJGW$J<`bz$Zu-DH#mYPA(NI=L(b- zzbjKXXU&ZnDSE;B=h(Jlj{ph>VdFvjN&A3#_W#ZxJlz8X&7k3njsPh4RE98`LJt9HebkY`MGy(Ogzz z$QS!jo!PUCIM+0Y%daq#;iU=~@kNVJ*^HMq^yhu{pc}RH0IazHhDVfQ~w1*wceVF89nCIyi_kMxT%{S2T84;KQ$vQlmyo$2E)UNZMEt9 z?4=4z(-d3}AR1RM^u}SsY1%#SYC?3?M+&Yv5REG&%Bf?9sb`i2Nw(>=x%D8@<=1LK zuiI+Jj@wC&<39;V3laQ!u-B0gt$2gH!j0k8L|l#H>JBMU?X_2HwRcpIw5wx2ZtaY8 zas5d*e_g7tJvv=O>OA7Gh-+Cy@N4Id{;gQUa5 zx`|j%K)SeAr#plOJyY#$>qx^gD{|EjL?9))hyJ6jCMT>H_I+(HVO<0(6Iel@6I-E? z#{7;!(#h>(M6A6aU95x{3@&p;wN^|cX+jxC3F|P3KuYw!^T4I*+C`(~_%rAp$AUmr3V$5njLb6pu9v zlCVODH8Q^9m2j!MxbD;>>D=U|T$K~)Voi>A+_$e5o4K@+l>3#r>L4Qc3S>m5{bJa) zWnz(e^gTMLe_}lmtC0r7m>D7BhUSx`RnOiDSYyR{GFEY^GEw%8sAY&!<2$cJte&DI zJfisPic*%BCcZn=Qo`yoN{Ez5ci+qvtFI1}_FUX3Uc_=&5~ql8F_q$;#TY+OE2YUph%U^a<#vGz{yZKqY2rqR2W z&q`M1_6-n$lnjO`qX$WodOsJ76qzVu{)syc{Jz1gX-%Z(c1K0ae^s=BJ0na)q*Xn(iZuuCRuO?&CZZ`9{plxd7uJdX>-`l(;93OHRFipT5G{FT ziar%5YF~EEVBJm(Vwpj$O_=-OO5b3(m(@~=+3h2$B^q!DlpS+BI>kEdnpkp*t0+kB zT-Jv?kT-pG`sjBx%#=&q{c5lleK?i{R2s_c%g#1omVwnBIyn$JLY+}!jj>ij5Qo6b z3DI;~y?BOj>q22+SJpHRfxSgEos^9>X_H2kRI47SsZCCp!=kRaGsFELt}ceLoz~8) zWNqf;qH6q3dkvo)a-Gl4boXS1-497fiR!xx^Jq`xhH89TKaL0X7Bd_=b7$kP)##U? zCYhUYkrQ}m4KB@R*VcJ5-|t(JsroS}K%0LuQZ2HynTk&UAz@}MLc$Bkhti_Xbyo92hnuadChAv+N+*eV&@PJfs$ZErSFV}_zLUIbHrqE zA{T3s2TE%&JefN}x{-UiSf|1c5&adm!d+Ra;wToZO_0%MBkm6P)gj+#^ zBqrzw)kT{gdLz0<))3q78N#j4u@#IJAyhw4DdW&0@p_dVD#j&j#m`{5^}%$L+kyiZJDK<%;$qJ1g$SyptnTh-mO{Ya-9HoRZwo*s;HDaTtkt~Jqp@o8bEgX9 zV?ut2rZ>H5&QH^vH_RHN!AzNuAIt~wSVD8YO&chQ?T@N3&nD!DXv#83cU?~v7KbgW zpn=Ar9-Ba~h{xbBrL?TV9i%}+B2~~=3HhP4^lk>(;H;nfgku(a6)gw(fqjrK*;S~P zc9?AN>4X>s?GE`Nn)bHIY9k4eL{E!mm)Fjmk@(eX~doGhfZ-8iu=VY~>WVLgL zMXK0CU ztRSn6C#!8jR*Tk&{18p2EXZol6OXy%8Q@7K@qA)(0$Pdv5Lrm8{mO{ZSESiu1cLAH<^* z&G{Lc^F|a6V4gFPA4*H#aVM+YOjcWbNF)~rkss(4@wh>{>qnkpJViCoSJY!J`WOuR z$!c}7!O9b21hgE`a1HE(;$RiB!Hwh@I_mb^+5q_>n$FPwKAHKTj)!B&yf~(|7{Vs+ zUYm?``F@-vga@6oJbP)A13tkKMM{+E6T*)WUmW{5U@M$w9ufQ-asB!L2W*Af$0Krh zT)jRZ1zQ2y#3O=!^BAA(nu4uB!oLtFe)qgW(&iLw1*7m6B4>10y1S=hD;Qmgmud^~ z7(-*_xN3qUwnAUaBewoV6mL5r6r0$N zDF4gQ1>FNU~-V|+Wees|D!a!e8-1)ydp#lAP^nX%BQ>o3GslW8cK*ZgA8dCmsHVHng`3fETdW1O4amuF-SI* z_F{>tC3MAgrtDeDhY$y8bQ7#&MV~*t)b)kM^W{SMZNE@`eC;QeL(Be=%he3i7d^aV zIq+eLd}x4m&btv0`f8}w>QtH|jtR~=^p6lDS|^EigqT#i&OV&mxd*DT@$G7{cMk{Z z(f$6D8$2z~mc@@HL~i0SgAj*ZzBopvPhgv#iA;;Ash7?l$dW#p*oCoG^|qgfvO#uj z*yIY02q6<~U05TZ;vAaZ?r)VO_9jH#1qV_u zJ^P2P8Qq7~ZFRv?t?foucKA?s?Ab!giHXZuiNXEZo11C$=A=aZs7;6yJ!`fyu0Jcc zdQ_Ud%HzwR=d4ZDm2#n&!pv_<5Tjb(Z*7k*b>9J7!T2z+8$uXJszJoV<=$!sYy~6D zY0NK+nnj4?X(gR-Zc#H(7Yqh3;?ac=(t)l{IL|o$pl>v~Td5z3gjlt?TpDV_mVMVO znV*))kvqb5L>ml6iN`=f9N95G4d)!^87-LJYWzKe_a+59qGr%JD<*EK#hxARt2=mp zkng5cWPLAskyNpS@FpIEpLTY{R)`Kc){r$jSC2KX=Sql;grM*6YBwGkQc-`_H}1{i zx;nD{w;goUH(JpXBA5`R>Nasiy-MB{&z!4tWAnRyv7nAo&62dF9wGiYxgZVoDlOL> zwqiwhb~W~u14+L9{#eTLc=cmlimDc*MDH|^R3U_D+-^xK^qgHi zTb3PmtHB~>4P`CQ=VA3PRbd^RMv`9H5RXfQ*jJ{*KGa0;U4QBBf5c;$l}DTAPN<{c zIXTVeJVPq#F7iV?ro5e`+DklA*k&j6YM_0rM1_x*$ED}X=j34OM-pk`0z$a0G&!M$ zqvj);_SJ~T8A6Pxe!=PTo)-F(21DeoTl=#~nJx5?%0pz=)%{p{ZF@ayyT9B$W(4sV zLOfOx;?1@loVM@qyKHeQxI)h5HeE-}r!NW6SdAcrtyItnTQx}8Zuz)4S$_C)hMs?A ziskXZP4e^7Ge{HZ9TSn>G0{dQW;xz7$6FHDq{yioqx5DE5-jvxG1=}*ls^A*q@_vJ zKDoidXhNhB!ix~0O;0#AIP+g-dxz8Vl)za1eaSqQ?vGE%z0Sqx_ilB!I9M!lrFt=h z7)v(Ti4buaoAx1MQ>FHqI|pBr2P!f8KW#iRuQt3Y`){=(8W4|ALJXhX+Ueito~AyV zpUL%CM{}_cVqHw|GNTC>K?rL+KRn2fvnY_Avo3?- zD2;AwD~~CkouIdz-C>l-{uZ`K?_g<*7Y%a6Nbh0#VQQS`ll<=A84T@)R*)psU_$J? zTbPUIU)`$fb(c++yA|@{VmqBAZwZR{qM6t$O9yX0#(_7RBR|*pie1?CY9se`Og9sUPDA zvB&RPiu$bRMovlK6CTfEHWzh||?x5p38{7xrXwS$2XVPBKND z@)57(eS!1XxRyQH@netZo{1H|Evj)xa~j48)MKz_Mmt#4^S&fi_==HE7y&STz*rH& zh5BL56B8Pnocg{fZ)`(zQ1fCma~|`^c*EzOe0g0AD?ehDniPLm?t3hT5T6O*MhFML zFbC9K%wAEC>8&m5$09aEWh<#t_6>`l+M`n%g5SdAT=>a8nTC1g9dQf$kZae9@5W#n65$`Rr)A!ZX|M10{?=RH&P z^alpHW&cl>=efi6KCj-I?)u!Z_?(!gudw@Qy3p=1<%!PJ4{I)3#Pwdv)lyURu#gOxozU&83SzH%63QyiNM_ z_?~*p?M`y{Tt@wMcNcx!_jdC0jP`^mLRm%=LfGCN>$KyaX8N-y!{kn*2kIRrw$#I# zy2(EZ^wZZG+UZNbb&$tj>p+NVglI^JyNf0{VJk#O4Qix!9Y0d`^mik~IqC3cUe(3Es{-5)Z3hh0I}GjG7nR-xO2znOy8$l#Vt}6=6bH{ce|&@u_I3 ze3bcP~ zZ*k5Z=_ENJA_(#HYTwj}cPBCSP-b>DDly37|kxR7~iN{kKD{EA%<$u5dpPh23s`r?q&rgAn* zmk$_%}4^fl8Q-!#rgq3@zM?|&l>rL9gu zzl7cn{TO8#G`e%CA9u&~N!5mr)AyVzBR_awj`M2h?Z_t*VjUqu%au#>Tj-|$ELd0W zGNGZ4-Y#|SNPWwYD)N{7wmRJ{QXxs49!mDnf9`(tWatOccNq-lovB_zW7VPWuvX~F z&|hhJYwB;}{bc_~9>k*$NoCFS2dUH2(38OmLPyU>=Q7BmthEfgAH~uzV?nQm-j41U z{cRtgp0wYG`3Gj6tqEaW-K~fh9dV_IIWC{Qo}+%m5#mL+51jWw&wxJ0U|2~! ztXYPgZD>pM87&|8W*1`|*@K}D%#JE7J*mQSy<{V@kDUA}YDr`&X2rPvbO>(8%rl#@ z9tMdJ1xecn5D(kNN1f1TV7`laFx`PoQdw6;WsCH6LSKUZ19J(gk^Sz+l?UBgA>!!g zDwfdeN99yGmfe{3D%0lNDY@Y_tM_rH8LUe@R$cH&?^)G`(UfUSqe6J|_FN1u=jSPJvl1YMqVKx6Vy9 zl~3!nKXA<~JvhT`YUuLA)Q83ElRND-?R(5jbPj-c^dZEUCrz58mqG7?l*s!K!j%xg z0l^OFWzct_SE6rDk|tW~iMQKFq~uAD)o%w_Or7iXwK%+v(qo^WGDROtw4m>z6ODve zONesE=cQsEg&qez(XWbd6d^A7c1rDWd8}SwdRck&hl)D-5A;gpuV|IJpAb{KbWFom zh(@pUM-z94Hcmlbg8l=uD9SP@M%^MFtI8Yqq5nX?g4MP^tL@PpS~}sX8Z#N*GwdO~ zvep0=x~UFmwP>llo#&^~-A0J;NAuFqI?>K~Yd%aotl3iV1tXWYqXlC&Kwn-YgmvHG z$dheOXm`Q3Z7o@w56H>AV*awhA_7Hc^3;be+U-LtLK{TeBp#%R-H68u_c^JUtE1ha zrO^o?>UlgNeztdXv>zIz7h9c6_OrKPXi-tiBK1XW@0eyz%An{xjr!q3h>vGqw7|HH z_Q=~{V2dQN0@d{U-l>#|wsy2*y#A=pUQ>jl(ZpNSUh0Qns4*4eqGk}1rk@}=>w@hKt>6|^%NkHN;j}ViSMx-Mr4fC7~82*L_K#Q9@Ez>;Nl>z?lC4B4AxBFS_7!KbVN%2 znHyOA{UNMao~81P2aB0=p}y>7!fE;TuBFV=p&zSXM5P(@BHwOHi2FrOI-!Q6t?=5u zhIm-BzJSpeoG?yc_KI0Y62mW~Sg0TUh=ZiDr?SgVt2q^)C{b6@LE!z5Yq_Z zT4GNsRzLWP$N$!YG=mGs&P$WFOB>@`VLclBIkzkKr{Xm!yb>4BaRzZ_X^)*#a);&n;zJcx1Icatwn=A{Gw#o+onG9`W z{HS=#7Bxlw)W*7kwEf-lS>g8`w^ti)d1O%J9Sfovw!&CKH&c*aS@Yf0y7e5<4$z9w zx@eb-GJrjVxcPZPD&``nySyg0BdM%)hDv?rwjA!in`NvU$$Ha9BaT(EdCBbL%;D@u zAA!724r0ah$tkFDq19KhvF3qn#LV@7jqYlaN+BK(KOSs_J;W%ABSLqp)0{gIqFCsO z6tq;ddERPYbWIZ91qNs~?~3mKclsVyweKjFGT}hxt+&Z6@8RKWiRHoT}(^ESwq=T7Yv3EG=tV0uAhBdN35!#Bz%RX z1W7fW5J5-IIbc7G^>?tN5hIxGvprm&{_Hfod0EB*TOqo4#l37{+9=k+Z#1o)TM`fJ zZXYe34frJIck@Z3O;f#gvR6GlS))8ZHq#ypA*@;W^GQ*u2hMC~ojZ+Sp^3*$8jW;0 z8tK^q2TZ6vzj#wR6dG^=u@>4y6AtkzH)8(7su745tzjKqY73@v? zg&3nA6zD^OV(wn!IjJyjM+s^FV{R>>%q2R}7!)Aks(Sg?OjC=_newvQvskjXjeJWv zC3niOuALh`x|!kJB1GI-d5W}kb6(SOZIj&dpE!mHq(tuWV`HHM-LbXPW-`YESM*4U zJoP1K<uA?9j`4`Di(?gOc}KBm0FP+7?VkAU$x3W zu8?Z|{qkoVLo}^Fj=WbM)N>SF3Qm>q3HAvok(N|0r7rI7A@uqdBDI*CK%RK6{5l|- zosB(^&2PZJbh;eYR8+aUQqCM)_nmOE-ZZHm)LSu=MKo2Nhm}xYR;nZ3`5YwS6O;rg z(Vc*e6NRHi9K~uZnCm(AgGWd|_A5WjTol&Fgi0t0%8tBgS0-?mdU|_1#qNxcG`#+{ z?4A#uFoVk(Fz=#~@f)wUZIoXen>C3WD~vwqG3Z^Hd#UO||4zz)EN=;)AU_;+gCSz{ zHq~wNI`zMi9ujhg)jdNr)n0!~HG!nU-l9}IkAoqRf@eov?A39+gtms3%3IXZ(Q!ic z6OuUe2EBa`m3VB0XsXG~O;u->OA<~F^473U36kj051p*G_YO5?|9o}zLr)E#K+pd= z@AIk04)x?xN7cE`cnwbi;Vv>#qJvI#*Q$L^k5Xo}_Sdi#?m_bio7WT7uDR}+4|`4F zq(TJtk8U28W%z>_rP84dF57Y1o@<85n!^Uwt;nB=6G0*PF+QkR!q_nto z@)>g+w=d7{-Dx-cg$}{jMbG$A8b0yPS3|bA-IH@qiqa>os3KqVxFuKk8bwm|_VE%5 zUD+khS?QzUlNmO5OkXBs$sJ;2|JonS)o7#f!oE4;sSOh~Y}Mu8g{IBXX>#1Zv;IOn zips0(bP1%rwJDrbh`|0)t?zW4a;R80F{tHKuIDMu4O0KMtK`#{`B9+nZO1=WZrm}7 zwVwrP*a}A)=Y~$uH7hC}&i|jdaNBSV>xqyv=rJW*%9~fdlIy2iPa!Szwg@TnGsSiv z$7wjCSb;=J6r)u^AItv)`R$DB){lGfHr%a#rK9GRJ%W<3dJ%Z#6wW!|Y^ z{ayKa4I#gWlX`MvFo!@1t%$59T}``vt*2h{mpgCFU#zpzYH3)uRDYiQ;bBGp;aw^C zo6xPxeR0Nnk8BnpOMKY{9w_*<+PMiS{5(6~sB; zOGraz_Q>XuGose9${A_?G;S`((qhlGMWnL(Ts3?GCkL{5GzpkJ%z`F7*7amt3OX{S!Ayz zmJzcj={%*%M{k?kK1@{a)tH!#Fx&6V{5B;@?;ZA1&g@&-(lIkqpJiMvUm9#D{&T{r z?Ik;$F)sM$fZAu;FCIAvlDqow4T>4azzI(q-6ttsm4{yrK$K_1!j|C_hL zP`IpO&fFfS{_8YJL+-p4k;eQFaq09><>b*a>ez=N*;y+&;9o4&qe%W~r0(r#uTO@z`wnqwdwt9>u`RAGK7n{_NBZ4)2 zf;_C~97@!u?Pr`Hxz`rv9r@+qa zT}UoQ@uN%$DJXNLYv!&!a_rZ!x9QY&n0fczw+Ivf`K< zbL2#uc#`VHj~~YMu?LKEPVk5x8zRNL^AhCVgg`W%Jx?|p2Y)?lymgsJ3>a8STIoAW zK9oCNM>OpTSKDk{<9Xir^BRvZtvM&f`9;Xf^2Y0kCM{|A(s-`x8ROcMVH(PdW5xG; zc6WDSP@!T%w~0It94q8UH#Dub6Fv+pBt+3zVJn<}9?|=4jdb5S^M%Fz!Ze&)oEu)M zn)NRV=f3Ax4P;C6_g}CA5uxuVV zQD#b&cCt4GyZx%>Yty5#62@#ijC$E)9{2TMguF497=TVwTf9tYIsVl`fN1E zqyL8ba+=3Axn{#?9r+myo?Z)tv$-~k6+8KH2pk_o)BU1f)(FRXJrE~;8KM0xNlrB2 zrP}4d$j*8nc6VPwEqLOazI&o@#$&szQ~p69%~Vr`WZo%yKkLx|OcIQkp$CvMxa zocPMe-R{o{i0#{#l)ilLp5a4Tg1ZDvN85J{9BahHLl)BLnI*odc+} zCBxW3F|K&dONEkP{|ttU>)U4R9L|JWlr7?R z;)e*^PWy`Oe5P!{QU-r%n(IpWv2Uy#GAoW*J=`Nhlw4iN-T`MR8`jGmlt}vDhY%+T zk^lcd%+Y0edxO}&(7xVZgh##Zi?6?VWb?S)IybYG!ex^F}Y^PNcTlQz%N;lge zEbVTmT>C!|e`L31f6&vXbTN*p(o?Ozb}GkXbm0iO+ch84`tq~b^a~5+Io_#~Qo=eS z-#i3m{=m{|_2Qu%;%SfPrW((jsoA(Ts?x$%vfd-qHfp1ihG&$%Dz0mMmMJ) zEhphVhy$NEFQ~mYs zYv&SO#7)=BNXNf*%0@i3Db3zRjmW0!P_s1KK4Aod9FG34Rji9>cd3kIW7Anex>oJW z;b;B*hf*CvJib^)s!s@{^*8zt;-4o4#9=NarC#5AWRGr+o#UGwkPVVl&1wB%7xhvs zLwEP1H-N1FulLWJe_JDzq_x3{FC#dF6`jKm(R9ytyuJ8y#|JTKo|^=bjG1fnmd}>@ zDv!7l@s}ssRql?EYsYPINOw;OTMY|tC7Ex%bPJce<&9@m?i-}h0W0O5 z*W;K+Vk>dwgXQu=+EJ#j(T;v(Os(?KnEObWgij#LU`UCowKK{HGs_ni%I@HKeA~2J z+UL4f-gY34<3~N8pU=5gg>>hWKf)xWd&p(7`1MeN?3^q9FCHyV_7lpLu@{c`g-H{S zPc|)d@{%8r$C0v1nj$`LkdxNLG2}=4gNtkhkJUwlHye1V5X~cE^Cmho`p(bVHNQMu z&L}QAG0yZe&vyA~^Eigyj^3zhbj4YwYSa`OD|}*|gB-8M&&NvrjSxR+l;CwVR6@Gg z52R!;1lOJ;Y~0yWuvF)Jj;#<)H%G?S6q2_%i6hqrOQ>Q!vEo^ za}e1){+A6@`{JV>qxf-?;s?eIYd>?BZ_mjMtgUjil1KDlwt^S!v4m|7&PL?q3E0Z|J4Zr;p+k9l@!r$2k}$bT zHsVhn^=A&Oh(9y<;7|!Mb>DRH<+s3WL{1iFZIz=L*55f2Qmp-1$y{*tcjJZ|VbXsw zd!5s0WnwYJGqid1F?0j}>B?sB=|7C42!SV3U2Jq#9CWJI0RZM z+9SoN1MP%nQ(KD8yMj5-fajL@Gexm^X9;Vz&JvfNo570+hO%eo?%GwyyCJ6pT&k{hDi7X=^{T` zdG#tF7I}I@9Ny5AJKcso=le0FQjT@*0;SFQHs|RY=vn0?ow)?@qOlfA%5sI33U`Tk=LuJr2Wop(mo-P)*omG zh(^t)U9t_=_D{~0AWZh;a|T4Cbx~#eOeeEzDTDCsDvv;`_yUhTf7nOdxlJg{<4 zZ}%UJ5$5!*tF&|s)36ny%U!Q5FF!QSG`h8QSB4Fb6^2)DGuVtIfAhGPR;hFvkOTMiEUn z8~Hpo_jPeo)rUdcP6P78KGA8aZl8sp!xk$m-9tI4lobNDC@5UafsQA)8&CnJUK>-R^5 z*m!UO^>MX{8n${n?3(<(@>+{_CR9JtElXbdU$muSbL)<~+o}lheu*k-ai2g9pCDbN zWH6Lk79fs1RZa~%Jds1JdypX?dFgA}GcDpTsjk+O1^VWR`r_tTt=W-ctZu_Smh(&f zbfn9lH5f_nO$;hgRW04#mqR=p{X#E)@fd8`bbc9}S-%59Cev zWw;a)ioZFgmb*2U+g-9|#W^P+ctluIfOz_BIkgV;9D9p%j^jpOk2rJEdC>0N>f{If z3}SClLaOPzH4$qx$fpke5~QL2peFJ>dc1jHp6D=NJyn+G9L`^$Uh#;E?H&oa!}lvY zx`k?J2WUme&tQm7u~*Io4^V5{Ox4hykspuPKhjA!zHGQMkM<_eXP~!3uSD;8wHmF& z1(jEQ57HhBoWDTNfD+Pf_*ubNSdBIJvwBg821pnAk(PKBSDuv}p?vh`JvH(}G`%6c zB2Pw?V;*w`#Se@V$Pc|X)c`zinx*dN%mvPdX&8$zeju8@kCS>X!!3PuMr(?L81IlD z#w$8y;l0=V+P0xNg!Wi4rXoK?(;L!bA7*$Ky_DXCcwpQ{ei(OYbiXb!`$tD*+@g4n zxdHM+G=0U@_E|=!&)fEQB_5c)AV16>Xmsrtnmg5vNv}kC3FbJ+57Fe|8t)OLVNcW} z77xwsQhnCS{jH^O&!IYRsedfkVDSHZNc3sypl;aX#UU<+RAfzW7S{VW^w80-(5lGh zuy~3&sBd=ih<-~evMzax=;bPS=!mAgJ-C24;d*|plS@A>d{;a6p+R~5S$GE>B^;l- zEnDh$)AF{WJNe!5Rr83WmAqR2!~Hp_iWHF8<>ZT&m(@IV9&z*AYw_UQfvWGbK^%|r zKbx_85e@Z4QC)SE&|uiqxQf`rx4hP5TW4)j?qO_WTp_)}m@fLDQxjO&qYC=5^MW3_ z-i=j`x7P!kv?i$zbgV5dTwPYX9NC5A;coB7`djkrYm0Q(krJK#@T@O}^eV3%FVa~< zS~v+f-2U^PQ&dH+9$WNno;xWwkZY4X#EVdDAXgReRAqp`sRZz9ZKU zJzh_qir0%ps`bwf)NtH!&UwV=$mfDXmjar3Q$G#o7Dtyytjn*6xth7Fwd;CmsH3Ru z$dB&Kbe&IMNB>V9yum}mNQQdFBkHc$VmuLgKsCmVmw+w<^k2255*O`-R(CVipHKN+ z0GqKlTs~y!XYyCJLh`7)>ORn%R+A^ZKb^oL5=_ql>mIkVa zLx6;>3S7|Tr4OcCIvtwMctpRU#mxx^R;#|Z{W%2glJL76S?hXCUZPc60Ek-S+#=g&4YhTRbMxl!qwqy&yJ8C>g6`|=@H9#9*gHjW}I*1 zuEwVaaR{u*A)5BK{fmiO$)`${Gr^ox*sABPwsLBfMDf!k>%Lmi4^%jAQ$>zx zI?i-pu$71KEZ$F%Xi`!&!f_mlg6w|g_MXxd_NHJqHP^he!Z_e^|p04BjZ?J<&4%x ziJB26VJqAP;CC}zE*gv@KP8#hzUC2)k7r5!B7)^LwCm92=>o~4^CbDlCo7MtV?LN) z<-27rbSzB5R!A3jHYnnx7&3Z>zRf5}`yWUP(bL*56`Bl5kmpjply2Z(w9IV(pG`*5 zceFPFPmnHT288%`H>YC`&)v!uYD86F`eHlLb^O+`Plcy#cyw$uOAJQ zkSB>Fln~Bu|ar8NDda!|$8B*ed#+GV&B3aWD>I^r2Ho1DhCcyRA~^ zRtn&D^-&TY(YnE6vC@v>YPT#u31cc`9Dl|0IakXImwTAiyEi6q=KwI)@;r82qi>~* zwAE5qxkx2k-B{wd8v4eQP7HEU_Ne$UmXcUVzkQ-J*||Qis#tD_tyXa*eM1wTv>ofr z&MYXR7w^}TAtk!?^!!e-$DvE=u+9A>Y!wyUhZUCV=~tFG{e`$UudFmQtA#rAQfDc# zbv;(^h^^lFQ6C0*BKxwgD~m4IRL?)siKLqNHNSMZgOkcoyEtp> z_RX^J(ip}gD)*Wpbl7`WJ@CqtLp>#g=`K88bJ zZiqTYcZD6?FP`vkp@wuFD{)UiD(n+|MB>kLcR>j@YGW z7qw7};S%-`XAS3uYJCUp3tgIhS0`XCZd+0Ch|O5RJ0Ra zR+ZGMZ|crzJI*>^9 z&ghFXb=omm5Ga<630G>CnxbJV?MvD0R<~Ns{0kxU=%!Zi?xQ#bOx5np+-kAXEq*>y zM}EY^@`ndq-eKsFH%f^L;H9d2NXg7;#Utu>zMy90?W#0(AFVatP+Yh2c+qQuj{L?t zYuP+Jt6AT0a|{bqpYETfgnXaON%g++#_U!B<->Fyam=rZ*4@6nvWs=rgvD|;kH$M) zbmZsVu%d32F!z%o#G|9zb2V`NY^A%c2PakCH-)lWtr|X3=Mgh&x@bSLB*kT;owhDw zOg4`;2g=fmGJp8FobQy4u5_|F@u=6Qp5}UFp7PmF;-soo$~n80^Bqa&5&hKDtzj2;(C| z&t({0;?d{#3?A-%N5m&EgA6IrT^7G*uwLPk61IXFWS}L?V6bZ9&tIA-;SpY1HvS1 z1s=}IBio~r-z6Sh$y1N~<*BVa{`UlYFhfcPL+NSV)KgtPng?y2%K3JXMCad-URo(l zU3j{JSu5tl`9!?Mfk!mxT}r(gQP~{i7RvPlZbD#ypnjAisZNtrgSSrQ?)?C%{_4k) zk;4R2xwgv3-h4E`syyxv(3uJQ)Qnt@9-80Y=Mh+AM>O3$?0!YL*mj=(VDZ?ZsBY@ zi@D?bX5;Vv1E zXwoiRtTQ}Z$t>XQQ#xqjfT9FMSxcrI4=2vmBwcyPOx zUmjVq?a?we*qSqB|NfO_jLZ8@thY*4iXI!LVJpZ>|Jnt}b7rSl?9D{wmBoicpd`3A zN$&!zJtO+ui&4HkAIxWpS1Lqn8(k>uGOQA?bds6D=(mHjW{_7s~3G^FFk5|OS!p{StHK>o&XPqIlRFz z+~>I%W;aur-rPfiQDn#iR{*s88k0*3AD35cyL}+HHo#R8Qlfo>$p6H94!abmHXahT zf*E8yqHxV{ z6P19fQzWE|{E(8t@T2Nc@x}u`<<`rwTnzxxJmPd_d9mv0C+2}ALnW|OhLsSkywKjn zlHsDOTP~!_s3(vQI&9hy^$;l;Nvd^UirkGncozGSOmPIKNckdu#`@8V-<VypVcBpx_U zF6IXsK!<3)I^-97mnM|pd~tkPseDS&K4bWZ`0t6Whet^}Vf>PS9L4<9jxjuqqrS1* zR#09C(6>vZ^mK`1_|11^?c1xbOvLe!F%N`30H-pwL8`b_iG9KsNV{zu-5Tcvx6i6Y z^BgnoB&r?iNOlGsXB|fihKO0ejpkj_T}wPT=a^J-{5k?g!}?KVIB(sorag7*a81ff zw3yM}h|4jgA2qakk8qVBxY z(MtC4j(=%51@pr>Day|HP`>*5$3(UNKN{waUyPB^${n>nuQMg9{h$3MIGS;EOod-# zfHy4`*W+uRrL}jBFUfHVj$(~-0&l99ZF&FE`x5KC%_P~DaI|`y6T}3ZTbLg!vm-G! zsu4%CrDP++QS2eYMt=`pe#lUJ@dlLR6#V`J&Ph?8zbV97)vWfk7aDO)g`=3ui23ms zwSpgdBvxG$A?=+p6^@4v9;UZa@d^oX_TpbUa-4!zGRb}kFPWw6&tVsN|sgJf2gSZ!5envFm_F z6t9-3MqR8?|4z85&5RtEIB-=2#hL|bH5c2`fK;#T`C@YMcE_4a@m{eOhP5+zb-JRa zrv7{@ao{QWoD=JxST9wSl@UWpjxjOzzz6b)BBsLo1V#BX;TYMGG}vA(Q!nXM2JboK zJ&sqQTy)%wID7ReEv4NZ-fiJs7--@3VUKfezI_<%Ik9gYqS6r$9pWu*97N`pim(TJ z43l>BXqTd+asZ+~SPgc~&8uw(s{yt~V5$>gTUto^6Z078tmxYz=050*E*1V zZg2|D4Z`8X1eL>qq;eps;EcsM1sD$JIOX6R2if#>RB~x;mu&imrO4SHI;vf1-G%!f zDQ8|_q35X0b<~2=i5a|VC3*=*)^i>85|>pCI%16Td=S~fb<`7Gdb`)S_9XT2%Dh^a zDtu|K{%qMEAN^33Vv^@-c=jk(?@M9*mY3nhy1QinnU}jXzw=g=d^wS?fi5FXFDy!9 zBDZKoGgarAp9C|vkM;GPPm4-krPvb`B08w&NQDh=wbq*(aGZiA#5utUmf}Ho51gY- ztyo3!NySvNuQp^oS2fmS{;dM#Xy93%&W;GsJY#A~Qcb)c$m-4Spyz&8T9*+~#mbV7 zBN-o6ssxW87Q?1*574I-O{Zh2&b=JVGUV{muk3a=c+}2HhW^cX>Y^n%PN{q2S61vZ z(JM!1)p1VXm%%;~_nDdafa{f{_P|v2hxcVMy@K?0pV9)4HxvA5o2s3(An(!~r_??k z#_o*lryp&dS;u7pU39QYwiIZ^FJJqG=L(+4O4ezw7vtw0n8(7j39S6_`g)#R-(h@w zC__nw#1{O1qbyR%m&Z(IaaH{FlJ?BHj2OKlGaa-c9}hT|PeNdR1u93g_-2v%*tO?@ z$G%m~sP`{%+MI0}q;g=Yxf>$cb9IF7(dj)Pz71(gtEL~IZEBf?W2#Ff`?HzXWAtuM zZaZYe<@U``wLR{@QY{}ki)Aa(To3lT13V`0aHB7F7UNGp zq?hUnqj#vI*tJ`|^)+>l10pn_4b50`ytbnMXAP%(YaPWdwU5>J1zdDs2|)`VA4*!C z592r7&uNQ1rm_p6-SnKdXFD*DE?MTWu}9kI2fk^*BWOhz;?ungKk@F8RE|xDX0xcN zE%lM3FFIsI#Op%z_toxv!ttjP0`sf%I+iV7IaH6nHXC^C{4E?#vkt%Z|$= zBQ|G`BE47k=ALaAXpxN;vV%uE>Z6rqjsq2zvRyC3^v~6rI{JoBXCXy<=>v08;E^Y> z3|(@@iihLQzT7u8P=E4TTb6ZbZ=i_Yc#>SZ%=8mZbE*ZnlvB`R_Uq%AL z!>=bjeR`UPwFJ1CPnW$C72E2JmrtI%!yTTyhz~o>ibFw^ieJvka6Fn4fLq1h#Z= zjDCG(0pPKJL0`J2#sckiy_Oo59hXT)TndgO)6)&+%g?9M9+p_fdhh6_H>l|D(EnJ@ zrY{NCm-lXbAUt*^J2JeVo@SdLtej!nD$zkZYw&q%vr8q%RP}C8WZoaf>O=lA5SMlj zpt0Wv3zDcxwUr)zr68|Z^8aE+2dCI^cG(t{4o!G z>vBdWhwB^v%DN9;c8HHB>K{Y+qEU~0B`Q=78S!V2Dzxmhn!L}^?-By@>y9ON(=YTPY_ekP5Q~^K{G3sflTqGq=DVdbMYd{hz& z{Bb#Csm8jGCGBic+$Vi=g7d`^rfIsAm9EfLU$xZV1|D>+#*xRqQT*(!0D@EM9#3E` zF7?!3Y;0%4Il;Z{FBRzV!`?h3Pj`t2Mhxf_$Bu6r1uq@910FAEKk9pBw&tHcko-O+ zhK=)|qECnlx8X9$CI82FD2a=TR;L_rp;H8aL!DK|yZai1!Qv^$b%QUv| ze75F5JH5akdw@q?&mwee$#VRy#~lgrDsVD8J~>o>HD{CUFLf+i5;0KkIb{ zug1;L;s+m+%7Lk#eILryiWBtNOAQ{+=QSl8&voXV(mW-<%!_07<67&pZTD=L$F!33 z*tS<~^iJ71AbL$~Kn|Sj#Pw3I2&Tfa%ZM_)a?_DzOY-g2(ol@R{OUd#$`;n>p=U07 z4|u%l*Pd?c9-|G6cti57@6Bd>8L6jQ{mO=A$7O<-<%+nI5YJ}3MEYD5=Q|bjo%x{e zbPD}$>j9C=dL1VE>d352Q5H|AN&MS1;}hHEpg844qmeAkQCCm@JPX4)!7Hx7qYLmT z;KC!K#|$>3Ze#sQhSxUC4{ovsq@#%k^6>1{ib+yo9+xXcvJyGk=o{@>K&m;{>(hLd zrfMzU~a8z3&6Y)C6@jntkcxKW()>(xlsEOvz6ZNhsS&Ph>j ze9cDgjIr@~j#3m$;(IloHLv8Wzn|vDM(i5LTKB7>S7=oNcnqufjoGo%LZ0ivyzM z${XtY(%yXZ@oE(3izR88DvHf`URZxqt`;B~dt@Ye`c~sh+E;^HDIx{?H{+b(mgyhY z$Zw0jXzLp>iY38R*xMAmsk|?dW?L10XoF3X3iFT=kJDA4X`2nuo^AD(cwmp#ZwDH( z3}YJWrCwBla-_OYiUx*8X+_HTN`9~Sj9y0M?NX6;Dc(?vh_69$3a(LHKDevj-~zeh z_g%~QfKeJhB5U>;aPcvogtMVff68V~B#lVB>0mi4Q=_HktGtpWVn z&gPOvhNY6r(QbJZtz2%Aw)ewH73+hT2iCP95?i^-bQba9XC|J3v@#2xN;-AzuH#tEwA1y}|1>^; z^=q)I^{GN{O{~eMho|<#l3*&lXMj5<%i_tm-9vcSs7Jnd*MOyx%Tcak6nzvrUmNpV z8V%=*rNVn3IR9|3MCa%B;onE+k`Q=Tgm-$NCz6R|(49fN(w|@LSYAwp_i%8dsz+b? zsrMYsD>6jG`C>`%J`r9x>Q{mOd!QO`v~{S2z&l91dxi7tu`%S($^pDiQb!H%U$G=u zLTJI>;dFME`C7l|B^usU&)FNzf;PtMd)_T|;C(yjqQ36*^q5NAt^a0ee~ziJl>*-F zyAn+rjP1?0d(4&g&X@|@AHbg>G?=Cu6sOhNb6K()V5zW;13Xe57NGq)m*H`RUP=gT z{lNAa;KACGx=~>~egBIZw!L6Uu!PWei?*Zbdr#4R@AXQ<79niQ!u;U<+ReFW1OH;& zzUUV?ixgHTjKH=mh-GoU0ol4Vh>w5!Uc;6xY$=k<5p=a7?btD1`@3Csj;&|do`~&? zijwr|7aBM|Kd%;2K(fPODr{R+l-e08k+gAv-2YW3j_rn6Lb)7Qzt^INx=+;VbtuWP zH51!+F+Z58YriFrhiB%k)hd!b5hJkW7J6dMti%JXwFALgi!HR+$|;v4TUc&-_sm?a z_gKcUtr%%!l9e0I2N(7x=lXc^-w#)nEZaD`gDlm;O4rn8!>jUpqpEXkSI72b8IjbW z4cW5#FLnQkVQ_0Jfkk#uZB?re0}V2SHNF~bYthBHZ6Ct6=P&2q;*If+d#!;rNvB^f z+Z`bzAg)0ITkd#Evg9>hGD=`gJ-r-&hVKye;Z!CEpy503i~OY5jR9)-ZzF+667zm= z&i`U~56BDgi`l}Obc@mI&lmvzzkcOQ3Ou-^?yWJxMJkIQgZnB7@!^O&Ik)efU!GXt zA*Cd-oa&MNORI)MzLp@N{i^-IiMht8$6>1L&z3Ns=a&Aurnl!wIi8$5Si-o54gSOFhE$PHK{~Dwt74KUu|X) zQXorS+IqDS!_>-`8TTtiOllF&6z(*%YE0UaH1zhRHh{n>RyhETbGp#ahg9ylhV;4L z$K-*>ooLPCC_2915r497*gUdA>t`Y`6^^p%jGqegRl^#j<;_*(7oWadu3ho!n<1_9 zO%p{KKh=jciC9C*-0K4foMM#&>Ib(|vrcWuq>rg-neNH$k6TsT=OOod-s5ijR;TGE3YDw3DJuiU_tN~GX?v4nHxHzF&t-BBxq3^x(ZcU~mf zV<^(%)kDA z8CMF70bsMM!@22z;kV>S8cYY+^%8cweNY}w@wE{hiac;E-Gio}e z&CTzW_JHrWaQ-x7iZ2`)dt%6h6Y4je4mA^8GGOU z^lfrPYmtKUwZ=Tu$WY+X_6Iz~TN#*NTJ4Qmv;1g2=Jy4DhGubWMGw7iTeiW_EV`Et z(d+*?e!uZ;-w>=<-FyO0We!x^rGf&-(;U%MDFx8Kd57s!$N1UgoX!VTB`xb-w$E6T ztdR*V%+i)zw3>ad(vYQ|^?0U7#Z28NYiKDw>}+}6;Mev;5k1$a(&qO)@bGwxAAYV*%BKsx>J=ews(KvHvk~7;v&3`S- zR~P}`mOcm4UN76(arw_sK=+(kij=+Wt@T+6^R5e(7VPEd{w~bqArR`R^rXyDcb=-W zzlpF)2xzNJz{BzDH;3<20_b#2bCd7o6&?{CWFjzC!$lt*PuKaIJOpB5;(N8w*#3Nc zt<{<#RmQSy^t$(ccNjH2p=&ce(QCW;9hk9$-fd}j_`aFTp*DLoh?mJdRWqop6hNo+ z5{I1A*Kyy}@}a@J{N#U39#*RXy85eHdfZ;cl1y7yjd`!D1)wJ;u=aOr z{Espw0#jXhSww%frj!dJ@0t^8cDJs4|MQ2$$Ty{>OdctH%x3WD|E7Vyx!O7S{=7;d zyhtDZ>wCCI4+u>4y+kv;#p`V@h?ti9)iWOk@%2Tf$_PMP^A+%T@kd*Ig!_0vXW8~% z^^Y3PXLV&J0#l7T8>H9l=xy>4hza@csQtDyHCmP?My1UznDsj7!=%M7*f{#|;~ zaAXHwSx;>utdaxOy4kh#x}y}ct^^|M?YzWm`U-8pCs=DC-;~~9QdJqS$&s~PTl0Hl z-Ik7>bGpFy?kiczmv0NSdDDz_Fo{_yfKKTdW=)HnDwfVfMx6Ypea_xl<^c$+{UImY z>^BbIE_HxMmrJ=w+0I2d*Xx-GOjU32M@Px!{-#s{;j_0CX|$t&cJdJHIk6;=Z~b0g zjx*20OvJZKtq!c8Z|sU!w$4nN9zJKE$wr#xuu=eR?a8H_b{*WW_Lx|PpHFQAgf;Hu zzAKe!!-k=1^$7v|V&NhtB4yN?2&-)XA^P;xmj%hlT?@2*1&rE78VgWaH7ZGUssC5? zUd2yZd=IEyG44zrR=r`glFG9(DLdz^{p^Kg-6v(`G!eK3ty)lWoq4W0-Zi4-s}(SL zgif!+VD^DpwDz@T?FLpV&8GcX1il{~$ViUm@}v(2*D?_)yI+%P?w2BrEKVM^0#WE% zPEu>_H*(soqlpkZcf6xdVhsY0+d9{64mowOl_ke&ILO~YJxzqz_a`yWGaGH4XSFf; z3B-tOm56s}8?tr65ECKnK1pn4W-r_8jmfaZ=g?^0I2zAi^>|U(M?t;cX;8%WuzNRCcFRTvV^G-6 zPSh?%;-hD)%`>}N)vUf`qD4+YHOiCCW8+D?i~~)nL|rAZL6Kgz=T*A8Aa-}@p>|nW zmT!3jI-J-QNfC5$>{sxOdhmG9%G+u9x?Vq7|4567BSlq*Fis|%XtONK9)dUc^%Zp|{nL2T-bHGfJcNY>c1S62-Y*zm zmmQCW;lWz-I+VHllaaP0Q*LTbbbzHGXy8i4jO-@N-`ztqNd7o}` z;pb+1uQsV4O|*Q*siSj^PLA|#AdhY>Z1Ik=)1o%Xt>@n z0`pUp+nIN$OKihv<>@`mayWSyR7cWwWTPUyU0TpH;Wzbau2HmD*mu*;aAQD6mgc#) z?cljBtWiK$HfrWc|FusyGkcaWwzyqBo1z?#nxfXs2XS#LHZ&3M9)z&(Gw;w5;oI2j z7TuU<+HV^$8tf&1?Nl!`9!2+iJXhtEB6Mt|+7&5D%vsZz zA4FDN=1@K32hkpL6Nr)5=ljhdrq*`bf$wYB+o_$|(>dd8qlztOk%=8x*SIxMj>(Uw zsyp`%qG#M@nh1{?%~^Juysw#`yCXZ%+h)r)VB+`V(LZCUAy;Wk_X^;A>a{ugrD0nu41b%BubN0+aaSG;vc`Hh`>@CUk*LA7q zmx92m*Q)%2f@{Whkxp}|JPPN9Uo5m%XW&t9Kw91c!0hC^FsW~>PDtiPCGT01V`M2(^sDjs=CF8duKOlS6H*L?;!Tr1UWL^@f-cL zJfAk0NC-m`CqEp|7Vby2IqG+*YB_%Jp1&0P6Z62lVU4O&MO{&%3ICMW=p~jl3hG_# zim}HY+=B4(PE6CF4xcp6-9)5ViXb|=@HWL>h!Fkz6ud>&xCuXVyny7NDCaBqLFATF zv(&QZdhp2LYm(gud+A~CJs9V2R8`*;%EKD`Eg^83WItq|HO17N<$`#cIq4`)!8|0J zlM+6?w;FJ55Fb4f=3UqWIBiSV2M&9oLG9l6QZFS$@Ny3?NC+%D_V)wbCy$?6cX>bF zWW^526A<&jyus?cdWu@O*I=GIbSja!gM^l43P}s6mTxzy^V5vxX%FvLjl7&x*gp+> zh=C2@byoF(`$+yJ#M3N?6M=6;V6>wA-EX~m7_p((JW!6YgHA(9$QjQN~;nXRG;f(__Q?K*GRGQMR#y; zPM|YXj8G?nUthOquu}uVvTP#>@y#dLe;li+dJK)`E&OVmh?Kf=V4pG>vHt8FwSe~! zey#FE4X0plDv7t!|GuYsy;Cr+aOkVaBgF!xW1k}IYXoOS!)B@>Zryp@Vu<$&vO5vj zHwvS{qtVAhz45&(pK|k&gus$u-!F(QGU2-VsZS)&Bv0{IxNnLo4 znr}5UQlIP9ttcmNPxG4;P@bnQKuxKf2%InWX9DZTm1XL*i8Xj! zm#UJd6Xs!{MNTy;|LYg`XIXx(tWA1@2dxHXEeOQ-CU5rlZers-F9HhP)s-c&=3PKX z&svgLDxnqcl_Lko^)A<_wMqcuSYAK1bwC&XG2L5D?s13;^*4C=WQUu&l=bC#JMWWj zPD*_Vk2J*&BZ|O?nozs8bhi(WD5GCFM;d71FwSehI8S`5`Qq6J`@k9q=lF;BIbnu- z4l|q$W;i^H;u#L{fcdKN1|RkF`>uT4g-4Pnxk2Sz8H{hsI;?zFdf9i+4CQ;$|4s0U zgZeJRw{GATU8-L8Q-J6O2)tU#R8~zh*gD?rd7ix>m2N1Yo(NP{zk=_IYxnxj z`&ypg9#1INSY*vYXdIwrTwR!W?i6dOvNkESS_m$7uQpLm)}#A26r!@Wjj1fl3rP4RRW`C+ z52ob`z9m?vHtNS|7nk=RpZ)HuH712n<>gxg<9hS5O0O|CpTsQVJk-d z3{VbX_iY5W@OfYh_b_eY*n*wJge@G~$lHPq*)2AnG&F66jnuuk}ZD&_RuM5L_F@Esw} z=v~e^alRO>3(o-)AG5l={|RI7jL&|Pn04+92vH+7;e>Z8obVnsPIv)fojb#~ zb;1h>>jYDAfakz-@Eka7cn$!SIQ33qmgfKfKJ>2A=dKT{xm#ypKby7ThQ}5lgx6FOvplu{Vb!6M7JQ>hS5SDM;Tr`A;r*4wEZ-}_GrX@gq4p@@!btpwc(~!4SO+Ss~Xn&jGGog z$u})veBit+*_qL=gvTcG_yq)>`*6P2S_^38@oVxBwmyu;{4RqRYt9D&_O*tuGuZl$ zR%+tEqklZK6!LY(9<<8U0teOIo!4nTyWnhF@~5@R1ZYb__%{4ryCwU*0uP*m5tdYd z7%%)@0b$7wDb`GF@(@1IpDGt29k)HRPbJZ^RFdqL_a~rVfDe5g@S)Fa`p{!PZR|sj z{ly~aY4m`$!N4&?$Rph(r5s$s@i!N`i zxG|F5yfK1r2^44I#)u^qQI~mv)pkYTGePHRpV6}76c8a|j1=c-sPTvPoI%Rvb4B2DN4(n>XWltKl9a zG-p?Y=s)rp6lhn3=nZne5)!&1MBC!k0NYMn5!f<;+x*8oL<+VVU~2;6VYZ+c&+=?1 z+6f{4(}KdnhCQo(hQQvR!n)&%5N#{>lK)5rWl+p=h_y&=bFuok^03x$=q1+v1HQ$+ zB=cFk8d;)n7K;$WylOBqwYx20Qcu8-IqG;nxQThU+ zD&4EV&K#T%J3?Og{&KKtdetqKyX*&Ti zEcGyYF~h$H3?9u%tn{`hih&M1E{q$b^##OeK;RUdFV4y6eQ?(c5R3bcF?jeR9_9;h z#@nJOYC7;Reoh2V!TI8x6eYuWc&ib3M1xcy3G^GQuB=z)@T&rF#xf3GT}UYhPQm%& zoXpxKMo%)#iaBS2?6K>DSb?e#&05&UBCl+qJgle zaKwMq-;&Fr^-C!SMnL^I$D{N{0Gvm`hzbV8@Z^$PRQMeNG;WgH!#Qe=y0Q>x)JiWG zKtv!I=P|$odI`r=X!dbIe1h3$03a4rp%MbkKGJ&%a6}LlE{c($Bdw7Zh2|*cRn|IiB%396A(u&1kZu; z!|3Wv?)Dw;he{>KvHRpGg0G*ApbZwSx0hd1Q;I{6d0^g(a_gTFbYSxm+J__W?3g?B zN>jpSjplgBh&PcV>5)IOYQfDl6;t6T=5ln(@2!T@8EY}1?O%#jB$zvn-ii4sN}He|^tO+`y+-Lt1gGFg z;5cR~+^E{nhvq*2&R(wWE`n1~JKJzhaDp|t53PCbg}p?`ZV7?ovSPHN3@8vuuil(s zA2Z;T6ulM4k(Ck8`ZT967q77g&CgBI$YD5QFOKA^D5QNLUE4OoZm(?WyJkBZ`Yz5F zN7)6RyMyiMg1j&6ou;Oj;_qS}n75*=8t6e^3>jjdRL|6RO&*56gQ;-TW6)lo)}pg6 ze75^l^pxTuqZy8&nGbS2BxX2@sn87Pg1C3T4lQ+lsQrUmX(_rfmIO-(bIJM6H1I}G z`>1>WN>R*l{os0o_dlRt-GzRY4f+-CeYjuAy~Nquz4!0%#bXfnc039cWgW~6>tJRm z@&RrQqUfD?WuhI64HY&wW#8jv~ z0O8yZ4uo|OuXlLm1gU`1+$Vxm&fVP#SZmQ<&4Jf*kkCXJ^SrcI<9MaVS_VjHB8;^w zdFM3-)>_zkajbt}-3RML$@{2qK)^nVqg|2lO1kqkFhk$9^seMxk)bETu83n@4eNIx90 zg@!EcAW?f5dmLwb03wgjccpzTYI9>|&{MQ1Kp^c^+HIqLWz1bB!k8;1T~x9GpuTHE zeb)xJ2ZUxRStiiJ4vox*yeEKYvf$_az+V_ZwId(>oEE3f1UO5SR+J+D{Oe3iXViATSl`eLqL|JI5O8;XgrO zDm;pQTvwP1>Wvxvj5+GZ2uuZSVmj?_II? zcCFXmeP)mB^&5Zw-#q8l`FxUZW+pS4B$H&eZgiwi`?lTM_H5a^Z5y9f1AJ<g%vaj(3o4Qxr0G7;hwA78;RSj(dK_-?-65E+u?2&?WNg0(D}h8)ZP z8v^<&1Z!D+H7P33ZwO2B3$F(5#9EnCWi=keWpMVi*jJg8Az%FZHeCKRN28&p?Ru zYx8P%w?sH~j3eLu`7VgAiK&YwCulfvojxFNU=&diKTn|Kn;$&isVfKB9u{ zBgs+xa7Tu`e-`j@0L3-Yt7f0tm7zHL#l z7HZA1(4V8W&)4JfphD5?a>b)6)Y! zSj&>h)S4x^If5nWAL^^GdrPoA-?zwE%j!2%YgX@?BUq9yjI7E!Rmjbzo^X?~7U~Aa zrX*D&4W1?q`k!=@u>{-2mLy3huA)hUZ@z7ju@>@<+)C0Ql6(M3ev2f>TG&6>Ba)QM zURnOou_sGtF+#>#r~~YEL4!lFmi6D%vxWFMYGW%^mfsPL!_7vhSj(bk+LFc9PtUM` znVlAuROrL1=?oSVQnKamiG#GHgO~qQM z8`P#GJ)u$SMqYFnjan?R+BK~NN3$eNBF|uu7oAU@0c%;jo0fG`qVY82U@fcPOs!eHYtC1a zbeQyUfxKt}&1zT+b%P#Nl1@)=qP1I`>VM{s=)~=M&o+Vl+YmS7$KV6{xi0y5{`Ou( zBYc;?*1qv^IrCUwVgA5clUhC2F9mw=xA#n6Qumm@k}=33hX%(9^G8^fPx_n!8TqQ? z1r6J=G)B()Zv4pwbN*;HWr12ebya!h?rs7C+eNe_Mdex~U-inb&WP+T%sAL?*7a^i zi98wky@e)M)obTqrB58U1^g4qu*B+7bB?m~Va{-pRJ(m0_P67SnlHy@8G8{CUMt*< zW`jIfCFFhw6Rjlx>S=ys&1lcsFfn;`8hJfi$IghrQo*Nt*h)ba>7S?QO58 z57Dq>Q|L+kL7NbsqwRNHwB1&xvTFA9hvXWS%4j$aO6T3DuL&*9bIng_xOwl?C(bRw zTlF%z`jqCGI&Atjx%h)x0;0mG1U<`$(mcU4rGaQks!Vp(f$S>HSYH8wob+y^>KD(I z<{#ox5RJ1pE~^DIZIBPnZ=hib(m-w{sZ_LG8&vhN+@a$;75PPL7ZCxeC#&HV%F2%U zJv8heq=y_zQubSS;6!tXghUP)ClKo^Q(PSlP4Twhl|Fo;MgeXLoh!%%v zv@zPTH5CMFN3=!5w0udbNOm>)_9@#|&v=HT$l~1`6PD!Wno*J>NP{g% zgQ>|g;7G+rP5h-Rn9%Kr&?bdn^)B*`iAg~ol_VON+syQ zXG?QWmy`zTUy`CTu2o|lDcO@T)wMyF_UT=`LinAhA_7~Iqy>}vsJCkRvMYVdYnNm9 z=_~7p@HYoj7>F)+T+w^PhVX-trX^N6?xB9^<6xUt71UB?QuOtYLU_ezlHrwVpZ;=O z2=6j0g@G;6O5b(3`r!IJc~hg#THZ1z^@(Rf_||gYb>swXOp=9WQ&clQk-8*}E%xv8^FIQ-Kr)qHmTssTT?f<@@e@BhS!gWvV|zUPH7r4T z*peg#T`9LOGP;_)>&-xIw%-kX+t||FecN{(dB>3^NeBApR5mm}DYuF0q#?hEz?LLw z_r1Q#=4#nl;dN1h9EiT(?uK3@O$hgFXZl2!{>znFpJjHXLJ_U|(;NEIqal1?PEm4E zj`_>i%K7!9wn1gPYZ=`nW733Te0gIR13AGlFG+_sHId!-t(UuA?4%)eL|{vjG&Y@X z%i-b98qBGyWmtDZU)?i=@4Wg=NA&GBk}gZR03X^f1w@91womgXO~n39L3dYDiyqCA_?Gg!kCq=zj@QsdxC zY*d;1%2CZnyOSn^@t{vW?*Dfd19?Z^MJoVXPWC;~F5j+OMMHiOfh|eWhg;j^`Pysw z<^3o@4n((Xox#W);={{S_9V&6)vsu)qm^JE&y~?Sq;og=h2-Z=V>|`PMLEu{Y{gox zJgiRGG)zX%i9T_Vr@Num&cX}U^ClV(Zg*tMPL+|zoc&ux>d3o@sQf4|JN4qd+)B=; z)$z_~Y`pBlhYj;I5M7{*yAhGslOG5-_iCrOw>)4|Q8s#Yc|i_DKa(;U#bF+4&PZcS9G`(V_VqPHuKXX|lJ`vtW*`2|%8)wNLbN2c zTDL-;7}1mEI#Aw*)Db=DMjGQ_y^P%MRfxFicD0x7W2tDiww1d!JhO}8*)bz8T*uEi zUWLY+l7WwI=x^L#l9>a&7nT{SF0df1XAEonMLnLPc5{4lH? z!*y-V#83K;eC~Wjgs&mWQOota(z%O+OlkNVic?tEN?zaTlbBuS6dBWl!$)a=bBF025g zLyz?r|9bGuBMKNISCx+3QELvdvu*c2%Sc_Q1!!6=^*W#qD%^$n1_mmv#(&aB?{nwP zV*Ct5Pg?$14{DW#|LAD0+w;ans8b$QV|!Ik%`e4cJ(Nn?H1jp)xIWTTz4qY43luW$ z#=X`zkIKZoM)(n8@7pMK=DX@_{wWU)OOPJ6BuNji6w=mB(&RL^iZGNG*Fm_#A)SW@ zXr;devyUgH$^yS2ZKtpUdbJbzc-l|qYN^QSG+On2^;pMc#Z{z^=;I6b>#bAz@a~gy z5~6aB-s0KDHl&Wc<7!!wB8ND% zD_iojmm7+!NFC8G!Q1s8iv#(>UFP0-N5-_;=m|DWJ<-WSf5dIPE|0nuzKR zI;p2aIP)!%N9(vk*X=j+@uh=u8HjGZcdPF9B#;+MWk%KV_OxlIcRiPj`hQZ9I`WP? z07A6RrscYyo#jiJNki(0p0Q|$Uixwg-f@IE*IpTWLLF79ILrAemxk04oy%>99+a^p z_Znv+y1cKduGr{c9k%4tvX*=vUqs_-nPQd=GpRT4RAj+x@(BoB6~E}WSMOLdga-$h@scTF+0`PC94zgv0>UaB z*VH0n(D)$rAIZU{cPXG@NrC;_^l1%Ca<@J%269WsByZ=ad9D><7tRI?djsT3M7(@_ zRV}&1jjfzqR>M9)X|We1>D#^gYWxdLj`^pipby-oU`vt|pqEk?WUatnPZ9eH}Rvt;znh{l;n zl44?Os$Sb7*^s|83$q%|?Ks0pQsJe$)oZR@+2iW36{L>5iwN7*Yid%#y3E!pK}PC` z#+jPdqO13)j*VO7ffr&J&ic3x!dX<3QVx5k1Z1eoJ}t;7tjLfPl!;=mw#;g`?t_@t zFI56kM})YNd0h0PQZGjX=29!Iz!jo#HSuph%!7{*ReCP^CCZ?bLN zo%-yxB(4*m{GGx0>xMfYd&AejH6vN#iKVi?YcKYE>gzD1j=YPA)y3}0-d#dj^RaFM zSBS>7uOx*$KO$E+8Ypk=+@9e&8g~;YlO)xcRzvow!B~la0vb|BIdBI+b~QDKwdh=m z-D*)^Me2ygeS#!qE!mRQJbggU)pClATp=3wB9henL>2bAdCi1JseJ@FaF2t#CEB0& z=_nuS_4XGm<_id6i(sdBq*)B)`{;X;S|FQ{)z&$7KUTG)X$6c;Fz974_!y)XQkrPplCXdswO_!F)z0*|J zkUAp7z4K<*O6+R7ZA$GY`Gpt&qH(WIv8Cd5*r>TL)Ujv&QZYJ!yrWEXqBtY9vdai( zyZ03nA`=*&!6*gI=gp#J)^oqSdS*Kz&Vam&h}P%+mg_e6wjJ~BCPZ1}*lX0F@b0@M+wsdogvd6=tS~Y~Ck?gUDIc#g_HwJA z5bMK;C&v9Gsn*c)YW=F&*z^t6gvcH8E+Sgg=%%*Ha!ejEv9%BvMcy%fDM{TsOj1An zg_1N{&8%)->R?%h7Zg^O$O+0MNd-Oos>-K=Z0GLsLhKb0xMq~3 zuYavoJ$zHJfV`1HoEmw@H6zh@a9-7J?vOtnsjuPM5Tn2t>y@MdSB5D?$M2UXrSGDB zH996f?|arwujG{I5y-(|v8GG-@_JeISEUDjF z)gSmDbiA%r$%(dFlB5=y7AmE*0j&7vI;z?3<;2!}M2p*rXWLIOw#P;CH68`@ij5~3 zDfUJ27xDKJC28{F6ys@#od2LjRvT$wbiTA$p< z86k%vcyyhnM5AT09JxpiEI~O?KAH!!ZB!m#>&b%M7OKbzqLCiW22G|ZM|TWl*(ENU zC3$+hXN|+aPwt@w2Zi zuFP7NHZv}sWRyu?ldt~kIBBrpg=I>`frFU+z%vC)R#cd5R6bIZr|UH>QKVtYF`eWX zdvZ?#)ZjW=0U+aXC4 z|5~oBEzy}h&Una)NY=B%@6>3cQL!rgcGF>w%yA=(a`h{4*V?lQvGVOkrPSMAEYJ;bCrvIa-%n@(2%53A04(*{4)gi|^Wpv+2_HMeDfY{iejSAPVy2~02BUgVbp9F$V;7hqhm{w zbnAYg5?H+}>vK<4k>3*Kh8tJzI(X*?i*=+&-e=f(rA$&=wz%ju)$9|?N8y>5h}f`m zmf}9S8q3=?x6|*YP8-2@yWMm8sMu^_{Os0L2A+k{y1j6ERd3me6$vm@Y!~U7|E-oJ zY2MY%%3oD#Qyknwm}`GW|3a*ryiCav(UP4$`cg%H(W4?gNjhF5Rw;4Aj}4yY5KbDV z4hk`%qqB0~&bf_;PeYB>{@M8Yxn^|mT*(Awc*=6DT(e*eOa8StH1t-5dAUm|3~^=I zF5$DHxxOJQTv>j~T7a85OIPBd+=qS6G5vi8S_~U8^+RTaE3x zlS@O(KwHA|FN(cR*`ciO8WGU(u%^2j59Tzk~O%k?0J-n)wmtu zL@auol|Q^v%!#njq4Tckw?15S)H%VZcem`zqj(I?#7Z2lt6>T5moef^b8XSZ%Eq)A z*_D0K0s?E9c4g5vXSJ$IqrbDVtzTk^lvOEx*tkoT z1=~ft5~FHf*%vA^GX}7seQm;N2FBq`8ow+t?BISSQ~un{H=vr6h9xc5LbN2U-+V@i zJC>VW?;XKz*7h)NKmYD%9aNly&iVCUr+qYY-jAKFEZy$P<~FR)T)YnHO=cW*T#cy6 zzkmCvUnu0xk5uy)(2{hC=JSg$T-m5R^%-!&qlUcJXVDqd`{8~ZTau(S36ff6K`ypA zK0=^jqLatDb3RX&oVbehJguy+`d%LQs+p69RSVn2^#h#`epsZ;ZM0vOPIqQlV$!hI zC`eC|cFxM7lzQgQ;sc`@@{W=tJxOZv@56+$&plYz&^ioz6nk1kl*+Csy{V^UOSaLvBKxV&M59y2!pf}oUD?_N`ve+|J`FSS%yaO9XO=ih?20o+CWZ5B2lf);-m>{h>RK_( zt?PFgOInQYWc+wZCwzVHIFMU9Hz>YUInW@2t(%aCVJ+lPMC2l_77|yZf8z@K3OSUd zW97Fhz1LJ{t4HT#C?U3s^du=X@~JZYbT0NXF@hByxl4a`$d9-D;3;?s_tNp*g}3Sj zS`_C+vZp5+D?d$9X3wq0GWN;Mumm|l8>8D)#&YFbXl3?(uaAI0t`JQtve{FW$)Bn* z&$qb*t|n&RsUJ!x#Xs~(&5=Wj>GzLUQl|@LX=|1e`U++lq2Fk|OS9UnpR*dnS}^zh zhM042rZV7CP4+%AtH2ek0620;XDsVxDNWoOuu{v?3kV#Kh^D<7&Cb!14{MoJnIR|W z=gq$QHRC*|Jx(I+aS8_*&QWWPXS0?y?r=O(gnrgmCC#?#>}%hg41G9SC5}g$an{{a zE|kf`ww|oY&_|)S!?{F~Qjz3mTpO@V%hL-tGjV?gR$>t1q^?}7a8>SJqn(DUZCs0* z2y1;!H-s9WQl?eS!<0M`8m{hfHHoWCNxF77P>H5pYQkMr#hoec)nGi*Zu?5RQOcB& z`{ko4yZq0N-rB{RTv;V9kul<7*0SOk=6@^lLT?(TEmo>z7{vZ{ zq>(Xxfwj#4Rs@OWkFAT9ppk>v-(k-bi~?fR2+$N;ipZZ@wT8#w(GZV26NZtzay%Wbv$`gkS*?=fhDcmrZ=lzoGVG`1R6-2)`_(f)U3-w z+3amz%lx}nuR0paOO>1?MvmURTy1@9XoteMt%{2 zElE<>6vxyIrK=zZqC2+UqbD8q<3n0{n)=vZRh>;2hWBL5C-_8^T$H1iOGWL* z3}1F2X;Cah~?dKvB)a74rDJJC2u_Zd3U zeTL_$atpp4XCG{d?xZ%}qejPWk-NW&(cmne&uBm|c=BcB%87z};+aqSi#+apN;O}i z@u;k2K)>gbb6o!GKI+gKs3hWujxh=}#o@~FkX#WTO0xxV4%WTcKV!C5-dsL`zg zyYFTwO{W!PNFC8|;!cR9RB2eTHw)!#0g(*uFmOb}2|pn!)18T0bZ6qq4l!zgXt+f{ zh*Yu9%@`>{9wwD*XF{F-YIB_S$%@VcbZfOj;y?1+t z)DaCQ{DfGQ{F-A{&tL%oHwPTJzNS}nbjxD*&s!D@Yr*>SH$>t5gTmkKkZh+e4`IkJ zN?VKG5I79ATun$9i5v>wp3cZ3#C}$$xG>lZ{#<{Tby&DN! zA$lmiT`Ej(mk!pgB!JGNFC8|Mo)+=&BE1NJRAEwvl>I{h=w}>gjmz;gK{aJ zu_qq>0s`(DaNM^^(uun76rXF1t>5a$uomvx=J~ zr&irrHL5QGN(E(g0r6G3ozWjq8!)~-ToY$N9*+Rvs^VxK4GPgoQQJl>F`FC z^WVCF=}+57jodnCc+p*-qA}) zQlkvR)gCwI$?Y3;W;jxjcl1OQXBerq zlwN?wm+j7Q?nB;jZl^pG^hU83y;1ypu8c4{qa5NXKw{!9`D^}n^1}Kxgf#>5j%yT2 zdiE?gYgw$S-0fgRVO@f}<2s057Snsq8}y#@fab$+^@67(J6OngZm(qJ@de7O6-gA!MGz{<7a$NP} zDwE{s86nT0H;OG^6%ck4$O*1wC24t$BCK(VP_}taPhm}s2yxw>Jx>ev?(=22+tMBa zSI9f=6C~+JNjsAQHz=9@_SbOFfqONSiEb`m>t%aKZxlDSau?#Fc*chNE4qQ5v|6rw ztOuLn8lWI`};bAR2ex zl9anZyi&q(Lrz_{oq)g{J;ny;-fOD}b@e~h*t`T!;base=@_w~Q5&16e*e*h`MCMp zkUH`%B1Wyfsy=_`V7)heRgn`!W9)=_cj6JX%H-5+{0^=m0^>;--I1hX^nP$9y&sHc zIT%KSkQ0=NPU23a*3NXT&#qPv##fCT5!e#lxf@nQ8&WILW z=tS{+Y3=%elC13W&-ijuh{IuQQIb4n*3&jjPs_f1$)jR46J-+Oe$t?}&D2!+>2$YI zULp31oM1Fkl3u)irOG+OSW@n9LR=IPV(c}1POx^bNg=js)_Ng^jJ#v4m-aa28)+Bg zQ?Oee`DBbPqf8iwrMQoWO^sT^S!hQwvW;t8T**q(_*ci(abrre=)&0+ z+WMW|EOLem!)P|5aqUYliznH%RW(wuVy^dOJW)WIuqB#t^wQxwF1NS6nm**eJVli4 ziQ}pUR|b;wG0kMPZl$vF{dqkE1g_^0{WG7;*Pr=h{>yAcIej>`i?cS#k(^JaE@g+Y za=K8~A&#}gdC<&LWag9cqYN~VH-=*^amHy#*^}Z<9=GNBC-T2MMU)YSTl6T049EG3 z@~ZiGux^xrCij{O|K(3KYhk-0!puN3>SqR;|1ujh2+p|P#`d~K}cQmz% zB{)7TG-bIVuHFR%Xzul|%N1<71uMaw7w*Vtu5DaKTl?=j`TX1z0s`$A(LeJob^0l} zfIv>r@@ZY-XVcyzFgY z+CQ?phBk`UhgK;`b!bHGp%F#7!c??y93ME+gj`{mjf7(@3vG^O+Ic1C3M;=MMp(CF zEsHDDV~{VQ5ta96t}tQ8g0(Eke`@gm$df9Jb1TyvW&0xN%%g07rsRLflWNvNJzH7%DBB+){*))xv<3@djynrM+5QOer#z`< zEsHC&e=M#dADY(wr#z`rLi{ODs#(iIm|C+ClyQ>~f69|;*0Q)VwPtZe88->>r#z`_yZ8>PFDue|b_(O<4$2&lck6sQpu(RI`@Fm1#>BS3f<&pYo)d zwJga^d$lD0>3#l`C)KQFY0VrHR`34waDU2^YSu!np*H`|JgNV+Yw91z{Gaornzbz6 zO&deMLY`sx|K>?GYgzqc+A;dBKj%p`Ygsxl#|rw#Kj%p`Ygq_WYZl_?T>Gaysb(#U zD^qJ0S3l?4Kjld^Ygv+;TC*fKXNf=ONi}Ps)~wz&XQDsnNi}tgT0@Wee`b6atORZB z&l%rMyF%NAoaDrnmG>MozMHm-<3mLJDdW32J}iVexuc;~-SALO4(t0;n;tM^X_;rWh`EcQ_ z1fnHr-HC5%q~uz`O2vQ(lq=w)(E#`Fn@l`&~7LJ&HHf5luHU%erVOUM`o%m8>S*p+|by zk|gyCb7;AwiMAOj{25Y5-VrTH!=6TIr+e*@AN718ukJnCIMlTwFPwg?@D>^G+|ur@ zWkzjva6XpT-<=@>`wH*uQ>GB_lv-SVe-?c>6T@2A(<0(M-5oq5xwCLRE5i~$cp;6n z=}p6}_S)gicWk{zpB3&1XTLqcxVpI-e;-rCAtLHt_R|VJbg-UN3n=)y+qcaW!&i&q zdkeO+rRq4vICLP2{}{SlmZY^CJ81`GRqoO*yZq?tB*WuVByaT3eLKEb7vH#Feo#tl zf3*M`l6QrSZ>RB2GPWd18@9M58eIYh2Pz58ngb~lm(V!jJ+^|60MM31|^+PMdQ z?Ax6aDrP3gnQx-8;A1sjaYq6D^p=Un^`+JMRqP8nO#b`Go zis$?hn24|N@isQSYMj+aYaAab&*~JZVhOg3EzymXw*9pjCAZvdiCsY8jc-KLor(HI zwBw14olKikuoC1-q|t`#Dv0cAV$T8!mY`jsy-|Kqp9ro0kfHM6{h74}+Hhl0Av+KH zu~;v=dyFC9t;DC#j@L171KrHL9H_O5xhm^#yfiGqTld%! znpjrD7xwWP+Zyva1@f`SpXs?S_cmO|hVpw=PLh>$PQ0X^`kIsV%owC$3BHiWmMEq_ zAV6E#bgArUR7^mGOGAx>PvJbwbL(&U09sYap^X`uk$vuxUBfpGNCVLndtF>YTR-il zT>48E4NFi5*b>Q6ajW{J))Tqfi`v2~Y$j}A z@M67ft5D;0|17*izTAe0*jB8dwz7d;4v%8mbGeD(qx?Mr+6~)IVpzs}33P%8!R_pX@m3R`?3-Lc#m^@MwKd5ceL0U`92@K(Q}^h~|xx!Tq& ztd)kf@U6c1@@3)WxoWE>d*vz~t%TS8_>LO6l_dM^i|VY3F5#zUbr4>Y$NadVdyYKk zC|=KQh=@v^+NzF;^KA{){`AJ=zxA#mU!S25+_lEB>TQkR-k9v(SWzuGG^HGpdw`G^ z2iCX-wnSM~>iMdp^Dmbjbz?PbH}L2U{Yaa0jw3DY2EHDmc;byz>hra_>`LdNgn0qqK@)Pl+~x51brYU$RWL6PVr1_lWnyvkgNnpDq0Cz4@HEx71BD~ zSZsSuBMSWzjwl>ybc#&A-GzMnR`TuW&(VLNU!lEPDKBluKVd9e+P_qsy>M1TuT3|w zm-=ao^K#ats+WRuIIdpAIjY67!djqbFbi0)R9Ii($^us$bZheIJ9T%iAXesBMuzK8 zT$kbskY3l&3c1L>9kPv9$hd336|%VAy-$0CbF?>@PJ08~Vd36DTU*Yi@M>}77P(+Jl^)ie!RC~ zPc^HBfh|c=inuA^VfzzRk9=JVw>qqovpx;8HS_MFb!$D& z5imuU@AhwKta>`e(I{#vdo-(|5$rP0u_fx3^7>>wlH;#bS8Oh6=}R82u^P6UKcR`E z%ND!6&AFxmntVyjDEZ*fTjAX@_tUUlq=zlhj(%UX+@|q{fqzU6k%RAp{>i0RVHLTU!cafu7?lbC+tad)I7->{Icv zI&n&EEui~tNB@@ziMOUR!{wj-j)VF7CPr4SX4qGrb>y!2+4;0nRlg-+TF#Yecd zj$EbQCA!6ik{ns;ACuD+Jg0VVRY#EA_VKRcYWq!zj$6#wk@AD1pLRVlSCO)W2&{co zF1TT_dv_Pb|R#6AV>dnnz2x;Lqjb(fWY|$+)oJk1vjGs%JGMquu2! ze0`T7y}@Af+XJp~xmd2YOVq6|!!#^GIa=*=<&`FRP&}(JA*!VGV0H5DRSVCuX;^Zx z9pyQ1kVk(JUGO&=Dc$n2`r(sRAG=M%cCp{EB|0}q;lW;c?^T-+4Q%(HvYvcz(L%aQ zy?npXm_MnW+J8$bwQtG(TA5HU`|3UJjy^+L3bV|>ymW5tTH0~P)`H~dU;U&KJbS3x zy>DO5_^{sI^6O`Nxg{+P9Ou}QBo%6uPmQW{$L3nooYj7<0B}|-zNcZL@4_fY#h_+H z<4wkNYDCy#Tg`Xz8kQg@*b-&_3La(hY2~_OxW}UCG*U zJfpRXw)^s$D&I&-q28(8Swo+JV-S4|&FAEO_L2AbLf!}c6?z{LG0)|Sts8mKYve`I zQ==CZePT9RVjbTeqm6yLu(V%B&h@>M^tC73>#ci7@Zid`bu$y+<2zNk>!MkD^?YL} zmtIyv93w=BMGZ^4sa3dJ(MkFbU&e!v#5T6p7h~Wi-w~r#nEcmH?04)pk*jpX)j6UuxAxUi zC?R@L5%HP0qA&Mq@pJ3#Kz>n!A|hq7T5;|@pjFMT}mUMT1T#~{v+wDuu6Od6&f*zc%8ktZ@zXav%a% z_ZUr}Xe}YW5+YmS@w;#(j4@qYYtt9<2=RdsiQ}&C!j&+_!m*{F`Y`1%dl#d%c)Eb6 z4iuRn8m?sRr6Q*8LR)HZ)Q{JSZ>rn(NIY?6LC(t8)93k{cR%RE(;9u>S-W0%Uq{RV`v^ieMOd`Yw) zv_wSH%$cl@amP39Kuuwk0`)|v;e@zJa#YONawlpEBU2(G4asqV5K}kbERFq+J&k&D zp1x}Iy=`sX_uC;@3wJ4~8~Oqm(J*b->@?hyAt&`Z^|G&=oWk*aQ%lkZouxWyEHOHj z#@;_8isl^AKWUh93_Z6%Ky1C_&gGy&dV^*K`SFVH9hV!uOnf)B4AC$p zH~ntksyj=gZqZ7RHm&-|i`FN*+S=3DiSr$54LvIDAW0urh(_kf?mLiQ+>?tD7Rxh~ zShXSqwT7b>TcRA;M8llbzB<~IJQJ@ObB86t6tmq4%Af3 z4^teW-wrDM%Qv9a#xIMZH@t*+O^9y)O?(i}_`{#YVe_;CM#Q zfV61`NquEnd-u|pO5;dHoui(9S;_M=x?m+3o5q;+FB*5oP7r)M#`iJuLQwUctf7DMBl`YJD3`;e)wyU~ZEp3!6c9JQy3#>!p?LQrd{b5Vm{#Fe>DthK$3 z;CDx5UFzsqewn6Ms!RE>erfaPd~S{?)0besht;^|_&dwi#7%u2JbRl&$Nej96LU4F z4!&f={O}O;`lxekiQa~jAdEpgV?o_e#ET@K zN{Gs9Tb9ALuzyfDk~D&7d?Cb+hevkd$iWeeXqs!&NZRr(G1~oQu4R!1#t|L?1=nji!>ikUHUm<95XuC+8zNkZTnB%-elUzH|%OLM4lkK<`bk7(4+mQ)6PAL>Ko%9@=^mK{?HJu>!{hpcy>C|12TnC_tCt@d#zxLRtQL7dXU|vt`M;N=^_SZu z-r#mYUTa--{o=^9zpZ43%qq_Yc?Qocdglv;`REo;97&-{V%_Vu-{#uE(-z6Y?|)apl+}w`r<9oSW7fI5Djb>xk7H~ zymnejwma^o`cFEUp@djVl%rHoCRVUdN?Yno(G0D92jA<6eVse;&a@i5nY7KZb^lv! z-m98qC3gZdv0kw$ZHy3;4&HFER?8D3S35W&uq8TuO@CIdly{GM^LTxM2I>P_lB9f> z+R5K`YwB%#JBHM842m@RH(jx>MyJebQTjR%jvSnkQ$*%+)K0U(p3B~XH;TRQ%O!&S*!y}TvNBr94vRb)mN@LwKuCQrE@F^((OjO7949KnleXzE?{H-j!-UF z7{agwwTUg!w;(>AQJP&`W_xvQ5W{xG`*8n74T-A_`kk=IBW0Dn`-U*o0k(_uC??Zl zm297{DN#9k2$qOFiakwp?N&t&iQAwynG+*;AGC0^e0uv@yfj-}V6ytXr9VSIh~5Cb z1npAGMzXEzvuZsn_{q2*zieZ7#{Y*;;c*FRNws?}5Uq#|h@ z)!I9F-dtn#u{%aNa8*lRK8ef6R?v5TFWz1(V=Y|oiin`J8Q2AnTH2j@H3Z2EtgXsd z4xg$Q%lFETwCP0Ay*%?sAE5QN7nHFr>^Bk7Vrn?6wXLZ3EaYI%aZ}#IJp( zq#_#FE^>%1(Vgv%;p}DDX?4XjSBAXfIzg0Ub5c=O!js+#?^k8)QRDBK-4chwlbyzb-R?T(DmcWfD@OVVIMr0(}h&3kO1 zinT5T*m?Yh(R$0ClXVesvxUqm+)S^fJ%3CLQ}v{OZj0#TK>5kMHWtEkXQQVjEr0^H4_wwnTSvY*knz zS5>{aCWVG280Ey4Naxj~nE#V|>YZnYRiuuRV~NeF;4wR2(wQ;?f$NMn#>FTb6&Jl4VE`pC%O6b|sMv^72 zzSE06yid3L3-?j6fSMC+@&y;-e_A?lQzUDa8;EAn%P zLiMQ6;{-n_B6>_}$Nc*+wc?{Af-foXvAvW>dhAp0A!^dY&w_`G z-Vw|Vml}HKt&jB+mrIflj?lj*-6T1D2+@@gp^rYRSb{zgN0<3^t`009v#c&itEtF| z&{yDt$r7KnW9QnGQWt(cD$qbQ(vu`l;wn?0A!<3|3aR6mN15oJWwYKa^Yv0{uTgzf z)B*Oi*t>bF_hxqwhNvDaBdLP+49uTSdKGj-!qN5y5=Ygc`cnwnq+J4N%sI*X`NbIrY^z zIYGt}Tt8q-bVF!qM>bfVr0y9yUsz?V>JiSTj$r!py1O0CGllVgKHBvx=`;t$sV{b7 zcMla-H&5OxS6^O{f4&o{cS;!Nz%>J|C1@Vp)Qx$~3sNuJRtT#lL?b=={ztKP>_R}S zT6&BkV+qQE^ypq+)_yF!d;v9eL_J|8gKJ-;N4dh*_hHNDbyCB=`Uxvbk1bVs(*-5< zDcxH;Qgx}yUGA6EyG3>+$xl!3&o0}8)EQ}t39ImH=Og%|)+O}IwW~Q0O<6VxF`f`v zenZ?`63HjF57Oss%-}#Y<$)a4n^nD8R~>V+p^R;z9O9b#KG7IOG*YK7CcECQ!4G=` z>LttHwIdA?vHM+L_T;gzS|(Q9P2kEKTcZ6(^Zx8){!;3e6#;U;jZu7HXfb`zHPw!_ za0N);^u80vB5B517ExJPCteJz$r~;V(2dTu?bs6Sqv{W21NVoj2fN&|VOzM$6cI6r zG!J@|QoVmv5_VoVqL3clvbYz=CKoHA`p++A!xE$+j={>>K>8Y6pn7xHO&j(Pa)`Y^ zd21haV<%7etN-pq@v~1%}nwP6;k9?Ie7;3 z2Ds|S@lUU|CWYD#OdiDMjZUM!tCru<*2JG*uauY-UT=_v0ugLx_@us7?qh z!FJ96R!fr9j<}lopc?bul3O!N7MCo@%bf70yHWprUBmg``hpYf)shkU2w~Q;O0ZpQ ziB16s5wImU8~vb~lg5tbPaJdNxwBpCn+9e}zrLbWoe(~Rm`n&P!FJ96R!j87LPFS- z{c=c^E>0RVyaqbnKW*rwff@gQeP=X|5Y$gH^_P=|Rf6rB|E-qjW!NtSgAxu1ZgTtU ziwFk^QG#fcA)WkQ%lbZ&h^R>j>RD5A0b!z(b>pP*>nj+h2J;YNdNKlQSzkecKBU-E zLqeE3H|b!z=Ko~NaF__|izt*gitK7IAxb49uoixG;}^o~mnF*BuK7QCtT<^{-|3(j z8F3Xx{gjvb>-Spt^@v}HR)k0%Q3Aq5TO-Pp41kJzDi; zB1GA2cJ{Efr)Ji&#vr0iM3cg0c%zP|2$6>nRGWonvpW&iI6$G&d1H$oXDqQHAWvr16-z zGGzfygz*712w}=mhH5_`l!>tH3eg}3Av_2{GMK&lKRUP2CL+17XqDkbh!E1?l(S#y z!ul`EF#lVYXd;sJL5Q|x6me{@UriYCKui%(`dMCseJQ+!-+`Nl!0gyv1RElNBZ&R+oeuKBhl}gEmhW9 zPQ=L*6Ir8QoM^obJ zF7+31BG?kpAcWah%Sm#xzf453v`$2FFF0u=%aKeY4b?XL%S2e#fM}COa$k|oO&ZsU zqZY)OS+mQ2L_oGEzlnlz;Id4yPcJO#T{{IC;YSp%X? z#6RsHJL=^eMu;VZI8*$vJpXtK&8%fvgZbY=J83l694DvmN~V!Sh$Tb^YB>PSO+??oj-OQKP+00s2 zkDC82w3Eiqz9K~2m-g(^x=XT_qm=?By7}MI!N6TrdC{Ru9OhkKx))A}!|9L6b9Wa~ zfw~i6>A*xRika`InR+3`mQ2KjL+fSl(<7XS`N_SAXcIBI<^)Ic?b&rYX&^-2(<9{5 zht@k0$-VfKMl#w&WZK)#(I=ldf0#6=efccWamw+tmc#sS>A*yMh%D^bJA61vZX(Ru zxd{cFI1$MlI)Fwp;uuLje|MpuG?IG}(I5vQOgXMo?;gt0%4XKGder=%+*eK-$$dp9 zKM(rHvBzGrJRtN)g4veUi{^hz2V-y4<@+D3vj5bFiRj~7LcXj`SAaUbx%-7S5nFmJ zvtNrEL$_ld5@K>*FZp|qCr*Ubi-|{Nme)%)YbE!hlZJ&h z5pTkV*e6{qO9+#ztJ-uMappt}FQeJdOr7RLSZEXR)+@sPqIs)iME}qu;SarJC&KiW zG23T55f<7+T*&BZ{~RBmj4=C&`pbzZySzuDMZ-dy2=o8cZNrlhW<(GC-_ym$|dD{cAtTiVM3vD8j^^uG)Yp3k_ z#AYIrN2e2Ep-n`x&Xc)HwnQhwvT8(|h-AA;MwtC%>fNkmS-AP%LYs(W+hufTLXT(7 zKD(;7d;X>1o*ZM=CSqpx(8QnC-s4$3+fpuz8d|xhVwQ~glsnP1YOIB5x<|Goo;8e1 zrN$mU>O@4|ysw#7jc75lJ^Al=R`0Nzx}nWq3YK7e*F;+_(HEx(vE`7Py0P6~Lev?f z!y=+Z+c-9^)l;P`eXqeRNwzpAS5~`X)cIy?94oizwc^!1n-B{(d)KmjY>6_yFQxpb zAG)dY`p2qR3!{!0jig&)gxE)j8Utd57&1mYu_Zc7?bn$dI+RoWxMZ)BhBfZ6mKZ}0 ztlfbH`F>O?zB(yHwoNZuH234gcI`gtCfaI=cJzfiuniZ!DBW9}5)c^QMKpcMj1XSu zzbM5BfweFKEg~9d5$qhDpFc_GrC|x472%5^x-UAU0ZW;^irVn0Bp@(ujPYd3j5j8l z4S&YeFYR44EI}Gbo3aSD@no5L9|@mVrnazpHCF(pFQN6P@G?-6didpJbyt2*==mkm zx%RPY;Y%cZp+p(2cNM3+?dOzP4ax`zeBp#IpXlp#MC1C3?+Lw$29_WV>2qSb{W6w8brDnreC^+^5QVxl=$7 zVegD@@bCp6-6N|NEq7~?Ro=0opMb!3clc_LBEqNV*rM*XmwPSkFTB)48s?7G+P9Nk z8b2e|rY@!||>f-eIE*O%GPfYjb#gn8hpBBhRl5Fz# zqOrm)J*0uODFfy)RSt@MQ~vyvu1*@sqm$#UFub?;6EU&(|00lgMANrxKDe{i`QLt2j`zs$b}RX-l=OAgq!!As^^F9s@Mb2W$tQOAWZzO|E5Cxi1db)(Ii2wU zOFqikKR%jWeaqBTty~z)6Arw+gYkX3Nghy{-7KprjcWP`2)x~fx87)v)3+uom#>Jr z<6$P@J{;Z`M%t7gu1+1czFT?qXbo54RxxrVB1RHdBg?5u-QT#vd$!0SWf!~Njin>5 zx-47aT<=;dZ#)aZQ$WgSZEMON+^wU|(O)=scgZUY2cDQ9n!Y+sh_korsIL=61fHHC zn%b-OFGj?z4L8}Qx0p-fxP1>5Zyy2#2Z5F zBLtS%U`nLzM_#r9P20g}wxA(i8I6CjWRp$TX z{Riz>1}rGWO2(_U+}BGBt0i;PS~0|FZM=Eh^iB4smAq)pP+?{Wt5tllElu-M8kRgS z>dn)in_$2G*~@@2Pl$}2!r19&ZgRh*qD~rCySL{1@PX@!Ij#-xFt8T74j!Mlu3`A2bJU*KJQ}ek}be)^9dY#(BpZ8(26YJ=1#^Rj;eCwLV zi3RK~#MOymHQB|%1=KdRG7E^9TfV%+b16{G_zfz`^oIa#tl9^xZmW&c4xC1B8?vpOR!>v z_bBlzLIoPQdc~ILe&UwW?991SO12@Tgsc&$XV-k*yn@d#ZEe$>)VtE0Fg7k%vGC$S zL4sXvE9lLK&7JuF82jqDs+#BjgCYuIA)pvY85n>dio)H!XBEZ34p1?%u`w~g?vBUq zeiU0&?m71!yIUU{v3TrmAAhs=vO4F9&-cea+}G>OduL{2c6WAWm$su5WEIm2rcSeS~==cM#b9Vy3%VtXizV@YGUE^fe(-Cc6TlfLsKZ#TE*^>L2I^?Lv)(kZpL)tz9M4=76 z=-8M!2A9o;72Ov@HI`TVWOQDaY29;*l3*WowFmY6n)Beij_0jBM7da7T}jew(v=>p zHMX9zv3= z&sCZ43@3Tx!h0OiJ%M)Y|HaU%@&N^ZiECe#RS2yhm#A>ps)yh$N#iH=pgSJdC(|43 zQ!o{liu3!0ur%mSEoohevUHDv<>f6XJhys8&eSkkAax?iIPR;nKD@UJ-}}_vK5W?O zX7ae5d7-ygh1?}abt-W%dsz{Js{18h7P_{hJmf(hO^=wCOsP+v#bjWgB05CQ40yeK z>ri<}@f;dPLwrfDNV@#mA@VLGhYo@Dcx|r0{Priy6HdH=+8x$Cl8!lgnauz2LBU^M z&h%%c2PMllbA7R%QwV9{=9V5c>E^VZq*1xNDyG6x;aY$--0T+guFoVgztKkpOER%v z0BhbiN&e>l)Pi|Kl*P_inlCnq^r-hjhbVm|kj2qN`LB{xlzoeUis zvP_$Hr5uJSI3?R?iqzTEI3@YrXGrK2j1AQf*sx30*9AAjW4KsGu( zQGRsm@!t@?zwbidS6e{BM{XdvEG!k)55~vkUi7Tg*f4C=5vx?$qt@!>6n@y|q19NG z<@bzVoF0Hw9qRX_6M8L;$Z|hR@Rysls<3I}GH9D#Z>?xik|ecu?nT=T{cQN%(PHHx z%EdK`OM>&-&YkJIO2Nv})azD+SiMG#3S#A(Pgl>R{E&m8HMeB#QZKLJZ(8J>--A9q z(c0veeolwr+6qY^eUZiVpGHrAc@KJ2hZg*EWna_4iRTIaav*OAyVRiq-MsFjRS&@% zUMx)PMk@}on9^EbA(#qF#rge0-1=ID-hQ#&^lE1aMKhT$JFmulPgZYab@Tp9ML>@m zgR9dfp4CmkZb1}(33^bHxxa2l-`)23+gWO!qSfhNXC9lJ1_$Ue4g*Sgu^B1j%$0Yz zFp4pY?z_PX62?n}QVlxL|=hnRgH z@pm(xyELOkI@&35A^9l&^2fk3tiXmP=Dp9It>>JApCla!Y)G3w4per86{465OM)eY zD7{jVbc11#axK0H#Z*{xeS0K+u1k29vx-wt^&-!xCQiCi(3 zA-rF8eGvk0u_^}psZ}Wc!h2=*YWZ*dYHO=7nm_d~LtZUFho})+ik)_V+bDLsSrGy) zN&CCBq!(6?Cyma&*V(JH?JKetvB~nP$FJo4R|43H*Tdwh<)6S9>@ho%-mQ>9a`-&6 zp73VR6YRtff9A3;Sss`2Nyccn*WgJQ4IMp^l$_~n)m$L39&cZGvo4qF$bqJOp!wAE z)#;gnlgZ^!ABw+x_VQz$PR7dtgqHbI!c%1C3u~P*CnWSEs~T` zrx%U>`pr;!nW{)=<&9UeNJ2ntOzA#x1?=MhgxyFwd&fu9>jH`a`!6sR|1CT(V0~65(OyFynx2k# zBiO5gsrc_-XWKQw?~@1oKK9`E!Tu!d_u(}yyj1Y^z{>=By0fd&rPMB6)IFx+zkjV6 z62Yrxf3K+$3Vt~3o5Wr<)E+Wq*K8?E+ulq!t(J_s99}#-qxJw>(i42I4Z!!>34E{E z^NW42==1~-PfwaiTI44~!vno^S=g9L?{ywCU>+%3*o&;(+h3QxjJ?^|%PmRM=5ICi z1`oa4>mlmjPZzR1^txDHI7?l>o+tqYNWQLpReXYh%GJfK!8~}^Oa^t$OA5{Isk;*p zp8_GBpzjuhGp|W-=2aEWyzn_7J|)v5-o;b;V8M06qKjo!d;*F+1*ipKMEStU=wY`y zN&uXU;uBYVGO9;J9`8;IEH{{{r(e=#*Wi<5)W?8_1DsTQed?oVaJG%l$?@5?9+A?2 z2+i7>FI=uUR>9};7>&k?8FpUlN6>q2`IT`I8+G|OI3|E2L=1u?aev}S@F(`{KRKO$ z5pfIrx9}(GEkpBLqpAO=T!#K0)5AHHhy>!lMVv&}uFb9Uhb=;gBQmyrj%a+XVFae) zzeOy@KM@nVU5(f>Zmks|s5nBzd;Al@sW}Q$@!uk*=>VaLDaw2Fg-I{DnZ2&!VcEuz zw&sG0BZRH}Cj#mzUDU3i;t1h^{wLzr*3aoJvRhD4afFyl{)vEkGIh%CC4!10M8En^ z#6e7jc&PtGKxVBi01fv-`xhaI}Yj#Q}N#-0!EME zZJynNR)nD92ocxyPegVvvBvudDvrqRG5;b}c2Be-1Qkb!_%uBa-b=E3yHzSd#StO~ z?w^S45oJXPDvl6wcK<|Vk6J52P;rEa<@+Zh+cH=Yf{G(Vyx>0(+1AI}O9T~12uq|# z@W?YBlav0t`WwM2+$dna;@ z2U>73#H4Z_xVH;5NBr_rbE$ZHL%Ul?E$;0C%@HD^)uzV)sM!ZlUz`W-?E=jazap18 z58mF;?$!|{#so%lgox|4MPOfp7-3I{5k_CEr>|m6@U@SK9flk%h$`lB$m1an8F9CI z>%^Gg2oYgyi*-KBBcmbKnIlB6#%PYnj);eT#Uqz}fci9`IF;zt7;WW|9cOJr_yGd= zD2U3s+Y)WS5#mI^hByJ`1ImgJwTRJ(2edhl***)JPlniYP9Zl8YS$m) z+c}k}QH-|o&}9$s3zkJEqMXSmhxBWe+&IYLC>!wcOI zr~ez|0z89U04o)WRu^cF5IF*pv=R^xfqE98I70ZsF`6TOWpi*IuK@vktf#Ly>Rz+~ zNBlaQ;8_rJp#1xgH^Ivl`4NbR^)y3dMA$ME;z08ceTG{RBK{wvksi<<%YX;ZPzZk3X4{~KVLewHgbA-sDv1Pt22I@S3;#9(WhS3}$@^oxGx`ISJ!-i7{ z9~nk-gvjQx>G2%2wgc@s6}Oz+BZSc$A@YrEb;aw+9&(oum4?vP{U9&N7N5v7k-CFa zcOgHDQ;FVy(TE4^2YHsze9#wII8!#H_0SL~+3F>JPpju0({(MS(K@XX0>pu>E~8Rb->r7)T! zL@ueVJ*q$p_JX`rP9<6mqd7w4rT@xUUktggILDR$7WuUZ0rOysIhDw3=D$UTG)MeuL6qrj zMTl%`ju3I393di4;XVN15opW8)@6Dl9vb2S?ZI>Pc}_LxVnv9|bdJc@!-^1@x{&po zogrQ2Z&~piA#(LOk6$gwvzN2;oprhT9Fg4~)-2;+Er_z0t%&TrW-~{K>}Ag5*QmXA zq%ECwm3NDHjX& zAy`9<#=POZqG}1W;MWzVad3Ag)&rxrrj}(>`wx|~7V*>YLygD$$B2*YzW7=h#zxUWd{Cohq_3Jx0rWTsdO@pvrWD!y@I?!?HASLI6vh1ebR^ zK9#W~7r$0yr>YN=M`pbMgx8PCG}nxU%B4+ZDW<~O>JgPD)})2s6;}E=ds8egMq}QR zRB=`#I{&jVV%B*#isi*J5?}2&N=^)j3wFKGJp;5H%NX^@hR{KkV9yx^?OYBVnZqBjuE&d z=!xdqw9c&ZhA}_9=+vVDY~O{Ua^49~WQ>m49KGGt8t0OIO zHHcl#(MRrc;h`@62A`5j(uAny)Y!iwsnRD8#a}Q#ToRnC-Tgw|Py1~8@~JJowL6$? zOKBw^os}tL+1-PJSb}#ix#Kx5RlV_E)PC5X>3`I%L$SOVflHF4;ED$NbopFE`p618 zJutehV+cE0Ek=Ij!y}#Q(`Gb(W&mk+)sf;jA{<|&*JHkW5^31{(ULoE8}81jM(;s1X3r-v^1GS$WQ>lA4rMGjL|!>B1El&k zzX=`YR+c2ZcBVKI4A%lK32x;&|Hv@d$BR4(PNI9dhO)T@9vIs@Ka#N|QFW@Y)Dgk* z_zL%cM@dhO6!t7dqzOGJ=8h4#BnW%mRFd{T>Pc29k@VcYP}X)xhT^XaVcvfXs zw%<1{xWePePR*`MM?Ne}nk0DW5S7eT*}JC&fA3P)+- zQ*ueleLh7=+rOXmn$?9~x>K1M*MFxscfFIb?DwOquvO%u@nVg~Al2BUMoR3aRC51x zPhDLZw^v~u9^E%CRUgWF#QL(nB*A$ZSryigVhu45%v+M?ca!Lfubq~ zt2&(-_rox&a3zYVaHN|aF=LRs`Yt#R-S1dJr@3|_kmX$1jqdC8Q6AR}Zgm~f+0;Ao zD@fJtg`c{6iW5B*<3#b74c9BNGKuxn{y8P4*Sw)rM47NE2hDmEL$QXK3Zo%rV&+ED zFM1y-vaP*N4~*_{Er6AI-dtUmz}G%?R6Fb z%pJ?FM_ehjkmPlJNTNMsX!3{X5`G&byq;Ybz8(LnK(m>(_)qCW=&sjZ%c(Y(vL z7_hup^FJT@vJS4(&65duE~L0#;i_q6C3^8fiV1&-zT?Y0Jg1q@-p%{Bx_W6Ct90nm zlKyb|NU(;OA4Wr_-h!#5hMzZWUb}`)bBvy!<;SYLpK2by%Ne9vyEvHM2oEN$vnuQ3 z`cS=5GnkH_+?ZhQSav<)z}sDqhf)vDC3`h5kE z%r9e>dFVDCHCbu#iuCG{qiL^N^G%pLmR*lw&Kj~h(vKY;vCurQN&$w^ zyPtY9hn%y_YX=tu9_5!u(Q}KF$j5vxIz2GjcaINiTy23lZ{0$GSUmZ#(!Y8++8S~* ze*EUizV4W54)HF;q7If~`+u8k_6#rdH$Af481ed}3tf_YO2OQ*>=-Rcshca&>4(GV z{FMO)%pIfc9(b|qZj;SD-gBv*?P*P`$95z+3ce;dS{27~;*#Kvkw?9iL{Dexb~#$@ zKD#7))MkV^?7-3g6P!6-YVvfWyfgPL4ImN#~g8{ z^=Eo3&nJ4bV_j#Mw|sJ87=7t&DRy*qqWR+3!l1{M;SlQ_RFaf&K230(F4hT`1QGE! zZ<%&p(nx2oUTWz-OR@unE14CGt4@!_9-!aW7UqwqIgg6nJe4_%Qpv2K-YS+C*Mc6= z?ePb4(e*aj=Ur39@?tdRElGy3?)1){4P;HTiOS8vUhL`bBh1CtyE2T<{o0fH778%G z7~=*~MZNA#M-^CN2)&&~aNIPm1zZxW;d0I*b<|>{|DpkEd^>n0YeGlrxWJvg=?gL2 zCpywDkKLJGs>7v=(0Uj0kw(+&tC%~c!f1F0YephXIb|{Qi=U}XZ&Hely%}t-v(uen z^q>l!tW4vMbfUr|e%GJqLkEO5ix@I6jo>&-tP?H?Zh_i*jMNLeX&UX_Qys2(vSD-2 z8|z+n)#-IwR6MQUI>^xP;zNR?yfHd#ektabOOgX~ z^15<~txelk+o`lDo?FE}JuJy(S1(pmE+&tA!)Jrs#VXU}-wr8VZNakS-teTKI+zw7*oI8IxS*xbA`of1Kg0H0$tUF&iBY1kf+Wd1_6|cPU{sZd-@3EYYqUCoa zljw?tDCUmW)HrWSl8g^Olbi8PsPpqB1arq|yt9y`u=dZ>TY!~|Qx2K1R2YqSFYwCP zUpdvMtHWuns`nL)z`G*6zk<3-t4^PF>q|oRmDcUm&nqWyV8t*2-UbXd9z2NP>CS<6B5qOu1_q#A^zXj5}zt5E-2wX#ED1*A-96kL9WAS`+{@Bh zYewq)3|Mwt63hl(p)~!}cf91;yO4?0UqWAXRAx zqbhZoH^u%7jK&@vI6q(Et+sz!mJYgjiC_fw6k(qeWK_k6(rE+jNb&uZbsjG)3Dya+ z$rGoNiRX?J<#`94Hwq*493n@y zc3cvyUhN|2>(g%xLtHCR>}kY)SnU0jq}#98k+T=Kk-RrM>b!$kc0Ho#86V|BlQ$&c zT%68liDk!LRmeE>Ev|Mc@P>RnR2c2 zfri@<`!u9YoC_20yDk)a`|()_K7o*=`1?P|BDp+CTpFwM&|}&42q~--$%-vU^0ytP zI|ab9E=wVt{&FDyGgX@YghtzzWWyadx!xNQ@kZDF18 zDG=1|?k2R>nbM^DEoa@?9hL;2O~LJZe}vLaP3s#1Od+~cGK|ol-9-&9L`|*7n__-6 z(VfI$+3{H++}F3}47m!oSzSETh2qmme0GOVrRoe?D(`7-ifQ>LYqEGRzCk#hvM^P ztP?(0g|`~lwV;hwl_z=nIOtBpu_Rb0@N(8~M7M--{zt~;s52>ofeoXMyLw}t*W z!dn*yfMv(0?{JUTUAUbxZHeOYs4T_j{a7b_G7cUuyH?bc?oTE)vDfK=&**W~0=y*z zZ_$m2C~F&gmVEu55S;iXC1^&Gmm3@kg&oQ6GTVn@1ZXZ3W)VQ&cLj%CNOCgAIX6SfAY z!j&$At`W=~qj5Y7L@qnGqqTPIR1B;35FCYq(Ku!XJYF?p>BjoS$ix$N6m!S28|i^aic9Qy-zy`=P|S-WZ~YVO~3@jh5~9A5+{4YPVuFVB6--0fim zM>OFGA-x{+65G+z2W}e@BR&!wXN5g1*b^d2Ynt|_rM>f;yxwfm#YSP-^@u;aL5#uX zDCO(7f&@oUVcD_o1kMK+_N1NOpH`Oa>=}lm+i=7dE(vZB7`L9(&-d9h-KC#8X@-Zf&hByFj8Te*@sfwVl{R)@g# zqu)Cl0v*+!x3`lyVUfC18O#IohRov366*Ty&&i;(zAEO9bJ{lQghKH!y1F2 zdcEnZ?i3lXmf^P0z_#kcg*o6>J=le1*Dgnh-@K;r87st7Z?C7`xK@OI8Rw?pFZjGx zpm|9URs1GUb=>!i>`N#>g}f<;vShs8#cM`5E3zx6o@;ZG^qlOcL*R1pX+NxxTZXBB zKF&e=m48L>7t90mmZb2Og_V=%j~kx5kD#K*?Hm3;##DG!3olMBzNO?Sw1<>~J3#Rl zyiUX=Nzz$kWhJ<#BPo7z7{ye0MW#pG+~`Pibef}#cdk!`WjK2Nm5kR6c;1DVVk_Ju zeeVxcmTZgDA#k~PH3+XYCpRLw;Wgy-J%;PniFkd5c|$Dc`QxOKN|k{#x>8JqrP3n; zYImmT`5r6AYWofN3%2dp=7TL6SdMnPnx+I)^w;TuR~&fO2HXCT(J!;FC}A(Z6Z{3w ziI_LUQ*UTVJFa@DSOzcG&74>&J)*1+rJH)CE3fY6Q{}Ut<+R+rAuHWp7we2IDnyv3 z#?aFBpDE{aOj0lc&kWd;4kr!G+tdErKPmOoIv6kl*AJdc;JkKcI~q~sgCdX1G~q9p z2QCTx4BeX02^XFzZHlMreELFLKKtkqNdZmi(tJ;pB1Kbmvood=Xx>95DIHoc$F($N zR0V(CdKb5#9x-vC6WP`~$u!)5q;BVh`z!9paNp9|!fK&5JIN*|gKqDP$0HuWl62`~ zv})M(fy^-N&_&i@D}n6_>}v})R~Oa%Mq(2u>Ebf5wG#+#A0=sTIalTB=Oc#7MMvm7 z!a@>0mk2%hj0&FZQg?{&)KSXCU2!^}KBf|N#oGoVGmG`7ufiXg#&lS%>sOcx;>}pf z?K$Qep&T)Ik2_VWnG74}Me9}on8%k8N46~>-TY?-F4d3Znud8*&ylEOJ#_Oq)}vU5 z!fa9br{>)r{6ukz&rPM>(@J#kf}*;45ZBMeoWU$pjX_3YcO#U5L6HJB2hsVIrGM&cX zN#T+Gbtgp8R&sIr<6K?^e-Y*KR$KN+V$nWJ%+nk4SR9X~-gGSZ;NJb%u3#!5J8!i~ zUXHA!x5YgAByW$E-%gP!rJK{FS|=1tCF+N_T6B^N%hU3iIV+RLmw2+;#IEN6x~KhE z1yhMO;H?(7peQ?9%ii)PiMQag%twZhcB8BNHFMOseOWADxni^HKBQqURi($gSzs7y7IHzK`@o5H{NQZ zb{}=(QIn;|N6~kzIBkC>FTqr}ZEi<@l{3AjWw&4gv|v?eLHBcc3I2l1#U()u3rLj$ zQUysn2&TfaV`(935?XK`XuhP@34*C`{oopb*#KJbJ=E^a_G1aA!fk+SUDtxim`eQS z?JN+sQTqm3@E!12-EORcsRTdXmxNR{%PeIu4%9XE86QA+?B#t+hFaCm z5l@&6FqP1Wx0=x0Hml{`>rQXUCW9NyIG9S*8*epHyS7>FI9O48u%gF1uGU#N+&0*v zO492eKgg|JanwbASmoN}ysT-h)7H_6+aLEHNjeUQM}Wv%yLJ`)1@}r^68M%RiCzFi zTI#Mnmn$j@fdhG)vmo8Qwg28 z9n>S<0OBSf3d;|7V=7Ts+z#pyc|ea#fEYaH_8v@yN7R2JLNS#<^HHluO#NDq63ZAR z$Lf5vLaZlyePXjQf0~=N`<550=j<=%-cmsOk=u*49#LHW!>OPKd$sc|Xx@l%itqeS z1XIl!26wARl#|Pp_&Z|jlA&~Tjq=KZut3rwmpAh)TVD2$E~w*ydBfW0dlL188_e2| zsh|vf;RSD^R*(Z<6x1-f{0UF??9>+HiAnrj%WiUex*%$-p>wBC3cd>--|~)20$;`t z7ux52NoC@dXzJkP$qWxB8P_y&*RUkp=a*#dT5mRb1-b!`CTBX*cc*hG#?UN+xnl$_ z3Ht7=(e$g<+f<|EjqsXhJXzs#TaA|n7SS+z{S;4jVa;UY7QZ6ENYyf<3dU@wtA9LJLjh95#_tIq5fNrrrRCKNwK_`2j&fDce_W^SMvkXcbB7v zISV{li(ONUt|f|U7@e<)Co8zWuR6X2*ZkmS9Wc`>HESxoc}2OR^fN zG3M#F3Ttbc!aD?^EzMU>76z%lgybO=?v5j4?j}aLrGuvDimvo z5x69XhnqKq?sX_bF7J*aSPzVD+Orh9bHAmz`*>H7s&MTDI(Np(h&h)JD_C2Mo&gcx zyK2Un8|>h1UfI-KndbEeF+J=^L-Lhm+s3ppm%Lb5Tb#?2O;|C}ye_Ycwy#Dhc7Nj- z^Y#2Lfbc){jzm9jrd~AyDdvu4*CU+Ucc!6nS4gj@+5~gQ=qjDO*yhAB=G{j)kIUY@ z=)rlX46i>OQt&=+HN_S7jsv&Pk-^^*%Km^(&q zYUjgtl$&jixm5t9y56oi?Rcp_={wm@#jix*7ZGqta68NZXLaYW2zv0wNfLb2o29S# z&HUt?vt}CV!|KM&HcyzGPp1?3mUizj{gz`iwan}ofw^PZF&c6Ka%Ymcrp7ehq$(j* zeOcS_3(XT371S{L%w%8oOr2$}+&(|(QLS1n+Gg1(GJ0_logNr{JjsvkE3weL?gdAr z{~4$rd0m;Nbc!LEJJxB-Jzo}HVTRd{IRWB$ysw%SM`=cE1i@b>?)PKof+m_*W;p3; z0baW)m8>*q-;Yi{(qF;yVtyD6CvjsJlF3PoJ`Z7wzdnLr55Xl#(mJOAHTFjsZJYYTbhTwU*7R~IhSB~zby(T~3w)ng~huwlN_&6y6)8b&YrXS0zy@MZ!OjdmjrP#M;fT%VY%t$d$SeH9qW|SKY)E+GSd*y z?W;wSHjVdE?TqktU+517e+jr0#A>vjO|$NNwBVB9U9#R5rQeKV5T_QRVtFwYMuV60 zLIkP*?I{^vqn*0cz5@GpsDU}qOD%r3)t?==lA+k+?+UNIR zHZVDvmizS4g5UqZ?}9+2EUQ9Gw6PLKI%tB*md+#f0_#n&Aplec$MvAh`l(Iu4CyK~6cAu0E-hfcjpQ!{(`l|CBbQ5aI*67{&?cNx{q38LMU^c_{I2q`vVJ>eeMv@yv9Xi z{#+uOPDQRld=<YM)$q<0ns6UaV2n>LTdJ5lMqm6bludnIUiLbj0f;5>(X`$%S8^%TRXy)il}#yC zL9S3V!-C&t!S`XqUEVwE(uGf4NuSCdD*l4`;gVpNI^dGQtuHkliXEk5d9k)rONOvo zw`kOAijC!hjeFoqD4m&Snb2@2j1#)Lf9uo!{l5qUVu~$R#&AbcCA!KclJ^-6|NsW zV$9>(G}^^mIpSPG#TsHX<_$Oe4Q)cR>dp=C;9pp$IYyf;6HUQq^^rvZ}~h<+)o~Hl8KQ?$hlwED4+D z&-%tB$#Q?rqhC@N`oxPU-}9YSFn5f=CBb`;J37&tme_Rp*mLFKT7UK}d9>{D`LhM1 zGmDmG?t2EwSC81i`l>^d7`pm_FS)%khl*ck!ml>rlHjfvm)`W{&OJ)Nz??cg9(*su zt~?tcH*098b=X*%1!Q)Y+kVdpJPtkYP8+3OR9vRTnDCcj@HWTchH>(dbGbFW9^dEm zr=yR?Dt;jg*8(m{l6>cNBC{VkskH_)qS)hwCAojnhe^o|W#{LPz$4nH z7hRzpR@D270aGn_@5{P)w3VH@=hpOy0fyn!w|k_rtVOB`%Zt&NH@pS0cp%NY-N!W6 zWvODx@5e|$2l?~7JQ_x0e;Gs$^y)yvOCB)f%X+Qzs^K>+@LLzqch7gA-govIax8hJ z;4he;-m4a$(1ETjbHMQFp`Hi!!(o1Ku9mYc9X9H_A^hui9S__#m>)QGR}G`XGw+xz zry>=sA(ljsn2={69c^Bql(u9Ta4ljqt~Yq)7~XyD5Or0FdUAo_mcm|6ToRlrR%lDV z_L9iH8sBw25lez~f|)b2FFpVJR?~@7+ZD_mBlJD7ly`r6{qS6+*26#r_Y922Js;jH zD$R`H-`9L>n zF#?w)N!v&l>X@9OR33X!XG^f`*mi+e&D@&4&6laP_nM|)Yl*E7wi1x-G!Sm(+UP^% zGJ4yNCBfDXdSa0_H0Rnw>Bs8WtC%}R=xuw;R;_4S@21M{&XS6)Ge+aN1Y$q#*QfUn zYl>6qD+SM9SSMT(#1y@0L3hG~Ayw(5_*F{L?p`WhO<^K(rjEL` z4}L2LuY=&lkVUm=wXOk%auvLF>k=%x9^v~cnC>aK%T#=KsBZ0pWyk9|u+#y?Xk?!@ z%GF!7RJ=mMYahI3gxuG{&1htY08-q~Nw-eKdf-(p+$VE1oYrPb4BMVm)U8Fa?0D@9 zw|HDFN$WRAO}86fSGV59vg7qN>?U5nBU}D>W$JjWor+h*Sa!UI2VY-m6B_%dG--a% zS+{P-vg2KbB(-lCNJ~t6WoYXerrR4}+3{Wkd>QNPsd8bGfz)lS+kar$@qP#5OF}o3 z$GOhen9;AlZs&z}EP6eP#zfHxAw@{;i^X*NLHwc;-W!5cFFdII>C)t5!zkTe4a=@a zeEYhKl-XF07@zgh?I5x2c#jKv&fW_R#;PUB2zi8x_nCMvWP zyM~Hxdq~s;y-x)EFRsdUzjl&xD;=T*br zNbF&Q`!YUnCw~+tnYp?M9bBL3yqp-J_r0FZNLD&c zi>8m7I;q$fie<;XUhq?&h*bMb^q~*OY&?Md#y5TZ*pYS?oNcfGu?M)yBy zO`>}E>wMu@66_s@RmR%Qq{|5dEndn^#oRGM?+ZV;t(MZb?Eu=T%{T>1h0)meE=eO! zmr;{m8|aOr-nvr&tOqVhlJYx7(yl(k$ob+$bb4S9JwAJZGsvn>NUOOGY0vtq?%V*& zj!!ngQfrB(t>Z`2fDsKN@aY1U9iN`SxpPKg)%{Ub8eHZi!6z~JYzm)+z)Ge~a~iq1 zKdC;?PQ__ zQWeY{%Z|@j!E3O#9UVL=lN@pEKrnZV#wW3obZgNc#Ng;cgQ{1dSQ3oJr@gTMXi-SH z((@H@cWbXh;8SFL9u4dEdVT4^OSuhBW%nqUJC+@vc|+`A?tawUH;UY!TH zCCN0-iFS*gMy5}$uRGPpXngt(>#K6BOx|hEdn2MGuxujw6^mmR*lHY7C&|3Y9W1|K_{a<49Jz}ztc zmn2EVr479t^wHG)w4{qj!Dt*a1NXf)&Ov7v3R2RtT2UOOgJW25bc!SuzuSd+RjX=v z5R{?weqc#(lnq$81Ec8PH>XUSoM#@u+%W?C93-j6r1o_3$WBVx=<|-Yp)YI+m z@D52YRq&BRWM2L-rB3edx_uOuN{`spdbtu4KZ=a~>sO{8#I#%R3K_4Q;S`|W4a4V6 z5vIMhM*WQJ=LoDV-ZMy2nY`tcDQ_Lf*P6q1y9vxgM1S&<;N7JHRDCoxANAU0QbZ&v z#O7P@IuWlQAr9bFDYf~*!=%4oz|ZUfj=-yBjFzN7E}c;B&KyDhSkp;|z}jLooFa!+ zQ{&vqP_G{2h=_=V90LnpE#X)SxZ9A#szoBcliQVzKQj(F0?V#nCsOam>HvuCvmbxN zfWKfKm^XN~i+xct{#s1xr!@JQp#V|0y4Wae=fQ`(wV--?gho<^hwBh{m7$-V*)}g# zh8wy1ZSeY;HvzH08eWTFG@ORdi&As{^@_~hdG2RjaRja({faDYb~W{0{%2&>g=?Qp*J7Y+5{gtT)@x~fP;Q3LKT-{~m z;Ob_??${vR%!y|l(RX=Ca3*~26j?AmKsj#i`ZN0sB9t|3+p&FwJ52w$Ltf?{p|pT# zSur{}0+)+tJ4te!F_g0yKYw0%?8-(jCn%_=+|hP=h`*JvE)^PsjyUf zMC9o9bbO!B%FZG?Be1;K&g&7AuQ}6esY?`Rk2<=!7R!!xf_ITGxEfyOnUucc)M#Ct zC2j-UHt_D!o<+)!)wPIU<-WT3MBJBfACsh9S{rp-qny?#Z#*V&e-*#E#Q=L1>aR{> zM@gyae!9IgrV>23<%3)P9bA-rEzTI`xsK3zKQNWh!)AByzRn<7+Y*)9sc}006{Zq( z#b-On41-xM5@t0onAPySjb}AI;y<#_G)yI;{2_+|c&vlGi6P-8!%&oc#<^puM2-Mt zM*w2Q$eM;w$eZYdvd_4NSaXqw067$Z7za5GEg+{M8D*dGTEw+0avdOt0ucX}ea2f# zAh?YZ2*{xT%is+>rUQ?zDEo|438}cf5>i191t9($2ia$kH&FueKQNWhoLd~BIpk0P z;xW`!6UaWRgtE^#m8e~AS48bX4h10oE&Gg9;ZcNgC;;&v*=Ik?<*g=S_8~6->Z&;8 z<0L{pPFZQk&)f`7C1mHVhO!C(F%xo^MncYyin7l*m8c)yYAAC75b=<^#52Q|qwF(I zCE9?u8p@6U#J^>qaVmk}ttJqV#{`;>hukHe;Wij$pK&T76>l{m7347i;tu345zu2S z%0A;%LUZ0~LUYJt0)zqTswmV|DU^N2sc@@_+J%e=K>SVrr~li zKd@II)f|xO`;YBEv(GqpEIZZ-avGooSAym-DEo|Si0cQ}8>EXs3-ZjcZz%hW*CK8M z+%~!v{F!~mTS_1xSLSDH+D7d%XhELgb^v9caVjAdRGpbUDPLD^@VN@xzb zGP-^Y^ZCDIpK&TtyL?QD+O=7@f6G4ORJhe}YyM~UnXZ@MF%R!Sf@OG7)nu51vd?%g z!L5ev3dF;u)HI9*E7|~MpYfiETMb(!sH@z;11cJAkK-lKN zmcXMcSkVzE`;1cwsrZ-|QrYIg#Hlq6l^}=r(a~SoXPioC&h3iO+%^y9g6y*l$UZBE zvd=gbZZ%Q6wt4X1vd?(i;#R{J^*^)EevU!j{ zerBKXzKh3)9`SG4XMB7J1Rq^`MBZN+Za=fnIF*o!k6=B5>ye#B_cQy9QweRkmCz&p zE&Gg9i4nyuksk4H*=L*zkEs7d;Ow)XJa~KP5fGuM@+>{upXHGF1$mo?>O5*JJ9ewj z_;3G~CuQmo2EP#^S^vdy$Y?3RTDy5z5x+|MI|5S`Zd92ScfKd{lKvZksm`R;VJRn4 z{tpDEdNRKWd+@ob@jrP0W6L2-b*N55HoR*|m|y=zs$`p-mP42-B`0AgF75n35SZ%p zS#S2_W-jRA|BDBv+IHuIY<}SXe;_cGW$9x1q_O7zfxuKvXI?bA$29(TgiUdf7gND+ z^Zys(Cl&Cs{HIhud0;Bg$?~6?|3qLas5k9DYxgGtQ$gEk|Ji~+5ts_vU;EEq@)Lon zppR+)Up?_B74&26fA)6ZV>yJWV615Wb3|DYmxDdq+_m3fu0So(|m5g z`0sU(>dS7EYqJCOJq~Fu;qufnRe|3nKrANd!~`!*VJiOn;HV?=kL4j&M5W+8a^cf{ zfVc&SuTk!F%Jqg;grMSxZH=AT>RxVEL_oU4j=J+(Bd!CYkzFLs`^CqK5L6uTzF;Lb zW7AEUOEvzuC)+&f1X#OAfY=e!jTSp_onR{dyX$MlzP24{MQAsInOkD_Y{b!wR@6gs zR5{h$A=O#?Y1=IP_nMa_+4~JSG|uDJqk^n}`Vwr{L*S9<5J(+6)vzK26-NyE@Je>M zT-u75Quww!&95lbB}dGS{Xm}O>tIC)DvsFt=K@)qN34j*K~v;9Hv$0h8W7c5jUuPl z4Y48w6-P`Of5w>6roI)?WoEju_uLwQcm)V(v}FHnqpb)*m5neXgxQ9;YvZ8^9)Pe? zWlLp2Qdw+LW$U2`JwPfe6-R(h7Nohwruh@#0d=K{x)M|z0rjS#+SP2e`vMTq9;#>$ zLB$c!HX3gm-X1>w<+bI0E1^AZ0%Cdjf$A;$bt|1Ipts@lB|O>0?Ao-j5T5Ltk@HYA<6=jdZa2r7;c_Jbqx%-bO= zDc*qC35flJ-Dy(MMplHN;s{|sIHFDSZ?a2k{&MdnK*)wjx}k!v6(OiNLf8+Ec(JrN zn>pqPScdU{@L17}HvV>no$CyUselL@m_%>irdEWY;t1$VjQ1su z*#D{;^YgC`{VE+0n}(03B^D%`Fctp|{gv_l$`Qq#LfI!@C+NG20I@i6Ahi!&u3#$u z8^#3VV}c{%50zm>-z){hd_W}m#L%Pujw+_&zlBxfi0V1=vyJbcWb@b`9!SlLYgiG2 ziX((ofydOfA4svL9jpjJ#Sy})am4%`6Xoe`D*z(jw$SvHwWCP+ z*F&rbLB$cms&T}UQ)$Md*Q)};1rX55l0SbPZAA#GY=qUSWh2Zsgc+m)9*W=r2rE^# zR935&EtSP4)m)n%iqHe3vQlvb=w!8O908hJY?_Y)1k{x(>Pk>?1k{_=s&NF=u4b#< zNq~U%P(^zPDvl6VjU%81HCqcF1O&9XD%xC7afGmH909#Vv-J|*6QN(JqF)Irju2Lj zBcLa0ww^cz5YTs3(RT$EM?gQeS~ZS<-mckt`(;4D_)x|85L6riBg$&kI08nLW*bqP z00CoA6=P6PaRiJcXu!L-H%vWPa?%KM^gMH zyIiYPtG;aIp*g#Za^F?qfGCxAKZ0~mC$(SnwjzY>;|O8ZIAZs@19D@FKOpP@QMso( zt(Cix6(OiNLRdA9*tW!;Ev}jm5Ke%&Suv6p^z^kN1QkaJtHu$1XZo@~eme*D>OJUj zVQM#OcygU!D*jtoHIAqm5yrX==nDu7AfnqP(Z^?~6(OiNLRdA9nA<{T@0T&7Bx!)? z)@3wZI5pXXsrYYU)i@$gUBdDN7Xs^(28cEt2GYxAmn)cx{}xt_Bev8DWOg6cW+O%y zjG^s39aT)le+#R|5jU9|oBaL*Aoc?f-%5crd}<9VLQrvpuxcDp07+K~;=FLB$cms&NF2TFo|UIReJHD#p2>;s{~YI07t# z#bz1)0zJT%D8iNqDvl6VjU&MNSZvnkDImaJDZ*X}Dvsd&jaxO2;J^Frlfjl8n0tWl zCZu66M~U6U&%J@zS?qBA&Fny$)A6}FL*HGxevN7GkuQdAbfiF7cPX4|d&^8?u@~(% zJtBGA0aMtbk;<88gT)@_=WasmML6OnjkQ!uYzsWbZ(Lz|9`xAMdfrbSR;f5ugRl3@ z>k@1{ej#=xJu{i=6jT?+H_`F99q+95did7z`B`PH-ECKGM8Y@A!IPDM$Dhh!Q}DZ- zYUKA=9in#CvzAQxrseGdgLbF+cT433evOI1I5y=BC+ zCR(&xl4ZgC)0WZqA^{O|HqG?s(@%%{GJoW&Oxz9c+&cFkgi}ld+*an&x2hE#-=2$~qS9(Om zV|&HlgQ%B6%ULxSySw7&j9S}~9$JsOg|sqvqO{jJeYBj_(Wu`c2H`UUB$N`8NfLIC${H1D0d2QU=JX+(9zSg=DB|+xPi=Cz~J1eP8 z(`u-g3QL7~L-bC-0h4NMrA}U)$10WBXL2gB|EwJut7VM{({@)q3iC(8Uuh<}bSt&i zX&XXNbu7?WySc(&OLF~WQL8l5#_bBwf}Huy6q^9i01%Y{fxqB#F+YgQXffTisZ^xe zrGt-ED!~KSDCP&FcFbv0mT`dkJz<%3CoFcqyj-D^TcbEF_k~*8)%w#xs*dHRn(BTY ztnLgNqu?(~mc?n&8yaX8oBLWlA)+LRdwn<7WIv;aI@9r-ZnvGfueEmYafIe@afhYM z<2G8Q2}bQviB-U(4j?2ztOo@Cg85+yq0N`AGWCcYr4|X=rrVzn+7hS5IyThWM&-8{ zU$xb~`8Ls(WR~`awa-VhX;+(3>e*b$Cj5n$i}&ik^cVt~Q_%biXwIp`m$Iwlw7$io zwMPjhESMj>w&{P~bliWq+CP(6eE@hzFL+$r5vP4y6RmCbDk4K<=Hua}1kb^0)mD=U z{?ZV5tT8vxDm?L(Id4%Ctd=GXG}Rn2O6~4{z<_1<4~f$nylAA|d)3&8OM(pPpo6B3 zpNn*yr#| zs*4YXn_@waGoS~SHzp`fvyZ5)9le((o)klK$aGKOy3p^2|y@}5N&7G&`QI@APR`*UXNb#4W9?i7*8v`_l(8pG( z1aIi=fY=O(6@b80SSlI1JW?yrK`Ozpd+%IYT;Lj&%6)d2Ah5XpeRUxH7Zvs_+x)ABst zVC5l7f_wVy_LKW< z&Jj~OTKey7W34Mu66DvWFh`pQ(-I>0jFZ4dDiQB$Rk;atA$lOJN>D56llW=!|RB!4`lJ7*K4uNIgv(v|N zq;85F(5)390@8Py$}yFc>zP3D7tDi83vF)Y4R1TGIBH5b?n%egs$=B=eaU))kw0HS zt@_4K@`lVn=2N$dwt*I6y?61xd#3MFQ*1^qI;~l(4uNIIXvhj|n)0O_#a}Rw?D1&j4L4J)bXWG2>_XF5UK6(6dP>5nz&cycSjP5C z(b|1Cu#B54L8=wy;`cwfHHdy(KZD>e1y7FGQekYY3{Doanzbb8SN@w#_YynM)G=?Y zJVd#6?)|h{M?+ZAoaf~!uLfze-c@BA0yN+euyVYqSHqUHM4r4>%>@G24@Sefz1(Kg zIpFaLc;K=IA4<{=de&gU3A@FNW7P?I>VQ|K&*kH3Sz`vlR9Gim3$VVL({=wH(7fh` z8M?Z9@^!rS@g-vmhK`h9IZx4=$JJqB-Hf0|r4o}&hC8F^mNyd(Ru5G6xl`%!)3v^S z_1W6|hm3Q}%+ShSuFob0M;qZz@@vs1DRl_7PaCQ8A#+J!Mz+@ILil~US`&=1EO7H+jll?=rx+29a7wczig6bXb(5nXBXoam^oUM z1W_+nn)6%(nt#(}6Q&9sJYB2kTA#f>dhBnAkbt@-hjOE-vD!Fm?Fvb7jbh%=OVVnZ zA}SB021lFsTzJf}Bpwx~Y9HrEvF9!x7O)H*QcREY4yQNHHc{}G7FS_S9Tvr+Z+eOI zD68)s#s?i^Dpa!%b?%v_@KzHiie(cgYF#JSVz(0eTCz5c(cU$sEYo=b@c43Nqf%gL zSDI_ZEFA*#SUqBj_ULLIR^UfDKpeTcQF*bXD}BCvmh%7ldh58VmhXLh+g?Sn0I?H0 z5Clce-kf6rCU(cQ8(UEjyRTi?7}xHWJ=?wQyym?Y7It^XcMUL}XL$cUKmIx|_B^v@ zX02Ik&6+hc_yuVoZSnw)Wn#zQ(~D{Q=o}=qidGYedz-@+jIb`I4{!{R-(?zkDnoZvB1P$8nv!4XlaQ=l8DbL;5$<+E5%0OQn0(gQ6W3 z9nmrIDG+z>kJg9oX|8Dxey^hvTZL_}St8PEb0@%&<@r`>mFu8E?DU2 z=R|&p9o{rvXU(aHPuMr^a9Fuw*O_Ct?6jv@7D6<#B+S#@e|=DwA8aonu->hdgSVjE zcl+nfJeEWjD!M~j-sMm>tME%i{CPh_NqaVj|iC2}Ts*1|7B zG{_&v_Rr{(h!C+bMDq*?XJ*7VLi8%{ZhYBQKM^6~Z5$!c9O2BqxJ`)2TQ!Vo@kJ65 zBBsX?0?iT53=faTQMS_+x*1F7TvK@|5jW(&1)3wAStRd?Mz^mKM)YVc5g}reh~@}q zrb=3(@$gra5!E7E=cPpalm8ZIj&SD8xDaB+FNy&?UdnhW5o1L(M>sQX@^Hj~=Eki@ z84X@a#BmYL5zefh0)!a%sJ!7}r(5d?A!5ad<_KrzP)Cp z!kL{^h!Ay3N3nDfLlY4cB~OfbbA&*1g!wy9>I01~_dmZxj}nN)xH?A&G)Fjdu{eTg zsDg%w-6tcGqw<)^RV1k&s_2KqA@(^qLZCUqne~>JBYq9g1kc4@3P%VuM>sRsopgF>sy_cR4 zB)giBU9l&`5dzH-&J4lVG`eRhbkmk4&kwQh#1R6`5zZ_`KBH(3YGMwGy)BLqXpV4Z zIzAv8G|x3L&&B>3M+h`W(5y|)x#X=PU7`wIBKGJwLZCSUayhA0q_0$=ueglyC^<(6 zG)FiytG*D8`GoK#4JUtbYBi1)HPPyh5Y4Dn`$)sd)SdOp^tcx7Pd)!Y8jd5JJ#@BR z?$aGY44}~sCJo0C&QWxtIl?(^Tz1bB2PY5*Il{>)Cz>Oiy!l8px{{R4B@M?BPHAwW zIl{^RbVP$oVqem59O0BWCz>OiGR9?>OZz+0a2(;3YA2c_oN}BvKWIkXBn`(A&Y9yx zbA)rQyvr*Kj$@e^l#{hT{m*OTV*91)3wAbDnFs+@yW} zAPvV6m@g{O93ixlqVUn>GV_@g_HWh zL_eGw*{N%jTa~<{$fbnF$`E7a)cQ_+&Jn^&(9S3!xWy6ta9S3p&EN=OiRe8@jv%Wh zcGdT?iV}DG zga@c7&kn8BPk!C1`c3a=pkIq<^fDDC_rLS?&(*SM1Gh9W&_72{mLr@#^_5l=^>q}l ze0R~qz%>VYOt<|#9TCEVR)o@LQD+`VgYdAWc*{ZJ2KGXXKUl%f5pJ6G! zniMNbx~C|prrv#ggywUrF2l7ft|oE)$#0aat?w*7LYuT!Q*kZJONliu|1I*%6s1Jt zC2V4e-rC-${Z))WU_5}gP(%=DCH!~S{Vge$aec#IDn@QFmXQLncbs1J-x^w%e~V}s zhvB6}e1`uPaV~|eH`3_!hIZ$ zaPIt=v>#QI_M`NY2W+^nhWk+*A@;xMwrSc|t3>;1oxH~|+(pEFHI5MbZSkzpzRTi9@p5P3j~vX^MIqMV}tD31(F@!!Hv z;0Tdxl$3cEO?gXgDSm~e_;2BhaD>QbO3EWER<1%~ZWNZ{zlFcU5h7c@qudhbH(TN^ykn)j2|B1tv)e@mv!;7o|8ttOqzkWF98*gXBsRawSS} zgjjQMgvf5B`>Cl_B)giBT~Uf7#JYwfL~bPA#!md8`JsvVAxd$CSUYiq$kJ4l z%t29#BgFcQBSem;qGV5+=bD)3q7+AnbuCATJW@sBd1RzZRG~{mDUJ~9T8#WKq%$b2GUso{E}R6Vg_!aCzG6WOJ`*W@tpE^bJAG= zEX99|OgD}YdA)RhA|ZBDj&LNM1;A4Lx6o=FA##W5ToECvQy%gvItzfM_-~=rI6~wn zC!Gawr(EX_bQSNpzerRHTh*BIO zv>HcLo+RL2 zpEJLNpPZaQXRr)9If1{auQ4N-$JW#gmZ1cPoLGJvt(K6 z8b>%+6K@HTw|Nvh zN9Q@Q6#p%>8b>(S1{}eqjGyPkQpvv)wOTSFG0&RrTu!2)3L1DmN}R4rZdKxm)1-5d z)DKnkLzLn)gjVASXM}~HgQT(2#8`<^93iwCM>r!a{5&V|LlgWEr8q)pHI8sbSh$ps zBx*tug_hw6p+7i6#2k|PLDH@XX&0q9Lg){Ua7HFB6AhYCnwU|d6h{dC!4b~L#9czr ztX0LV6{R>roLA%sXJq0mAxJZ*LNka`93k`vNATZCk%=x}8ye@b9}V0Tm(w_UbBr~z zMvx=8>H@P|?-ACSu%tbDj7%wt@!iL$dE+1TqUB$z0$UyMnmnyuVqOoHLbReROVh@fmg%Qj ztk-wjnab0xF#o!V*-ePXSSH<)Mu_q*Kh@m5zuT}BX6(p_tAsHA_^D1M8u$hCmXJ2J zs!&_w-=@FR4E^RvIYmeVY13_1EgKo@@4Qvp9A2qnT}T6Srs&43y@QR;T{j#!w_%2Q z<>*wa?_Z&ghE22Eu@uH(6{Q#5+PY|AxccJ6PAOx{ermGSv_^1Z?ikiYdlS^Ey!YO! z6{%HN7sh%KO}8{(9cH-pI9KhzM&VM97uJjYqxJb5o6+Lob@j=Cv>MihG%z|$cP@Lj zF+#3hXOG-wsQ9IG>Is(qu)1S#`_Xo+iOzo<4KvQ4d(GY&f2&REjkdI*YGPI)A}|_F z5qfIX#79Z3!Y`Pmhc(gqe0~$-{<#;d(uAc_s}PO!Nc)~BZH)0fsvZk0s$pG712Y5( zajLX&v)oa22O;pwB+90`(laUB5No2mrR@ccptk$eO7p!nEQM&yTOP$JHTLimb_J??Vmk$yIis*&Qhd5)nvSQGU#?WBl^Fz(&-4z|elY z`#9LjSH|D5eUz0VE9_iML8E@yKDFLvZz(GbEe_U1X_g&o8=Z6g%N}-q#W0TyX<)V( z?XfKLv+ddNNI&8kWwhPyYL9psrk$A9!Q#JL+-qi@$kIxRs#4AeA!ZZeXfgszVdPfC zVJVi;C#P1azl}AzQO6jueVe`C=$fWquVCxb!t{=-jlIkl$4gq7mOi!5sW9E#JC)zb z@%XRwTF~Q3%*&{6;Fr{Y9kaJsx4^tPwTgu`(XH9j%4lo;8PB}0c^g=7-9OShIvHcl ztQ87bbBd;Od=DCD)_7ltXt+)MEWNo6cdidY!m&Fs=Usbvr_ytE-?uX~iU8U&k9$|A6oU~gqg8PUFt{PwJ&VbpC1eGrISJ!l}8$g zrkK>p4f@YtTbOHXKLhLHXmN@TYog5l20LtT>ZQ_KJxrn@&O0u-)iG#yrnL4S**aRI z+ql~4Ew!MhN7_-V>YQ(+*H^#U2JeqFuvE$&0q4%>XhP)FzS#y4f|n9s_;0b7iZxMQ z-(@e=_2LEFO}`P+{J@rE9ID!l-K~O(OlV83`s>IZwRlNC_Q~ui@gx4s61yHY*0@xx zu~m8NHv7j>`46QlRi6+(MdqpV{)^Y$8V{5ZI3K%wA7dXL(oFjv)tnHS%1%~4);*%X z?m5`NFGvGrjBdww$*H~lGLfC}uO-b7ls+T1;&}BvwYh9ZMWW#~;I?|uJstCYCQJLJ z>D%oU#}z(Q^-VpidRk^LnydAp3vEIP5fyb<&GIb+^Y-c~%@6D?qUqg?t8dhScQUbj z@7ozzSMds`>`PWnKIA^GR*HE({z_JDTt#m-+@=_Rvo6*bTGjacD^-p1bR*&S}BBFumOaJR5ttclJ7SRq<`nh17{ zXkcB4mJ!RBm(koNc4W^xRW`6*L}33Yhu#d*hVM;?`?q0934uLt-ZZ`A{`~Cb$a*{* zcM~D*65=5ta73{bqG{jY;aat-XJ*!DbUy?6j69GfF~2oW)vAQ)JqHakaOR*KqvX@R zL05lUjarv%)jLEPIPb6&&Uw<*nf+}?`fX)j0>UMI#Y+hrCAX^d5xbh;x`k!C+{-{+ ziyBTwSY)FHl8y2w8-;cWtpSb#$rV}7^U1cBw?tS-Y&-Ue^e){4d7N%AuQ zve%b7m7-NA8ewNv??xK9j>6W`E#^ey1R;jZSuXV)>0t}$YzFoG4k50GzTAbSkRG;> z)*pmOv#YIUxVY@ZQN&gun%;II#80BJp@e&797QZ8_rsI=agq?bPuKLpF+qw}gQln^eE8p+#gKb9-8GUW?6RGF%M5E8r zB|C9^a1{Qx=e$)*y4LZ*b61$dgy#atPb3;Q3Be;lh`>B4%-N?GT&U-J2*GAV_#px{ zk?b?vCK~q$G3jaO9z>uPMeR!K52EoOA=a#!Tp2mlu{yn;oVKO;l>M|LXDN4q5c3HU zKRCo6IaPj6dPmOUIn0;$N;#0TwEm!0T_wb|e{TA=N;TF#>t$1|c4Tu$$xShKkH+nd zkQI$nAYLYq)t+kicO%aa^>nol-?A#`^X+zy4DJ2xr#yNEwRqf?cz%x%cZo*23@i5_ z0<(osVv^*F%Wl^zJ^T=X8A*7SkfOBI^FxFf7#;3|l7VuC@Pv>spsPf(Q83~KS~^WPFRz(=YPG7@k5Cla*e;Z6lo*t0y4Qeu&gJTH*ePGsODMaD z=3G!TK0l7EoaKuWho@Tq7r|$3iQSo{`GKP#pGz%IJcSdUi-1b#1#_dswGQeZFP*Kue1-U zV^+B-=7zt9o6WWaIBMI*n@1kR5Eq3f^RPvZ%E;U3HPsza3uc({Z}OW+I|;!(fbu?G zl~K!}zLGikidw}zfP~{|_u$+{8zu9jKkaqfqQWjaSbRVxLk4B<&uwIR`hT<4wwGR{G7$l#F3_V;)upOLR9MY zaxWr|5~4_%zsyFies-K)wC6<#ZgC3sZMp|N3mhNR$4PQ^DY;cxFVe%)^0X4Beq11g zeKzw!Ukx=JqG=bIT6K#M7tGK-I6k;4mJ!@9;Xd`cS$=y^mT;_O#92b{`}C{0l-Y~z zMOniBIknHMKkx0vmY~-s(-=fF6ykY4Ep9LBD6ALh(Q9cmR$TiW&mB`4XAaImnMM^t z>?Oqbj>9F3gQak!>7^!TL|B6ruLD-5i5b}9&Iv_%N{C!r9_jl$qY@FxG33Njc&~*M z@uO!>t;E_E%(Zl=25V#o#1>MlKYEm`tX(ub*rXd3H7tcviGHx6RA`b@bM4cFH5?PF z;TK%vAZ?0Y4H>WItre%ANk2sDIeN&b=V@1F`dZZ^`wM-DJzPRyz4H9rsPC0jv=BX3%XVimZ2T7xgEkR49DAh;#+j2cRX3I4xO5@f*@Blf8eh|&5 z{_AZAK3Z{GTt;d51wALMiEguUOQ*&Z?!#RF8Injt-0!j@XVajn>5iBo&FeY5rfdq@ z-{p|`X+6JHC4AnAIFA`y*&kiQB?PZmWcDLkQHo5iWb3kG1v_?OfQEJ9_;9qKttkB{ z?$f#dR<eiBzS*@nsHLS}V6>AUijWuh|vpZ16i08D&;`6o|d-tY}G(WJE&-uId!Y5{!EhD_C zAN@SMwBd`#F_&`w8h**vA)RAz@o{FQ^o6DQNbmOT`=v&)J80t}$tW263TGpTKSorHa8m@$0+GKHf z_>VFREzaXuF}sN4bH?uGitDL}#=bToT8ZNoSi5T;8h*i*1=d6_VWuso<(t@*1#a+> zXrNU?dX&YQ)l1tG-j8+bQB})ZDZRsW%UH8z+d>X3g=o5)>Y=Zeq4Y3zw0vm|zo72I zn&@uBQjN5r(NQe-;xtk}&@aV4k$*)T)QE#i%KB@_HLMru(Mx8;kMYEh&cqLtCFG#Y zkHWe0s(F)T7v~_#F3uH-`}}OH|5^E)E!(z8Ev5btks>|^g;t`Ri4}QNuWd(duda{K zP?Mo1Lfu7PM)`T_yDRZ}ov?u#>Om|ew`y(lLp3nZEq&L6KQ*)fsDtI6A1hT^Tfsb- z&-IELS{WQsxrXZX|CAAdkKG-Q>qS^DeiuwcljZcB7r6GvYBr_r00VdR9%NY?bZc&Q>)n_@ zD=PipY6nL)>wQxjwJPS&41Imr7Pcp2xU}1cr8YF4cj(0NcjkhR{QVbug>m}UOq*EP zv~UAUrT%O7q0U`httoW^EgA78WTS4p+Q_<=4>#}&A6>Ddh&zpnGWU6~9`fO-e)CtP z@%-ybwbyCQO4#6UX-nrF>a;x2%I4y4J$9da=%SmKwRnA1YE?jNYrSEXxBBiYkp_Oj z7Gh0wuUg}QT9{XPePPT}mhhsC!+VQ|)v)t&bHuDFj;yQQtfps+ntQ5vJN)vEw5q?HP(BCr8Tfs_0AS|BsfM|#b+-!k^giX3B9t}?`AiBRgqm%KT01c>G)b@ zq;)3qOcT+>bGIn%=a-`T2kp6z{n*&r=D44b%c?y;!{1&x{T*Xwja+31aXY^DJ2?? z&?)NMmYMZ`nhY`Ctc$aEaOAeuY$|Ro&p6FqW<)EiUCGi`hl1hun~$4XEei6RTWX)W zp~loYrq{aLMMA6}LeKLa?`mD2oKHeigg)}9t?Z^^Rz{_t#@>h@N@ zF(pz$VA~O`C+2cm_uo_MDq@LgX`cz$d_;6ecqJdwK2GXXRBb)A1Tjrn6 z!pe4*IEdqe*%!3$d}FWLquX>guxe*1%L4cAP8CNQ;@Ex?2XTK8_YLW# z@f`(K!*ey8RzXG}Z&15ZmR|D!H4o9KKs4|R(!f5EzAERcHPZSruWj<^V%u?Vk`Oi0 zYhx~tW~XyBly)sK>qQ>jaZv%<@#tW-FKbE3;$SIx-+5nb8EsEQUskHQue9TiJJo3I z=)EG!-f7mWJ}Y*|Pm&VM%aLh3o6uRCc{hM%`hJmNT^KvTRWaRb@H13v_|uoU)^d~j zfxGXBruE0!!CIFGKCJ7cc9KrSs0v096s67J{#xFd1=-DN^CbkX)e%j1I{nvG^DgAZ z%6C04A+YU;rV~6%Mrs|)XJvKFjgsEQxCX|~6y@8#p<2cV8QI+QttE?tZAUbD`rSrq z`>uV{Q_Xy&V_m4JQRh=m(YpRxy7ZaZN+pJ2y;uq@k)n7fwAQk2_GG6veP!5NEQOp^ zlrqG@8pOf(HQl5v3yFi^MbSyM5^uk`XtJickzh-AC4*>Ot zJO@K>q|+uI>d&%n2{TZC;Jm~6NT*rca%oj7Zqi%sX<(qX#8Psr#s+7$1$Td|7tInS zc{1pipkATVvY!Lgp95d$+g=YhP@iKdxgRxNA5}jdyP{{C+tWb1gr%^BWO2wZ2`0a! zYo9=dRv7&fp6tV+XNluRH~e|D34ES?HM52fkbF_}CQ%=g{g`3X>R%YEud80hKud;P!#*jB z-;g8hV)z%PUkWy6cFkd3`{il5KFe#FnH0-Em$$WGrn~j2cW&!Tg&?buo#zyFe2~s~ zGwQuQHB$?tOXu5WoKL9LdX&4h=jU4AAe4E)kDI)hbnN(<|=mfFIa$cG~u_oLtIom0>_-R+2ZeqJZ*YmK}TJ<3SQ;%WT3 zxvpVM>a9O+Sl_y_Im~+5#?x%mHpuE-sg3pL%3S8DwKc6iFIrjqn&l%O?oHmx#=e_A zM$GpmI+k+XZ?_8HYiBhnd|-`?ICXQFk-&Udj>-ku%BO)=k#oJQnzq0-jnnyC%YOE> zJo0;(tMB<*w%!p|`D^LPr@pbNztLiOT^8A50>e^$3i?>LPexeLo&{4NmZxpW@)eF{ zzqa-^`h-p~S;cQ=;Di8cLf%1UU$0zN=Jmc-m(hpKOkstsQ3p%V=w=#_iGB7iW{hZR zH---`YdyG8+S*<&y@hw(;~n^;Z$!{KD${-a zf&WF8aZ5L;ANb0HjA+^9JF6SKhF!c~-#|{`yu`RMhdT*(df-yGnc;8 z^zlI*4g7-rz?x{S=9ZH!xp7w?a%6F1Fbu^{H$ShUCfdVG|R6iU*r7J znlZD{1ij4B;Rb%ew&N;XQ9hlF*Sr4rSkH55q(lQ(^hl5Hz`kFM?I^lDuF8^;5{)K< z3Yo!bko9Y}Pl~bncldY~{i!a?aJ;{P8USSpTS!s0ItJ_aVl>;=wX@7~&>!+xom}n3 zwt79(=e~(BuwIm1x#usowKZ1eabbmPeq=Qw%36mC_pqW1&M_aC$Y;Iu?qo&QykL5T z=C{82jkG4cXQUJVy;{q7vB1V+^X4(IR32}4%V&CoHNDQo6o}7+$hFYM2Bkn)Wph~7 zmJGLM+Tu+_D@ySaeT+@Lwz1_)@=AIawKnQ`dXHuDK;uNQ{Orz+Nm4&TkCe8|@gpt& zKPH=OXC=%3PJ~rDp&0dJ`=|~^&p9>Nq5(bV@S4kQv;)2XgXuGeG(gBRI%3n-OSp%bf$@=5KT9Qj0-fTW%$5GTzk*T z4Jcz>ELzXQ!isi*139v_y*RJ*k)F*NfS!qokfVI$oBbYHoe1O!>9Hi48I^f ztVvNE(dms@pQ{+xvOJVV7kP91aENtnd9bzX%{&?_mXO^jv@+Ou^lhZXLG(C~9&zyL z1C~&#kdeNAQE9A@n{A$`R&bVTR@bio5{)W@`mv{z+Zry5npA3guve7?NEwx zkqu;v!@`a0Wk*T(M&Tck8?A06m!27VpvaI4J?K4 z@yLigy*jXnJKn~-mK6;Ag11h|-cmY3^dv;uRu!bXsn8>n5f+W^Wg6YTX>_r-IJ$Dr zJ?o5Og{U8!sUOHS><9LbZgkl2jAhH|ZsgfiTIxBr1m`C0J707+%nj8Iv+@LK4q{7C z@+r2|BC~Nlr?)X%c_;B4TY_>-vzF$$JI(V)b0QheXOs+-7)5b;U&I*H2~Zb(xcdGn?^=m*VKli{5Z+t z;58ue2?+0YeX=M z%QisrEYTN14~OoDBVY6}`J&$Bi=u~wz9_bk;y$#3yhtm^uC#(gKM_}u*h0GNl6=v_ zeBs+-GC-?lz&3L`c?u{((oPN@)Z@5>4dq|41 zb!&bWzHJdZ{UcoR$Z%~SBLXwu*T2x(;MeAE2ChtSZGdRXtZDa2&r55Z#k8WZ8j8qwSutAOH=<+(eiuEqtaPsVFjRNa-+U;9-g!M`2VPrj@k>Oe&t-h>% zW{~gWmOCFSNWKroGSK%yuZH%7r*CFI$1BFLt#u@Oj(S(_`OmXI)uFW}v#(_uYljbh zvwJ=Aw3aHa4$Mx#tOeR@x>sB~akdf5c%Yhuz}A3w= zba(69IZwx104nW^tM0#nagVQ)YpM|2a2-Rf33P@ z<1{v9dp8YBVa|-4S+gsfyLz>6EPHdKpN3zsUaX0tA6NfYGhCj>I(_J(ArCNr0_iEr zP_G~A^ScAsw;atR1ZG(vT2a;z;vyklr$C_eA(~?P^GoR0!(&OM|CNPF}Xr-f_y1y-pJq)n#*7v)k{ z&059|%?Ot`h?yfuo8IQ|ucoeG@APq3hD#ho{@*IIE~x4Bn%1jA{6)6XSyHK`E-cV@ zYmpj$S)Ink{^DAwRqLIPBr$X|1tDedY-gxhnSZ)(+5%2BI6JzB2zREOwab`8+*ORbSh?ajBgv-Z{Xa-j6kt5&I8 zY?<9XD0u+HCs zH7Uw1t(V@Ye}aDKN2DYr$iYuDdmLJKC(s(-i_`c%{Fr{X!4v&bfk+L%AOa#2gjhV{ zm|nQy6a6e9@C(Fb99R?Gax=ZHwsl-DUBC2GP4~WxqxD7)YjyB)`)-fij@4s4trjm5 z>?;a+I1bw*Eal~S(n`O2*4Cz-zkaaVxI!9!iLdMFSbjRf`a15k9c!XnZt4%zhRqDp z7j#)FX&)?Ay;=Qbm)X3M7&jff?KwDs9q=)LF8Rq;#gfiv~->B?x>cGR`aZ+y3JY%tJT@H#DxRrW$&T9%uq;&yIwX!ymWZ(2vM<%6y8 zk-wx-puM72HMPxIX6PMq7SXWOyZ-Kuq3#jZs}&bhAjVNv*w}z5Hl=tKsa2S(h8bdt za^}w(TK`ijt5Gb!gurY%MAP}&83Ee!C!uV@*%DGd9QGVXgl^fS9mSorqv$c~kqt)? zcNB4_kz5Gc=gi}kl?}MN(S~0zLmg{Ul=B<|YVQw{LC!8Cstvu<& z#!YLd;up-uMv0-@7GnBqKXVph^GnQAu@s&+krBH~w$?ILtIBTQ`K02Q;29Il@uQ5C z`E9iGKdZ7UOWsNdJl}w5%1?aWS}S-w4;$A0tAxOo;E4#z+1}bk+j}&K^&Njk#V<$$ zTTA?S)mZC0-=EFTmQlm@qLj#pe;akzMhtdip=(d7I6g=ZTc{{gX{S2(hEhqMY0H}0H=0oiG^219pu(V8^FMA8gC^X96k z4bYR3TNUEgQF~$x)?a>pqoR&Ny(0Jgd%Cpx!#f}JjcKAJy^DGtEd#xGS2f-i?)pi0 zTRu`l3n1ASVXOHT6>vz!5E}_pT+o(1-=co@?-Pf1(8mOVQL<@&DQBh`O znH{)s;(AtmTz|>ppk0zZfY|)|)pJo(S#W`U>xN8bg5%zw-0 zvU0BUC99SvU32#3@d!Qrnc!9$5UnWxopm?n zt*UMe95g|_xwne7Wo0vKjXu-<=s<`S5EE?G%rW1-Ii$YzaUH!Gf8LYEs?YESY~#9` zMypDBG#q#22fjwEDDkaYvbl518*$})G%SU$5zB}R)iWDczg0B44SuIqXj{g5owFWg z7@o5uJ#3+(M0$m@s^0C4uu^waEQRk7;M>x)@4TiTo0P7$v3ro4)DL{E0MUwKBgA|{ zEJ=aDcbE}PG~C9rZ58?&j@lDc97Sw9zI8zUZl;l}L&LU4|MquOEQM{CU$#Elcr459 z*4JouY=VkkuwJZ*&Oy#Q!q(sEVO%Qthtw*JGhqCI?p&sPh8OGW8mlVzv*DL4&4a8~ z<=R-Qvb&{_lK81(*!)F9jJ5SP*|6vMRye-dK(|?y8^dZ<>ub!tB99fm3xQ~QkABo9 zX3gwtXiNT3u`cWf(pHoS&x#lu!cMb&A*Cc;f-)x0^RPMnjr5~R(rs3ARIh<$t*v=_ zSlzWbcKa_s>+t8Emid>5y?kjOtJLEN>q7V9G(W-`h8wwd`?E`%=d1X|@wudRBxa;F zdebaB)uh8ZY0f_+>#GPpj0T5wwqf+Kx4mFG>#<=Or!rCuvbE z)nT~1b@rbKE8EtKDG*t`2N)-w&tjR5=9l_`QLc#l{#Git;a0fgB%R5e{H&j`K4J&E zlq)O{OHqX7cZ^I%L^W+>*fOU!Li>!9^c6}Xjv?*cWe+mm{P&Xey7fxZC8+Ii+$bN; z(ZaZLA%pQL_Y51>g)}hYO}D+Rf6aEDoTj_g?5Lg5)|<0lRJC%dUXDGPZkw51LTQ)O z-SO$*eluhB4p!(@ez(ZvmT8SSMLy~iKeo`YRI`jn%wEkqS%22Zn*x#giJcvJ;LlDL z8mggXLCb(EOUgC)=WkXqeXw3-a(~GhU<+>?2{!|Jhg!Ao@b&qC^?TVp1<1e%IyNXu3?e5Z8A(~EF^vq|ppKs_HZ6VTFp>_6o_t;$3v9Fb`e^%)_qewsUPU0AZ>~vSG=iD-Mf*+FYG5piZHf>uldk!xbDgd^ghjEOVJtu-fl-P z17l8#a{S~NW-D->?VHs>8`SfTc`a)u>s9q~jmiZSv^9S!S6+m53^=W*(Kvn#JN7%y8ikq}5@!r?!x*aL4& z_t%w(gN<9h)89>g$rcTj`!U1%Vfw~CHEnhM95Q0Sm;^oY;00FaOgE_?_`(ssd_-q0 zv%9csx1OWf|Seee|}d|ipwYVlPVi+4AcE(npv>SIC)tA1<-tJMBt4n$M#M-hcBD3RINJ6s;! zvgM0g73!zA#wuP8L{omr^_uLPrKw1wjr}f}uS`Xs- z71x6@jf1zd8zW+Z4e!B`(#i{ai}Wb#Wm+coV&Nk_^N$f4Mh9@;K=%5k9!twE_uj~I zyzDFai8!NVpWzgFOEKgv6((;9qaWxkA^&M#jk3Z53l}mfH7hEuopF3*DKYm3Yjdg$ zwY@D?Kx?|+oh*E`H7e&NJI4Jmwn+Q6MF(od9z3(X{W(|NAMBHe_;Y4)JH{33Qmtw3i4vX~YcCpw} zn!auk8@0ZIwEuzi%KiA9VV#=4)RDN_tiLv_pG#stW-aq|V9XL@nG`)I#H|uX;_9V9 zV2l*e@UqUPioH7q9kN9K;rG z?I`W)W2>-#l#7$@puTft`#5@+p0~>69OOO6-8Y zqKrM8mz|gt7w{x)q(lQXsvH-+dqVH0uiX@>zMV6D^?=aePo8)BPorLXEQxBW#^c=an=ydH`4x>8r9OjcoTX>YIHu ziG#StMLkdVixQ&tgNyo7Lf{u{3AT{#jwYV3TRtstEb$z_pkIpg=>FZ&?TyKMM^h?lRQIv&*P?ufN!*0n4j7%Y#vcg=vjQ?u-8t-n*k$fMr0Er{bZ3)s=l+iT0 zH9{h61!#2f3;J3}kIof6j5OSi{TJ6gox*L@?|RXPL*I^WV(S!XXv22slRrF^ygnZB z;{4~c8f&7rm+8gObbp@={2H=MqJgnRq(}J-N22(BXVIM(ouJp*`3*Bk_4421J^(oj z>3s2#TI_=Kto!8$Ql^t^EwQG!Vgt3;C!g88zRp##F5K;t(ZiDM`N3avRV;<}Tt@W$ z$X}JGdw$YR3zSFE86CuNqc@9btWwcf4XLwC;yI3$Ji2L#=M9PHhluAmi;(9i3$!ak z(!Q3Yy&*|EYBiL0oCTEcL)ynm);?%iQ2WT5;X|@D*i6;{tuR^xLj1N8baOpf&O2l| z!^m=?XMvWJT9t_48k}xuA}?bdc^Lu43rN`_=w(pP6QzfHYV^k8)2Kv#yy_80FM&Db zmH!qQjdG@AtDuoan(k>>%<~6Q4kYk^Yzo%oxpJVfV#;eFVj>%u%_8SQqqv{B%8 zd83gBy?^f1q9&G-PriIu*4zlbx1Nm|ca7l}%tOYSCnGguSd zLQ6C<-e1o$5)G^u^PXiIslJyo3hjHPS8%l%AV1RC70l}-eh?zffmeDiLf{w71jU*t zBHX@#k-FALoANA&fz&bg9COkYWiTN&65{z&8G$F95UnVuV@nzy<73&%73HP;c5DgK zrrh%)f3YrUjvYMla<6<}pJp)p%IkyC!|4dku(diM%20 z%v<%FPqdqnd$#J)`E)Q5uCn*Xbge181yE#6s! zciB*`!LtI|(ya#%#%~XnZn?phU`@0lYF0s8+^v*h6<)$Mbz(or(=)Lp@(oRU>-5n6 zsN0jJ3EIl=3*Mc8HBrhPAvVOD&Bq-YAAQJsxDXgxE_6{DLjSK9M9g9j;|~kyahlNR@hy_e|jZ6STYZZLs#O#u%2z?~X2iae8`k zKUNcsmPF%V3L1E?7Sf}&^X5_97ggdr)cYSA!WShEAdyeJ9PMThjTS`XRG2E=Wq~y0 zR^_I#T2EuOg2oD^4@XxXtJDWys~Hc)RZCBjh_e$VQI@L;`Dd%{GzVw38f>5*#5pL> zsF}(7>N@Ewv|f0ITh=85$Qo25YY;=$0Bty018SAYwJX;WbP|cI^LDb%dC8umXMxt4 zdQK%1qiuw=ktef~JedaM$)Hb#o(zp{B7)DGB%TmH(er~Zc4)f;T1A{p`uqPxB+hvr zZ9(+^AgGRLi&MuDmHF|1(STB%#&3H6zci?qN%jg5Gy?w@4Ui=}()%C8?|#7eq_8-I ziH6brjewEnx{F#PIQW0H3g!e~*Cy7K%vw6It9<6lmpOqXd#U<(tt6spe5WR z|J^?sA+G_P+5iwqG@`{=$vVTif`C?~=m*qAUnCldqx(P79u0L7b%}=P2mSy50S%5g Ar2qf` literal 0 HcmV?d00001 diff --git a/ros2_humble_crx_description/fanuc_crx_description/meshes/visual/j5.stl b/ros2_humble_crx_description/fanuc_crx_description/meshes/visual/j5.stl new file mode 100644 index 0000000000000000000000000000000000000000..133e431d888b1e9c1a2261a99b18a55cc7bd5ae2 GIT binary patch literal 161184 zcmbTfXINCd^Y|SVtk}DVC?JT6qKF`{IlG4{O+gd|m7)S-?}A|OioJKe?Op83CVP%u zEZBSRz4!K?!_EHgiO=`d!z->U`DA7?$)uiao2by*$=!N)>z^>NTi4o&X|=<;4M+)1 zNF@J1|K?c{l4kA4l`IE-siJ9D!{u&j{adZ&Su1ANd$GTP8Z|IbzVy^V|NCMSwf4bq z`Qy3_Jt5P9SPewpl`lG@h<`waKHz9J&V_9Hix>)o35bgo zP0esFR9AlySwO4@B7WYV-8k3s*3Rm>Iez&yEowFOKf)d7LiAs?YdqbaPoHv~UXEYI zUQcvZ?M@ivDgS(SYA!WYr(5{TrnDCNZD|eE&b|TiiZ*WG!Rxy#^KMzsb>rrQah%J; z#!cPe7AD(Qo~BQ-X{uVdgv&v3lYrQ<)tg=Hc!0e;+MVNE(J#H!I-}dkM@4RXp=W1lBR~yXjD3?k&B3+zM)gPrg$#*X?i4eQ!Wi({K z0L|wF=R*H;L_od~Aj1}9c+IOO;ao_b329{_q~jKE)*kGra;&?Ab0M2d$Z{YW@2Sik zCO_A;n-eDCT&UhmsCI#f0)G_Ex=za_tfDv<_D%Qe_0$A=UwOUN(0YWtpU{tQTE2+w zJX4C{6jZJr`yc9RZ4{q4^bT|Sy`AA)NcX>b?cHwm__ZMpJS*@7!?{rX=ut1w6H+as z5WjRKk~fVX!*DL-0}1ss@ZfRphpczKZkh*2;#}x|jtIzS1v0LJ4Bz-M6z4+nOh_xJ z-ISzyyy#E|?(Tnr;#|lk6YiUY*g{=Z8*+!0B0DI~h3d_OY8PZo0)HG_wTLY_Rf^(V z*f+Ru5>jMhKi&sC_~mpdic@g8xFoO~w8{eydi>r_aW1So)|QaZ;K9A%!R){j6z9VA zgKLD4D*t(q;#}AVxYqymV4r_INN_In|6jefG|0FH9@IfA!MTvUzaqmV@Ze*xqoMx^ zhI1jC{)#@Opsu{YgMMTO!?{qs{T1P6f(K3D!EL#v7|w-#gS|<}0qC_uA&QoOUW-$( z*Kltpv%NRJ%X~gFgyG6!lA3B}6#v8yryy$+bO3_c}J>WlGr!v3+kh zKlOBp_Og8wVsg9er|NgMk(=iRLO<_0zLxaygeSk*Vj0D?=o#s!wtC!N-hTfu$21{R zPv%j#w~qYb5_<`!p!zZ4k_f5S=9=#D8!MJwBSRQJFmYm@zq(*inEbT+FwiP$?GD}D zYwuZ=fOrX~tUBPY)*Tuu&mTS7glZQE|9YEro^SkFw45&CTx3$9diS$l4ojQ;7t!R@ zA-2)>GJX3pQbP4^nslS3I;)bqTfVbe4qTvv=^pPp8xZ~O*II0ehVvSCzfVaJCoYAP+SwTWWi8aITgbACF= z9c_!6>V$=>@l)(%hfC98{Mheg!#CJ9mj+kgCJ?yXE^|Uv%W!9T$3GHimDr&=?>wrS zwD?2Z^A#MQ< zyxJ5`$*#h9VMeyUZ@603(oX)=S(4tr4O7FO+slb#?m!>h-NT6wS)iA?u2^NnGWJak zS3fPTBe(9?(G}A$8kDu+&9>W1i+o=(To%>}mqf@mtHo^mib?cUg;ZhIH?(SqnmD$x z?3+78zh!NZ+O@K`TxQh_u%pb_Cu~?p3(2L7mq1`^F-^$UT9Eg{hXE1+6RWo8*+w%jKaek>b4f%W&C|?xIpA}4N}L3`N+%8&C+95tU0)chMG$AvW9-=pfHQ>?@JC1rMjuLvB;in$Aj+UQ(tq58*yOc+JFRsNy zwl@%GuOA3R*{C}h46+i$}?B*`U>DkTD5lG{`){aJ^$0h=BfaaLOy)>VX!lwRHx^HHxC>Un5TO)$7^A^(M-; zcjCBZpm_Dyh%?V%!@FBGm+DpD#&8Qqu|zNSsFp@Yo_AJ~*3S5(!*L1sT9N4Rs5o!D z-bVURtCED{D~?1+o{5mQc^8dq4t>xaJDwroc#b0~vI&UMix1QI>u=b@?I98#@9J5mLp&mT2zpK}37z`Fz>$aMi9%9r^s#yvCR&Ys7f>Dbz}R9$QBq_i_d29<9{=3AN?;^^yyw z33065oY%^-mli&nOMiR|Q{7KE$fdJNn6ORQPlOcBjN)ybEu}RU;S}3}30xA)`n-Ga z9DkJ->TpZ21Jlbq!_}4(9pvEj(onl+`=s#t5xhmZ8NLA@-mX$E7rELpUZ}qP)+jzD$iFVvx9lA8i&)HuKT@*)3Nu>9fc zG+ujpN4lZoW}gl%!&IH(ELRBbZo;*IO9C0eHF$&YQ}o6YS7~!vu-dzZyPT9V)r2*{ z{f3ai{w;YkkNtGEfk;?7CU8lx9vq#@r=Fih<7Z5#HXdOrD^_2gW}9fj^rTP0>ajBJ za%jX1uw!b)Vf?@kUutuqrmjash?;z|nS6HEA``X=mqbYVq?_#OU02%vP@-T5p8Mb) z4E>|g0v2_*B;D|#pDJN{NgRu^$iX3vm*<@@&l_g_y@OYup%0%>pQNcx*^yg zzwNljglhqpM2L4GFI~r>dS=~Vm=LepFsNB8uXpr%1Ks9dLVuf+omQV>x z$GVHete>5Es4~x+Wd5M7`nOc4=nb;lKg&#*?lM16ZE6aYn>88-GE84HdH>w4x*}(C zbk7Yz>V;lm^2$N8OxPw|5+Selw$=qi|73ZcI!m=5`l}}wwUHgy`I)dLIHE#bE#2*t zJoYWidYK^MT-b7vSTN@)tM7J_z3vq%VSO=;Wy5+fJCZ+ooybn#wUq8V2C3^RhRL7m zOfg~F{Yij&qHP(ZtFLkD+eZeyPkQai{Brpj;+{Mt`!+?!nJ@)BBWjB659D} zQ*ODgt}uS!_0Hxre|4i8Eyr*F2IKkk3tL&UK@EB7lTH$rj&&D_+eHKU>lSy}vf58* z?3_ULSW1+<|97Mb(@SRts8*Kk<+ja!gN(?HnS7~!k#Xtyhq_Cn0@VkbI>>9jmNj9U za7l!W`LTvR8`GIDuE(iwu)jL`NC!E?GLmCW@EnDZLt7WpD77=MSp7J~xv=FT!5zji zi%aqR!_dx*eDn-J)+eElkGUgOX#sS!t|t`0jjS>j2w{M7Ay}w zkinnyE6cWQS*#5XXR}a3v`zsxuk>Q!%O})R$8^y@y z-_LAB$kL#WtWC|KyxHYXI^S*qYFy74`JLy%ZCDf04#n4#+l0FE8_jm=hPVf+IdZK0 zAocJzFRwuLP1yR*xjqw81J!e|^FOV^i0cQ_g!H5P z=vdoce0Y~fIw2QoW4P7{u|G46XIRx?_eSp0VNYS3a4kT*l00~+U3PqX^*I#VfeBm^ zA$hs&+4~P&x$p54LTkq~Zey@YEwPU-Xc)s|m#P%EYOFi15kl&>$l!19A2+%#Dl7C_ ztO;(Fgp{`N;V$>TFr)hip?_dP?6qNYMlofYJOACk9*ms-MH#F+juM1~R4~vI+r0Rn zE+T=W51t3Zxxuy!eog9~Gi|0l#jy`-g5wITKRWpFk!Po{fom!W5e^f$BtmX|T*s6e zkJz9eQNs9vb;nVgkfc_vXyd^j*|U2w!oCmI9oq!+#L2K4>c2vl5K&PW2eBqN&cp79 zb2wkTx1_Q7xT?a4g9&jQEI<1u``NA}E8erKFsfnQ@wiJ!*2*|me~dG8bsH=Ycs$1| z8A8gR9mW$&+Rz1giVn{vuqJqVtzG>(~rH;4wSn*7j5U0drY!JOnx0a3+)|_}Qisy`kw78wd z4=(RSn|0ppgXia16Fm1N#KS*{XZo3Fp@Us1mW~Nr5+TnLW&Ue>A*o`ua}>|jF^yLi zgcvi*@tnTa()aGs&4q%%wO-QNb+h~a+J$Z2XdJOL&eT(u}Z-#e}U-Vxf;Sm+~UiY

oEmc`K> zbX9t5KDNqhhI8Rs5Q)IeiEQ-3Xnt$|4~F%{G?q<>OS~ty_)?X(xVV>LeKCD_Re*ZY zK3X2!RNLh&{B9WkyuLge`0=W-ZvQ~FL~5*@w`aSAX{Y!=)ip0#HUwA$(IBM~{k5Y3 zf6~H>3bB1X@jMpTSpNTViyWP@R>U8mO+_)?R+t&{2=+Cc6UFVT&T=dR56Kv4hWR7#;S`dlN*LSg; zv0K;|uQ-nN#Wa>ph~?Y>KBkf{8)I36V|_6l@HtSuJfNjKxWqKD;~C6k!gR?#t!LUZ zdO1-28|g#WRGVCsiE&$%4xBS^_bpOJy^Zi+edb2vkVAn;w&~MZxl_K+LL!&9HQ1tYb@uz z&Cp{_@V+msik^;VA#caiv(tKUoC{kk67}P(`I+Ha)aMZ8SYJ$I*@Vn?>&Wl_9!Br& zd&sc9n2szIs#c6`EUU#wgB{nshw%~fo6##L7aIpP2v!3UedLw1R_ihSKnhi@TpG(Y z2E#WR$j!$Cn{x$5RhS%iMlP@&AZ*7iKUKzsFy^oya*rF};q8;)K zPyW^831!oZa;z`Tg=uJs#k=xy@(y~4&0|4Bwq-oU`LstbpFvhie9f; z*60@zs)l`NBsVrq)?<3$!7w$xhm$qVZFkB_BRVu;SURSwWrwR3j?|H74)X&Ue)iq@j=E>)&PqljmX7JVkHgiZ^g6Os zBN&M5UDEjMa>?|0_@{$!pe(ywJGn&l?-Hi%O0`nwIn|MslC6Q*Gr^r7TjVB#ZhfUGedY*#5bKWnJe-WaX~JEaSCwX5KPQ~HW8HCFA;f)TI^S@wHJv#2V-A*% zb;pqpZgRYZc9pY|_L?_Xh*y}#@sW^Lx-f3t`W$tZ?g%jv>yBeEj32e_xy9RWbls+E z!f1e_sA$KzkHdKIY8UDh-P(wyW8LxCMaVgy?)+`XWV&d=c7~;68jo-=r{1aOb3cxw zBi7UqMm0?1Q55<|%cA`8=sEPjvryrL7mtH@ydtE{!c2ZE@Sbj2p|wUV9qW!~AA~&E zl*mgJAEQg!@q%ILn8tGyLfYSS;C3EWe9m9;6=oTj#`7RJAN;h0_3P?mT-0R%$8!-p z%fNFj*tu&poNws%!zZ}MeIu5Rb;q+ou;WoXer~)y_`^RC=1p&nCox4X=z?I@TS}=Lw1T2yFn~gp^ezzNK;nUbX#ZhNWW~ufkwOzjzu;IoOsLD*r)Pb7C5= z^k8*2HH+4DY0GU_d}4TQiS5Al5i-FA_C*IbWcA8dFkuA^m@JnKSdJf`8Q<@4ZVXQk|s}pjewUPQi@6H+aw1>v zRFl58f57%`^-;rDm5|#9Z&2btgsFv}yw$r8+NvbYY_AR)^;X~0bF2bmRB|eJb91AG z!}c?rvdJn;HEk{-&$-=D!6gxLr)z(1%5fe$&P(U# zt9a0)=v*UC88^zvpIgXEseLw44ek3*zu7t41UI%Wr}1_j8q>l7B^geMF4RU{ zf3}2tyLBxWToNJAL94x>Rb9{urzBg&ss3f&>Ajn~Dr0&ks1FS9^ri2V1Y6ik)p-s-^fR2T)OyK{ z)EU8F^kLQ(Dy*HmRpb3Wy3_KDg9M_6S25Ljn5ALoBu91S^9rhZx{%?(EgK;AfsBuB zX41PL1E*jaST@`*8Slic&X%VyYf`?VdmZ(gRY|#Fw@=FA;a`+2wUit=-C7liqCrl) zQvV9{NC*|QN}AY2o&4aFKDl8b6_-Rv?L%R_fvqiFY*~@x7Kd|Tnvmi4!TjZYC;BS4=w`Y8RuzlamhGkIp=_qvjw z4Mw+(e(KK61Le5SZFl|p=BwVjK0v;(bBswm!Ftzz7+-O4ldfEJBZhNbENoDvh`#du z7Nr&OtfZ0IN5?m78x%-sP=WqM1YhBz%=uvndUp$-mkvohh9ekzRJ-oC) z;2m>Jg9p2&^VJiJ&_ny37%mHIDE6q3hQoM?pH_6*68=;i2P)^TH2@=ms>{ zZNw>f|67#dS0$4d+Id)a#rl;I=fZY~M1|SuTsO8Dtz5jeUgxXaX6owW33Blo z3zYh6o2ae-bdndhT@Nv_^@%jT*{ui-xb7|xSgS%=k{UF-x4b^ODG&#y_UCoG{Lr29 zna^;_(xN`8@~AB1Kn=d(gK04RXW=kU#L247D;Z|`T#F7AV&Y@zqte)9E&q8_U9IN$QOVtIEgQdAhq#-&)02;! z{a&|eO(TK8y5Dv!ul5i0ked=MwqO5l&m#xT(XH9-%W(>pf#W0Gx`#-;<4k$_8X`58 zjw7{5m==d~HIC43dn$6Q3C<;2o)_4Y_v`;dN7Mrh*C@^9B_skO^-_q`0S*rsj?Q={gXIyD1Ebnt7}Y+(sD?*KJTi!5RDT$qcf;sRVRXhL z@}{!gRDSTCKHAT21MX>rJce1uE|_KLVU~gCJ9w5MTHblcR@SyyU3$)@7mtY9qEOk| z;Cx)KUTV5X$+(njNNm$WWy@og>%Q|0iyZ^N=au^$W`SAGwCtP|fp~Lvv2y3oX@m7y zPk|=nO5ek54iH;ri^RpKHA?4t*9?bMcNNpHClfS{^=c47PX+hoSbAM=OXW!)YIr>{ zQq6oCqty8BVmMSK478f;uCNCsThfZ#k~vPADyO@T(zVWalJlcsKz7@-HS-7S} zpU<`8Eaqfk$;}WT$iPI^2C5=CS2kQe;scg{h%L;2ENn^#nxZ*QxtIG)v9c&_c;ngR zuenbi5RVo$rNe>1x$ulk)M`6e{-?MV{Rx(1YjF=2Ex+GfVTDVzq$jr~3m(M&z&622 z_4)ox?L3OkwC~G9g4!x$iY_u_l?o8NhFc{e{Vlt*u@>X$Y3sfmr|cTMKpDC!&v4|H zr;1C0vx%yyZ1{w9`q8tWAY*CpTT|6C{sz0pkt%Lugp^cMS=^Ulba|D29OnwNE~2Dx zZv(mVH{qPvodp&fMwfZ_yk8}}Y;*qlNl-Qa!vi@szwZYrl z%Dz?=OrVgDFIhKxX z5@l>CwTd&s9>7oTqYG=_icN=cX3s?DcgTR#6hhD2E|6)LvQsa;ft#6_Mz<={)-~`UbUn z9L90V_^;*E{XSlDhe?H1Jfad(p<^~{vF#`w-Y14*3$f)QA$Ob2h6LTGgNJtz?7%W` zNpM%~pu}4&zDPq|EjXU<3|!`>W=!ZJS3J2usS@j^HuLBrFE6tQEWf&;K98BG(At9> zc=i2t)k0q*DgAhn+qwslJ8#%jGwfR-8}kRI81B zWVcuD3Z7-cnzK%I-td{PG<)m-hI8RrrbvAAwB=0=jifV;j|v2yWnvn>I818En>IW| zk1zVl8u_@ZSp&PtMGMVTux~I8H)YGrVFPA#l#VREB+Op1hPWhHpM%fi7ha^znp$w2 zf_;wV!Ofai^V!@x{iSrfJH{EcVVzlcu)N=6!Mc}M^s0UE068h>Io;fiK(^IPvULda2^Iu|`}jp0{Cb;V$Rg zU~YI-PFfP%Q&@B2aOyk-pV zo&AbVI6s8ql>OXSjh;I|p7CV99+w2IJ>7}>Z`4am+!yL_o#48{G~C(lwwpCL*Gnoj z`i2gtV0pMC_o$;)X z+$g!JA?iF;&+Y0ZzvxX3Z+F7$7mJeRTU|$ijN=jOSkl4vQr(JIC{Dqe;F1Wb)wmG9 zeX_YUXy{jgIDXGlRhB2ohklIv%Z`nwb-et;T2l6+(bSY6srTY~%X3nj2wI6U3jg-u z%^KK9bxKbc?7%+9CBdBuj}~mavq4H7UPtQLzP1`OJydSf?zREfRkpsNx^H^4{L9q{ zmb*8Z&Q49JAO%JFOQEJ(YLP*K^6Uyv47EC1tF4v=$bF7IH{g;8@tIPEzj%M19(HLe z;j%C-53QSw)Z4G(YqO$7D#h$WFSqu5r=HjYnEf+cVqLmCc=%hN_ z>rns=8LOAJ}FGX^;5{gMtza!53hr~FyNA4 zjq~CbJGtZu{WKv^!ewDvBn~dy#2o)&G;CTY32V~q=?CT76l*!EY7H6Nr+ve_f<=N> zOF=8_1FRL6M@X^q?z~#yEjpojSqZmr+;*{VV3tvv@&lu5NilOq3(*I+KHMtdZmltt zr?sk2>u#(ljo4pX4J%htZuI1{;Yx&$x@2VuIeO(rLy^buo=lJT`nhrUz~}cPJMijq zbsBW2kc4x2!*^v1VE@~3`+>iR^*~ewV%=ZF{GDNH!t1yCq{rI~m?k6!ZVt5C+<+dM zU5lQ7AF8^-S;6H2jST)>6Vy=Oclw1_f9Rct#H)67-|5!|RtBw-kEZdt-y73Y;iUuu zudr7?OjKP5zSF1JZil$r0c3=Lj5{C$r(hXaHnjH68N5h}Gfi#u*aw&UBe$z6XTQ_0 zzE??~eWa@zzvG?0_AWb+u^))%$b$9&TUfr|pt-is6bf_!4jXinwFgH4=+ZHOMyopptC%@Id?7mF! zzxHiL8gC1AHGZb(k20;})P;ZE>I-*hYDlOWr*{4NR`2)P17zH_>&1OGI?*Kuwosgc z-Ra-AMj= zB2nc?55DDr1+7{wN6-pei^pKNlL~fB8n#k*9qhm<*bY&~h~gvo;NuRuzH^uAa0FCJ)>;)DPo(LcZ$u z6ssl>_yTBhC8}o;kpX;7H@DOHwI1=I5MaTe% z)T1C$r$VI0V-$|mBJl`jOU+=mL}9i>(1?s@OQKfoU~~?G(b;ZJEsAGFcytym&zmOk zXKgCc_Xp}qcy@HiEC&`tP>)CDQ~H8Uux(wEmFP~S5mo9EWnU( zAOeW8cb72VM=j{D=6xiba9`R{s5I0ct0lmy2B%UDcV9bI~{w}dspxiC%0?@lE+dE!QO z!EFSeTa0+FY;m+Q{J7slKL6~2@~BH`!;?>Lpw(9(y#5D)=M0#JbDYv&**Bd7jdSWK z$iS8xxFr`#Og^BPH8rCtY>!vUm(5k>s=Ox1uzzUDd!8*#_k~1DI0er*a7nNaSM?=xzEF~u93C&> za&a!)ZwR@)>K5zav71s|lqA$5YLy~U)Aaz0>E=XF97&aM8^yJN>kYn%OG;%YVu#U4 z$9~d;UvErycl`{*UWn}#w`16+P9Df6&L2j@#`KjU*345b4mo3})whMvKXB`T^N-CD zY@gE<`et8WpxadGJ!mKdCG}C5;yG z?I*~|C5t$n zP2XHi5C}XM#VrQ*^lvO@-g(>UKQj`A*(;VIuC|B1JY=+=dXFZJ=_<4LN*4SD^yEBlK@%Kd9(>#r4!FsU^XWnJ6_eS7B_rc3ULKnw@s z01&ocD((J#xsiV2;Rm|DE#l?+=RD-o3&PY(76FD=sorwLg9z1j#!^_<4glg95T}cg zJ(!r&p`je{T2kknK4_Ttvax)^)lc2Le+{e$hXIiT#MD;lf{dM|%gD_ySgUsvtmQqg zYRQY=G*;Jr`vC;JJS^=2V&rXl)(49$a)mpch|{J!|nP_(CoI^(FD+`B4~ zXErXSdRaGuR-*Z1FA$|qba2O7;hKKrcF7Ro_(0h{%eR2g{4w-?suEnbQ$_-50x1G~>{3li=1YVn# z;AL)Uee&*ImQ^P5(JklbZ|>@Z>qjlT=%e95kcFDLz8Mf&|2POl)#4qpv2PD__mo$K zhpU;n9ty4zxE&3I)(00vFLKBI0Q+1d#sjef2wOL==D6Om2SuVT5O!espD>GkxKH33 z#WfB4B|uyN8Bh227Fs(#qs28%NCprLh?CaMcH>&aXX&`s|7(efyYqJ9NM>u<#&CCu zzcMhhNWXVoRUxQf~?5Smt+KeYaV zi4sGb%OihCB{PVnh8uIYbc$rX?>YRbwzxJL2)0$dWD;}mH1#QVNGPPy3o zx89U~$W$~eK_vO;4Y||Nj@;ot7SO!}X457T8b!68k}`eThmlOyIp~yhr|T zY&ZT7e@tjoPv&;sYHav91$&bat+j6hV&M^gckHQOOX|rj)4kOumGTtq*?(nd5$<^7 z=-qgnz%fzu$K0BJQtzn_()62eJ+U2l|64rAG55g@JzKhC0-s=tr)241ho;rDxutev z0-wa$jk_+#~tzowNTkhU! zr`~%{M^z*yLtPDnx-$4Xcwjs5>;<=&e|xQF$CQS4?zlDJITbDmPBXxcAc$ARCluO) zeY<<}EJM_-*^0HHz3SLzreUmMmhyB}duY283R+3y{*gjtaQl73@KN_d`7=pUi&Q>j zc$#%u*_jm##H<<+;Xp>0v-9@iwuDA#lPAbguUZW(yw z6k7@WriBE*(;!Xi({2~`Gj1iK3~iox6o}bj@q(z@som||oZ*eQZ zzRCaH3~4P8nXk^c;}IEqQ}m#D2GF>N<8JIVe6}sxVJ7My@ZXIi06sq#iR)lTFlcq7 z?luqX1MESO&}67UWUoE98`nF|CB%86jZwRS2pN5>8LmYfsWJWEXmG38rEEOM!97Z> zU2Wd3%>de04c~>W#Zgq0F$f6F=WRQ-+JooL_?{HD@4tTTG<0M$90Bm0LDb5;VwrTL zbu%1aagP$U%Cq&8W>0jGCX9aTiT#XQqDYuq`;0?Q!b}Ehf;EJ%Wm6K2h0o{c>WmvM z1=t^x9zoS!a4x?tuQ->sT3=1UDcizc+4+ z97*|?LBh_&g0KV6{GX0BzH1UzR z`+--fSRTBFxS$$+u%%uOtDPy~Ip<37AZ4gkrk3Ok!VN<_t2{NYPJ+dZ~Xa)b`R2MK%!YNoDE{TvSosJvN^hz^! z4H+)Tz-vG(544(E+&ICzCcSqfL&9Dglo!e!#d`Nk6bQUFz%(J*w(}1*cfZXBuS}9~S$*$h8M;=Os~ld`UY@mo zwjs9o5+&gs{4x#sbH6N|=-|OR1g8lE-kI3DWRRivtqdh4Efxq%!xrPYcFS30WPhne zy--8k>JX*qg3dC|g=zRYGqwtgrkz-9%^?y_!9K?&!Op~@bCfoJse89QS;FOFJFtCl zZqUg_$2OMd(Jdn-Jky`^{DR?Sm#4};_}!ny^p)X*Ttsc7HU~Re0>S?W(Rsef5SVmM zdF2)?V;b)JgarAN4!+7R6-kk>53n~e4f~0XpXkq|!^THRaS~3!8sd`RY~pr#DJjU0 z?VS}WVSVw61=H|Sh`qh80dwcI3pJBsR=+d+ylbhx{^cf5>}DnRXk?=njkT8X`V;QS z^v=~iJk*e{Y~n596ue@^CBcgR#YL(=XUPM{PzjfdR&;;K=nKD2k+fwS+t{R?gv-Tt zh%!d4{Y?D>F0fHg{RPW$E={9(92vxZ{(76O)UL`z=3U>1W<C{K}Zjv2-j?l<_lgk}kkwIa{@}KgaX7tRrg-tw!!pe(a4@Pam9ZcvX6dviVLs zuw(q`VRYQ_87!)OFOFw@Hza28T6#w5QanV(G$9Lbmyr^ymSLn%gg{`+qbi&=*sZv) zwB6zdGOph&BkiqQhRp#2=j!Tw&G35pYbD1+uiA{cXc$=SnR3Ek2I2=0x9!WY*+AeF zTrMsN&OhA7P+npWJ69u#<6PJdY#;2cwJJk(hD8O_wUK zXEnz4#Gu=i7{8%oSBtJo)Ndl@tP?loSKCbQD;ox5Y9P=m|R5T$Xa&MMA@Y53~5RxjOc zeGr?nES=*Nq25qQaPku@8z<_1>2|YBj#ou^9lgEgG3kI+QK|itIM8bT1uwR;#}D1% zgK0eZylg5OWYlMFjaBhFN+^j;UesN;ve7`gr14OW%k4SWM{l(?i??W$po%hbmv+}( zX*`gQ|BIM@tc`wYnZvy6m;@Em(AqsL=>C@*bmP8c2(^2w z^!Lnx!uL4B-r}?@(~Ok2`WMGLfL2%Sej4o>?AA>#nJLun+RP}^`&GyE%X|I3zgs%b zi#ftKqvdkaI4&3a1N#a3U~fk@<{wweb`9mY+@(kpToSxoAL7S)e2%AM?}8mDSN*+2 zNpxvpIP2I(#XEY0Y}wtNP1~DJ8GKiSbKx(ML?XUM3`^Ku)5p;!o#WPkbr;*!EAV+1 z_&kWqywuT_R}FZt5AOlO8;y3YsdrL1 zAJL+Wgj0(DQ$_Y|=d2c6SW?C%K};k4=2wBxczB#a^I^=K`oU26*yiRi#bmU=+ zr&65K@tp`TByBiUyK@Z)zAa&St$uPx-mac$I!^s^T(3BEWS&`MGsmf;bjn^Rma zKCg@M_LLWdN2oLYl!e;ueR(#mX6nH`D~zW_PBfDbGz(LIK4@>ixiAfDgRqNqNZW@dwh3zsy9P~f(mACQ`LdpRmUyy-T)lo9wb7B~ zCf{}L@+_Zlb!cLwg7?ngjg(5hQo_-)yhYJ94ClhTY9cXi@JE{RG@g&N>XdWyOAEON z)aZ|1-*T`#e0l~W&XPLPp)mnGwVSUGPQgCFCBdt8eSD-1hI-sSuP(#VF^%QHi*gg4 zq*c5c&&hqo@QyG(b!gemMLyEqPo1=S6Py+8|8bP&H1yyH7FXhbCOFDJsgL^cYo0Oz zoo3*Y2)SW*nOb#k$Ilkp#dZ~Ump_aMQzK$JD!5!M58mbc>MdopuEdS?cQah0`)a$( zw|U@oO0_3)3QzYEx2jDe;RXj&3B(^zlhd?t)74jAxE& z`}$>ItgX1=2_2tQmM{IM3CAfYCjNC2*J_QcRN}z{R?(&c$K~R>(id`&N9tOr<@el% z+O<7?jh4D2^T{i}Gn@<8bcT0bIew>?+O)(~AeI7g?6%Bb0D)6*xws@k!hWxz1DAXA zpjy>A&V_Bl+Wr^YpSSnm*jg0Z|FV4M`{Q)!<3P@?d}Y|r*bcFk?EmI1t%#_^+u83H zdKC6K_9l#+5U(0Ry!z2NF-M3|sCVJM0&kuTxK7(H?8sX!m`ZUx$MFNl6+*UOZ6O7^ z6yqBg-J^Jv!Lb&{VE6^%ePeYmHwE*jW32P*YVaaSU7LMN(dzBQfLdx|=^84oY1pBk z){4G!4dJuTR}k72_KilHOM=~xsaE&r7DI)TwAt z@7}zoV1Hmg!CMx4T@GC5UJpJlYMmehw?r%t-e;KEn~sM2weQ-t z6yiCK&R8D2Aq4MC);^fTBOJLPL(65ZT`^wWnAL@rb?U*RI<6Caf0ehcw_W`x^?gaIIYPOkexIAa=>{((SLsx<;de`MoaI{~yAfOC!v(3Ay|xfqt$U zz`KxY!n_^l(*8HsI=o0~-N#>P`kN61cQu)ZfS}W*>;ec_1{)`-fQM z6Ib6R|6i;%`#>YiG`!_qva#{|>`Wdw$ui$^b6sg#ndyDgk4ob#yXBVzv!zmvjaH#O zd5Cf-pD@=IvP01b$IhM9RZ~*HgIhpG0U_9dYe6I6R;5~J`CYI)2xNQ%tpX-l3U(kF z1|$QB5L0({#(D_%s#BPulzdIhy3c)-s%+law!n_gKq!7me4onli2~_@?i!(+6s}fV z+aB!b3PhhAf8OUnRj$dRAh`x}!7f@QR*FByo z4JOF>gqhZey>Zpl*54|^d{@(I2WWIi(+mioy6Fo4(mtOs(;88>{B`A{mpc#%Kx_v> z^-GeF3>nd~M(mJMmCJU)5KB`2(<+}R&?KKIkdaRm$N)mKqxZj-=M!d6X)??-vIB^Y zKorz2)p8ZIhJ3G?X^kkTEAU_p5U2n3U_N2?8m2X(z#l-^#av_^J|yv07}bc_7tWy;(Mf}I{PI74>|y$mEZ4-r-X6|KG2AW+FWV; z*am911`t~LK;;wWTEsMx0fbgpO~LZvEwibX%Up}v|7IH50k!K4L_4V6@462tr3<1 zmz5T2rwe3U1_Id(73ti$JDqK4Gp!Ol!o4 zxIIcxuOJ1!)C1xrS@`Pq4|WlHDFpJ3j9%^l~zylOdE7sE_2J!{x{PaQQ&jf zvkc+gxk}EmVU{sQlw#8UH@BsEqY~7-_t6FIDj0~=M<({*lr2Nj6-;Zya@Po@U;8j< zS1o}!vU&|;&4%X_=GK5|jrba;Q#?ByEg%j;ZjI7%nOlSQznRvEG1qOB=XxszW*H#k z5opvCG}CgKTLY#wqQ}%{rnsXGfY9t10ahOc>$O}3ts&nIGp!Ll?@TgT&X)=Zs3)CL zKvW6ctk+r`rZqw8C#3zE~NUW25Z)sl85VWvR0FuQFL1+EpM@D;`vMzgQ)) zvyVW-*W@>sFz#y2j?d}KaapTgrzuL%6jQ0GtyFCkHOq##smi3XT~Dl7*1o~QtPkg! z_#joOx38}0kwpY(b>mk8v+Puud1VdZI7OQ+X+F1I9-lvFG|wMFM&Jk5`Tm2Pehvxw zohBM?J?WHcj6vFP02Z+AXc0KjSc$1h1-i*W{g@*Ri%oJ@YL$ zmwR{1FJ*OHg3@APJr$P(=jS1|ynDhzmQ}ZfKxkT-eKWZmQ5#f@P)4wNpjE5tw*2b8 zDE2$vAb7CK0-`z<4^%e$JF6n`W0XCA=`fj91j}&>)(Y1GA^&V!!8*+QhrN05Z~rjQ zcc+KtC>L@%DW~6itGKVg8RUrl?0ofX)}(W%{2pZ{R~p<8qT)&oMs~z zaW?Z)TY;Ff=bCaaVwlq7ToV=3gt&ft&#oH}FsI64f(NJ1eyTi+%2ZA_c2O}6@6bnH zVh8&kX8|Q5IZn~~pjkuQ7T~+oKui9;^)7bSI#7_Y;GgHp?;07(l2r{=EDyfUB=2<# ztSx!OtoD+&mX)GkDxJ&t3pexd%{oG=cPOK4@1DnM?(Qz!xx+WXa7l!`jl6Eu<*j2q zTlW>#gZQ=~zJ&-cdCqHWd|x+@y;#{@AaJ?(78*n!ziBz`SKepNW4cK=19Ss~L5cmcirU|JDL?a-M{6*jz#WW%9hEFy=N&BUH**7y^ zh8C9~Itw>&@%=kO7T2!92dDb!@`{H_C@$r%KMG=^jK9K%FETSr@bC_YbdJ;8Nhos4 z`1^d3xLw(vFMF%%Zk+R#a0-4M2+M}ozd!r)38km$>POd+wDDEbM4JiYT;i)ky|?T6 z^zCbP_IfA54*Z&tNQAjlKI?onCKq+emtmgo;9U4U2tqmmvHM&#rqc-YDwFVn1ZZn6 z34Yhot2YmNQJiiYzLjcoga4aHp?59ti%`(d)1!FLJ7Z{It6%x^5_4Jj^$Ywe2D};p zMC9Eu^!;B1eo;)INyAFr`Q*w&eKMC`ptvlop;qf=*|0XKHk8jU>Q5&N${aU@*xi+1yi+mf)VD|ZG74IW@LMwY zWp>!pFPh4yx)R#B%MpfCkk=ICO$ENf&g#n(%NC{K7gh=~uub^Qb-33DzdhiRS)0~B zD!#^!f5%3YvAuabpAi>An>D+~uqOD0dHlN|aKC+W2ya>EuI|;IY89&;#%^zzE;-E0o!@ukTyJ{yI@o!eobYX}7onL8$He;tr*pVUnb{`GZ!*z9yD@ zyAjQ*-(7f5AHS6TV_cfzTV|3z>rOZjE_s}}cc@7h+N5$^F4jbRTfJZO3D#nEH9F2W zh2yd?EfRIczhjfmpVd|IiWls_y5kxlmNTnmg1C>On^ z>l>7e1Y+Uc`D|)$51I(C%HtG#YZBk4gtj|kF$)>*L$|l;BM?{yrr`!e&nfKgJqKFt zdVk?&=H@Bk%6q5Ddi&v#DwYkS+O-9YT(hT!+oD$3T3ie8`?aUWvwIh9=)T+mf((3j z^e7KjI$Dp`H+rO5-Ya$_J9e!yt@M2$$0=AV(ejrkGFgRlk90qx2XpVAfy$z}Df-}m zHY%pEJc!hN2eERxUAi4(hQQo9Q0aRvSZ~N^qhcE0hb5$KiH@v!Hu144k}lko#dlJ1 zN$^WFi`uZe#oFr5!fR>H9fOs#VLzl}bK0ml7rxyJvE*nsrlbtZdDu6N;}!O%uN@R? zYRz|Uj#PQ!)=KnT_%bHC4b;^&`(##izN*Q5cbYYr+)6^Lc=>wU(@Kxb{z^5{Tt4>wo|1JWQyJZ$u?&5%qKU0q zzMBQ;Vg&;2!^tP^98j9fiB*2~_W@#D?ai$E=#7kwPmplRvquM%m}RlbjlMp@IUd~c z`fOr1YVBcF-o;2b7uE`E3+J`omsmvZ5tg|vQo{P8-H5+rv^rwTqpL1t4yQcxS6&6X zL;0r}=5vZ0E&eE<@5d-}X4C^a7B#Wu?+OiK(;iU?r_em2eu@oL!s*0SuxL+ zuRpes-8=iQ40E|QO@AncM=46NYxQJY63mc)SLYRTx3NxZMFQIqIOdaL*fc=tbkiBM zDjrjf@66l7zJz;9I0ehl=8R_9aFd+>Vt1zQWhvu>^H;*=Gt+^vQ~2rs(RG#KRU}P! zf&>pvumpDrZpodw_W}tJA_Pl-1Px9C1b26L*TrRVb|JSrJ-EBOJBuz3UvG^o;RW(@TUrwdZAD-0A zY>)j#qY@>YSQBM8-ua!SS+gpBS@I~wYA~?JEz#{!yM#O;)tzq&UlQqC6iyg-*q3B9 zD3p%>NY%zwzN>0yKy49CHst)fSn@Kt^joF6D!C0OeIG5hZ0u*R5gz2+(66s};WxqF zIc*5Zm|A2p8^fyWeaple_y+SCVwObmi2r8xC(2L} z`)1!{8$V~%OYd&0u)>UcSd*rGCd5iYcoPCkVYWXNv3&9iw(Q|v+pQ_BmDcU_`Jgy{ zW-MQ~-S|hw#S}x*@IbQS6eKGS){9mgIDb%Eb)EQul^VRpRwi#t1M5X5Sd*qb&*{%% zK7O+GtCD0RlcyqSjlyWq3Z?6axA%(JXU}a&GLp}3%j$--^xHY3zkzT5T-8Lpe4CZc zpd5s9HLz;ZwDXH1*yEe2_C6{)KtZ4kjQXb;Zdec2#(S1+SB`#4J^+1mfY{1g*!@~H zbfRpEP$<=peLH!^CO-F35QUo874@F=x0lS^(1~bGtG2&C+cZ73zVC5w12YA*o>E^# ztR7>}vn|YtXz~QyJD3%pn@*oSskeb|kUQ2ycG0_I+1W?A^?du{jD(^M#P#sW_8fYc z6J@A~W*KI)8R;wPt&Vh8SYciRtckwb;fvYwCU*V((HJFPAATRLMudw`e7ZgF9GS!P zK%0$hZyG=STGy^h*3;m-okji%z7+4CqV|GD`uU)c`ZG7*mZ*CB4pte{F(VF(UbbFS~mW)jg z?Q6h(M;U!ZZ_zE;#XJdVPD?!wMR#It&K`6nOW7|GVU5w3AuVE?f@*Wsij3mi%rLP!Xe7{TH~+D!aneALjJ;mB;#4fWvtGHGAw(ASOec| z$um=weUwT>FRz=pI$Jeq+U(LL*zD7(*@9vN6dA|_}^3p1iJE!By*0Sc2zjHXdu5RGS)1j#8(K$cq zk@<8*7WO)T-|Lb~LCBW2Jht3Zez6aAR5$YsPeX{~#fr1}r~P@*wmb&D$vgO~{Y$ed z<{L+b#J;g)lXqLIRBZD!C-;9)(7;l*KinL*`&TlLZ_fA+MB8PjU1`Zr=6ys-152SE zlHo5IowucDyZZ<8G8M8W>S1x8o++8*{5W58CBEOu?$5>S0nZt7&)wLzR z68i{oGbF>OSg1a2ZaKdFZux&9(4X4!#@4i@Q^WLIqf7Ikb(NK@5o_K(bF5sK#|#cE zOXb$R>*eNuEUIIiTy@s*`dJQhV)>FzL}PXjim6`q+SXxq zMn3mY0|T>;!1>JCHHFLZadb|z>5P)pAD_Ka*_s#dtK#-E$mbk(W6jUvX#N zD{CEDUgtKG@04c)mzZjskTE--8xdmQ8>|=Qk$?N}3a$f_JbBiXstg=`D39#B^X}Vj zHq6LfWy1`t7h3`KBRgE?5Zk-U8F_`MhDzQKEQM$~73FBF&#LLg*I#oeeU2@PEloaN z#Tx5rU+3n|ZM6*SH5?^s59UgrRWH7}2`@0yU71UyFSzCZpXS<9$AXl;W>le6)VjIL zw$V#w_viX|Por_?{7DA$b#T%Sj8l`*DYH&W%Gco?ddQ-W?b;ruv z#mz$ZJ)Kw+<))faTlW|p$bYYqRgv-W)gg!NQ8{z?y-bQcI&_`MaHe{ z4;*El6f)D~$m>LT^hfC8dG%Ql4S7_ybOzRo+F~ncl(sHNx96uQB?e1kGjwx(U@wQUQ{%>4HpVG07H;xSsDZbpyPwyh(?qJJQe6{2ZQbY|Bd z{pQI7uhdf_?|TQ|aD2a)gZ^$^!bG-oqVMdd_v+@!(|o9-Aad-w?`X8Z)4X}On2Bie z#Yt967ZW`Bl=zCjtP=6l}M)=xhz z%y0IvDH&*{eR%3 zSTQYhKR6{!KQOyAuf3o$$5M#C`tg}##DP5K$8v>8kBv1N=xc_T;mgic;`jzN$C}6s z>0q$F`g(ajad$Z-x@O%CSbgH`g zr9X@FwO6Yvtgx++p{6;W>~(d%<<0jt58!guw``NUHZ^x#s#(N*GoyfchKD=GE-GS{ zts?(l+q%1tYuiIl-s3=!g1`};igp>#{k_evJ&O^dKFj3lb1pkC-#Ucj8W?cbJ{I{!q8 zm4O|SSWu<3qkSQ}x&6D01z4Z*Z2X|eaeRaFkRjd5*q*u` zt_tHL7S3Z*p>O?Qyt zIa&2AwK;#_orw6kqc@+A&>T~eS2o9e^Dt8Znj*ulPjU5IScJD~?^F;tGX7ZNbo8rH z+>Gq+O`4DCKi9RkLRmgxMGcN`%1!ohv_DhQJTW7WDK)obQx1rIn_chi)%cB8~DWKCbz6? zZb?XQVoelTJfej@s$kQCn;)iTI`YlR3e<*K>c~Wo1r| zt%x(6iWo|>=lTk~ij&< zXIt);iqdY$MY|^g!)oSn{cO>b?WjRbFK@J@$pmiIfcrRh?!Zh!SL&<=y8qzub% zQPYl)ZD};wmNc?0p)C|`OA=w(oM%?xN` zpd}t{y{bjHt!Hljp>tE$!moh_TII2ndT+3i?hW#esX?|Mr-8RUcyECB6qE@e;Ts!H zcPz>1js@?d@Qy{jF}X3}sO`|>H2j)R6D0>7?h~Q^={wIb&BxVx^eMLTKqn=q6PA*# z`)joKrQ6r#KW|_0#ue{8p$ADu+Wkjd@4DZ%jjS|SxkZLv`$x_*j~(mSLh?w-OCBlc zS%DrY=&3??sjptM>&su+-py~x(bFFK!$jX7+VzDc<5ki=w>4|gjHBlfmO`|q)g(`+ z8|3L!jy#>v&k8-ApwCJ3RU#Q5b)o?8Q$9OKzb-_pK3MAGW2d!{K$U! zCz5yDALOOCgS_;Pke42M8S|ExWU}9bf4`| zcNKxYgZWRjG3$4KZQod8TLQHeA&M>AXKNFC!i8@TF~q%{nQs1TySP_~5VZ)=m=M=u zPPp(5BJkg-lo4q65bic%zwPjkM}GJQ5$YdSy$R8D{C?ZIG>`qzI}%GFI?2znCiz)* zBtJ{^z(hYw714?OMRStBsM}L79sNSlmlIl-=Jr&}V)({K8T4_18 z(tB;w~7OZc~ppJO)>VU>~yE2j3}h@am_ zJeHEr*0-V}WYn*WVogc0mVmG$LeA}03}#YvW(>u1o}_qASqi@o>l>5^D^fEl%5;BH z)NdjJzYhy75mq#45`t6I@4nwwB_id=Qv_#0~q-b&($(n%>B!htrWwc9#=P-&8n4g_i9Y*QBy*DHf?8Mhi7bU9(LzfZR;+ar zg8G8R6G|d*BwA>Rup+XP5Iu>}8Db_8)_6sAF$Qr37yv_$+ISG0%g zO;PbO6T)v4;|_1^^4S`%a#gcp-;-kX=TaQ~R*Its>4|$0YrIN?6(OG#c|V3?^^?Ci zkchBG9HJ${is4U+?*B&l07g!x{~MPR!LHYm)I4Nvt;h%+CN! zl(7Ud2q7~eq$CkMPqjES?xlHB`PxjK?E zg~*I2J1Or6NKZsqV@V>cj2;xRPBLWfl5><>L?W!wfM|)Blazsm_S7=t$r;LDa)$Dk z$Wqp5K(s{s%zome+*DEqA*38AmDtZe(TO=(enl@!89!MuV3LTi`T%55pIaGEWUd#9 zuv!t(pa=E2%&KyXTK5y>laZyY7Dco~SearptpMe$kr{zX>u(ctq*$#eOIdv&_lZ_6 z8;V6HL`BMr)0^_*fb_)7Ef!iLtb931GI~?)oq3ddM!0?ncPK7>+y zQV}f?KXVIFf5?nLvkB3QRx5%Y|Hx)liV#hybxZ1R6Z896EsAI6ZtZ`3Z6B_ga=gnIvx`Kv7zb(1{Q~StTMc)0EZE z67kF8)#aDwiHM)tCia?z20f_Ht*l(sx{3L(te%3lO3Z&|-63gO1j#r~S-Ao!ubM1n z^_qOP&{D>)Y;TV!+ndbY)`oJo!JEWhv-(+{Ypv{Z;(5n(YwG{~UYM`jUhO1bpfQ!YJe!M1YdL8-*teZTa8 zEP_gQN{P07CV&;q)W=Cieai4R`<0qS5abDvN35(2f6`KMs=AZRj{2|=HQs|$G{;=ey z?^%d9JzU-R>&GaDd;_1(6uIZSiNBBeJ4-*?CPul{7T)nTVs&9=06*%H+ju*>ypDVk zeW2!c;qdbpFIww_SlY$lS?+DttMAXOutKz3Y!j*5*AthU8-$o&t|A{xeuJmq6xaVu9WQnlZ!Fpk@pU4T!i#o@dS?T~n+j5o z&FRbW=bI`UWB$ymV=2^DMWn6c%i{;R8I#jL)sZivQ8s0V`Bs|GW-#ABfV>Wo5Bjw&hID0*w!)P%^`{KE1HVe z-nh^8XPR&&1`BnHNjM=M#da4B-buvto@sfpYV@xL?qQ&Gk zMMT`u8y2Z&pmd)bcf_L5zGC&Ovd#uIpNXJNeZ=Ho8Bz6R-&^*ZcYnP}lW+s2Bf9L+ zXF~kwE7G)pZHZIxfPFi<+83vGHPs<-Jcsz*yinTE-DqY)0a{X-K4vGLe5 z5q4yN_|&Yl6YnF*LO(SbkC{`G-Pu71D1|X!D&k1 zF76>tWS5AP8#JCQqBcvxn=0{Ys8dS+_u|!>o}%Y>=_xzOH-g;@&8X*_*VjPl$h}0x zPh!u=_M%H|i5QkOnw_<$(2s@mHSkS}PoKn*E$u~$awVKt6W!fST+S--eSW(y_cV|% zmO?Z|{r+~A#Vlm5@p(HM$QRM+JAW2OdUOzDydX0d=u9fM~LPxi#w6Y(h;A;zE{zrbybPjvUnsr^<|E7i zR3p};X$fm*oC>+0Rbn6me~2p-yu{@YjFiRcj}HIoGehzVU}TRo$H;{@%F zV%z@+S3CzW>Jw{{5r@9E@^vP#@0I!(3kQD}r)HHB4ceA+A`|EH?_y$_05PPWl+k=z z8umE%2-c!PZv&+x0&9|S!b@1x^f;DcQx{|QFwMM8(W@JSN;na{zu6Cw&cBo>5G`XZ zzyEl`X60zfV)nH#>g6O2uap#fLrN*plIRUVS+lFXWygm!V}&O*Gw=<{!5;aSJ;_&c56X512se$D4XuKTa04MeCDwCOS&kUBYM}Izr~^WuL+eZ z$yM#es>dwZlu#Dp7G+>8Dn^#7nx9{^Snqwti>Dq_UC}&Z`a3bI>W_rv%*WYn&MlG6 zoRv^xq5PNWg--59pOZd(jYQ6I?Th~6AZMz$- zAZkV46z?j>B(!K>{U1@k6VI4T>lwkGbZ&28DU6UsA06_>9rRJ3ldl%Pu=kRFc*!|2 zG~PF1a|T~0a?h0hnz$A_Fk!T3HDdL5>Mr`V0wsBov{ek`iwLZV{zmIP&GqH{3wHf$ zYlRh}BafaJ6~9(VNH$;Y6F>ae%_3{mWaqARQoN8*57dv&Y9HR|d&`i&=)k3l9%a~B zu_v2f!s@UZ&d(Lsig^{r7_GL{BpHLpopDc;s{s(QR$ z(?d_~tj=Ro6*Z7AmO?Z|*JSs1t?>HF?)8l_`lh`|D_PlupliNPM3>*NRur#0-MD(Y zHn9@>=dq)|hcVB2F^2p5b)s1IHO8e_e<#M*qAwQx#dX_KmMz-G+RcnnB63k4)HdrptF0fo}yz^FMG^t zDI?pg>H2RAd-6#Wv*{=uxvPk+zPJ1i#nj+8>iZZd9nlN_h!bN!$JyPUN>=06^^=0h(_JZx!yna=l2fgH~v1;TcoNv%bK`6vp$ahzzg7 z^xspL=L2o!dCDD)MXw4Y>`QkAE82eD*+MifGQsX$QMPW+vEB8M$O`<$h%y{C#I{lq z)waL$TXSa!-%)O-3pGSE%GR{ffqv}lf(D%Xrc?AlbkpTc#iWhH>?KmmsNdP|7O^jG zL)l%QE=u$=w!)o+aN&43#y+jAjF9fy;i>J$-n@KSKph_Ys-cM3F~J^iFUVQMJxJsW z9Bc2{KiJtKW2hJwJ;ct6$^J;$&dHLm>diYnYQ#`Fa#s<0<^A-x^k81x?~#tu5q-6N znAlxnpnX!D)MMh-{cOnH!L0wrwn|JjqU&A?6CeFY+IMV~dOSRq)3rB8D*j22;K=>% z@jAjeV7R^BonYtS%t7LoXCHgbZc>jU#~!hf+Z*yMf2?OH9l5KB4jc3Hs6Q+43~jdP zC>_x~Plt#nf5zFpw@5t}(LV9S!-mYgeT0FL@EF~VHIbkGnDQ)O`cXFhZhOjEQ(LU* z+rvJ(N{I7uzCh6?V`uxRbs_)I!@sHzzx;bP?zQ3$L+QvJ(G;myD4cK3_l~6=JV2km zFhtbJG1$J@EzF7NnO?zSddp7s0r#aI!&+tLgZF4`l^&|(13;ayCW=IIo6Kf^k7H(+ z7=C1CE%9SU6Z`tXAxyw18{6AFRdpgn-3Gkw=ZS2FaN{T)xg(lvORM_u_fP7u zR9kB3g*pU@I{RYn<7$RE5q;)eebFLs6Z`f2a+Hk9>BVDiu8ZH8v7UiB5-`UB)4RNOaP*2?5T-4s9bf}^e{qx1Y88?0$^Xs=TB}eJV z9ns{0eS9E)H-4I}s#a3J`FEh`TRy^`W>lCH(P!rciPrmy+uOF0dh}%8RNXZ1?@wB#`yrK3(ac7}*gOJa@9Veo-H{kofEY-KPd(V(BmO`|q6kqCk?)EHhAL9yhA{s5}be9^K zii+-R%h=Fg={*7MjnwH~jC!T5IG<{-+**Z!` z1lB~hzN&3`)-p@=@tHO=)DY3A6YZ&key|Niwqf89-BO%&&qF)uH3WTUOy zp}Ge4Ei%DYkU0ki@XVz;*&Z|r(os4huqOHw&6QSs)7Epo1qICxFv1ayqf*mm_{?L) zuD^)S)Swr~5w3jm@ZHc%ZO_XGiVpF466zWFtsxT}$F!%;(VO3iXw3FqudkzYL|{$i z_qsle8#U&z-*bOr$O_RoOK4ibRU_D6Ax&7rwLLh_I5-ERP85&RGBfu}|HIWFFx0@g z51HV+LaRaZrhL%$_iS*=p*l)O1lB}%UYE=A`l)m9;}vhw4*Ay#fM}exDeKVea%@_S zgKYNA4jfkiTnAAnT5At}V5UbicCB87fol;m!FistW|u0&M^ofv^rH1TN=F3Nq-o>L zXDpy<174}~R)(w)jjJfd-KFT}I{Lz$UrHaL=z*&(WNi1J_#2 z&q5yY9geXai$l2n=$ekwkvr}t!4`Gp^?#VQVL%$N2^VW4zG;|`E^`kNN` z`OFy1v$addkO`u3m#JxM&J57gJ}$;j9I3)_UyIzaCW=3=F`BjN)s>Y_*4@C}Hpc(p z34rn~z0T)y1qJizx~GBCk-LiMwcTI8Pv?&&JiQC|(TK*A1!Y!Ey-NS>tAj7lGb{Uc zJh9-}hwcYA$Fg?s+Oe%wdnzX{WP&=;9xhpC+lMX=?%unYfzlD7p1d~oo~5sJ^y0OS z%(EdAMB_=1ZWKG6(dWFb%g^3=$`FAkNIZ*@zt4_->}LAr?DuM_9(W$a(>+DFHTuJ5 zq^`s}jIU&%bmWewV%o#C+^^UE)PXOWQ$ z6HU8Q)7z*OU57XIpRQPOkUQ2ynp1Q_MYAs3U!${PjY1}<6P;_f__^$9zA*2TQHtFM z5vnz+?}qWZ&zACh|J#xVT8EH3TE8e~&8f6T$Ne>VT78?2_BOO%VNJB_>vWdY+HYek zN3>Jo?$Abxc1GHlM0a=9*zkyLJ>FKa+#z=rarX2C{rOpMzBSs%fidY@=?9?G+KK zMR-fOhqg>buCXoCqZNxVaz_g^jjND-`qt}j*|1af477Qp4H<2{WHo5?md&5soXv_; zE%X@Sh}L?#wJbl3^)QCA0fS=|>p5~)5w8{}cRfrP&qBJYw;9MCZyjh)z1^;F^qjy( znmr7>=Rli2TI(r7A^0uZ_oF$>8`Dg=l|d$`6XlxhyqwjTt+V1aVw4*bM5wniC*86$ zj|I6|s*nN7?GkdwTOjfZOZ(98&5tXt4Lyb!c<+Qd;SCM_P4LktHseP)i|66WEg3Sw zdm~NTJ0qUu%8`Kuwd$hWU?D=iCHup_H#^y}x9d%oe#&hha>rXax_54M#dRXpM!%Xv zhZuMdh&tho8U1@;?{}8GXk%7-R#Qa}yt~89p>$I{;XK>${GjW|^bX36B67zYOv)}c zauuszeWYJQTBGpZ5xL_nDed(CYR3+bOQ!d2rQX+~PFRzsu1@wwR>!9>4q2Yfss4jbJMDJa2p$$p@)9B zd`AOsrxA^J>Ey+_BN<;GP?2RG(bT}(dyGp)j{?eb*E|`&@m-Ji32vd>(Ia;iaeLbr z_TY9Y{X1`__yHhy^i(v_|sYLY(|R+#Ull|qqmTzwRQ966Y9UROLv>)XLjkpPxo3-c-m$ z^>m8)P=YTnP*We^RbBC0LWJr~6+Xn5=V^<@ZycQm57psi zJ)Y`W<1Z@SZHPwyJ58%Strjm`rl65y+CCflz@c{=`uNd*GwP({p(F1jaU=;Uy)C08S+W(MLwzMhl;j0w6Kv?t#1hD7dPl%uf5k%I&xPLpZ2xn_eX!! zd#6|&k3OP^Mw=Y@W$dWH3-r|tUo#m;&s9XLcDSAgMzKuO^Xf11_2L8C{g%M447Z;? zT1W9JMtdoZs~gGq>_*v*fpZEd2=tCc*_7Gn`);=S+Yvp(uyBPHdM=}EiXN!eU7z`S z8S6Hv3uh10iz4^j9dT#sEB82fR;N4R;??zX9^=@6&OH?bT8dN)OKk65wop|BuRhU0>ZJ7vFldw1Pm}f_gshd3v{Auwo`Yaip#w@J12Q zlsWR~dp+cGP989>u!2B6&{jh`%fH6!``V=<&w*gYii0vxKk|qlRlx9D?9a&>pjmH9 zr>^R>o@Fbb*8-iqJiU#_^Xl*ogC;5`VLU-vXjv2G#VO`xY`^d1Lw7gUu@s)wR7BaY zf9v_1=j8b&6gDhv-_9!YKUT6{JoRbX#cJ+G(4I1U!KUPjXAPdCuqL`cKQYktroEqS zvOd(XM#I$ZrJT4!#$6`mRda7+%NTpobtPzsg21x@qG^Xbw7SmTj%V8o^i&XdDnc~< z*K*BqTRYz@>}Iw>3Ie&~Igu7St2VHvH4VK{^LOnW8BFrHfy$=v#`7q_YAm~piy!wEw9rxpHaDKCIbV9q`Th+9@)V3)JuCF2XiWO~2bOo*qWcSHi zkk@)y-Kg?l976=|A8_5(wD7&fxMwzpk>D(ELj-DzXiXdI%*}6v7BNQVc*U?TjMKoH zG;RB4FJ5bNWn+)$?+p1`+R8OiMGV^S#d|HRY&7-!UD?B7DGM$8iAKBcdbT*2>-RTB zD!XtjrS|#9EfrW;zv_CE1AUcqEsjJL(Qup4%g%bsg6jktI2+)%f?pT;w`cG$O6)7k z^T)nbY-Bj&sPom!ZuyP)F}3-}O}AXQPT@oov6eSx>b^%@?Axc-ieCoK=N2ou z&eQaKYb`s~CqZwwB~rOjw6v8gwbgF2ZzvYvL^uzad{wX3dWABsuvEEfOA@M{o@npZ zQ6iq~%+BvjdTJXyD@fVNpp4gz&n2|+I%dz?QhEq=-r&nFH{ZkR9O}fe6mpNcnMy2~ zL^&JlOFcXul+kZIs>9pO$*Js1uzfbq$|I(yE#SCYLbg?*rc3ntadFBTC0o%#$ko6? zjP{c&&TW!$m}K;rlheRb7Av`ySgeNTDocp)O}?yoi#;sIp-#$*W9cMU221mLsY(;# z4Yk#UiBD|6;wwg{VK4P=ENhUZGus1cW27R@5`f6*_SBr0~dgUm=ubI{lni+~rdum%l zGXs{gxXY1<^9tR{&@8%yX3UUrEoMzD*2Rm^rW$7e) z&C*=1SM)~&YO9*G;&i7K2TNJ)CVS0l-K15m0QJWT>W{{>s$nVY8=O%!t$&_coKG&y zcV7Ci-Lu`TgegmICw`sS|2TTcXPXdz5~9uEGTZSDj!LYF{tZZoKM2un@TTop3P=9G z5mJVn6S0)_EayQLG4v-ZfB%COv6LlG&VwpK>amApl=Anlh@~u@0KxAvzDgiUR zV#k9hku9*gIjf{gjKA4f+#OiMEI59L_~U+Ual4q!r2OsUbMWFf>KLyJ)Yb7#@UfL* z)cT_0TR=?{YofjA^0K_-_rk{Q3tJezSrcQ5eeEKJ-?3_nJj&t`QG-vtdP*M?mw|Vi zW{P~5T8W+8sw?%PJhBd^D$3sn7t@C{(D{~XrYMlAt>7Q3n}}X@a;5NSUReDzl}SM^x?+Ri%{&Tnk!60D>2 zbMqI8#@BL)u&%Yt<}=5ORml$~xMiXobJH5TNG6sudGX6+V+n8@VT z_yOYLUn3HRWhSCv%HIWxmzlOZjwB35W6*rmpi$UU#eq$1b zdc9g3t#LS2^c4IU1%1cx0 z5ATI=EQNod#q5i8^V2Oe4<*Eo`ym|PV7*wArVVX*hLzngO}|kv%5ZZ;h*W<3PU<)1@^O-D?du{Blb@F1>BeJ=UGkt7TrSqlVZ%Dxyzd8$S5-7Tu@y za)#0oeK2ifQLD-*BPzH7$yk&r6Q469o4&D8sPb1`)EsM~o9c_VnYTxEeMn$yBeg9^ zH1yICanxxQRad-srz zd=ZVZ$$r(g3qM(SjvntZh8?}#P`IBTVBDJ)W+Hmm@(|ImPzrn2SgHBAm~8w`g{=C` zpdjTh$M|nytcmPCHJ7jtPCwg%GI2(OE_KA6)}M{2&D3l2YKfjVYTHxJ4Kd^1)fG<` z`rFH;l08@(_(L6~BX^dc~Rg zB3Jb~_Ix&}$GM1HeE9k2wz!M+6g?2l_XUcjkLubJmdO89Kl(D2bqs##Ds?T+K<;Vo z)Dk`uTH9;24>2>=t|xk=h_bt#lRY@|b#vbL$#Yj|)gL-aNA4=3{Idbv<9oPk(6X8g zr6anse~`F7EXv+1ZK57+y?DW}bhb0Q>MH-j#{Vs2O>~+V(3w@3HJvSN6k{Owc0K`O z_vrz4kBlLv{wYx0nBCppb&}MhYkVE(o8ArnzP+fzr`4{QrI8-@mph0O-oCkOvikGfN{@pH|q@Z!0T>L?w#BbxrI zJImmKDRS{!zB3t0M|7Fnp`v8ZzV;ilr5<}frQ$rW99z_?k@7clMCbe%DrUSJW?y$x z_F$?!L-yA4&BE*F3o|BV4-u^{jkBi=3^pgOZXo`O8)jeV9-`=^X-$JRv4Tt5amT5- zI!Z_Gh}N`^Yu)+u?@pd+yI?3C(SPNXY^|jE^d6AV81>-$Sk@fLM+`l!d|tjsuOv6+gG~k zE+4?--RwF_NA8HGnc?LO)^AQ@zWCcKhSCwep+j@ACSthVoyoDgWARQlYVl}R;!?Dd zTOI#%k2Pspli=lgrYhyQ?qAGkmZg_SaPMiKKD@r7$Ig&QaqI3l`^DlxB%|*2&H95P zrMT%;!a%;*3MxW84$%9p8Nf>gbhIH~M5AoF%}7(!6|lMiA2=}!|8Ts85F5tYGhPWb z5uLEDw@7ighkedI$tu~Yacop?yVcn_ouv7d1V`+b7=&HZj9I zWkZY{%~l`l$J$no<@g5WVNJA?Dfvu)Wk&Ja`>W`y>#Y#(!%X9^v$f2Lt`#EU_HHBY zMr~8oqeJ-vdUT)8JWJ8XF64`)5KT6jEr)F_v-|Q!f0b7BK=l26D@9$#jGPzbUUc^5 z9&A{#cC0~xp8TuNYO!kBTccO+07Y|Ek3Y*~GQLd;3^6 zGCuc8YecZyDZ%-MqepwRNN#_ET^VTV8hP(v%{@>D4HXB=+obY zS44!dyL@dz3~iU)@ZS@{e|RLfq4WdaH;U}OWsRoCo#xVfTuhGX#51Ne2vNM+9{sls zq1=A;Aw%hi?sb`qT}NVh{wETVdTJ@#*^N2)ht0tpr6c<8mjv-`d?fc!U9mhU(^iqmG2RdrYnzCESlblo-c;dlQaK3W(bCH}IJq{j|FtMX>Bzls;B7Ip z&g_KEL#hzsWxyT%Ldn{Ee&^>5-@Ko2Po%xLDB(`uDkj!Mr@QI9^anF+y#Be&9Qk4? zL{p^qmMFjWdK&&cOE^cqh#s`d6w8LdKvNTyk*zmqxlz%~>JgkZS4Vdk_{)v_4Z5yZI$k%JuU9n@z;)EuT zE1UI$Ux=n-&nB$zQ9-g2E%n&QTs%#M+8p^Jx>Ddvv2@9qgay|nV(*RJuArbBtjUgO zMGr)OZ~vFLyy;XzI`4{vSn}l<8+SE;ZSEG$Q;&QlW<5Qg@Vab8bK9`j!fW}FguWRn znwb5aX1D=|*z~c%EG~U}j&D#~tcfxex}NDr$YSv0T6vCqQQO9juY$!F5KT&zCRTsG zuBvy9{>+w+XvUE*qN^17CWiMbAYKPcMBQ9pT;;AY)`a>4r6bxS<9G3U>H=a&xI_d8 zo?~}QMY1X5+Hlks(N|u77k%UMi(UZ|F=t7H-r@OnHn4LiUS!M4a#*CgE`63!+(|_XPy0Sba zC$p-zVmR_e^v2?vc|EY2NEK0%SWW2rkiOPP#`j0^bmE8b68XfzyroSAtKj=it%YALfij_J$loEl^oqn zL5%a#%8l#bkcxqTA53bYr!BV_BgYgU|1YcR)_{LDa(Z<fRzdFh%))^p^G=rrOPa`} z(3`(S@_t=}?^1~v+x$<~>0@16%AgpI(h-3*ksWUJEw;J&3fGLb(Hx~C`or+ z(e9M|qN=yn`0dGIEP0`(%HKSqTYeNv(#MJwfhA0=iFN?R53_(n6ZK;5t$Dl1$70Z( zexi<1#zZEaYP=SyKlBv&=>K<=->2PeR)D{->1Eo{?)8^+L|{!cx7T^kHsmPns@AI& z*WBNT%f0)E^6@22M2{c-m@={r5O?dAAsMdDZv5o|2P;0Tse(8+^RZ}pZJ=0JtBi?% zD4~<^a5r8$&|sHlH|1DrDj}XU8Z1uu{1f5st8rJg1bxiP07df^#UG32gZc`+NEtJt z>@VU`j%$Z%@R5f>eOvwx6@Yk2eHR7lt zmO`|qrP%Jy$Il<+`*Lf9q6eY}XSyn~t>`OmC6p&t9k(Up3%Ba5;KL?-)~+k!PJ@A> z%bD^fYK|?UX>*$ue|B;P%D>2?SdtC_6_V$VxJ*dB^aG|`3XtdUol{0rTell}G_G))H|Lr#+7TThP zp0$RFI$=$kW}oBE=f~W0Re01?k%9JhtVz>Wmhs{bTj=`h*0q$I21KYb?(QtaE7)G> zebaj>ZH3%XCr$fi&&exPs$hJ(e}Z8v;{Au(R#`eH=Mf==SofRi*hMDT3UqH!FEwAY zXqoNnfu>4-AVTf)yA4zF+mvhRVZT6*y@uRzjM2V5{tfH;*4@}XzLGN9Q75d4{`2$H zjo;ZB$cis(!tv|G{|e#vPv@x6H>_ap8heM0Y^{7B3U`<>$Oe$^3Tsxiy568%Tji@o z?l`Y#TFG@gS-`Gcdd=#Q9A`58&hdMsJ;U=Kti_TL)@E8$W!^>ZicVVH&DYro|FN!S zt=lVeA|ljzH|6l{%=UPuZA6+_W&J?zIM35vYTPK+?s-E!@5CM)R~FO>=V0==^Zmx2 z=ZRp|52||LYJjU9y5G*0=0`FtwNj_}UPo&mYz zu13>N21PT^9v@t(XZBTgGRPfwPUJ>baIMQsH_?@5;t-De9o(1T?u>3NjhC!^ohX)a zQ*(|xNc@Wy?olbQxXv1O*sV3oAJ#?L^&xi^@nA(UmSSTh%i6Awva>|)xc8+~(U550 z?&lh^%zXxM+++S;&zt>CF?Mnp9|E0OILquiXrghJH&z7V4TDHlvJIB)xo+ea1?yS1U@(0yr!*{h* z&N#>&&v2Ag<&VBB*N^3F>6y;TISRSsNslbsMb5-0pL2m7n694HkUO3xDX)Q6OE2B& zD_dVXg5!w}&uVyLr7!B@0rGMRW5tT9XJ@oC;5k~;ruNIsZnZzbcCGE8oP?3Pinw_w zg*tmgwuBZIRgV^Y0n0d{23tHfR73l@2;wLmxugA(>=S6B&6@s|Qhf}&@NPKs zj)+lg`uLw&wC~eDq&?@mhUcxryN&SXC>^=0h&9|(cexGbMgPj;LRN^zdkV4|TwbfE zE>)BNKEcDln-SClYtpn`zT4RDtHapRG95VH*B}$riLx8B#jKI70k2T|6GQ2Uz?wA8 zGs9C?s=o&C1*41TcoTzYylK+31{uohb21m?hl@K5ytTr6JiG;>oKA7~S)sF?Si{kg ziXM0$h4*cA?_4h}Pq=FE?%(z?l#bl-R*rJk)c%t_akb%dAI{Q|6{7LxkNyrk>!M%Q zp_zHQv0(<@BI3O&>O>xmIa2d`W6QA1JsWY9j@%FOdZI<15%#hV{lDJ^Kx@5^VzeG=*SAucoR#ld*Pug^vrX1BY$fHZ*}o*8+FpOUbl1c zfqr9Lg&qZRl#bkezXpf}vpd@B`8Omz9`@?WI~uE5kxrour6U?|tu<|3i`smOIL~I~ z|DYo)MB~jk`4rvl&5WXp*)_9^q6gl%#aBL|nkjs-@aCTP^=mCMg6q=SP zzZd_Q=b=r@pz4AC3?*9B6Q_c{7>8!b{@DMcA78e^OW&Wm0z>J@9lbheX4o6ScW(X5 zcA{o-1DPNiJx9pjr~FA)!jaiFx=3dQfgUO7+d_BSPjc{T{qpD|a|d$the0N)9(%{d z@TC)G=#ksnF_ex7tckoPn}zc?&u8hcmp{;v38K-HN7Ht%*ux%$`Ra3AoecCHLhe`- z`DN6}%DwyK(|1k@QhdCS3HtufoEX`jhrZgPH*$<)C>;^1Z`7L>O?d7UhxG5q_v`4Z zglP1|q8r6HH=cj?TzzrR5XCnNeZ0_HjC`GMr{+iZ-Ld5#)I|9^F#h)!z23-=>~;%o z+kZ%ZHTyS)(viE0Sb3xYPyXi@J>!u%Ix;~t`rnbadelQ!W!^b`>xOy;di)`Gtci9q zmpypX?$d2)*ELl96Ojq(L^&GI2lKYi59%K--DM~p5vqUUoms&=SHdKD6kQiZ#i6WGQ)f zuWPO>$s;)W0;3HPEroRQYF?Q~N6*!BWh~55I&xPLIW`;o>GZ6|vWaUL`s^YaZHweH zv7!V&MnBUz{@rdv4{X#4Ya%@=bYm?h4bs;=?Eb%4GK#x0(Ncug7K%$Pv5jrr&-G`? zTPO&$ks+GyIft)jud{GHWK*Pquwo1-YU>}?^UuZKGq*Wz#>%Ct^&DkbF%6O}<>X+o zdOF{&tl-R!iVQr_<4K>!Rpbj-$F&b^rB)A85O~vswi-I)xL5TplRcg5-Ibw=6$dRL zDywS*eKr$ub$KqXYQikCT}d=RuKkCY~VCYk^j0+eE!Yx9zNL zZ1n$P`y>LjMcV*nt|7JoaRv29;19{DT-Lj-DzXHmL|i_2|1eO{Lzyz|P2 zZ%_u-ME-DbTlGzqJh*eH<9{)V6nA6d`2)`-v;#Pk!&ud~20xK|`~UQi2;{Dwyw>#A z3^QFpUh-)U1K*$wikb#iz_vq2kZUtd)@1XYiG+} zQSlOidqZ`96;ySSE%Rla8ILF{*RMPiChm|Ct!WEV=g~KM^kw$w-v5ivq=+LE_tA)^ zwbr>sFQ4Tm+fuTzg1{D4PenhbkJPu6-N+ui>Y(@z;+ex5S5h|pW8`Cq-ZIY&HuP|; z;x&n^RK(E*!)@Q|mS@iv4K$E1wt|Y-vw0`0mWJu)H#GlW#5%=6nYcRR3P(HrkU6Yd z$?kd!TQ>!PKHG?fa45r?Q6*dY zuO($Su9l^$kt*-+Iz(rgSPEBdTAlZ1ho99hNaJ#W5_ zrEtYj5tr?``0o2}$4RU>akSdqs|X@wQh*mJ7v zjxowEHtKKPn3R+E9A8+m$>2Ak&R6X_7cj)Or2Hi~4`M0nSPx<;hZVI+ z5vPP$Ls6#5Day1y#Olj7!M3s@Ln-2v5dRgcFWcQh$W_Kd+$|wjod1f|m!&LLa;~*l zQN$@BUTyYe`6KtRs|SC@>dR7==5qD1G^dDDLVTvS%1=?Iy&zU!mcsFBwJt@RN4{3amcln_TLviLt@^_5<;A{;4-k`VtDt1tW3;x2m)VlWBu8%0Qepa|)iwSL9w z%TiYR$XO^tE)PrBB2h&oP0xX5?gY8EDyQ3c5M6JtP{)*L? zt%!Yqee>V3`m(1i1VtAAuQ!vv+N#upZAiuK>{3fi{O`75UD^_2Y!d}DPB=5HWj@AEPy|VxDo2UHk zG&7``{M6PTV)bPy>@}QM{ySD*jzsJ=oV&>Dh2rS%Q5=0F#Olk@j=hHSW6~`8&scr= zMOg^hYZfADRm=IXjDCt_w1HTCS;}H1d(C3?b5)~^C$%Y7KPRmQSjy5|_L`-6(yI1f zvHG$U_L|kYawVcHH~$fRfN<-#_AV?SbbT_(pJuc zD&oIl^<^pRi;^>uiukWseOU^>sDC5=BUb-^GUWHDB3619HKXBC&l+xyyNA&VrJW8*-Vs8=kq$=Jj2B7`qFK+d5`D9;aXYF z+!UNiVWlDp)J$M=(@bVw6Wj0s$@V#}^)GLx2*_k2`fJn`N6jL|%wv8zNe`{h3fHB@ zIeE3Q_4&6$R~@6%6*sr_$Z77Mf8FtQU2$_}mYinPjgyXr{mPmpa700`sMa(J_a+qn2`;O>A`OKj3JZ6_t_Z*$H z{ATi~ydgAxvZwQ z>E(LpsM9&G*}6hLk`dLi3r}CfS1(_08$;>HT}5PhQH=LqHl za+%K9{N}Y$j~sESbDLkv7a$p(YliY1-R|q*pO}tsP+P2ta<`2h%-?2dYwHr2jG=~z zz?!57wvERv5o}w34@GlCPyIi_z5*<(<@x^wu?Pi~l2VaWQBgsKcMp3kY*Deh^V;3m z0d`~ewYzxF!s<2AYj<~FyW>B5cn{3_yWjuydG2%Hhclm@nT^@m*_m@DKBhjO3-X9k zML??Jw*$1n@d3=$q%hn+SlhPMpVEWty!h2G0s*fuW$S0|Bd_x~E7R4dv{9@lpFE%t zPZ{!rdMtP6j`l_P_+yV~@jAx<;Lb;<`v0a!Lat_PaJ9YKq4$Rf=8k2@ zXz)vl1~R|-3LBcuQN!FZ`sI}e^nRiT|FKR;wYqU`t&l?vwxg>joAK!xZT;Dkcl=nC zV|10MN3`S{58m{603hBU$i+6+oMo=QuCa34a*w{7>B@&pFUlKyxl0G!cH^VB7nO8^ zFEx!W#4LBSvoB}!E0{Z$9i!o^q1hg5b>cg)LXq#IF?WpaS>hhO^~9YQn=PdJe!rWg z-oVD}{lMJpeWfR~(+Cf~a#0|c(DXiC81BKlp9};<+l@>+m!4>Ox37mXHuX9k@8-&P zoeki5ldsd%PB1oa10)(ePcFvhB6b9R{&HF4@UT#2urH zytz)DTDtRyOG2t@mk&o@Xws4m8f0Pv>fEG1@4NACr9!ydo(HtyB6oi4SP;i8fm9Qm zv;&oQS;|Zqu3+w1r{2fT(1I{d%~l8=?Th(nQ}5T+KF=Ja;3st#q|*s+-T3mDAgLEj zrknkeE$vE`WN%hgP_Vq1A4bC)1RidTcDOa1&5!XVix=IX&lBCbQ^8=4(d(b4(`yIa z`KvHdUGwLqTV~a}CHv$3H*I&pQ*=-%ch35Ua@-5JC3ruBt3SDv&xt+Q9;Y;1vYO7l zSCF5|7RWa~T1_AC_Truk1Gy~K*yq*B=1x(pfvvsy)0$$opGsd(%HD;_fqEAS=8nn;#8$;unnvGw=eS(!4GY4-8KyhaXRzHg~Y2UiT{Erv#bf7 zm>j^vB7~Q*FQ;ZsD^-V$z3$5J6U+~{1QyOUj}jhHhxJ?Bkc>Q6hK_J6#?MC-H!O4l%VjE+0+L{A(l%`d(Xh`&0HHP>2H8|r=BS*gU5 zv=h|5otovvG5T#wNBZ|(xZx-!&L3u5cjaxP%4~JBF&gHMW%oatoi2M-mgnz~2M|7P zSIMr>I94O~F%5Ia=%EYk=%rlcxX*ln=+U(=$#Jv++tACFVeS|`rdBqpx|ZXsxj-~{ z?_r+uy(V*MSCI9&Zci)BFU_~N$j>o)`EwgOG=Di>{GmX=4yF7(p&a{~_E7UVZKCfN zmFK@a>^YXiHZeQB?O%>BDk2a`>m8L}L1o#f#g8;hg|(Ft_h0=*zD!q{kCvTbc`+LE zhUmxqMr5^8gUuL`pJ911x>4m{F;BOb=Q)bngH#hDPDB^KTZ4W0<;7kkz(=mKmE)6s z@`K&x&5hM_KK0hQI`xRj=Z3{EZJ>anotum}UKasGYc@1EcNG5?ArN&}?jsH-^0Erc39I(f zfwtHb&7Zuq<5&_|kB^&%k$JNM*??D(40Fc_+!DN#WB4y~?-do;omM3n=8n-tT^*=$ zGn#+7UshaFG&oS#0gY35}fX9FG=m(C(zhCbKc7i-M$lb+?>>4@xv zr&r9zWj(Hziy}#bJ=x`<)fko+Q(-jhA9?qh3(g5=8-A8!Q_I=YPC3kc*-kr-(aUGK z(c@JJ*W83uE7_TYgJx7?*W(MZ!;!A^&Yy($+G@*jFW{D-elQ@Ad|q)vi|*8!6^toC zL(K|TcH3|)NuKlWG*&b7+zkYe8Mp46-vq&1(pSVY%pD_eOYqjAsJiB)siExpP{N8m za;4oz5PtKqEyrl>S#kPnuEK{+vH>2KidRmFFIkmE+ZADpB8t;a{xN*#PZP&F;g+C& zaK_^3hHRqN;>19s+Gd~47K4{l0%6lXxa_J+x{(h6dBbwy56P7TG#R&80L-< zxFyJk8#}GSPiH?icrLtEWoB{u*L{VbsbRx0I`_VYw8M3UPPY~I{IW#{=y?AYa^ z?0&9z`uFk}UU#jDW1VnIP)oL{lrA^&6+FH_^VRkrkxokK_H$Id|zpjhsm7j|>$db${{XP@cV_+z&cqECou$X!C zGIkvI0&WR12gnsI{(K7(+ODmnd0KEHeN!ijN9?!b51Or}U+YEiiO#u!$DV{QTEOKy zB(gkZ_(|VJd#Gzj8NM!;6PNXH_E@dWAN$twbAE4z<;7GO4d0_bUPenCa7WYDwPl`4 z60KUr%v)@*;~1UzY7brbvkc$WzzL)ZzZGSue=%%*SCqIuJ@*#S|jQD7DJaEIl#1oF};^}zFCSrtasrOZ`7F{=CrB+z$E7@HvJKh-}YS8a%^vVHa zEkVsjF}xRHOO0)?$<(vbnS++l%520CcpEg@Ik6;oFM+T2)EaA!Us9O0x?V-v)i46L z1X;yuPBNUn(ZDO$Y=2){A!@dF53GbpNQ?aPV2Orv3V_rWB zNuCUr1n=$eru2U4=FL4zvXfiNOI`*>$exVjuUcfquYBx%g_;ceB3O3pIe}lYaskP= z^P%RtP4?liPPirb(#E8o6^8AKW!InjO1>zT1p8WWR@-Dt#uux=KJG6ed3_im`=Xtm zk0w4%1K9A<vFR5H!`?RbUa^;HGTmsJ7`5|LbylsmkE93o zknsrsUUt6Uoy=;evWTihB)=WYj?W43CWL*n$(4Q)EP0DR!`?lX9iK(ui?;z+NZ!?f zEO~5UNe_(1=N-tIxE2!aW2wQ?s(VXk94tFNkwFIbfKXDsPEA&NnX7b;!m{IYo5{3e z>q_$DcvZHihJ$og!?NSEA-qrK$a7Mnb2OXn^;5&AQGB|S_4tteaP&o`CL2G&OFDC6 z+3}eg@|K=dB6lh`U=?%ZlFqeQc6{+J3ie*UZ0Oi>F8IR zJ$^Q~&8NVkRk_&a3!}I7WhH#}OUKh_5x%JbHdDR_2rk z!`!j#IOYVsJ9`Wn7}IZwQUIVL9I+_2W2{p zU~JJm1jpNO{0g@O_G-Sx+@~1S@A#Y>w4qHyceRIEIMPII0Tckz_||-j8Ebj^vTzyERWO zqOo7R`LLG^XfQrLK3&^MK1=!JNRKbydjK((`CexwHo+O7Qjydjd zV)!lvOCsyhK0J;%*$icUs!Xw9?ihhvf|{Qd@#O1}Hf&bfO@g^&G`zlLHA=wzdoy3yhdpvlP=h60B*Xe^<()C?t%pD_eOK?hUo2I!O4`E4N0;GFR zjK=q>aCTNVYrCHHjdFb0Tfuj<_|_WVlA28G`*gCLsoscXi*u0lz_+jXb{TH_-aXbP zmg~S)b}tf*xntS!9W?CDGyU1lmATlW-nGU-f9N;5&1iMSyjJ z?C5;CG|#=&S->+-hPh+e@om4!G}IKxQl~1+esx|A-?C#g&Iy2Q!=}yH{j+M&ld}*at5UWyzMDTH~)C1WSd{I1dCe$!n_YyJbDe!ShOb;QSJtsREI0 zT1KnAGJv)CW@eZ>mK|rqK%AjpC6;}lMSDIvC&Sz^8t2TwZm@hLOC2}Iy!O&OizErk zzrlGqCX*}V6p{JANYL4Ig7b*5?6@VkOI>28RlDlNRL^f>L#uDmaXk(Kt8G zWO}!_4y!(`fb#O-Z3{-=oI9MoXEN1mS<=#OcVQM0Tvf^h#4#%znSv^zDX+BoBSW+= z<6231eOPuGF@u+8$8)YCeai+gED4q!$Fkr~xNljeEC^Euuc@Zt+)6AvZV58B@~qWX zT;`Ho|Ikv0-FT^TxqpkjuK44lHonqFvV1|56kEbE8Qc=A z^Vs@i-;ilq+^F8n_Vii0ylQry7?z#mr~y8Cn@mm#XUtERIcxdchf4_DE{+F5#4EC% zHhIk_^Qwb`rAQHuuwdSh{ps>G+OOyVOM!DE8K%Ng$%r}AK9U9peb}?s z7m!Qjp=QJ7SO(^STLK@Bucyoy(Xp6_!dygmt}6eDmgG&6<@_j3*a9 z73A0p$KE+)lK*m2iXAV-YOj5nskuPlvj|4RZcxudVWpy(x!qa`f%^xeA*YDu){fP+ z)5=U3rWm8<)V(OjJ{->dg1(BsOg`1m&fLO?gut?6?;Q5p?&HX>otw0B`#Vd1JN9ug zZ+PQk=Y3|MouQgt%VAQ+7M4mz_z(J^mGO5_uD36x7}lU$2RZu_?^jT%x7vZ7{3n3q z8CzdM7^}9=^gu3q8HYUlwUrIZld~fSE0_xRkL)LINLi>=INyhCm@DTFVlNE01bgkz z=UU$d^+>#LODSs-OClqD(?4s)%bg>BbVhAb$}w)+)Ts@kuY5I8Sb-Z{tZ^fdwg#9ATRx~a=u=qXn=_P?#|7mTL8Q-84`+p-efxWxP!Lf`!G_u zcOQoR1iXhEy&${~*wxaTFuUp3$V~WZDDHQoN5!mcvhy`^=r!*ddYKmIReyn}Ek;s6N9~ z20yWv7*dUS<4Foa_emwV28n12Jl2a-X8T(tf60ua_4P58+G7 zA=YnUV=Cjf7&QaIV#Nr$Ky~II;IS3zYcZ9EA&`FG% zp?R(OB7fH&`fA7E+ghie+X$vI`b~_Q(YwvOL_JQ#q(1E1l118`(+&hv;jtN<{R4F` z>uw#vNic%zVFW*kRx!vHRtUi1T8&l!_ z!94=?gD`^Ypm+a*`dUnd#{l;_yiFHIFxdJnY)obR7UOInGFI(p;4vI{e1ZB}Ol9yB zbIFh@!!pE!9(P~_pTf7WF_oc{n6HNB8P>-e`f34;VCkRRG)!gmn^+S@?`BxIVlaa5 zVFZhvanLXo9veKG@SZ!cqNTx#hQX@EPmFfOEWxW8ZkNC^?10MqIbazul_9&BiP&Pm zItMEn30AZpSRYJf^pBYB*eXHp`GXSV3s|_iVBs*8F$Q8qVaq35QA}n07Nce$GIq6O zu%g?5M*>)COl9yBqh?5zu}9s5w-jh#MPI_#JTR4^lNdEa^Nc-eCG=Gdu%a7a$H7!a zzll*ZdROdM&{tqZ3xXBh(`Kb);qcgCiwbY-g(}nSP-VJ!vCHmOUGC8N&+YZqiN_z$ z9+PQ2AhrR5bamK`pWs=ETQZr(0Aep7x+f&c2*G0y zApYDnr!1y2_z62GBPLk&2(Fi_9HugK5_V8V2+el@kA#FgAr+(JI^Lx-`xfDcY`lR-t~xf_i^`tt$gmm`qS%Lf)UUBWZ`IOU?GpT$ z7I7)U-*4~%#FL}%EUrObtX_O|1ykL2eMn0@_2;?Wen;f;4PnnB73EIeMV6ys$LTuT z68vF_e3Is$a$KMj-v#l%PZj_kW4}eSgPV#g$MZNxV-0b?4SaKjUV0wDEp6NYvF6rw zEw)FTGVSgm4L`x{;+CLR<}zhJ8}27n;7%3y38uo*!rMqj8=(f`H{-`)N&y==&C!x z-2Z_)AdWPgVOhJ)lO_LCQ^8MgPve##L+EZO>#^KNF}J-$u)L+}AE%947v~?Ex~Sit z9Ht#!l;GUQ8F++5d$SX?18KTQRj|Am?RDiaeK$Ld?|&!|0Y?sNwKsRydfe$C>4DKZ z`u{~;`;_D*nz#U>^~#18?}ff>``B0oYl~&iJMRdMuThG(YAg`rT=FqD|Dwvq*4Y%y z9m_tb#%k)49KrWp%ms+vACt*e9LY-KrEfHTDve{LDccCeHF|dqw7~sq}hK&@fwFDb~!pud!1*LJiibx6!<0p6q~#3|^SB z9`Xi%g_ct=m3dPVy_{<1y-NO$sQqG`R-)}V(k=WC1ki-_H>~+fg9075;45RN|^OR_iE9h0!VFyU?nw6+ZT<4Ip-0 zKa#SgR5^CZQdYsTW1ak-bfHxs%e&fgf%vvA*s|dMhp1UcMk#fMmZ4obDtuXjjfy4d z3OU6ou(mQ{!tEC+Q|b=a!hQ`>u)G+Jc|)$j>D?)9 ze%P{#cbY3$UW{&1p$r{#SmAE*LaGMwJyU3dXm+S&3FSpxS9&WthM$kHQ8C)36?ym?aGeeL*- z_6p{XW#_H@sNFIc^PvK){=(VD1vSPdM zl0??yn$HZs0=mR^_?#mCOcq2iX{-6CzCkm&;>S&bPvmEqyG zbU|DMFZ10|#gdFHWJ}AuF3(5z7d-ZjUq%97QFiTWJ_U2f2;36fhKB@_R|{iVo(Z1H z^`1Xs7F4XjA5F@wVl;haqBq(^@SNUGz~h5fAUZy|2Aea$Tk#(8J?2}p2>zBjsaPl6 z68Ju|evpdiRaR}>C4#xnYmtp^iHP7oFF2~Zr)8(Li~Q|zecjIw-6_q-t0ueuAOCl;;Ay6y2&%=>KUogrm;`j)&Z?giWu)b=HR zBOL}dV0+^dNvDC{bmHSMzT}guiX|D9D<`egtt_9KP4K9ew3F0=uV!ufe1>4|7=c@Y z%$kTQ8@(k(v|4-pb*}vtQYY3 z*v3_v1#jPvtKCk+Pd?6%rz^Jy@>XknRjDP@;L~a3p%ZsTn8uHtVbtbL1 zwPyP#-yoMac+#`C!+6#0ZYoBPncI*~JRitg)Dq{YZ@+q&=iI2ly7l!^daRA3UY!GZ zo^FLy+zYrRm{*1FkQR1v%=U1qHuL3t+ViLn|7%)+iY2+^-H4WN63E@`eSyc&8EK@> zp&l&ZK!^o%#|YdK)Qp>fX3UsKE}!bpY-av6V|g+9+S(2D&`2-d?C&6us=zvDGOcMn z*0{Q};(c{J&G)7t&$c^6#eIcag51GwVdUG>o!Xz9y0atoHqhKf3-YQB0@bGJDYQf< zcYe4)kUF)rg)Z#v!Ox8qJhB}bLze7o#%@=7qG9e>b{R3Je=kyL^k8-%XFIcV%MEnl zU@u0xJ~pT~Rf#iyKr|Eb6N*|{(*FXo5Qa1!?NA;lgKXD9CMOL1uc8hU$jzeOP`Mtg;xqjmbbbNf4@ zcb^t_B|FZ=Gm|B!q&Y?p8Fr3dp5@N_`-TAG?^hvOmn!=$N81f!x#yjwciXt~5&Hwx z=5?;qa93BZ-U(2rm%2`mb#UX`ZG`5DF6ovneuOzq2w|8zmR&}ySY#h{7jjG1Iv%!Q z?if93!gac*sXPDnQ1H;soi#@;ZpM<5Z549q2JH^-^jRDeqMlxJj=p*B#;2AJRdGw; zi=JMu1uWaWfA!Wr49i|_%sm=8*_Dr5T2yU!_%5As*^MVNu?8Ox->R+5Rh-2*1vAVY z%Pu3zxK`Ju!`Gl~f2LYqhTfnPCcE?pA`0pc5Cj&>-P0m9qvD%_olh?w4MHd z7{A4j^}1)zx;r>C%pJ=vBPP&$+JWSb%rRt43g(W{lioj|TjzW5eTzk3y&2fi@^_;~ zY$b6}Ms<5at55adk0%GJ4F^1+>U4L$>1vRQTY`AWp%6C6Ii56eF3+&+Ayc2wM%&%_ zx5e}nY_ByWrdr)BBmyLwA^K$(s}hg`NN)t)B~lT(2aM!c=d|DQdAYjV^w8# z{I8$nMZMD+mKXN|ZVBqPeMhqL=eC*iP1$V5@?x|c-`(PuG%s7XdMCl$F#@*)Gx6w9R^pkP zw(63DH0BtMXC=%lm9S6!_K~{r&J53Ryw35Afeh0yN9|7e>MXKhK?SchED4^+@J+q4 z!EB#uW`o|k5zHMUa7*Cn4{gCteBZ8ZIcd?bR2Yq|1bhio4P_I28o znXE)*Ed%TT;xnti4d$q7T*Kr~%Ukqa_ z+CH>k?ih_dK=4c47Mu4quE>542xC|hjK*Fj+%ARXit1l4S}VL#_II)DxFwURW~)Nv zM@&4ky_8eI-Zqv*)}!~Q9%Mg!kFJaJsuau}BXCQw8!YWX8hh4cX(gN`za69TIl*Ll zRWgP&Z)M9KW@{`V@c9FuWS|=GjyvfyyFNQP#ZfwQVoC7H0G@I1J);4`Cq*nfZVBw}k;~>YUu&|? zaURmS7RLkd85b&~M=v82&-P{`C*~%YJC5cIN?E zqUB+s&Se;mC*YGXKI1~Z=++J9>RaltQZrl?9J9cZV4X~+g9VbwpO-qatNT|H%pD_e zOD0q2I$ucK+}12|NJKP_Utlzjwm{Tiowt$?-f&!h&0Hz&gLT3!nM^V5tC{UL)ndGo zrxd@!lHm9ZeA#;21oEX}6IQCxD=AWh5pw+MZu95F7T)IYX2BvU4u@sO@iOpzyb3EJ ze^h3(TYWc65jqs{!jUO>b@aK5(H)?gd__+$DV~TW!4Wo->H41y$uFC_j6QQzFn5fQ z+!EZ~4OkjIVoD9>IKo?s z2xCcb#1q~^8(4+d7l>u|9=j`;J4VP6VP9n*2^pra+(+_Ak!_5|5oq|5a=4xHqeUrJ zB+^#FF>f40#<5=b>cT<0==8zWS*e#kQiL8$f@9Vu)7zfD#QvE z-jUL|lB5Sl<69tz;tY38c~YVpOE_Ify7|Gf<9jN|{fJv=UVWz|8=kX*bi0IQ$G2JV z)i=*VWL(z*?AV@K(hU}t9p9M2-NfsDByZ0b+U^6*q`NzO=Oybgu5F`~&+V$PN#BY{ zH*r{YeA5USrt=)lwv7TA?W9V#eOPvU9|_-BAGO9jEQc*?HLbaH2Z?3Jcb*VW-2Tfv zvfEB=*YchUzNy4Fiuhg?zE~L8Gv%UxB{pGwfOMCNWyd$aP;ppmYs$q_UhJh)P3gWC z%Z~4dA)n#()s)+j*R}RaXX#ED%Z~4$O{OwU=cI&}?WuMBIatBB-uM<-*5lZuE-5Z? z(JZk|3F&Sd%Z~5vAx0K|$Z|R~I}54ORJuRMvf~?m@I~#5Yn2;L(3+_Iq&s>nJI*42 z{PsDWwUv9uM|;N)QSePZzN5#P3Xqff=zGe>PbHcA;R*`QrpSGL8C?W7uC4rYsyJT* z;_Y=qwY@!WYtve_lQJN%>@wox!@1g!D-SI8Uj3vj3oJX%1A(^)?meVAyzfkc8h2E1 zE(Vqz=bAuO{PlV%J6k$p8i!^$|J*BdN`*HG6%Nb)_&%gtc}0YT*?Z=vdf6| zP0KKCnJ@8<3s*3AEIZDP1F7zoXM;NASLRnfOmJo%&Q-%LK}O1$0@{?i9xSX~4F%^R z;+PeVOhMk#u_A1g=Oj%TQ9;V z$2FDWS2&)Ca}~jpsaamza-NWW>Y&UT6R5|KZW{1u5^_Jf&C@1!>_dtL^pp@dej&#I z%#qJE_wMz{hRCcMUcm!LZZH}u)~|okMz~xi_G2n%*2+N5hl=A@7!B`-d!CbdMtUoB zqML-k(K>tS?2+jjU^-lZDGAOei2kK*_n>c(ngoxLKbaQz1eA+SiHlUIJEfAOozS#mxedO%HpZ+e| zuP!5`J1=}ohFgMn)*O38T;IF0hrNnt*6>1|kBU!s_=E)S_~jqS$Lk&}0#*GA1a23f zcTJ{Ge=Z=?eQa48e5o5h!90wNc+nEnW-KeBblX!!-GGkXW*BZvnxT*O0qoMMnd4T0rszvPJIL!%@f*!RIc5kzr5 z%_28UDexA7b`k<-p(WOCnDm<+M)sMRPxQ1TNo4_T_G&7Ilp=h>AP^ZYX_!=Tzh z#XBd?xrH0W5ofeFJ{L$(n|cxg`wtimaR%?4mROfb(KXMHk`P#1>_vfp_0I$?@8ua} zta}g1zrs9>6)dEM%KK&EY}@maN|n&Mne}Q=gQ4Ob2k%5sV`3Z3Dl9Ce#0^W95P09k zXo!p6bYYXThbqaZK1m4NKNt^Sco;?&7OtlvP$&>LP-%81AN5^f33gTZ0Uw_k{I+kb_Isqn5QBj&{VuvR%D zlmPffE|wQtXBpu$+nc$rj8O7 zYu0el%D4@eP7|0)p6%s6&myI5QnX>PqOg_0D@sQEx!g@js#B4*>bi?ytA?!swh|Bv zf8?bUeQRcCrcKwd)yKBhKxA0zSL+hUyBZs`n+v;0`6bxS8&ZkA3$nb|d0UFob*dNL1oxhRhyzg7_y(#P zJEQtqL1pxh7&TOz1&AR~Ik^ogC+DO3T0v!uffzMZ{{@JDtFIMQ211OQfq+U)K>Pzd z#P@4op!!-tWk@AP&5#NzH39K&^|gY^&|Hj~p*d7)0^;B5YXz0jyJFOg-i4YkK>S;M zt)RlAhAPGY@jvQorFJpDf3L3<+_CIfC-@o^jNk_t!E30#R%nR(2lpGCYoT|Op?All z`dZP8cnt8^{Cj<^7%2k*)qt6!nXzj9phCJk@Hm0$YXy}d6;uOej%J2sr~`UD20fmk z`dUF{Xb#nYnWLFueg3V!R!|wECf0<}yBQYl-|A}x6&^J_n*X!DHnUwZ{&>y9dsyHt z1;ZvkGj~DtwSo$d8n!F{USBI_A|5qtmEbLc@Rovfu%dlXeXW@7c+{|cl&vVHGJcCu zGY}bj)Cs7s-3>ejgQdn)hE!tI45>2qC@1)Stt(j3K-dj1m7%#9HAC}^J?h`;YXub^ zHKTVkPLTgrUn|BIj~ce9|FgbUnk9ISLH@3_E;R<#*NS^m}5WAr+br7nr z6>}G_4;k@q^|fMs7znYtWQ0+}n~dsf1(hL{Siv&Fs1puA^|gY^&{kN9|BLv&zE)5f zD@s@*8S!uRwSo$-sQ-z;^|hHi#Cntw(7%c}(`NiT3jJ;TJF32FR+oO9T8cx|QQh(W z2hvE7Ol9p+=%@eDSGrV~$~qqZfxuK-EYE_W`tLsw zm%rmL1h}3@_ zkI^s~@K2v50+A|yTluB^{}GtVs`-B)FqO66`2U{=rm~LBe<1!ZRr!BM=z3>y&!7Ty zre&}a!2cF?>TBLO#D$pO4Tm_HF{=e)nJTE3o`}|eyZBb3VMois?+Snz3y2sUu}sZ+ zB3qvf9-<`$5NF~pkYWS6=sdC{S*FIMHKg~TE=uq_`1l|#Jh2G;-U*1ufC$hL_zAXZ znBQPP>~9*RWGg~-9?-j1+Xs61r_K_p#v%4P536N>nXyd0vN?~srqU<Vr22;P*;Eq-7$Osaa3-nV4xs zvs#)02(K~&lqEl>YhpZLCR(YMsre5UQzu+Y)_FXiQC3~pgu?GNfbaptJRPx2&3ck) zA5-O)VgOMzag>rVLYY)Cg34-90kKToa;u`6y-m0E5R>_LL?%_eHEn$E-8Z}2;_*Wvd#KpX=^ zy%2jHfvK#$`x{~dAgr@QM_6ZrD)Y;nJ@9uicMrh4vMoY?lPYtT=sc|R&5E$jb{%0| zA3BdLewnKP{yragIMlyDddx7C(tU`uo!SxO8W%fy`cqzguky16!gaFcsJm(Yru} z5ms9wW{Hll&Iafg%ulx^VqU@Dt+s@LE%{9<-Ij=1qVurMH!A{ciJ0v=!aA#U9$EZ! z%OKVV{M~9xG_WPVNtHRrqF5EfK33ep_vc2DaoksWMmX zZ-~V(OTaG?wgeEFmO-Zy{4)F!?5`lppd+m7Tt|SHAuI#@&a^A=dkF9VpFym19g)?G zSo2IP0f;{V0Um&Lmf*3)@MPQDR={ zh%CFC*}JOXk!2InEYT6x`2$p$vqVQ^S!(Mn5#FnT5MHW|$l7s^s{d#I5Wc7(70uWu z@UE8WSwc(JSt2}39RZpP4^ro0^(=L%Ko8+@!f)#=Q8H}1-n+sdg#N)EfIdsa$s7J| zoh8ESGe%H&cRC`=FVV+Cc!ThF>ns6@Oru4+S-x7v?+m-E&k}L+hA~I}l`#{o9%LpW z)jCTA0)8WJiCJff&?8O!&hkYwrGmd(XNmBAbcD69xIkoi$eEf0!a7TYC!-@^mWc7t z5m|ma_WF@uq9d}-ADJTv=*$s>-@E!`BYP6AFT#6~BvZyb!!P zI93%BX3dxzE5Dj;26CdNbkh+lgOAZ2jZ5eV11%8N(+i+&o7I~mE}`m zL_%?Aa&y)>a(-$jCM2=)0C_Y0HvMQq)ebRJoKXzeQv`btLtRT}h_jxf+dLh(Dp23z||gT6BKNQ1sIc<5+rUs-Li zwXZbjD~X4-udI89-d9${{L`<^4u=Y|$=j;yh((i}xcJYitR7VD7ftUV!Ak6~JzG zS0t$f72Zp-5DkVuFt^X$oju;oHPNon6Fz1<|lXvk1XTdw&1EKnRB@>`?@$ul1flneM6l` z7Gmkhg5-?L2$+T7qk!xN52M`-e=d_p3{>iYRDD3IrLA*rbNZS5=gZS?Mw-CXBkJP~MX@9I3Py$%S`yEUPAo88W(U@Flr-V?Jtax_a6 zL1jDfmzOL}3wu@rcYU5 zk0SrHA^AGml9tICJd7t+J;V;D>tVEHGEI3@fvo*DjXd4d$IwHk5<3&idBXAL7wIG7Q}MfRjKD1YmA3Z)%zG#mvk|y zZ<`n4-5#`6Bhz!KuPfvS9)GjZ10sSSq2D(Gr~Kmo_KO*SRXL^Wp zhkz=pCHQ(oVheHx`l`=weYNX#C-th2z54KqGspa(!fkY3a(jV?vb94ECO^sY8Du@~ zZz@85Txg^m49u?U0rpCdQ#MGRq>>arwfUUuY5i=bsYTKQ)eWmt!OrJynV*dHjaQa` z%*EspYB>;H}yDiV`Q!s!IADZ-%L`9zv=t#QcOW=E&ea%8dfcb${3J zSYt0wS3BJ=rFwRro0ez#4E5=*a%%fge*nK<&s@o&Z+(?M+mkf;iM|hJddo&j5X<;= z-aK_wCuLgeE868sN$}>8VrpxT&1tnZOjqlNmr`q86Srj8Tb}D&jLh58PRXC`mM)bM z5uRa}q^|uIs_xmmEe*G1GL`ViLDr6mS87M()_XULd)9c!h$Y$$^M{h%lnZr^YFHAi zxh&Pt9{EWR(nJ~dIh)SIkP44KmJr@R(=UW{CViD0YLc#pIDce#6Ip#Vtinw7S@DXh zX=ViULivs>&2vf&SBeexmJsWMW~#~KqScWP-=~huH&az=DQfOswNg!{9=s4~dS0CD zOeXnB#)%~((u_|pU51q;Tk{WBeoeNsU_^Plnd+_-MNJyj03uKr9lO+@teDyD` zh5cp5?aGp5_7(7JGX1qV?N+?v-#51s`Ycg>GNqVm(_xdYhjsk*-`4pCzfXjum{)f1 zq}0iOP1oFba=GjbwN_HNy5p~DRBmauB_E0R=%+;TjJ`4uxZmbXouO7+R8Fn1{tw{M z;cz~Z>ef#wb5icz_P1uJuM^6vQG2RT8S#BvJ~9Tz!x0ep36@Im%i`Vsf*bMt5Tmg7 z{xG*PZHDT$ZoHZ;-b)=b_8C1;eT2GtXMXjc0pi`CO#tBnh!cRoPa1X_sA})>swD>G z1gfl-V2}E1s`+kAkkU9iRdBm9Ri+gM&2P?iAXP8cSMI!X)TOdoYFfX?G_}>&K(+km zRNBZqNew#Yr`}t24G@hxd6T5;?UdLbxApNbM(xi(rm53xg47$AQzbNfr`qI0CY@=h zj6Ix7!R-pE41VIb(Gq0#gH+W)s%yVVg(Z>oQ?mbK&QZl%NluDYUOergdTe!6^PF*1 z(Y~bjmGyKFzuSCrA=_RBC=R0(UGuCbSv`td$~@f>INd3~w`+|c{KjKuwaR2gtb_8% zJ5E8qfh5(RZ^G2Zhrd#v<>HN5;qx1l@23hV<0Gp}Jo@!-tPZM?U5$9@q4t_(R{hK- zb<6^h%eiM>V{#1;>j8nE;C5wc3o3m`_X2K8z#mm59&NsKQlnSdt35-VRri#(sz1C1 zdXZm#;E_Q3ke+}j4G8=MOC|FVK3vBPA5P~1-mCEXB+W&SSbaO-k$ZV%vT^e}61cay zBo*#A8R2jBMO!Bi(hKYYCiL$w zNhPSPX9Jx_7DAkHI%J%2bcAt=vyPg6x)W&YsR(%Ff-}wxIOF^|u!SU*pt7EEbRJoV zb_ofjP0=`Zx~HAQXBuwf;Ik zt4?VUBQ4aDOt{^Nm0iemsjR)5c1SE4P2$q~ zvID0kN_xC}Syo+or8@7>wTXm=6aBE3r0_F{aMolRZWoQgZ&GQU;z`1WDs1&uPbR30 zv;NlGBCD}9|HI)`nwXW=`Nm((n_^1M`MA#KQWxov}XjQ>wuotq=VqY)A`VAhwAj%Z|2Wi*vlva4%whSVA~E zL+=vk-HN9tYIxLe?+QfL2;TY{MNYuGyb_D8GvgVDXNf=<2fh6{vYcLl<*+8MinOGbo6M;LpNKp4A$Kp1;T#vZjUBVM8-j2%)S zj6KTAL*L;{rnKv$N!2>9$<0ko6uj#Tgf*6-TTyFd0<0*9{rnHu&qHB9$371B0IZse zI0_(Mc;q9#^&%AVsicDaPmGqmOlR;Dcin8KB)`8+uz!yIMA_?W4_^3Q@WOk5PmNCy z*b5hktg}x!INi;K(_LXW-Qn{RKHUjK);X~{oV<3x$tw{~Uih?)PhN-ztlE1M#zfCq z7Njign{m5j#4-exaqgGn0mbeujgDS-fwVuDal2&oEWu`E#Y^Nk%1DS`X%LfX3^5rT zr@}EAG#=2B19(fDz*`F1+nkAUHezJrw-JGo5yJO5o8kND2qSWb=9O+stezV1$OE3t z@eEH!M;P%$fiR+jf`>RMi?wbtodv&SIQS(KA!aG4j3}r0ZNw}E!n!^HVGmx$Oz<)` zLL^mC8BtmB+lZuE^$3(}wF6wOesqKp zbr$1cppjId54y)O&IXzJH%4R|Nd*WIZ@1pc=m?l4nb|ZjOZ1E#fylBx=#E84z)3MP zHwI2Z`pvjN7~TiuOjvJBzAer;r5d*x*7>UE%m{?xKfqlXx-k({Rz#}tTilokM3$u% zJjDG+@#KsMi&ZLE2l~1bJbv3b(QO73R94M(gjEk6VeIp8+RnP0&=J;~1{hm?Md?{6 zsISDBXWUwfn+6?W9YGyo+^Y#hR`fg@jQNKS&YBn8_K9}I97S2B`fZ;;WX(kDydp5K zbVSzeWENT=L`xa7-8!$t?W-XbHL^+#w3Uaj)LD9n+gC+M1$qbsw3%rcq!SXnfhI!_ z0($6(tlQ$O8(zc%TKe|Lg%qu_DSA)C5z4m7$+S&%ds^~Q8&&*Xa{p**snB-%ZeZ*_ zCR6sukXKuIQ}kXd0#o4~E(@_fHeQRk5JVbW8K_j+5)xB-Y%V$}TPt;nHYRmqcRPBd zLlZT7hrukg{OlN()DooHRlJ|M<$*{`{TibrsYbUu8S^r9TxuoOR;|0uhHiRzBz5Zh zHh`$KxTK|LNUXWl02zV#jeZ{z^VxekNm|hw5EC5RT82l>GZ%j`Qo&C!58Na0rP$!B zDSym;WtkT`QkTlm97|GuZaq3}FioquzZLM5z7Y2)JK zrJjbf+6-4R&ZfIIxXD0?M=cnSmA{szeF=%z$HVX+Os2pI6-mGKo3(zGdnm|qsu3y(gS6=xz{-@ZsH{)@M#o3z;)^Pj)Y~;qdV-&EHZ+-9#zvEB`LZ*| zS@Aj#!|THm;+7!yV|5R5efAqt@my0Kf&DAPL+YRYk`D2?Luc7i(7bzHchc4CB#C8xMc1|_XEzSk^)Nik>AhD{|K_`C{c-iwc`(QBPuxN4`^JGD2lBg- z$g_#W1n(&lk{I5k_-)AUvwRJ`7qXWo+^7qPlBx&U^H(DIoTHzD+Z70dA8rZ!#DZqh zs>fF1c&598+xi`C@P^qQ8f97dC5{ZLK2)*{{c2XFZS&5jdp|W&ZO?Cs3GF(TPCM8b zr20roSxWuci0pM4s^BNsGRW(ENYl!e@{O91P0xo&2z5|}7^Ui9n%l04iqWv+xQ;Q; zUzbSA4ILm!g?n^{r9B+;50!H6pb{ z(8KHb00s9b)2|UN}JchS;%=2gbcA8a1j4Xgvc1X%JLivxzS?z%fjYvl zuL5E0oI)pKUxE7b(QC-$Q*E@gHISHr_6%&>WyJl7ms9F|-yA*h+9(C@OPC7xo5^%+ z)F#X6snyImj*nFEE{yj?c|80{xgBO?|b^%MR+-peX38CF|#r)~6dO?JGSamtJ;J8}=x#x-8WwK5gSuxXD!f=Xlbz zuBud8;-O#!zGIPZYc{N#My_<4uauUJq;=4P1rw4ISK8vsgjg>YRpGpYaqZkd}49h)} ztQyfrspwRilsi5|UDBq8x*^Bu7%U-e4!71huM{P&j|VGXHH95Gdw{m*dQ!{>&ztd1Pu4Zku-rh;;a7*wO4?yey#7RKl`(=#4EkTs?a4n_H z*~4Vl_vgesy{uX%xwks~&s{XgmZ-b<0QE|>sghlR_o_J#Qc69cWNLB+@=mFs&bc)~ zz1620ZINzPtA3uKUL1BZ#=Nhr>hpQAdOPr+7?Y`1-oeT(zbNv!c__h8hI*D(FZWAU zr);c7aZ6Bd(6YPIuzG3o;NmWVsUl96R10=bR;zW2{|)isW=~~b%Zg-V%4&k`AZ|C$ z^%824R>^9wqg`R0H=WTD_4;!B0Mp3Q!{hlU0Xv%YW0npx+3ke`Eo2=Dw%p zcFRb0?UKdnA;>e-@}-<+uT(dSMLz1*2I-ys{dElbw*W@H0@E$ z85MQKEP^PCNDzhTW*P%V%os3W!W=<@B1Tk9YgWXFilVNrn1LDYWliXcdDon?YtFj* z)rIBrY0i27%{e_!S5=3q>h9|5xD}dkX*XM3bHAM^BRcGu!UuIqR}1v1smdju;$7$( z(t&gi1GH(h6OBNk(VA#%b8aKn7K{}CK0A?!G>|s=S094;$@gd2g1J9bEUDI|xtKCF zT-5)dYFHEbqR*P}mPSEdyZSTsvRZRd`ay3oIDfKamvF?;E>4|5-kWyr`rcZ}umovf z-_Sd}Mhm{Pv^DQ`ehEW+hguEMG_FXu-zD81Lb@IQLfu}faeL9|{CLswXgc*r@cDK; zL#xCc`)*LN1nb3`h{jYqZkM%Goz}{ipPE)#>~WeRN_D)Wjjmi+oY}if)W7gqLkmYc zUIX)SJtLO69_%DpPP9vCuP8fyw3%e8=zhY~bF?980j>uqHZ>y5z={lW`$T$5Tw#kQ z(-Ta`%=Ti{IZL*ljteib{@t&!Zm#V){)N3J)94#nf`^>7n#3S z@=!znQBjUQzryaj*z>XdYjXSxJqsBzreq5?^IIJ*7JEwwJe$BX3wi^z@J9CfiyaRd z*;qoLv>4|=c_4|#9HQYtG_V9uOpsgh`Uo+L5GozqU7}dOQ zU8VCV<8KmT&tm8QIw}E8t}9GsxVQ+lcV**dS$L21`Oxkw=&ovFNLAyL_Yzo zDCM)P*n;n#XU%(zUdFHly#ciIluy5H58lh=I-7E1ljK>VKZj^~1;fshzt~uiAKLv? z@-nbDaa7WY$-W>Se)bN#bFseUk)bbw+|sFKVi1V)?Unt@h#=Ns_;CQttQa#3l;g6n8p`_NTJqH&IB+&jEq#T6FP zkk=o3->zo2yo33k1MyPyC$5TcWl7^It0*sDtQGeS-zu$y@h?Qv8=%b!@t4g#`GV(< zB?Rg&S&O#GsLw;p&iv5uMUrQU<5gY>e+pQ^y1wec_e9*4&ghXVnMPFyXMQod3GaBA zUhRP$2y9VoX^JY|`3s*>dtN>)|ouDalPMZ{j2+lL+?vyGyk?1LjxIkOSd0}sMc2oscv@Be8J4Z#)FbQ zMaAmPgfTV4$KAK9D0JFW*pKPw^JlqfqWM)1LX`gJx!U1tQFTtODI7~uy&Cxp+dfTH zuiHdmO^R~o*>knTx1#DiLf~Ho!&~sVw8Pf_b6!Mv*azLWU4r^Jq#sur{$^U8)JUw3 zbre^w+%%P~7$)-Vu@Ue8xoJwBGf_-DXoMo;c4+AgVh!V z&;4bhd&i|gLil5STEAUniS`< zk{pP}J!^{Oc&MpkcE_`|!(|${FOH`twC238slJ5RoCkr@BAQ;+Jy(uZTJa|fjR}^{ zagY<_knW$)s>^2nrn9Bz|DcRZ(}+|e;B*`wK)*}q0_Y1X1WmwT|5TQo}zOJKK3 z59e5deU9^=;w-04WCQpUc5+B>j(_1YfwJsND z4N67vBQs9$??>y1Lc@Kexs5ZJUQGYImu>v9Mr~DU3}4oBx%PEgC$YFeePL5#inga) zs4$In5<8;@Xg~Ibh(cwZX_Wjz{#(Qubq{yG@CTSu?8U8to z1zcOD?yNIRk|Tb=F74Cxu3{m*(7x;4GA+HwL}BtCuU_iIU0m-q8T87DXDkM`sJ^(U8t)iW(3IhOeD>Sx;Dd9f(c&RJkhG;8mt=_vud z)EPZTN!9@W%G^5E^x^#y(Q1h$63}Dy9=&Clk6P*9F&s;(4hc7P*uPXHop2JU=SlCz z?a`lw`>4;pjp6v$sb4pnT12lAJC{;!ZLmb-i*D(3r04Jz>emj@eAe@a=_h?+MaCg_ zNpjf^mRr9$&Ha~~YQ1ey9NPzHu#DI`NK3Qp9iY|=l&!Pv`+DhBMU1$mG!aOf?!L~R zoHmc_MxT;aHf&6`qV@P4q%{R6*|@jV3cE+i=N7p-eJj zMM5Jzq>C4umxl(P4ENaJE za*K@raX>Hd{jM51WRx@#vDe;L*=uq?|5B^6*rMTVR^8T5cWlVc-wWbcl67^fDLDA9 zc6pm?o{>0&F^E07Ntu~)ZGF2#1Y93>%e?6wpErZMN&XmKB#6IX|B zPSqDIi(*@*kKtH?XWK}d?rq!k(o07*W07f;9S`Om(vT6)p6UA62_;yie};3E7U?0H zBAr@(*ULrTRA)^H1^m>$~(bvx3yf!DBgU9MlrB4l>i3)pby zx88RjhjO$_>KnsZ;0Lnz~n1mE$iw-VPn>a*qw8-f7qf9hw z*Ue@T9oMVXN=}q~2DI%c6P@F@uTT$%7hx?6MoB&c>OmYa_O{Tl0;5+p@BVZG>I(`f(C7hOWW zD0-~ui^_<*LwwoV;?vo~)bWxBfFncpcQ<&ZcwMww#dc2!k)n6-FIl&T-(AWUm0HW5 z)f*~#063OpuChq)`jFl|MS2%kSg3d9c|JNwOZ$y%loQz~T+yM8!roMr-E$_Z*0VaX z8WkcXPX_y0mctVJu{$zD~Q|tDBiT{ico5n#A^CS3gEb2#8xT-yXWt zr^v_|TK;X8%oH=fj7yt;u@9RzF~Y#Vg3OLS3)922=NAL=ApEv>O-s%6V=H$>8dw){ zCChPomosx~xrJ5r8=Wore^G2^r-kdZDLs<4UDlnGF8s;@ z7Flx+t!8((R2w>Kdg zQOX?lXaAQh?Q(#DC6;>s(-PUEB)29-xwyxMB_2J*s+=B?O(R#@a~1b!i@Ky~Hx9Ko zdycxMUHEoMJ2{~R(HMQF6AP*J4_lEMXkZC)h3%#&e-VwnMB|q{G_a+S9@!6y3ad|1 zVXfVo84&%I%{$&b$juZ(=V}y_8k7^0nk`3eiG`Eg`&d|$6e*jH$i2s4LFCea_*9Y{ zBF_wnFw5o&?@;8{q$qoS#_t+fS6=i_ge68eDMoz4=L<6GRvNc0)O_X1h;^F2{JeV>3N!Gpy0^cj&(CbHxxeX@2l4QYrXMKZmHoRv)WEvlo+$6L z{&lFQ)YLNKX<#?K!XpPZ`tn2rB}5KoM02`5FgoY< zfPw9Uf61*|kD~4;Qq=vp<|7T92RITfbLHn~hxm4B)*>2b7rk)wGg@8JJ~)F>ODM|x zy}enxnQvI39lf$=RIYxt{FSRwQ9sgNUtC3|o?O7JO6J&)T+3oXX;I`t8qN=D^dVMD4u| zw1Pg~<`30J3$F!^6#FrOXdEXR^SZ~oV_h&G1D86;$TAjMTkw2W8JV19$)t{`>mfql9HbX zS9C6r#*b4N%0U@jw+8GgF3pT;=1HMR}8$6bmXe{r_oc5Z%A6pSK7GSIA zaAj#Li-g!#c+(qifakQXMGo(JzIzdYni@4Y?TZpusf2jlq;@j4JN6*fM44L%agz}D zX7%2O?VdYV#9T)c&UuPeBg7^`SS6&nV!JoA^E8iWHcV9cJy^qjq7}=3Z56acamSM9 z>DA3Y9NURCTd!z4VrrXTZ0jhptj<6WeyG(-Y=ZD-M zmiLMdksNvZ12ZpR-{i>gJ0aS?;rp=_@peDn`p@aX!-UvqbxG<$7>Q;Wp)@~c5Lf#M z(QLL`GR`&ZbEHkNIE1k1_K4E`-LT|GW(BkBWKDcI``UD-qm}tii+XhGP>N_+bcsd# zT=Q+{ioJ&YjQyl2lL=uNSEbLaa>WvpUj_5G+djf(@oNoxlk)WuBApOZr`6ww2;7rf zH>`wNtLiS!a7#SgL_%0Jb;wjFchr5@YuKAPt!v?G^6fZRYlMwm$J4k&FI@krd>%*@=1=dp2hz9w3B;2A1I7EB60SIpQ81azovRb6b{U z6mfNiXzb{{(H%=LCkOUsj_+gP>cz?S`>>}#&*y2Y5TaojiHnw0mSz;#b2IklPdS_i z2PR`5pdCbRb4I(FXv}Q)WFNMB{Pl|F)@C6-jeTj75xLfRLsaK|Sb{Cxb_dzmhXaN0 ztOeAA3rG&jX#ab7QFokcIBOA|mX`?1@@l3{W6F|6GD{n#cr+U3@@$YGhancKtMP+AW&f*J3#z{dO}M+Z}ZxqDd#xYN7|N zCfelpc16zu>7n(ZtSW>kOo*(e2M(gPM9F0u7AhDLwBpN#xmNtd&pC=ZMaWgmbEM*FcpC_8maU-t&skAuteQbg{*e=?@5{KR8jf0PS zhmARRicJkN__1K0e1OGxfWW?ptJJQ-b^iT&~nIh46;@2R(rAv%BQn85{ zYa*Y)Bbv3M7?#Y^!wonkF?X4jsRbS?DMDR6%zc0RP3u&|Sv(7DNOIVXxX9-9v1Y@| z4Kc6;PE5>jl0t}8P79dd&QIRf??MeYcQUsayGv_vr>m$lw~qObIxDr79m2$-Ee?cO zem|XUZDYmGTpey;NvUg_wFjRfMOG&}GuA|_JEs^uWYJCUW$z{$f%dyiWi~Vt1KK#6 z*S3u?bqHB163;oA*{N}+O^=p{AH6MkSROjY=oMmadcVnosQGk;>F=4##O9;*CA6Xp zZF@{#S1|+LM{4{{ zHZMs8KQC`Ce?8gM!DhYK6;p$_8mmrYBMMbl_e~EoOf52e?ltWyGEaM&A9O3A4H_9K zx+?DG5*uu_+4&+w`drH@wf5des21zpf>3;(ZIh@S{X4Q;CJ?6&norM zpfM7S>H$-ALnG=e|xbu_Cct~_fK7-(cobgTeo73np$g^fh8yta!dQvPd2g6 z*8a@4$|&RO^>EE)y`vD$o@V4wMr`XBz_wUBvDo<&jYStqXoJq%i+X*S8G94abdEFq zta^W`n;JY~ilncm+-u7$t%(`Y ziqe%dTo`G%!KC3(lc9z~w4&(!ma20)6k&lSqYTuXh(?*{-d#U`rgzL@Z^a-3^&sj; zJVTGZPrL0ilwJf9YP@_@F6UDJgUY$by4sUW}P}xI#I+{K>6qu zjL=$YiDz-_^~nhaQpf#WL{m=L*Uj13S2vi=fFOx0>`gqOqa42x16jU3x7a?reo~*~ z-n5KhJjttW(Ut5#T!_@V$O-O7Qyg;Xx8Ck6HnVDN#~WCJ=e6j4(0=>)&idn5OPKGh zG1A!t?o!}B6W#dZfm2TB$P>%}!37ym*VOqR2Le_a_+iFLR+QEDsv3)_uian3AEYfXOQNb(c0 z*U(Rtd+-;UABAatyrubp;|J%5JlaFUYN@Sgv_GWLjw2jL4306%Dxc5n-K%+jR^>p1 zq^a>QnJe4vQ`yk01UCBGFv)V_{E)f&vZn%ztrN>i#ZQpz2mXchC|gke^#c1 zGdp)dw$7+Uk)ERLqWCM9mmS#B3Zo?JjJg)lwA1W=hAm&WO1(2vw$A9uqNP@pR^$Pk zCl5d;4*-1w^Z;b*{Iud!cA)8YwI6w}SQmQ5=+%%enb?jM+!v`n?iFdEFM>84+l}&H zMO@Xb;@nei&I*>iKJ@g^N2UA>V@Bw+Q%0*7e-Ag%ufr_QrB_&aVT^XG zzG2b{FKSMdNm1T?EXkL(Da$urt!yls?IC=-cNOmLS528!n~Og8dyCculTH2^-9*|K zKXG&L0rHx|H0p$S`(gseo-B7PFlMgZCf#d0Pxu$aujxd*q+w6c(XXC1kotRp`t!U@_!*uVF zCK592MOs!t^XnRRA~UL*=s&R{`P4C!`?JS|ym_PHb_RbwRGc2+DPC^SO_&=M-%ufa zB{s0ac0N4mTY2eq73@K*i8Mp&3vAG*{Ji4}A8C{z0y$I^>oXp#b0>TLpuTG0Uzk}H zGp^D;L%qJN=sE}9v{zFJf$z%5*;{{e?8`o_b>KmH5ctLnqUp_-Qy#22aaG1im0r|A zu8>=rwOs<)9tRu#=O#Y`CB(Oc@Kqx6WPJOw(iLs^kNGkJrA0Ko)#!VS#aFz*Dp&1d zm{yk%XUA(|Wf5zspXGUe+&`V2Nx#p2z2To72axNl<6rV9$#iw+mp&!3@%A;O88s)y zL8x?JZK|4LVhi2GxHV%%@UDF{+BaFb^IM~@FfYA~fh9P%aW>P=UA>BYUcGy2*yeUd zpDV>g+l~`N>oj`pEBuwV{r(UU>0xc&)9suV{8x;a*wr$2m)9-9trrOPenUqC|3Yhk z`jK+hZ2ZV-+!~_ZUfs{Y608?%A`LgF0WTa~ja{ndDM^kTnmfJJg5E6%@RB2E;gNCUQhVWj29nY&NYoV(m+%i7%!@(4Wm&~Ze3qKIo6ex?fP6o zs5ff~W7Qh5YuGjkO*86gFkk7K#eO*dNW=T!?YlJ>OQwel&ugj)^&{=D917xR|GL9M z`_R1;d?oDU^a+Zn7~Sw)f@+f7Ck_wB)-)V$7mR8P?DzpJ9K5i0%)m}kP?l(~9&tS|Qs zYebpMpX;a%ipEwEtNw};uYye`>`hvKIQsD~zgx2(18faMpbbYfwbieFd_;>(c53Z= z9d!w!kwc0cDAj`BoNmoa=*#rLfcC<9XplIuYOV=o!geDY<>1L5BoyT95}xYly&yeA z)1LmOEo@}f@qDBDHWhPT;k|ZzSBm_^Qma_TZ{zu$!%w9brzUm=aBg(lnKWI?WC^T%zA7Z%Rg0qnuhthuwJA`(K{C! z@F`|bZr)y0NACr_8mx&Te(g*1Voy7B)j3U~(ZnfS-0a#?9Q@MSgf)@&IZp3Jney@i*`ia;#*a~##M=iupwD9D{-N!om zABdJ|M1NStstgI{b}8{Xa)KOUwt1pq9mhPn4B>n3ZItrR<7;VH6Giq9TgvKQ@52jh zJgehh_|}??D44jK{cb;&U##sSwH5Z7oGJhI<)v&$%klhDhw?g>U~YYsNl|9EU&-8# z58>CIZj>_cV?KQuvELZV8qMyu-8xynX3-f-m+F1Ui?sz&(f^Lzhth`uG#Wm&erCw%DUN$BH5@ z7T_H}x95}YER|^Byp!cfn_UCHzaC=PrXCcvjKIe0=OG9kmS7Kn`hs zDDkX#;c%cpP z@oOD2Sepelk|%@t`p_GoJ<9{5c%fU~Ed2Rq9laN{`q&Ee5=~e>-tIyy`<~cII_E?` zTJ~ORcCq1OG7{PL=1f|pqE9V*$VHDR+{-GKRpgx|?-gkvn(mm;ir$^}0G88=9zAbd z(aSW}bSlqZ@nqF~g1>?50rcTz8cz?^=7-xnVfm(4lh!ymUeP0`%wOxqu)>!L@yhO< z3|wL18W2xU6s7g+oot`;O=g_!CY`aM7cRH1ciL+9qi`7>;@m=dzZU7?T9nRM0ynU= zed_QPO&Uw@nBZUXy0&fm*KBK@{CxRTPib9?YYtiR<8}M8leF57r`0y@C*W#ZrePIv zi7jhzjUDxEFSQj)i}Vy_8IAV*{*(ceMmz48;AofUM>m>-w`mRvnu9pka1Np$q$o?< zw&rTI4NIUGr_f_XZ6J@UwE9=sp4Rq!Q{$S_ju%=0S@Mo!I~vZTz0`${<#`O9=K4j4 z3j49!GUyXhoj<>P&7^xcN+ zZO_KpoV>s0q7`c2B>UUkc&ZOZX46`2_Y@bg!V>R?@!J$fwttGT zc5|xwY+EfAOR!$KCR4&Bqxh#(H9ox-!@qK)g)DarkXy?9)pM9JvhBa>xicr26vYa$ z;Mh-;(YpFjBlgp3H7WEW3)yXn3`i1j<+p1EUb$p{>wUd6IST1>=kbP>Q!!Tg{c?sS zNDpgLl&$qA8Sj%0t1ed>GOQPQ$C~Ii`KzIZPv$B0u+tfa{9?UGkM_d5w>9qHx~3-C z{37)^Mrq2?xaaIT8d>TRHR?$@34!!5u9LXR>S|OqS7Ur@5soED1IIMw_X)3QO!~M> zT@l)XW3(Ygd`h=-l~;otj6T24QGH(eNOyR#UW`?wRZ)9)V{cR`cCwKR#}cH6BcE(7 zadqdzE_DrYh1BscL{kKv12;Z(Td7uV=E$)XksfkLuP*EkH2QQ|tNzXvjuG+LZrIY4 zRpn5KF*;_iT42T^h9ewD296j-Y1qTT_|-pF4WKt{Q3D_+@;pD45NtGDl&LN)aFL;2 z!f_>YbuiY^m=e)eO&G|fGnQ4`t<68qhl-i?UYRBb70aG0UJG8)e#z?DF2?Y8`PKWv z)4-DT)o)N~lBim~T%LHJ2VeaS*9!;L`jg5TSnoGh-`p-PROsclnUMuH$INh+svL}h;Cyz{66YYghw>P}M#Hr0EX$HnU;$L!1(Lb~68Xwjk zR=c$02A1FnFV;j^%vU)YdPW)5Y5|wzz=$NQiFOC?R5nJgJ)l0H-^Rdt@kAM8xfLbt zcz2^`|E}!slZr$GmebKcZ>?9D2oa0jL%Qg)DulB8CZfe zu-z!W#A&>-w#P=bbiR#x?ar3ywIngRVwee|W-+dlRz)e1#?8;S)zJeQ=vb08xKTFx z`4eXo)BX<7yBPa47G0lfyT;vo7I)YpXgYE?SnNbO8Ude#)RDk z+4f&|q#-AG3kGc$?Y-U_YuvkaNey_tSw{rQlslU(_h#r6phASPEZ~kh;JCkzB}fBn zqTTamlZ*lv4ym<|G|*-0KW(jyDAuO0(dF-b>VSuzrT)OSk|jUl+tGL*x=gj*U(Uex z!FH4T{O=ESjA^ZG+1mVE8oM}Nag5P+dytE9YiKw1cx6umXDVt5nMT9>m5k`L!fM^D z_6F(?jO)YMMZ0R-Ug+EEMXDihg7~Lz;n^Bzk9`AySyeFG3hgHn!mVzkIzJBr{VPOM z27zHQX(K|Mz5f{<&FxCN_*h1JN>USnStBr;grbzM$Mst!lhqMZBP9f8hmmt3&AJ(_ zZ~E%aYV4RGAu!hq=76E~`2cJElV8cyErX*Z1hxWZhoZb{H=^}vU))(UqJbqy1Lez+ z;||F&lH@?@D2I&j84;6qBh1-KmexHq(oV|u zhB;sqWn787?BKV|Bbj>#OW9#Cw+z-qZ{ByC!5Z$gRXtdkL<4iZVBR>&xJX=8aeD1l zjkv-R%s?a4xHrq1eR+RQ{Zw?aL<2L>U}hT18qs|Qo3-6mtwmg6334UVNG~vpWzPRI zrL|igIbc*`)=J7?7Gup?{>K%TAXhSt(o?GO_ouB@(?vgi5pkP|7iFZW;&)g zvQ4%5%U?IB5m$UA$uT=A<`<^;66!&#_nAj7QV(Lin0F3N0f~p(iB5iqt2p9n262Vdk#`w!uH_j1@=U|j6EF9(#bp|0OP-n4O~dTHn2VRLQ-$z+VZG}005luT@gebXTjH*nL5twBa(UhICMnC?^(Tc6{d&96UfD6t5?7dwA2Yeq-B&_HB-ToG-&~zz334UVNV1CJr~b892eAsw5+`99C6+ZH za)r5(DfVN`Bp!G1S2d%1W9j`5%%+SrDN4$-Nxbvpk+kLIF7*e#1tQbfNa~% zjy~)Uxpk}1{3t^6;}*>i)M_|Cz z$YTE-J!GRcMDg?8PO2yG8d59{?yAb@zJVS2ovNq2_8%^9r0vepSCbq3W5Sb4+z+B% zwb=vsjDb7U`1Mb9tP4-Wac@~sv|asp%fu^cYJs=Xt~1iZn&`&5Lnx2A{5JKMq$Ls! zJW2MN6O7oB z5&aq# z<>75{=vE@G+Sb{WUISM;ju@|TAsf9=mq>ggPh?@Cs zvqbl|M~*cfB5{Qgrg$%eb_ajlVk=6$J<`xsMqmUbqN&eG^5DHCz1NfESQknzb2WNe zFa6o9N9weZ;l}Yd4Sg&&%Dl6QblVBY=s#B?f8RKa&&X&B_nTzz~MQ2kwq=ZTc zY*G34S#zS%uI5cI8=`?FNCRn8+)~C1Jt}&O+IvQjfz)w5C?oE8l+^>rpGm3TFUmkp z@Gn{NhWlqS!>M{|RW;1OKES`^akY`g?n)ZFb~JWT_u<%;5%Hw28k4@-N%{(PE$S;- z`?Mu%FpsRk5V8hn`_O*K*1+P$(7oJj3ymen3Cfi7e=Y+34|#9l=bnR%KpMz9(vuNL z13e4bFUi5=$bksl3&mY^nFe_iWP@^iQ9ND1nq&ly4D>}%J{f^^;jRJ7BqNX$lmly$ z5m|Th41@&Pu}|{o9(z$_5brV?K2K+)w!B7<+)x}{bJzbsdtRI;Iw;e{pPW| zHeT83He0t2-qz?y8xVTsx_9q1swq>J=_)5u^A!+Eb=_Kz7~;w$PW&W

neAmH&-s zDb({}W{((-YRZ%|ha!@%oENDy9{zjA zsj9v<;@TShd;RfyBz-gANdp-@X@DA5)gw1?HF-RegK8gA6hD zku}>IbEOKArMzXjRdw&NqYSavvKw}am|K0k z7G)GMw=4-%A+oL&>@WoF(3mS#h^$-wz>V7zQ7sH#Y0Q->MAp5Fc(jRNJT&G?6(Sg7 zV-ZXUz2b3Z1eH@&saDEYsZ?8wpxHsoRd=OQk5~i^VcxYW3SLwy^*U|#S1ZON#z3l8 zBiolHR_6hsRGK|yCThkhm1bzl_7<~U^Hr&|3Q|S27(uNGrPA0WtLt2O1dkuQuY23M z>%Aj1jH6B|<%_Hfe0C>IT&Je7mhR>Z|D3sxQ}P zp3xlGUX803?f*;RdpElCg|3>344|5%QdOk8E84z z%wy1E|KtDjB|a&r1kp$`D#)k{qM=kG4~Rd_T+?=(?_pmTtt{K4Rt>QO2(i4bUQ{aa z0uc0Wg%`YA6JJ^Pp$vG``U=)-^1T^}*cjNWNOOdv6!5 zfRIeIn0uVXj;?qC2+72@_^O~%Pgm7y%kI54_o(KhJKd&HJM)aEEtkG`;yV^|%HHvo z4yvIJ;*7`Qq8(g`uYd?W5i%N= zU3;n7ln|gDf`ET6F)GOD3ZhHSdRr(` zAOH*TP+zHc#S481$)&EWKfzbR3%*MAQS3fY$X-D!v9Q=P#3PLeh<1o~p;gM=zPu6{ zEs43>VV#JX=(}^(a$l((;;W&SC&X-`rt$9vom_^*L-`gOmI#S+;a%xUjS?YVEPOTl zEKwP1xkj^;q0)tK-;@zBLwZR;rRb{q?$VoDuR3kkvK@^%*HtxP06nTZe*EROUU7?Q z-Kv`S(YX4%#~i)>_>abQ^onMQa;mDAzPg{u7;*UFZRM*}lA(~H2))8Jwep_m8dlYn zvz9d(n=ZZS5UohX-mV%})f_m_(qB(v7S$_UJ7UU|L0fPCVGmk;gz5FY|9*cQr&qlq z9_^FyUYvKI9tJ@f+y@n1RWBZLcze>(N3Y+RxF57iwO#C%`@i^tX|?l@--lK|y60={ z=bl?&{cRRG(55BdIaj~*d87LJP9Jnj#J~T2#0(hTx_Qb|_!*`WxvkZZSGIaSp!U%Shu*Mkq+wWIpd3yx5aSUe2Dc(9jv)TFN<9@&Qp z!KttCuF6nORrNz?LtoAPue;jX;kc$e*2gyUEnw>tzPvNyaT6kUDBi_xxYdg)su65rK5b6N^MGr77=W_w1X9;8d9G$i?-xS zL)L~MI^0PWL^T}Mhg&=euLocKzaoNGLBl7_f~1wnaOuvM6Pd_vRMof8r*=fYS`K|n zd{xYCo8CX4MGzeh2=qjggq~QJ7#M=`IJcDu^eaQ4!_~y^g^W@wMd%f^LpkC6fey{6 zj7G;+=@Ro|)=Jr4@r)xG4*#T@_ymOdN@Xags`}uN!)r?*+wYvXUtQ`PJ93)g8{hoL zGv2S@-GR&JwqCN;!w1)uO1eQG;-Pr1{TKETrBbxoR8@-5E2_J4vhHJAq5ITTU+Gs3 zwJ+=j$2@)rcLR7gO-Kcm>=LkCc7wuKDx*Zqk@qNAp7tU{Fzr#cX3yuzqN;8|97Y^< z^!jT~J-jA6XL05jeS6qN(XW6w=_h;Dk9uu^^|wFv;+pKpjr~>#6Ts6q?%gO6zx~bR zdWF|H`@UEpWN$CfRrU5FPFZ@(0m8U*Th>8fkqLwQs9`B5*Okt?6v9SWr)yywk;7=Ki^2D=q@P42fB?*8qzS3afmJ@EbxmzWGeB(1vQ-LA;! z&K@CJb;XW8MDA*N2jGsg%0>%X--U*K2$5c7yLzP5YOntW%i)Q_a?OPjp+1plS_C!b zM45M6YN13Bi0s3D8GI%@VF17F?R(hEw*KC7{S#Thga}HnMLhECqv%q`*s-58FHYI| z&;RX#^$PHGFTQ17izaH@?zS*{czQAVme;vP zD#tm@K1BF@MbwbIYKV-6$Zn9DuYeGJn;L)J9|O79hsIX?))22ZN`%y1vCBv_0|GG9 zswKSaz8J0L6fT^)g^WtHD$cT^VL-TyN-XdBn)fNS=1oRIXr*fW#k)a9%e{N`%i#op zf7^M$?a=x!Whg@8-*^59nBXg=(mKx>)883HMv)~tah6(%h3M3&U)f|CbGK0-TH?iG z($gF>M9Y1pv6al|YAzHqDv?p_OCC*7_tl{KUFxGN9_f}cvKO~4VxV3x5yGoDO$et( zfoO?V#hF7iED@T!O}7@gTg0Z6p}kf+wRpEr#&BJY_2Kfszw~ZPEfoJW)FY)Wmp&v-9-42em_N z#}9A^2vs|NVA<=>A0vM2R@GdOY}r|6mFL^@bq3pdMRe~fC!A~X?wvOt+<2vb;_0RG z)y|-ts_Ns9KTda8l$T^*S7HOL-uuVL6Mq0ZHs19sxKqU4a{K@$)<`vefU}R(IS_|V zKY!wit3BWT(X`2(z$;LRe|jb2tV3?#{j2KSd8QT!)kM)%^`*}*Sl<^~o$~lU+o6Aq zAK=WX8kW1k_wHQ3{u_Ar%VXy1=oP7nu5zlXYvVh%rs0XT^3|C^IaSr&6DHKZ53Oj6 z@QTx`Yj`evIAI{n?TDbAaTq~CL`^0{n-sAcEdK>$obdQRaUM+ZP#Jxv39-B`GKxK1 z>}XU~`%^!mR;{yke5$61ur{ps* zwRn!Md?g+Ys_K1 z5V0rPJ!Hv@qQi;bfRG4wB+jurPq02;BH&59!VD++7WMJg#;03%-Q|pv8bZWF0$E=v^g3?0|QZjIPM;(@OP~ zH6|IJcf+1o$`H#7Dn*xwbD!#&wJYqqIHslCeahSom~bjmJ7kU6B%2zg47E_?;bf8I zbxVX&t?|}-u3@}`5cbCsp%zNaW52RlqERA*Z_zo`hlXf*CW^id(Xc7@1sRU0#EY?_ z!ZaXg*cM*FyP{Q3?1;4zW}*VoQhf!{5KhekQHj2VRuavwAzFU^5bqWfnaB$1)pVqXIarB|yHqz8neOBrKt zUe)^UdXN!38u%(&?0{B^&?_1b<&;#yq805JZ+0kJ<&~DJg{r&SR8_~^x4-%7>F@5@ zR{w-bU3Y*TuB=)`=oOWxoM=aW9wmH{SE(E5x-lGLylA3Y*}7ZUfqjsC!xhn_uZxNu zHPKx)iEEc35v+^fV+~sTyAn-km0zv8_`RoSi6*p`+^wtbik4{hA@qvcq@1!&tV5Nq zXq8vwZe1-@wAy6xu=+q=)g-Iq{u(^09iv3(6_ux)Xh-NHTm^*j#jck2a9wvv*N?Eg z8b+(Ysn81NLGle(M3aVS*eDTtWvEszgL-AnRyG-9$FA2@d9v;rc|w#|5*nG2*3A+j zk!tS#qm`n(twFV-t^a-Zk3IpRmd{?snP+?l8mv1&J7kUhJlE!Iwd#ph;F9dXI=plr zv`&pH%SAhO!8+N|hY(&(wL^T^FbS>U;vrf!)rUbRM@X&VIp?0xVBGFMw?J6ej6x@$i8z~K?GONpq|i?W8i?DbNH`b6v~I*}n-ZigTsJ$d&NELVNia<#9} z3U?rrzCEGp>$?FHVlMvaiAV7+(Bx_O46l~kp$L_svJF9y^(?Wr@Q-pT5t2V~2MD`? z`co*+iqNLaGR9`AJc50_$hg;qHN>!a2-}~{7y@xRMKJZd1dY5SS zk`kd;GzQ8^wJP~$D%G~MTrDiA)FZSyyqH_6N!BpL-|cX6R<2%=EP=Jk36|S?Sm-OI zQgp~^_wJkFeHj&hO12}f*l_|?$TyEoh=X~#rkSWzq5BZA9yE-I7PZqW(xdwJkEm6P zKb5b_Q*DDb@K=knRClFPkI=W?53AUHg1(|5`fl#v1)`-_WF70V&vMI1p^AKsD)xD< zw}!_h9v!i^pc4ClkeGMGTF6KdjD3YNI6o*tGNb4|%Bj>!`6`uan__O3O9cCNwbHxv zFkdaaqmi?L>znEWzf0MUb$+qagl8*(27uNHIGHZfN14@lBH`NE2mP1=-#&vCJjHqa;-SIP3y+T4Bq-z*oc`n&+Wk_`2g@NJ6hK3{2lhzxk4&kl;g&RkU`ujC)_O^7}j zs)@t^xtqMuhmah_l@yQJ%ZNKpsEJZWs)AAm5Lvp~q}o>1OuTy)Ut?mH&;7eKP_+{V z=Is9QiqhI-d9SMO$9v}&iwNa)_%GMR)qs}Y<9DB%cHc#vd%jldEOsEe=t8|)-~IzW ztvX?F?AV_{9$#Vo)MLjqcl~IU_`B!U`D}fSXSOkfUm-%*$1OYO0RD>zP}hMngkK>- z*Wf<@4$z9Ph=BDA_2L!WnfTeDt|NLNAfi@=@GBw%Jw0g{5z%r(MBNK2BBDoth`wsW zSB3~uCm6!1q72hGY1N@Ew1d`Bf2HCY+L|W7c+lFXGL?`-+S9(Ha z>&Pj@qs3SdB{Bv@hOMKv5dmM(azpqPB6J-+0>qj>`P;-12OLme?~t!zcU#D^@3(Jn zg4{~c#2%IEBgXu`pYC37ZFaLEVw~NMm>HVwly+}I?Kb>eoH8TD!cGAWKN}4iYRqYUO+DJ67vuL<~l^c80YL-^iDM5Zz{XNDkyI}T?Cml3ZhmDw=>jU$58L`7f4D@tWvkeEkA zC;Ez4pi!c-HTlykLDQ&}A@Y?Z15`=Fh=?15f0i+riK~3AK7eVmyYs#CHkY|zA~!l1(R{9cCjDw1NH-8Ma2242Ha7wjFpmlo!3r7ki1KKMZx=4t1_}s8%W?R&6I#t$J5|rJiQCH;^S=i@C;D zqe-o7;*=~Iw7k;HP^yFmlG#2ta`*d|yGaJFC{@yGFjVb#Ks|@mN7CI8IrEd{K+q1@ z(55YnRIVbW(*1)~3ma;oYPC|8%FxYFo3sNq)M!hT!CnjLN|iclv;#KOX$uj#<0zGR zA@;Et53_}c*g4%-k;*(B=PTObwh)o~t5PKy&8lKvF{eV+Y7bBHK&6OSgSAkDmWgpM zN;VmS)f+09GEh;qP*J)MT5RGTmHalq{111cxDw03cV>6=qbm;l^c+4*o7o+)!Kwp? zuX22YRI^9qeQ9R*fDIPIeSs^1?nmS+rHttHVGznUM$@!J(rY}HQd1Z?0-^)3oY}&>W4&Z>NG~xvkbTKNS$Ex0`(>anMP8*=S+*cd2D(quU2Pf`VRq!+ zu6;1|t{#Z`dZJnz`GU$2gXpNkAe1UvZiwiSjDQV%&FqeUYW>U5O9r{_n|I^>C|b2h z#VjOmu4A3sI@S$1^&_AaPY^~GcY{83M1Vh^oRt1izeP?>(DnH$Td4lgd8Hqr{)xG3 zUWhrJ?SMvnrM_fTvAS%XJtB4(LakLVWSjc6%F?rDC2 zynY#(SD7VQc0U4^#~js4)rnIOEqYfynsZ4rl+)e=aq8o}4C)!~M(s9u-(s5}kJrZU zb{kxB?PHo>Y4Sw&5D<4RdVlRVZ!g(*XF{oV8*Cpn#{m8V;=0Dz&Mz_b{RdN@++i`k znQFH|@E?F2_-Y1Z+}{{m-whLNd51-*c0;#Vd*GqPHo4T!Y8_5}v?bUP?y*z%OqI~c zcG>|O>a;~<;EGZuI|hOsu%Sj<#133hs^kUyo_4^78f_sWo}CR5J!`BvDIRUw5@p1*no^mD7Lyc@4sD5c#1o`anHMbXDIR7E5&2xJ zROacyvyWdA_W@{!+d@P;{l+4XlKssAEn|tdwl~S_#aPr)QWY@NGX+|Q3bSvHoz7`&^OFk zrQ$l@HJ}}|0k+g71_MgPb@bIhu!A_!0iwN34e<>B$(GJLp@u)GkVmz!PD;3wYfw`69QDbfqK^qu% zrQ+H)343ON9S4;D+AUt;zjNkC+3Y@cy+rW0;Y!Y9BAh3GmWY^%@JY_&PeypQlPaPS zwf_ehMin(2_+*4qc^-c1nh{Qn0+sbY@J-d83=sdTSJ z;L^(?*b4u&sKtFd=kc(XCq$HCF^?J|Lxzc9LMT=A!v8=hmG}8!Wdt)IU8#Uh`$r_e zk8jO6wtm=JOSM$~SYWs-Hl{nsbcrtUccu6Dh;*Y!UsNg;yE4aOL9~T;KPD(F5OG z@aS$;?E}OpAVvdGUQxc8Q&l~4{r>e4A5CfBvMis`Cn~%H;_2?8qn968`KZlp?eg$x z@*~F8_jz=5XVPUSqwi(}*M7f@=%1~#=s;Cnfm)%Ak&tmYWat%@QF3}3h(8@NuKn2I zE1HbxchltQ(eE^O`So+Q&NAklHm-jA%Wt$tyfhE`Z}KRl=lf!m_vll<2YNneMj4Mm z#&eLNSGaZ=C8uYBIPT@E%w@Kw)!1c?Ef8cX5b7 z%)vM0RhDrJe6`Wji`3WO>4^eCwBMg08kvYb!fdCEXCUK|m{)#9WvJ|`It5jG-Dg&> z|KKY-nGEMkD!*$)H0p7X^;lIu0OAE8u8IhyLZuFRXUK^CfcU~32qCo5p#Fru> z#>1%4se9h3Ga`2C8auV}+x~_NZRiqgDpx%|J|w2&G~T@*QX;BJOH6?rM64YuBojy#{z6_k~%t zL-HPF782pUBEo%GRo4LV#zD*1r(%yHm3xtEk022_PCEnfWyG924yio0Tzg&-;rWJ1 z6o|W!iF+XvN#z;GwP!vNIj7mFfBW(qwdK&MNtJ7@ygTf*Syk+!Yi_?oZ4Y!&B680t zpCQD^qKiHsI@}C)xQK}THTPX=mHSl%txi4c=JulKK2fW{y-25q z&Ok)oi}F551ng*rJL#7IvHvk^c3ypJ2}9&PRd;0FQDY5uSc8<|J3ZGvWl#np$md_Z zs#+ZJ_!*{*Rr{t4B7F7{t$^Sp^UjL1+RNv>vZ;s&pRdGnbh$A=Aluu_c2fDQ#|5H*WNzy-4ma&Ow`?yh_K6q=PeIDureZeAQ0OCvFb_BST7+}xH7Z5 z-noaexV)z|7mWvEsv!{>xj-u963ogWX@zW0kA3au#5WpMrQks}A* zoxUY@18TK45NiRUSIAdqIF~(CE2Z*0CORW_fQ;kn&(}VG1+ zcB^VfAbthJ+d$|Q^3^=foFsyHpMFW@wW2mv)lQIc=fO|ZM%+2SRg}-vidNZGwKWj` z0%AiT$}2OwJFc%5e=CuDs7tnszKF8pAj73H}MuJ7CN zGtH^XjYb9U2E=F}{sDwuAz!U|mpwGEl*)TaX@~5bHuXI_{pgiZ=VmSW$<7(igKIoI zrE|@=btay@!Lw$E%TNuuc20QbXF$v#qP$|(_GoRiDemXe;cPd647)-qQz~}2EMs^0 zYSdZd+pk9NIwERiGPs7PdyHmP5rKHL84tY@{gd|g%xRdICn}#AN;?jKj3Xbpq&+@o zq9Ifs*T}>{W`3xT_kp-HXQEvpU!5QFwA8PaQu$n>HU$}PAN)l7>$z&6F%q6P;@ebya@=BgXl+#dO zsSKY>)us|b8M=r6;fBka5AV{(9zL_%c<$BaX1k8VS}l)S*}TK`BENdG@x~nQ7$T$l z5#-_15)fTSWV9e!*-NR>gk3IT>=386t(s!uR)F#*$5uoNvrI&VOZAFG5h;v`%d^Jx;zx5+D!*ku47ka}-P^ohNFl~FodpCDv zyr*RQM|yJ|egeAlY!EG8$vex;?xB0{+B<&W&xXk8emn9`Urqo(Hv_sKk#n?+f6nQC zgnCr{hFs`{%ol{&fsBhjQIBee69i&c`bYhiJ<^ZZWQ)(>Q%E0~fASu#vrj)lCnT*E zc()m1(~rm&YA$I{>_@2OnkCt$enggTF^^HxXbQr-iwMRXo!M0lb8Pw%$dWX@sNZsq z3Bux$dxpg(`bT?AKO*xg^Ek_n2-v_^p4+(A2xbk3k&*n9sWj%xd~>b(rjM-A-gg^* z(gN>Qku33=U~k`Z!p_ZKt;oM4_GKU%r@h(!?*a1}!l`0bn&m`%^G6RiKU(Q{AdUj> z2kuy{Gj-rl+i^64?l&SXTIIdwA=Td9s;WW8eOr(3oVe`uc8A`nD8uWKh`Y~wr8(`k zwVL>wNRTmW%#xj}uAFI;rBe~%J(!5^EqiJ6we#)-;&N(r^A+tW7p&M(Dz3c;6Y=W0 zuQz^t^;$3(#LUa$ zI>#W#22Xw<<5@)TVnk4>xJLHHIBO@m5{UbeC6kdQO2sv@FXobVRLw-CitCuKIgfG2 zE68ZO4A1H)FV;k^6@1S&yt^$b>Xj>k9bP#^qEvW=nRX*csLaixqoO!jWKU~%$bHJ%Vu7Fxw~2`8b)YYXj2o8Svi_UtpEHC~oxJ^h&80p%%4B53<&d%L9=q00 z-}Xk!L`P7Ddzvz0G=ZK48IR3#V13H0H$B^9M{ad)eCdtm!*AN=m6=4XEOr6y%$#1oKl3oJiz`seD(mut^T zBBFgjUjZ4T;N2U)I?)hHwQ=LZ=3S$1H5nQ4OUPgZXZ`I51%fiXRwyGz7U)+X<2xZs z3{g`3qp{(MubPaExC%0uOOHNxP=SatVx9Z@Ts{E$Wytv2LVLB5iH=BAdrtUA*JY3^ zx+oCQj<(wYtqc);6}ykw!A=bXvZS`uwPQLnvab>qeARPb!H$TC@#uIw;9Wyd2BI1F zC5s3556HLcsS%$$MeehQU)?3?qrrFTsQD3Q^-Ijb`H+D zo2ZbxJ(*I?8Zh{quV zb>8thcfOPnJ!&$d53!yK87I&CN?UqK+*7TW^t_j3#D5?I{fb%AQNCOwE%4(0YTbvq zfHg7^lbB_qA-Hxbt^$=JVuv%WN?utjm7V%khy99(tZ()e5$=)HeL6ov1WUhL_pt~P z;c?1&#a=>0j%};sc}0Y055Cs`mZLLt*cph(8Q1D~wiDqwo$B0bkceCdT!$JY!Yi$+ z{s9>q$Id_mJsPUh5Y`zYq7mlAD}g`_)>(s5Ml)2WX=VK?Y87|t8-Z93UG&swIqYbL zS~JV7ixL6Ln_*7$-aa*Y7rtU|Z&051b|T{MyD8i2%yv>mUY1L~;}8*L2 zgG9iK)YlNc4-yf3VqYc_5xb}%=rv{{5nP81<$iu4=ENuQvudq($zM*I2cN)vt2u7X zUr&E-mxY=ajD4|5PKZtH!B>Ow9w0cGg)4TJDX2>HNuazPh_~^xxB_`^-n&zCg$19A zXy3kS$9>1Peq}z510?num=0EztJ^F%#44dJ&QLC8fgW?cbTvB&w>O z0^&{}#v4Mf=-!tzrmDI?+y}&@h{)2FO0=!60^$lx$OrOl0NtN^=-%dOXB`FUcn{5S zFE*dsWkIt%@6?%!JR<7iAn!{p4AE}%)%%9mQgc=*Gg609ube*>8`AgOr>a^Am4+GrwpN2uz!8} zisq{~UtuzGrCkHW94jwbeW7#8pCP=0tBR+)1A*Av5MoCmLpjX=;pOap0 zyz=*dnpT<9tw3CL)ud6&@qAuT(UNgpNAO=^ha-ajGDPS;UEljM6<3bF4Ty(c`uoKJ zAy}rA^HhUBk_QAj zT*o?G=wxwX6~2&%{unt?2D)e`bWxdo3M$0^xEHBav#L5koDIZ}b8qj3-d@f@J~`pt zR6tw~gzW~zTcswD(G^td_ZMp>hO7pnx#y@`zmj51<7XWb= zewJ5;Oqua)cn>Hq2ZBEf1hn$WiQ3Y`VMdM9Qk&C~Y7%V9XU;qap9;z)PJgpK*}dzr z70U~c*pz{pp%Z2X$)zI4B&U5p?}YtaY61v7-Ni}2hqD2+dKe=+yO zbgw7PB9M`16z1+%Fv(c=3I0iUZqiHzM4q)`XQ*3e2r)?aVbaM0h&&C(8mxsHlv%W( z(z%owcoAl5{*1X4=X1$EpmSEzo1UBHH&}6k89(@|?u5paDQVp`@`NbA&FWKl_lYB( zGxU+&+ZrW8d5Jvyord&{Swj$+mr|+hQifc?chDuRbloRI5h4RxCE49lhFnqqVBKd& zD|?&5x-CNNqie^u%j`^NCkAGKjw{o zM9Kyrl8m?xoD5<8Zm5imQ2R=RUI}a0ifEVNo~^JLim*(KF*mgN%IkoC=ZBdQuE-kR zO&Jp`cRTP&)^w#SmdCYe1sU*eLWp+@O_WpNUHmQ6yi$gt%zB{$B5BxoWTVH-rcLMB!(=2xOQ}AX_Hv?{EkYv* z8T`9_jlp-Hd#A2w^0#la?$-*s4?3bFGP)%~d8vk)F@~TRlc85+4S7jJqa$hv0#wOY zU6I`-HD88kslJL3uXl~y5tT}pH9pCns-R(rmTRRlR1=kF2>f5Lqom5#ii~cFP<>_H zkl57w5h-fuU1=TbCf7MpK`XJN;H&bCI!OwACoz}6S7oHN(dPFp302g}(7Lvm2aPB# z#K5VNuYgGFVG)+$(27*9VOm401z%msbUSg$0Z=7<<2oRMM1deAQK| z5Lrho^6E;|t#veHXv~#LHLR+LsEE)jYOQh#Duw^YiO9M^kgim!ZE3mcu2kxgLaVxH z64xO%BD+y&RdgAp64^jVJnEuJ?1N@g%*r4yAzFwaG+_k8716!ml(cFgB=Jh%tMbHe z&`RPF?Fa~^QjfTdkiQba`hxSlZ5p2Yy}9exJoc)s&t7a%$Ox|?h|Wf9ylGUpbJ|gK zi4c!=?>XzQhWOns|B z9co{xm1xox4LiR+=f32(5}{PGu6OSGogo;T0ulEQ&pz%rlQ;_vwHz>uU`zCEXq>}t z5YVLzjge>Z{g@O~Jda6}o8FUHsM%8I3|lrF=Cug6p`xC`yiVQlH?eCfBdh~ekhk4ni20QG7wqT2 zU$9qAlqz_H^1ATuRmYAp8AmR=VUcl475ui{AnTF(*sDc-vSYqmA7lq%GwTMl1QhWSdXR;fZ{-Mff~y>o!^(3mTg#>OI; z5PC(kQaR!2l4zxTl}fd(s%Uvd%T;%!Qjg$?V(@N7@2Y>4O1(}m`KuM<5hA5j8rd>S zG|oz;m4slP&){y^h&7}V%{&q5a65g3W%oL0Zz>!z8Zo6MMA^A=4>rb zS5$_|E-hESTyOB^dG6iBDIrX&7^x=z(R$^~-uNqjVQc2qHorSE{N5%2Bgg+Kf|h!Q zbN%MM`wWNBDFLJ>vNYJxlT{xmDdXdd;KQ7^1xqU4eJr3$gkB-qvl`QklADUVzAHy(d+ z`eyt7`C`gQSHg3g_*Az)+ezs!l~J2{bFZo{vl_j6s~dYu?)0)vp-C$PDPqzi-QH%; zjcD+KqDw@6hK={0tp0F9C^{ipm5mQms^WiBL^6&fjm{o@{E>7u<64^uxbdS!YO^ z^!aCqj28XDm-1D48qHSy&nG{7@lwlPZoMQ?K}LSBi9YT1p7`fmXH2Jzgups!(uW>u zd3bjVcwztWy;kR-5}{WpkCp4P6DQx*T6P5#r1Z7#oGP!Bp;z#JuLA9y0%Fv$?+438 zMnb^y{N5k;6}8~YI<;u!d})urTddT|_N9nWG}qysPL#2E>$K6QJ$bNcm99V&JTs5) zrlNFA$dS|RW&HHX$(;!s-ei8my6)=|0U2rDnfH)|8&xa3)9tLiMmLU{e!rm;qD9%t zOVLBLGU|SW%20HYK>%LaLaxJm)v5|wb+cBtKk?|OgZJLsx{vBR$9uEt8!Um(m;}Ey z96fs((5mZ}tKWtqoEKztOa^o#X#k?>dggr8MVXS zD@^aVFj*eu?NIwlU#W$PKz+n_axmK;zx~Q?7T0|&Seordi9kcQIvpE|SSA?%}YSm|K zciO1Uf4bNTltHb0SHq0bv=bfd$nQw$w*#|J)6bTeubY16R1Je2FS1kj@j|Cg@>F)K ze$6=>je7miU2Mlmnn1%Oua8sm70oE@AYVV3DyLTc#c6AfdTHPYlaci8gy?f6-l zl2fUb?P}4Z^;PVCl6hBU+ll@{KhgV@ei_PX_A<_R{O$T~=dhpn>pEMv>T8|1!l*NG zzoeh{Vg^oq}X!Q-JmaovY%b<5QYO&{Fli=+EBfgN4abb zfAo2-L?~7Ck0C-I8}9i>jG$4`yFR@Ri)c|_y`q|^>{2U5s8%YwMD$Z3cTL0DBlLUWC z!}r}714GceKCvpgl%c#-6O~;el$TPe?1X61LcJ0*afpTqL4fD3QDGuu<`0i(89Dw> ztyLK@uM9nV8H$KCI6NXv-mz+fhPVC+f4h3xFbJhmzV&`YvO}*xtF$|F?OsTBM3nUm zldkeU$?}{(jJfZF8vjy;=BvhhScHW{Yg?c8My+}zN-_)){bN^1<^AfD5Cn#ftmx>4 zVPxpOL~nX8;o3W2sTC~ePT!>@Se~ecMYKo-%hP zx!9jUQo5bI7Em8DrM+hKx*aB4Y>CEi~%u*PXXYc{CV*5PT^1lh2cM&y!>vzQdtDk9s0$; zeafiA{_x1fM1)tkE6b?ay zn0>;%4BgdYhl^TmJ^q3(@C0ejil;_BvBq<4{Cus{M~etlRND3R8GZEhFqZ379D7uc zoXTwHZ~VoX!QVkc%cTa(ymEj&)t6qIW;mjUkGV!l<2-vr^rGvYG_fv<+@dmNJanH> zs%&|4*Du#!-(+%|KY{K9gAOuYVI6iKBEo*PIVk@L#8(Uvycn*uI^#aSSaZwgHw9Wb ztpm!B7g?gS`XYa{@AsMfx#gQjtXVS|n4EaJw{_lqz5&D=Kzzy&x-Ydl$6v8~^PKis zUCPLuRsdq9MVII-GDL=ImF^}$9%by&S|?g;(`!8OCK(ONpu7|3TLbd80%G@s&?^ZI zscAuin!O}O0ua*8Lb_*YF_&Jf8qB(0^$`Qo-;(!y^l)KD+940 zEZ<;}AR~Gah-9syV{EXl1F`g`liT=d*5`?=)!FTX`7!AoWQgmYzPR!7+B;(XeIOn} z%vUl*tCO#!_=5_Z)6};r5KnD3xxGe2Wa+AvqH93ZHl19dy*?%8B= zZG5zY^?^(@-65}sOmsWC!H&&<=mIez+YzrQU(+gbigwh39ePElev4C-HwH33yXX@2 z4J{seMG+Rk*tItW;@^ubQU835V4g)S$9l;2M$D34$P(t&Ux4^~%o5~JyrO*5i45qN zyLH;hSC*01-I(pYBHQ~BiOOpb^$`)VYU`nDtvY+5&XXNLCk=aemIXWBg&lLpswJ<$ zSG7_^tn+%P^W;(RN}jegIzyDrESV9q1hyzuiY5?z`JD-5IqReLZTu{+XjfBCk|jfA z#IvEvh#88tWP6{CATdn+Dlc}?dg!9+lhO;>^4Q_Xzg5OI#iK!KITv<<#s5S+UWolF zpM+w*AXb5|ki#AF%GGIIB374H^AHBu3QnYk9i(uX%Ego@KOEw|q zJN<6I8Mod(slNAGO90XBPJMrc-scu*;!0U7v3KG3YwUaGsNT#qYunpr8#Eib-Pox? z)$KmC!&TjV9^4h{BUf0aUG02!?K?N@VKVZS6g87a>(S@2e*CbfX54YYA!Y-4y}a7~ zv7SSggl-Vlp*9cr;(jyU>1@A-7cZ=`_c~8U2RJ1Aqc&qe3jF!@a|uKdUox5 zH|$|rMejCa9;a;2yU!vg&)=TD`9Qrs{}+Hz-PNY#H*i`WS#l+^SVTG$cm+$?XR3V`1B`1jV|`OhD>H#~!%tWw>TDpeE^ zF&^y@551y&MLESR0e`+MwsE=(>(EOq7x?=|RbBF*^(H<(X^+mwuU>;0&Y}j%AK;2o zDVn)^&YGKdLhkAn^@4I@eOwMis1K`yI3Xu=S7c*-QPv7Gb<(7dO3}kv9_l$zg*sPG zM}=O}4!uOXPx5q+vQY)hF{~wmbzVX4GPZqGiryjg#7^jmdPTjUoGQG~6WgIDs&ws% zsxAA~yPXX>A6makem7rb4OO1_swLiS$Qo$%Tdea=sPm*RG9}3aTH{~gg&J&!8q|E% z8tg(2U##Y>Lw(djeVDJ}%xUttmzccVm136EL++ZsahkL^v(Go8hKLb!S`f&qgy;&D zt@AD+S|R31EAX?}#C<7gh~J-j(V?~ZUt6uV%-!rh_jZ?`er5NZ`*(rv_jZ?>eAK09 zzsgUHsO3kUKeoQ^4?mpPxL|Cj_RNFb?_7L&cbx@(+T{AO-~am3s@lH~J!0QCLV z?!+T^IK0hotAFWlmvrC!`eaaHebO`_e%^=P6nlE50SdJn>9?{1*dDE)#A4=P_G~Sk2ZOI z<#*fms_NYa*RElSUJ6?6{`%&%qaXUBX|?MXTLbYHWX$Zkh9!F43l6QFb;eKXM{adF z5chU(7_ndP!%bEcet-G}W9t`8Uafx1uMaS-4p{H!y-5RKG_71ia?0pW zL8~J#IHd-N7Ka23wTKm6g`ymTC?k)rVdbT3vnqLA6=`ck4uI68!_Jq*WjKAVlz;b0*eLUH0>^ zKIIakr5dIPg3}&|;9MhjZcemfxw2F0STE%R~I%PZ7JHuBGqXwUPdqkbQV%?cmu3>54;?U|ByUbHN=Fy*+ zR%^GO)J+>?Mq#>jV|iGYM_gnR#`*c6Jr;hfiCL4YM_gn zR<0qn%IMfdXP}F^uNvs0rj=``_ElBvqHT0h&#NZ7sA&ajqlUU`$1d7N7d5RAwI;f# z`^q$ozKZDBMce42o>xtDQTLT;7=0Ddv5R)lMNKPonI^iZRT1(kYG`>C=atw+JLsZb zgH3c%t0LDh=2b+;F4{&HHLXyCK)hu&h`cflsZ~bDF4{pC1;V;P6J6A_${MEm0l$x3 zw1X~cTA^Px(M3%wbWzigoH9Cg(KfoMbq4gPCc3C;t9lK};T@=<^7iBge4ys{_AUMS?+CdjJtztGbRl^b;yJ#C- z6qZ{TWiCO6by4P+X%!;~8L^AD(M3(GSa+sX%yz6(wqqT;Xd7L$Lru`5SUIMZYgpPB zyJ#C-)U-m6V%>pP){vYsI(AX^E7K}Zde#S7+on}KO<*0n=nQmG)5<43)sR|c`(hWJ zfi4=fijy9-at%u~JKQ06tUKc<%!zu1YnNx}#Oc@Q?LYhBhcocD+aca{n@aStm@Mae zZMF8YW_jv;W^H9JPWL+dvcsLW^E~Z`F(;Cjdr>u1o2qIfX!Y8ZTiWj;f@P$#e@gV8 z(CUS0@3bdcmS{Gph8bN|OG2ytU*EiaDCR`+@{CgrHU9i7F=OlV-@ZU+3(TU_D)uGh zXs(qK{aToJI~Q9;Y2~Pf8C_NEaMLb0sC_KvMDo(^;~G+{T+P41{&&gb)jB`NEJ{r< zy|V9`R<5Dihi8tMmd-fiC!Mpb`)HR@4b?t&xbt_J2L8C$o3-l78uD^q3H=JQD5A$# z(yA-#zV1_Y>ZBDAY28qCRk6cedj3J}S1>1vg{l?MNh_?+MFfwTvRdcvBM+#NSKe8& zhGG*C*J6g-1-?4KcD3XmTuEACozYdr4mawJ&D)D&P9(3G?KT1AeJMo{=sgj^U;K7~ z&i0r^$t&;SSwpoCJrNOn>zs+5(`^DsxzwXpxVMP<<9*7E#=Bgg)p5Jb(>@4uB6-E0 zXj-|3lI`HM8+`RU)ZmktWXLPeJ6S`uud4QjujcsGJMHakT1s_iTID+v8C_NDL#wad zzV3``Fej3i&uyw9wTj&ioK}Zce@DM!)>ErI-DM3+^l#7^K8=30v`v;eL8^usT~)D* zPDB@VUv-C0mNUCPGgejXq7%_Y-B;cI=~eBks@O$q=%PTFCh6Wnz89|c#V%Sy7xld2 z`P?Fyr|@)d0KSS{w1zHfTIDl`S!)_bUzvT##Lz`+=%S`oyjyD#jQ3%%&gj%dYv`h; z6*3$YX|gm8V_xyz0ItO@T1OZ48st3y%U9QsS|KYVI(E@Ix~OTD@3&j#^G=az<>=H! zYv`iZ8T2IV8d58CQ6M?h#x7b%7d5ToJpivF(~w$abnK#abWtFz8^k9KR)gT1YB1Ut zyC|qr7fp8!TtjM=PvLT+2gbTgx-;P#Qmc%Xy9Picts1iK3MZ^%7pYN+E^1o&q({E4A+?GpZ^({abRx3ewDL($ zH7wDwi`LLZO{>aY>8T8Rm)V3}f_(*R+)}CsD*k`?JKo{ns)_olAK`cF$~Y^henhP2 z1`&S$s+8T2P^w&a!^mj4?n;&W$0s3_%J0bxt5uSrR55D3Pev$J-j{~aie^BL?q0gT zei9<@!s%2ryjDqu-zlIxcmY`v?jVrBUnxsk{Z#ODI^8=pf0hWPitEO(zKSf;JZMx= ztN(#es%R5znT@X?C;7*yqTl`pLaF?o{wK>&su=$vGSE-(J&jl38~(^Ee-3VD_x}5~ zUJ0MM2f|;zej4Ap_%^;pkcj*#Iz`)ipye}>-^2G!{sm95i11GtmT3Dvsq{HWyr%%) zy7+T^<07fjC+7;ZeeSN|pYwAa`6SE`@w14Ew$CW0PfnVQy35F);Zt<^sm7|}Q@D1v zqwCT$ntJ#r1K(Ws`5R$*Jy@<+%y02~wag=t)8Ag{jD>gW?%n)OazzAA>0RZmSAe)P z$0L1T7h;pv)G8qu^P0yz$Jrv7KAo9mQ(i{&zrUSVnHl{VGb?<%YV7e@dgfcotE%nb ztEC@dmhk0X)NdN=_X4scMzD-jj)!_T@D1+{;yUM*qRaSeCYBkO(PfTRRnGP@t2OiU znwsQ_Dl12;E3b*jRm*?z6{=G!IIpEAf>JG<***28?KOSKnrKWSazG zzUr&<*qvu~fvyL1KSFiS)~Xl!5m~xcs%qPhP&-sZ#Z{uB z?7kxUvkNcQIO@*3O-6`p8#2B=<&^d@Yi!ebV$T26NR_W>W>~GnY;VJkn}IlQ&i~kc z?pZ?gN?)0?ao*%dOa^5ycEJ6R@e=HKA6nhE`l@YGjWylqI|WNP{xVBxwLj*mSLSN%ILU^ zLk|8j=AdUGV;A^}k$qs!eN0BaqI|V0(N{;Vu}yvar;@L_?0u90Uv=GAu%lDhQ5QSn z73FI-8Kos|H=nQR(fp<6}yz^N_r3eziI`^n~1c~s- zVmi9|TlF=sT)%eh>2shne7YB|+-oxWyb%3%G7!J{(`&VN{(dB?w?wF?b8JooV(*#r z*55v*gQv(PLZg}E{~I8d+w}U{-#2~?_LK;V(`)UEhVhlgKW7XrKklma+s6$P z55}2Yjdpm~4iQ}a%JtifpkCqHBd8v!Dn{^BX!SOoeO@0Wf_eM#a@V%o zcGqBJFMor;NPNa8e->TWRrOcgHJE9q)RDdX>3&6rZ#4JMC|A|DaMxfPI}a+N{BD5! zxyw1`Tk__efLPbg=lB#=`ksN2z5Gedk`ry=te+p{d6Td39^HIpWG{c>wB%G(N8wz1Nz@9T^tNxbro4>MZ&qGww=dK3da!(C zFMnoqWG|!f+)BRV8BdsixbOjAWT)M^GcB-^^WlotS)QB4>%B%lK>VmN}|yM@tv*Szs@?S z$u;f3Cyp^Kopa2M?d3kYs6FfJJJ!o9+I=!7XmRX~wF8&lwX^RLD`9ue9f0Ud|GRhZ zf{%_g8S%SpAY;;TH@3GpZ;Q^^GyYX0RlcHpGbi*U*s&83$IkedRg`xeqJMw+{=IuP zKHX%{SNMhm$e0f@_JLLdN37H)RlcHpH6Cxkjvsz_QTvv!?^tvnq8GesTJOWR&odeH zF23U#GEP7K#`c`cEYtb$lC?Xe%2$-HcAtfTKoDD(%-FqIk*{b? zXhkgx8G9|gYkiv-bFWUyc=?a#rYPWk7GS**anfgbUgxvL>K^aRe zduGbrVBewe)y|0d*I@a@F|YC!<*WU1((yMUXYqIGXY6kE;T1(0T(c&)rq@G#oQV2Z z67hIC)~{gB{PqyPKc}m6zJV_`7{oMeptn@2(E-lFIGi+PzDJd%dbQ0b(my zj*7BuckdG6F(<-vp{khe-}&&O+HJ@yQhCg|_Pip(^DQ8zqBAfPN#z;Gwbus`xhF0L zt-gV(y(?Zf(7Bk!xHib8$<;PlPs28%|IE!A3Iq^=L^h<<#I>&~S zB~L}$*=eFgXf$*DiFgz9?vi$5DG{16UMu)KClJi`XY5o|B0P^vFHpv>aVpw#7#Zrf z?CFz$*av5Wy@#x%W;zaJ(ZnqxUD8Nu;5M=^r5 z(66|)q1R@Q;2m^8+yt%K(27(pooknYPwk{!s47~{^Weg;oK$Wh*KS9Npp3b2Dw+@8 zC6#-TYxh-&h!Jctf~4|%<=W#>B4Pw=pMhDN)a~6rtf;P>9rH4SL?{>+pIF$&Ia+@tXBJq zohH&bDu26_b?5l)y(K4`cRPM!LDb^6Rw<(VMq+x4uW*ja2%C2!I(WpthiAw+D#<`z zrL}Sj0)mW^mm>0-^f(XJ{XB>aPu40`UdJ;wVg5}%PYU9%%<>~pU-pl*)EeZBXgownA;=5CjCUE=)5K(YgJ0m zd`o$DqOXS&ed&{IhwYpxLp2`dx1nY4mOj)>EHf@=hRqBq$Lu8B2`6E#14Wm4tTkBH zTCS-6`oOui9nQ5{=Ze+}egrcECbG_^@l=G4WAR}3L4R!esfaceQ(s%AzIa9ZhsuaE zT!%9prwP}cGSE?*ekwvoMOGe~r`L{5ukniV&77)=lRlgXjYpgl+nf_=hsT+Apldh%R74*Zr-_c7CgK(4n>kfg|Eb7jP@Z=K%42;D ze=1Tc?CnXbj95I(qV>C@uRO!a7khj16{{=Tfzw@GPIt);mq!hqQ<`4uoL+gw>y9!o z4WyX!_eDI?sVHAjzL`^1@kEb#x6XN&GQ1m52Ihy9yFsf%kyr7w&9i|`0QrjY&76Q3 zdMdKL)??tOB6=azN4#rLle-3~K3qd;n>*YUumg7{>bx^SzRpYSQ2T;+ai5{i`wXOV zJGgf565(F2D#mAHRYPt4aLWK92s(KhQ*2SraXJ=A* zm*Ltw91-66%9xYNdmq<~T8OhoaF|mOEKjGRYaQUxsFk*UGS`q9jAJGJ7G;)OspP2=!a`G!dAoJL872Lt~Sp z8E5J?XX<`CH2yhb7>~c=RK%IOAE7yxv$FqG0}&qc5)sd}^#h|F zo^eEYUX=)*Yk!YyKQH>qvziFc-4elg{0pZdo@+_vmBY2yM~UE^_)DCMF3C>;5UKEY zYMHOT=BX%r@8tKVJaQAB8x*Iaa3ypD?0r3U21TQj-n4yZmHcdi`yi;oeC6x>jkHUA z1ItU0dN?tLqOvAh;{c$)IT@>wzxio~T zMCkLVm`jGpXg}}Jhx43t+}M1Y2s^#UIiv0G4D(b31YWIw<5YB6exjKCK3jyGaWsEa zUO4-B#tc0b`IVe~%86>}(t3rg}f#r`$~Nh&QzX>YLmtzoQgafvUh!Epm+Jo znds-5a3yC(m;juUW_y{{IbXF3DC6s>sCRI%<2u)xqRU#r=fhFwPv>WM>D!-k-D%BV z5GJzDR&pw0JlK7>lihRV*|w%lxN88*AHcovg>XlBX1*65uV~a%#@vv>r!rraQxRi8 z8Qd9`d-?=h2QQos8S$Qe->HaKl&@NTBxKYvUtL|CiViit+%4Zd_Apz=X$hSApB3dR z%2(sTsc&68E4ouoMT{-&;4V6~w~wvqX*|b;jO*~^=S`eB=g!Yq;uYnqS%N7XJAc)} zvx#)_@{Z%(fbv)?`1=Ns!DmHh;n~E2Q7fh5UgBD1#MbZ?p2XG9EKWtiSKP1MSFEUD z$2HK3&x-U^6t0v#G1tny(CTo^?eoZ~$Yai3)ML&X#9v^@@hDD3;fmH>nDj#h9|${s zfK$w!eA|SQA{+>!CiLLVYZT zcs!7wrKbAGJxXhZcKie0{g#}HoUhx#%+KiG!@CE=yT=!&qSH+i_bw6HCXe~Kaw?*C zsk_IVh#W!Y)kb($bi1627;_>#uZZw`3z>KhI>SK`;TcDS*9Q@~KeB4SimE+cPDL)m ztCon|AK6RxMK7t#smSf{UP45iG7<9&f!H)Wua#3#@RfHsB65G!m{WJ}eO%L~5ND0x zQJCSj#j~Qz%PHJ^rC!K>A6$kF87?oVZ85;hs$wTZ|XLp$!nspz3$;^Ezyh@6#-;CJz?h!NB)Tzdpnb~xj7 z@T}+>ITd;5bQwbtd%^OFaw_sZ=ysF{`szJ+_cL-T@~-B-DiJY)Ek@9F_g>=hC=rx# z1fD4VEXwd~AlhSIBAAJ=qkgiSirfy*s}jKoc9HEj$f?ME<+)oTXvd>C6+I}YBHzip zK1u}hHos5Cx@9j+mR6~V;)Uo2;r%nd*1OJ%2=B}BxitT6maASkj5Bq7&z;TAy)Zjl zukHC{2@RucO4KtB{L>46@m3Kwmqs)ZI2&~QY=9W_d;-X5n`$E`BEl=bgU)BpjJ9)0 z$qU(+>_A>6zPi>a+&XgdPe$A19661;+fI;me-ei(N)beT zB>!Lzj$Wr7n2_sXLRJ~!U1%X5HaSPcftx(alW_44x{wXF1Ei=is{S_{supJIT9~Oz zs;pt~VM6eHUJK{*@(R1D%gbxV0;lbIIBl!GFi^aZ*F@+UM?IQ-ReD4t7~TWtS(4GV z*OqzJf)1EPHA@t&8AGa^yJe2%T(X%VWsKHGSqC}WZ7vb5a7yijQ>xaWqRZ;i&QNxM zT&Y_B2ZV{N!-TAo?7q4jd$(-=1|1iUKIKxo}`k-YvWnd5Q zNk@g{GQIY_gDy<3uAy?m_r1anzUS_oJn5SkDFc&5PkL~#n8MSuB5LJRxNArmIX1j| zjybW-IgwX9&Xj?9rzc&zSDYq_chLE1BJ<6h>^^mIDsmZ==N*UgSW&~Dij)ewe$px< zIE(UqWG6;nc}$x{Ft`R@BfrRaKl`>zrPB#VeIEFz=+8^Y=wO z(y1t4QNEcIzJC{XY=TqK2k}(oJ%chZg{9mLS}}X#X}j+obRn-?Lu%`s?AcxasmQvT z$3P~ISOxK}K~3%&r25EwwN_}y|KU``I}_x~2s&T4qtq(iXQ=Z&0}*Z^*X~{QI=({) zGH}D%eD6sB60=u%((+jMLau`D)0)YBJXfSD)Qb( zG^;4|L5<)rry`?t1S^&6>^IJdn5k==spE8)5bEh18zMN1a;EM_Xf$*D<4mp3ijoY? zn4Dw7oQe`cvod>uGWt$M388+=o{lqh=jdVV(AeZ?#+kZ(%P_vu_~(qF9kXyM;!NG| zE6uT-mHnq8zoHRTPT~D17ON3|QM)`D?`nl)TPz27k_GFZNJ*&C)+$|Bb z<8GXac&;UtR}R-+A0>hl+2`=A=#KcTXpZ-0)i+q;DRljjy_2?F2cN?AzsN^QUq6NU z3jeg(=d8U(H;$TqzacWZs&rjdKfrUGi|kWEBYX26vT&nn%`ikpSCy`->N1>hj*ZVh ze){C(`h*Q{GDJq>bGV5UwF|Fs#sQ+^h>Wf(U7L)$%K)#gYn9Q4h@8kDcGTSt=-YM6 zGupI@oQQz0;HTg#_@v|B&1kbcav}opsChhc3`X`c+PoV%m5BZ;yvnHcM>A_xO3yM% zd1`rSVYXvrFRv*V5scm~y_kJvxgfp*sD=MAw~9#Rc#Q1jHK}rzl-ZEuY>1dWMC42? zGcM-q>CmcT(?&_mJ}yjkC&_3o>@aebM=+g~`(OrHrljU$#;E+5ILX zc;QjV_$)p*u^Fa}C*wPW@)hN4F^^t&6qEiBfbe%yxko8u=B=M@EWKjeWKj0L+uaQr zKZ1-Mpw$`i^Emm6^3`~320Qq9oQvXV!sARCbG`Si`k#M(v&oUrf`D#V=pC;g4>oSyqn0Gzq{CyFRy2K-1QNCK|%-vtg zGZyO04o4Zt-HzvOuut-;E_nsZc}4kZ_knkd(}ed#%HSt}Src3%7dl0K)TBP*73Hh7 z5^FF$V{u+;2Q_s2!dVR!Ri6(PMJl(DYxizxQ>+hrw;`$A?_8rkEapUbF4*%ZW_yj< zPAbm^u95AQi9}G_u-k2pcuYfQ*exPF6C=XvBO+o?q*lBKz)XxXta7;as*PGT!v5I* zjK!;#2=66C@b_VVWcN7~HTYIMO~69%depPTIvf$OFZM)@Ir*~AJ83wk^JU+NtnWS$4tG}so_+l2#rmSCVh1$=61fv zixZ?GH2yhbIE#J?-#Or)$5901%&x}Bde;t?Pm*UWeuY#XL6wbnszU}M*#2WYO}KO- zTt^q(d?Qbc$jmk4GFB3RolK4bB0 zh=|y`ve!cd_rSS!RYZ_fo^esD*ijV`BUrmV`zq}+p1Y-1W(U6ak;s^Pn^m=PH|Bw?U&d*o8{bp3^)=5nm)z-Ph3H2P4DJsZm7Dn zBcrQI*A|bO$0NsJWG|!f*LM>q%0L7oqW{YON7#3OTUA_bZ&ZvW)~GR}SP(%`q}apV z`<`RVr!mnO!G;|qcExDySBfRE#1gTA-5`R!%iZVfgEfj86-zXvSfW^?sQE1Mf8Vv& znpyjB{eGS&kCVISoq1=iHEZ6PU5IftE>X^KBt5%HmS*M6) zjsyR?N)J{&6@9Qy5zDL|qof)Q(a-A?u}lO!*eE?%jkp*~)ff{GYP6%jGv=uWJ$jv@ z8oO~uu}AZPNBg<*G}hYnvDW@T?@d@AoVDBB{$g#n`TrIzq2p-cdpOul^nqr$LU$AK ziubec<1%Q5v!UB>)^lp(%RZJp`nB5UKYLBIgjxanxj#VZ?*x@`rtT)<72mEO`6!HI zZy=6Vg=`jOA78EZD#kH2V_Ex#LVOY9I327;>uw@m@$Gtl@ZQAI82M$Y^v$w{&R6YNjtBl_4A*4-KVk6YBbzENkJRQzyyDx9EhWjH&hc zqMT6~XB2DMI9N98R&B*`V18uBsBSmw5@8-B!aSQK8to~gowdxjEL$WJ5u=CCcn!e( zVC=G%MIy^KKZvk-6XL4DxMD4vA1vFfCBkNNIda5RgK@=LHfve7TtbB97(8KGMoEKF z!djL~ShfsDgk?UNQNib|Wf_iT^EnX~3%Gv`MK%Z8XO^CY^UAkpJUqYdXNZ<2A0j|RfOG}pa)sYB93K?t15!g z4iBdEAZuAvvuv?jMR4RdV@A<~tYtHYWt$&W1V&xiO`uj`dKYnw*&22euIzUcU{cs_ zBBDjrYD?@RYBbegx!RXz8F_NLWzjcUXALA79He9-nN@i4|=rd618;uZo*~}XD#wd zVY>+(Q!}Wgu$zciyq|p^?Yjx%&OVTd3foPn6{6}3yNP(kx9dmVzMC+MvJd1gjHBF5 zXx~x2hTTNG;@kE9Xx~kkpVtQz$5Z=XRKW>=~7+jbKH;UmW8N{_pVfbdZn zt-z7D?Ir@k+bvqUhuuU#c;7^C_OP1>2=D(GF+J=i0>Z~wjLP=igk3S8yWNDewCHZa zdMCpAP`#^&_T7YykO&(`716$%Fe?&awyGj}*iD2SW&T(c;dc`j4eY~wUPZL;CM@EJ zu(+xs+IJHc)kIkARuS#H37a`Y*!-v>pxwBS(tpERf4^tN+Ev3gs^d+7R{6)lQoiKN z-whl-d_$Dm5xy4Cg`q#a@B78{uKqnBR(a>KV)j3ml6GUQVXeJ>cYg7|3;X_m5Yx_k zx_Ir8?+f~-pY>{;`Pw_RMOnSK{lM1#r=8!)ajbC8%B|tUZ$YhLt-qeqzjfFTM)iPT z8yI1WwFZ28;XwTMoRrlfDC@|(SYoZ#4d>Ply?70&1@1L)mogaEz%U|801%tKw@&@s z^>;&N8`k>w$zRo$J^G(gPVZQ)o+P)S+}?*rfO{R>1@YCgo76w(x~LftQee9ndEG{? zwL1BCMb|0_{GVYh_@ie2fUW9gD_FO_h;_T#5jtA%7Z1`3D7Qz6_j8OTA7lR)!pGGj zQ36K%H>?$-q3ZJ(Z|!~f$bb*vvD;vu|0_y-T*106_@I*rEjP&|%&0D2iSbj77}hM~ ztsN2Lry33HDY4CIabm~j32RXh>{p@4$(zcK9-b; zShvTxl0I}6Nh~2^YGwZL5$gIdgyxK4EuR^_+vhO@1g~|HZS-urb)#=(2DfYmFM&eYF_hcK;eGBs7_)>!bg>Ve+f7&Q)N$zicL?++^F!ye*orwyEFI^6`^f!F z_5RS92D-fuZ!14?#Fg63_0dIEI`70j7%lcWWlmfK!OrkcqCM2oIWK7SKP=qND$awD z2LVul|rj%oLb$xWPR&1+W0c_okeJcXB`LBxbt23`Il0^+cB_pF% zZ`#Op)xLS9QyYIc^$)Ypd}3&N?GZy-2VJ#7arVCk)>%I5q;&e(vo@~pICY4O_{u8= z)$yx~V@Egk|8!)>;2XZp@B7b?*5ENK7V}@+u+H+3$=UQxuHB@9PLdzhZ_9Vv`N@tq z#_-D&VH{{Hu6-VjuhxOpil6V>{e#6f5>|`<=Deb4tR?LlL$Z4J-sOwyULAmzmH?|s zf9;zN_{~CLHMZmY;;5;8g_SY%<4cmGx4$j_>XA#+mp(j1SgD_dmHMWFPLgZE>Xtco zbzkz_8p7(n|Ng1?-rdUzD`QAj=TG@vamSoB(bDx`b>QT#^o1+u3#-riJYD?q#P3VH z#*nNGjo)|P_O^V7`#(mzR@;2kebg&U2&*-BPg>`#_OBY- zHHKuh*F#ShPra}VTIvl}D<(732}?GF)sf%p)vE9FPL1svLyyLLkK5gr&s%BT?6H3i z6IMRjjiE>5cf-MI-)Sr6Q`djKgKe$(yH#6f&zdQ$j3HU|`Tn=X4mZ7px$@MQ(Tx{B zdp5n|hf{=AHhQ(zCfCjqR>n|T((&QR0eJ9V-SuqA)0Pufnnh*a8AGx%bQxF2|EypB zufr}9R-bLXervg7_b6E@L$cc7>Q!1-UU4g1f~_`uVL`gs8oLRrht}!e`t0hF!pa!> z@g>RM!0N~U+6V6z&B5J1ucJbqub`9UKG>@J)xr5Ox2z(p_I-Fz>z`wO-^q53Az7V0 zykG0fKEDL3zF>9kQD3DC9-Y_C5zd;qaqFoe7j?313_UtYevP=AcKqSlbwhq4taOd) z^b9>3zw7{3ug@8V+K7BGQC3Y??j);Er*G8S;EW5=(q>?_=2?870b`1+nyxHkvhgL! zZiuUu@8_@G@?X#*O;?sN+4z#=8nAlqwZZxDTUY6JBP<-NrenpHz^W6rn)&Fw4mZNW zvGQXAVso%M1-6^?3?3{TD?cV6=)t3Q>6icaR~HE@jdo$B9xR*((bCFbbrIrf zzcqGC$wXsGSg8jqXuKT_4_=M9dg8e`!pds~QyG4IWwd{dIe1q8=Sx=Q%#n7DAz5j( zgB3k^*TQGh$5xvntaRoGD`QAY8#+nGA=*E}99;Ia<>1BYs&5Sa_>$yq*y`M^Kk9zw zk03MLjC?ildktZwIjY5WjiE;;$)RBN2=diE{~RW)yaF(_ zPjEFdcLsIj4Z5-p&uWvGTMLq#lGENF20el(zQ=m8AGzt6$h;T2oDZ?y>GhG2@8dl zu6@GF7?PEtlVl6T)i#e_nr`*cA;QY*5@SeKhAvl}?VuUfePXDvnsib=06IZf8AGzt z)fudMfz?3^M|K>1~P%>sKVW_sMLCJuXDw!Ng#^S05C1ax%hH5K82PKn3$yi*4a~OD2 z7?Kq%E$EbpN+ySr5mt!N8kCH%LSzU-jVnP1C6hzR z2rERmo(P3Ak_tK~nGPr!VFjH~hmw(eWemv*bFc;_16HbJawr*Lg=|oVl97C649UvS zLCG|rWP}y60r!KF+l`^lK^b3AGAWdd<@P$1OqoTMAz2|`)u3e1k}8=TN=8^AbJn3` zgq1NQD;r->G7TshVWs;TVPy=-%Fsc{q);-p4%VS$EVm0ovO;dJL&>lu%t0s_`~p$A z;$W4jL&;cf7ly*>cdH6ID47P7jID#=?9CXGm5nbbnG{M!SYf5FL&?bcigi#Jk`$xhK1^`_gp|Ub9A`HpO#ut=~AXF#tY^l?gO*05OD47&Wro)Y}=GrxVMOJJH z9)yy~p=3n$=?H6{p+^TL(}0r6$;9uS)oy-F=tGrE3MC_~u+lRcgq8ZB<~&#nN+ySr z$z3!ED`V)#7nDo`N=8^|ETOH)kS!THD47&WresylJ7HxEU9_VmRWdo0jIh#~Bdj!D zE9jtP8c;IuV)dlR82a%ACDQ>VlX8TbW$G;J+!kADW&kTyGC7otu+kh=XS>GGql1!Z zK*41_ER#@qok%g5pq^&fIq9s)_Ih2gB(tIwgjG-T2P%=4`jIe@E z&@=CNszz3Z4oap2N=8^=rRVA;tc)R9LCJ8%0V`E9Ih2gB($z~?8AGx%bWk!ml#H;_ zwNGqi49UvSLCK7Ok`Y#R;=y)}Az4AmaCJsYs${yMWQ3KSc(7e#=+QyRbVJDqE94aX zEAJ>7Lyu09Rd8OC@BAcHM#EoW+4`gZV@vxYGc5V(NGh4!_s+77sfxY{YH1eK(gcj$ zkC0`y%d;MjPLi=uWD6d-H2(|EOW2lK(K93~8&j!drvJ5XzBbNe*p_+9GpwR{mhtb; z_U%{&QR1V)GxX>r836VA^ZP%}cS9tyEsHqMkgUxASOH+GUrz4I-@us++p;;~8CKEU zbKW}Vu8v7K_aPITIi8_MC&`E9c}ZgqW-Z&Yx$PN}Rh-S7gR3Sp^Gk6i!?rAcc!pIp zZS~MLA9Wmwb00FXEaMq^G@f0A2jA?jHJMRM3_UtYYKW^p9)Eb_O01l0%PRn5NLF!0 zT^FoQ$LjntR%f=Q+CWr>G4$gr*V+eP9h}~Yb04x&{UNKqG4$iBsEow1^2(x@K; zfUT~9>T@G3T)TcuK#X*$&Gy^y9;`v|u%5>yJ8~#<>rf*e=d9^k_VHMYJlJ97@L4LEaM*R#<(6p|DbPP%;^mjIhFr%zH($zCy_eL$b1a z2uY$!CWVrb)fqa0_oGBJ7(=p(Xs&}$GC7otu+n=%q8aqAm93&OzMy2X1pnBUvg&kY ztor_rkiWac5h^RuSH`f4RwaWohNO!*%I;LTvgsfhUr;g`luYhMSaa=mI#wvFl1ZUt zMD?kCYMx;gtx6_`lIb85wNK5l@?%0Ds$?=K8DXW-Agt5}(CWd1DD&sheuhgPYGC7otu+mr(R>qJm89FGL3`(ZKwshtQD`QAj8tq`EN+yMpDOu^AT+fg# zMYJlJ97;x5>AVwG#?YgKlF6WCgq3EQx@SmMni;@Kl}rjHBdj#b$nIC?wv5Tf7nDpl zluSymX^yJ1Yz&2!jxQ(~-uV$$nvsQ-F(fO^qV=F;QYaZ=r5RaR8AFaKqE*RsL&*p$ zy(c8Bj3HSWIw+YGN=8`e+9#}xAz4Am=<{W&WKt*@VWszLgq1NQtB6)5(+wpftaR-Y zR>qL53>}nA2b7GkvJ(%sYYfQ>N`|X5Y{fGfD47l@8DV879&FbbR?(_tcn3>ZAw$TC z2R&#EJsNB6^(Qs9x_?B+l+Q-XnI#eKi5+>GM$vj7=V55k;q&{ZtDm$`5ccFEYng_t zB5pt*A0E&!_1P^Y z!k!mnEgh3(JKmcB;*UVQ59=O>Jq{7}j35!}1Do@-G!TrERjwbHp7PQUC9c#5xDxyG zEtP%jizpd+(n9IOo~>gas`_oN=(*_i=wsZJ2Rdf|^yfCu^-5&OKCGoA>BcykQ2M*w z^lc^DS*z{oMtxeHBmWvR>S{$8lWMyj%{~?a!9IMu90%tL&lCNaa7Pj2ICRPb-49|M z+OGC47C)=tLsy`90RM6{m_|AM>9bmG7*PXb7V1=~yCc6~+B1jAM&qzRGWZe4fRw zJg3iEUZX?=ZPlE4V9xpB+hy6F5p`(Hn@iBgp6Fxl5wkIl zVe|Xut0K4iD=gbMs;rn3lU_4(W@^^55wfh&S5$4qO#P#I3-am6)U2h^Cq6I_5@G%i zc^7vXl7tBJtt)pDVNqE|`}*&AOm^R>$IK=`5^@#HDnW&cDU8~)>;>737w zmUeGFX~j<8->5w%Ngqk_Tqm}4eYTU`CXRn}-{Ia$3@(S<5 zJ=gU8mF0nT^xfnLx}*=5zN1!W6)|_-O4*M#LLX0W(kN{*m^LYVe~ux>BIS;aF#|N{I>yEt@)3G8ve@0UnlT$$JK-L9wM=ft7??ID&K!hl7Au+ z{XFo|UX9&*^fydLAg=uE^fSuOv?Ote)YbBHTgzpPC5dB|IVLs7P|Ib+U`76LP&)Ve z3F)v$#%F*2uosllhV?Oj+eKz7%YRyRA1MzXKBzwT>3uPyRy_Edj<>EIp8X5|+wPoR zt>Vam^-;h1AF0Li*s&uk=p^}K_BI_$^gc1`IB-(xqC{$OrXufF(0CX5tS{1k-Y_Ap zj~Vow6X=@3qv14CqdWIgIB)|A%mz1{p$+H{#dEWF4JsKwy zSB%Sk0T154+b!u0{rU^5$2VTR=^1X)Yi(gQ_vzQ0@cGz5;=Re|o|KOKx}UJR`@L0~ zo}owMIhpHDO?!dWZ{NPZ!_PrCgDYq}19|p|*<;sDkoDHF>U8Di0~hueR`-wo5m;R} zW{d11*oyPqvFdc?rbj2qrbnEWe!Ikpf^e)f8ZCu+^(z)!OZr+>Ow)>U69+ zljPnpgR)6rb>}%J<<35yRRxXQ4qGL#)fI2w-|g(5$)4Pk8HS^ zQ}Ya6v}65P0&}n*Y?Xe#R>RGlnrGZzt7tJ;TJXk;d3TX>j zwB{LlH1;2dFPYO;FF!vn_p6L&=+XF{hG`v*p_qf`BHCA7=?t~cYn`6qtfQw0D`Ziy zn)TqajbVtZ8%|x2zj@)AI>MJaJwuO9lD$6JC0`t@c0{!MmD4lyXxx3hVqD|*n1eSX zGpw-e7-5Ah+UXg-dFg5D!PhYd_Z~Z_F%Pyn`P`H8?WX@qSRspcdWIeiR@a@He-Es7 zMP_gcpwlz-=p^~-tP>l{gB4O@;#f6Zx$~jD4;EI)qF{CYm@OJNX%=;?ny%dG(eU{Z zXXW2$7ImzeuH5O-Npd`F)fcSpz>4EW=vg%#t0wM-j~Uds0<6ZLb5iO?=vh_J$PBO* zSLa;gmj%LfqQBz%^DQOG#$d&DkeSr?&RSl*YEHyBR{d~L{wGAq=Fq!-ghZIe^=O<3 zYleFUI?-FvGxTFhk`eIWU%}{fc+h*wGxTWub^gf+(lRo+z34@-Q9_jMQ*f zimRHlk7rdu#|$?FE2oQwnrG-d2v+|=T)hGhE)Ff~qM_y)dUTTf9hv$vu=))YfQzM? zXXw#5alss12644EbfTL%HP6sRJ2b=EnnlM#$+($Q^9(&YNwz-wi+nLe`vj;ZH}7hm zp+{q{hJ3XGSbd;6(Ug~G=rRLX)ijHK2G!@XOhu7-bdr4e!JzydWQG-0@0x=24E^|$ z-yf5wny-Fbr*vZ(Cnkwq&?-!t@R$)c%d(S}#stYr*68c!QS>8}J^&4o_% zirzEyI{u!58GK1T{cKZF9-?!n% z`mm#a2ex_=TGZ{4J3T{>PLiXr6CQ~gD_8coxaWl({l&0V zf`bsp%J1UacEU^I)ZlTR$oJlx)FL- z6*Qi7f~{Txs|T>+IQw{36?Bq}(cSh)tj;bP3eV7a5Ul=-OMRGLl^DH5TA^>FI@+=`X4A6H**Tl(4(P! z&i*2ugJ}O9l#H8qg=gr|NwNd-6|?C32TT&3Xj;uPbeRFHcGn&KVqoU7OyzXYqa}-` znneX+O3yR&6JAkm+)Qzccbi&Wt@f992!~lq36oGOZ(v$R(vg% zEhknH{vHeMV|_SV)tomw@jKP`E}y;q?zWA`p13jhS2$OQ<{r?ugy%VTTrXQ5<2Z1^ zn;k@y++Ua2HH4pOn0fB*l5f}5>U3qq?o}_pkbVwUGf((BPi1|7ZcMPB8+qny zxiK}X2=e*_ecbcJ`l8#d58t1&H2QGcTBjx8p5r$g;N8# z{>PVJ$Ug$B2QhMgg-V8Kp11mz@I>Q|>ot~vKlXt?s1sR>Uh@d2ADi%Cc|R)I2ltA6 zEvJ^+cH2wdyL^MTdKghcR_ueZ+umOpl|0MPKDy9H?rS+F!Z0E*Kk`*DjtQ6_KH7bM z&TciF`;^x0f^|jp87pVES``5g=JW?=l)vJdD0S@a_7!Vr4#eP(}DF zzCYhm72)k(uHlP54N*mS-}?Kf9{t@2A4{c@DZMF(F7u!thn2Zj32RbvEjFaaOZ7>qV{=h`YSJOihG7DA^Y$jpI>@&@@9>z zo}ALL*5u8yBadCK_;~(G#l{y6YOy^0hj!lVtLyCpKoxnLlEu6DOr}pZYSw-$ z7l#el7_9ydR%?zvAU))|jfK_Qw_Q*iJYpSb*BJWo;S>j~hTU*u$A9)ZO;~+8^nzlg zJJuFf#?X%s_s?IMnBPA7i?rB!q_A4|zGsTZYRd~NV@Ou74!W?o=ZST|>Whh+H7=Qa zZ#r-ITEgnXq0bc0zP+5VGKOSjXx!TdtDA=QPUqe=R#+W)+T7yY!gBh4wWfUVZb1(kLyu09lV6*dk6QaD*_<&e z39D~+T)p+uOScOvV@Ou(J+)Zto^#$qd>uMzv&P83teo9@@Vu05O?~@^t+8Wo7golQ ztPGtb6T#|}iKEi|(lv$E6$kzhcDhYi8AG;Y=p@+#tfqf?V0Pu!Po`|^mLCsj9k$nA z!pazu)lG-54m;feR^LBsv&O*Z`)3%0~B6jsL2j}NNv<%xNp&yUTD2X+xw+204ZrZ00z(=#NiXATs zH0~lJu70{-dHt!*DXUIbmND7*@ZAr3 zaL8ot=o2zgR-LXaW3urj$?C{g$H7+1KDbNnMp$#KIvuM{oJN7wH?Y-KpRbm?5!M_l zKPDh<0jsxRtMTWK?soR6IaYp5K+J{*fArOX*|%FiDXcUagq6lv&3Ukfud0C6FJI`N zZFb8g!b)RFSg8jqXx#q*tFQJPpFVQOE5b@+Nmyx&RnWLsglOL%bMVPAD>Y~zojKC3 zF(fOEcCea_%&^_7D`x`_nkTGu=19B7kS!S+Cq-cO*`!hF$$wZgr+swZ2`ghrOB*^# z&H$?=kgwiw zzSv$^X^yIUh8~?H?<3l`*zb#U^KC{7E6vEl${3QBX3;u+Jp#7+@5Fo46NarNtTZDF zD`QAjhQ^(0u=;37@ATq3#|kUW=fcVu`te~^!-{h**1-enhYKrR`-GJ-Br9EU!0HXG zI2Z1JK)T}%8w)F4`-GJ-Br8MXse7>c^7sVXKRv8CJr7+19K-?6@Ixg0M1%WM$}bb>118VWkr% z39Gl>-eE)N1YucbVJElT-Bgt%vQosZ6)ZSWO67OVTBm2LCIKL2}6ym8k7uJsglW|WP}wWyapv> zaU~2jt^^&FOb#U@tPtTfC>e_@VMtbpD?tY((}0o@R>)U%C>hCD#*nNq2WwC=V5LeX zhmsLi$Od&N8Oc}1kgNQFM0uZ$sC89FGL29%7jLhh?W$p|ZBNLI*K zbtoC+D^)TLC>hJ`c<%9bVPy=-%Fsc{dNnwhq>zWGuG}L$X3{7j#fE4Ja95 zg_XVzB_r!A)gL)CDVYC5ms2~>rgVXzG58|hGb>vpk#6=8DRy@P=}Hc z&46`K7?PEtgOZU`1Gc5COp6FZvVxMSL&;!0S0y6|wxz60iwHy45)i6no3*@@u6A}E;#l#H;_Xb@KFg9GnXF(fNP2PM;hk`Y##Wm=vgS!ref zD^)T%luX99G|RMDHijM@luQmKBdjz>wLC+Q4oW76k`Y!|>6wv*l`$kM&7!TKWO67O zVWk;aSQ$gIGIUTfIh2gBf=*yQ7gom5k1r^h97;x5VWsElC9I4gSwYEg#Q`f-GC7ot zu)<2u)k|0zL$We-P%_<6GQtWvfoq?zGKOSj=%8e}p=5-Wop`WaV@Os|GF+X(N|j7E zl#H;l6A!j)3_Ut1nb}Y>!pcrO=s{!X(WT0mGH3qmp8(;nux$MiZ7tz#4k(z*pPbU& z2dsSWEZdko8t)HcA2sT=XQ-AkKSGuh`8Py-W9V`mTitMD_u_k>Calbgo}nL8lDrO9 zyN*5}AB!^?GBHnih8|t|LiTTNc%xp-1ESE2!|s=r8iwIQJnFn>n7LN8_FsSp75`mfwl<61HV? zn`L82RyJ3#M!{C^zWYhO5zb`Tmd|j;(4+BGF?K9dC--mMhI1b>u`J^m`tg-2TP8OG3~ zljLyN>hjU!^Of&?rGstRn&BCemF3_h`7dm>_4EB3192w9wrpMU3_UtY`h(S7Umn=F z2&)=dss0dF#?YhjoD5hUz2k)Za-5g2Ew2EKAz9gag$xH5{&4Sx9fv5gyX?n73pKV;Q6hJJh%mC@x`*=YoIiB}v@084?@q{*98$#gkZqR5P) zYYB*V5LdhGccLI1D?3#YE#g`N;#Sz|Z?M%KI4^M{6lH08j?wj?wE!#5-TNPqkHDD>+frpAtc;-_AHG$L73Vmt zgNNYUhfGv|2rFag$A>4+V5%U`&sheFDRJ~C>e_@-YXIh+If=Niub8tD^)Tnl#Iny;ZAXcq1sBu7nDp2C1Y{L zdqTp>&c)PLf(}ZCcYcHwBAoY%EUtv1#ue{Vft4zm6iP-|A;Nh-%Hm2Gk`_bCCChEUtthSs^L~9h6K8B_phm4S26evZyg6E6hROrvfWgGAWddutL7#{V2(z z#*nNG9h6K4B_phmuXs;La=S4kD?w$p|at_7+c4812T8tPCBLObR7q>mctH2`ghrR!}n7lkgWSRmo&f zGPVx#ew47n>LU!v%Fsc{WKc4;4)UImurh{ZW$2(}QYaZ=g%z3iie!DoIw%au3QC6e zslZB=Oa>(*te_KkKT0$M)jLCMISAGW2eny&2c z0zm<&lF1VM;|P^i)0Is#$oPVi5d^)atn5^UcdbkZ$@qejNugvq+z1QD%Jh}oJqt=E zgOW+fMD0^JR(?#)pky*AnUt*5K80uK(Lu?iP%^?wqd{1y5A5tj?lcA^lR?P{D~$$W zWeolJf|ALgWQ3K*lCUy{etbd6q);*`+tQgMtc;C6#U#*i%;x-thd zH}8a%F(fNP2PKn2$p|aWGA+;0Wd^X~nGBRn3MG@VEzL45mW`oD2PKn1$p|aWQ7zBV zql1!3p=5-WW@KSy49QBfDDsRdnG{M!SZPKUR>qL53>}nA3MC_~^q!EgGKPM9LCJJL z$p|Z5`-GJ-Br7Nxt~g+&N+yMp5mtJ?Mpzj`vNCi~GAWddu+p_pSQ$gIGIUTfBcNo2 zm7RF7U1LaAdKU<+RLOKe$p|YuvtYZ%(4&Kr;TS`ako56C_qV0(NS6Ht;;@V%-SnI59zo`ve=1nQ&OLR=X?D7L;pE%AV!X8Z|}p`vN=J- zk@qcEY%pts9uQzv7%QtqM4adCeVA`q%X`yep~6Z$Xc~tI#8_d`Zs-a^Mh-t0HlsWu zD$90OHrLpPk6nxDMf>o6_EEBk&%20ayXIS#y$3B8Dt*YveJzd3o_$WJ^Z_5#=qdK$ zBPO0%wvXI<%_4(ni-o|d%k?4Az*;^^7V&vN_$aY;iD=c-G8bi@2LwhA6<$WT`d>y4 z8>%j8ABT?;ZC7Tk`Je2oxx}tGCW2TbN&+jkVOiA2m|CHlOT>c~4eZ0u^B#RJ9<=#P zghpk>o8%D2A$@p1d&GD9+&raygr@?{PnAB5Rd`Cz`{uh5<|+1JbDL#DFWQIMowbx< zon^E1q6oXvj_A=JG7din{fx4iwrC%IPWah{KID$jq6j~7&2~*PG%GBMFuts1=NBxq zX3uMs`Ifbe3CqTC(LR((Cu=D~iT3Z#qBc8;@N@9HJ*Z5?Ys%0(C<-S@e!1B2#>8Q( z=l$?swre9~8Qzpy!-p?h?7P!4wdT$1VMaZ;`0&OVLs!qAPD+HYHF~Gt*3Q_a4^AmO z;yu*t)&J%Ej1^XqJ}if`*2r7GuB~(C8`wcETfBVooZ8Z7FNr>W+iQ4Z*Y#h{zgd2j zhQH!jv1~2jYh38#xYPSK_FDY@++ShYRtC28La!C;|NY6$HGKUW<2d!yzKt)E65(ro zIcweet?T|mSVhFiuu;EWTQt5}>I!)}!4T}j@(25Pa{vDIeV6-PCr%A8jtv&uqS1Sq z65(rIzS4&E>jz$dJ+4QrjXu^|ZgAs+%@2}0iiThxHYbRf(7$he;BR+!ARfHh}e7v>RP0Wl$2s`2r=3#AXsSFH8?E05O>KWAyE{$-0-`+tEl-+G$| z>+aKQsm9p%7N-7+XT`F$lq83skB|O#X}-^p0hzzTvdsy$^ze3P*Y0`ehb_GJ0)HGl z|I++{!6m}i+Wx@hYG3_i17Q^rzkB+0-pNQ>{U4KO4JQAN$*->7Y1rQDj8Gx`kO6<0#6Jp9I9; zf!GNM*0L*}70WTVzX5;j)@!M35BS4hVcD_)TY?ACA3gXd^f5D8DqCwoiSV@$B^YTL zB@uBf5czV0v*$FfEL*Z&#BR%C7m?U1Bk@Ow-SvU^9I?wI6pzJ?b3$wOmvo<0$Gh~(-tX=kDii2p(^H!M| zh&cB2zS*dlOGM+c7V=eL`6?o=fUWB5znp%GeC69^+15m&k>QFm!>x;P9J}7jX=}L> z;cFp_7M4XLVjtM*jA5&%YvI4XU6vW`T$k7fGIddA>L3(8L_nyc;T1&E; z)(ZQCm`kQ%9CMIG2gJ-E*-}|ardC$67scuf!~@9f!!gfU%W^o&wi*zDk;{%1a}bD! zuzoxdZ6zxU5w=DV0qe@1I!P|Z$X7_VXzYMF$Xd4Ev1}_R5wM{F0T2<_^Hmv%>%E*mjrqY^rVUs&l|h85k0f~% zL-;F1TP@#G*+<{`zserZo?GN(JD%1KxAzTnJP-HzdDiEo)hgp)e}-TmRxbN6gulYF zjhtvJmk8{>+V29`^9;NT0DUz)+#M(pZytJbHvR2iVtxz{C-lA+`?LEARfNC7ay&hc zEtLqhmE1AW5!M_6$}%8ol|C>(0$<$0h_yVrittxhwmUSwr4pfWh4~Spp-zPQT*_)) zWu^XTu$GO3XkYFb!CH2OXkRvT$x7#-u(JE7MEJ7CG}J8rY3vFsAj1hO*j>iqYq7tc5&jCx9&P2473O&Z^IYa2<^-Q^vb&b@ zggX1f4A!UBiNUOGAj8QVM2yNfd@c6ZGs0hC*`uvoVP)Bez1y9*P*%20L3G*q65F+L zkW~-m5&>9wBIRn?ol$wl%eN$bBb6i2hlbrmU~9{D`aK0ST=Oohh_$0g}Kdn zAgjJ903ynox}GOG2Zfc5!;gt&YpFyU!e3##R*Pk8smjXt?h(GF5@FV5EgLOs`Es=n zixSq-s1~o8eb|zf%RY1tie|8=Cfb*)KDSxRS~k}l!q#?~&1D~!eOOC-m-W@=9a&kq zGIGg2IzsH7!pLn+)HjiksR!6^9u8NQLHddfabWv~`()#B44EMv5o4`mLva)~gt#9Ht{yFxPS^6#CMK4hM2 zTQ*bKpXDwomk1q)M7#2p`Qgj(6UU_XQ(Fl_Z6XL?RvThm_^v^!-!*7ldBx^-9~fTS z+@6RRf0S&v)}Dg9#~e1&Xfz?&`uEAq?@{COESuW4eqm!iA^u%nB>u&5= zebi~f%1-4yLywlX0aN|1fv~dYtk|wGBrA*1B)MqfX4zNxuEF5V))H3sESG2K(Mj?I zSoOoZuS4$`E3E9k0a+PCkCwLqQ~j=iu(Ic@*sd`os~GKFu+>2eK1ol*lV@zpp5hKkVdh!FLS? zA2KgzTlOrMXXw%R#VN2l^UP7{e=c5ASlL}NvNDDqEpG#+`dtGkna%AfB@kuEA+|@{DcSvs|8`N8@{aVDQu7j@eYcYtTg|c1OvTJ3U(7 z22Az423QA!2a!2LyKTGF+ra9e3x;MF;K?&L!os!N^k_V#2UbVyFd_Z-S)=hAZoz}d zuaTig%iDmde%C-)*>hH&q4OYG+7}+Y6W=vB8&96GEqj*BGxTV@SqxTNj~t)wdfO|) z%I;cuh8`_%1E%_2gN$w2Q(7z=L$b1!2=fEcemTBta6O(pV_WvDnrGVa(RXxog@!{ z)!ON>^oY;47gn01u--+69xYFWrTSe1VP(%*v0Y5TKf7(Lu+n@ktc;;Y%iDmde%C-)*;86<*BFvjT+dH|t(HIFfbZEb#XF@WDc@(jt!##gS+k2dFzxailDgw>PJH3#tfNA#dE^yr{u^i4f! ztHw7c*{(69t!!rzluS32jM+-wob(JmIw+ahP%>sKy-&VXVGKPwC>eg&z~ZXLw@h`k z!jP<>WMuD?B&uX`C>e_@zV~mo5{4cfluS32jK!6_WvaFkhH5K82PMPr8VD;yIKOKk ztPoeiP~%GWhC#{XP%^>_bCBOP5LSqMVMtbn4oW76k`Y#jaDLao;z}5jm7#-@;dc#$ z74j9oYaqGZ7?Ks{Aa@gJNtH|vB_phmuj>3l6WcY0WM$}}WO67OVTF7pZ!gnU#?YgK zlHqp^gcUL;zZxK{j3HUYy_zbS29%8DcHAGhU04}IvNCi~GC7otutMg?i zVPy=-%Fsc{@Vf@W3Yvjm4UqL!-wd<;j-1Z~C4=8AhojKC3F?7+6mQ=|!pk#!V&Kzmi7_ucp2PKn3$-s+Y-U%yXNJ|?!C>eg&Kv-#( zk=?H`beRDysglW|WEyNsbCm3UjiDc3P%=4`jIh!ig*hD=vL!aRWdo0jIe@|;p!!dd8Pi&EuF(fNP2PLC#>ctZewrdQ@N>^vt zN|j7El#H;l6A!j)3_Ut1nb}Y>!b+b#6%QIik1kclipBidPXOVsux$NtOtGcYpPh^}7bbO7(}`sis0|TRHW- z1bGB+YDQL~mW&};sp7zTejPmcUin>v#IX`ZW(-|RK;XLuseacWp?yphxpJGzAgi%E zOvqn^B6A}wT)R!j3guZ~bqKy|a0(y$np8n zI4@ya8tuX=YQx|`WWBNQ;7oki;5eMguq}=D!ZY;aleYm={jPzX=_9X~clb2MDrl&1 z*y^weqw=e8Uc$CCGYBhV=%O90#vs}!aA*y_|xd*^H3K2})iiqrB8$;$R^NwO|%wa=t`^Ve`D!?twA5mv^qipKXWQ~j=i zuu}bD_gG|~>Bom>qrhritbRk`Gz0JFuq`_y z@eKX=?DP(jG;#dB{Kp_#%xva+f<$*ZDnUC_>~y2fs*Nfk}+HHy??Ql zF|49h$?&@dW-HzY6b~9hKfa)3I-q1MuK3=+u(I7GX$Mn1k}BO;9o^l#H-K zzLM{3vt46IRyIEQt^t({ziS|@kgw!^CgaK&dUQ}SDU^(`LgvI9RpEq17?M>yjaDU- zLCIKd=T`$H4;n+Vvhjs1%I_KoD?26Ed?gIY%Fsc{q);-p4)Uu3mfM9PSwYFP%F`WH zG8vSNt%H2;-?FnXBr6-AeAj?VhTk=?bx`gWla(!o&7fZpP$i?!CyKt3uMu#x#;}T3B_jyhM_JjaiZJx(k`fL0G4 zL|K(g1|=h`G#Z4JG4$gLN`~Jx5LOyXcGklftDu9DNugwNwxu&iSQ$eX?O>%!CWDd@ zRyuQ}U1P|WB3gG7@@)|}?}U{xq^%4cluQaGBdj#b)ICG8(#!x>s$^0qnFia^993u8 z7*^4$WcXc!23cv2s(XeW9h6K8B_pgfp9?EvNLHFfp&?btq);-#O7pp}GKORo(W+$l zT?1jI`CM2TLqEQtWICW^gq5y+!pazumEHvcD^)Tnl#H;_wNF?XL$Zo!RWkgpfv|#3 zkf(HLD`QAjh7L+*1eA=hvNH>|YYfRsS7)*+l}rbejIgp354LLzt7v?oiAsjwH4s*b z{0mPW2}6(O?mA&nRzq>vJ;cLawZe?#l z^ni%HOD(jC z;jVAgbh0H~KbmYe#1+b0*_%3oh%2(!4DATEfp;*(qESbOc*EZvqKkb*yH~9n{iF!g z=D%vKxCabpGSMF;0ElQspVhn#+xv(ac`JLDsK&lyyt#1*D{s+0MTEYi)XB2el5#xpatNTSIT8NA9mN?n{#_#m<#vSk zxmsEf(VOjvcqRBo5Z~={??LUaAgkz`_CDg3Ft-KKqX%W=en#nNtq*>`2IclXqTQ>O zj+w6=5$!JXBUm^3$sxKpLhl2OnA-pCk7&g(Cpw9UGtKpZF@?D;v8!|5;+S74sYbgX z{QU3;&B0ZKjKkZ?M`Dj7mp)>|g=|+R+wWcn(XQ?@f{qps#tiO8F03M7KT~D3`;L)& z4|;z@KWQImpZ|i!5sUiV&Z}k4cdP^fi-tRKnpb4xaZPMT`0S%-=`UuY2NoZm9fYqG zJd^NOh!+_xziWV#kge@qLZI;`YqlD`QZRXiRRj^+ifaiG`o1D8Jpg^2g)a!K+v|Sp z31cmmZB7uO??eJ|Xs_Yf#`qq4`}#WESnFA(D&$p zz+3UML&cl--Fk)Z%R^K9T3#pO-PcUteTCkw*0Mg>U(`fbVjPd+t@urbl&rk=vGtWL z>D#$rbsrFT_ciNWP>$Scv0YdJXBjiFZxdU=-^}w}K-_`%glDRCtriiMKZww`jNy-I zu+Hz7=Xjeu!OHWB)^G!W~fkCX9k_(RK; zk!ZDuuuMdRzLAZw%)vOm#Jl0QFIGmo)gl5@Oy(UCEaRAex=hp)wQv`@5~yy=~7Sib4q;cKxReGq+< zB+p~yhromQ`UUpqu@=kvrgx22h@K_l21Lo4h!S6m37Jtbs$;Dx8gF`M58_SljS%g6h3|&TjEXZg&fs$77)Qg#VYP^k z*&t?#B$@>>H@$y`X!o^Pj#({cJA91sq^fH{8A_!m?&K^an(~Olzm~k0%|4-FCd<`|y3^WCDmeyR491*Rg%2 z57x4gvnBNt`dA27^}(BG^VaJp2w%&;w;vIop^y9e?Vg=7_fv^oL$D9?2m4UZ!Wyrk zk7wr}n%z3<)mwjmDBNNR8ZxOR5Ok5K>z&Dr=GjK*4 zzZxPlDt(~e?v0D1&qFQ$)e!hYzR807QHZPO<{#R)OXJGgWgmz!ezOKA=@M7+r5Jqo zqm13gl7D~7VmH+C-x)z%DMIH*!{&#z%RaPL!9Miwm>-;jbHVC?I0xC5)bd{@iHJ|j zdET&jZtb!U9j%~seDM9}=wp|`n>YRxa|vxCwfwhCBH{`3fqd1ld}Zyj4@4ioK!ba1 z@#`mL7JX*-$MVZ#77exh*H6^5@D*Ygnnz-{!FDx9rCpZY7n&HMKxp30UEY-|o|SJY zey!Hl(R9U?dhltiI1j1^ z^-7ZrZ5<>+Tf#UQC74keXB2B`?>3{reSSfNvIT-F1M?&0{2)Tt4~sPY~eew4(K)n2y?b6yQ zGX(L$g4xA;i!CMyLlg0z!zLEf|3IIt3dEBSPE4QK`C>u5@#=@gw=29{BP&A_vHgPX zV)|Wd=?_3$QoAO7=vRl9tTtY@_1WFm3c}Dt6l;E5+&kz80dw%WK{s*0fXc$)*nuy*v z{iwC`9XkRs9Eg`+dnARuyBwnF%AG_^o3T!-_v&Y(r7eNzx}cfvfBy~G(T8>mhiEzk zTG}0mQ5Z+sZyoeAu2AlRP*#Owg}?U);-}kQlWudwp@LBR2*S`r=*aPRT6dENCZ@f2 zx>ykEgBJTUG!bfDAl3(B_1CvcN1i&PWK~9qAPh}}dJuo-IKD+(J+Rfog3wqJghok= z2#pf_{dgd*ow|OzK74M4Qx z?;7phh;|!C4bg6W2wMB7A=>eGjrJVTE(naahG-WA#vy1OM-9=AziYJTh;~81qBTUj z_`}ddz*aRxI}jS}IikH}wehlbM7tmiO$7W=L$u@X8tplvT@Z+jI-*?=@VTIgfY0lQ zcKltVJx8=lBqG}Dh<1rxLlc2$uOr%l&}h#S`6u&(h)#`NK@)*!uOr&gl16)uXqOqK z?baN^<_8gINuxbSw4)!1c5)Ylp&cvyU86lmv7lWJUDx)PocA_mJCJ%dF_pM3~+1-W?Ek)~?BOagiAA?@sF5d&WowYPdBs&|L2+Lhb@(UnV`{k$I4iXRmBexS_8QG)Rhem!YM0*FK-TI*ZkUk7egys1V?H!1A z8wd4=AmW-4G!gn>Zb!7Ih;~6>wA3Fq4neaITd$zVfIzgTh;~81AJiY>b3?1GsEN>r zMth2A7lf_C9J!&1fIp~-;B$@k6wxjS)gRJ_p@mhcYJkvaPZ8}BiK;&&b`4DgqMe!u z2+i#&^9GriVsYgr5vqw$)@V-=?J}dZU73T1c8E^=x(aNCXipLCIonn4f-tmWRSVIc zBH9I^_7Q}kiBMGo1amv0Jw>z&LVZwo)Zd8M=4?#rVjw`$eV=S~Ie62WBWj^W-xgFvC z>?1~Vdk^FAh?v!Sh!Pn$M;_-|$ZFz`I5*o_!Ow-|l2|KbIK)Cb!p}jUOM0A9V%_Ll z$t%H|F&5hUh`t?Hcn`){aELCB+}F~mghfNP>%qElc81Z)4355WeaJZCl`7)9J?LjG z#-!`3pTX^YcpqrH;z3<;s{W9Xd+TbslOylZRx%Ftn%GCZX(QKp)6Oc+gX-*34F_~P zBHAQGrSunLx*ZWm7-kVhE15_mv>oANH>$9(a#n36BlmITqa;R;>!XXk!{;HFcw2q< z$kop>TJ?XY`a@S#?E~$HyvuVq8Ewq9|JTT4@6|Ob`pJz0-FTZ+*V@=$JHqEgpW$NW zYez(VE*=bLCvhz~4^J-t4)0(ckN@7k*$%}8d!0A1_stu&SUzU8j8K6y9DQk9U4Ng5@jwe_eZUsW(KC+l~ysYl%Kq z2Vx8mY|E~&Y<>8a@N2X{9D(;B_r-gVywdgF%JrpgzD3%F-j$OZ-x8jH0AkMb{TmnI z?HZ3@`OrPrt)Fn$Zi0rs)>9n5-G2iRmjJ=G>q;#hc?DguuIP4a*Z0S=wS*^~(8rPR;C^`jgI6>% zq+RuYrN1&tHbs<-##`|o!LmlB>?|~5karm++XBIF8`3^@g=Oo*w}d?>5WVou=&^Xy zf>(4FNxM2%dgx;YX4GByu7O9etg}`SI%~m-vvw8`e*}U|>GE>-*C&NlVy4 zmg7ioi6bwNaim?0gJ%Gh{z5KEkxOJ8@LGXfBDLTfo*-1v__a;+@!`aK(-VPE`$)TL zAL)-}YpEQ09pAG&B}PesjAL;n_dM8=^%rtUhFoIN-a;<1=#zUML?B}HjtR5qQTQ_6 z0YLaGWP&)B{#Zt|OG{W|fXMOX$eH*`0k2>Vwvch856l(0OTw1oUR`rZhFl^DWQG=U ziDiQpPl1UrblJz<=MBw%gl`V`E51LLt)((wA^XS^hwh5xC_S0*<<5{xGUSrfwOhFU zq-^N2kE_6HalAjsT6V?v=Ub9rab@<&n0I+attjoPeJcHxxdf|0hFnrX5Uu_YgnAIM zeF6M&7!dmaK~{E!W$VNDU1pyjA+ESa@rp)ViwKP+DO*cr?7olKJt3}~jCNVikyjYI zg3!4Fg`;aN=SRkN?TYWi_Z`;rlL*0 z!pg3&mi6KLE;9pk2{S`w9IRy{uOisTNLcsSr~u@2khRQ%ESuHCij#3YClj3q1#9W- zlCnilHQI^LNbDrS=7cLZ%kTS4M97^o4j$%s>O@1xeGWxXCkmPwoT~)x>;v%u!v(Hh9)9D!!ieb3_Bys4q10uLHGzaG!gbR41C^uPWqP-duIPQuPJMk zt!nJU&_u*1YnBJ%yt5C@QrszHEkExJO@uw8lO(Uex_jJx1lOo8hiJNTClT>^pEu|a z^zr_y+sSI6?OH5x6>U016Wi;HVQ9w+p6rcre06%3jaYZtj0m-l zMITrFf(RWs5NE-)aL(tj>pLD_;)M(EU?Sin`spAl|j)PA?0in^} zK(q@27L|P_5r!tho*crnQDw9@5bc7noI!-4WgO)*Q}BmIdjrvKaV5J(A`DH0JG%1g*>!l6@GO2z^=%h;xuj?*Hh~?&Fc$ z{S}spW+|F7yLXRfG#*`!%A~Os+ zxNoC|+|F8NMUN)J?1nGhqK{3^$QoneLDn))c{CB`*(CWrGTf^p_H4X{+|F9|B%ntV zVg65&?*nn}*@repBDb@aJtOGRL|BaB%fqnl$h(h_Xm<$9&hmsI5jG2wa|XRVQ%kv*CS%fTVqI}q*Ghdd+f(L`9DNA@YBol3^W zAx|!AAA;6CcxnJv8to~fT@bJppH^=XVe68Pqu?qLqCG>jm*Xg(N*8|^nh4lR*2EC) z8KPYf@HyIH&UL;CP zKZIzP-8S1*gjX+K)gX2?+A~CZPK2o=nM(VijN1)K;vmS{De7_7u@B2=%id3{8Z3upXkFN=6W-gxQCoi9ob7 zN`TO4??AK*f*G0FnFvD@foNwW0N%Heu zk8CV{*EJn8UU*o1uI=LcO(Tqzl&z&C*$IeSW*?Z|wAWSmJ>d~%-NGZt(Bim6_QsDk z&%x{viVU(&{n5z zwq`o_@Y|&ii$0>QKO!uS%RbcS(uc3*%Mq~;`T(x$=H5-~gW4J2i60T7oqd#TbI-|t z8tu}Dv0^P>E^89Oar|bpHS;HQ9AF~v6=)yQpN>P`Ll9)wuk}|E+iRhZ9uVq}-24HH zqURanbL)?NAS&g}g|d$|@f(Ma;x`V}qQZ)`dPZ;#E_v;J`816yM208}qOCuo5he1j zL)pi=_{GB6_{GBZT0J9le&jYkv@MzE)*t)Oaw3*MYQ$jEZvfEBy;jeN zpP`Q>?z*OXCbB3IWg8n=7M1?khenL{p>ZXB7%SHDMp(7WBj?h-;Fz0P{l?b)2Aj-dlwbo}MDVNvbLH;7N^+BCj zS)IwsGEs>@TxFc+td`m^~c`msdlI5O5!zNN}gB}-O1KAjC}D?zADED~uq zn=4XIk`DYb_cVN^U~Bn3`Z%NbY(sp8!9TaQ8ERh8@8$HQ+Sd}h>610I?%ut&Xbe+-z`7dMzLtOfY7h{6oz}O}XR*@f@SsMuuO#i;hR{L?!_ftWsQ^?ZB$mmWkUYE=7LK8|VKnLseweS{NT&bP3ZXiJ-; z=47xs1+0j$XQO<7EJwEg1H`r%`TK}=BJ9aCUyJ2v5smi77+9Bx|JTGB;vf(OF?7Q^ z?t;N!NDzcGkWJtYYd8rSG#5alQCx|>%`{V2(aHaRrqeaeI$@eDaCiNnGo<# + + fanuc_crx_description + 2.0.6 + TF and robot description for CRX-10iA + + Christoph Andres + + + BSD + + ament_cmake + + + ament_cmake + + diff --git a/ros2_humble_crx_description/fanuc_crx_description/robots/crx10ia.xacro b/ros2_humble_crx_description/fanuc_crx_description/robots/crx10ia.xacro new file mode 100644 index 0000000..40ab40d --- /dev/null +++ b/ros2_humble_crx_description/fanuc_crx_description/robots/crx10ia.xacro @@ -0,0 +1,5 @@ + + + + + diff --git a/ros2_humble_crx_description/fanuc_crx_description/urdf/crx10ia.urdf.xacro b/ros2_humble_crx_description/fanuc_crx_description/urdf/crx10ia.urdf.xacro new file mode 100644 index 0000000..b17a946 --- /dev/null +++ b/ros2_humble_crx_description/fanuc_crx_description/urdf/crx10ia.urdf.xacro @@ -0,0 +1,233 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +