From 64fc72d613425b332a002bb62be7956f43361db3 Mon Sep 17 00:00:00 2001 From: fan-ziqi Date: Fri, 8 Nov 2024 17:52:03 +0800 Subject: [PATCH] feat: ROS2 support #34 --- .gitignore | 2 + README.md | 49 +- README_CN.md | 53 +- src/rl_sar/CMakeLists.txt | 90 +- src/rl_sar/include/rl_sim.hpp | 53 +- src/rl_sar/launch/gazebo.launch.py | 94 + src/rl_sar/library/rl_sdk/rl_sdk.cpp | 1 + src/rl_sar/library/rl_sdk/rl_sdk.hpp | 12 +- src/rl_sar/package.xml | 32 +- src/rl_sar/scripts/actuator_net.py | 4 +- src/rl_sar/scripts/observation_buffer.py | 0 src/rl_sar/scripts/rl_sdk.py | 17 +- src/rl_sar/scripts/rl_sim.py | 223 +- src/rl_sar/src/rl_real_a1.cpp | 4 +- src/rl_sar/src/rl_real_go2.cpp | 4 +- src/rl_sar/src/rl_sim.cpp | 257 ++- src/robot_joint_controller/CMakeLists.txt | 81 +- .../include/robot_joint_controller.h | 72 - .../include/robot_joint_controller.hpp | 92 + .../include/robot_joint_controller_group.hpp | 92 + .../include/visibility_control.h | 35 + src/robot_joint_controller/package.xml | 52 +- .../robot_joint_controller_plugins.xml | 18 +- .../src/robot_joint_controller.cpp | 357 +-- .../src/robot_joint_controller_group.cpp | 278 +++ src/robot_msgs/CMakeLists.txt | 53 +- src/robot_msgs/msg/MotorState.msg | 8 +- src/robot_msgs/msg/RobotCommand.msg | 2 +- src/robot_msgs/msg/RobotState.msg | 2 +- src/robot_msgs/package.xml | 30 +- src/robots/a1_description/CMakeLists.txt | 32 +- .../a1_description/config/robot_control.yaml | 109 +- .../config/robot_control_group.yaml | 34 + .../a1_description/launch/a1_rviz.launch | 23 - .../a1_description/launch/a1_rviz.launch.py | 83 + .../a1_description/launch/check_joint.rviz | 125 +- .../launch/group_gazebo.launch.py | 59 + .../launch/single_gazebo.launch.py | 59 + src/robots/a1_description/package.xml | 26 +- src/robots/a1_description/urdf/a1.urdf | 12 +- src/robots/a1_description/xacro/gazebo.xacro | 99 +- src/robots/a1_description/xacro/robot.xacro | 9 +- .../a1_description/xacro/ros2_control.xacro | 137 ++ src/robots/go2_description/CMakeLists.txt | 26 +- .../go2_description/config/robot_control.yaml | 109 +- src/robots/go2_description/package.xml | 35 +- src/robots/go2_description/xacro/gazebo.xacro | 113 +- src/robots/go2_description/xacro/robot.xacro | 5 +- .../go2_description/xacro/ros2_control.xacro | 137 ++ src/robots/gr1t1_description/CMakeLists.txt | 14 - .../config/robot_control.yaml | 57 - .../gr1t1_description/launch/display.launch | 20 - .../gr1t1_description/launch/gazebo.launch | 20 - src/robots/gr1t1_description/meshes/base.STL | Bin 853534 -> 0 bytes .../gr1t1_description/meshes/head_pitch.STL | Bin 124184 -> 0 bytes .../gr1t1_description/meshes/head_roll.STL | Bin 139734 -> 0 bytes .../gr1t1_description/meshes/head_yaw.STL | Bin 189884 -> 0 bytes .../gr1t1_description/meshes/l_foot_pitch.STL | Bin 724084 -> 0 bytes .../gr1t1_description/meshes/l_foot_roll.STL | Bin 110684 -> 0 bytes .../gr1t1_description/meshes/l_hand_pitch.STL | Bin 1176334 -> 0 bytes .../gr1t1_description/meshes/l_hand_roll.STL | Bin 27684 -> 0 bytes .../gr1t1_description/meshes/l_hand_yaw.STL | Bin 994534 -> 0 bytes .../meshes/l_lower_arm_pitch.STL | Bin 74384 -> 0 bytes .../meshes/l_shank_pitch.STL | Bin 394184 -> 0 bytes .../meshes/l_thigh_pitch.STL | Bin 1186584 -> 0 bytes .../gr1t1_description/meshes/l_thigh_roll.STL | Bin 504684 -> 0 bytes .../gr1t1_description/meshes/l_thigh_yaw.STL | Bin 440434 -> 0 bytes .../meshes/l_upper_arm_pitch.STL | Bin 533284 -> 0 bytes .../meshes/l_upper_arm_roll.STL | Bin 47584 -> 0 bytes .../meshes/l_upper_arm_yaw.STL | Bin 935884 -> 0 bytes .../gr1t1_description/meshes/r_foot_pitch.STL | Bin 723084 -> 0 bytes .../gr1t1_description/meshes/r_foot_roll.STL | Bin 123034 -> 0 bytes .../gr1t1_description/meshes/r_hand_pitch.STL | Bin 1178184 -> 0 bytes .../gr1t1_description/meshes/r_hand_roll.STL | Bin 27684 -> 0 bytes .../gr1t1_description/meshes/r_hand_yaw.STL | Bin 994534 -> 0 bytes .../meshes/r_lower_arm_pitch.STL | Bin 74384 -> 0 bytes .../meshes/r_shank_pitch.STL | Bin 393984 -> 0 bytes .../meshes/r_thigh_pitch.STL | Bin 1186484 -> 0 bytes .../gr1t1_description/meshes/r_thigh_roll.STL | Bin 504684 -> 0 bytes .../gr1t1_description/meshes/r_thigh_yaw.STL | Bin 440334 -> 0 bytes .../meshes/r_upper_arm_pitch.STL | Bin 533334 -> 0 bytes .../meshes/r_upper_arm_roll.STL | Bin 39284 -> 0 bytes .../meshes/r_upper_arm_yaw.STL | Bin 935884 -> 0 bytes .../gr1t1_description/meshes/waist_pitch.STL | Bin 610684 -> 0 bytes .../gr1t1_description/meshes/waist_roll.STL | Bin 1023684 -> 0 bytes .../gr1t1_description/meshes/waist_yaw.STL | Bin 67684 -> 0 bytes src/robots/gr1t1_description/package.xml | 20 - src/robots/gr1t1_description/urdf.rviz | 225 -- src/robots/gr1t1_description/urdf/GR1T1.urdf | 2023 ----------------- .../urdf/GR1T1_lower_limb.urdf | 1400 ------------ src/robots/gr1t2_description/CMakeLists.txt | 14 - .../config/robot_control.yaml | 57 - .../gr1t2_description/launch/display.launch | 20 - .../gr1t2_description/launch/gazebo.launch | 20 - src/robots/gr1t2_description/meshes/Larm1.STL | Bin 534334 -> 0 bytes src/robots/gr1t2_description/meshes/Larm2.STL | Bin 63284 -> 0 bytes src/robots/gr1t2_description/meshes/Larm3.STL | Bin 618734 -> 0 bytes src/robots/gr1t2_description/meshes/Larm4.STL | Bin 32984 -> 0 bytes src/robots/gr1t2_description/meshes/Larm5.STL | Bin 932884 -> 0 bytes src/robots/gr1t2_description/meshes/Larm6.STL | Bin 13884 -> 0 bytes src/robots/gr1t2_description/meshes/Larm7.STL | Bin 471684 -> 0 bytes src/robots/gr1t2_description/meshes/Lleg1.STL | Bin 219434 -> 0 bytes src/robots/gr1t2_description/meshes/Lleg2.STL | Bin 314184 -> 0 bytes src/robots/gr1t2_description/meshes/Lleg3.STL | Bin 434484 -> 0 bytes src/robots/gr1t2_description/meshes/Lleg4.STL | Bin 450934 -> 0 bytes src/robots/gr1t2_description/meshes/Lleg5.STL | Bin 28984 -> 0 bytes src/robots/gr1t2_description/meshes/Lleg6.STL | Bin 152084 -> 0 bytes src/robots/gr1t2_description/meshes/Rarm1.STL | Bin 534434 -> 0 bytes src/robots/gr1t2_description/meshes/Rarm2.STL | Bin 63234 -> 0 bytes src/robots/gr1t2_description/meshes/Rarm3.STL | Bin 889084 -> 0 bytes src/robots/gr1t2_description/meshes/Rarm4.STL | Bin 32984 -> 0 bytes src/robots/gr1t2_description/meshes/Rarm5.STL | Bin 927684 -> 0 bytes src/robots/gr1t2_description/meshes/Rarm6.STL | Bin 13884 -> 0 bytes src/robots/gr1t2_description/meshes/Rarm7.STL | Bin 609584 -> 0 bytes src/robots/gr1t2_description/meshes/Rleg1.STL | Bin 219084 -> 0 bytes src/robots/gr1t2_description/meshes/Rleg2.STL | Bin 313384 -> 0 bytes src/robots/gr1t2_description/meshes/Rleg3.STL | Bin 560234 -> 0 bytes src/robots/gr1t2_description/meshes/Rleg4.STL | Bin 529934 -> 0 bytes src/robots/gr1t2_description/meshes/Rleg5.STL | Bin 28984 -> 0 bytes src/robots/gr1t2_description/meshes/Rleg6.STL | Bin 151834 -> 0 bytes src/robots/gr1t2_description/meshes/base.STL | Bin 990984 -> 0 bytes src/robots/gr1t2_description/meshes/head1.STL | Bin 837034 -> 0 bytes src/robots/gr1t2_description/meshes/head2.STL | Bin 104884 -> 0 bytes src/robots/gr1t2_description/meshes/head3.STL | Bin 12484 -> 0 bytes src/robots/gr1t2_description/meshes/torso.STL | Bin 919184 -> 0 bytes .../gr1t2_description/meshes/waist1.STL | Bin 795884 -> 0 bytes .../gr1t2_description/meshes/waist2.STL | Bin 908184 -> 0 bytes .../gr1t2_description/meshes/waist3.STL | Bin 152184 -> 0 bytes src/robots/gr1t2_description/package.xml | 20 - src/robots/gr1t2_description/urdf.rviz | 225 -- src/robots/gr1t2_description/urdf/GR1T2.urdf | 895 -------- .../gr1t2_description/urdf/GR1T2_simple.urdf | 1200 ---------- 132 files changed, 2315 insertions(+), 7214 deletions(-) create mode 100644 src/rl_sar/launch/gazebo.launch.py mode change 100644 => 100755 src/rl_sar/scripts/actuator_net.py mode change 100644 => 100755 src/rl_sar/scripts/observation_buffer.py mode change 100644 => 100755 src/rl_sar/scripts/rl_sdk.py mode change 100644 => 100755 src/rl_sar/scripts/rl_sim.py delete mode 100644 src/robot_joint_controller/include/robot_joint_controller.h create mode 100644 src/robot_joint_controller/include/robot_joint_controller.hpp create mode 100644 src/robot_joint_controller/include/robot_joint_controller_group.hpp create mode 100644 src/robot_joint_controller/include/visibility_control.h create mode 100644 src/robot_joint_controller/src/robot_joint_controller_group.cpp create mode 100644 src/robots/a1_description/config/robot_control_group.yaml delete mode 100644 src/robots/a1_description/launch/a1_rviz.launch create mode 100644 src/robots/a1_description/launch/a1_rviz.launch.py create mode 100644 src/robots/a1_description/launch/group_gazebo.launch.py create mode 100644 src/robots/a1_description/launch/single_gazebo.launch.py mode change 100644 => 100755 src/robots/a1_description/xacro/robot.xacro create mode 100644 src/robots/a1_description/xacro/ros2_control.xacro mode change 100755 => 100644 src/robots/go2_description/config/robot_control.yaml create mode 100644 src/robots/go2_description/xacro/ros2_control.xacro delete mode 100644 src/robots/gr1t1_description/CMakeLists.txt delete mode 100644 src/robots/gr1t1_description/config/robot_control.yaml delete mode 100644 src/robots/gr1t1_description/launch/display.launch delete mode 100644 src/robots/gr1t1_description/launch/gazebo.launch delete mode 100644 src/robots/gr1t1_description/meshes/base.STL delete mode 100644 src/robots/gr1t1_description/meshes/head_pitch.STL delete mode 100644 src/robots/gr1t1_description/meshes/head_roll.STL delete mode 100644 src/robots/gr1t1_description/meshes/head_yaw.STL delete mode 100644 src/robots/gr1t1_description/meshes/l_foot_pitch.STL delete mode 100644 src/robots/gr1t1_description/meshes/l_foot_roll.STL delete mode 100644 src/robots/gr1t1_description/meshes/l_hand_pitch.STL delete mode 100644 src/robots/gr1t1_description/meshes/l_hand_roll.STL delete mode 100644 src/robots/gr1t1_description/meshes/l_hand_yaw.STL delete mode 100644 src/robots/gr1t1_description/meshes/l_lower_arm_pitch.STL delete mode 100644 src/robots/gr1t1_description/meshes/l_shank_pitch.STL delete mode 100644 src/robots/gr1t1_description/meshes/l_thigh_pitch.STL delete mode 100644 src/robots/gr1t1_description/meshes/l_thigh_roll.STL delete mode 100644 src/robots/gr1t1_description/meshes/l_thigh_yaw.STL delete mode 100644 src/robots/gr1t1_description/meshes/l_upper_arm_pitch.STL delete mode 100644 src/robots/gr1t1_description/meshes/l_upper_arm_roll.STL delete mode 100644 src/robots/gr1t1_description/meshes/l_upper_arm_yaw.STL delete mode 100644 src/robots/gr1t1_description/meshes/r_foot_pitch.STL delete mode 100644 src/robots/gr1t1_description/meshes/r_foot_roll.STL delete mode 100644 src/robots/gr1t1_description/meshes/r_hand_pitch.STL delete mode 100644 src/robots/gr1t1_description/meshes/r_hand_roll.STL delete mode 100644 src/robots/gr1t1_description/meshes/r_hand_yaw.STL delete mode 100644 src/robots/gr1t1_description/meshes/r_lower_arm_pitch.STL delete mode 100644 src/robots/gr1t1_description/meshes/r_shank_pitch.STL delete mode 100644 src/robots/gr1t1_description/meshes/r_thigh_pitch.STL delete mode 100644 src/robots/gr1t1_description/meshes/r_thigh_roll.STL delete mode 100644 src/robots/gr1t1_description/meshes/r_thigh_yaw.STL delete mode 100644 src/robots/gr1t1_description/meshes/r_upper_arm_pitch.STL delete mode 100644 src/robots/gr1t1_description/meshes/r_upper_arm_roll.STL delete mode 100644 src/robots/gr1t1_description/meshes/r_upper_arm_yaw.STL delete mode 100644 src/robots/gr1t1_description/meshes/waist_pitch.STL delete mode 100644 src/robots/gr1t1_description/meshes/waist_roll.STL delete mode 100644 src/robots/gr1t1_description/meshes/waist_yaw.STL delete mode 100644 src/robots/gr1t1_description/package.xml delete mode 100644 src/robots/gr1t1_description/urdf.rviz delete mode 100644 src/robots/gr1t1_description/urdf/GR1T1.urdf delete mode 100644 src/robots/gr1t1_description/urdf/GR1T1_lower_limb.urdf delete mode 100644 src/robots/gr1t2_description/CMakeLists.txt delete mode 100644 src/robots/gr1t2_description/config/robot_control.yaml delete mode 100644 src/robots/gr1t2_description/launch/display.launch delete mode 100644 src/robots/gr1t2_description/launch/gazebo.launch delete mode 100644 src/robots/gr1t2_description/meshes/Larm1.STL delete mode 100644 src/robots/gr1t2_description/meshes/Larm2.STL delete mode 100644 src/robots/gr1t2_description/meshes/Larm3.STL delete mode 100644 src/robots/gr1t2_description/meshes/Larm4.STL delete mode 100644 src/robots/gr1t2_description/meshes/Larm5.STL delete mode 100644 src/robots/gr1t2_description/meshes/Larm6.STL delete mode 100644 src/robots/gr1t2_description/meshes/Larm7.STL delete mode 100644 src/robots/gr1t2_description/meshes/Lleg1.STL delete mode 100644 src/robots/gr1t2_description/meshes/Lleg2.STL delete mode 100644 src/robots/gr1t2_description/meshes/Lleg3.STL delete mode 100644 src/robots/gr1t2_description/meshes/Lleg4.STL delete mode 100644 src/robots/gr1t2_description/meshes/Lleg5.STL delete mode 100644 src/robots/gr1t2_description/meshes/Lleg6.STL delete mode 100644 src/robots/gr1t2_description/meshes/Rarm1.STL delete mode 100644 src/robots/gr1t2_description/meshes/Rarm2.STL delete mode 100644 src/robots/gr1t2_description/meshes/Rarm3.STL delete mode 100644 src/robots/gr1t2_description/meshes/Rarm4.STL delete mode 100644 src/robots/gr1t2_description/meshes/Rarm5.STL delete mode 100644 src/robots/gr1t2_description/meshes/Rarm6.STL delete mode 100644 src/robots/gr1t2_description/meshes/Rarm7.STL delete mode 100644 src/robots/gr1t2_description/meshes/Rleg1.STL delete mode 100644 src/robots/gr1t2_description/meshes/Rleg2.STL delete mode 100644 src/robots/gr1t2_description/meshes/Rleg3.STL delete mode 100644 src/robots/gr1t2_description/meshes/Rleg4.STL delete mode 100644 src/robots/gr1t2_description/meshes/Rleg5.STL delete mode 100644 src/robots/gr1t2_description/meshes/Rleg6.STL delete mode 100644 src/robots/gr1t2_description/meshes/base.STL delete mode 100644 src/robots/gr1t2_description/meshes/head1.STL delete mode 100644 src/robots/gr1t2_description/meshes/head2.STL delete mode 100644 src/robots/gr1t2_description/meshes/head3.STL delete mode 100644 src/robots/gr1t2_description/meshes/torso.STL delete mode 100644 src/robots/gr1t2_description/meshes/waist1.STL delete mode 100644 src/robots/gr1t2_description/meshes/waist2.STL delete mode 100644 src/robots/gr1t2_description/meshes/waist3.STL delete mode 100644 src/robots/gr1t2_description/package.xml delete mode 100644 src/robots/gr1t2_description/urdf.rviz delete mode 100644 src/robots/gr1t2_description/urdf/GR1T2.urdf delete mode 100644 src/robots/gr1t2_description/urdf/GR1T2_simple.urdf diff --git a/.gitignore b/.gitignore index 680e994..b45f491 100644 --- a/.gitignore +++ b/.gitignore @@ -1,6 +1,8 @@ build devel logs +install +log .catkin_tools .vscode *.csv diff --git a/README.md b/README.md index 05c9062..c2eacaa 100644 --- a/README.md +++ b/README.md @@ -2,10 +2,13 @@ [中文文档](README_CN.md) +**Version Select: [ROS-Noetic](https://github.com/fan-ziqi/rl_sar/tree/main) | [ROS2-Foxy](https://github.com/fan-ziqi/rl_sar/tree/ros2)** + This repository provides a framework for simulation verification and physical deployment of robot reinforcement learning algorithms, suitable for quadruped robots, wheeled robots, and humanoid robots. "sar" stands for "simulation and real" feature: - Support legged_gym based on IaacGym and IsaacLab based on IsaacSim. Use `framework` to distinguish. +- The code has two versions: **ROS** and **ROS2** - The code supports both cpp and python, you can find python version in `src/rl_sar/scripts` [Click to discuss on Discord](https://discord.gg/vmVjkhVugU) @@ -20,10 +23,10 @@ git clone https://github.com/fan-ziqi/rl_sar.git ## Dependency -This project uses `ros-noetic` (Ubuntu 20.04) and requires the installation of the following ROS dependency packages: +This project uses `ros2-foxy` (Ubuntu 20.04) and requires the installation of the following ROS dependency packages: ```bash -sudo apt install ros-noetic-teleop-twist-keyboard ros-noetic-controller-interface ros-noetic-gazebo-ros-control ros-noetic-joint-state-controller ros-noetic-effort-controllers ros-noetic-joint-trajectory-controller +sudo apt install ros-$ROS_DISTRO-teleop-twist-keyboard ros-$ROS_DISTRO-ros2-control ros-$ROS_DISTRO-ros2-controllers ros-$ROS_DISTRO-control-toolbox ros-$ROS_DISTRO-robot-state-publisher ros-$ROS_DISTRO-joint-state-publisher-gui ros-$ROS_DISTRO-gazebo-ros2-control ros-$ROS_DISTRO-gazebo-ros-pkgs ros-$ROS_DISTRO-xacro ``` Download and deploy `libtorch` at any location @@ -72,14 +75,17 @@ Compile in the root directory of the project ```bash cd .. -catkin build +colcon build --merge-install --symlink-install ``` -If catkin build report errors: `Unable to find either executable 'empy' or Python module 'em'`, run `catkin config -DPYTHON_EXECUTABLE=/usr/bin/python3` before `catkin build` - ## Running -In the following text, **\_\** is used to represent different environments, which can be `a1_isaacgym`, `a1_isaacsim`, `go2_isaacgym`, `gr1t1_isaacgym`, or `gr1t2_isaacgym`. +In the following text, **\_\** is used to represent different environments. Currently supported list: + +| | isaacgym | isaacsim | +|-------|----------|----------| +| a1 | ✓ | ✓ | +| go2 | ✓ | | Before running, copy the trained pt model file to `rl_sar/src/rl_sar/models/_`, and configure the parameters in `config.yaml`. @@ -88,24 +94,25 @@ Before running, copy the trained pt model file to `rl_sar/src/rl_sar/models/_.launch +source install/setup.bash +ros2 launch rl_sar gazebo.launch.py rname:= framework:= +(e.g. ros2 launch rl_sar gazebo.launch.py rname:=a1 framework:=isaacgym) ``` Open a new terminal, launch the control program ```bash -source devel/setup.bash -(for cpp version) rosrun rl_sar rl_sim -(for python version) rosrun rl_sar rl_sim.py +source install/setup.bash +(for cpp version) ros2 run rl_sar rl_sim +(for python version) ros2 run rl_sar rl_sim.py ``` Control: -* Press **\** to toggle simulation start/stop. + * **W** and **S** controls x-axis, **A** and **D** controls yaw, and **J** and **L** controls y-axis. * Press **\** to sets all control commands to zero. -* If robot falls down, press **R** to reset Gazebo environment. + ### Real Robots @@ -119,8 +126,8 @@ Unitree A1 can be connected using both wireless and wired methods: Open a new terminal and start the control program ```bash -source devel/setup.bash -rosrun rl_sar rl_real_a1 +source install/local.bash +ros2 run rl_sar rl_real_a1 ``` Press the **R2** button on the controller to switch the robot to the default standing position, press **R1** to switch to RL control mode, and press **L2** in any state to switch to the initial lying position. The left stick controls x-axis up and down, controls yaw left and right, and the right stick controls y-axis left and right. @@ -133,8 +140,8 @@ Or press **0** on the keyboard to switch the robot to the default standing posit 2. Use the `ifconfig` command to find the name of the network interface for the 123 network segment, such as `enxf8e43b808e06`. In the following steps, replace `` with the actual network interface name. 3. Open a new terminal and start the control program: ```bash - source devel/setup.bash - rosrun rl_sar rl_real_go2 + source install/local.bash + ros2 run rl_sar rl_real_go2 ``` 4. Go2 supports both joy and keyboard control, using the same method as mentioned above for A1. @@ -146,11 +153,11 @@ Take A1 as an example below 2. Run the control program, and the program will log all data after execution. 3. Stop the control program and start training the actuator network. Note that `rl_sar/src/rl_sar/models/` is omitted before the following paths. ```bash - rosrun rl_sar actuator_net.py --mode train --data a1/motor.csv --output a1/motor.pt + ros2 run rl_sar actuator_net.py --mode train --data a1/motor.csv --output a1/motor.pt ``` 4. Verify the trained actuator network. ```bash - rosrun rl_sar actuator_net.py --mode play --data a1/motor.csv --output a1/motor.pt + ros2 run rl_sar actuator_net.py --mode play --data a1/motor.csv --output a1/motor.pt ``` ## Add Your Robot @@ -160,8 +167,8 @@ In the following text, **\_\** is used to represent your robo 1. Create a model package named `_description` in the `rl_sar/src/robots` directory. Place the robot's URDF file in the `rl_sar/src/robots/_description/urdf` directory and name it `.urdf`. Additionally, create a joint configuration file with the namespace `_gazebo` in the `rl_sar/src/robots/_description/config` directory. 2. Place the trained RL model files in the `rl_sar/src/rl_sar/models/_` directory, and create a new `config.yaml` file in this path. Refer to the `rl_sar/src/rl_sar/models/a1_isaacgym/config.yaml` file to modify the parameters. 3. Modify the `forward()` function in the code as needed to adapt to different models. -4. If you need to run simulations, modify the launch files as needed by referring to those in the `rl_sar/src/rl_sar/launch` directory. -5. If you need to run on the physical robot, modify the file `rl_sar/src/rl_sar/src/rl_real_a1.cpp` as needed. + +4. If you need to run on the physical robot, modify the file `rl_sar/src/rl_sar/src/rl_real_a1.cpp` as needed. ## Contributing diff --git a/README_CN.md b/README_CN.md index 448b312..a09818a 100644 --- a/README_CN.md +++ b/README_CN.md @@ -2,10 +2,13 @@ [English document](README.md) +**版本选择: [ROS-Noetic](https://github.com/fan-ziqi/rl_sar/tree/main) | [ROS2-Foxy](https://github.com/fan-ziqi/rl_sar/tree/ros2)** + 本仓库提供了机器人强化学习算法的仿真验证与实物部署框架,适配四足机器人、轮足机器人、人形机器人。"sar"代表"simulation and real" 特性: - 支持基于IaacGym的legged_gym,也支持基于IsaacSim的IsaacLab,用`framework`加以区分。 +- 代码有**ROS**和**ROS2**两个版本 - 代码有python和cpp两个版本,python版本可以在`src/rl_sar/scripts`中找到 [点击在Discord上讨论](https://discord.gg/MC9KguQHtt) @@ -20,10 +23,10 @@ git clone https://github.com/fan-ziqi/rl_sar.git ## 依赖 -本项目使用`ros-noetic`(Ubuntu20.04),且需要安装以下的ros依赖包 +本项目使用`ros2-foxy`(Ubuntu20.04),且需要安装以下的ros依赖包 ```bash -sudo apt install ros-noetic-teleop-twist-keyboard ros-noetic-controller-interface ros-noetic-gazebo-ros-control ros-noetic-joint-state-controller ros-noetic-effort-controllers ros-noetic-joint-trajectory-controller +sudo apt install ros-$ROS_DISTRO-teleop-twist-keyboard ros-$ROS_DISTRO-ros2-control ros-$ROS_DISTRO-ros2-controllers ros-$ROS_DISTRO-control-toolbox ros-$ROS_DISTRO-robot-state-publisher ros-$ROS_DISTRO-joint-state-publisher-gui ros-$ROS_DISTRO-gazebo-ros2-control ros-$ROS_DISTRO-gazebo-ros-pkgs ros-$ROS_DISTRO-xacro ``` 在任意位置下载并部署`libtorch` @@ -72,14 +75,17 @@ sudo ldconfig ```bash cd .. -catkin build +colcon build --merge-install --symlink-install ``` -如果 catkin build 报错: `Unable to find either executable 'empy' or Python module 'em'`, 在`catkin build` 之前执行 `catkin config -DPYTHON_EXECUTABLE=/usr/bin/python3` - ## 运行 -下文中使用 **\_\** 代替表示不同的环境,可以是 `a1_isaacgym` 、 `a1_isaacsim` 、 `go2_isaacgym` 、 `gr1t1_isaacgym` 、 `gr1t2_isaacgym` +下文中使用 **\** 和 **\** 代替表示不同的机器人和框架。目前支持列表: + +| | isaacgym | isaacsim | +|-------|----------|----------| +| a1 | ✓ | ✓ | +| go2 | ✓ | | 运行前请将训练好的pt模型文件拷贝到`rl_sar/src/rl_sar/models/_`中,并配置`config.yaml`中的参数。 @@ -88,24 +94,25 @@ catkin build 打开一个终端,启动gazebo仿真环境 ```bash -source devel/setup.bash -roslaunch rl_sar gazebo__.launch +source install/setup.bash +ros2 launch rl_sar gazebo.launch.py rname:= framework:= +(e.g. ros2 launch rl_sar gazebo.launch.py rname:=a1 framework:=isaacgym) ``` 打开一个新终端,启动控制程序 ```bash -source devel/setup.bash -(for cpp version) rosrun rl_sar rl_sim -(for python version) rosrun rl_sar rl_sim.py +source install/setup.bash +(for cpp version) ros2 run rl_sar rl_sim +(for python version) ros2 run rl_sar rl_sim.py ``` 控制: -* 按 **\** 切换仿真器运行/停止。 -* **W** 和 **S** 控制x轴,**A** 和 **D** 控制yaw轴,**J** 和 **L** 控制y轴,按下空格重置控制指令。 + +* **W** 和 **S** 控制x轴,**A** 和 **D** 控制yaw轴,**J** 和 **L** 控制y轴。 * 按 **\** 将所有控制指令设置为零。 -* 如果机器人摔倒,按 **R** 重置Gazebo环境。 + ### 真实机器人 @@ -119,8 +126,8 @@ source devel/setup.bash 新建终端,启动控制程序 ```bash -source devel/setup.bash -rosrun rl_sar rl_real_a1 +source install/local.bash +ros2 run rl_sar rl_real_a1 ``` 按下遥控器的**R2**键让机器人切换到默认站起姿态,按下**R1**键切换到RL控制模式,任意状态按下**L2**切换到最初的趴下姿态。左摇杆上下控制x左右控制yaw,右摇杆左右控制y。 @@ -133,8 +140,8 @@ rosrun rl_sar rl_real_a1 2. 通过`ifconfig`命令查看123网段的网卡名字,如`enxf8e43b808e06`,下文用 \ 代替 3. 新建终端,启动控制程序 ```bash - source devel/setup.bash - rosrun rl_sar rl_real_go2 + source install/local.bash + ros2 run rl_sar rl_real_go2 ``` 4. Go2支持手柄与键盘控制,方法与上面a1相同 @@ -144,13 +151,13 @@ rosrun rl_sar rl_real_a1 1. 取消注释`rl_real_a1.cpp`中最上面的`#define CSV_LOGGER`,你也可以在仿真程序中修改对应部分采集仿真数据用来测试训练过程。 2. 运行控制程序,程序会在执行后记录所有数据。 -3. 停止控制程序,开始训练执行器网络。注意,下面的路径前均省略了`rl_sar/src/rl_sar/models/`。 +3. 停止控制程序,开始训练执行器网络。 ```bash - rosrun rl_sar actuator_net.py --mode train --data a1/motor.csv --output a1/motor.pt + ros2 run rl_sar actuator_net.py --mode train --data a1_isaacgym/motor.csv --output a1_isaacgym/motor.pt ``` 4. 验证已经训练好的训练执行器网络。 ```bash - rosrun rl_sar actuator_net.py --mode play --data a1/motor.csv --output a1/motor.pt + ros2 run rl_sar actuator_net.py --mode play --data a1_isaacgym/motor.csv --output a1_isaacgym/motor.pt ``` ## 添加你的机器人 @@ -160,8 +167,8 @@ rosrun rl_sar rl_real_a1 1. 在`rl_sar/src/robots`路径下创建名为`_description`的模型包,将模型的urdf放到`rl_sar/src/robots/_description/urdf`路径下并命名为`.urdf`,并在`rl_sar/src/robots/_description/config`路径下创建命名空间为`_gazebo`的关节配置文件 2. 将训练好的RL模型文件放到`rl_sar/src/rl_sar/models/_`路径下,并在此路径中新建config.yaml文件,参考`rl_sar/src/rl_sar/models/a1_isaacgym/config.yaml`文件修改其中参数 3. 按需修改代码中的`forward()`函数,以适配不同的模型 -4. 若需要运行仿真,则参考`rl_sar/src/rl_sar/launch`路径下的launch文件自行修改 -5. 若需要运行实物,则参考`rl_sar/src/rl_sar/src/rl_real_a1.cpp`文件自行修改 + +4. 若需要运行实物,则参考`rl_sar/src/rl_sar/src/rl_real_a1.cpp`文件自行修改 ## 贡献 diff --git a/src/rl_sar/CMakeLists.txt b/src/rl_sar/CMakeLists.txt index b2cc6c7..68b2eb9 100644 --- a/src/rl_sar/CMakeLists.txt +++ b/src/rl_sar/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 3.0.2) +cmake_minimum_required(VERSION 3.5) project(rl_sar) add_definitions(-DCMAKE_CURRENT_SOURCE_DIR="${CMAKE_CURRENT_SOURCE_DIR}") @@ -10,33 +10,27 @@ set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -g") set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${TORCH_CXX_FLAGS}") find_package(Torch REQUIRED) +set(CMAKE_INSTALL_RPATH "${Torch_DIR}/lib") +set(CMAKE_BUILD_WITH_INSTALL_RPATH TRUE) +set(CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${GAZEBO_CXX_FLAGS}") find_package(gazebo REQUIRED) -find_package(catkin REQUIRED COMPONENTS - controller_manager - genmsg - joint_state_controller - robot_state_publisher - roscpp - gazebo_ros - std_msgs - tf - geometry_msgs - robot_msgs - robot_joint_controller - rospy -) +find_package(ament_cmake REQUIRED) +find_package(joint_state_controller REQUIRED) +find_package(robot_state_publisher REQUIRED) +find_package(rclcpp REQUIRED) +find_package(gazebo_ros REQUIRED) +find_package(std_msgs REQUIRED) +find_package(robot_msgs REQUIRED) +find_package(robot_joint_controller REQUIRED) +find_package(rclpy REQUIRED) +find_package(gazebo_msgs REQUIRED) +find_package(std_srvs REQUIRED) find_package(Python3 COMPONENTS Interpreter Development REQUIRED) -catkin_package( - CATKIN_DEPENDS - robot_joint_controller - rospy -) - link_directories(/usr/local/lib) include_directories(${YAML_CPP_INCLUDE_DIR}) @@ -44,6 +38,11 @@ include_directories(${YAML_CPP_INCLUDE_DIR}) include_directories(library/unitree_legged_sdk_3.2/include) link_directories(library/unitree_legged_sdk_3.2/lib) set(UNITREE_A1_LIBS -pthread unitree_legged_sdk_amd64 lcm) +file(GLOB GLOB_UNITREE_LEGGED_SDK "${PROJECT_SOURCE_DIR}/library/unitree_legged_sdk_3.2/lib/*.so") +install(FILES + ${GLOB_UNITREE_LEGGED_SDK} + DESTINATION lib/ +) # Unitree Go2 include_directories(library/unitree_sdk2/include) @@ -52,10 +51,16 @@ include_directories(library/unitree_sdk2/thirdparty/include) include_directories(library/unitree_sdk2/thirdparty/include/ddscxx) link_directories(library/unitree_sdk2/thirdparty/lib/x86_64) set(UNITREE_GO2_LIBS -pthread unitree_sdk2 ddsc ddscxx) +file(GLOB GLOB_UNITREE_SDK2 "${PROJECT_SOURCE_DIR}/library/unitree_sdk2/lib/x86_64/*.so") +file(GLOB GLOB_UNITREE_SDK2_THIRDPARTY "${PROJECT_SOURCE_DIR}/library/unitree_sdk2/thirdparty/lib/x86_64/*.so") +install(FILES + ${GLOB_UNITREE_SDK2_THIRDPARTY} + ${GLOB_UNITREE_SDK2_THIRDPARTY} + DESTINATION lib/ +) include_directories( include - ${catkin_INCLUDE_DIRS} library/matplotlibcpp library/observation_buffer library/rl_sdk @@ -78,24 +83,53 @@ set_property(TARGET observation_buffer PROPERTY CXX_STANDARD 14) add_executable(rl_sim src/rl_sim.cpp ) target_link_libraries(rl_sim - ${catkin_LIBRARIES} -pthread + -pthread rl_sdk observation_buffer yaml-cpp ) add_executable(rl_real_a1 src/rl_real_a1.cpp ) target_link_libraries(rl_real_a1 - ${catkin_LIBRARIES} ${UNITREE_A1_LIBS} + ${UNITREE_A1_LIBS} rl_sdk observation_buffer yaml-cpp ) add_executable(rl_real_go2 src/rl_real_go2.cpp ) target_link_libraries(rl_real_go2 - ${catkin_LIBRARIES} ${UNITREE_GO2_LIBS} + ${UNITREE_GO2_LIBS} rl_sdk observation_buffer yaml-cpp ) -catkin_install_python(PROGRAMS +ament_target_dependencies(rl_sim + joint_state_controller + robot_state_publisher + rclcpp + gazebo_ros + std_msgs + robot_msgs + robot_joint_controller + rclpy + gazebo_msgs + std_srvs +) + +install(TARGETS + rl_sim + rl_sdk + observation_buffer + rl_real_a1 + rl_real_go2 + DESTINATION lib/${PROJECT_NAME} +) + +install(PROGRAMS scripts/rl_sim.py scripts/actuator_net.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) \ No newline at end of file + DESTINATION lib/${PROJECT_NAME} +) + +install( + DIRECTORY launch worlds models + DESTINATION share/${PROJECT_NAME}/ +) + +ament_package() diff --git a/src/rl_sar/include/rl_sim.hpp b/src/rl_sar/include/rl_sim.hpp index 9601024..a9e6807 100644 --- a/src/rl_sar/include/rl_sim.hpp +++ b/src/rl_sar/include/rl_sim.hpp @@ -4,19 +4,22 @@ #include "rl_sdk.hpp" #include "observation_buffer.hpp" #include "loop.hpp" -#include -#include -#include -#include "std_srvs/Empty.h" -#include -#include "robot_msgs/MotorCommand.h" +#include "robot_msgs/msg/robot_command.hpp" +#include "robot_msgs/msg/robot_state.hpp" +#include +#include +#include +#include +#include +#include +#include + #include -#include #include "matplotlibcpp.h" namespace plt = matplotlibcpp; -class RL_Sim : public RL +class RL_Sim : public RL, public rclcpp::Node { public: RL_Sim(); @@ -48,29 +51,27 @@ private: // ros interface std::string ros_namespace; - geometry_msgs::Twist vel; - geometry_msgs::Pose pose; - geometry_msgs::Twist cmd_vel; - ros::Subscriber model_state_subscriber; - ros::Subscriber joint_state_subscriber; - ros::Subscriber cmd_vel_subscriber; - ros::ServiceClient gazebo_set_model_state_client; - ros::ServiceClient gazebo_pause_physics_client; - ros::ServiceClient gazebo_unpause_physics_client; - std::map joint_publishers; - std::vector joint_publishers_commands; - void ModelStatesCallback(const gazebo_msgs::ModelStates::ConstPtr &msg); - void JointStatesCallback(const sensor_msgs::JointState::ConstPtr &msg); - void CmdvelCallback(const geometry_msgs::Twist::ConstPtr &msg); + sensor_msgs::msg::Imu gazebo_imu; + geometry_msgs::msg::Twist cmd_vel; + robot_msgs::msg::RobotCommand robot_command_publisher_msg; + robot_msgs::msg::RobotState robot_state_subscriber_msg; + rclcpp::Subscription::SharedPtr gazebo_imu_subscriber; + rclcpp::Subscription::SharedPtr joint_state_subscriber; + rclcpp::Subscription::SharedPtr cmd_vel_subscriber; + rclcpp::Client::SharedPtr gazebo_set_model_state_client; + rclcpp::Client::SharedPtr gazebo_pause_physics_client; + rclcpp::Client::SharedPtr gazebo_unpause_physics_client; + rclcpp::Publisher::SharedPtr robot_command_publisher; + rclcpp::Subscription::SharedPtr robot_state_subscriber; + rclcpp::Client::SharedPtr param_client; + void GazeboImuCallback(const sensor_msgs::msg::Imu::SharedPtr msg); + void CmdvelCallback(const geometry_msgs::msg::Twist::SharedPtr msg); + void RobotStateCallback(const robot_msgs::msg::RobotState::SharedPtr msg); // others std::string gazebo_model_name; int motiontime = 0; std::map sorted_to_original_index; - std::vector mapped_joint_positions; - std::vector mapped_joint_velocities; - std::vector mapped_joint_efforts; - void MapData(const std::vector &source_data, std::vector &target_data); }; #endif // RL_SIM_HPP diff --git a/src/rl_sar/launch/gazebo.launch.py b/src/rl_sar/launch/gazebo.launch.py new file mode 100644 index 0000000..e5cd5e7 --- /dev/null +++ b/src/rl_sar/launch/gazebo.launch.py @@ -0,0 +1,94 @@ +import os +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription, DeclareLaunchArgument +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration, TextSubstitution, Command +from launch_ros.actions import Node +from launch_ros.parameter_descriptions import ParameterValue +from ament_index_python.packages import get_package_share_directory + +def generate_launch_description(): + rname = LaunchConfiguration("rname") + framework = LaunchConfiguration("framework") + + wname = "stair" + robot_name = ParameterValue(Command(["echo -n ", rname, "_", framework]), value_type=str) + ros_namespace = ParameterValue(Command(["echo -n ", "/", rname, "_gazebo"]), value_type=str) + gazebo_model_name = ParameterValue(Command(["echo -n ", rname, "_gazebo"]), value_type=str) + + robot_description = ParameterValue( + Command([ + "xacro ", + Command(["echo -n ", Command(["ros2 pkg prefix ", rname, "_description"])]), + "/share/", rname, "_description/xacro/robot.xacro" + ]), + value_type=str + ) + + robot_state_publisher_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + name="robot_state_publisher", + output="screen", + parameters=[{"robot_description": robot_description}], + ) + + gazebo = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory("gazebo_ros"), "launch", "gazebo.launch.py") + ), + launch_arguments={ + "verbose": "false", + "world": os.path.join(get_package_share_directory("rl_sar"), "worlds", wname + ".world"), + }.items(), + ) + + spawn_entity = Node( + package="gazebo_ros", + executable="spawn_entity.py", + arguments=["-topic", "/robot_description", "-entity", "robot_model"], + output="screen", + ) + + joint_state_broadcaster_node = Node( + package="controller_manager", + executable="spawner.py", + arguments=["joint_state_broadcaster"], + output="screen", + ) + + robot_joint_controller_node = Node( + package="controller_manager", + executable="spawner.py", + arguments=["robot_joint_controller"], + output="screen", + ) + + param_node = Node( + package="demo_nodes_cpp", + executable="parameter_blackboard", + name="param_node", + parameters=[{ + "robot_name": robot_name, + "gazebo_model_name": gazebo_model_name, + }], + ) + + return LaunchDescription([ + DeclareLaunchArgument( + "rname", + description="Robot name (e.g., a1, go2)", + default_value=TextSubstitution(text=""), + ), + DeclareLaunchArgument( + "framework", + description="Framework (isaacgym or isaacsim)", + default_value=TextSubstitution(text=""), + ), + robot_state_publisher_node, + gazebo, + spawn_entity, + joint_state_broadcaster_node, + robot_joint_controller_node, + param_node, + ]) diff --git a/src/rl_sar/library/rl_sdk/rl_sdk.cpp b/src/rl_sar/library/rl_sdk/rl_sdk.cpp index 039c87d..3946e62 100644 --- a/src/rl_sar/library/rl_sdk/rl_sdk.cpp +++ b/src/rl_sar/library/rl_sdk/rl_sdk.cpp @@ -486,6 +486,7 @@ void RL::CSVInit(std::string robot_name) // csv_filename += "_" + timestamp; csv_filename += ".csv"; + std::cout << LOGGER::INFO << "Recording motor data in " << csv_filename << std::endl; std::ofstream file(csv_filename.c_str()); for(int i = 0; i < 12; ++i) { file << "tau_cal_" << i << ","; } diff --git a/src/rl_sar/library/rl_sdk/rl_sdk.hpp b/src/rl_sar/library/rl_sdk/rl_sdk.hpp index 5f86f76..c55589f 100644 --- a/src/rl_sar/library/rl_sdk/rl_sdk.hpp +++ b/src/rl_sar/library/rl_sdk/rl_sdk.hpp @@ -11,10 +11,10 @@ namespace LOGGER { - const char *const INFO = "\033[0;37m[INFO]\033[0m "; - const char *const WARNING = "\033[0;33m[WARNING]\033[0m "; - const char *const ERROR = "\033[0;31m[ERROR]\033[0m "; - const char *const DEBUG = "\033[0;32m[DEBUG]\033[0m "; + const std::string INFO = "\033[0;37m[INFO]\033[0m "; + const std::string WARNING = "\033[0;33m[WARNING]\033[0m "; + const std::string ERROR = "\033[0;31m[ERROR]\033[0m "; + const std::string DEBUG = "\033[0;32m[DEBUG]\033[0m "; } template @@ -45,7 +45,7 @@ struct RobotState std::vector q = std::vector(32, 0.0); std::vector dq = std::vector(32, 0.0); std::vector ddq = std::vector(32, 0.0); - std::vector tauEst = std::vector(32, 0.0); + std::vector tau_est = std::vector(32, 0.0); std::vector cur = std::vector(32, 0.0); } motor_state; }; @@ -156,7 +156,7 @@ public: // others std::string robot_name; STATE running_state = STATE_RL_RUNNING; // default running_state set to STATE_RL_RUNNING - bool simulation_running = false; + bool simulation_running = true; // protect func void TorqueProtect(torch::Tensor origin_output_torques); diff --git a/src/rl_sar/package.xml b/src/rl_sar/package.xml index ccb0b2a..f54b43c 100644 --- a/src/rl_sar/package.xml +++ b/src/rl_sar/package.xml @@ -1,5 +1,5 @@ - + rl_sar 2.0.0 The rl_sar package @@ -8,29 +8,19 @@ TODO - catkin - genmsg - controller_manager - joint_state_controller - robot_state_publisher - roscpp - std_msgs - controller_manager - joint_state_controller - robot_state_publisher - roscpp - std_msgs - controller_manager - joint_state_controller - robot_state_publisher - roscpp - std_msgs - rospy - rospy + ament_cmake + rclcpp + std_msgs + gazebo_ros + yaml-cpp robot_msgs robot_joint_controller + controller_manager + joint_state_controller + robot_state_publisher + rospy - + ament_cmake diff --git a/src/rl_sar/scripts/actuator_net.py b/src/rl_sar/scripts/actuator_net.py old mode 100644 new mode 100755 index b62b705..9d5921a --- a/src/rl_sar/scripts/actuator_net.py +++ b/src/rl_sar/scripts/actuator_net.py @@ -1,3 +1,4 @@ +#!/usr/bin/env python3 import os import argparse from matplotlib import pyplot as plt @@ -8,8 +9,9 @@ import torch.nn.functional as F from torch.utils.data import Dataset, DataLoader from torch.optim import Adam import pandas as pd +from ament_index_python.packages import get_package_share_directory -BASE_PATH = os.path.join(os.path.dirname(__file__), "../") +BASE_PATH = os.path.join(get_package_share_directory('rl_sar')) class Config: def __init__(self): diff --git a/src/rl_sar/scripts/observation_buffer.py b/src/rl_sar/scripts/observation_buffer.py old mode 100644 new mode 100755 diff --git a/src/rl_sar/scripts/rl_sdk.py b/src/rl_sar/scripts/rl_sdk.py old mode 100644 new mode 100755 index 2761b30..16fb820 --- a/src/rl_sar/scripts/rl_sdk.py +++ b/src/rl_sar/scripts/rl_sdk.py @@ -41,7 +41,7 @@ class RobotState: self.q = [0.0] * 32 self.dq = [0.0] * 32 self.ddq = [0.0] * 32 - self.tauEst = [0.0] * 32 + self.tau_est = [0.0] * 32 self.cur = [0.0] * 32 class STATE(Enum): @@ -123,7 +123,7 @@ class RL: # others self.robot_name = "" self.running_state = STATE.STATE_RL_RUNNING # default running_state set to STATE_RL_RUNNING - self.simulation_running = False + self.simulation_running = True ### protected in cpp ### # rl module @@ -228,10 +228,10 @@ class RL: self.getup_percent = min(self.getup_percent, 1.0) for i in range(self.params.num_of_dofs): command.motor_command.q[i] = (1 - self.getup_percent) * self.now_state.motor_state.q[i] + self.getup_percent * self.params.default_dof_pos[0][i].item() - command.motor_command.dq[i] = 0 + command.motor_command.dq[i] = 0.0 command.motor_command.kp[i] = self.params.fixed_kp[0][i].item() command.motor_command.kd[i] = self.params.fixed_kd[0][i].item() - command.motor_command.tau[i] = 0 + command.motor_command.tau[i] = 0.0 print("\r" + LOGGER.INFO + f"Getting up {self.getup_percent * 100.0:.1f}", end='', flush=True) if self.control.control_state == STATE.STATE_RL_INIT: @@ -261,10 +261,10 @@ class RL: print("\r" + LOGGER.INFO + f"RL Controller x: {self.control.x:.1f} y: {self.control.y:.1f} yaw: {self.control.yaw:.1f}", end='', flush=True) for i in range(self.params.num_of_dofs): command.motor_command.q[i] = self.output_dof_pos[0][i].item() - command.motor_command.dq[i] = 0 + command.motor_command.dq[i] = 0.0 command.motor_command.kp[i] = self.params.rl_kp[0][i].item() command.motor_command.kd[i] = self.params.rl_kd[0][i].item() - command.motor_command.tau[i] = 0 + command.motor_command.tau[i] = 0.0 if self.control.control_state == STATE.STATE_POS_GETDOWN: self.control.control_state = STATE.STATE_WAITING @@ -289,10 +289,10 @@ class RL: self.getdown_percent = min(1.0, self.getdown_percent) for i in range(self.params.num_of_dofs): command.motor_command.q[i] = (1 - self.getdown_percent) * self.now_state.motor_state.q[i] + self.getdown_percent * self.start_state.motor_state.q[i] - command.motor_command.dq[i] = 0 + command.motor_command.dq[i] = 0.0 command.motor_command.kp[i] = self.params.fixed_kp[0][i].item() command.motor_command.kd[i] = self.params.fixed_kd[0][i].item() - command.motor_command.tau[i] = 0 + command.motor_command.tau[i] = 0.0 print("\r" + LOGGER.INFO + f"Getting down {self.getdown_percent * 100.0:.1f}", end='', flush=True) if self.getdown_percent == 1: @@ -424,6 +424,7 @@ class RL: # self.csv_filename += f"_{timestamp}" self.csv_filename += ".csv" + print(LOGGER.INFO + f"Recording motor data in '{os.path.abspath(self.csv_filename)}'") with open(self.csv_filename, 'w', newline='') as file: writer = csv.writer(file) diff --git a/src/rl_sar/scripts/rl_sim.py b/src/rl_sar/scripts/rl_sim.py old mode 100644 new mode 100755 index fc88643..abb7f64 --- a/src/rl_sar/scripts/rl_sim.py +++ b/src/rl_sar/scripts/rl_sim.py @@ -1,90 +1,94 @@ -import sys +#!/usr/bin/env python3 import os import torch import threading import time -import rospy -import numpy as np -from gazebo_msgs.msg import ModelStates -from sensor_msgs.msg import JointState -from geometry_msgs.msg import Twist, Pose -from robot_msgs.msg import MotorCommand -from gazebo_msgs.srv import SetModelState, SetModelStateRequest +import rclpy +from rclpy.node import Node +from rclpy.qos import qos_profile_system_default +from sensor_msgs.msg import Imu +from geometry_msgs.msg import Twist +from robot_msgs.msg import RobotCommand as RobotCommandMsg +from robot_msgs.msg import RobotState as RobotStateMsg +from robot_msgs.msg import MotorCommand as MotorCommandMsg +from robot_msgs.msg import MotorState as MotorStateMsg +from gazebo_msgs.srv import SetModelState from std_srvs.srv import Empty - -path = os.path.abspath(".") -sys.path.insert(0, path + "/src/rl_sar/scripts") +from rcl_interfaces.srv import GetParameters +from ament_index_python.packages import get_package_share_directory from rl_sdk import * from observation_buffer import * -CSV_LOGGER = False +CSV_LOGGER = True -class RL_Sim(RL): +class RL_Sim(RL, Node): def __init__(self): - super().__init__() + Node.__init__(self, "rl_sim_node") + RL.__init__(self) # member variables for RL_Sim - self.vel = Twist() - self.pose = Pose() self.cmd_vel = Twist() + self.gazebo_imu = Imu() + self.robot_state_subscriber_msg = RobotStateMsg() + self.robot_command_publisher_msg = RobotCommandMsg() - # start ros node - rospy.init_node("rl_sim") + self.ros_namespace = self.get_namespace() + + # get params from param_node + self.param_client = self.create_client(GetParameters, '/param_node/get_parameters') + while not self.param_client.wait_for_service(timeout_sec=1.0): + self.get_logger().warn("Waiting for param_node service to be available...") + request = GetParameters.Request() + request.names = ['robot_name', 'gazebo_model_name'] + future = self.param_client.call_async(request) + rclpy.spin_until_future_complete(self, future) + if len(future.result().values) < 2: + self.get_logger().warn("Failed to get all parameters from param_node") + else: + self.robot_name = future.result().values[0].string_value + self.gazebo_model_name = future.result().values[1].string_value + self.get_logger().info(f"Get param robot_name: {self.robot_name}") + self.get_logger().info(f"Get param gazebo_model_name: {self.gazebo_model_name}") # read params from yaml - self.robot_name = rospy.get_param("robot_name", "") self.ReadYaml(self.robot_name) for i in range(len(self.params.observations)): if self.params.observations[i] == "ang_vel": self.params.observations[i] = "ang_vel_world" - # history + # init rl + torch.set_grad_enabled(False) if len(self.params.observations_history) != 0: self.history_obs_buf = ObservationBuffer(1, self.params.num_observations, len(self.params.observations_history)) - - # Due to the fact that the robot_state_publisher sorts the joint names alphabetically, - # the mapping table is established according to the order defined in the YAML file - sorted_joint_controller_names = sorted(self.params.joint_controller_names) - self.sorted_to_original_index = {} - for i in range(len(self.params.joint_controller_names)): - self.sorted_to_original_index[sorted_joint_controller_names[i]] = i - self.mapped_joint_positions = [0.0] * self.params.num_of_dofs - self.mapped_joint_velocities = [0.0] * self.params.num_of_dofs - self.mapped_joint_efforts = [0.0] * self.params.num_of_dofs - - # init - torch.set_grad_enabled(False) - self.joint_publishers_commands = [MotorCommand() for _ in range(self.params.num_of_dofs)] + self.robot_command_publisher_msg.motor_command = [MotorCommandMsg() for _ in range(self.params.num_of_dofs)] + self.robot_state_subscriber_msg.motor_state = [MotorStateMsg() for _ in range(self.params.num_of_dofs)] self.InitObservations() self.InitOutputs() self.InitControl() + self.running_state = STATE.STATE_RL_RUNNING # model - model_path = os.path.join(os.path.dirname(__file__), f"../models/{self.robot_name}/{self.params.model_name}") + model_path = os.path.join(get_package_share_directory('rl_sar'), 'models', self.robot_name, self.params.model_name) self.model = torch.jit.load(model_path) # publisher - self.ros_namespace = rospy.get_param("ros_namespace", "") - self.joint_publishers = {} - for i in range(self.params.num_of_dofs): - topic_name = f"{self.ros_namespace}{self.params.joint_controller_names[i]}/command" - self.joint_publishers[self.params.joint_controller_names[i]] = rospy.Publisher(topic_name, MotorCommand, queue_size=10) + self.robot_command_publisher = self.create_publisher(RobotCommandMsg, self.ros_namespace + "robot_joint_controller/command", qos_profile_system_default) # subscriber - self.cmd_vel_subscriber = rospy.Subscriber("/cmd_vel", Twist, self.CmdvelCallback, queue_size=10) - self.model_state_subscriber = rospy.Subscriber("/gazebo/model_states", ModelStates, self.ModelStatesCallback, queue_size=10) - joint_states_topic = f"{self.ros_namespace}joint_states" - self.joint_state_subscriber = rospy.Subscriber(joint_states_topic, JointState, self.JointStatesCallback, queue_size=10) + self.cmd_vel_subscriber = self.create_subscription(Twist, "/cmd_vel", self.CmdvelCallback, qos_profile_system_default) + self.gazebo_imu_subscriber = self.create_subscription(Imu, "/imu", self.GazeboImuCallback, qos_profile_system_default) + self.robot_state_subscriber = self.create_subscription(RobotStateMsg, self.ros_namespace + "robot_joint_controller/state", self.RobotStateCallback, qos_profile_system_default) # service - self.gazebo_model_name = rospy.get_param("gazebo_model_name", "") - self.gazebo_set_model_state_client = rospy.ServiceProxy("/gazebo/set_model_state", SetModelState) - self.gazebo_pause_physics_client = rospy.ServiceProxy("/gazebo/pause_physics", Empty) - self.gazebo_unpause_physics_client = rospy.ServiceProxy("/gazebo/unpause_physics", Empty) + self.gazebo_set_model_state_client = self.create_client(SetModelState, "/gazebo/set_model_state") + self.gazebo_pause_physics_client = self.create_client(Empty, "/gazebo/pause_physics") + self.gazebo_unpause_physics_client = self.create_client(Empty, "/gazebo/unpause_physics") # loops self.thread_control = threading.Thread(target=self.ThreadControl) self.thread_rl = threading.Thread(target=self.ThreadRL) + self.thread_control.daemon = True + self.thread_rl.daemon = True self.thread_control.start() self.thread_rl.start() @@ -96,87 +100,82 @@ class RL_Sim(RL): if CSV_LOGGER: self.CSVInit(self.robot_name) - print(LOGGER.INFO + "RL_Sim start") + self.get_logger().info("RL_Sim start") def __del__(self): - print(LOGGER.INFO + "RL_Sim exit") + self.get_logger().info("RL_Sim exit") def GetState(self, state): if self.params.framework == "isaacgym": - state.imu.quaternion[3] = self.pose.orientation.w - state.imu.quaternion[0] = self.pose.orientation.x - state.imu.quaternion[1] = self.pose.orientation.y - state.imu.quaternion[2] = self.pose.orientation.z + state.imu.quaternion[3] = self.gazebo_imu.orientation.w + state.imu.quaternion[0] = self.gazebo_imu.orientation.x + state.imu.quaternion[1] = self.gazebo_imu.orientation.y + state.imu.quaternion[2] = self.gazebo_imu.orientation.z elif self.params.framework == "isaacsim": - state.imu.quaternion[0] = self.pose.orientation.w - state.imu.quaternion[1] = self.pose.orientation.x - state.imu.quaternion[2] = self.pose.orientation.y - state.imu.quaternion[3] = self.pose.orientation.z + state.imu.quaternion[0] = self.gazebo_imu.orientation.w + state.imu.quaternion[1] = self.gazebo_imu.orientation.x + state.imu.quaternion[2] = self.gazebo_imu.orientation.y + state.imu.quaternion[3] = self.gazebo_imu.orientation.z - state.imu.gyroscope[0] = self.vel.angular.x - state.imu.gyroscope[1] = self.vel.angular.y - state.imu.gyroscope[2] = self.vel.angular.z + state.imu.gyroscope[0] = self.gazebo_imu.angular_velocity.x + state.imu.gyroscope[1] = self.gazebo_imu.angular_velocity.y + state.imu.gyroscope[2] = self.gazebo_imu.angular_velocity.z - # state.imu.accelerometer + state.imu.accelerometer[0] = self.gazebo_imu.linear_acceleration.x + state.imu.accelerometer[1] = self.gazebo_imu.linear_acceleration.y + state.imu.accelerometer[2] = self.gazebo_imu.linear_acceleration.z for i in range(self.params.num_of_dofs): - state.motor_state.q[i] = self.mapped_joint_positions[i] - state.motor_state.dq[i] = self.mapped_joint_velocities[i] - state.motor_state.tauEst[i] = self.mapped_joint_efforts[i] + state.motor_state.q[i] = self.robot_state_subscriber_msg.motor_state[i].q + state.motor_state.dq[i] = self.robot_state_subscriber_msg.motor_state[i].dq + state.motor_state.tau_est[i] = self.robot_state_subscriber_msg.motor_state[i].tau_est def SetCommand(self, command): for i in range(self.params.num_of_dofs): - self.joint_publishers_commands[i].q = command.motor_command.q[i] - self.joint_publishers_commands[i].dq = command.motor_command.dq[i] - self.joint_publishers_commands[i].kp = command.motor_command.kp[i] - self.joint_publishers_commands[i].kd = command.motor_command.kd[i] - self.joint_publishers_commands[i].tau = command.motor_command.tau[i] + self.robot_command_publisher_msg.motor_command[i].q = float(command.motor_command.q[i]) + self.robot_command_publisher_msg.motor_command[i].dq = float(command.motor_command.dq[i]) + self.robot_command_publisher_msg.motor_command[i].kp = float(command.motor_command.kp[i]) + self.robot_command_publisher_msg.motor_command[i].kd = float(command.motor_command.kd[i]) + self.robot_command_publisher_msg.motor_command[i].tau = float(command.motor_command.tau[i]) - for i in range(self.params.num_of_dofs): - self.joint_publishers[self.params.joint_controller_names[i]].publish(self.joint_publishers_commands[i]) + self.robot_command_publisher.publish(self.robot_command_publisher_msg) def RobotControl(self): - if self.control.control_state == STATE.STATE_RESET_SIMULATION: - set_model_state = SetModelStateRequest().model_state - set_model_state.model_name = self.gazebo_model_name - set_model_state.pose.position.z = 1.0 - set_model_state.reference_frame = "world" - self.gazebo_set_model_state_client(set_model_state) - self.control.control_state = STATE.STATE_WAITING - if self.control.control_state == STATE.STATE_TOGGLE_SIMULATION: - if self.simulation_running: - self.gazebo_pause_physics_client() - print("\r\n" + LOGGER.INFO + "Simulation Stop") - else: - self.gazebo_unpause_physics_client() - print("\r\n" + LOGGER.INFO + "Simulation Start") - self.simulation_running = not self.simulation_running - self.control.control_state = STATE.STATE_WAITING + # NOT AVAILABLE NOW + # if self.control.control_state == STATE.STATE_RESET_SIMULATION: + # set_model_state = SetModelState.Request() + # set_model_state.model_state.model_name = self.gazebo_model_name + # set_model_state.model_state.pose.position.z = 1.0 + # set_model_state.model_state.reference_frame = "world" + # self.gazebo_set_model_state_client.call_async(set_model_state) + # self.control.control_state = STATE.STATE_WAITING + # if self.control.control_state == STATE.STATE_TOGGLE_SIMULATION: + # if self.simulation_running: + # self.gazebo_pause_physics_client.call_async(Empty.Request()) + # self.get_logger().info("Simulation Stop") + # else: + # self.gazebo_unpause_physics_client.call_async(Empty.Request()) + # self.get_logger().info("Simulation Start") + # self.simulation_running = not self.simulation_running + # self.control.control_state = STATE.STATE_WAITING if self.simulation_running: self.GetState(self.robot_state) self.StateController(self.robot_state, self.robot_command) self.SetCommand(self.robot_command) - def ModelStatesCallback(self, msg): - self.vel = msg.twist[2] - self.pose = msg.pose[2] + def GazeboImuCallback(self, msg): + self.gazebo_imu = msg def CmdvelCallback(self, msg): self.cmd_vel = msg - def MapData(self, source_data, target_data): - for i in range(len(source_data)): - target_data[i] = source_data[self.sorted_to_original_index[self.params.joint_controller_names[i]]] - - def JointStatesCallback(self, msg): - self.MapData(msg.position, self.mapped_joint_positions) - self.MapData(msg.velocity, self.mapped_joint_velocities) - self.MapData(msg.effort, self.mapped_joint_efforts) + def RobotStateCallback(self, msg): + self.robot_state_subscriber_msg = msg def RunModel(self): if self.running_state == STATE.STATE_RL_RUNNING and self.simulation_running: - self.obs.lin_vel = torch.tensor([[self.vel.linear.x, self.vel.linear.y, self.vel.linear.z]]) + # self.obs.lin_vel NOT USE self.obs.ang_vel = torch.tensor(self.robot_state.imu.gyroscope).unsqueeze(0) # self.obs.commands = torch.tensor([[self.cmd_vel.linear.x, self.cmd_vel.linear.y, self.cmd_vel.angular.z]]) self.obs.commands = torch.tensor([[self.control.x, self.control.y, self.control.yaw]]) @@ -199,7 +198,9 @@ class RL_Sim(RL): self.output_dof_pos = self.ComputePosition(self.obs.actions) if CSV_LOGGER: - tau_est = torch.tensor(self.mapped_joint_efforts).unsqueeze(0) + tau_est = torch.empty(1, self.params.num_of_dofs, dtype=torch.float32) + for i in range(self.params.num_of_dofs): + tau_est[0, i] = self.robot_state_subscriber_msg.motor_state[i].tau_est self.CSVLogger(self.output_torques, tau_est, self.obs.dof_pos, self.output_dof_pos, self.obs.dof_vel) def Forward(self): @@ -219,21 +220,27 @@ class RL_Sim(RL): def ThreadControl(self): thread_period = self.params.dt thread_name = "thread_control" - print(f"[Thread Start] named: {thread_name}, period: {thread_period * 1000:.0f}(ms), cpu unspecified") - while not rospy.is_shutdown(): + self.get_logger().info(f"[Thread Start] named: {thread_name}, period: {thread_period * 1000:.0f}(ms), cpu unspecified") + while rclpy.ok(): self.RobotControl() time.sleep(thread_period) - print("[Thread End] named: " + thread_name) + self.get_logger().info("[Thread End] named: " + thread_name) def ThreadRL(self): thread_period = self.params.dt * self.params.decimation thread_name = "thread_rl" - print(f"[Thread Start] named: {thread_name}, period: {thread_period * 1000:.0f}(ms), cpu unspecified") - while not rospy.is_shutdown(): + self.get_logger().info(f"[Thread Start] named: {thread_name}, period: {thread_period * 1000:.0f}(ms), cpu unspecified") + while rclpy.ok(): self.RunModel() time.sleep(thread_period) - print("[Thread End] named: " + thread_name) + self.get_logger().info("[Thread End] named: " + thread_name) if __name__ == "__main__": + rclpy.init() rl_sim = RL_Sim() - rospy.spin() + try: + rclpy.spin(rl_sim) + except KeyboardInterrupt: + rl_sim.get_logger().info("Shutdown signal received, shutting down...") + rclpy.shutdown() + diff --git a/src/rl_sar/src/rl_real_a1.cpp b/src/rl_sar/src/rl_real_a1.cpp index 1052954..3f54ddd 100644 --- a/src/rl_sar/src/rl_real_a1.cpp +++ b/src/rl_sar/src/rl_real_a1.cpp @@ -116,7 +116,7 @@ void RL_Real::GetState(RobotState *state) { state->motor_state.q[i] = this->unitree_low_state.motorState[state_mapping[i]].q; state->motor_state.dq[i] = this->unitree_low_state.motorState[state_mapping[i]].dq; - state->motor_state.tauEst[i] = this->unitree_low_state.motorState[state_mapping[i]].tauEst; + state->motor_state.tau_est[i] = this->unitree_low_state.motorState[state_mapping[i]].tauEst; } } @@ -178,7 +178,7 @@ void RL_Real::RunModel() this->output_dof_pos = this->ComputePosition(this->obs.actions); #ifdef CSV_LOGGER - torch::Tensor tau_est = torch::tensor(this->robot_state.motor_state.tauEst).unsqueeze(0); + torch::Tensor tau_est = torch::tensor(this->robot_state.motor_state.tau_est).unsqueeze(0); this->CSVLogger(this->output_torques, tau_est, this->obs.dof_pos, this->output_dof_pos, this->obs.dof_vel); #endif } diff --git a/src/rl_sar/src/rl_real_go2.cpp b/src/rl_sar/src/rl_real_go2.cpp index f414b1d..c19d4ba 100644 --- a/src/rl_sar/src/rl_real_go2.cpp +++ b/src/rl_sar/src/rl_real_go2.cpp @@ -122,7 +122,7 @@ void RL_Real::GetState(RobotState *state) { state->motor_state.q[i] = this->unitree_low_state.motor_state()[state_mapping[i]].q(); state->motor_state.dq[i] = this->unitree_low_state.motor_state()[state_mapping[i]].dq(); - state->motor_state.tauEst[i] = this->unitree_low_state.motor_state()[state_mapping[i]].tau_est(); + state->motor_state.tau_est[i] = this->unitree_low_state.motor_state()[state_mapping[i]].tau_est(); } } @@ -183,7 +183,7 @@ void RL_Real::RunModel() this->output_dof_pos = this->ComputePosition(this->obs.actions); #ifdef CSV_LOGGER - torch::Tensor tau_est = torch::tensor(this->robot_state.motor_state.tauEst).unsqueeze(0); + torch::Tensor tau_est = torch::tensor(this->robot_state.motor_state.tau_est).unsqueeze(0); this->CSVLogger(this->output_torques, tau_est, this->obs.dof_pos, this->output_dof_pos, this->obs.dof_vel); #endif } diff --git a/src/rl_sar/src/rl_sim.cpp b/src/rl_sar/src/rl_sim.cpp index 69ebcc2..57cf071 100644 --- a/src/rl_sar/src/rl_sim.cpp +++ b/src/rl_sar/src/rl_sim.cpp @@ -1,14 +1,43 @@ #include "rl_sim.hpp" // #define PLOT -// #define CSV_LOGGER +#define CSV_LOGGER RL_Sim::RL_Sim() + : rclcpp::Node("rl_sim_node") { - ros::NodeHandle nh; + this->ros_namespace = this->get_namespace(); + + // get params from param_node + param_client = this->create_client("/param_node/get_parameters"); + while (!param_client->wait_for_service(std::chrono::seconds(1))) + { + std::cout << LOGGER::WARNING << "Waiting for param_node service to be available..." << std::endl; + } + auto request = std::make_shared(); + request->names.push_back("robot_name"); + request->names.push_back("gazebo_model_name"); + auto future = param_client->async_send_request(request); + rclcpp::spin_until_future_complete(this->get_node_base_interface(), future); + if (future.get()->values.size() < 2) + { + std::cout << LOGGER::WARNING << "Failed to get all parameters from param_node" << std::endl; + } + else + { + this->robot_name = future.get()->values[0].string_value; + this->gazebo_model_name = future.get()->values[1].string_value; + std::cout << LOGGER::INFO << "Get param robot_name: " << this->robot_name << std::endl; + std::cout << LOGGER::INFO << "Get param gazebo_model_name: " << this->gazebo_model_name << std::endl; + } + + // // get params from this node + // this->declare_parameter("robot_name", ""); + // this->get_parameter("robot_name", this->robot_name); + // this->declare_parameter("gazebo_model_name", ""); + // this->get_parameter("gazebo_model_name", this->gazebo_model_name); // read params from yaml - nh.param("robot_name", this->robot_name, ""); this->ReadYaml(this->robot_name); for (std::string &observation : this->params.observations) { @@ -18,17 +47,6 @@ RL_Sim::RL_Sim() observation = "ang_vel_world"; } } - // Due to the fact that the robot_state_publisher sorts the joint names alphabetically, - // the mapping table is established according to the order defined in the YAML file - std::vector sorted_joint_controller_names = this->params.joint_controller_names; - std::sort(sorted_joint_controller_names.begin(), sorted_joint_controller_names.end()); - for (size_t i = 0; i < this->params.joint_controller_names.size(); ++i) - { - this->sorted_to_original_index[sorted_joint_controller_names[i]] = i; - } - this->mapped_joint_positions = std::vector(this->params.num_of_dofs, 0.0); - this->mapped_joint_velocities = std::vector(this->params.num_of_dofs, 0.0); - this->mapped_joint_efforts = std::vector(this->params.num_of_dofs, 0.0); // init rl torch::autograd::GradMode::set_enabled(false); @@ -36,7 +54,8 @@ RL_Sim::RL_Sim() { this->history_obs_buf = ObservationBuffer(1, this->params.num_observations, this->params.observations_history.size()); } - this->joint_publishers_commands.resize(this->params.num_of_dofs); + this->robot_command_publisher_msg.motor_command.resize(this->params.num_of_dofs); + this->robot_state_subscriber_msg.motor_state.resize(this->params.num_of_dofs); this->InitObservations(); this->InitOutputs(); this->InitControl(); @@ -47,24 +66,26 @@ RL_Sim::RL_Sim() this->model = torch::jit::load(model_path); // publisher - nh.param("ros_namespace", this->ros_namespace, ""); - for (int i = 0; i < this->params.num_of_dofs; ++i) - { - // joint need to rename as xxx_joint - this->joint_publishers[this->params.joint_controller_names[i]] = - nh.advertise(this->ros_namespace + this->params.joint_controller_names[i] + "/command", 10); - } + this->robot_command_publisher = this->create_publisher( + this->ros_namespace + "robot_joint_controller/command", rclcpp::SystemDefaultsQoS()); // subscriber - this->cmd_vel_subscriber = nh.subscribe("/cmd_vel", 10, &RL_Sim::CmdvelCallback, this); - this->model_state_subscriber = nh.subscribe("/gazebo/model_states", 10, &RL_Sim::ModelStatesCallback, this); - this->joint_state_subscriber = nh.subscribe(this->ros_namespace + "joint_states", 10, &RL_Sim::JointStatesCallback, this); + this->cmd_vel_subscriber = this->create_subscription( + "/cmd_vel", rclcpp::SystemDefaultsQoS(), + [this] (const geometry_msgs::msg::Twist::SharedPtr msg) {this->CmdvelCallback(msg);} + ); + this->gazebo_imu_subscriber = this->create_subscription( + "/imu", rclcpp::SystemDefaultsQoS(), [this] (const sensor_msgs::msg::Imu::SharedPtr msg) {this->GazeboImuCallback(msg);} + ); + this->robot_state_subscriber = this->create_subscription( + this->ros_namespace + "robot_joint_controller/state", rclcpp::SystemDefaultsQoS(), + [this] (const robot_msgs::msg::RobotState::SharedPtr msg) {this->RobotStateCallback(msg);} + ); // service - nh.param("gazebo_model_name", this->gazebo_model_name, ""); - this->gazebo_set_model_state_client = nh.serviceClient("/gazebo/set_model_state"); - this->gazebo_pause_physics_client = nh.serviceClient("/gazebo/pause_physics"); - this->gazebo_unpause_physics_client = nh.serviceClient("/gazebo/unpause_physics"); + this->gazebo_set_model_state_client = this->create_client("/gazebo/set_model_state"); + this->gazebo_pause_physics_client = this->create_client("/gazebo/pause_physics"); + this->gazebo_unpause_physics_client = this->create_client("/gazebo/unpause_physics"); // loop this->loop_control = std::make_shared("loop_control", this->params.dt, std::bind(&RL_Sim::RobotControl, this)); @@ -107,30 +128,32 @@ void RL_Sim::GetState(RobotState *state) { if (this->params.framework == "isaacgym") { - state->imu.quaternion[3] = this->pose.orientation.w; - state->imu.quaternion[0] = this->pose.orientation.x; - state->imu.quaternion[1] = this->pose.orientation.y; - state->imu.quaternion[2] = this->pose.orientation.z; + state->imu.quaternion[3] = this->gazebo_imu.orientation.w; + state->imu.quaternion[0] = this->gazebo_imu.orientation.x; + state->imu.quaternion[1] = this->gazebo_imu.orientation.y; + state->imu.quaternion[2] = this->gazebo_imu.orientation.z; } else if (this->params.framework == "isaacsim") { - state->imu.quaternion[0] = this->pose.orientation.w; - state->imu.quaternion[1] = this->pose.orientation.x; - state->imu.quaternion[2] = this->pose.orientation.y; - state->imu.quaternion[3] = this->pose.orientation.z; + state->imu.quaternion[0] = this->gazebo_imu.orientation.w; + state->imu.quaternion[1] = this->gazebo_imu.orientation.x; + state->imu.quaternion[2] = this->gazebo_imu.orientation.y; + state->imu.quaternion[3] = this->gazebo_imu.orientation.z; } - state->imu.gyroscope[0] = this->vel.angular.x; - state->imu.gyroscope[1] = this->vel.angular.y; - state->imu.gyroscope[2] = this->vel.angular.z; + state->imu.gyroscope[0] = this->gazebo_imu.angular_velocity.x; + state->imu.gyroscope[1] = this->gazebo_imu.angular_velocity.y; + state->imu.gyroscope[2] = this->gazebo_imu.angular_velocity.z; - // state->imu.accelerometer + state->imu.accelerometer[0] = this->gazebo_imu.linear_acceleration.x; + state->imu.accelerometer[1] = this->gazebo_imu.linear_acceleration.y; + state->imu.accelerometer[2] = this->gazebo_imu.linear_acceleration.z; for (int i = 0; i < this->params.num_of_dofs; ++i) { - state->motor_state.q[i] = this->mapped_joint_positions[i]; - state->motor_state.dq[i] = this->mapped_joint_velocities[i]; - state->motor_state.tauEst[i] = this->mapped_joint_efforts[i]; + state->motor_state.q[i] = this->robot_state_subscriber_msg.motor_state[i].q; + state->motor_state.dq[i] = this->robot_state_subscriber_msg.motor_state[i].dq; + state->motor_state.tau_est[i] = this->robot_state_subscriber_msg.motor_state[i].tau_est; } } @@ -138,49 +161,79 @@ void RL_Sim::SetCommand(const RobotCommand *command) { for (int i = 0; i < this->params.num_of_dofs; ++i) { - this->joint_publishers_commands[i].q = command->motor_command.q[i]; - this->joint_publishers_commands[i].dq = command->motor_command.dq[i]; - this->joint_publishers_commands[i].kp = command->motor_command.kp[i]; - this->joint_publishers_commands[i].kd = command->motor_command.kd[i]; - this->joint_publishers_commands[i].tau = command->motor_command.tau[i]; + this->robot_command_publisher_msg.motor_command[i].q = command->motor_command.q[i]; + this->robot_command_publisher_msg.motor_command[i].dq = command->motor_command.dq[i]; + this->robot_command_publisher_msg.motor_command[i].kp = command->motor_command.kp[i]; + this->robot_command_publisher_msg.motor_command[i].kd = command->motor_command.kd[i]; + this->robot_command_publisher_msg.motor_command[i].tau = command->motor_command.tau[i]; } - for (int i = 0; i < this->params.num_of_dofs; ++i) - { - this->joint_publishers[this->params.joint_controller_names[i]].publish(this->joint_publishers_commands[i]); - } + this->robot_command_publisher->publish(this->robot_command_publisher_msg); } void RL_Sim::RobotControl() { std::lock_guard lock(robot_state_mutex); - if (this->control.control_state == STATE_RESET_SIMULATION) - { - gazebo_msgs::SetModelState set_model_state; - set_model_state.request.model_state.model_name = this->gazebo_model_name; - set_model_state.request.model_state.pose.position.z = 1.0; - set_model_state.request.model_state.reference_frame = "world"; - this->gazebo_set_model_state_client.call(set_model_state); - - this->control.control_state = STATE_WAITING; - } - if (this->control.control_state == STATE_TOGGLE_SIMULATION) - { - std_srvs::Empty empty; - if (simulation_running) - { - this->gazebo_pause_physics_client.call(empty); - std::cout << std::endl << LOGGER::INFO << "Simulation Stop" << std::endl; - } - else - { - this->gazebo_unpause_physics_client.call(empty); - std::cout << std::endl << LOGGER::INFO << "Simulation Start" << std::endl; - } - simulation_running = !simulation_running; - this->control.control_state = STATE_WAITING; - } + // if (this->control.control_state == STATE_RESET_SIMULATION) + // { + // auto set_model_state_request = std::make_shared(); + // set_model_state_request->model_state.model_name = this->gazebo_model_name; + // set_model_state_request->model_state.pose.position.z = 1.0; + // set_model_state_request->model_state.reference_frame = "world"; + // this->gazebo_set_model_state_client->async_send_request(set_model_state_request, + // [this](rclcpp::Client::SharedFuture future) + // { + // if (future.get()) + // { + // std::cout << LOGGER::INFO << "Reset Simulation" << std::endl; + // this->control.control_state = STATE_WAITING; + // } + // else + // { + // std::cout << LOGGER::WARNING << "Failed to reset simulation" << std::endl; + // } + // } + // ); + // } + // if (this->control.control_state == STATE_TOGGLE_SIMULATION) + // { + // auto empty_request = std::make_shared(); + // if (simulation_running) + // { + // this->gazebo_pause_physics_client->async_send_request(empty_request, + // [this](rclcpp::Client::SharedFuture future) + // { + // if (future.get()) + // { + // std::cout << LOGGER::INFO << "Simulation Stop" << std::endl; + // } + // else + // { + // std::cout << LOGGER::WARNING << "Failed to toggle simulation" << std::endl; + // } + // } + // ); + // } + // else + // { + // this->gazebo_unpause_physics_client->async_send_request(empty_request, + // [this](rclcpp::Client::SharedFuture future) + // { + // if (future.get()) + // { + // std::cout << LOGGER::INFO << "Simulation Start" << std::endl; + // } + // else + // { + // std::cout << LOGGER::WARNING << "Failed to toggle simulation" << std::endl; + // } + // } + // ); + // } + // simulation_running = !simulation_running; + // this->control.control_state = STATE_WAITING; + // } if (simulation_running) { this->motiontime++; @@ -190,30 +243,19 @@ void RL_Sim::RobotControl() } } -void RL_Sim::ModelStatesCallback(const gazebo_msgs::ModelStates::ConstPtr &msg) +void RL_Sim::GazeboImuCallback(const sensor_msgs::msg::Imu::SharedPtr msg) { - this->vel = msg->twist[2]; - this->pose = msg->pose[2]; + this->gazebo_imu = *msg; } -void RL_Sim::CmdvelCallback(const geometry_msgs::Twist::ConstPtr &msg) +void RL_Sim::CmdvelCallback(const geometry_msgs::msg::Twist::SharedPtr msg) { this->cmd_vel = *msg; } -void RL_Sim::MapData(const std::vector &source_data, std::vector &target_data) +void RL_Sim::RobotStateCallback(const robot_msgs::msg::RobotState::SharedPtr msg) { - for (size_t i = 0; i < source_data.size(); ++i) - { - target_data[i] = source_data[this->sorted_to_original_index[this->params.joint_controller_names[i]]]; - } -} - -void RL_Sim::JointStatesCallback(const sensor_msgs::JointState::ConstPtr &msg) -{ - MapData(msg->position, this->mapped_joint_positions); - MapData(msg->velocity, this->mapped_joint_velocities); - MapData(msg->effort, this->mapped_joint_efforts); + this->robot_state_subscriber_msg = *msg; } void RL_Sim::RunModel() @@ -222,7 +264,7 @@ void RL_Sim::RunModel() if (this->running_state == STATE_RL_RUNNING && simulation_running) { - this->obs.lin_vel = torch::tensor({{this->vel.linear.x, this->vel.linear.y, this->vel.linear.z}}); + // this->obs.lin_vel NOT USE this->obs.ang_vel = torch::tensor(this->robot_state.imu.gyroscope).unsqueeze(0); // this->obs.commands = torch::tensor({{this->cmd_vel.linear.x, this->cmd_vel.linear.y, this->cmd_vel.angular.z}}); this->obs.commands = torch::tensor({{this->control.x, this->control.y, this->control.yaw}}); @@ -247,7 +289,11 @@ void RL_Sim::RunModel() this->output_dof_pos = this->ComputePosition(this->obs.actions); #ifdef CSV_LOGGER - torch::Tensor tau_est = torch::tensor(this->mapped_joint_efforts).unsqueeze(0); + torch::Tensor tau_est = torch::empty({1, this->params.num_of_dofs}, torch::kFloat); + for (int i = 0; i < this->params.num_of_dofs; ++i) + { + tau_est[0][i] = this->robot_state_subscriber_msg.motor_state[i].tau_est; + } this->CSVLogger(this->output_torques, tau_est, this->obs.dof_pos, this->output_dof_pos, this->obs.dof_vel); #endif } @@ -291,8 +337,8 @@ void RL_Sim::Plot() { this->plot_real_joint_pos[i].erase(this->plot_real_joint_pos[i].begin()); this->plot_target_joint_pos[i].erase(this->plot_target_joint_pos[i].begin()); - this->plot_real_joint_pos[i].push_back(this->mapped_joint_positions[i]); - this->plot_target_joint_pos[i].push_back(this->joint_publishers_commands[i].q); + this->plot_real_joint_pos[i].push_back(this->robot_state_subscriber_msg.motor_state[i].q); + this->plot_target_joint_pos[i].push_back(this->robot_command_publisher_msg.motor_command[i].q); plt::subplot(4, 3, i + 1); plt::named_plot("_real_joint_pos", this->plot_t, this->plot_real_joint_pos[i], "r"); plt::named_plot("_target_joint_pos", this->plot_t, this->plot_target_joint_pos[i], "b"); @@ -302,17 +348,10 @@ void RL_Sim::Plot() plt::pause(0.01); } -void signalHandler(int signum) -{ - ros::shutdown(); - exit(0); -} - int main(int argc, char **argv) { - signal(SIGINT, signalHandler); - ros::init(argc, argv, "rl_sar"); - RL_Sim rl_sar; - ros::spin(); + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); return 0; } diff --git a/src/robot_joint_controller/CMakeLists.txt b/src/robot_joint_controller/CMakeLists.txt index c64c9e9..9e80a17 100644 --- a/src/robot_joint_controller/CMakeLists.txt +++ b/src/robot_joint_controller/CMakeLists.txt @@ -1,31 +1,66 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.5) project(robot_joint_controller) -find_package(catkin REQUIRED COMPONENTS - controller_interface - hardware_interface - pluginlib - roscpp - realtime_tools - robot_msgs +if(DEFINED ENV{ROS_DISTRO}) + set(ROS_DISTRO_ENV $ENV{ROS_DISTRO}) + if(ROS_DISTRO_ENV STREQUAL "foxy") + add_definitions(-DROS_DISTRO_FOXY) + elseif(ROS_DISTRO_ENV STREQUAL "humble") + add_definitions(-DROS_DISTRO_HUMBLE) + else() + add_definitions(-DROS_DISTRO_UNKNOWN) + endif() +endif() + +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(urdf REQUIRED) +find_package(control_toolbox REQUIRED) +find_package(realtime_tools REQUIRED) +find_package(hardware_interface REQUIRED) +find_package(controller_interface REQUIRED) +find_package(pluginlib REQUIRED) +find_package(robot_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(rcl_interfaces REQUIRED) + +include_directories(include) + +add_library(${PROJECT_NAME} SHARED + src/robot_joint_controller.cpp + src/robot_joint_controller_group.cpp ) -catkin_package( - CATKIN_DEPENDS - robot_msgs - controller_interface - hardware_interface - pluginlib - roscpp - INCLUDE_DIRS include - LIBRARIES ${PROJECT_NAME} +target_include_directories(${PROJECT_NAME} PRIVATE include) + +ament_target_dependencies(${PROJECT_NAME} + rclcpp + urdf + control_toolbox + realtime_tools + hardware_interface + controller_interface + pluginlib + robot_msgs + geometry_msgs + rcl_interfaces ) -include_directories(include ${catkin_INCLUDE_DIRS}) +pluginlib_export_plugin_description_file(controller_interface robot_joint_controller_plugins.xml) -link_directories(${catkin_LIB_DIRS} lib) - -add_library(robot_joint_controller - src/robot_joint_controller.cpp +install(DIRECTORY include/ + DESTINATION include/${PROJECT_NAME} ) -target_link_libraries(robot_joint_controller ${catkin_LIBRARIES}) + +ament_export_libraries(${PROJECT_NAME}) +ament_export_dependencies(rclcpp urdf control_toolbox realtime_tools hardware_interface controller_interface pluginlib robot_msgs geometry_msgs rcl_interfaces) +install( + TARGETS ${PROJECT_NAME} + EXPORT ${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin + INCLUDES DESTINATION include +) + +ament_package() diff --git a/src/robot_joint_controller/include/robot_joint_controller.h b/src/robot_joint_controller/include/robot_joint_controller.h deleted file mode 100644 index a58e4fa..0000000 --- a/src/robot_joint_controller/include/robot_joint_controller.h +++ /dev/null @@ -1,72 +0,0 @@ -#ifndef ROBOT_JOINT_CONTROLLER_H -#define ROBOT_JOINT_CONTROLLER_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include "robot_msgs/MotorCommand.h" -#include "robot_msgs/MotorState.h" -#include - -#include -#include -#include -#include - -#define PosStopF (2.146E+9f) -#define VelStopF (16000.0f) - -typedef struct -{ - uint8_t mode; - double pos; - double posStiffness; - double vel; - double velStiffness; - double torque; -} ServoCommand; - -namespace robot_joint_controller -{ - class RobotJointController : public controller_interface::Controller - { - private: - hardware_interface::JointHandle joint; - ros::Subscriber sub_command, sub_ft; - control_toolbox::Pid pid_controller_; - std::unique_ptr> controller_state_publisher_; - - public: - std::string name_space; - std::string joint_name; - urdf::JointConstSharedPtr joint_urdf; - realtime_tools::RealtimeBuffer command; - robot_msgs::MotorCommand lastCommand; - robot_msgs::MotorState lastState; - ServoCommand servoCommand; - - RobotJointController(); - ~RobotJointController(); - virtual bool init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n); - virtual void starting(const ros::Time &time); - virtual void update(const ros::Time &time, const ros::Duration &period); - virtual void stopping(); - void setCommandCB(const robot_msgs::MotorCommandConstPtr &msg); - void positionLimits(double &position); - void velocityLimits(double &velocity); - void effortLimits(double &effort); - - void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min, const bool &antiwindup = false); - void getGains(double &p, double &i, double &d, double &i_max, double &i_min, bool &antiwindup); - void getGains(double &p, double &i, double &d, double &i_max, double &i_min); - }; -} - -#endif diff --git a/src/robot_joint_controller/include/robot_joint_controller.hpp b/src/robot_joint_controller/include/robot_joint_controller.hpp new file mode 100644 index 0000000..7477a78 --- /dev/null +++ b/src/robot_joint_controller/include/robot_joint_controller.hpp @@ -0,0 +1,92 @@ +#ifndef ROBOT_JOINT_CONTROLLER_HPP +#define ROBOT_JOINT_CONTROLLER_HPP + +#include "rclcpp/logging.hpp" +#include "rclcpp/qos.hpp" +#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" +#include "rclcpp_lifecycle/state.hpp" +#include +#include +#include +#include "controller_interface/controller_interface.hpp" +#include +#include +#include "robot_msgs/msg/motor_command.hpp" +#include "robot_msgs/msg/motor_state.hpp" +#include "visibility_control.h" + +#include +#include +#include +#include +#include +#include + +#define PosStopF (2.146E+9f) +#define VelStopF (16000.0f) + +typedef struct +{ + uint8_t mode; + double pos; + double pos_stiffness; + double vel; + double vel_stiffness; + double torque; +} ServoCommand; + +namespace robot_joint_controller +{ +using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; + +class RobotJointController : public controller_interface::ControllerInterface +{ +public: + ROBOT_JOINT_CONTROLLER_PUBLIC + RobotJointController(); + +#if defined(ROS_DISTRO_FOXY) + ROBOT_JOINT_CONTROLLER_PUBLIC + controller_interface::return_type update() override; +#elif defined(ROS_DISTRO_HUMBLE) + ROBOT_JOINT_CONTROLLER_PUBLIC + controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override; +#endif + ROBOT_JOINT_CONTROLLER_PUBLIC + controller_interface::InterfaceConfiguration command_interface_configuration() const override; + ROBOT_JOINT_CONTROLLER_PUBLIC + controller_interface::InterfaceConfiguration state_interface_configuration() const override; + // ROBOT_JOINT_CONTROLLER_PUBLIC + // CallbackReturn on_init() override; + ROBOT_JOINT_CONTROLLER_PUBLIC + CallbackReturn on_configure(const rclcpp_lifecycle::State &previous_state) override; + ROBOT_JOINT_CONTROLLER_PUBLIC + CallbackReturn on_activate(const rclcpp_lifecycle::State &previous_state) override; + ROBOT_JOINT_CONTROLLER_PUBLIC + CallbackReturn on_deactivate(const rclcpp_lifecycle::State &previous_state) override; + + void UpdateFunc(const double &period_seconds); + void SetCommandCallback(const robot_msgs::msg::MotorCommand::SharedPtr msg); + void PositionLimit(double &position); + void VelocityLimit(double &velocity); + void EffortLimit(double &effort); + +protected: + std::string name_space_; + std::string joint_name_; + realtime_tools::RealtimeBuffer rt_command_ptr_; + robot_msgs::msg::MotorCommand last_command_; + robot_msgs::msg::MotorState last_state_; + ServoCommand servo_command_; + urdf::JointConstSharedPtr joints_urdf_; + rclcpp::Client::SharedPtr robot_description_client_; + rclcpp::Subscription::SharedPtr joints_command_subscriber_; + std::shared_ptr> controller_state_publisher_; +#if defined(ROS_DISTRO_FOXY) + rclcpp::Time previous_update_timestamp_{0}; +#endif +}; + +} // namespace robot_joint_controller + +#endif // ROBOT_JOINT_CONTROLLER_HPP diff --git a/src/robot_joint_controller/include/robot_joint_controller_group.hpp b/src/robot_joint_controller/include/robot_joint_controller_group.hpp new file mode 100644 index 0000000..0efb7cc --- /dev/null +++ b/src/robot_joint_controller/include/robot_joint_controller_group.hpp @@ -0,0 +1,92 @@ +#ifndef ROBOT_JOINT_CONTROLLER_GROUP_HPP +#define ROBOT_JOINT_CONTROLLER_GROUP_HPP + +#include "rclcpp/logging.hpp" +#include "rclcpp/qos.hpp" +#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" +#include "rclcpp_lifecycle/state.hpp" +#include +#include +#include +#include "controller_interface/controller_interface.hpp" +#include +#include +#include "robot_msgs/msg/robot_command.hpp" +#include "robot_msgs/msg/robot_state.hpp" +#include "visibility_control.h" + +#include +#include +#include +#include +#include +#include + +#define PosStopF (2.146E+9f) +#define VelStopF (16000.0f) + +typedef struct +{ + uint8_t mode; + double pos; + double pos_stiffness; + double vel; + double vel_stiffness; + double torque; +} ServoCommand; + +namespace robot_joint_controller +{ +using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; + +class RobotJointControllerGroup : public controller_interface::ControllerInterface +{ +public: + ROBOT_JOINT_CONTROLLER_PUBLIC + RobotJointControllerGroup(); + +#if defined(ROS_DISTRO_FOXY) + ROBOT_JOINT_CONTROLLER_PUBLIC + controller_interface::return_type update() override; +#elif defined(ROS_DISTRO_HUMBLE) + ROBOT_JOINT_CONTROLLER_PUBLIC + controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override; +#endif + ROBOT_JOINT_CONTROLLER_PUBLIC + controller_interface::InterfaceConfiguration command_interface_configuration() const override; + ROBOT_JOINT_CONTROLLER_PUBLIC + controller_interface::InterfaceConfiguration state_interface_configuration() const override; + // ROBOT_JOINT_CONTROLLER_PUBLIC + // CallbackReturn on_init() override; + ROBOT_JOINT_CONTROLLER_PUBLIC + CallbackReturn on_configure(const rclcpp_lifecycle::State &previous_state) override; + ROBOT_JOINT_CONTROLLER_PUBLIC + CallbackReturn on_activate(const rclcpp_lifecycle::State &previous_state) override; + ROBOT_JOINT_CONTROLLER_PUBLIC + CallbackReturn on_deactivate(const rclcpp_lifecycle::State &previous_state) override; + + void UpdateFunc(const double &period_seconds); + void SetCommandCallback(const robot_msgs::msg::RobotCommand::SharedPtr msg); + void PositionLimit(double &position, int &index); + void VelocityLimit(double &velocity, int &index); + void EffortLimit(double &effort, int &index); + +protected: + std::string name_space_; + std::vector joint_names_; + realtime_tools::RealtimeBuffer rt_command_ptr_; + robot_msgs::msg::RobotCommand last_command_; + robot_msgs::msg::RobotState last_state_; + ServoCommand servo_command_; + std::vector joints_urdf_; + rclcpp::Client::SharedPtr robot_description_client_; + rclcpp::Subscription::SharedPtr joints_command_subscriber_; + std::shared_ptr> controller_state_publisher_; +#if defined(ROS_DISTRO_FOXY) + rclcpp::Time previous_update_timestamp_{0}; +#endif +}; + +} // namespace robot_joint_controller + +#endif // ROBOT_JOINT_CONTROLLER_GROUP_HPP diff --git a/src/robot_joint_controller/include/visibility_control.h b/src/robot_joint_controller/include/visibility_control.h new file mode 100644 index 0000000..b1354d7 --- /dev/null +++ b/src/robot_joint_controller/include/visibility_control.h @@ -0,0 +1,35 @@ +#ifndef ROBOT_JOINT_CONTROLLER__VISIBILITY_CONTROL_H_ +#define ROBOT_JOINT_CONTROLLER__VISIBILITY_CONTROL_H_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ +#ifdef __GNUC__ +#define ROBOT_JOINT_CONTROLLER_EXPORT __attribute__((dllexport)) +#define ROBOT_JOINT_CONTROLLER_IMPORT __attribute__((dllimport)) +#else +#define ROBOT_JOINT_CONTROLLER_EXPORT __declspec(dllexport) +#define ROBOT_JOINT_CONTROLLER_IMPORT __declspec(dllimport) +#endif +#ifdef ROBOT_JOINT_CONTROLLER_BUILDING_DLL +#define ROBOT_JOINT_CONTROLLER_PUBLIC ROBOT_JOINT_CONTROLLER_EXPORT +#else +#define ROBOT_JOINT_CONTROLLER_PUBLIC ROBOT_JOINT_CONTROLLER_IMPORT +#endif +#define ROBOT_JOINT_CONTROLLER_PUBLIC_TYPE ROBOT_JOINT_CONTROLLER_PUBLIC +#define ROBOT_JOINT_CONTROLLER_LOCAL +#else +#define ROBOT_JOINT_CONTROLLER_EXPORT __attribute__((visibility("default"))) +#define ROBOT_JOINT_CONTROLLER_IMPORT +#if __GNUC__ >= 4 +#define ROBOT_JOINT_CONTROLLER_PUBLIC __attribute__((visibility("default"))) +#define ROBOT_JOINT_CONTROLLER_LOCAL __attribute__((visibility("hidden"))) +#else +#define ROBOT_JOINT_CONTROLLER_PUBLIC +#define ROBOT_JOINT_CONTROLLER_LOCAL +#endif +#define ROBOT_JOINT_CONTROLLER_PUBLIC_TYPE +#endif + +#endif // ROBOT_JOINT_CONTROLLER__VISIBILITY_CONTROL_H_ \ No newline at end of file diff --git a/src/robot_joint_controller/package.xml b/src/robot_joint_controller/package.xml index 4d75904..f27caab 100644 --- a/src/robot_joint_controller/package.xml +++ b/src/robot_joint_controller/package.xml @@ -1,27 +1,27 @@ - - robot_joint_controller - 0.0.0 - The robot_joint_controller package - Ziqi Fan - Apache - catkin - controller_interface - hardware_interface - pluginlib - roscpp - controller_interface - hardware_interface - pluginlib - roscpp - controller_interface - hardware_interface - pluginlib - roscpp - robot_msgs - - - - - - \ No newline at end of file + + robot_joint_controller + 0.0.0 + The robot_joint_controller package + + Ziqi Fan + Apache-2.0 + + ament_cmake + + rclcpp + urdf + control_toolbox + realtime_tools + hardware_interface + controller_interface + pluginlib + robot_msgs + geometry_msgs + rcl_interfaces + + + ament_cmake + + + diff --git a/src/robot_joint_controller/robot_joint_controller_plugins.xml b/src/robot_joint_controller/robot_joint_controller_plugins.xml index 05cf7f2..2cf7c37 100644 --- a/src/robot_joint_controller/robot_joint_controller_plugins.xml +++ b/src/robot_joint_controller/robot_joint_controller_plugins.xml @@ -1,8 +1,12 @@ - - - - The robot joint controller. - + + + The robot joint single controller + + + The robot joint group controller + diff --git a/src/robot_joint_controller/src/robot_joint_controller.cpp b/src/robot_joint_controller/src/robot_joint_controller.cpp index 41d652c..9d372e9 100644 --- a/src/robot_joint_controller/src/robot_joint_controller.cpp +++ b/src/robot_joint_controller/src/robot_joint_controller.cpp @@ -1,198 +1,231 @@ -#include "robot_joint_controller.h" -#include - -// #define rqtTune // use rqt or not - -double clamp(double &value, double min, double max) -{ - if (value < min) - { - value = min; - } - else if (value > max) - { - value = max; - } - return value; -} +#include "robot_joint_controller.hpp" +#include "hardware_interface/types/hardware_interface_type_values.hpp" +#include namespace robot_joint_controller { +using hardware_interface::HW_IF_POSITION; +using hardware_interface::HW_IF_VELOCITY; +using hardware_interface::HW_IF_EFFORT; - RobotJointController::RobotJointController() +RobotJointController::RobotJointController() + : controller_interface::ControllerInterface(), + joints_command_subscriber_(nullptr), + controller_state_publisher_(nullptr) +{ + memset(&last_command_, 0, sizeof(robot_msgs::msg::MotorCommand)); + memset(&last_state_, 0, sizeof(robot_msgs::msg::MotorState)); + memset(&servo_command_, 0, sizeof(ServoCommand)); +} + +// CallbackReturn RobotJointController::on_init() +// { +// return CallbackReturn::SUCCESS; +// } + +CallbackReturn RobotJointController::on_configure(const rclcpp_lifecycle::State &previous_state) +{ + name_space_ = get_node()->get_namespace(); + + if (!get_node()->get_parameter("joints", joint_name_)) { - memset(&lastCommand, 0, sizeof(robot_msgs::MotorCommand)); - memset(&lastState, 0, sizeof(robot_msgs::MotorState)); - memset(&servoCommand, 0, sizeof(ServoCommand)); + RCLCPP_ERROR(get_node()->get_logger(), "No joint given in namespace: '%s'", name_space_.c_str()); + return CallbackReturn::ERROR; + } + else + { + RCLCPP_WARN(get_node()->get_logger(), "joint_name_: %s", joint_name_.c_str()); } - RobotJointController::~RobotJointController() - { - sub_ft.shutdown(); - sub_command.shutdown(); - } + robot_description_client_ = get_node()->create_client("/robot_state_publisher/get_parameters"); - void RobotJointController::setCommandCB(const robot_msgs::MotorCommandConstPtr &msg) - { - lastCommand.q = msg->q; - lastCommand.kp = msg->kp; - lastCommand.dq = msg->dq; - lastCommand.kd = msg->kd; - lastCommand.tau = msg->tau; - // the writeFromNonRT can be used in RT, if you have the guarantee that - // * no non-rt thread is calling the same function (we're not subscribing to ros callbacks) - // * there is only one single rt thread - command.writeFromNonRT(lastCommand); - } + auto request = std::make_shared(); + request->names.push_back("robot_description_"); - // Controller initialization in non-realtime - bool RobotJointController::init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n) + while (!robot_description_client_->wait_for_service(std::chrono::seconds(1))) { - name_space = n.getNamespace(); - if (!n.getParam("joint", joint_name)) + if (!rclcpp::ok()) { - ROS_ERROR("No joint given in namespace: '%s')", n.getNamespace().c_str()); - return false; + RCLCPP_ERROR(get_node()->get_logger(), "Interrupted while waiting for the service. Exiting."); + } + RCLCPP_WARN(get_node()->get_logger(), "Service not available, waiting again..."); + } + + auto response_received_callback = [this](rclcpp::Client::SharedFuture future) + { + std::string robot_description = future.get()->values[0].string_value; + urdf::Model urdf; + if (!urdf.initString(robot_description)) + { + RCLCPP_ERROR(get_node()->get_logger(), "Failed to parse urdf file"); } - // load pid param from ymal only if rqt need -#ifdef rqtTune - // Load PID Controller using gains set on parameter server - if (!pid_controller_.init(ros::NodeHandle(n, "pid"))) - return false; + joints_urdf_ = urdf.getJoint(joint_name_); + if (!joints_urdf_) + { + RCLCPP_ERROR(get_node()->get_logger(),"Could not find joint '%s' in urdf", joint_name_.c_str()); + } + }; + auto future_result = robot_description_client_->async_send_request(request, response_received_callback); + + // Start command subscriber + joints_command_subscriber_ = get_node()->create_subscription( + "~/command", rclcpp::SystemDefaultsQoS(), std::bind(&RobotJointController::SetCommandCallback, this, std::placeholders::_1)); + + // Start realtime state publisher + controller_state_publisher_ = std::make_shared>( + get_node()->create_publisher(/*name_space_ + */"~/state", rclcpp::SystemDefaultsQoS())); + +#if defined(ROS_DISTRO_FOXY) + previous_update_timestamp_ = get_node()->get_clock()->now(); #endif - urdf::Model urdf; // Get URDF info about joint - if (!urdf.initParamWithNodeHandle("robot_description", n)) - { - ROS_ERROR("Failed to parse urdf file"); - return false; - } - joint_urdf = urdf.getJoint(joint_name); - if (!joint_urdf) - { - ROS_ERROR("Could not find joint '%s' in urdf", joint_name.c_str()); - return false; - } - joint = robot->getHandle(joint_name); + RCLCPP_INFO(get_node()->get_logger(), "configure successful"); + return CallbackReturn::SUCCESS; +} - // Start command subscriber - sub_command = n.subscribe("command", 20, &RobotJointController::setCommandCB, this); +controller_interface::InterfaceConfiguration RobotJointController::command_interface_configuration() const +{ + controller_interface::InterfaceConfiguration command_interfaces_config; + command_interfaces_config.type = controller_interface::interface_configuration_type::INDIVIDUAL; - // Start realtime state publisher - controller_state_publisher_.reset( - new realtime_tools::RealtimePublisher(n, name_space + "/state", 1)); + command_interfaces_config.names.push_back(joint_name_ + "/" + HW_IF_EFFORT); - return true; - } + return command_interfaces_config; - void RobotJointController::setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min, const bool &antiwindup) +} + +controller_interface::InterfaceConfiguration RobotJointController::state_interface_configuration() const +{ + controller_interface::InterfaceConfiguration state_interfaces_config; + state_interfaces_config.type = controller_interface::interface_configuration_type::INDIVIDUAL; + + state_interfaces_config.names.push_back(joint_name_ + "/" + HW_IF_POSITION); + state_interfaces_config.names.push_back(joint_name_ + "/" + HW_IF_EFFORT); + + return state_interfaces_config; +} + +CallbackReturn RobotJointController::on_activate(const rclcpp_lifecycle::State &previous_state) +{ + double init_pos = state_interfaces_[0].get_value(); + last_command_.q = init_pos; + last_state_.q = init_pos; + last_command_.dq = 0; + last_state_.dq = 0; + last_command_.tau = 0; + last_state_.tau_est = 0; + + // reset command buffer if a command came through callback when controller was inactive + rt_command_ptr_ = realtime_tools::RealtimeBuffer(); + + return CallbackReturn::SUCCESS; +} + +CallbackReturn RobotJointController::on_deactivate(const rclcpp_lifecycle::State &previous_state) +{ + // reset command buffer + rt_command_ptr_ = realtime_tools::RealtimeBuffer(); + return CallbackReturn::SUCCESS; +} + +#if defined(ROS_DISTRO_FOXY) +controller_interface::return_type RobotJointController::update() +{ + const auto current_time = get_node()->get_clock()->now(); + const auto period_seconds = (current_time - previous_update_timestamp_).seconds(); + previous_update_timestamp_ = current_time; + auto joint_command = rt_command_ptr_.readFromRT(); + // no command received yet + if (!joint_command) { - pid_controller_.setGains(p, i, d, i_max, i_min, antiwindup); + return controller_interface::return_type::OK; } - - void RobotJointController::getGains(double &p, double &i, double &d, double &i_max, double &i_min, bool &antiwindup) + last_command_ = *(joint_command); + UpdateFunc(period_seconds); + return controller_interface::return_type::OK; +} +#elif defined(ROS_DISTRO_HUMBLE) +controller_interface::return_type RobotJointController::update(const rclcpp::Time &time, const rclcpp::Duration &period) +{ + const auto period_seconds = period.seconds(); + auto joint_command = rt_command_ptr_.readFromRT(); + // no command received yet + if (!joint_command) { - pid_controller_.getGains(p, i, d, i_max, i_min, antiwindup); + return controller_interface::return_type::OK; } - - void RobotJointController::getGains(double &p, double &i, double &d, double &i_max, double &i_min) - { - bool dummy; - pid_controller_.getGains(p, i, d, i_max, i_min, dummy); - } - - // Controller startup in realtime - void RobotJointController::starting(const ros::Time &time) - { - double init_pos = joint.getPosition(); - lastCommand.q = init_pos; - lastState.q = init_pos; - lastCommand.dq = 0; - lastState.dq = 0; - lastCommand.tau = 0; - lastState.tauEst = 0; - command.initRT(lastCommand); - - pid_controller_.reset(); - } - - // Controller update loop in realtime - void RobotJointController::update(const ros::Time &time, const ros::Duration &period) - { - double currentPos, currentVel, calcTorque; - lastCommand = *(command.readFromRT()); - - // set command data - servoCommand.pos = lastCommand.q; - positionLimits(servoCommand.pos); - servoCommand.posStiffness = lastCommand.kp; - if (fabs(lastCommand.q - PosStopF) < 0.00001) - { - servoCommand.posStiffness = 0; - } - servoCommand.vel = lastCommand.dq; - velocityLimits(servoCommand.vel); - servoCommand.velStiffness = lastCommand.kd; - if (fabs(lastCommand.dq - VelStopF) < 0.00001) - { - servoCommand.velStiffness = 0; - } - servoCommand.torque = lastCommand.tau; - effortLimits(servoCommand.torque); - - // rqt set P D gains -#ifdef rqtTune - double i, i_max, i_min; - getGains(servoCommand.posStiffness, i, servoCommand.velStiffness, i_max, i_min); + last_command_ = *(joint_command); + UpdateFunc(period_seconds); + return controller_interface::return_type::OK; +} #endif - currentPos = joint.getPosition(); - // currentVel = computeVel(currentPos, (double)lastState.q, (double)lastState.dq, period.toSec()); - // calcTorque = computeTorque(currentPos, currentVel, servoCommand); - currentVel = (currentPos - (double)lastState.q) / period.toSec(); - calcTorque = servoCommand.posStiffness * (servoCommand.pos - currentPos) + servoCommand.velStiffness * (servoCommand.vel - currentVel) + servoCommand.torque; - effortLimits(calcTorque); +void RobotJointController::UpdateFunc(const double &period_seconds) +{ + double currentPos = 0.0; + double currentVel = 0.0; + double calcTorque = 0.0; - joint.setCommand(calcTorque); - - lastState.q = currentPos; - lastState.dq = currentVel; - // lastState.tauEst = calcTorque; - lastState.tauEst = joint.getEffort(); - - // publish state - if (controller_state_publisher_ && controller_state_publisher_->trylock()) - { - controller_state_publisher_->msg_.q = lastState.q; - controller_state_publisher_->msg_.dq = lastState.dq; - controller_state_publisher_->msg_.tauEst = lastState.tauEst; - controller_state_publisher_->unlockAndPublish(); - } - } - - // Controller stopping in realtime - void RobotJointController::stopping() {} - - void RobotJointController::positionLimits(double &position) + // set command data + servo_command_.pos = last_command_.q; + PositionLimit(servo_command_.pos); + servo_command_.pos_stiffness = last_command_.kp; + if (fabs(last_command_.q - PosStopF) < 0.00001) { - if (joint_urdf->type == urdf::Joint::REVOLUTE || joint_urdf->type == urdf::Joint::PRISMATIC) - clamp(position, joint_urdf->limits->lower, joint_urdf->limits->upper); + servo_command_.pos_stiffness = 0; } - - void RobotJointController::velocityLimits(double &velocity) + servo_command_.vel = last_command_.dq; + VelocityLimit(servo_command_.vel); + servo_command_.vel_stiffness = last_command_.kd; + if (fabs(last_command_.dq - VelStopF) < 0.00001) { - if (joint_urdf->type == urdf::Joint::REVOLUTE || joint_urdf->type == urdf::Joint::PRISMATIC) - clamp(velocity, -joint_urdf->limits->velocity, joint_urdf->limits->velocity); + servo_command_.vel_stiffness = 0; } + servo_command_.torque = last_command_.tau; + EffortLimit(servo_command_.torque); - void RobotJointController::effortLimits(double &effort) + currentPos = state_interfaces_[0].get_value(); + currentVel = (currentPos - (double)(last_state_.q)) / period_seconds; + calcTorque = servo_command_.pos_stiffness * (servo_command_.pos - currentPos) + servo_command_.vel_stiffness * (servo_command_.vel - currentVel) + servo_command_.torque; + EffortLimit(calcTorque); + + command_interfaces_[0].set_value(calcTorque); + + last_state_.q = currentPos; + last_state_.dq = currentVel; + last_state_.tau_est = state_interfaces_[1].get_value(); + + // publish state + if (controller_state_publisher_ && controller_state_publisher_->trylock()) { - if (joint_urdf->type == urdf::Joint::REVOLUTE || joint_urdf->type == urdf::Joint::PRISMATIC) - clamp(effort, -joint_urdf->limits->effort, joint_urdf->limits->effort); + controller_state_publisher_->msg_ = last_state_; + controller_state_publisher_->unlockAndPublish(); } +} -} // namespace +void RobotJointController::SetCommandCallback(const robot_msgs::msg::MotorCommand::SharedPtr msg) +{ + last_command_ = *msg; + rt_command_ptr_.writeFromNonRT(last_command_); +} + +void RobotJointController::PositionLimit(double &position) +{ + std::clamp(position, joints_urdf_->limits->lower, joints_urdf_->limits->upper); +} + +void RobotJointController::VelocityLimit(double &velocity) +{ + std::clamp(velocity, -joints_urdf_->limits->velocity, joints_urdf_->limits->velocity); +} + +void RobotJointController::EffortLimit(double &effort) +{ + std::clamp(effort, -joints_urdf_->limits->effort, joints_urdf_->limits->effort); +} + +} // namespace robot_joint_controller // Register controller to pluginlib -PLUGINLIB_EXPORT_CLASS(robot_joint_controller::RobotJointController, controller_interface::ControllerBase); +PLUGINLIB_EXPORT_CLASS(robot_joint_controller::RobotJointController, controller_interface::ControllerInterface) diff --git a/src/robot_joint_controller/src/robot_joint_controller_group.cpp b/src/robot_joint_controller/src/robot_joint_controller_group.cpp new file mode 100644 index 0000000..7e2bdf3 --- /dev/null +++ b/src/robot_joint_controller/src/robot_joint_controller_group.cpp @@ -0,0 +1,278 @@ +#include "robot_joint_controller_group.hpp" +#include "hardware_interface/types/hardware_interface_type_values.hpp" +#include + +namespace robot_joint_controller +{ +using hardware_interface::HW_IF_POSITION; +using hardware_interface::HW_IF_VELOCITY; +using hardware_interface::HW_IF_EFFORT; + +RobotJointControllerGroup::RobotJointControllerGroup() + : controller_interface::ControllerInterface(), + joints_command_subscriber_(nullptr), + controller_state_publisher_(nullptr) +{ + memset(&servo_command_, 0, sizeof(ServoCommand)); +} + +// CallbackReturn RobotJointControllerGroup::on_init() +// { +// return CallbackReturn::SUCCESS; +// } + +CallbackReturn RobotJointControllerGroup::on_configure(const rclcpp_lifecycle::State &previous_state) +{ + name_space_ = get_node()->get_namespace(); + + joint_names_ = get_node()->get_parameter("joints").as_string_array(); + + if (joint_names_.empty()) + { + RCLCPP_ERROR(get_node()->get_logger(), "'joints' parameter was empty"); + return CallbackReturn::ERROR; + } + else + { + for (const auto& joint_name : joint_names_) + { + RCLCPP_WARN(get_node()->get_logger(), "joint_name: %s", joint_name.c_str()); + } + } + + robot_description_client_ = get_node()->create_client("/robot_state_publisher/get_parameters"); + + auto request = std::make_shared(); + request->names.push_back("robot_description"); + + while (!robot_description_client_->wait_for_service(std::chrono::seconds(1))) + { + if (!rclcpp::ok()) + { + RCLCPP_ERROR(get_node()->get_logger(), "Interrupted while waiting for the service. Exiting."); + } + RCLCPP_WARN(get_node()->get_logger(), "Service not available, waiting again..."); + } + + auto response_received_callback = [this](rclcpp::Client::SharedFuture future) + { + std::string robot_description = future.get()->values[0].string_value; + urdf::Model urdf; + if (!urdf.initString(robot_description)) + { + RCLCPP_ERROR(get_node()->get_logger(), "Failed to parse urdf file"); + } + + for (const auto& joint_name : joint_names_) + { + auto joint_urdf = urdf.getJoint(joint_name); + if (!joint_urdf) + { + RCLCPP_ERROR(get_node()->get_logger(),"Could not find joint '%s' in urdf", joint_name.c_str()); + } + if (joint_urdf) + { + joints_urdf_.push_back(joint_urdf); + } + } + }; + auto future_result = robot_description_client_->async_send_request(request, response_received_callback); + + // Start command subscriber + joints_command_subscriber_ = get_node()->create_subscription( + "~/command", rclcpp::SystemDefaultsQoS(), std::bind(&RobotJointControllerGroup::SetCommandCallback, this, std::placeholders::_1)); + + // Start realtime state publisher + controller_state_publisher_ = std::make_shared>( + get_node()->create_publisher(/*name_space_ + */"~/state", rclcpp::SystemDefaultsQoS())); + +#if defined(ROS_DISTRO_FOXY) + previous_update_timestamp_ = get_node()->get_clock()->now(); +#endif + + RCLCPP_INFO(get_node()->get_logger(), "configure successful"); + return CallbackReturn::SUCCESS; +} + +controller_interface::InterfaceConfiguration RobotJointControllerGroup::command_interface_configuration() const +{ + controller_interface::InterfaceConfiguration command_interfaces_config; + command_interfaces_config.type = controller_interface::interface_configuration_type::INDIVIDUAL; + + for (const auto & joint_name : joint_names_) + { + command_interfaces_config.names.push_back(joint_name + "/" + HW_IF_EFFORT); + } + + return command_interfaces_config; +} + +controller_interface::InterfaceConfiguration RobotJointControllerGroup::state_interface_configuration() const +{ + controller_interface::InterfaceConfiguration state_interfaces_config; + state_interfaces_config.type = controller_interface::interface_configuration_type::INDIVIDUAL; + + for (const auto & joint_name : joint_names_) + { + state_interfaces_config.names.push_back(joint_name + "/" + HW_IF_POSITION); + state_interfaces_config.names.push_back(joint_name + "/" + HW_IF_EFFORT); + } + + return state_interfaces_config; +} + +CallbackReturn RobotJointControllerGroup::on_activate(const rclcpp_lifecycle::State &previous_state) +{ + last_command_ = robot_msgs::msg::RobotCommand(); + last_command_.motor_command.resize(joint_names_.size()); + last_state_ = robot_msgs::msg::RobotState(); + last_state_.motor_state.resize(joint_names_.size()); + + for (int index = 0; index < joint_names_.size(); ++index) + { + double init_pos = state_interfaces_[index * 2].get_value(); + last_command_.motor_command[index].q = init_pos; + last_state_.motor_state[index].q = init_pos; + last_command_.motor_command[index].dq = 0; + last_state_.motor_state[index].dq = 0; + last_command_.motor_command[index].tau = 0; + last_state_.motor_state[index].tau_est = 0; + } + + // reset command buffer if a command came through callback when controller was inactive + rt_command_ptr_ = realtime_tools::RealtimeBuffer(); + rt_command_ptr_.writeFromNonRT(last_command_); + + return CallbackReturn::SUCCESS; +} + +CallbackReturn RobotJointControllerGroup::on_deactivate(const rclcpp_lifecycle::State &previous_state) +{ + last_command_ = robot_msgs::msg::RobotCommand(); + last_command_.motor_command.resize(joint_names_.size()); + last_state_ = robot_msgs::msg::RobotState(); + last_state_.motor_state.resize(joint_names_.size()); + + // reset command buffer + rt_command_ptr_ = realtime_tools::RealtimeBuffer(); + rt_command_ptr_.writeFromNonRT(last_command_); + return CallbackReturn::SUCCESS; +} + +#if defined(ROS_DISTRO_FOXY) +controller_interface::return_type RobotJointControllerGroup::update() +{ + const auto current_time = get_node()->get_clock()->now(); + const auto period_seconds = (current_time - previous_update_timestamp_).seconds(); + previous_update_timestamp_ = current_time; + auto joint_commands = rt_command_ptr_.readFromRT(); + // no command received yet + if (!joint_commands) + { + return controller_interface::return_type::OK; + } + if (joint_commands->motor_command.size() != joint_names_.size()) + { + RCLCPP_ERROR_THROTTLE(get_node()->get_logger(), *get_node()->get_clock(), 1000, + "command size (%zu) does not match number of interfaces (%zu)", + joint_commands->motor_command.size(), joint_names_.size()); + return controller_interface::return_type::ERROR; + } + last_command_ = *(joint_commands); + UpdateFunc(period_seconds); + return controller_interface::return_type::OK; +} +#elif defined(ROS_DISTRO_HUMBLE) +controller_interface::return_type RobotJointControllerGroup::update(const rclcpp::Time &time, const rclcpp::Duration &period) +{ + const auto period_seconds = period.seconds(); + auto joint_commands = rt_command_ptr_.readFromRT(); + // no command received yet + if (!joint_commands) + { + return controller_interface::return_type::OK; + } + if (joint_commands->motor_command.size() != joint_names_.size()) + { + RCLCPP_ERROR_THROTTLE(get_node()->get_logger(), *get_node()->get_clock(), 1000, + "command size (%zu) does not match number of interfaces (%zu)", + joint_commands->motor_command.size(), joint_names_.size()); + return controller_interface::return_type::ERROR; + } + last_command_ = *(joint_commands); + UpdateFunc(period_seconds); + return controller_interface::return_type::OK; +} +#endif + +void RobotJointControllerGroup::UpdateFunc(const double &period_seconds) +{ + std::vector currentPos(joint_names_.size(), 0.0); + std::vector currentVel(joint_names_.size(), 0.0); + std::vector calcTorque(joint_names_.size(), 0.0); + + for (int index = 0; index < joint_names_.size(); ++index) + { + // set command data + servo_command_.pos = last_command_.motor_command[index].q; + PositionLimit(servo_command_.pos, index); + servo_command_.pos_stiffness = last_command_.motor_command[index].kp; + if (fabs(last_command_.motor_command[index].q - PosStopF) < 0.00001) + { + servo_command_.pos_stiffness = 0; + } + servo_command_.vel = last_command_.motor_command[index].dq; + VelocityLimit(servo_command_.vel, index); + servo_command_.vel_stiffness = last_command_.motor_command[index].kd; + if (fabs(last_command_.motor_command[index].dq - VelStopF) < 0.00001) + { + servo_command_.vel_stiffness = 0; + } + servo_command_.torque = last_command_.motor_command[index].tau; + EffortLimit(servo_command_.torque, index); + + currentPos[index] = state_interfaces_[index * 2].get_value(); + currentVel[index] = (currentPos[index] - (double)(last_state_.motor_state[index].q)) / period_seconds; + calcTorque[index] = servo_command_.pos_stiffness * (servo_command_.pos - currentPos[index]) + servo_command_.vel_stiffness * (servo_command_.vel - currentVel[index]) + servo_command_.torque; + EffortLimit(calcTorque[index], index); + + command_interfaces_[index].set_value(calcTorque[index]); + + last_state_.motor_state[index].q = currentPos[index]; + last_state_.motor_state[index].dq = currentVel[index]; + last_state_.motor_state[index].tau_est = state_interfaces_[index + 1].get_value(); + } + + // publish state + if (controller_state_publisher_ && controller_state_publisher_->trylock()) + { + controller_state_publisher_->msg_.motor_state = last_state_.motor_state; + controller_state_publisher_->unlockAndPublish(); + } +} + +void RobotJointControllerGroup::SetCommandCallback(const robot_msgs::msg::RobotCommand::SharedPtr msg) +{ + last_command_ = *msg; + rt_command_ptr_.writeFromNonRT(last_command_); +} + +void RobotJointControllerGroup::PositionLimit(double &position, int &index) +{ + std::clamp(position, joints_urdf_[index]->limits->lower, joints_urdf_[index]->limits->upper); +} + +void RobotJointControllerGroup::VelocityLimit(double &velocity, int &index) +{ + std::clamp(velocity, -joints_urdf_[index]->limits->velocity, joints_urdf_[index]->limits->velocity); +} + +void RobotJointControllerGroup::EffortLimit(double &effort, int &index) +{ + std::clamp(effort, -joints_urdf_[index]->limits->effort, joints_urdf_[index]->limits->effort); +} + +} // namespace robot_joint_controller + +// Register controller to pluginlib +PLUGINLIB_EXPORT_CLASS(robot_joint_controller::RobotJointControllerGroup, controller_interface::ControllerInterface) diff --git a/src/robot_msgs/CMakeLists.txt b/src/robot_msgs/CMakeLists.txt index 108236f..e297cca 100644 --- a/src/robot_msgs/CMakeLists.txt +++ b/src/robot_msgs/CMakeLists.txt @@ -1,44 +1,17 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.5) project(robot_msgs) -find_package(catkin REQUIRED COMPONENTS - message_generation - std_msgs - geometry_msgs - sensor_msgs +# find dependencies +find_package(ament_cmake REQUIRED) + +find_package(rosidl_default_generators REQUIRED) + +rosidl_generate_interfaces(${PROJECT_NAME} + "msg/MotorCommand.msg" + "msg/MotorState.msg" + "msg/RobotCommand.msg" + "msg/RobotState.msg" + "msg/IMU.msg" ) -add_message_files( - FILES - MotorCommand.msg - MotorState.msg - RobotCommand.msg - RobotState.msg - IMU.msg -) - -generate_messages( - DEPENDENCIES - std_msgs - geometry_msgs - sensor_msgs -) - -catkin_package( - CATKIN_DEPENDS - message_runtime - std_msgs - geometry_msgs - sensor_msgs -) - -############# -## Install ## -############# - -# Mark topic names header files for installation -install( - DIRECTORY include/${PROJECT_NAME}/ - DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} - FILES_MATCHING PATTERN "*.h" -) \ No newline at end of file +ament_package() diff --git a/src/robot_msgs/msg/MotorState.msg b/src/robot_msgs/msg/MotorState.msg index fbc5477..a1cd87c 100644 --- a/src/robot_msgs/msg/MotorState.msg +++ b/src/robot_msgs/msg/MotorState.msg @@ -1,5 +1,5 @@ -float32 q # motor current position (rad) -float32 dq # motor current speed (rad/s) -float32 ddq # motor current speed (rad/s) -float32 tauEst # current estimated output torque (N*m) +float32 q # motor current pos (rad) +float32 dq # motor current vel (rad/s) +float32 ddq # motor current acc (rad/s^2) +float32 tau_est # current estimated output torque (N*m) float32 cur # current estimated output cur (N*m) \ No newline at end of file diff --git a/src/robot_msgs/msg/RobotCommand.msg b/src/robot_msgs/msg/RobotCommand.msg index f8f6bec..0515c9a 100644 --- a/src/robot_msgs/msg/RobotCommand.msg +++ b/src/robot_msgs/msg/RobotCommand.msg @@ -1 +1 @@ -MotorCommand[32] motor_command \ No newline at end of file +MotorCommand[] motor_command \ No newline at end of file diff --git a/src/robot_msgs/msg/RobotState.msg b/src/robot_msgs/msg/RobotState.msg index d11a054..60fd506 100644 --- a/src/robot_msgs/msg/RobotState.msg +++ b/src/robot_msgs/msg/RobotState.msg @@ -1,2 +1,2 @@ IMU imu -MotorState[32] motor_state \ No newline at end of file +MotorState[] motor_state \ No newline at end of file diff --git a/src/robot_msgs/package.xml b/src/robot_msgs/package.xml index ba89639..c8ee2c3 100644 --- a/src/robot_msgs/package.xml +++ b/src/robot_msgs/package.xml @@ -1,19 +1,19 @@ - - + + robot_msgs 0.0.0 - - The robot messgaes package. - + The robot messages package. Ziqi Fan - Apache - - catkin - message_runtime - message_generation - std_msgs - geometry_msgs - sensor_msgs - - \ No newline at end of file + Apache 2.0 + + ament_cmake + + + ament_cmake + + + rosidl_default_generators + rosidl_default_runtime + rosidl_interface_packages + diff --git a/src/robots/a1_description/CMakeLists.txt b/src/robots/a1_description/CMakeLists.txt index 0415ceb..315164e 100644 --- a/src/robots/a1_description/CMakeLists.txt +++ b/src/robots/a1_description/CMakeLists.txt @@ -1,18 +1,22 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.8) project(a1_description) -find_package(catkin REQUIRED COMPONENTS - genmsg - roscpp - std_msgs - tf +find_package(ament_cmake REQUIRED) +find_package(ament_lint_auto REQUIRED) +find_package(urdf REQUIRED) +find_package(xacro REQUIRED) +find_package(robot_state_publisher REQUIRED) + +install( + DIRECTORY + config + launch + meshes + urdf + xacro + + DESTINATION + share/${PROJECT_NAME}/ ) -catkin_package( - CATKIN_DEPENDS -) - -include_directories( - # include - ${catkin_INCLUDE_DIRS} -) +ament_package() diff --git a/src/robots/a1_description/config/robot_control.yaml b/src/robots/a1_description/config/robot_control.yaml index 0e044d4..6675ec8 100644 --- a/src/robots/a1_description/config/robot_control.yaml +++ b/src/robots/a1_description/config/robot_control.yaml @@ -1,70 +1,113 @@ -a1_gazebo: - # Publish all joint states ----------------------------------- - joint_state_controller: - type: joint_state_controller/JointStateController - publish_rate: 1000 +controller_manager: + ros__parameters: + update_rate: 1000 # Hz + # use_sim_time: true # If running in simulation - # FL Controllers --------------------------------------- - FL_hip_controller: - type: robot_joint_controller/RobotJointController + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + + imu_sensor_broadcaster: + type: imu_sensor_broadcaster/ImuSensorBroadcaster + + # FL Controllers --------------------------------------- + FL_hip_controller: + type: robot_joint_controller/RobotJointController + FL_thigh_controller: + type: robot_joint_controller/RobotJointController + FL_calf_controller: + type: robot_joint_controller/RobotJointController + + # FR Controllers --------------------------------------- + FR_hip_controller: + type: robot_joint_controller/RobotJointController + FR_thigh_controller: + type: robot_joint_controller/RobotJointController + FR_calf_controller: + type: robot_joint_controller/RobotJointController + + # RL Controllers --------------------------------------- + RL_hip_controller: + type: robot_joint_controller/RobotJointController + RL_thigh_controller: + type: robot_joint_controller/RobotJointController + RL_calf_controller: + type: robot_joint_controller/RobotJointController + + # RR Controllers --------------------------------------- + RR_hip_controller: + type: robot_joint_controller/RobotJointController + RR_thigh_controller: + type: robot_joint_controller/RobotJointController + RR_calf_controller: + type: robot_joint_controller/RobotJointController + + +# FL Controllers --------------------------------------- +FL_hip_controller: + ros__parameters: joint: FL_hip_joint pid: {p: 100.0, i: 0.0, d: 5.0} - FL_thigh_controller: - type: robot_joint_controller/RobotJointController +FL_thigh_controller: + ros__parameters: joint: FL_thigh_joint pid: {p: 300.0, i: 0.0, d: 8.0} - FL_calf_controller: - type: robot_joint_controller/RobotJointController +FL_calf_controller: + ros__parameters: joint: FL_calf_joint pid: {p: 300.0, i: 0.0, d: 8.0} - # FR Controllers --------------------------------------- - FR_hip_controller: - type: robot_joint_controller/RobotJointController +# FR Controllers --------------------------------------- +FR_hip_controller: + ros__parameters: joint: FR_hip_joint pid: {p: 100.0, i: 0.0, d: 5.0} - FR_thigh_controller: - type: robot_joint_controller/RobotJointController +FR_thigh_controller: + ros__parameters: joint: FR_thigh_joint pid: {p: 300.0, i: 0.0, d: 8.0} - FR_calf_controller: - type: robot_joint_controller/RobotJointController +FR_calf_controller: + ros__parameters: joint: FR_calf_joint pid: {p: 300.0, i: 0.0, d: 8.0} - # RL Controllers --------------------------------------- - RL_hip_controller: - type: robot_joint_controller/RobotJointController +# RL Controllers --------------------------------------- +RL_hip_controller: + ros__parameters: joint: RL_hip_joint pid: {p: 100.0, i: 0.0, d: 5.0} - RL_thigh_controller: - type: robot_joint_controller/RobotJointController +RL_thigh_controller: + ros__parameters: joint: RL_thigh_joint pid: {p: 300.0, i: 0.0, d: 8.0} - RL_calf_controller: - type: robot_joint_controller/RobotJointController +RL_calf_controller: + ros__parameters: joint: RL_calf_joint pid: {p: 300.0, i: 0.0, d: 8.0} - # RR Controllers --------------------------------------- - RR_hip_controller: - type: robot_joint_controller/RobotJointController +# RR Controllers --------------------------------------- +RR_hip_controller: + ros__parameters: joint: RR_hip_joint pid: {p: 100.0, i: 0.0, d: 5.0} - RR_thigh_controller: - type: robot_joint_controller/RobotJointController +RR_thigh_controller: + ros__parameters: joint: RR_thigh_joint pid: {p: 300.0, i: 0.0, d: 8.0} - RR_calf_controller: - type: robot_joint_controller/RobotJointController +RR_calf_controller: + ros__parameters: joint: RR_calf_joint pid: {p: 300.0, i: 0.0, d: 8.0} +imu_sensor_broadcaster: + ros__parameters: + sensor_name: "imu_sensor" + frame_id: imu_link + diff --git a/src/robots/a1_description/config/robot_control_group.yaml b/src/robots/a1_description/config/robot_control_group.yaml new file mode 100644 index 0000000..84056f3 --- /dev/null +++ b/src/robots/a1_description/config/robot_control_group.yaml @@ -0,0 +1,34 @@ +controller_manager: + ros__parameters: + update_rate: 1000 # Hz + # use_sim_time: true # If running in simulation + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + + imu_sensor_broadcaster: + type: imu_sensor_broadcaster/ImuSensorBroadcaster + + robot_joint_controller: + type: robot_joint_controller/RobotJointControllerGroup + +robot_joint_controller: + ros__parameters: + joints: + - FL_hip_joint + - FL_thigh_joint + - FL_calf_joint + - FR_hip_joint + - FR_thigh_joint + - FR_calf_joint + - RL_hip_joint + - RL_thigh_joint + - RL_calf_joint + - RR_hip_joint + - RR_thigh_joint + - RR_calf_joint + +imu_sensor_broadcaster: + ros__parameters: + sensor_name: "imu_sensor" + frame_id: imu_link \ No newline at end of file diff --git a/src/robots/a1_description/launch/a1_rviz.launch b/src/robots/a1_description/launch/a1_rviz.launch deleted file mode 100644 index 6d74b9b..0000000 --- a/src/robots/a1_description/launch/a1_rviz.launch +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - \ No newline at end of file diff --git a/src/robots/a1_description/launch/a1_rviz.launch.py b/src/robots/a1_description/launch/a1_rviz.launch.py new file mode 100644 index 0000000..db2f9ba --- /dev/null +++ b/src/robots/a1_description/launch/a1_rviz.launch.py @@ -0,0 +1,83 @@ +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument +from launch_ros.actions import Node +from launch.conditions import IfCondition + +import xacro + + +def generate_launch_description(): + + ####### DATA INPUT ########## + # urdf_file = 'moonbotX.urdf' + package_description = "a1_description" + + use_sim_time = LaunchConfiguration('use_sim_time') + + use_joint_state_publisher = LaunchConfiguration('use_joint_state_publisher') + + # Process the URDF file + pkg_path = os.path.join(get_package_share_directory(package_description)) + xacro_file = os.path.join(pkg_path,'xacro','robot.xacro') + robot_description_config = xacro.process_file(xacro_file) + + jsp_arg = DeclareLaunchArgument( + 'use_joint_state_publisher', + default_value='True' + ) + + # Create a robot_state_publisher node + params = {'robot_description': robot_description_config.toxml(), 'use_sim_time': use_sim_time} + + robot_state_publisher_node = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher_node', + emulate_tty=True, + output='screen', + parameters=[params] + ) + + # Joint State Publisher + joint_state_publisher_node = Node( + package='joint_state_publisher', + executable='joint_state_publisher', + output='screen', + condition=IfCondition(use_joint_state_publisher) + ) + + # RVIZ Configuration + rviz_config_dir = os.path.join( + get_package_share_directory(package_description), + 'launch', + 'check_joint.rviz' + ) + + rviz_node = Node( + package='rviz2', + executable='rviz2', + output='screen', + name='rviz_node', + parameters=[{'use_sim_time': True}], + arguments=['-d', rviz_config_dir] + ) + + return LaunchDescription([ + DeclareLaunchArgument( + 'use_sim_time', + default_value='false', + description='Use sim time if true'), + + jsp_arg, + + # map_publisher_node, + robot_state_publisher_node, + joint_state_publisher_node, + rviz_node + + ]) \ No newline at end of file diff --git a/src/robots/a1_description/launch/check_joint.rviz b/src/robots/a1_description/launch/check_joint.rviz index f0f5209..7545fb4 100644 --- a/src/robots/a1_description/launch/check_joint.rviz +++ b/src/robots/a1_description/launch/check_joint.rviz @@ -1,38 +1,33 @@ Panels: - - Class: rviz/Displays + - Class: rviz_common/Displays Help Height: 78 Name: Displays Property Tree Widget: Expanded: - /Global Options1 + - /Status1 - /RobotModel1 Splitter Ratio: 0.5 - Tree Height: 420 - - Class: rviz/Selection + Tree Height: 617 + - Class: rviz_common/Selection Name: Selection - - Class: rviz/Tool Properties + - Class: rviz_common/Tool Properties Expanded: - - /2D Pose Estimate1 - - /2D Nav Goal1 + - /2D Goal Pose1 - /Publish Point1 Name: Tool Properties Splitter Ratio: 0.5886790156364441 - - Class: rviz/Views + - Class: rviz_common/Views Expanded: - /Current View1 Name: Views Splitter Ratio: 0.5 - - Class: rviz/Time - Experimental: false - Name: Time - SyncMode: 0 - SyncSource: "" Visualization Manager: Class: "" Displays: - Alpha: 0.5 Cell Size: 1 - Class: rviz/Grid + Class: rviz_default_plugins/Grid Color: 160; 160; 164 Enabled: true Line Style: @@ -49,8 +44,16 @@ Visualization Manager: Reference Frame: Value: true - Alpha: 1 - Class: rviz/RobotModel + Class: rviz_default_plugins/RobotModel Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description Enabled: true Links: All Links Enabled: true @@ -174,92 +177,86 @@ Visualization Manager: Show Trail: false Value: true Name: RobotModel - Robot Description: robot_description TF Prefix: "" Update Interval: 0 Value: true Visual Enabled: true - - Class: rviz/Axes - Enabled: false - Length: 1 - Name: Axes - Radius: 0.10000000149011612 - Reference Frame: - Value: false - - Class: rviz/TF - Enabled: false - Frame Timeout: 15 - Frames: - All Enabled: true - Marker Scale: 1 - Name: TF - Show Arrows: true - Show Axes: true - Show Names: true - Tree: - {} - Update Interval: 0 - Value: false Enabled: true Global Options: - Background Color: 238; 238; 238 - Default Light: true + Background Color: 48; 48; 48 Fixed Frame: base Frame Rate: 30 Name: root Tools: - - Class: rviz/Interact + - Class: rviz_default_plugins/Interact Hide Inactive Objects: true - - Class: rviz/MoveCamera - - Class: rviz/Select - - Class: rviz/FocusCamera - - Class: rviz/Measure - - Class: rviz/SetInitialPose - Topic: /initialpose - - Class: rviz/SetGoal - Topic: /move_base_simple/goal - - Class: rviz/PublishPoint + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint Single click: true - Topic: /clicked_point + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF Value: true Views: Current: - Class: rviz/Orbit - Distance: 1.0307118892669678 + Class: rviz_default_plugins/Orbit + Distance: 1.9769524335861206 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: 0.0760490670800209 - Y: 0.11421932280063629 - Z: -0.1576911211013794 - Focal Shape Fixed Size: false + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true Focal Shape Size: 0.05000000074505806 Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 1.0047969818115234 + Pitch: 0.21039816737174988 Target Frame: Value: Orbit (rviz) - Yaw: 4.558584690093994 + Yaw: 0.9653980731964111 Saved: ~ Window Geometry: Displays: collapsed: false - Height: 627 + Height: 846 Hide Left Dock: false Hide Right Dock: false - QMainWindow State: 000000ff00000000fd00000004000000000000016a0000022ffc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000270000022f000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006101000001be000001900000000000000000000000010000010f000002e2fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000028000002e2000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000006400000003efc0100000002fb0000000800540069006d0065000000000000000640000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000002e40000022f00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd000000040000000000000156000002f4fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002f4000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002f4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002f4000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d006501000000000000045000000000000000000000023f000002f400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false - Time: - collapsed: false Tool Properties: collapsed: false Views: collapsed: false - Width: 1108 - X: 812 - Y: 241 + Width: 1200 + X: 617 + Y: 102 diff --git a/src/robots/a1_description/launch/group_gazebo.launch.py b/src/robots/a1_description/launch/group_gazebo.launch.py new file mode 100644 index 0000000..d77031b --- /dev/null +++ b/src/robots/a1_description/launch/group_gazebo.launch.py @@ -0,0 +1,59 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription, RegisterEventHandler +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch_ros.actions import Node +from launch.event_handlers import OnProcessExit +import xacro + +def generate_launch_description(): + package_name = 'a1_description' + package_path = os.path.join(get_package_share_directory(package_name)) + + xacro_file = os.path.join(package_path, 'xacro', 'robot.xacro') + robot_description = xacro.process_file(xacro_file).toxml() + + robot_state_publisher_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + name='robot_state_publisher', + output="screen", + parameters=[{"robot_description": robot_description}], + ) + + gazebo = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory('gazebo_ros'), 'launch', 'gazebo.launch.py') + ), + launch_arguments={'verbose': 'true'}.items() + ) + + spawn_entity = Node( + package='gazebo_ros', + executable='spawn_entity.py', + arguments=['-topic', '/robot_description', '-entity', 'a1_gazebo'], + output='screen', + ) + + joint_state_broadcaster_node = Node( + package="controller_manager", + executable="spawner.py", + arguments=["joint_state_broadcaster"], + output='screen', + ) + + robot_joint_controller_node = Node( + package="controller_manager", + executable="spawner.py", + arguments=["robot_joint_controller"], + output='screen', + ) + + return LaunchDescription([ + robot_state_publisher_node, + gazebo, + spawn_entity, + joint_state_broadcaster_node, + robot_joint_controller_node, + ]) diff --git a/src/robots/a1_description/launch/single_gazebo.launch.py b/src/robots/a1_description/launch/single_gazebo.launch.py new file mode 100644 index 0000000..ff847f7 --- /dev/null +++ b/src/robots/a1_description/launch/single_gazebo.launch.py @@ -0,0 +1,59 @@ +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription, RegisterEventHandler +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch_ros.actions import Node +from launch.event_handlers import OnProcessExit +import xacro + +def generate_launch_description(): + package_name = 'a1_description' + package_path = os.path.join(get_package_share_directory(package_name)) + + xacro_file = os.path.join(package_path, 'xacro', 'robot.xacro') + robot_description = xacro.process_file(xacro_file).toxml() + + robot_state_publisher_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + name='robot_state_publisher', + output="screen", + parameters=[{"robot_description": robot_description}], + ) + + gazebo = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory('gazebo_ros'), 'launch', 'gazebo.launch.py') + ), + launch_arguments={'verbose': 'true'}.items() + ) + + spawn_entity = Node( + package='gazebo_ros', + executable='spawn_entity.py', + arguments=['-topic', '/robot_description', '-entity', 'a1_gazebo'], + output='screen', + ) + + controller_names = [ + "joint_state_broadcaster", + "FL_hip_controller", "FL_thigh_controller", "FL_calf_controller", + "FR_hip_controller", "FR_thigh_controller", "FR_calf_controller", + "RL_hip_controller", "RL_thigh_controller", "RL_calf_controller", + "RR_hip_controller", "RR_thigh_controller", "RR_calf_controller" + ] + + controller_nodes = [Node( + package="controller_manager", + executable="spawner.py", + arguments=[name], + output='screen', + ) for name in controller_names] + + return LaunchDescription([ + robot_state_publisher_node, + gazebo, + spawn_entity, + *controller_nodes, + ]) diff --git a/src/robots/a1_description/package.xml b/src/robots/a1_description/package.xml index 6796895..57ccc47 100644 --- a/src/robots/a1_description/package.xml +++ b/src/robots/a1_description/package.xml @@ -1,14 +1,22 @@ - - a1_description - 0.0.0 - The a1_description package + + a1_description + 2.0.0 + TODO: Package description + Ziqi Fan + Apache-2.0 - unitree - TODO + ament_cmake - catkin - roscpp - std_msgs + urdf + xacro + robot_state_publisher + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/src/robots/a1_description/urdf/a1.urdf b/src/robots/a1_description/urdf/a1.urdf index e133ab4..376481b 100644 --- a/src/robots/a1_description/urdf/a1.urdf +++ b/src/robots/a1_description/urdf/a1.urdf @@ -44,12 +44,20 @@ - + + + + gazebo_ros2_control/GazeboSystem + robot_description + robot_state_publisher_node + $(find a1_description)/config/robot_control.yaml + + diff --git a/src/robots/a1_description/xacro/gazebo.xacro b/src/robots/a1_description/xacro/gazebo.xacro index 7248a42..e03ed0b 100644 --- a/src/robots/a1_description/xacro/gazebo.xacro +++ b/src/robots/a1_description/xacro/gazebo.xacro @@ -1,15 +1,7 @@ - - - - /a1_gazebo - gazebo_ros_control/DefaultRobotHWSim - - - - + - + - true - - true - 1000 - true - __default_topic__ - - trunk_imu - imu_link - 1000.0 - 0.0 - 0 0 0 - 0 0 0 - imu_link - - 0 0 0 0 0 0 - + + + + / + ~/out:=imu + + false + + true + 100 + true + + + + + 0.0 + 2e-4 + 0.0000075 + 0.0000008 + + + + + 0.0 + 2e-4 + 0.0000075 + 0.0000008 + + + + + 0.0 + 2e-4 + 0.0000075 + 0.0000008 + + + + + + + 0.0 + 1.7e-2 + 0.1 + 0.001 + + + + + 0.0 + 1.7e-2 + 0.1 + 0.001 + + + + + 0.0 + 1.7e-2 + 0.1 + 0.001 + + + + + diff --git a/src/robots/a1_description/xacro/robot.xacro b/src/robots/a1_description/xacro/robot.xacro old mode 100644 new mode 100755 index d106404..ce1200d --- a/src/robots/a1_description/xacro/robot.xacro +++ b/src/robots/a1_description/xacro/robot.xacro @@ -9,6 +9,7 @@ + @@ -24,7 +25,7 @@ - + @@ -61,7 +62,7 @@ + izz="${trunk_izz}"/> @@ -91,10 +92,10 @@ + izz="${stick_mass / 12.0 * (3*stick_radius*stick_radius + stick_length*stick_length)}"/> - + diff --git a/src/robots/a1_description/xacro/ros2_control.xacro b/src/robots/a1_description/xacro/ros2_control.xacro new file mode 100644 index 0000000..fef4141 --- /dev/null +++ b/src/robots/a1_description/xacro/ros2_control.xacro @@ -0,0 +1,137 @@ + + + + + + gazebo_ros2_control/GazeboSystem + + + + + -${hip_torque_max} + ${hip_torque_max} + + + + + + + + + -${hip_torque_max} + ${hip_torque_max} + + + + + + + + + -${hip_torque_max} + ${hip_torque_max} + + + + + + + + + -${hip_torque_max} + ${hip_torque_max} + + + + + + + + + -${thigh_torque_max} + ${thigh_torque_max} + + + + + + + + + -${thigh_torque_max} + ${thigh_torque_max} + + + + + + + + + -${thigh_torque_max} + ${thigh_torque_max} + + + + + + + + + -${thigh_torque_max} + ${thigh_torque_max} + + + + + + + + + -${calf_torque_max} + ${calf_torque_max} + + + + + + + + + -${calf_torque_max} + ${calf_torque_max} + + + + + + + + + -${calf_torque_max} + ${calf_torque_max} + + + + + + + + + -${calf_torque_max} + ${calf_torque_max} + + + + + + + + + + + $(find a1_description)/config/robot_control_group.yaml + + + + \ No newline at end of file diff --git a/src/robots/go2_description/CMakeLists.txt b/src/robots/go2_description/CMakeLists.txt index a0cad9a..2bdafb9 100644 --- a/src/robots/go2_description/CMakeLists.txt +++ b/src/robots/go2_description/CMakeLists.txt @@ -1,14 +1,22 @@ -cmake_minimum_required(VERSION 2.8.3) - +cmake_minimum_required(VERSION 3.8) project(go2_description) -find_package(catkin REQUIRED) +find_package(ament_cmake REQUIRED) +find_package(ament_lint_auto REQUIRED) +find_package(urdf REQUIRED) +find_package(xacro REQUIRED) +find_package(robot_state_publisher REQUIRED) -catkin_package() +install( + DIRECTORY + config + launch + meshes + urdf + xacro -find_package(roslaunch) + DESTINATION + share/${PROJECT_NAME}/ +) -foreach(dir config launch meshes urdf) - install(DIRECTORY ${dir}/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir}) -endforeach(dir) +ament_package() diff --git a/src/robots/go2_description/config/robot_control.yaml b/src/robots/go2_description/config/robot_control.yaml old mode 100755 new mode 100644 index 2991707..6675ec8 --- a/src/robots/go2_description/config/robot_control.yaml +++ b/src/robots/go2_description/config/robot_control.yaml @@ -1,70 +1,113 @@ -go2_gazebo: - # Publish all joint states ----------------------------------- - joint_state_controller: - type: joint_state_controller/JointStateController - publish_rate: 1000 +controller_manager: + ros__parameters: + update_rate: 1000 # Hz + # use_sim_time: true # If running in simulation - # FL Controllers --------------------------------------- - FL_hip_controller: - type: robot_joint_controller/RobotJointController + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + + imu_sensor_broadcaster: + type: imu_sensor_broadcaster/ImuSensorBroadcaster + + # FL Controllers --------------------------------------- + FL_hip_controller: + type: robot_joint_controller/RobotJointController + FL_thigh_controller: + type: robot_joint_controller/RobotJointController + FL_calf_controller: + type: robot_joint_controller/RobotJointController + + # FR Controllers --------------------------------------- + FR_hip_controller: + type: robot_joint_controller/RobotJointController + FR_thigh_controller: + type: robot_joint_controller/RobotJointController + FR_calf_controller: + type: robot_joint_controller/RobotJointController + + # RL Controllers --------------------------------------- + RL_hip_controller: + type: robot_joint_controller/RobotJointController + RL_thigh_controller: + type: robot_joint_controller/RobotJointController + RL_calf_controller: + type: robot_joint_controller/RobotJointController + + # RR Controllers --------------------------------------- + RR_hip_controller: + type: robot_joint_controller/RobotJointController + RR_thigh_controller: + type: robot_joint_controller/RobotJointController + RR_calf_controller: + type: robot_joint_controller/RobotJointController + + +# FL Controllers --------------------------------------- +FL_hip_controller: + ros__parameters: joint: FL_hip_joint pid: {p: 100.0, i: 0.0, d: 5.0} - FL_thigh_controller: - type: robot_joint_controller/RobotJointController +FL_thigh_controller: + ros__parameters: joint: FL_thigh_joint pid: {p: 300.0, i: 0.0, d: 8.0} - FL_calf_controller: - type: robot_joint_controller/RobotJointController +FL_calf_controller: + ros__parameters: joint: FL_calf_joint pid: {p: 300.0, i: 0.0, d: 8.0} - # FR Controllers --------------------------------------- - FR_hip_controller: - type: robot_joint_controller/RobotJointController +# FR Controllers --------------------------------------- +FR_hip_controller: + ros__parameters: joint: FR_hip_joint pid: {p: 100.0, i: 0.0, d: 5.0} - FR_thigh_controller: - type: robot_joint_controller/RobotJointController +FR_thigh_controller: + ros__parameters: joint: FR_thigh_joint pid: {p: 300.0, i: 0.0, d: 8.0} - FR_calf_controller: - type: robot_joint_controller/RobotJointController +FR_calf_controller: + ros__parameters: joint: FR_calf_joint pid: {p: 300.0, i: 0.0, d: 8.0} - # RL Controllers --------------------------------------- - RL_hip_controller: - type: robot_joint_controller/RobotJointController +# RL Controllers --------------------------------------- +RL_hip_controller: + ros__parameters: joint: RL_hip_joint pid: {p: 100.0, i: 0.0, d: 5.0} - RL_thigh_controller: - type: robot_joint_controller/RobotJointController +RL_thigh_controller: + ros__parameters: joint: RL_thigh_joint pid: {p: 300.0, i: 0.0, d: 8.0} - RL_calf_controller: - type: robot_joint_controller/RobotJointController +RL_calf_controller: + ros__parameters: joint: RL_calf_joint pid: {p: 300.0, i: 0.0, d: 8.0} - # RR Controllers --------------------------------------- - RR_hip_controller: - type: robot_joint_controller/RobotJointController +# RR Controllers --------------------------------------- +RR_hip_controller: + ros__parameters: joint: RR_hip_joint pid: {p: 100.0, i: 0.0, d: 5.0} - RR_thigh_controller: - type: robot_joint_controller/RobotJointController +RR_thigh_controller: + ros__parameters: joint: RR_thigh_joint pid: {p: 300.0, i: 0.0, d: 8.0} - RR_calf_controller: - type: robot_joint_controller/RobotJointController +RR_calf_controller: + ros__parameters: joint: RR_calf_joint pid: {p: 300.0, i: 0.0, d: 8.0} +imu_sensor_broadcaster: + ros__parameters: + sensor_name: "imu_sensor" + frame_id: imu_link + diff --git a/src/robots/go2_description/package.xml b/src/robots/go2_description/package.xml index ba52e13..cab7ce4 100644 --- a/src/robots/go2_description/package.xml +++ b/src/robots/go2_description/package.xml @@ -1,21 +1,22 @@ - + + go2_description - 1.0.0 - -

URDF Description package for go2_description

-

This package contains configuration data, 3D models and launch files -for go2_description robot

-
- TODO - - BSD - catkin - roslaunch + 2.0.0 + TODO: Package description + Ziqi Fan + Apache-2.0 + + ament_cmake + + urdf + xacro robot_state_publisher - rviz - joint_state_publisher_gui - gazebo + + ament_lint_auto + ament_lint_common + - + ament_cmake + -
\ No newline at end of file +
diff --git a/src/robots/go2_description/xacro/gazebo.xacro b/src/robots/go2_description/xacro/gazebo.xacro index f449f44..bf9d63a 100644 --- a/src/robots/go2_description/xacro/gazebo.xacro +++ b/src/robots/go2_description/xacro/gazebo.xacro @@ -1,13 +1,5 @@ - - - - /go2_gazebo - gazebo_ros_control/DefaultRobotHWSim - - - - + - + - true - - true - 1000 - true - __default_topic__ - - trunk_imu - imu_link - 1000.0 - 0.0 - 0 0 0 - 0 0 0 - imu_link - - 0 0 0 0 0 0 - + + + + / + ~/out:=imu + + false + + true + 100 + true + + + + + 0.0 + 2e-4 + 0.0000075 + 0.0000008 + + + + + 0.0 + 2e-4 + 0.0000075 + 0.0000008 + + + + + 0.0 + 2e-4 + 0.0000075 + 0.0000008 + + + + + + + 0.0 + 1.7e-2 + 0.1 + 0.001 + + + + + 0.0 + 1.7e-2 + 0.1 + 0.001 + + + + + 0.0 + 1.7e-2 + 0.1 + 0.001 + + + + + - - - - - - - + - + false diff --git a/src/robots/go2_description/xacro/robot.xacro b/src/robots/go2_description/xacro/robot.xacro index c03da97..a897dac 100755 --- a/src/robots/go2_description/xacro/robot.xacro +++ b/src/robots/go2_description/xacro/robot.xacro @@ -9,6 +9,7 @@ + @@ -24,7 +25,7 @@
- + @@ -61,7 +62,7 @@ + izz="${trunk_izz}"/> diff --git a/src/robots/go2_description/xacro/ros2_control.xacro b/src/robots/go2_description/xacro/ros2_control.xacro new file mode 100644 index 0000000..21232aa --- /dev/null +++ b/src/robots/go2_description/xacro/ros2_control.xacro @@ -0,0 +1,137 @@ + + + + + + gazebo_ros2_control/GazeboSystem + + + + + -${hip_torque_max} + ${hip_torque_max} + + + + + + + + + -${hip_torque_max} + ${hip_torque_max} + + + + + + + + + -${hip_torque_max} + ${hip_torque_max} + + + + + + + + + -${hip_torque_max} + ${hip_torque_max} + + + + + + + + + -${thigh_torque_max} + ${thigh_torque_max} + + + + + + + + + -${thigh_torque_max} + ${thigh_torque_max} + + + + + + + + + -${thigh_torque_max} + ${thigh_torque_max} + + + + + + + + + -${thigh_torque_max} + ${thigh_torque_max} + + + + + + + + + -${calf_torque_max} + ${calf_torque_max} + + + + + + + + + -${calf_torque_max} + ${calf_torque_max} + + + + + + + + + -${calf_torque_max} + ${calf_torque_max} + + + + + + + + + -${calf_torque_max} + ${calf_torque_max} + + + + + + + + + + + $(find go2_description)/config/robot_control_group.yaml + + + + \ No newline at end of file diff --git a/src/robots/gr1t1_description/CMakeLists.txt b/src/robots/gr1t1_description/CMakeLists.txt deleted file mode 100644 index d2927b2..0000000 --- a/src/robots/gr1t1_description/CMakeLists.txt +++ /dev/null @@ -1,14 +0,0 @@ -cmake_minimum_required(VERSION 3.0) - -project(gr1t1_description) - -find_package(catkin REQUIRED) - -catkin_package() - -find_package(roslaunch) - -foreach(dir config launch meshes urdf) - install(DIRECTORY ${dir}/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir}) -endforeach(dir) diff --git a/src/robots/gr1t1_description/config/robot_control.yaml b/src/robots/gr1t1_description/config/robot_control.yaml deleted file mode 100644 index d622661..0000000 --- a/src/robots/gr1t1_description/config/robot_control.yaml +++ /dev/null @@ -1,57 +0,0 @@ -gr1t1_gazebo: - # Publish all joint states ----------------------------------- - joint_state_controller: - type: joint_state_controller/JointStateController - publish_rate: 1000 - - # left leg Controllers --------------------------------------- - l_hip_roll_controller: - type: robot_joint_controller/RobotJointController - joint: l_hip_roll - pid: {p: 57.0, i: 0.0, d: 5.7} - - l_hip_yaw_controller: - type: robot_joint_controller/RobotJointController - joint: l_hip_yaw - pid: {p: 43.0, i: 0.0, d: 4.3} - - l_hip_pitch_controller: - type: robot_joint_controller/RobotJointController - joint: l_hip_pitch - pid: {p: 114.0, i: 0.0, d: 11.4} - - l_knee_pitch_controller: - type: robot_joint_controller/RobotJointController - joint: l_knee_pitch - pid: {p: 114.0, i: 0.0, d: 11.4} - - l_ankle_pitch_controller: - type: robot_joint_controller/RobotJointController - joint: l_ankle_pitch - pid: {p: 15.3, i: 0.0, d: 1.5} - - # right leg Controllers --------------------------------------- - r_hip_roll_controller: - type: robot_joint_controller/RobotJointController - joint: r_hip_roll - pid: {p: 57.0, i: 0.0, d: 5.7} - - r_hip_yaw_controller: - type: robot_joint_controller/RobotJointController - joint: r_hip_yaw - pid: {p: 43.0, i: 0.0, d: 4.3} - - r_hip_pitch_controller: - type: robot_joint_controller/RobotJointController - joint: r_hip_pitch - pid: {p: 114.0, i: 0.0, d: 11.4} - - r_knee_pitch_controller: - type: robot_joint_controller/RobotJointController - joint: r_knee_pitch - pid: {p: 114.0, i: 0.0, d: 11.4} - - r_ankle_pitch_controller: - type: robot_joint_controller/RobotJointController - joint: r_ankle_pitch - pid: {p: 15.3, i: 0.0, d: 1.5} diff --git a/src/robots/gr1t1_description/launch/display.launch b/src/robots/gr1t1_description/launch/display.launch deleted file mode 100644 index d4cc4fb..0000000 --- a/src/robots/gr1t1_description/launch/display.launch +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - \ No newline at end of file diff --git a/src/robots/gr1t1_description/launch/gazebo.launch b/src/robots/gr1t1_description/launch/gazebo.launch deleted file mode 100644 index ba67d26..0000000 --- a/src/robots/gr1t1_description/launch/gazebo.launch +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - \ No newline at end of file diff --git a/src/robots/gr1t1_description/meshes/base.STL b/src/robots/gr1t1_description/meshes/base.STL deleted file mode 100644 index fd2f20aad2e1ac4bfa555f3fa3a2f2a089c9e8d1..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 853534 zcmb?^S6mf47jFa+6s#yJcI*umg^ldVj0GDY_U;kI-T<*n*$OI(y<sHmujde?xQZ-sLo?!)D2|Cse(J;_QY$+Vw3b^PRjJ|jo_jVAv;{tk5@ zI|sjQhwZ1c_1jr+#AjA{`a!yF;SNT~xwPYo zS;NU{WF!$W;@SO=?5;7I9-qF4LldGdZ>2hUR*}+vUsg1}6)MHjk`K4D+511T4yO*& zoB_Mpbod>1{}4@FyANd0Ih*Oj4hD7flckA|tt+tg7rj{5d+w&S@cTiU7i*!rFH5o3 ztU?bjRz6mh2}$nWR^69qEk)J1#mT^Yv9^RH(P*hJ>72>#4N9V+$YVY=2EYsLR#WHX_uslKyvt!T4xBl&I#F}6km=ht-u2vGwz6Pt~qeQy)_Aa@2ygOUprKOxY$yzw^q79qA zY=dl<<0_D7NwRg0|QW9A}IsDbU?H%f;hg~T+uvTX|@l;XhPnHbvr&45PboGsmzC4C|bVW zfPCc^O4U^{^uUZ|MG&WwEyT$55cS&C$i#6Y&DmsEPgbo`X&HN( z_wImF^Aa?zG#S`e*xFlQ`Sj;8^aNP~mhbKAm5&%w#Bz+loCx_@{n+t9kTDhzIOA}> zHUckfYha{X{C+}~OmFis-@EQb5SVJqICDi_8c%Cgs}EYG|FOL0^2kKolVQuTM+h-% z{rq?UXf?Zt<=DH}>x5j5yOfVuSOkIngVE3eYZX_Le1g>!|GO0Hi|uG~&RjA7>lj^b z6u^#}CoRMXh~UO&d<1cigY6@vx_yTDhK^Q~n^YGuFDwJ+8zDi=^Z%NO7{Obf5gDpx zyWe6r+D{O01mFDp$i~k;MmL*$8E!X(ymInacUMhNS{#Yx5Z#|^Zlo6fZv0QouG2n@(lZskiRcg5p61mNKIF*m%prY6g+KP(@Q0- zgy=7x!v5N==vC@ux^ZBnJb!$9`fyeo6Csm+8l>IV%F5Mu?Qz30FyBCsx1!rMTBcGz zh&kkmboX1?L-Q>HhGEG&&lI%amndT31pz$ZdlD@gVaeEX~ms%!-B^Ah+_-Xg?9-$-u zBV+ZgoAg$(7)~A`es{feXL}UL7(L%Z?tHBpbxY=DVA%ySuJlozvw~axM~3I=^Yrqt z1Nkxv( z%os-Vi0~_3x}JaRSowRU+_?S^Veoa{4s2h6Rx_&oaDFbk>*j%sR!$#iy&l#K%j0Ee znYeo8o7THiy>-EW*j}87ZwJ+57|kONr+ewl1{QetXT2Y?W3_F<@oZiztSuoGoF34; zzCYQuuwWGO|k;0Lv$3;)DC&9gz9N5wrk8JI6_|Ah1(Izwu9Wua*55=n7kENj7R+LcZudXKNj|H2~}}cV~=7_6JmR6jWB-731<6}M~vTO>C{hGlBUiw zOTuVEx>oy(IfP7AK6RQUU4#)}#oQcfwkV2)LzP)Q;X8eDVgsikAycd;39I@SSC(B5 z;k3eS8_Of)a(qjs_N=eW8xt&H%dtG{1wt;s77B-7tG`|EI^zB#2r9jz8H;df+{2LGh0*Vi(<2Hn2M=t4K!2Ojh{3mI*^k`$Wlqi zQhL>wtxX0FF%F_xL&>EB<^(c~CM4mumo9x!L5s?3Q-}2_^;+MsLU_``QB_&%E@OoG z#ln-kmQ`lHC$73ZuMrOIWAWSB(wN}oY`8^lE)#L~@iJPbdFg)qX|#L;f6<5a+OfCc-`KpR zKWL4$W1xKu9(yuDtEnj8@9yNcIFJn~^8K$~sie|?r zumj5@WLD_C{5o+NAaEar5m;M7-bB92ugLlX0(%$xCm!S(qJPlU6-R@wdao*%pw-lC z0D&#U2+WC)YWux(>;G7et;JrzIYvmvB`@8*o&}lsVUG=KUw)r3`D0iTM)Qd1z`04| z9|fz)Gi!;s)#B;}N0yMsugVDjtPfEqzOv?GjuANigm||uBNl%$N1c7TJZCwky0$rs zZTgx^bM0qD>DN7oqv;#FR+ct8+o?Dnt{~_wLnyXLmSKIL7n z#+IA+eBpwqaX7X03PRI-RF##F5pk~it`Gic|@PFH-*TNRa7ymyNb2Knrw$&LaT6o zdRv25_KJgUesWE<<;|`f0#o6thLCRl?Q|vGR3&isWEDTbh?GX3SO$Ggvpvi~M%r(4 zA*E!Z67`QChrm?0)*@u*c9e>B9|Tc5X!C-ag_&7eyH8E#w8EO;UIO}(G37;dO90#XC0JeR_*C|r z86`ZwZkANkrouiL+WE%fdh^G3sm+2=6-)no^9Sn%b#!jeJo!{+F-2;YMs=mlARb?X z%S%57j~6G5@!$}c3eWUl4Ir?FXox<}Jl_X#wJ6q*x1-71yUx%CC23ws14JL|v_ahCXszpOxqWg(kAnJPN9Qqe zUVCj+D>2(k*Wl0W4kNVwypRg_cChZVSk1S*QxVIxHLF5vL$ix1!O3y7RK`-U{8))D zbosmxDRjF9=POKwYhOYRR_UVLaGNdZW4Y5MvchWTOy=0wP^%TG-%>q4Z=);3DD#l@7N zHBQjs!DZQ$TIPzXPomDBe#$lCvl!W6qQM4j?X~6eCN8k5CiN*2bF2xDKOxs)bnfsc zf|b25%Dt-)HfU6MlGZ1l+K?$%8xo#`qe)2dhhDmJf5s@B85qqY-XFY~A3<1E<1!Ij zi!~%9AfSS{O}C%s1_i4)OK|pK*|7FX!%ZKihe%&9msRju5B3}HE8pjN&ae(A%>%74 zLR&Ahjxy4|S@ju46Y?@ar;VJF2Ow~J##9(h$oHI*Y}=d==}(xem@wVkDeu5GFs==IRUb@47Y9HKFV>_@HpiX>0i1r?6CtXbTmT>RG zWr^1(R_pCi`a{|V{Z;Ra&FL728dBNI-8jS>M8&U0?N0X6o$FHIU945t&8L%cUfQs? zBZ|i3_1bMhkI}_MkLMxkpqWu}2#nCvc9`G~^R)2698?AyI3w06ydZ04yP)^7PznmS(7%6FP9^uChFoSuZ{BMNz81YU=Q zG3rBaI{8A9;`?*5gl7<#Z~sc4*gUr^TIX6c$fz4=Mvq0MD4nNF;ktX^#hUOkZancaCWfv^)K=H949u6$65n+f*}z4O#BApvwRl)IJ5cH^U9dHQ zxx+|3eCQi`yPT0N+?>tc-FiuF>lwjUdYDJe_%k=aBMat>#+JIz1sZ*b4dBYuCKmLd-q5JUyV&~%sxGMsI1Hz%^|Qn zj3#79owY2tu|aYwXG^>Fx||fU%$epcTccmR-cgQ$Hyax+xa&2WBDy%y`8})!LOPnY zQf^qylv2xhD0!5r>9%ch>90CKm!#ALT2>GVDR#F55C98Q{k-8Z2LF zCjSfwQ9W9eQ<`a7h1rN-+&ZwAV2Asq(xR)w7>3bMh5xFe2$e$AN8alN{64C|_0~ew zxlS~=#t=PzHwF7L`b3EXy7YUp^LL6Vz6qTN%RkyA;IYbu3 zV~0;kaoeMY45JANT#+ayjIXW^@oS_02C8{hzv+y;uktXEG3?8C+G<6X+#c-9sB9rV z4JiW=tlr}vn&*(KxUK(-Ls)El%}UkCrX8-{;n1)z<9Zrx*lL~Pux6@i1yoV*p3s8< z=VhzsS*#AUl?D!1WQ-*8{FOMB8_dEBKLv+m)U)p-mpInm421ilDxOh zQt?xp861Mt{mFXGJxv|oUEt7!*zKCnzK&bM>>h-2c3{5i9P(J1FHdObV@*bnCcWsz zgk1U55`%=bimi~%>Y1ITe#O#dERT?B6OV|g4gpf;ur(%}4c*9kK_1qKMx?vzUshcw zjPPwl>pE?Qx0YG9yTy9r1Es;muL?MqFamRebZe>ZBYTIIfDzan?go|`MNpO7&dO2p9KTL{y#q|=LCbjds|OImvPvsv4QN*jI= z4uPqf1LDqq#lxk zf}dbSHIT94-73m)s+9RvY+*KBig(tXNUXR~ zczUQIHH)*AvEO)KS&g$4Px~he9bs)0^IZb1_HJYv%^R0gL`I9-#gxduqf8yLV2+M7 z!Q(4N!=8yd24RL!QZ(-45nI6Ww~sRE(?Ll^M(3gX-kRd4ony+`P;MN=GB6t60t|Q~ z4(vHniu|}xz^!v$oeM(R<*GClMrZ61=y$)|7Sm6560dmsa(46toA$NOq~1?WjF)kz zW-Y1no2ruMG9uwzstP^zr4v!K%KMe9+o;#Pjq|%7ev4BWO=}9wEWyQ2Mqo3i>!LwEQoIX?)e6_&>%b~_IiC)AiDou7S4-)8(EVNLCp^hdIbY+*%& ztX9r+{y!V!tj)>#d5Q~-vX-D1E%j-dfE?z@uFupI}63kTE`TKYbAMH^?YA zsju|g=ezhLY>9%OU<6)mA>`28i((bCG1Ar3t_p5zcyt~yuan@>wH2My_7UV2%z)K# z-*VeH1a&mx9tUe^1zJT;+E3pt)Ybs(pBbd}?(-FC;fo0{iR35S}mUafti+D zi+MBFv8)UCS=$yi;@=(Dut)H_v2O|SK^v`azq96;9M(NRdeZc;f)V8aoun%xj{3Ba zLqngqELTiy=c9Vu`OW!CtFJ1gS7mov-{<@WE09+{3s<_%kXAj6R50IPpoveVvSRM& zkRmerm%S%XYZW35KU$GPY;pU*iVZF+4(jaBFd9~!m0H4q{RXN35O0R5EHBZ=0u3nJweuY{7d@1gGg8_34G-kX(e_hRT$O~)=SEp(JME4NdE0ANtntJ z>^R!WLOeRvvIt^t=@aq?uXa+$Cyh8nD)_2JfVmi9Bn+dqeKIYDX2Ff68JUuVsak8k zax5nPj>wjIM9YwivhURjQp;_`}fiNnVm73d<*{=EEa|n6@*7gM*qgA$^;S z5ttM7)Pq0CzE+pTHRcmIt!{v?PL+I1CuE+Mv4*f(8^2ii@vEiSvU;$DsWJiaJNgby z+?iMev2*3(#HZ`qi6MSL5~h;CyVv&Jp?Cj-Sa4&pXqY`iZMfkScOC=V#M|L=`<%{0 zZo&4Z7&sXjpw+`(m#EphBpJ(t-MDue&}Y$U>{vvogsCWKl`;AZ-BLB`l{BqqXazmWiMMNJbciQnK_RxG7g@r^i!DZ zZK1v$H(0`aoj|K-vY#fl`%y$jRK|7LTdJu#*6PL~&VuDr`s}7(ok}o_hTS{Gnh76v zIjJQE=_E|m3}kfeyMwx|wJCy#%_zYZ<@QuBZnxzSIwACg zuf8VM5~ivFG8!hWqX{!w7C|hTvsaGw@K<~9Ixb?wL9k=;>{T@RcUOkdFk{IcEFQ9* zqrUyRNq=tKAYpZ_mh9k6Hq6;nL`t(=eVq7G;F7D4oFnNHt!3Q<4z&ZHZPE zS)<2(<9#)(SRS408my|PKG7W#bRU|M4&mF&<>}K9fWzY&9~BhL!Dvm%@|kCS|OnpNgqYB|l(4>YbsV8=8tB z7F8O-`hK562R1RNV}S4J(J!f)mx)~ht&+|@qG>5I>%QgzvlnmDw6R)+T&nJS)}lv< zI`3#K=PUdsuF`%xdFnK0Hm95725aHgw}tBBT(PM-laq08+dbAUJDcvcOyuMdVpH>* zxG2j+e(Vew+^08YjPuxaSW9Qy6Uafao=UbO&k{i%MR z#4>b*im7gbt-OM;-PttRd{*-LX_yJE@*@ zxQV-psqid?N0eP%m!;q9A@#0Ui9_Jo3r54~fibqU-;DC&d?AGMF3t>o9yQ=%Pib+@ zic;Q!9MiB>b?oV-`l-Ut@X>mV<`JVm zyk;xbMN@TJh&l@5+@JCbeX}mK}?0wgw)#OCtcB>5U+>SmkqKL zb!*T@7~kx^j4j9760)%5Qep7Iqe{k8e@+JGi`zUPCI_ka1Pj{cG=*9H|7u)Zk>eT_ z_KOBim-hOu5<5pV5O&;frm^84^(_v$>#>HsR;M;~P(3X!iC2D@adU%IIR7!=xS8m1 z#EfBigaj9(YEbMlW$26=T-ArqrQ%ABkQ$M}Qbb}yF=fUcQ`}JtI;f_N}Kzl>4Q0SYL_jcky_|pI&Y^-5_=SYd-Cg`c6Ok zjE*juIyZj$_|bZ-A+OahSofJRuW4(KVO5hfs`jpdreMeWGDcudglIC-|C-O5hQ8Bl zylO^#Gh?t;&?KbgUJB{`}5^5vs}VgA&}d0mD?da^ewM8{Dlwp%}dyZk@i)b-0AakVI}eR&yo-t||#TUe;JO=@%XF0ROVgrnOS>GAc4 z%KS6+g)4S7q@L* zhPJ-D@Idk7k+F@8xIf3eC?2&5srag+wDfd6)jzzx(EMz!aH6Uus~qgE#~Sil?aURV zz$4AnVZ*8=W&>hPWlLrQYi}5VIT4cDwUb)!%S-X>)Tbg|FTv|GxVM7}8D=ZL=Deg& z)=i|CYA5uGhKMqv<1Zh^BW&u`l!AM9Q-w9{6S;XU(va7x5TP%E!0U4s<*GA5IVaL7V{ueu5GBL^f!3 zZ>0DL`o)Kq3lsN-d&oVnSEB*1LS&5oe?wp@d|Db-w%yK)&Bjbr`%ashxE^-ke(h3@ zu6rFKV|o8~ME@cPOoh*q60+X1v=kNHPffAtlbG23qCB@Mp(Wmi$XFhaAX{sx4h_1h z70l))t_*xEthx18ICnZM>BszdA(~lHbMV4@`2XHJZv`{Z7Di5l*aB2rWGi}2<`I|^ zAs@D7EAf6K)G_@c6HVvm3eWf1(Z3*4SO(_ABZdOv-d;Pp)fkq9(L7?VZkrM?YpNRI zvNCb&&GN!BxfZnr85n^%K~I7Z4{wwg!cDbkpW|Uk7|kPwPAjQAfxQgnrmsrG2%MD| zO-LbPHz08KVFcy`^C(>d^~$&oQtP=*C~gyYC7o{{uKxt7Ju_UypueB%w~eSpr`@hB zpQs$3G}5syZSZ=6=~y;+;e8G2(9cmm|5=Nm-9G5sKi3oWEvFuD161d7CzyJa;t`lr zLABJI`L?XE-ovQzJz9FAe$R&x8Oy+&3J}k46(F=H<$q4l-~S$#uT>$MM_hdzq;Af1 zQQS(W88v+^hB*p{vkGKjL?I_QMfV3$!7|Ob6cG0ZISS6NAxjV%%Z6QHhy2ySFODfA z94aQR*=kEITPzozLi@l7%!x;g0>r0g%Z1FlVM!RxBfL_Es6O4zRliU%@#fOvwC&bp zq34?r86z+!LJAT7fQSY}{msdO{&H9nM)L^I^X=3azeZ{qlP`zBEfu5TY&am|0FmV| zl56J}fn~!RET~JO50#RBA85$E`N40R_)IJTJwwd~U8ONC+qr5zK(||OyuEih5rh>{HR#dA(x#vjY24%T+AnuX`0lI08E3i_x* z8CdqemP_@f+PP{L-rbZeSI~#&d$$nHBmTrg`e1umr$udDljU+|PKb=Fdv~s zYJaoka$wW&{46O%^N2s0DEhYUr^5)`Qn748+O(ab?(#V(cAQXF#;p@0FeixM8G~B0 zu??M5|GbPniq`{p?^<-*Nj+K_r0+>9OxoDjf3O1^^gBexCv8R=-@2_hQjguYo(B=E z9%)d|_v%A`Ip)fk?*yo1LgGKs7LSiJUdH>zO_c*;u(arb4bytdeo3{M|1W6gh%c5$ z$fEAg*xQkz(&%MNT(#cP$5e~8hO<2w%_IKw?Na~Ib6vF&AU4{LP5l`nV+7{(?`V*Z z(0cvEy>_hk@bLT*rx48}{)}o;(?+9QF+v;F3Nswb{&!T%M`)whEZK^E>=&Lt))pc# zCpZm=S`R2pyvV) z)g?YwZ1A-hx9)@MXdF$rZDGHK^vPqe^j^O>zp_v}m1C(8LChD+`?oHUB91R`)oPJK z1g63#BL1zGqz1Q^xoQOgAKXDZ&15@Evz$5SzjNs2l zbvV74u9yhx0LGQB7=fwy-0ggJhLr2PNK_l<>Mp^#_WR_u>Fn1K8K3$b0H;A`br>V> z`>yq(8sZxu{JnB@_z6bf^P_}3-7`kAYVbf@UZaWYNjQu8q|82f@Q)A~qj|&=Kv)A} z=kLZG0#os)8kK52q{_4Hq^N1VI0UA`84C9&0-_=y9G~`b#ZNE-pSvW)@T#R$v1D5* zWLY4Gz*IQL;6!fwGE&&hzN&c+HQ@>wSH<`SBDjO@Zf7OEVMq0sbxjqoGla%`XZ@DN zQM1fAhF9(h=>=MSuxhK`vT3H*?5MpdQ%HChB4c^HjFsP8NmI>T)rhH05-|c(;ZykV z9;d*&sQ^;e9Fp=C0yh`d)&T?Yk2QE$B60Bx=O9RL*KtJfgKx46ZZbwD^vFe z2FZOW(H}IFWUW703i!>auXPDw{}g0U%0~r>x(tvPi=)h_Mn5Ow-=w358@D*3Xh_&?sKc8x@p`zaq9W*5`MxVP~`+? zs+++nkc*9^zh|`LcBJ6dp_pAiSk={LVoX2nwuS9=M=Gfo%_a3`9}a=3X2kqpzSlp} z#RqS|_>mFXN1W{_(GRWWNZ3C=-@6HheJz;zM@xbC?)nnDO{dx{70bBH;ACLF{8^cf zB`?e8ey$X!`A_E%m6}8_c?Ei6{9bOa4y=lNy_>2+kt-VuAso6S2nQ(a;hv2Bt86&t0 zNxw>&ONAZ<44#O_}$~^ zce=5&w)Y%lNS{mDxP1QJLx&NV3Ts$kNAK45E_NSBa&}-ej~Kqn%UEq>!P(b3pGyd@ zR#?!`5>^5}SEjZ9W*=Q_d4sgb`>bhocs+`5L&JRWjYn|vaCi&)Wu6E+;q7Y+>x@)R>4|fk79W+cfOnM z47XWHGvV$8oP8L9Il+w%PinFjYeOXEbO{A(BEa3auTzNF&qgS6ubRPcv;IlHP^nGM zONJ5J-Ce>)B3As?j$t(Hrb-Nxb*Dn4R=N@j&RvYaoZxojO2eJCJ0RfBGY)|>9HR+o zqHN1Y!2P=lrg{Tfr62i4kG&Y3f4f+rhHx5i-tv6JKtN!>V+7_zNa;Wu7k|*|Q4z!~ zxVdG|x?gl`#8`&WaQ^(ZK{7U+DAemmD9#_8G5DTCLQY)UBmYx(kJ6)KpoDvzRZu6` zu1}Pp2?> zx($!OoZyy%suz{yexpSaGg8`XfOc^86>Z}GO!f)2Q1ZxAx_ZS!8Ta!L^EaoIT`MER zm6v@b`~;6tm=pBWlcI&rdpxC%rK(9j^{J&w|D>~2k3P#R)SDjhl z=uy(6`p-p-@R?(wSPptecb*^|8fwu!dBXe8ioJ-~WCYG*6E$8G-CA!Ggi^d7nZA1#WBF5B|Y<412b%x*N>~ z{nu9*fjPnLFe5foJKw{i{Str94y+-s)xi}5Mh1Hs4-6~t?x00(!t|1k^n25AeI=oS zAO={`=?w~E(+v8PvG5ztG*q0TTCP2y+%6{36yW7O={Wt^rX|CC@qO5Y98e~xB_^aP zE+dCftO=&VXlNhByBm+X7ifjs0q&#tEV=SDRBf8xOy2uRX6c|+VVWr&z}L&wg* z@3o_HX`9&%AcBV;?Nz29hEt8^Hf#qxX`B9)zA8@OtKM~tXvA&Yy838_B}(uB*c zY0Dc~`VhYmeci=n=@a<2!DQ=jy=RIe{Zg}~ytkZ|SLCrl`upfdq0hv-CM-h%d9S+t zrY*O2L<`HHiLe+`8E}F)id`8cK?q)S_(W>S(*awJ5PTVE>aerB+{ePqH zOX}ac8bt8qx={6A<_)&Ze7cM?g8|jr)kZqMnm4--Xv6m-^zTlS0g>~njY@{MmfpTe zWf*~}_!gyA`bVpDb?wsSZyiP?fs9kdGO`t<` z^Egd-#8<-wwq>LzojifB89Krp>%!meruh}a_3hzaWEwa(zV_JB5cAfb4C+_U6++}` zJNX4zxbo;J>ZI4RR96e7%JnnUVOuA53VxS~Wz=c=D6l*r)u6t%uSqwrn7|=0)m`9J z@raSS?$GWq?Oo5H9_=%dU2Hjn?FT#RHOi#h+izf3fa+RLIECx5fyKc8FZ^?r4)$FQ zi1|AW>h>y|g^XaYd~2`#{7geGO<*c$vUI`++SeyA-&gH6y{E-$cmu+Il0oer7Qt%R z>*edf_pHSk+HcAVW&(sd_9T5dF}#S3GRs5N)o0GpG}4q}1l9_BosetK4C+X`lS1Sw zgMbm(S}c!{E%x1w`@H{`?S-`nZiBc-g?HO4yo`3e|BJv>xIc!KiCAAXcj+o|vy&`h zFJes+zzc8NUxvH5mV>Xna}DZ)I(-DoGCDoh9Y+wOVXk%{R6Wpo8#`yah{i#r0xrFy z6)YmTcxahl7$-u$8G_ZBqbey$pSN&`6QIewPA{p`;YA!8YSGB<#sdQjEZ6GVnHjr; zceTUyoko?UUQoN`*5TVcA-|^vslQhZWjN&+#-i9aSI$#{jnvTx-MK zZ8uW{yHOsdoVR>0iV>I-e5pw+EpCu@F*8%Jw4{{-oxS?B+tAA4dW^vRG2G7}8Psu3 zE7>v2uUzipXyU9SWG#$Q?;qCD=X7eU$F&F^m(n0kR_or;QkBa<%!M$6>KFN5e!bd< zW<#V(W!|ETjppn;P&wJZqOMXou7508XE3#hh>u-d*N73g7u9|zojFMd+mrPvjG3HRmJJ%}sU6?&^Gxsq;JX)!>ny0i> zF<(3a@G`V@pP@G-=jI*u}y@G+va7=_*0AG+{I&*)@lpKE<$bv z7*zi&<5{?)6@3TR=9NmLVzcU84Di?mcMi;ko_d}yrPjr{5eLTubAom1d);Y zZ5V4l+)_yc-8a}=q!BclVQX>rz-F%;*|FCPoVZ$UPlf1sd!tbFmB zCau%%nb0zESg#1PNwaT*a3FeDA!CcLAw$vy6Fb(t>px_D_w^UpQ!|Aj8@O_+4 zwe+@!k}0ObdBr0%txkQLD4c* zz>f9yA?mqb;T~rc!DtQf?mRVF{+;i)-h))y)>peZa?pPkhv7DXZPGI4 zf0p0AzEddv*iuM`w=#H~(8j^$?qS03n&Empt`Ks&m_ePe8CuX4PpXX>g?`5)GOp+0 zeJ$%Fr1`E$jL0=eczne&ux!ZP`a$Zu;qKzaRZnFs1COs*9-P`L7pU6nb}RDs5!{Rg zQ^}z1u4P~7LY?+4p{&74LPq=dde3(T3HO{>Ltd-D`@;VAS*zLfwoL@A3D)o$c$e1u zhjxn4Dob6Kze=ATU_S>R67ds^z%?rL?Q^`0VSm<3uz!BMw8JSSzjKbUFE*E|ep|j;ASpQu>1gW#LZm{OYyv363*A zA55$ns%Cgxq}v)SsZR$t5h4EzgI}18IPMYt;d;s>MBjnY*b`c zREBgno^meesSQE}`AUEl?2QW3$8}sHXSsZoul+9gt*z+Y$_s-zPOSq$>hf8(;)kj) z^K~zjfoER)$f?=kJKZPYm^#^rb5xsc70x+M!EXogHLY9L1uU-(CoP=%jAKJo7tRjM zmmkj`I!sp|v|Oodb_(L=GI)-27OLgDhu_kK20cMWyBvf1P_O76N-f}KUa!G#1CHLL zA9ptA=54Uncgf3`J*2=_DT~}>%TkW)&9^XpQNR7qSN>mzs`p#1Q7j{GDA?LG&?GkF z0ZlsL#;`n?-8Gt`dbIAXB)o{=5LkDNhTGoS7}V66QS^Gu)qFb&^Gd5;t4w=IU!^tR zatz+^4jHVzbx#p2gDq4%-r*_}kD_qD=*tlGchyz$VBca29yw>iy12u*_cXcMVU`Qy zZpQ6b)Yw70QBI3_yu*$*UZq`)+d-3udFSaWn`2CqH@smgz5Z=)eg#-K1{WZ@F3fAQ ze6fQO%fJZjcVYclfM}5QFusqq+ka%V^gT>J*zV=z!96S|L)F*&0`-qJozJfs3aN@# z8HF0c>6(@X)pmVROHMtB?D_n2A1i#BnI8AG({D!sH3o%~Cjy(&s!ZL8w zu!gWt=CG&HnW;u-wNJYgZG*c zVs&?xh&-a95F$B_eIbnQYOCPB1lyDcz0WArgbjF6zP4OA|9A3`G=@>)5~!Pe2+9n!``ST9>!{a=FUFw zCQN&y_|zg?zo(T0ySDpuQbg%+J&r8ouEh|!R(4lG_XXM_(zh|(Nj|OSBl>(zEDMrz zSnqdNXiAD^$IQ%drtX|Wi~S7c5ZH2zhIhh0x*JV@b|+x1D!sDF*Q#6@UPD5}{@%uM ze^zm{cF@>;i5v%ZUL#YmPHv=7arb70-4UD)EQx)RD8)3Bx*w_zCtEzE=;v0`3_qd1nN$`6VuJ*?`eJ!n#;3C3b8dwey8i z64nY+X*bsw-e?csqHA`ZMV=ZW&OSYhiwCB{8bU>8GhTdLyO>l>-%rAK0%9tRhWnPX zXUS9j+*nw=K`MHOexW8G`(U?UYH*27(conJnoOEM2J>}k01Bx;aU zzpPQ&U*)WbpWp~$PS8`Eyo_1h3i1l)5^kxu1;cHjONUC~ZIhMPW^p3si|_2`WkgTu zZcO^~4id}2qXCu&l_k8jJol#!rhjb8I{X|U#8(Q}DIs;e z`c5f7(M7_VU|;dK$}jxlpgMTXr%}vZ#Z(xL?SopBE|qN~?O08?w-09@_Vf?v$KKm! zP%95D+uinh89n+Ico*A&y?||k{c!Ip3kj>w)2~V>Cj;|cI?O^T-R>gQ_0swh+fobk z&xLo?y)%!%R5&Z)CY=F3!o2zGsF|lh!cQ;)_eAi8yxmNAciBOSj0u*oudsi#{;K2U zm-K0{wzibEXoz4R(o1={Vh)GERM>A&`@l@N?w|LyIJR0Jti|~m#5r@Vo19nCk?v`% z#XR^@Pou+?<@sM-z~04Z9^uxaHdXppR{s7OEMe(bE9_}P26zlmtLH>331#n#IDfDg z@^)siN;~dSOJ~jU#ew!TJiNJRQ6pIG(B?gRZMsc6R83-mC4aI@hab|}n@(_Fc_1V% zw4qqt{S2ErFo?Uu6yIBlIYG=j`YJ=`2dL>k7Kr%v*2*zi>}~n;v{Ao<+)b_p>kKvj zRAkynri~w|Fn-|d!=nV8;q8`4WA{6e}(%f-twbK(9ZwV?H2!zhDg zVA)WYbQvO_dDxClI%1Hp?wBu@2m5yu_KI=cIw-|IO_FdtFroz91KQH-9kt!0-Tv*j z%}?|wHC=4sHATX_aIcMJ6VkkEF=_0J3*rq+cM0>wG3R@@tv1!fVYlW;PdZyDSSzdv z{+pT_3(}jR)k^4!1DVWP7L1O zMc{ZL8O7lDvoZr2lF)0cI82K9Jo- zG$ce$^fJ2iFF@cv10%3~u#0t?L3%yC7@a?KJj3zm2vOUacb^VqMuuYpHQeVQX~vy6 zws(F_5hFCJIbWVruY(B;qX~H%*WGAI3$&^SGds&?;Bo zb6J9O3Cn}`oRJ}tgNL=4d?{7NRM@*bqRZD%>D2jkR2&b8oFq)9zFW@%afO~Rl zr-LS(S2!zij=>83QG;~7nL9gL-&(*_oJUc{5aKcUFDdtOM`2X}Q8BM>5RYu{8`P=m z5yoqk@zl#W;ZMx9*{HS?XsZM7UF>x@6F1XKH_4}9p~Y!;D9)5qFs8FCA*i{AG{^!~A?w zr3y6ugPEyU+cs=id{-(xF*D8E>%yAWh!fs6Eop+;#N5F&<&{>>PdkaE^50SSt>Jvt$~KyF+_kqN=ZU9%srq z8yd3BARU^}9KK5Uzg`VfVR^7Jkx@zZY=6N-^57gx@!9gmX#y2vpCw_-u}2^tcTURv zJ2a%<5)2a71h;K0558#;GNz@rLU<77&yTGuu=N+cSl4^*CIa4lkmkk4=F=9F(X0?4z+Yd}&7!7^Nu9w2G89A(C$xse~`wxtUlf^HG(w3`()L(wi zBBsK5%p=Z@Dos-oW~-0bFcDMXR>UJLy97(>pen*NQ*#AV;SA?vUdk<4`s7qiSo6$L z!5N3CFdFtP^*JhiQ;3Wn6iEK zBneYtYk9=RB>}2?>u}N0ZJgNeOFb6+Ylm>eZ?rysoeNvD#$2eA8JRSZ>R8RGK6>*Z z+K#PRw()u?wF(=5)$pHhh85N#vsV!%$?+xqUP)_FrE}fby6+3c=Lcq}c>KWiE{{-$ zwq=XREUDSi*$RHLxGBt?>b|CPHXbVS?X#%JE++ki5a~nB@(Nyo!U#MUfiG0-Fk{)_ z^`!>2J4*NoM&PO+ZV-Sfr0w)n$ypoM5*|;vN0U+)(M7kU;UuHm2fb+>3|zI2(o} zEU|N^*mB%HaJzvSq~4$w-@lF3T5!HC_76t$hzE;O=&7G^;+2N}5|)m?&V;{v0BZoG zu6WZFAeDWyQNdsHu(Ho(r)!zy1YgjG|Tb4v?1|NlfH{(zr@#3L8@j|D890F7EGHN_= zmCwb5syZFSjlBU}lc*hi-VMl0i#sR7xzB+Og+2}ZbHbQ8FmZhp|^L*O%mK`+V-v7x0dkNjtDuMY#~Obhe)w6 zR=VEsKPT@g-Gv^_XviTjC-`!f+YQC^;<55+j%WVvghHQSt?>N=Fb$R_C$6;Qh4G)&0<-!kn)w)h^C|qx@UKs8yVZK-^ zeA@~kX9gW(H`_R>Yp5G{4+}=%93!OZ(UZ(cr-%;%CaL%YIqn(CEzM&~N_?TWgm|#L z)JY3*F|?14XI60$#BCef2fIbQd=JCiS%SHcF=uu5o?VaC>?!8By0!P9iPI7)u?oXs;gvAKmMvG zj5(uYNy#3x!X$Uo6{z~p*><4Co0XLB!Efu&luOlec3r;GUeWsr(@9^sST zTAZ}KyaBM6w_tZdmlpvoKV|hd;u;6@)qc-7>_jiL*JS+N&7f8uwphPBAc|rH))1o! z=`*IQ?(d!L#hoK~t*|C|{{(zz^zj=PWBGeJ=}rve5it{;sdw5$ zsY{i!3VwnS{JxA|#oM#$AEroqHt!KJ6^;Rq&{kK7~oFr6ZibD=A|%to!tF6t)+$l~PyslCUN?OL(oW|4vq-dmR*Y z_J66E3bzj);qup8CA)t;vGo8S74PK0R2WT&^J6!b7aJrU>f@~79Xt4Iw65Jhv9(WA z=+ML;&_1ecGE-`=43d5&mlQDqpI*mkLiTLZvlRVA<;bI1(!TVstZ&OS+J9S)jCTd` zGB%bC6K2KzAG*FetcvIRe+5Cx!bU~Kz!s@1u(Jb*f)Xm&ortIysGtZaV0X8u*ew#u z-PyJAZD66;-JRI_JInPxpELUX{lW9xhn?4)nmKdkOvTezLoFoy1tU1xLJ!L`(yY>t zq>#@+DyD(aD_(wPF@27cV|fDfk8fd-bZ$@`rAK9^;4j}@KC_T5r-;YJVysv5&&=iF zaboJHNj`TFoMZXXS3kGwY;qgyycYg`_nW1UfF5j}5x|C5uEVt$cu{9pS2d?of>Pl8 zPQo;By_j1#^*cY2_MKCoB~7i*w3b+GNlQj2J<^|n-yZO{^K1|@|_jSKSkVa3greczM787BTL*q$|)&7*ruMRNZH`eAV;;mH{?q4Y^A*QIEueu z1lBaXEAu&#Zk<*sSKDZCy+YH6mZ?cs4WH_Ay67IFVNxme$=McCim>cXH!5e7;W&o>He+K zH_i&mz6KU+3ErSE>Hya=u-;%cQ7v1qx7SItZpU#naJ}20->jMeXMwK00}E>2$0GBH zOTF!VIU2ZC^4{mfod&G#yZNMcZC-L*FQx}`&eiQ@=WX$7tprQy3rM@@-2;+G^Ehd- z79fTzRe^P^6{p_zX~`k*oQ@p3qy*&%)Iyh@4hxe`unA_G+;CkcCZ2&272za`@eDw=;|Ucuw95zgO*ZCim`d z1q(hKaauq4Mqj0&I$p&zj@JLcu8_y%eOpt8=^1F$x1Qw`(mOU=t9SY*LQTm zz!}8@jfmpbLf!#*Gyer*AwBTrcJj zUY1M0BQB~xKq@nJJjWF-#kZ2@@>j1@Qx+1(&WS1>WwaChUD_Ncah5-1?C0S`ZiUxg zwX08+-j|F~@fWO7el%#g=$z-csmaoo2p)lHU^JXQV;#kzIYXo_Eyk<36t*Uhs8OdL zJ!W-T+EKDL_a40jqyFQGhspd)w`G1j&+r|^p8lMm4h{8|@E1%EYsAoYwCk+}uD!S3Z zs9j9kKx1KJS2zElHrY6i#`Jg^^TvBA4^I!0{7a1GbaftfD}M{TPaJ#REgDOVy+9Dg zRZ37zFW<=tT=bP;jba3DF@oR&k$#^lb>&fY>=^b2THEzb4`A2Z-IKLm8&%eqnP=sK zTO4T-MiRUB<`LUIQ%^+(vOJ-X{*9Yt6>b zNT4TO&vCvF)5B=E&FbPWWmQ;7YUkUC?g7tPqS^y;ZTo++#pBnk*6Syvp2K;Wr{Vdc zx)kd+o(?bHM8RGSBf7yFYv-+xh|Qj25RsX@3l=M`vsFfSfeZ-HsAF=1L>0@E_dsq* zdYeyDla9;P>;7iH4(5@4fhR$7ZDyB{`o^`ke`lTMU&Z%?oqV&E^NE_rs6MYLYut37 z0ikxTJ=DqeeTQs}z}^|#3D)jzCn@jG+N;U=gyRbLj{zV@^&LmZrheLeeM!;HB-_{H zRiE)CBwVTol$sQHm~49aL*^0Xc7ByV%xbTMCr?mu{J8-n7pj~hQ!1J;j0T_hxU@Rg zeX}x6_EjTWe`5^;^2qVN0>fy&pZB#7Q{ztgvG;yuI0P>B@$z@pq2x{St^E&8jw%T> z)7z4mj07%RKQq^pH;I4NGZ~Lp*n`8|zt!?3s&`&wdz-< zGdI@aQoQ7S3gW1*?Kfh5$XvmtFby72JuS|CU-2dSaE zzzAFuoLzz)9DOf2i(UbTaxitw72gNX_$Jcb(JR@my=COBAfeVjnn3@+UTrMAI`5JX z_Yb_j0CGHm*Ub0yT`QV~Zx!(ujKDgCa}y?s)Rzn(>?b zoj^zAF*3J$6^8l6EfLEHHx-tjCf_u1QkFPQq_`KEbuX@LD3eRBbb2TAh|GfW?B>tA zEZ0AQL*O2a(XbwMVmCYEF`OlD0Pc{#(n>k_+$FDLUdTM+(B9x|-wt-lta9-b^Nu;> zxzgrpbuQO;8&EzpI}>y@%hQ!ivY8=cz45wQJ1itSB|?z)ev7BrTjDl`IfM+$&aHCk zeh0L^IVN}M#>H^h z{&2U5_Zp@6j0kmH*98i$3)A4|IHeL2Rq17G(dFwzhWi2b61$+M1(rHb4%?iA9(6=X zR0H+yEH`(2k#>WIh%CIy3@%5aaXTCSA2O;NAim#CRLfldCX+qhUYb3O2+an@_yNy9 z;az~Y!|C@Uzw`;$WC{0L%puR!i%NCKPS^q3XKpCLtpT^Cr18a-Dj!df%g>$wS6VB{ z&#dO|Fs?P%N^pdXwQfLEQ-d>;F1F(kxGiC{0nu{Z#`G3*LyBS_<7^aXBmPB<+&9qa zwNnrmEnx(vS44vrKOLG8=Nw$*8J4za&i<>CT;zj|c~Pus@Nm0#i7waTXpesG3f2|Y z54OKSjuOzLdP0xVdXbR^t`}PtvTDy%v9>4B=-N`jbzvGeVc(i=c`o^WTZ`ectwzh` zr?ryqG>B6%0+-@#-fHbeanuPLseekmioamQZJ=?hb3SQx`s^Q@UwP%^`T_1G(`-Aa zg)7sK?8fN|%LlJin%7}dn}@R#0}?qJxZYbpV`;N{r1ReMK%*J>_J(oO<$9Sbyf6*i z!m%}Bf4hI0JnC$1HVb+dmIK#|dja$hxYH@C@4(FK>jOnhL;G#)cbFbzQa?Op<*$0H zp80htt_%Ap>@i@?D?Wh^n4716o^^}hQkn(Bmfj_=y5IlHQ(xGgs7}gl&z7xD&c-nn z<^;DGLHM}HgM78MzaCHxI?JJXt{847kwP;zIQD9QLZ(m8tXUqaZZJ&u57p09@)wEd(m#w@{oaE z7iJ3UINoa$XrR>r{dcGQB3&6rOH4!i{Xg&HYP-zqoAXP#^h2J8wu{wR@9>Oq@~Oez z?7UG z(pA|~yw=PqJum`M1L;JzYGWK6mU$Fb$l!!}MS$;KzJvpzTi9 z{oG&`f5G$GBL&42+V~XFmDFzF|LA&7+Pr@~neH(}#ij7t1dn*rWJS))SaT)vWW0*M z;58ll8O4<0CWncWw|2(;cdcNZuJgazEdzNH5^uuB58^cqx2l{xE2*mjXw&KM6&&4T z8hlo5*4rT6%bo@rw>|gk4-c%%nuYWAVtTNPwdZ$n@A)puz?u_OOat?d>4D8BG?b>U z*GpTwMygdo!k*O+lD-p5vqWge-HRP0a+R_SYXnXSRZFD5^F~3kWF*4~Tnf_@gaeMl z>C%;MQd))W5=PXRXsUevp_2c~7h|Jpm@2AQ4srYN6SSM_(}~R1MJY?+{L)<2R5kZ*K+e!Y_{4QxX8g|RR8!6hEH)d~w9&!j=6Wr;vxF^vya8nDrxl+st z=8%`;NRJS*$0t#p{$dEh+Qm5_TodeoSnH;wo!QO4KsI&j&(C6uRc55X=b^mhr9BxM z+e~z9bx$ta&x};NbXXkIQtKb%Hcb`pW?9n0BV9NP;(B?mO2nOHGZ%GN1{K7rn3L)m zui=b?o=i-P zW0`n4iu>40)Ah0Hh~cmS1ZA2rJuDO4zz>hwKb<$99R(V7T=s~Yuhk&+Kv$R^_A8K$ zT5C^j6Q-~XDS(p$^Ul){?u3a|U2~aoG=a-4;XZ-evGzhmEjA!Np4xa@N;vO>OYu4V zH!XTGA#eo~pC)i}U|nIEz?bX^(fLiD-$I)sX#U*j!?8!zTKn;cx@2{cZ+Gq2Lwx;V zHR1!jx0VQm0d*(mj7P#kn4w@xs|?xWVk|B56l?Q|bD{(OfPZBkk>=$Dp2!2 z5gVtoUyq{6u&)UeON&c^v+ zBx-4MIS-80-h4cnerF`d z73O3s>^3cN=n|RPPxFZvo9|*xBX^5o=5QMc;skqYY*|=Kt#wgp>Q+ZFKR1Y@f$QbD z%Gw;SMkO|q)4y3txYTBNd%&vmeKIBS4!0HtX90XARgP>#PQPnNF#^kh(Ga(nseQ0U z#96QGUx{2x#2Ur&!R;4tZZM{C=>z7!(-`I#*Na#FV7H-JknX#wq1UcxwpJea)0V92 z!N;Gxzq%GPK|T3;2AkLxL!;Te0y|NC8d!s{U|w5EG=$V{CZT&Ze^tj6%v%T z9maBbYP^epM=ahStgAERU+;rG4wg?4YPa4krEO=*H>sCuw&FRns{Wq%UbxP!lJ$mF zpx&RplIHVXL%SN?qXK<>!ciT){FCC7`;1+wWF|d~FU7h-smnc!NoUTPvDeF=v-N!} zrL}h*A$pbCm!lgt)K~2reNpfijPM2Yqv6)l)9E50n2$^>`^8e*k%OeCUtcl5vn8b# z4&e-!vIE*_eqNWAmZ+Rlp}`EBYN;9 z+URBU893JB`~@S5gB%0a3ev5zI{;xmaJqJfkc4S_7%qkPx`PF;&X-E`2>9YYN(sHaK?L2X*i>qF3UdfK zvceeJS=UnOJ+ij4@7-&*bNFlGd1^D;^yoFSpIk_0)Z6=)u4cfh%)~QK<*o_m4r1G4 zn`1Pr74=A<(Wzg>W6pPq)@3&)z9C6I-()N~w!cC0q1}TsV+uRzaJ|_6yaitkNubhE zOOjA{mD3`op+y5m+JaCC?k+Wr*&=(Uh7_IEH=f79ykm_(ZYir8&3m$5iJIX7C#(MF zmvHowV)KrLym?1n-_YL8*wHeOX4&1A>X*9Ctq=AAbllFDq}!oKGLNu3oJh~jEz2tZ zcR|GU;+BEY5SPpf(k=Xxndl1lY*#yL$$oT6&cQG2^6&6!?W$?lDjE8bt#!CwtRJ4n z)ZlQ{`toR{wX9cgTf*p6XvfW+-;$pp*3fnzJPy(|{F7n1xysK=np25ch9~D>4*8d2 z_uJ;nr>sAbGUecf2ZR{1vV?O>oh7r|Y09AmVW7t?xh?Eew|knXYV~#;@KxU2o~MD) zaQdv|PZnfTgX$}`<`B5le5+6~Yvxb+@eODK#?~RH ztYauHh5ZMQ*jOQ07t+Bn)?$rfJM-^5Cu9fd!o&YX;8MIj@;?u!;bUcGN5nP}Q^(R` z`CwKL%Y{nv*3|@;!e}fL+$s;Pq-xmzxH4K0zX*-nu^_BiXsVw3)Ky(~p@f9% z>Ikjxa?MXIgLFH(8fZ)!@KtOC_m=c>O3uMFaO;6{!c~s3rY(<=n`!YX zM&MF>E9vc;NEZ*RBHwMYj$lr(|KR;qyW5SVQw&~$66cb?GpWWA0QY~`2hb>3C$}@m z(Rr#lDf?uDJkL2f2fvcezsml>qJW*;yHIR4D?!x|tz2fyu8l$RrVquoG0Wwj?M-v~ z-YrWer+3KNVwMc8eU?`%<;Jz`lD{~NlN=*(O>o1;ETR_wQkJ&#%#yH#*o!)XPkedg zJ=wcXyJM^SWE;AF8&euyp%jQ|wZk|BE`_-jgvVPM=?nKij0-qN@E44D2wWX?{7fo)Xt(vGbXR1P#l7j; zZ9f!@z@@MbVXf%ZNGYWIC*^HSR~3K32&@H&;SL4qvbz1-KX4nveFa93W(}niUymqt zZbTH>!)RMf1M3a;6om!rO8*~i7q?fQ#_bZpy0Aav2X1k=wPOw;Lk~MkFD03gHb0U` zI>e$m-BZb+^J`ceu-fe|D@n_;%b73yewx3N{FtbnqB~_4th@8ai((pU`_&+0u2qr` zR^oe?AuhQRmEqny$WGS;<^b16Eg@?QDbpg^R!`E%tjVRA4t^JhSJnC*s0%cO zW3A!$y?|$ASYa{t8?-*z;x`%hLpwJyAtymiPdFiuV8^*H7(vN%cE80NGV?(pAXxiE zHKmrsvb_d#^)3Nj^&0w$yr}Y6<`KIgyV-kICpOc)JBPs9#b}rbpG#Dq1l*FRHii{Y zH0Q*nFj^4S+sDx2lO{`3loWz{D%KTl`OpWWgLG+s+7h5Mg!T#Nk?Ix*vRzcf+GdV#mwe}eCv}{9gDGG?_4!g+2z)gQ4X6;Q-tG@9fqX!%y zxGvo9aDRl;90|cXr;Y~igY~1e-LgL;y>5L?;@UCHCWeexM}8kDT`m4x#56Ehn4Tb5 z--O#v+P)y3dq;9|q(OW22+JfUiTfBv3xboj54k~(xKdw?Y==_c{kD-g*S2z{FdB9a zl;r)@JeS#G#;v3r%{D!rY!JH@Bo&R+9~#dU3!n$X3*C1T)knQs%crbf$=K$P!3Kw6 zkFe8;1B~~gl`VsHyZ`74*Qy6KD6z6?iBw|mEt%kJ@nW9!fI*UJ&W3IH(z^GA74`_gg>ryw6<-PkN;$Dk2 zinRc(1S~iYjW|XNVj7q>%qE7wi#iXcGh(L`alKDLyB|HClV)yNjHmH56Hc=BR^=;; z8gM=ldo}EpV8ns98qckt!+LH{Ah>1V7Q=gn^HYO$X@ACZt(6$%z`SEG0jGp^2I(UH z56N*UJo-Si^lP#*!g&_E{d-(doM;@EFd_tAuUov;*5y~BHb%Kx)KF&?{$LaATB~^U z!u9e9)1cDorAGFuPp^^`YZq$)YZ@}!mpe%d=8UJk+O8w*t3P2|eF{j(Lp>X_@ELpZ zq<{ntV{A3_=9hO1$ir?q;Nk4o2kAciX}h>bX|c$nt1rb|7UUZw;Ntel~!3?|HVQcY>BvJ4_$P>YO)SY*t_jVnNTMrou#0ln5&c4ltyvQdPFKgO8ROPxTTuGBw zj~Y!C__87E1S$6H0K+%JM8HV2H|Zd0LbMa>D;>}2_Yc}By z^bc%vOpm8A;YWLQ=rUL0FsvM{`{6pv4SPy_K4db?`{0AunR%K_Y};rz&;;exQP;nz zqhw5`oOUr9+Xi$sVvrhVokZH6xGUjO*fzX9)U!dlMqLcL`qJWs=iQyPNr|kaoRKhA zX)UJQp`@J3tB-lwJ+mQ?j%Z`lMz7v#g~hIX$b#{YzC1>3-3EKdpc|^rx zxr)t$L2CD=VG`CN*4tT!8|+Z2m*i3@Ef>BxFj7^Tej)vj9h3YU++xW$i%T1NtY;Iz zYH7Dkr0GE`*-qb^OiebI`uMB^#H^-Ol@;%1E5st2;x94KmR=M$moC@bz;I3Q@?y?n zB0MfdD=iD7_zOljFMh;!wlR?g)>#8Iw!05e9=vTwH^*2~%n3&Gh=*}Ox($B+dIl|1 zbaP8ZvL>7N5^w{5#b904KjR11B1YierLADCWWJX9$`@S($5kWX{YLN`VliqHy6LagSFr}zs- zL_>?Io?#-n4BrAa9~X0yEFG4hPMp$_XnD#`Fs`1AHOYC{ThJd$up}p@E%JKectzi5 zu{o(USsQB`+1j!WSK$5S@%n>3E7tH@cin%ah{N&#Rkrz67@z%q^TOb{xrel!Q0$4%L_N7mUEI z2UZl1C`yW7xZ3!{5D9xV%puR!oiG$lJ(2h-zeOkM9JeL2`pb@^C|TkXRuu{;gyR%7YBiow#dBOMf+PiO;Nt&@I` z@AE&%IR5~*Mm$JRGjA_rv)6=kIRFjOE%Gt(&HE_xGy3GUzN%wzJ+<=FN8D?qSPm?o zA@Ae-rd?KE-yXWEQ17x=3kXXa%5VY-OCEzARI2?co)Ai z$J2Om_b3S~<48@1d8KdG&`|Pq7?WKFF#)j8WUtR?61(4ib*& zF`7plIGdp69Xrk<$E?oAZ(d^rt_iXq#}ZU$b`tKd*q_xEeARC7e~A@Lb1<4mB#EP! zG3w#e#nPt8K0lF4WomIWerdL8zmUwgoxst9?8ox; z;+H82bjQ;Ig1N%25~Cp^JJwGP>i$k@cw(I%=kYODm|M8_e8qZM_aTuc>8E+(dM(#q zVS|DelGd)h7*AvLj4<`(9xGaWPj%Rz2;L`Gl{>Z_Q9gE zK$D!ysTlF5(q$%ZSx@d3FV8R8CF`~b`wIk7zxqK)gVuVdE z!7Cj8zq{WeFPJ;GwN$J&#na86%S8MIBQR~)<$bl37!(#l{ijvpB*)$vYXM$Tj)nMY zSOPs$wo_3IXI#(5^mrPLZEZ>WD~VL;7JksRat(d!8x|}S_{9h#P&B16M(PBo7a;)|+>g2Lgs+4*xr{_BxcJh4*5hHL-f>5Vvij?ae zLu>5K5x;*lm#Zu=V;=#5(LBOM*)6BZPPAPOkD>^`xJn|X-ehH0?;w2^2#nWN`uj|! zPN^uG=5d7K*Do`_#qv)(^TRBgSM*u#vy?pW^X-A(3dRvyHZm`;_d6_ZmO>;1ZJXhhBZM=kLQ<+6{ zq8bJxPN|LONWR@MZhdH3%bV-!G+)g!w|Z~P{3a^O-ps(~GJYkg_8 z;Ci%TRT;@b%Z{y#XemEd9E$|DW4F zn^fQQ9dy+yJ3+nX5ufw?<{5_Nz-S&ZQk_V{o!zs$XE;b2b#E9E29!3qVXO&GhW#2tAH*$IUOt=dHL2b&`Et2-;^2ruMeh$9Uv0v);a$tG za4SXXVx`WLWnP*VwN+N(okM~AQP|1ckZfbITsb%qY1Qd zGnf4&(8`LNSwPl#Mi`y3+e!^#)s>=N1T#pNaf3L$VcKw$r|eAanX}rxl0%V)(=vCj z*PG;EG>=$XCQ-k)&nP;2;dTW}*c`apX09h)TM10#P@Z*=G~a9it$l9`M{2*>M~ysZ zLGas0n1<%BjI;$|qTL?FTmMT+C?BL^8n|Ap5kc^)n5FMtvbN2?dFmgXeKGHIjQ|FTh&ci1rJ{6saiWw7jP zV=njWW=<9aS&LY59%0wkQgYuEugXdbc7rZ^q^UkL42b0H@=Zi!e6@ODjNCNXU{j_&xBtQ3dcj6X^@A#lNC(S20L z8|<{x%f@>G;Iz~DOm?V)D_s=ms+I&q->??s(ydK0M)Qc@{yu7l>ZR$Mv3n%U$x6sT z-|BLJ^d0$3=DB+Da*mQ`VWsMq1gf|-;OGUn9zp0ayt5KD+Dbh)r@e|xVNb*(+@HCs z$MW7u?QffNG(KLt&L%b7LVg64WVj|lsF;#T?t`A*gpA`P$I{{(R^Svi=xP$^=~4$* zRnw2-vX*4UKv~9m;}LsK3aalCKlPi%X$e!uT=9|RlWC3AD+A^!=YKX+ajCj6ulYW0 z8*vy_>91JyiTp`%9$>4chc@I8xKCg-tSG)atwfHqR`t(B6@S5qFL1TX?D4yZTD2bZ zTK9=X?MnUjDOtjjV`=$&ilUM-*(uOdc%Uo&KD!b-2JNcB%Zo+r%BVLUkyb?{JI05r zZ`R&YFjtt9&%jlufbFDBer4cl>F)|;?|%tu{=fswaZ3T)pR=B1HX6ZpR{M|5_emqe zXD6{qi*i|VwGG65W+Wg|e$4Q?yDMIOG09TG2wZ9=Aoe^=BT1w^AiUf5VMl+BS04v= zQZT|M|0-)#d^4%scNRxa5Vpo-l8d0HiqH?Sz^Bt60!e7W6~h?=YH29Q{1Q z>ki0aJK0il1IcUG*+`x&4CJ)H%TdrioJghns=vQ};t;r0*rjW%u=`f>I@1dzA3AoF zY+8G`Izl}p;V&4m7<85KU@P(1q65SOrz5hUAE-7pv57z)x}AHJ2`%%97lAsbabSQivySi!(TA8yH65njjXn9z(W#siE%m_va8jLGm^JImFV5M}y6Kb#y<{Dn?y8J4JB? zduVr^uWDo|YjPN6;w8WN|3TnV_#4-Skby>o9Vj$$~+RR+kEYj=X!cHYV`hhV`0 z(d6;60Hx{T2`Vm?4hW{ZL>_MaF0zVKTil zt)Ki{3A?;Z!d&eIId(-|Aa}BNG0Y*%2W>tww*$*1zY(KVT&f$$k?#14Oue@0FT}dr zqsZ$uDU$iwacUOSn;!Ox1i)DLqBqcJJM0VbC|Jv(;Vta( znPdcbxQF23u;f@;+~*-~w>z7)7&QCJRNxS}6z=ozCejKIrTYPUdVW|-^(e^Eqfn62 z5|%K`6_yX~*-oo3&Ad-(Sgkr7VgvN3{wGbOOSk87Xh9e=eiiE+(3}4L@lC-rE(5(F zT0*)uHi2QZAYc!t^@)BT2wOD9;IFisz=tOqyq)n@aJWxDDU-m+NnzwvF+!8vSn4+X zUJHNPUFCvsV_}9A^|BZB?w6rpPPB3GR*;#bi%b5CtEiG99qRQ|def{JEdbsfKbc9l zE{-qqYDNUE2{QEkMTq3*w%DALSj5$tJ(4c61@m!T~h$wn_@%jDv2QUJc;_qAP+$EYc zt`JKzT8@=4SMxv)eT(8!UIfn}oJt9cCIMFc=*~v(r9zP7oK#E-pVx#f2gI{-#iX5< zO&P8U-uY=CO%~qpqUN*-{RxPj!@d%e$5q%mK%A`ql~kW*$8b%MlL3EqANl2j~V=x5zQmIghUh5J63ewl+GMirX%y%G3VE$ZZB(& zLqS*@98D|$F&hxL)Mk*w#_TouXlL^mqDxRT>E2<36wzTcEdljTNV!K=-Zo(vfol?k z;m(VtBVE0v_pL{Ai0wdQj7vTlaJ(3YhO_$MuO@)My79+f870Tk;{N!rzcM0lDa~IQ z`#jvynChV{+|ZT%9vH`QWd<@)vs~hL(2QXY;dEwTG_i|yS7wfiqqx*okmGTkT;iT& z{ud$z=7VMshwl3`AH1=sC2Kp{FdsDDPt4zDH3;T7|AEvq|I7zt+r#bL&kgfIBbrBa z0DBCGx~$l^L~vZC0apzx>dBa8Wf|rWX2L0Ll&gKr)u>-#6vv4ef#nl~0q`#1WmZ$Y z@vIexSOYX%|JzHhggP*c7KDSptBNim5o(EY1zaqO=Qubnh1KxnOmYeI^#0F$&?q^U zR-5nq@8;nFpeu;mRcIwe^TE9~P1vMShWVfo%_I6hcVL|ldaG5P>r-v~*zsr`X}W6x z!%5{l;utNyuIFM&hqyEeX%R{>=^VKjPG@^NgCdd1oTlSCZ)IoVeRqc1@bYFc#Y3MUp-RUt- z+|jKG6Z6)}Cx^kR>l0T7yT0YJphKT3&6qxAHH>OomOs+BuG~w_vna+PY@n2B_xemR z*)IFsNfqyWugj9>9RP$Td04+u&U#xog@(AoQ8DHaqKpZqUVDqVsU#^Ic*dgDyTtk&vCiAe@C?9!*tn&F>t@@|9AY0Js=mn~-e-3(j5Z+j*ZrOA zeDA5l^FfTjv<--!LY2(vrFg^vps|1c9%Amekzw>78jS*6eppl~vboX2VFadaKr~&E z?Y?T{d=7z2VgG1AR1ACLn*6MX4v!Pqt672XdIj(Fma3+m^C~yzq2~^mrN+T5726iu zK=3j zsUcefS8RMrQC7`J{U`MEeckG_S9kK{Ym-yNk-Hi(OaB7ks@tOp>ZLX-iQZ4-BK?}< z&aoHqR#Jr)QS1uXW=u&-DRfetmXo;`r%pZHNIKs(j$r+S0iySh0&>^&j%))mnU%al zdL4ZZH0mtup|}2Tglg4(zl3##^}};j{%QhM_WH=n9~|On;4uT!6NGoIC(^p>nn=U* z+-2-#u>Zg^!9L_i9$tkd+|-4|+~^n3PkQBMY)J2$oPMz0;8w@-0d%R(PAU9qr{aEq z+w0r0=hzY7%VfgN{h+Iy*74NKY@K*-T{#JRPOMR$tJTg4)av>>aViD@!m)CSG}+J>k2A`yW=*B zTi<8k>VKKk?>Eoo1SlocdN$oCwk_6l+cDL}NxfXy_+NLSmBi19r((<<)~R48!7UuO zCEn&emdwV)gOc& z~*|qN3hkntINaE_H88F#?y`4>j3WEiUb|s|me!$60@AN5d}EH@q0d zUvR(M4hSi|gk<$Y%Tt%`{@H7U;6^W-yK%b0`q6yJ^wt5)`d%LBD*m3oG(9bfcBrsg z!gXO9sX$}#O-re7Y$(vEe-?7bWk=A31GdUD;LFOnmeR}TDGZmwUP2IJj$V+K`}Cu^ z!^bHYflFck2&;Wx{H1wcB5B>1dpQIyl>oFwJCOX-0^rL2x4-1&+kx)ZTdDX9MvMi- zac@)U!2<0x$K3<>rGV^SG1o`)Q}0ehn;OQP)~a zPj`)1@fYj|2LR$7`1VCbzWsOHw-&RKYDy0-PgL<2jKCfh`p2OeWc#t+)b80=1xt&y zuuPXL=aukhht98uR`O%San z1TKZgD;NhK7O+OIpDPj9`>7*nU$#UXI1iNLKgZaoPqSPT|y zd~~_K_3RX>G{iqxqnJaUtK_JkmL^qY1WV`to7pKp4c;l zm|S87->jvmkPGq!;Hp9mTCvXUY|3)sry-_j!zl+$+2*yHnk$Pv6pB z#-+4=KCeb)srus%j7MmrbHf2&U4Fru5w=<{K*StcLt=vTEEs;5AeTr|?m5tvhNwFJ zrAxCmopo40+Pbqb&wytZ2E^jo=B~*@f^@i*U>caV0Wq${+x_-`(ZIIB^bCmdjTdCJ zF55weOW_&ozX;Q@J6vtwb<$xEhdog&NS=SLymac~ia(NPO$g3#&ko`cxD?j3fvbgW z%4Jn`>%?(|eH7-qWozI^0TdTf$?P0pXl-CF92R zRyxcHp3(oy)uGy@GN)a4x92Yw4aJ@KY z_?Jfb+n?$42Z!izf5zJZg>r$a>6wtu+YV?dT{J%7IoayDJz%#kHl%^kJrs!Y9 z>{|gDSFU+;2u;(*c@#z)xLS9;M8@0qVLEJEY;)Y34Txo?-S*~<^3`c|8Ru%aUQEw` z=+Syu#`L^yI;?kW4;;@K5Z1+G_ug*No1^jfEY+w51EPOLFSimtU3It=?su3&1LC=B zWw#UF{u~1P4~#Y->Sb4P3B41b!~9}7Zb7d-H~k`c|Fai((Q>t%fHx<*c+e7KoG6x1<7&ioALhNnS&o2r>W8-oWK}Da{3E&Ur?s1N zgCLFut`|p6a01k1tXH+T6e-m|hNFSCi|H98k7&HowdKQL9qy^P2gift#?w^>gnhM3 z8Cy~Vb((kXcwjR5l)aE)G>>qsH(jz$8bqf?W=i%wt=WiHLCnPRvK~vzb9J;ZkybM? z%h{eZL#_@Z^6j@{iB-k`hUxJ%a-JsAONCd&Ggp^;VFWI<3b<_|%_Ex^^!#JN=p7|8 z%L#3`u@>7Lw*`ab?R}TJ`qt~D!*<4{ux$*8wu>t{y?zp;!#FQ_Ivf?@8EZc1 zs^!D&kJ z_Oh)5_GtJ$o<1L0id0K2WVo(=(1V{ZKTM8(=qqD8!QJX($I!^rT_jVx&I|U8h{C6Rm2T47O{=!WRbWb0fNm3u`#B9WkEzuPYCEO=9lM zr+pRRs{Ay#y*xUD9OyotVE^&F*d>1Yu{XFnF<0mI~}|O1;45#>g8Z zN&<(ghi)LHJ&uAeDVP~a{oAyb#%Yhrq^4`61iocdK-sO29t zSFuL5{?VXEeMSzi(yuMQLVUQ>k!|ap2HFh-3pPuh!))>wNtk*ukakzMhot`4iwt`^ zIGfSm$>SKTf7FKc4@?6~i|Gl1MYG{_!l}#5)$X8#>%ufNEo8g@B<}v2c9%N^)1+n_ z6!~&7iV?V!Eg&8*wv^^B(C)0!9f_o7R*A~hiK!e7T(5OOIy0`1w@IOiS+Q( z39RR@{shy&rDCD={BOom=9fjz+qV)alHW`M|=l6sqyjAz*UR1Hq`NSW%a<4Y7+i}5$_qeuXm;S9*x!0&jv`i-Um=`tGyMa`QuhGp2kc- zyt`rH2FZKfEcwAL^I7nKUZM&?dQr$vbo(7v2VZn zti$n2GSAhC#?9!=9d*=c_jnrE9+)1irItyTmUeMbBU5TnTngKqM{KQ|?OF217qh)j>N|y=b`x`=Wsca~f zJLnYgv%AE2gz&W$HEZ#k#MZ9CA+Tq_Xt4Q!Ry4-BEPddzSi)Wn`^Q^A@5jp&67nn! zxDrd5(R!8JQM>iCC0yz=lq$C@nw+Sa%y`5Hpy3`=lX@3>#ra)4a$>X~oN4k~vf0*) z4u062;8JF=9_4jy6xlOv0OJu0W3J@bfFIGr$`6k8af{JnA7j)Hqe0W((#cmnXx9jM z!x=@E<$%V-lyStboDakF;Ps&=gInys*i5yx_2g(^J7ao=@%-D2@V#A~Lv+}y;T?N; zPniL6>}ycE|3)5xy)#C`eU`d*v}#;wn%>hz!EzixF$$K+K;w6vNzS9Yh3Ig-8i&UC zil?E)S1)dbxVE%yUnGaIl-AmfdzJo0#J=0(7QQ{0L*V!dqv598scmTb{R-3+US-3) zYnkn`2PToNW#FwRWE*&uWO`%TvqU|*zjh{vz%c_x7fG(}UpPo-lDjesbD~+z>d(G4 zo-0jq`wN|2UA%*I7=hzxjD}U2p8<4j>En_#>WhLo!BLGD$dR^qC5bi9f|y#j!Ihf2 zRi-zjd9!Gp2)bPRS;&5X+*zwuS~pe5f#@P47z$!;s&Yo zOO$yUtJVw_KgOgeicgH1zkPt5GQ@}6iFMU$e#I`d1u3zkwqBz*a)u9aZWIWSjDGxC zy`wIeMeIyeH-8Egx7BP;E)Zu9fop>J>RT&XdHZx$IH(rK6`rwR4k0div)0QA)(uP{ zn!z+QPOjNCBR!k~IeM@*p%bZCW}C8mW+fHZi)ToFpoM(_Ceom?bD-D8fv&o4ysYTG ztE;$_2&JONTS^n_WXL>X9awOY{<6~fYc&pmGyfP3Ct0T!NW13NR=-@SqvBG|K%>m2 z(vm}sM>3CaE#8RM?o>@R&AO&w1fCCKH0%*x--IsTt5bKhb5L+89A(-8y=65kOWR*G zg$Ur({7TfqJ5a5>s-%KT;V6?wlq;x92TrM|eiXh)1rR3~BRw2norV85D72BP*c|{G zOV`=Z^o{qG;v?KBE`{UvV}LjoXfAE{)n;DLzb8v-#CxS+O&5wwF(_3y;wMSWJ2H6XBvhH-9*=bVQC(E?5e&hk77h_#<9(2#j0>DyhEC@zH~z+6D6bytz&V--Ny z&$%znKHN)fx^}pv`PbjjpX(<$%hh*TGpi0kq;|knJ+G@@jekpLI#i=kv#V2F?**uL zeBNAAO_$Di8ciYU8@9@w-VXS|#iBTx#At(uo3t+7eO31%I$R3JhR=Xr!R|Ox+EQCl zyaU>;r8K0M#>fhe4e&_a7+QP0{S1kFBY??7F33pMkxEBhWjyq`cI)QEAZC%^7ZVOki_$VpItQdjRYi zw3s?=ft_@-RDVDu1UiUIEuz(WXV*!1rikZ&rq4FBc~WJmN@s27a@R-)xozZl_005e z4uMOR(GV_n($zspfM`>BnmA-hg4!oGpI{oe6y^{PlUw)n@^xJ&U91yLvEDV?L{x1? zq7$8E*CE}+MKzts_e1Vrj}hySdF`2yBE4xH!y&K*F&ge%Zsj1_*XXO-^!qGfX|aDS ze7c$KKU!WI?5EAV3Zot5GK(YCLxpEJ1TKZO0JlwlYm?(pr3J0}pgG0-YLQdJp7qJF zQ_*j;<_*mEED9GZikBQ#T?aAzkRsT0Q>WMz~T49mQuZ+ zS{7%n8^AV>LCCenu6xgba6 zGzZx#p{&|CHIzf(QkWjl82Z9<1Ne~)h<~u;*alb&a93Dk2eIOcjY`&_(G+un$E8ca z)$>lDh|9-3;Of6Q4)V@*=at{bhHwa63Udf=zMP0SU>g80bj778+Bi|rqduv+a200* zo-6&OP;uPY8j8h@iCn$}XFSdWSL=sABozcLUosUC**#4a>s#?00++%v!CsuX4)Vl~ zQOcW-u@ry72rLu4yx7n|{OH((xE+CABQUZUvo+c9+c;961FrU$xkQTH(YVT*=OE8? z3}(sOc?2$n=|P4C>~RUaTVUjPibwhjP;dN|!=&E~$Z#ThaPRqi2YE`OrR2RMo{JeU z0@H)LMG8X2mLpC`Pd*RjVg?*1Tn2j0I_)EK%bfu^%3KW<^G9Bime(A@A#f?oE%ZTX zC0^jy=fOR~_zOm04#9#h`8mbGj~s=pFpk@Ci@`Cx_R?RdSm%KabvV$8i)3(QaTDa& z38(uVc4=|qcc&FC_FQa6E7^K-G_W_o^bAqP=xT%a_WqN_G0tVQ`I+%#x%S(5lG%W` zgt9nB1fCUPG-Nq%hKg4Y+tNPz4xAjAcWfI2jSnb`gJ)aDISxqi*JowBQQVer{P_sl)#iPR zN!L_u#-eF=!}WS@4vhkevIfR_{~ia89KuXE#X0aHn_Ma?{5uwRpjQTMe?rx(FVtp8&DkYSqSU)%- ze+#;*Fk=Rp({=~wDilV}lpsIq9#V%x;8Iu%FcWU$AetW^LYJ>QFX4J|bpHcrco&~c zzB{b`V~?9A%!kt;k) z#T-IJHrzo@hq2s##YT<>t`~C%r%d}V)mL8CLy3i(hs-Pl@pW@Il5%gEtnDMDa3{;T zY0KoEuotIcmLEBlx(4FJobC?dR2b1VItCNWJID}RFB}@a?i)Dhl!Uj5szAy%^NwidOuDC96 zQrJJ5EN>qAS57~@(H(JF7Z0^C+DXL{YFsUu=|l2kR?8CX#aZMTNVa(F0m+klILJ;g z`p>Q3gsThFz#Iy~vbp2D%0S$+9`@E^8d$rSo*?WS?jSCNQB!wz9XCsL*5q)HBNaM0 z{gn&<-oZiE;)R0g;hf|cfjNX$;#jm7N6i|NsXXan&6fBFk&;P=IB9vVGRHwb2fu!^ z?`H+iktuNHx*&y&A5(_mIW=VN+BnG8izDg%!ZVy47=bwiu8xI@u9jZ(#L=cIo|EJJ zcUz$Mt;s39CeQq z%hGe}LsiTP&arm{uC$!~XEQCQ{}J}$bpOytwXQT$(RTdRYa2jHT*{NNrg`n&3@@!a zchHRvXy?k&!1ZDdVg7NxzV0b-l?Pm5PI>|-+PZ-$tQ%l7+`i|#L40sBM~VxMQgP0^ zKOpuVIY5%a2L82f5Z&8L=aP0_D$E_i(ZC2yPY~wR3er_?7)<0{iK>?6Fy`2CCS(xM z)BZo^qn7s_ITEr2Kzg<(?U+2YO4l5?!eK&dc*YKwF1!9O7OXUJK{MSxLz!iAgoS$?sX}%r}X6Oc#eiv z@0@DQNd3^8a=*!~#I^y=$pjDWEZNoB4&q(#BNmVW!Mx-ARbP-}=+Pf!XV*ADJZbD8 zyMYH?4EZIDz@;#Uko}nEAWGmB&S=>Qu$nR3k8|wZfX3&aW|Dd9RG@LR;$W}ukoQT4 zeU{iB*alc8n0YxBMaW8H$o*g%xL(X5-1{-vL2Mcf{R46hI1kqzIGM2DMrsy+`ma@h z_Bsa{GB~Q1$-%s11g0klO&n+HPo0ve=bnZX>s{*;?RwQGb@TJ&BTH6^oxj#2XD^%t z$;(fK{8ehGS`)GpI1AVcxH{@@D>aS~80HqVd#Ozh?Dr|k6k!@zKbRie+3)2b#|HVS z0U>ob$uSKq6J%1WhKY3oBh-=Q3%Jz`oQ?DV4x7xZD1~NgZ$Zda!o)t!hN}DRPjLub z3d;w1xRx+})a|2ohD;9rf)SWQ@IFo(#5aTE)PbeExx6UOg*FDRmUXHk<)u;JDrH(N zuSJl>837R!);rdZwrBg>!@495?rww=>wymPzCoi^H^}5*X>q-nLpb49^O@V`!SU*> z5oHz3i9K+lWoTDHh8Ck?etx>Ym+A3DHLqb4f-|N#lZw%>`Wn_i?%i|(EtlU_!E#{U zUpdVXt5s}70t&VBQ9Wn)Wk%0TRNem{T~{4e)$+BsqJW9r9T=FT9?tBs3&g-iMG?C( zKmkFp3%dim6$Lp8XYaAD-Foe~#j|EE*A+N)Y>Gxl1Us?^0qP=~nA!?qJEclJqVc);sOqv@!TK5l2N^H^6f^{Je zV|};O)c5Rlc4IBvKx}aIN-{6?l@LfJuRt1z%V&za&kt*C!4gEsYp-2Owo6qu-BD{c z>myJPBYUys?U>I~{}?;T`-FoB??9_Kh(K)-ouS7j=gEn0hPAdJca+Nb{p%}$p~sey zQxXe|Y-_<1L=+%IrG<*R|L=&OZM7(DzPsm)#u5Ul(2vul;;nw3sKQ(g^LFDDgzYxe z3_YBBMYuc0_*t+nLEu4vIj3tr&7}BR0`S|y&d^w@aQpfLZVZdrWULV zc{q~=mrwt}N=`LiqA_?(q0=>oex9ze#lGKTqOBD&5RMZsCtdn^qRKXs87G7Au2C8B zg-%q>`+1_uhQKij(HVLiUYRGcP(TYw50qVwyM`Xu9e$mtvgJFNGyKV8+p-0_bNti7 zf^{JedBibzG^+ROM3pTcH1x3L(SPvZ^-g#5Nd9@E%0^{a&2|^-p9uX%v!t^>PgL0u zhCOU~JEAk%>c-d=Nh$qXSa9VRR|Jh{_kH3?W~pI|)RmsvyWcqEBO#DVUfCwi#m=U2 zN!9lFTCfBWI5K2-$>?hNJ%@O)yhG+)*myw>(D8SYOZmaB^!4u7%-xQV!}LJ`WQZTQ>D)giGk$(QRA*RuTfK{#Z{G zd)aXJ*_B&cumlm`NUB+X?WeB}OMmhRIMmcVZCfh|fmCSC44Yrdv(bHEyVe#gK?Jr! z24a7=1BtmKT3c{^2Uk^4!VJVhaVs%ye+vnLRPu_K;U#gWEQvcO_*k$65!lihJU;9` zm-zXyucaNeyKSzIvtJYaKjHFUtm&2#Kig_{e5NGNAuS~YQpq!VL#jS|3MWnI=4ZhY zMART2-EJkaHuk2UJhDHX>%Qzo6A6J-@><4Y+OPfmp;pq6&JHmFmd7f%y!4gDNBp$X^ybP&4W3Ra#?(b*85=5ZKWFUG4H+6ke zqlE=a5P|m3K;(;=o#gV$$I_d)+tw`l&~Mu;p3(1v7jCl8^$U?b=ERratyVS{-NrA} z{LWT48?Cs(D~EaTe3N-r!5W(SCC2;P3zIo&Q%%k8mBY{0y|JZ+dyHFii3ipzuQM2J zwQ1hmB>S6w7A!#odQ65Mt+&rgx^z)SAQk#?2BO8&+3rJ!x3b{KVziZQM3!e>hE!=4 zeubRhM0gN7pv-HQX=`O_D{GI@yiejZRrOtI#x}vWlHWu!c!ZB^=4K6VCGo&| zI}?vz^K%1nb#7(%&-8!=mLNi&Z5xQSeNQI&@AtD{2_ocG0|Vi(<(d1C?kz1?f(W!t zM(Ymg;ox34*+)Vk75W%`|Ik8snSM)Em(HgczUPGPCbyMSw!Xa9w;QU%{10aIYQrA3 zp8De6dacL1?X0NP$dLOU_0m7ajp0q3IOs@qbJq$je@p@^U#o?7f`0pjZfAuGg%YBp z+f-IQFp6(U+h9cmQpr5>j?brU^rAb@zf4oH1Q7>_N4L2NEc1*>#Df=Uqq*b=<(0O_ zN(iJv{S@Wj_&j<_^G3r0V3i`w0 z$J7fi`${~pUU}raTVSG|Wyd;oXTkm)OAxW0r1EZfiA`8*ndAg(KR`gTK$Qw}-0;!Ceeq}O=C%p9H^B?P9f&$YKwh}}n6A$&! z8`i9cu}jZ1#Zi0OC97x_&_zNZ70&c%m9y?1b5NhyeeYjH@hff5ru3WTp}lw^zvm^7 zYC*@n^fiM!iY3D{bF2$_93iPHMEzg^KcY!0HP%t<(7Ts7GwZ2}2&BT<3+-ZEl}C>% zA1(@%aa6Gc5od`E{&zWZ6uD}C?l{gqxK&~LBw<7aq`JAwtldY!(|!n zsJ(BNOO5CkDIt&wM^QRUMtU4sm6tyYYbme<5f6w*#UaUTZoDV)=r+<(n|-w`FHyCL zgg`3HwG?IZiah$;r?&>o1+ z;BoBHu04wzRkt9O@!R5hp5>iYO8XP>&~?Bbry>uM5%IfU+0Yq0YFyszo^NM23sR*K zj|wM3K4eJ!Y+FX~A3seF^gi zx@Y_FAl|s(0d>^GW|HqZUvx7Ujdo=bB?G+QEvRAk$?wKaXLJ0S>8~?o@w^(>z=C;# zPEwVPNM@UIPSix%-dKNxiZ)wP0PyBY}9_|Mw=F;kBG%qS0&X9s6(B$yp601XAHh zoq?Da(>}@0#bm(}M4s_elm|Y?(N0FUAaWcidCs-bMGZfw94fvr!F%{Lu=CegHNN?>~lkTn_Go7^f>fH zL@P>sx!xl5=0SCaGDJllh?WsigGP%QDbw`wZtM1bAL=guoI+lq4R8Cr(ZG#1(cSLVR1PcWiQ!HGo&& zu-)XgYM55VGIaD+{lWLX5)Z6b_L9Tpii?NuZ|m0nRXLU*!iA)|^yUMzOfb&szxl^P z`)XT=+xdQ|h(Ibi!j-va(Qh2>E$;mrqhbjn%)}$)-8c5>rtuC|_;4S~RW)ue^+k?v z(P5v!79mf(Yf+ax86t+<`;dw}uwFT~JK66vU%j>3%pXMYuX8G;7R_3RjiG3XJdn4d zT+d9mU*wp_ZoLRmo3}Ze5;@a@eV#eb8__bN^j(YIBOzG4=rB!3?kJTnX&$!x1G{j) z9%(+eTyehYToF-giM>DsQpqD{fw9hB*Yi3H^u^ih6JyEttwbOOIsDJ3xKLpl=Ji3rnMqZMG zvKmDxoL0pvZ1h$2-uJ!|0;wL7w6J!iB zV>)r?jgArmsW95nt{1XLr_aTBfnr$%mLS4t=_3`A+0HlhiN`ZtY%ZiBD%S2F7L3TUToW}dEU(zA2wBc znUig?cQj}7J!`5%9vYjT0UZ7kCYpXrwU&B0Nbg#xw0HbU$woAn_>K;XM0ZJfHR_;)5k6Y1+k>5(2#h(HT6NOm6D-bbCv$ z->Iq;y~WPC=F|Q}47?ZYeyBw=34z{jAZ+Li9^VVRPwd{kffrI4zZWil&3rv8r1Ovw zra1egakJY=h&F`S@b71~`>}hv<~DQ&5BsxQ6Ib@@AR&yFwnZF7|I~b8GY|cwU%EYP zRP_jP@^&V*X1*TUpNPlS@T3u6>PrZWaEPX}eTRK5g_~x?cF7YVqGG?Hb1Y3-S_-xN z6M_DUz3Zpu*An*B7}?$nC8|@qw*eVUtKlOO`AZg>U_7Va| zXGCWpTI4RcXTYPDUPx7hctjk$$>N5s(f&lV3!Ccxafys5O$b}QgXjz%m(QGZKNH^8 z3#p8H->mm~o1kCf!*-i286O~Qd(Q}@+dy&$qO>Q`9 zZRxk7EUoQhiS@}q6zHBSwbU^$?O2z2-iVeF6?P2fjmBE_(C)qrwe7uXskS+2GaFti zP?I(HB}C;PJM}Lb#v0X`{9Ee=5u%BupFU*7LLDvDkPz!{q_Cr|OMkQZ zEfFP-R`+1lYZtdP>Z*8eC2if_IG9m$V@&M#!cFsdX?*i4d?-p>9__?@E}XVv2_mo+ z=!}VTB)6}Z)mp1`5gpfevEAeq$ckUX_#$pK7kn~E#}Y)yt^0WAIkk1!FItI>eFgRd zd$M_vGv`?6^J{t-%sw`S@+;!8b*xnlZ0ajTvH;@o zu}fxk$L-MHqUd$<-5%uWd7AH1F}~I%J+?b$Qd7*$ej7htZXe8BJj$mw9I;b1yxlf> z#SoACS01yw;e~!12j`90r=7A65na-DtLTZ?KhP@`CEKI&9+`JUi4PZiwX9EarfdGP zysSC4h@ym*EyzEcw&{rj8An8qfAX^NyW6B}%o>}5?MA1`pCnu7Iu;l9Ykj0%i~SrW zr2F(sc2J9tkJ9aPhj66ADAAhQZE~ga>`epXjQa>ew7nkUeY?Y0DV7)rTb>{z=6ubh zJN{^(Zg(G(j<8XUKe1ZNTk0Jfm|9Yk5v#rg>fd{pQIq0EO9-?FqUq+A6K#3CYc_uK zo2nvJGm?EkZndBn3I&e50Zpx)eBn=kBCE8T)NPsDsjMua^` zwmOi#$?hDf(A#B%Pw5Woy<8#u@c1Ydsj#oqqIS!(AhVilPaxU6UB_->&HNv#=d=C{ zeH1mv7NM^hp&ixoN5*isP2mjd#a=7(IAdw87Y+#HUpB+*)@!UzmsYZz_-~8%br}{+M+>9IwfUmDhbO(XBE@ zPQxCrRvb>LRXWy$wvp}8Wh{AOnH%cK%snL@7`2ff-Q!ihgK9?}l9VeXeKfG;hL}^y zh|#IZ)@DaDsm1R^3Z%mELq?c39AXX|*X#AZ50gfm9He=-4T614TcIJE{Hk>a)qmP; z{Wj|%A#ij?w4(TZoTfD>TSfTx;^~^(#_)o~V@B@X?CRq=nv7^f7CigaEQ;i&ZMhm|88TumSup0O1r19@FKy&KymG7wBMw@VX4~zru)ICT zik9{2NSTZa=`nrQCKg;_poaYDd#zswHU950;(h4|4aXuxU`|A*GdDVjN@;EQ+Iihn z>}y>qQXjc!ryeOfR>O!vFDdIo#q*UL)Q4JDDV88Yj=LAX9HTpS@91lv2J@*@Z>{s^ z*x4`Hv~l!%)u1F6xVNH)Bax!)t)HF$J=jJ36O&nBEBX^6$DGY9B4~=%kbY17yq7(U zH&)Mw_gtlx+xMRJXfs@($C-(0PQ?=}TlMu?J^DRh^b1z2Upyf;K#wwPVDu=blCdW2 zMQ9tknd0vX!f9h!p6Yc=$C!cjVk@NQ?P6QK{D`SF47bx0%Y0JN z9%utZ)5)+OKlJN~-NY8Rse93PQ72iCu$hDT_1b;)6IT|gXlKktkRP2Hb+P9;t2Gp} zJ06q}{m5!vI&NT1eY$IiR+K?clRayF2o{wy{i~x?D9M+{In!JBQX!*tNe|V~<42qB zd(pOtmJywf3DsKAUmPudO+`ttcga$%o2jYW?)4GpZuim=fqf9sbaQ=h0KfaxPS~|L zV?n7F`D$}<&>9O+6Fur5jL5uyt?JD{%qGiPWHZJ^df>}5{+^?Zj*rQNF znz1}QptjC7NR->WPD3h;I5MJ6a3$V1!NhkC_R~=+l%yd=K68Ad)CmO)dweH*Tuto8 z=Q>TT^LxLu^+y@;VB$e_dZ#+#<(dKlrNStI64E!8>-~9`*HiTdMV9LrGjhO)gJ@bw z9oCR944S9!uqz-Cfw2V9>3Zmf9v8E9uY-LXb&~ZMNm3Oa=%6oG{?f5t9Q$M*l_b09{_f`MCv`ELOhPepxqj(iI zLd*z@(aXPe)rWIC7GEa8e5G})slz0D7Vv0|x$~8nlvcsn*s?}3=9P_NO|*L_X@Dra zDM1ZC-csU$5f%B79tp$v>5JRc=dHXojITIeAv$Bd0D*^M5Oq8A&=jqgpFSY zV&sy(9%mLd_d=@vB-L1tC9K8m&gl_DMkLhO?h%;Q!V4|ffDjX+?9?pBR%jvgyOSxK z+UVa#KkX6ZJv4D`ppS$=uS7IS<+e>dQmP<9e1GH@Ga}H(5S^jNh^`5{j}~m=g)NHp z{?@wGKQ0xqcmLooBak1W>0IjS;bLpBW_ew9v--Q{w#b03kResjKrfGrP1<{5#)6(< z^hdjbKUjq&IevP{?(%jXb9=UyyaW+gQwEQ=JEGl}jqKxveH-hQ`?(Prszryo=a26u zA+TOVD@yKw`E1BJU-fJGu_BO0nQflu+3TqntqW*v$-DY_R{G(2Yd8A8+kXeyR`VUJ zqTH)Bk1gsRuN|I2clH6IJN-_6|ByZDbzMT!-Rh3()GTWc>E#}E6G+vO5TXBlW)X|N zSqIbljL)#=>{-e!;xRYa*D}B_V+L7$suOde7*)$B)`Zaj?L>DKFY2If+!rFQ?;fdE zpnB(@$f4%@8le@X-@%!)s}zhhI`#^?S+cBC((c&rMXfcH66? z&0vHLO!xh8@Fqv2;t@HpgtX7oUZX%&_S(yvYB4NdldgfRDE31*pQux+6Vgm z{O(OwVtKM=Ply|tZ?RI@ja!G}2{DW$IH zHVJmoDTxqk&-|qp>SWKA8Vxx10}rxCp;x=v+F{!yG~H{krl%U7y$pY_ol6KaA=vhf z?6~7v4bh5{Lkm)GuQzkMnDYFZWu-Rm_)4}kV3CFh-oz3@8z}T4!*G_j2~!C8f!au z<3qlFQDZxuVa2H~ml8`@pW9QV=#0E+_ve8CUa0>~b=tXEDk4xP9DQh3*a$x z?=vYsPx*FUZ$nf|b8KNJJLRIg+gEC@yTr39&B~|GaerkQR|dNC{f_1M3#WBDQlXu3 zETJ1uJ_d^l4V5~(KR?j1*EXh{sydDBKT5@V8^3-3-e&$>*2t-Es5Qk+UQ*VXOH;@(G4^#y%+9W9Zp&{KldE=DTLW zkP3USjIh5M&WC-E_4exNr6Lu2hKz7-5v`608Y)h-iI#FvY#&bjCY1Wke`SoevZKQm zmuWue+%a%3_9$#O8F7((*JXBJJ-Ogw6}h92$$s^e5LbM+=sD(BSJC@0ipmIM#JN4X zTf&;BjlEDRl*IUL*KoSoqqLz%mtI5pmZs5aT+3(`qrva!Ux-T7x=XLs)~9rIV<-uF zxGYs;QzSn%JHLLX*aI_`AOgo-`hMQHD}S7pNrb&JNj(R9l#HnHxGQ(@{8xXOYnYBy zKGeIm4#}#-e~zB_m*MTKZ7-^KR9zCtV8V|ynUExgVYR|m&CY&RM4XwOKV zT4s!1V02|2dlJhP!84&+W>rV_nEY&VBA^5&Xt{U+c~;<#eRN97RS995qqz9FuQBH=Q#_mHWRNQI(OeA?!)RV$AoA~z zNkKI2lqEeL#PwA-=Uc3!BpByqsXmaGEb?opuG<-`V+kVU*xoSzU>>n9NiC2yn~o(o z8uW*3fTlQAUs{v$L~-}J>olbDqkQK;>S8u0*(~J}in1WNt-7UN7;h72uVXw%gs~z# z`oMg)WuS4wZ3AU}UreL;p_9#2L?9Jr28z;P%m}_aJVwp&z*TQSS!J8F|ICZJ#+tBo zvDImGCd5-h)VnVu;(yFGSE=~LeC=>d3Zm&fuYwEMqwb@5e3nU4UV>7!rtIv!Wifm4 z-8dV*JbpggJ7)l2yY0AyKq|~v=;rzZXOepr>dy=8y(nceh-geajNEP^<#vklYG`3g zwgewOB42SS>q9Ec0BLm2)?RH}_KSLIZ6}TyBxbBQKGJ!$9oa;at=V{(r!&XaMSsP1 zquZ=*P1lQi?lO0B8!ctX$OA`FMJb)wR{aoXul`M*f+dKMv+zCj+t3d0SL#XU%_{aa zlnSM#*KQ)5w2&ez^;-TTq#O?G%}t(|tL7(G_P#N%ZDnNoSuv_vY*IO#6ErA^h9_Tl14Qj!@<5Mg{{ox3%s8ZyWDUK=}>&gchc%nb~C z5UGZc<{QHgvdAOX zh{wyN9n?u#&Z_1oy(9!u;n<}pKdw*LS63^@onAE*Sb_)~uM{QczP4(!aD|`A(@|gv zB7#V&^|>~)(T$BYncMq1sAn5;{xr0#gg`2s`zT7nZC}gQZW+G2`Awv`7p)_!L9r(E zS9$#Sa$%kNyg)a;ZOaj99_2@p*v3H|AL*6Kq)_qhu1PJt!Bxe$i;)_mUHVFqxaT}( zPgu1!7DQk?M>OROcYkQEAN~2T7dZrKh?=8>89Y==w_5Q}8(XlaVh=t_y?KTEXLBiM zBhwex`U{_b3tC?{KBuE+pkJYFC}*$>=S6rE{Xr>5hVjGLL0O|kb~Vq~#agvRi?wF#`#B6oY;`chEz3LMC-ePhl)b=qos@t(K5ow zz?(L|u;=mXc3vnIMp2Y7W96=rhh4IJ_WoW-m5cP)T1iny7Tc-)iAauqv?ots9|@70 z5VlbU(HT7Q<-5D5#PDb@q{>2w{rw-XZDmq58F5do$>*_};<{h7jy{Uojwhe4Mn2s) z-GaC2JJAdJp6baDThQAPEhCJ!D$u`*hf8%XNrfXPN=W%twJ6@8%{Q|+w}>HC?c~K; z`&%biry#2)Ba&ms@peL(8#-Q*5Kg4IdSMG2eQleDXxagh#e=`6zga;;>!2PeJN95j zc}~=y>95lC!F8|%5k|Y+fBK*Kdj-Rz@CZ{D$2kak+dVMj@D;! zRvoDdk%w#RRxq!%@tTad92v&f#yhDlubZlfz`l)W`btLDyFpfT=@=;KfwE&?krCLp zu@z*5+m9hU{@faMx?2?$C8(f@shW_@Kdzs{N_=Qd_h9|vM|#}rBq}$s7cZA=*ARhOIHEIp)V{ z=7m&UiO1E|E0|;XqS_w_adp|Lq~yI#Er`I#iD=sEoP1vwu8qb0k5BZxSJqmM`QWC` zv8H!TmRbL6l7|H!k4ZW7Cemt*E7RK>^FgCWeUDk|`X#uz7uGw7q)Ij=vEg~{T4f%F zCpNpk%hT)W1PdZCwj-K$q;wm_lMDCIYj*Hfk!lFFs8a!r?Ywf*DkB`LMexTTl9>C5 z!n%YYscfS@qUpPVOAj7DbhZ9Z<5U$jPuaB2I+?Vsd_E=xTY+{6*^T8pzj1cyP6vGm z)H{NH*Pi+h+we@c$~+!*AIm$KOl*`qVFlwu~6Hi&s5r?cYk4>+_=$-1Tn%~8C5&|jmV<@9p#|O zJPg13;dnS{$GQeyh``Je(TbAa?7+jyE?1x5Y{88-@uYP z^9-G6#(Kw7Y=2NKr@FCcEluXpC)*gFq?zg5os*6T%&8GgGhtH%A6=rjzIE~%4XGNE z=EEoDR&TWKq{)b?JAUZ(Xn$?#cD@?+HPi$3qe#83m{7A+)#puZ$`OJ7is+19Tjx?1 z_uE_Bc%fAF414^X3893vGjmxKHw`PLO?NJrz9-d2h53$*xH2S+=g%9e*E8+*#=Ha( z$d59zJ^i`=`6l|-(O+rR7}bj4XV4!|Cas_|Y%cgtn0_c(8L2FW8akmUTB&tQRwjOvJ-}{S)T?CWUzT zypH0GJJy-vxygd7i*POJ_#3S;bIF|Q(7vho9(}BmG^5>Or)z^{Am#Dh6pT~wT zGix%!?%N>l`D~YZ=0Fh%fnx@u|7=}jjJn??)`W2oTbkn4%saYw=SF zhOTA)`5iTxM^%z)L*Mc0Qv2Bw0!JA{)9o;`B6zj^)mhT&vN}e6jJ3mw-_z`;*!=^k z901yZ5s%ZTTm-FWTjH~Re*l~wFT=#^!NNB5^W)O&%(T}ZVmMY566 zQKH~+2Q&6gL^meH_j$S1R@Yh*V#4Vz{JZs=eyUL^9T7-{eMM2S9-hLu57!)>qd58% z`YZY|Y3?1#(w3#^F{wcusjwGeFQ663I*}~26rEUaRe~cGYKyI)DD_+$s{PJY<8dQB zIeIu|da}2hd*&2%z2B&hs@D=|XSC+Pf{V2^NgG)Gm078+I%xsoBDK}`{~T1KpW8eU zz3+OX7;83KJNJM3z0m0t-A4XR!J(9 zMD|1@zk2-6J1I+UcMJLt`W5O#_t5Lt_L!}a;>#lkDfdAMWvTezQNlH8hILJu%u;;C z$cg;uz3s~5MAgLm+Fo~04Sfj_vR^%>`CuH)2anKv5c@Vta))vvV?MZ|oH56t?~k0m zLkhct$1FI~BU(lnZPl;9p`=X-tt{9l(63NhTDiLvC0;Km;C-Y|0fyd=u@-&$e^PPZ z0;W1B6-rWp@|9yAugp!;zdQfbBOQU`1fpfcT~FEI32n65{YpWg@9()U3e2N5kJa+Dq;wq}sY_aeK*eV7&{ z#L*L`#E26T0;yyR(tcE7?63WN;FuToZPZEDqgSt?BC~I_`o3ATjtHc}K2Pt;Jcts< zN(Wed4qY%Kca#bvAMGiklauzR3tIIawHcNm;`;tY+UM<`SkFt#Nb?~Fqr~@NIkl~2 zu9*>mROtCMa^8;;g~W5~!%X|Uu>=tw)Vl8RS=92!jTNuxF0=G@BRYz+`TkRbJYQLj zoi!frv8I>nb87YTZZZ#k6_fIUZ zVoyW%g^BD=Oi2wrpI+|$cQAjEdeN(OX-zlU%Gi@yu8Q1N*oJh==F&3U`RYmabvqZ1 zh!Ae4*@a9qAN?4Ug0`Vojz32UulhNxXMzh^kvmG2^}r(Ss@(?Gq^d8qu6`s+6f5A& z@?~XRCh9;cp0iSuJlSqGGkPelY$;dn(Wciyhzw%L^rx$CN< zk7Da$t5aLi*S;h4wQnAM?L!3i2}Dzbdmkk_b?9ro6Ohk}+)=7P(xZI#@9gnB<8~P5 z7g1tINHMGD+f5PzspQeQ*uPQY@rp?6gNVPZSb~TF#G`7VN34Az2jbE4QIt6OaGmM; z&VM8XQps7yn%7ZcuQtOwEorsn?TA1hqjxRChl*Xzrs&~0hv?`H8?P_aqF1kHtH(!c zx#JgTUuJG%%T7%psiqJ1wVe5R&xG4lC(YQIIkpDvp@+UA_mAm?XR9~;deO_%DJt^7 zda(y9N@BiR{Q6(B)B*EcIF@``wLnYQE?8~T8f`L3xUc>>R^!%2l4^L@2>xSiVHS9y zl8OkV!l+HzQn^cddJN4C{_e@^)jrKeQzni!Xhbb~C*Ty@&@!7Q+vCfW(IRNW6g7*fkcK@K z?SXAbul8*AwM_VVQqS=A;k3u3UG-QKdOq5Q-ao&)Q6KTD1FvDZrJ@ZSNh*ELHs-%z zwuWs;yDVOGq0xDl+U(?EsdW)Cn_6L4@x3hbffZzr9mQvA?(@57o9&}G+TcC4Zi@9T z+jC{ZZ#jcH$wx#@9;i=CaFXnS2(%6DludFKq3b=xJ=ZXX_Q*?m%p7T_Zp}7PL)(xZ z@ou7tdol6l%0V41RgDm>|H`ah>(yAp{z$J{wdy8f$DG&W#x2lKl7`trzp|XeD`|`n zosPd_{ge{FA)ejYs1LMc7Hh})2&@Yc=nHgif_6D=FI%3`tAzqf8WWGWlegHRCk`5V z4BZYBQG;Jz-d(MH+f`sm146v}eu&*4pZhnzDizmFY?{4N-Mjp_jvj}I)1=?5tb17A z&1J}fc3lEQodI`MJ#eaoKq~am^c62rXi>LXv=h*R-iKZ}iagZV(fDsMV>WS$TK7b| z_WEWptx2c|**|+PMl#e%)+3BO@$Dsd(KFXeDFUGPAwNaAw9Q?#_NgSU=bNFT z?`9_pt~iuQy<2johJLIlMHkQT9MF51_%BOBdR}77;ZTwj_j74R>vl_T-49Px{r$m~ zqRZMm9C=_=Lw*$78~@N}4YC)Bvnl>UUW@(i2le0%*FUm#X~vHD@>&4DO!M;|ZyeO$ zM+2LLvQ#g^hKfAh0=3lhyLF5*7(X!1E6TM68`Q^nL-@ac)ksB;D@SdWR)0OSQ@U#y zA1RZe9j3WxZjh@y$^ykujPlCt6gqttLFvErB<_iQ-=n0mk>y`oe(!_?`0>d8@C%@h4~;# zg_5-J_-r-w7@Dq!Cw<$dUB&!Jo9Oi1$2J-uT1L#8`og>Xf-JoB*DjJ&C<*p?xN7wkIyS1kP0oUC?(G3w?9+59=p2QlKHw%AuP^2Cj6U+Gm#ZB}zU$*CDd#}Y(Dk{&IS*0ax3JCPnn_PT?lDn(NHlO*Hmzm%1`EiVvz9 zt051pw?FYX`R_XBzkN9IFz1gnAEfhr-bdG)5rI^4k2-dAskKmeICq|}s#t=E_Qc~0 z+sKxB8ne_T!D~zb1Bdhc{#zsjQepN%`})3}QX^{B6G^f595r{iQeInqZLZrXvH{wL z_7rt!z!QW1(O(XHuP>`zF5QCq_ZSl*uqH*>J)*F+#i71DXTNJw?t@Y_Bt0rF+Qts7 zFy0<0%r5O6HnA6X+4WRHAQk38^p$L*L*0iX8}l{K%W*70gd6c_uq=rswlkt=p>mbX zu3PGHrVHR#(gj&&iA(j-+(sQjzs)fi@u$0;w>6r2SWclauSN8qRB0lY1>nh0@ZVBGUrvw*4Bbabuj6iz1Jb zB-QiXS6Sf?#%#jkIKezAc7!%7R?c3L3iDFBGqYSCtJnInx;Prau>=uih{wrt|FR;V z*AtICe|I(aDSc2MadVJ_Kq?$}DNn55$o%I0A$?=SAdV%7s6;%jyS`w5oiR@2o|&H2 zn#-e*7}%nfgg`38WAxsi*sb&vZlykbPidF0xcI!&M?xT#oB^CUxY2sAtQY@q+LdDo zA~2UAPb~Yw+UR{FaX+BElw}~I0ZEm6uc8*-XY@h5PsXsVaVyuVtg$Avv)s=Yw0h~? z_eML>!!x(U1M8J@pK`}bSx-jv6#;Xvt5|{vBTBUDXQ%dVZ$!B6W6h?=^(uOND7E8|an@-GAwG)6p(`(#|kWPGnREOnA@v+DLW#)KmoT2oODcj{=~Vjm!?L}U@j z1M8LZ_I|EK_c_09FD}l>DX;_)t4XRgr@yfrQ(Z`^N6*JvTa2nHmIj(61XArJM5Z-w z*vlZ^mLNi&u>@W_?!DLRgMPSL z4}m3!FmlFmOP?^u;znk<@Y@V)(CsL__?1uzfm9kHV*1@;W6m0DOL(7*VFRN_?RSVZ zVJ|}4C`u3Sf+-~mnf34M!X+M9uRK?CK08eGn0(NZUu;j$uWUT9-i}_`v{?h9llpcx zZVI^`93WoN-6G}N*V~IyAyq+=b}ZdMbIi%e+q2i-YwG=YUCO;5Q3AQ6RK{H7`9-zST=jD{;+BS zL+&WmXwu`$l#Ogx;6T#jeV2g2U#_?XeUd2$=}_<7$Fe_FkJ9qikPmJu(y zj1!lGceBM`=1JU9DjaudKSN-+D0;_H4K-!cu>=vVNGI2VikffMOtRq5Si)K9GhQea zN`i5P?tr*cL0s>x>n;^tcx2jtR=O9(THt1k$@o^VZ}>E;Z)!C+Y>a*pBw(jO1D9w=Ek?Q4|z6OC%1}CLEF%&lqX^0RF-Dyl|FVV^1ym=Y*&;OjlxCcHO1Af zuFn~kAYv;?^$GYj9iKkwLitPiQlrTSb_*aderQD zpG8}ZlSo-w4He}p*J0&*B}oXR!tsh$SaL-Q%Z{dXhrTYRVhJLQ-`~!hU>mm?JT_bk z6+g0#(=x3K`vYO4lE=XglSB2bKHfa4dU=kmYka%2^*gk`qLh7GU2J(>oj=(=Q^kIO z2&{?D#B~lA-OV_9a1}smhA?VE%@P>UuyJ*XcUtw!Qb86TMiqdw`8vSHsg#Nbo012^! z5Or=mXGI$n)euejZnKt_>>V;PePi|1h@va6#hB0ra{tKJJyBn^F-F~y)F+*X%`>px z?ZmHAA)T4m8d>=A$?lqy^C2}$zd;fLsj%G?#qnTS)?;2No@8kzumllnh)36PdstB~ zqn{sYNq0(q@Z-x`6%^Q_NEJtj57V}>Sq{dV7H5{MQLRH|*cR z&DC%XhG*Aeu(CEqC-gmLj}%KsAnaA(ad93u1zK-!fjpe801> z=-@nEbt&6GLLgOX>Vv;lqt3>55+5eDU=EoaIhG)zBq4sS6z#3pR_wkSsE^Czz;PX> zEJ^bH>t!~&!FmnzE_rXQ7p>hJMOTS+`n668l` zOy)e%6WizooknDS$u?IrS~t1+WYy{L zDA6ZWmo!8w%+BaLPJ#LC$~ZUiY@r9o5=6L+>!zvB?^&TY#)l}6L8JF^?xZNad0d2wZG}>yw6qVocWbp`mEofK zyeT@CpzO0qk9DUNwYzFWIJ(7y(=8t2M5EIdOEYPvU_AH>lB z(K5oaAg8)2%P6sSU5q3ZN@B#yUwL9RhplYGf)=7wj^gQY*H*HWWY42~V{6*FYM2Kp zO7rnWw3uz3Me{!P5(0T3T2VgGNx&EMH;K*<;z))%$$GpbY6B$_2TBN}ilO|mQ`rRT z<;+G~9V+Ff|68e&_`Ja^P+pV-$6fkvK;!v8P2T83^R<-_NQL7(nQoe$dd6{rYN|Mj zBh?n_cQcpVVG*nI{5GCD66g}yJ#<|UNe`6W@Z%M$lwb88BD$5?sNQ{8QSDEX zTwIq)t=O-ZRPQXQf4I{736sk8_WZusS2K35MpL^yIT~ZSLbFFY&!=4oicK;8f0n+} ze@~5}vwcnK_7`g2Q~K8dSG8o4{hP~oHnC%{hB_f{${Bh$7m-dyc+tAmB&kpm?7@mM zDZ06s)TSh#^s`cA2xOmZ{DM!s~K3ZeV_3DS!gEYrhps!>F`--hYFX_4OK4B;o^1~LP^9HpB z3;oqTwO`-kk{&2KqN&%?n*g(E?wq!~KQnfA(R1=@kVk`urXaE9Sz9%(`V}2Za8xTv-t)ZD9kzXt@m1zrUvEB**Hojs%kx$>8NiwN{llnUFBJdt{>OUJMJiQc&dW??l*sv-sUv8PiPYBG<@ zo}I<@Dj}+4@7F3)MUY>)9X`Oy|Ftk(51USkGK>287E_EmqF7IL5m809NMx(CPSOy8 zHPM&2`F+IR8-M92L7!V>YhbI1m^9CrX7vD`-uGZw{*u1WhDe^i)ckD=rLUEkK3e9yc?-u zU8hNp#}5G`;LJyZCL+cHV#f|VFy};xmd>=)9+k6>$piYWnEz^to z;4#&=W|)f68TG)?PElr0ttqBIb{5kU*Xu}y@exM`+5w@C6Hx~ivAX&9X&8Ml8eklw zo&7;g#Zu+8zO%*$6-y9-ah`TyCwubXfGi^Si&rXAg_D;QPDo>?sx6X623j4YJ;En` z?h!Ux*XU7)Q({aQSFok&q($3G;-#~{K6;>uW4sC>9_xQxX0shvXvmL}lB;7xIX$kf zW7WWPscbO=sZd(VUY+PJfNg`-99P=>5k+m$8KXAsHE0?v;)=A=6I-6uF_K{{L1}4L z)S#Y;SFSDMd@S|i0o?DKLgX<*k+Jc`_@mvD_#vFBia zl>6X>93dj{X{3JArIUm}e?>IiTTA`p%Fpw)hv+r}V~m<}FvEhjtOl(~Yki*XBB@k% zz9aIPj&&gqj4O&VjIxXZ*Z);FTP?1zEEVR|C?S1g`Sd{j(Y%T1 z@Z&-H`9WJ0MM;b^cshB{oo|Lc&e2RFC)uOe&+~(}+y`}%5oHpa3+t3%eg5-&^rFYF zc#bWN5-Q5XVZ%k9_50bt`fH`gfH?!k6}p2iDo(X`nywz%J&>b@SnsF_y|p)0?y=yq z#_s6f&kx!n97Z)+j}9;DTBc>nuR3>*lz3php~S%TQ=bn=-VB}U6cg-3Y|CK>r@Z-<(gBY)DI>~yB9_7#cN{8}j`&bnv!8u2LlB)8nZ!D!>50dKW_&7bw=0M(M z=}8HJR45^xg4kbK3=x%u+I(O7eM?6Fxbine(FsZBFsq~Xs(ozw-Jij<_EY+dF(17B ztemLyx}iwxeMmFzSh68H(J7mDy*^ntw5Ay(py?#i(+TQ}w;??BKTjQH$1%JX=`r)a zZ_Mt#cSV6xg4!pBw0n&rhSNpS2fKTzjo)TYzX7uWt%t2V9%DiaqGdDoGuYo6nUG_D7q1p%XGD}ZolX1N zF*XI!iee(o1Jmk?jR|E0YKwV-(N?AW_p#GM<4E(3r1_1KS;f0JKM8?U*a|dqhWoQt zr9(vr`&b?8#aW7B^N>mj?B98YU-gNO({pYP6rRgYN(iJve)KxmlXTw|gI;*5STBzH z4TwiBmjt%L)98b1GJIFeyS2`Q2&6)Oiqa_Ux_)>b`n)-%qU=UA*xhR%JNVv9LkVe@-m&!lAs#Mw z=7_+^iD>$+mNQO&ygG|m^u~`P6~llno!g>S){9dLPYa;!Rew`%+Ez z_Izu`iRCpuTlM?L(@ShUXB8nzUD811(SZ!v59D7{65F7ZG+BU({fUx^Sy z@)Xru_vPvR+2*6Asjd9#Br{9&L`_B*>)=C5O!xZS|9LXjTa6I&rY5o+%fmH9)9z^c z2AS{YH%Q~QH)AwtbT%gajz(MW`lAnuc&A%Q0Vms8kO%q_@=NcvVn^6#x9B^~EJ(#j zs{Yz;w(VVS?N7w(vI{&!9zO|zo`L8L9@n)Hk2IGy7Nqhc9_3y3u<1BTg)o#>93$yywV^l=osE=qxiP{<^hO)a>?=v;h z>$2r)hJ?1v;@a+Dtq1$ardV51EHV7b+27(}s?*ehue*L>p%waQh|WMvFMZu3 zb2%RgVc7Z1)X(hX@$hte*w7h>ALH&PWnb7pLKq%n8<7!Bu_V>kGVSMiP9yrXr*DJ` z4q8+p|sI77D;4;dVdSo)bG=%;eA#P3E%6zY8)sY8AHRMNgPPb2bHM*s#?deKtzTthf z@)JL?q!zt3^o$9l)57@Atf#dfdC5w;U$h?FFKUwtB{A+&%=YX*YeM?>kFs`YaEZ5~NtEtSmbyL8ax9%WZB zLNwg)SliOcK|&yv+@mUAY-oMAb`-CYbGC|JJ$+jf&G(-Vtk@SHsTJs3>gV0ofStp| z{b8GQM2sVZLma)@(<4AbG|h_WKADwpzo;#HMa_--GmZJ+=5z~Qq4^+LUbOgmzo;!z zWBbU6#Jpw}aCMXjzc@pZ3VSU|s3ckgYLf~j38(DbSaa}K3{Q+E&F9cJuWzlRRm>)E^pO$w-d{0aaETHNXD?$Y zJ4OSPkn*cGd9-%4qw0O(aVk=EAwBMRd}J+-PtasUU{hg!U22F3TAC^$u%{xLZohDi zvrc#IBJ!Wh%8{xi@hD91RCkV;p~;9I^ldwV-n6(;KRW$BecSko+G1a!*N4d7#+T$$ zbR#MDZEQCgvG!ChR@bhPm^!$EBo)RFl#uePo8x%ZqEodU+GNQ`caR>&$lyz}_=4k_ zYFCxdZ1mi&)Xx{aAIA@A78cxJq+$uy`#!R%w)^l$Hs5o6#`wW!$3IP4sI~V(DmUU` ztXWQ>HA@frZOjuAY4(!w{@^Tnf3V2gjQ0nB(8}7^FSPfAUUg{fHpA*(EjIoA!7P`z zSr5H1=7T#fjT7M~H)z@IeA$iRjWyrcB=&vWP^~M~JEz9S8ez1)~JY9lQhgR&B{JUn6w0Gx11!L8~F@4ow`uHf`Jl??^lsiI0 z*%OIh_?ZW6k>?z32mSu&c%J#)nMXWYH;>}8Ce^fVG%ZTk(8v?#&fUG zhK%F4*Ui(mJl`xKkVGxoOrbWKKVAbW(|sKA$3 zb>XPF;fZJ?9$nXfo#=TNNE5@ut!F(m0-b zdIC%6Tv;kX1WHIZb59(s4qVoaCs)3o{tBP1AD~nyt)i6N62%?zx@jfsuUpXuXmi;f z13Gl)iz=Q_1BNeAF&ca%J)Sgs#g%wjIr zm3kMw3*ZpN-|pG!EEpIvVtF6-|1X7{2wClcAByTnHt9D@jQihtN=OaJbXPGOK7wTSE zU0OCP!zhZ{qW$TFo7&UsuLwt#TOtMeD1TWmJ>vLM#KAsKYfDA^`Qgn~)wjK~ONf?) zFueT@c{`$M7t(f%=l(;5_`rYtBm{aNqUmeKwuYVwdHV8zem8Zb8bCY@Z(nYBJMg3V z$AP(?I|nXxi^XZyXMRHx7-RvhCl;q`z@!i#W#nNH$-f72)prlARpK@>3TB zRIGO@Nn-f!Lh@ai$Nz^wdmx(PZdp4^mRaTb+n0?vQmrH&hVMQi-<1(TS87-kLVWlQ zfqsQ(McGohm!;F@Osw*qD2`OCh)48~(`?SsTAGYVF5)lThAh>(PH~bD=zWN$ua<@V zx!s8~`tD07RHTX|9GJa(6C*CA z(zmDZ4>2Z;QS$h4F>VYmboi7x_;8Sp^Yd9)*Mj~J0lTuJ(`#sKDNd z2&^f6cE{H&&s?W?RJ<3~)tB_hFRZLOts%;KP*%wc78K2EI~vpq5HZBw)JdV z8fy*2T(^~b{BQP>5J)B4JS~fd_)35Cf`;xzOBrvJ+4^I7`fcoJ9Gt_*^bH;(-d#?r z7v9MW>p~t2Nvh*7PqFtA#+f(+asOc2?gwf|34v4#2vO_vZMJ=haq?wopO?CKt=1xf z?s`F~P?Ey*W{$C6bW~28RNYs9a5cZ{Eb+j4{P>DBNa_Bwt$wtth^wsBs9EWH*mRD2750s=Y z<)X%Z(LU*Vv}+!%j-tC>mbQ(SvL!^z2*c*?{rc}2m)cK~stZY#Yr_jRy;!V<5@zVJ zxb$|nVXJ*41de@(&OpR2J+Nn8yC#y&(a!Q1Wk_`??Wo7RI-R_*1QCNs!ollbvl*j? zl9!C29i}&UO`g&yTE`I*wZ*z~QrXCRoN!cT$O5dkt1K z&dn!|ZpxW}PfLn~X*ave?MK}c7HmJ8HoaprvX~mV%-GgFeblPDc=e)zs ziE)Z@BIy9La}I%UUU3upnLXTk)>$E%cQ$gtG*4J8885in-xIFA9nM*WE#doa>er^S z+b9=l$llH}zLEld{OEO+EdIFauQAxl*N-kLl%+~XB?*shOepoH%vWtopLwY>Bjn1R z^BfPgyHM&!{>v()gR_wf_KEkS*?z5D`^q2^9bQeRNErw$Rd4%Q=LWB;kY^c6UF{lj z!*RjPezKW+bs1ZQE#afjh)EZdLym^ao#vYe_zEWQd|kT+&9 z9oJ^C6Rs;X!LZB1)te44sVivC*5pPM9)ozSz#2g0H2QAyW-@Z@ zE(u@3#8ZeRkILU9#x+-hRTbQ{^!%|?;>xIX3=>%DB@hX1E|I~Z%C|EEj?JPO`_)qK zDX;?qjcqK2`!RgkVX~(h_9r?)jF)jO;y#9Zk4lyQIf7OiyNV4wIEmr1u#TT#Rd3yC z5?nkRtlFLCrM@%v|E&$zGw4?{12V|s8GfL{bdr`H z>je?`LoE#^uoNC$u!cD8W}S(H?Y6eshcTix5DE;Vq#)@6YL!dhY<|3&g)JTRMLT za56%~_=Rb1+s>wad0B-Oj8xvdZ(Bx7%?>`%JoY-o>A>aUo(~ajnU-!#8AuL>f6(9_ zj-{%CRb~9%lAm?Qf>pb;p>#@ah%j1cB|e0HRht$Pzl{?ZmcsL{O7-Nm5q%10m`rRl zI2HSWZCA#8H#qgA!C@otV^rpHNB_%HIlwsame)B;af!dFRx&dkyr zt3F19XXMLZ;TV$w;$p1*Yj*Al-<4_qaDm2Vq#wbaV?SO1{kcyODRW!N!jB$vmfwzP zEng1u7O+*=lKb1byC`jAGEQla8?ZBTeFv4(cG#Jz5DZT2@Of6YbRIPL#1jd}wKTjl zAy3LJ7nQzi$XIZVV*g<8;IpAL^!00DO(i!8XJOcOOv9*!JaH{NmAMaZB4MkrCDZ3l zvHfJQ!3-bU=_ARnc)m${@;1f zKwv36(qNsse4&&yX1CP7q@S#+-lcRFPJmf>BjoCz9^WQUt`p`7{@rwYNRCSsdVAuK z#*%og3BBsjja~*n9-KQzGVB+zbMRZ4Wro5mQxS-vud_+hH_D8I=MUVkuur^I&O;kZ z74mipRV=1ZT<&Smq0D_IF!%8~KJ>Jp=XW$=q^%ppQW-$(cfU{aVpjY`Twl{%l1|yl z+xK*&xHsTlQXBjj(C{@GR{Ey*kpf2AZJZ!atPA^=Q2fB{&l5RQ&7>;#hR7b$R|$^~ z-2PUeL(Y9mE*6b}y4pH(r4+ohvD|Z@hU@K^=84u;0aWMjE!j9_2)Hj{DZVF;KG~Kn zT&a~E%XT363MQ~ma60~=#*!u?SdQ7fSHiY`f!f`1>@~3p9KbOB|KH|@NR4A9oFjZQ zOm1@7QEJ~JUfg5Xf&^`t;M-WT z3j8EJ2_DLgK|JnwKk{}3%ljTA3YIx>;)Wfy$fmZd#hfqUoIYO1V;~Lzk$*c*e6_4L z8B}GB*rnHFj^+s~-C$YM(}-SVapJ9&<;eNXr^M`U;T(ZWf_?fxsDWrJ#fddWmM6~H zr$yran4@_jM(Qj_jJ2e(2jj$d)1GJ?ZWoA~io-bqmjpW+fmj5@n*(v;st5U+DZLBD z<{pnZnkUp7EoAG4ZuIHeIPnMU1rAED$Xfpl=LlSqN@Wj(EfBkaXml`HGiZ|udkZ=+ z%@fPl6-gsTjig&6pv^DN(;Pi$#-{%Y=LlSqO0@xq;Xr%Uz50?Zd=>X9b2oE4u%QZEXPBvk+ydHBjPxMS~ zC!Oy*m%87G6G!U`oY$Oa!5&ne&k?vJm1_PB6Y0s(aGI01+{s=naMm4f!N!3OO!I{M z*1e>0M=jlHyUuCnyJP7C{hKkr-!MLqK3tNrt5{9SL;jODB2LUVK9Np`HfPH~2c~)A z$JNn-bL4C)504XL7P^b|{%goOgAPpKl2odi*G3CYK==Sr^Sp<+;-Wd53py~(6HBZw z3Z8xw>9S!maBV(j;Dj=&|sI0vE_h>~qEqWl`L*~bFJ!w|19%@fB{XVMs}rNV@SIPtQ5 zQ}#ghIz97iI7i@;;GH-i;(=HV#74(vZ0eLZ=_euXVwxvfypEv43LPn*9Vg~MrrpVQ zwL`||aE`zwDep8y(6K;_0OHpD7A(c}r$Y+NQJCflMMuUm9joz7@5jEHuU(G9?ix(s zlHh9|K)eJZ^{L*E;x%tv;$8KA7-*hI0MA{mmP*%3^zAXkW1ME|2fZH#Lb1wFlD@9I zfY=6vQYS$;>9cw7)jlnxjd1tM69^0+$49$Ur0l@eBy1k7j?m zqlxRTA0GyqCr-hLx?18ScXo{zQ@t*U^XjWeg#!KfFc7#TmFhGQmw^}ogfiCpyik#A z-5zr^Pu%`pg{E&EAb<0ZFO45xU8|E#ufsV4m!wkN0wN8FmV@I<xW;}H?2bYOkBBzW8D4`Bm@GN=9&n~)ozL&*jVG*6s{4B%bhbotf%_|iP# zd8`>33OX=>OM*9Yfp`x@?*;LtdC9e{b;&o-p=22bnkSUp$9B|6*?n$&X})uiRU}5x z=9o~j3`0q9niUY%Koo_=m*!XQTTF;2w1<*k8EBrcg^bLop_{yNYJ6$l7L!|`DGPlU z6H2yZC<)&A0pe!^H~Gqx_|iPl$G1>(33Mn~rh(>(Sja4UkF}HskBTqNKRfL>rRnoV zpC=j!CF?Vkq*CnxVgL|kqvK2SUGp2KH8Ws*DA}@s<_RUIuG-T`uF*HXG>d2-Cjr~i9|5p?B>cEP$+3rCyE*G!$@jBL+ze;IQ z){dH&Ra1Ng6ZkG1PGU_qyIXBqYj{P9@7(b!#d%n zryHbjgYx{NvshPGc&-_p5!Hhu;^7@EWd*7OtUx8gZ~u|!NYTv>& zop4V~?(0IXeBJE2 z6I1hkOVS?rLg`;t87#ql8qVw6a9^y~zdb!*O}M(kIQzUFjIJ^r|pgu+JCMn+qFg@LmH2N@8b{f7&!rF2D=%B8mAWB@UzYyxG^67qT z+Q*sl1+PT{Ca{zeuMFc6*7Pstiq241^Zu$UY!$W^&O^3{64fIP2vIK6`oqCt5aRion288d4OtRa=1Bm>i zxne^ger8vbOF+jc)AOWdh6ls?cw+g9e#8;#sqKfE6nlt0$72P~XteOqm26m@s_X&5 z1eW4sd-vE}@xZhiGI*FMEylzsS2=utvreQT>2!g zZJm2!dym;db^A~mU%>=kvBA-w1p zF5|MWj(6b4fEKyr$W7(T4oYlq67FMDZk|i&Jb0(64XKc-p9gb&oXDM`{-V;~%qLQE zu>V--iFuoS-n>Am)&BfaJ&_ayaXd<7HSnyl*ZkzBD7=`Qr54?9O zC3fQod27aJAsEJ8cjp4)xHp_lhxnoVrtmvOX+d}j5Lo&YU_+XiatMeGK;YGWO!I`& z<`s=LB>O;{E8}2=vpo^2EaTewGyLBL+I&wHCHg2t!+SaQ@jLr-gwp#AJ%;Zk-J@&j zLN~URwfO?~Gy_}6TVzX4nytkXz`R-z=?UVhvjCjXu0;9v^8M@M_?(O4Zynqw{pd{Kx_sA zU%^BS=rGK1Dpkgo`(lR*mso?n5!^h8X`ZN?)sN(PEs_FYM!+6o&n2iUWz@DApp4o@ zJvypgzWtWWQuOnnp-!+A-+~jbJaKrtG+cgirYhHWaerM1J@jbaTOztDPuw4VAC_M6 zoL2r}*@58Rj-~kgD##+B^qkb<$hE0hJGM%R^GZ+5FYSpf^2e7FC4UiEitoE?$HtM@ zSLe#tDw=RlMzK|RtibtjXY84FNT5tJFL4Bx!u=TD7`eDKrE&5UYSH^BmjU2ee>T*W zk^x*R%>X{DU3KeME|M~O%qorThB1h3$3DR`um2AMOX0Bsvw>?go18M2maSBSvkF`C z9Ohv6<)_Hns0q-5_5HSJ>g)@rMRQCfd<7FY8-RCA_S-Wr>)F)PXBP8)1 zU?NO}rwy4vENd(g$L3R+79w@I&_p714q~|d;k^kqD%BtM^iBVZxB#?IXc7?@2XQpS z60pjzPdVZkIaI*5<9fsIL90}r&9$^r|7IFp(m{g#z?NX2V0M1$M_*gMkn$~-NtnPs zVH$QJZH>^i0zYPeA8BCwgYRF-vGMa5u4%q@FTD?=L49*bQLmc9a;P8E{a;AjoFxp? zJh3vYhdgjYITm%inT$Qh-tupHm+Z?B(;RC{wl3iufu-=6hi^4@JEpc>Vj{SKAGk)b z6sDEFt2&@$m9XC%PKo@7eCzx*samDG0=5e4;|aN@t4;&$0eeO%E*IA*j$JC%{@NdPMOqU<`xk+wCPBPv zS^SNRSTPUAV9WQ_POb(W(|}Nchf13tf;Pwcc%pM>M>+A9il%243-}6de_RrrrDxMq zXZvS-;Bs;8VxQnC*&%DWR)$*M>H2{iIe0|zXN%lF++NnXxyY@Jvbphr$2O)_DnGXh zDKKJXYp@KD4=l9-+TZY|Kit>0+R4@>%$1XNRuk|QOw@)tOw}fl9ex2&yOV-DN>4h6 z$%n4S5KLgHHP9X*jgv|CGv%vqUk|mH2lsNJU#ny@+)MC?!ea%#7;@Q8cHC%Bcb-4P z5x9qA8g`ftuIBi#>>MiC4w0}FZZ)1Lh(50V0fdVUPs{_`*T9(!zRH;lsQ17-SVu?5 z>$lz%YBUUyaL;%)C4gCcEhJ~otmdKwoLTeLlP-@bk_N}8b7v>u^Aeol6oyGn&X8*P zwoq5!wg=0VZI%k#noJV#2_*Q`2>vvZ@tO#^chk9Izrwc!mxXok#Da67^7P7rVC+zb zJDCDYVSVs)Nt~rS1$`(&Fp0QrQBNb-=VbJp{LpI<5 z*#MkIQmdw1aQ87$_3uM5fy>3TO4X!xO=_C+m?iYIc&*)v~k_;YF+V((ZeH z9D$<`_7A?HAbxd(yhKu>9KM1HzIM;}JIM1QYf`JA8{DYHCpzE}tWq7;ddcZOwhIaG z%gR`4EzF{Z)2w*H?0Rwfw4zybXF`O4M-D!-1izyUr=(S`&FtL6=&fIrBd`<~$5g++ z#Azzr3!uK2?@0K~dmM@QQzM=f98KSRFo-Via#F%qFo9<~IJK_#AkBr?a5^c%gd?yN z7avvkkG&$-FNV`$p^F&Sfu*od@KviSYt@zGBWRTm*SPn#F~NJDIB@|RV$+*moLxu8 zp5wN`KEbJuN40dLd@ntJzdOU_a=8c>+ZEz!`n~iOKwv36x2rfpS!bA&aLJC&@X=uc z>%%!p>D`1J_4bloJ`h+6*Y3ZBs;Aa5fA$+S_Ha5x9K#BW^4pNlK~8PwEU$5VC8Ulw zqJI9j3`_d&f$2^yIHnWLryJ0T$J$@Oz?B9Qdj1$FWKDz&vD$v z5eLU$eO-kuyO$(p_v8p1;V=!SI@Yydg`V)eEk`QhJPMy*!pEzEqp@o1#o=CYRDC$v4Hnca13`k`Sb8P_|O z!gT2vq`6maBx$#HRpV2uCV(Z%$#1XE&17@nw{mXn-qLexmHW*h>W2=V)jiZoEgH_e z!UQf!ufua-x9h= zrMy6g;iRd5iD8GkCVTJo=FVFpKs2NUB>Q?4`M!Yp%RAsr4s8&R0RCBd6va6WbO zN6Vyl4<}M=yLv<4(lfTk!x>vv@LQ>c$50EfbGdV0-Do(=dpDfrjZf>r1TG0OvJQR! z?|I>vz_oyBSp7(glw1=d1-k*0ORX}TbEa6b}2wXpy zhNt0KOQff%j`U%xRuoIs0UgDfV)ALVTdC&;eJa)Km{r1v7sILX&1?Y^xOOoOPmy0Q zl3LfCPG^MK3s~yo`o1itO$nKlGmY^?VW1UJPPAVAaDN&maE!vVO65DfAA9j>CcWN$ zk%Xllf{ra`ipc@+*8Z4sVXY(HYb51na^Q=~1eq z?Af|iY3&+f_yf?f>s}(sbc|#?F~0kE&7@#od25YI9D$=Vrr}Eh&mx$wW0-s|(pkb% zC7|PD;W1LXSqFVrg1$?!6pn*DQ90R_+SRuas{gJ}7yj~OzF~!=icu35ak?*? zWB#5@J=1_Khu_M#dA7s1Y$59_7)KW@+sFEMyeq8);_&+`q(k%CT#Ujc!81so*0hQ7 z0LiJBvy7u9j)S-)cw=PBRQmh3L?({dCt(6h@qR>gbf>=VXM`DVJ_}g;bg*6d()2L+ z(lqu-rCOEVmkyX;Q?6@Li?uECWKFBWY5r$>Fn=?*(k~$f!WXkK4ZFe$C(`AgXGog4 z+a*kN2OY|nDJ|j4l$eJ1YaKo4&06*472f$=?87u4cawhFP^Z>Tbn~#~tTWW^{C#DF zF_)*aHlSk_e3f|Kl?4pzgD0b%CQ$3bZ0T@lF2MwjwR}vB^%+QYbIZ#9-`oX!#T@jt znN>`T*RJJsE4$SzP_1hxTCdJ?2}_j+tA-kVCFJ>L&O(@@>>O$KzEGj3WGR0<)t7Zm zeMBs0?q@&YchadsvZP=qD+l^IR(?Sq+U$aUB`1udJsvfYp5DD8UH{<8p2VLbVOd+) zFCZ*_GP2ZsCsRu5-1Q2HoU$JXi;vM|jPAML`WN0mm(gX69Vb>hs# z=`$SIoL-W1y=k}87q{22E1Qc?)*eVVu z-r&(W%7Q({p9{o}&!RIhnR~4Z> zQpP8f8eY*{y}^nw^u&Q9p9^y%{u6Mt#I|D#VNJisB-&YZPH@R})wG6|+TZ0EnX6sK zn!xy&-8_y=`Z=FreJa&Cn=-UZ6M>$Br@WX@gHRV~s|b2<852dxA(!Z8;sdBzSh`I))CY>MaGX zy(-`sr3G5~=J^cx<~dJzZ)qT}4zrQXZ(S00kIfJhzBFW#^;nmrCuP_Pn{w>-V9ELX zvwZPntD0=b0LdA?40P3$4leMQs(E-(TrSqfN9tMN$AR11NM!L9E+%3rOvCOrr}A<$ zKY#hj(>4TKg)NzPXqy;dZOQUI6{|9!1#KtolJ0z7E8$3nV=#{Ma7JUfCDQs_cR8tQ zRf=`sa`D(ysb1Ljmv0X>mVdu;mfU}sGU?fKG23aZ%Ye@<*xcWHMBgrBT>>nundQ?N zV$LQ{uG`H~&JP@^u}^UF z@Hau8`LLDzBCWE3TMg^Lx?$D%WguO5d$(|V#B8oTunvC4fiHSe%S|_>0QQ2LKX9DK zH0%RdJD&DSydtRb9}s*66a4(KyUA$!v-N#ppnW?ow&NKG)9}>N!k2daaZqwidcegi z9Ha0o0rzTSN74;d)(h94pXMSpo(*`SqTd+mG-jz#xlB4|6(;cP1JCGvC(xZ2jMFM? zy)NMy2V2F@2C20J=x7op?C!9Ki-|b;;P|LgMOB$h)q#to*I4KTHuCCl+x8jvts-sqXh`N8@+>km~A8DZYYZ7mluQvJqr5%?h)H zs7bjDYsa?ZSpxF*zUAcw>$XaPlRT*o-Ugho^t*U#-19U%9{Dlo`+h3zcWAEEc)?(< z@8aHvb0YZ0;a(&8M-MYOp>`8a2abtYAMA}9XiLpwBBcsP+sZiBW^{LDnHAoVkBe%v zEcopol25$*RfbH)8iAEmYbHIf+)zF{fhTa>#WZ{`b?aUswCNn7XjLF*6}AMoChWg* z3!;mk?3FqWagy*AOej7H8Chg>H^uWN)tFSNYfJecoMJvXX{MMJ(3xEmDyCzruz#?! zeV~_gXL~(a-PM&N@SK5Zm8x2PB}uZXMq~Z^!k0b&HzQ+9CP3{DiAW}u)RtgXr?(km zR&`hT-kl~Cmy0dLIU_uYYi=jl9&JT?)+C$`TrS_+1NN8+50{Lh7T!-JJW{cgayQ{v zc!Z43Q%*hg{~ga(!+lP|s)jO_!a8{3{+xr-;9WzdCvg*LotO6PsLL_Yrsj_{+%x#` z(bR0Ols+er&e=4VvkI4M4_5tH8bh`Xp9oet<&}^{&*oC!N)neLVJSXdncd#b)D6RF z$}b}UU%>>0IKmI=Nx82Zu%vv?A5Yx!Tf=qd55u)Q~-TX(z@a74z0 zJJ1QzaYFq!fgeUW^M$gi2K36CE))}33g3&snVDW%DLU}2@brKm#aA%#x{ezQJds6= zcJBin3l`)N)s$3Wt>t8nz*77iWqI2}2>Vzl+}<*T;wzZ20zb^oTq7sS#DI>hXL*9N z>qh5#KgMzdmcsL+N|iI(h^@cpC=EUpR!SJ|)i9yx+tDkZypK`*SlQ(w$!~mIN;eJW z2rPwXYL%*aFKg-{^$?q_a;EqSChWkE0X<%kdLI-Wu5b2{B>$%HHN_qrfu%~oDq-t4 zk~k_Fh;l=xv0t0au@q1?( z!82p991~F@U@5GFCu(oo#A3TR%A+sYayqb75O_Z4rIAq7N!eR_rPf4NwtO(NXrYzy zNW~+VkBR;r3k0*~qvVL9ID-Aamd%kHbf>LnB8IoE>;zJiJQU{$1dIU#POvXi{) zk0`;j)o8i#s$>ZhSc+f$uwUj+6P(M-ntpK_oY!Kh7|=0rzDfui=?FTGx1G!i-!+y8 zHFuLSfu;CWoSF@q(hD={%jM`V317iP3h2<9eJ9&HGzT5j`iKyCx2l|(+EvB`mclbN zynVL!wP4&~jx_0Z) zN+4@+CYK}d7{oOAv38jhGh#@n zWO(`khV{YS_RNXY(#1yTvmuEi8Vfy{XW?;DGGhzFG@PFFeJ*X-{ut@$P?jTbOvJQG z6;y60ef{c}FzvC##rAbz)phe2(ymSFqF-UT^bDs1bdNBNjkAuL(auvYU=& zn1)f?DU_b~2^FfWEW;6a#=*2o^{7@LeQ|w-w5G}y2}_*>s}3FCPtF`4%y=TFpTFE- z=5O(OaCxpha2q^>_a<%`cS`MKYm}};xEXZR&SiqjqNfb&(19O8^^?ivGR+y*2fL|) zBjjsBF0t*W0nml8c0M!=IpILA@vB_E+Q5 z4B0@#S(Ep?s3zKi%*d@PV?xnk$fGe0Z#7<-K{JxqOWC2p+^TF6=qP?#PKZ1;lHn+! zQk{S7N!M(wCa*Q|E3K=$<|;v11;!B$(~tqQdnx7a4wPcFLuA~}lkYjOHoB7ZPm#+` z@@;-*X%H>^xJQ~e#ZkaBKp0r{XxMMksc<91F&N&QjGsU^*qoGxkL=13#U8!b)yPle zRnSg`X_YE(iMPgd$xxczT_s~3c#gs}w8!vSw7;*TP;;;#VJRG=c*31bqYIz)6DF;S zknj~ul!quWJu{CitsVz)_wKj|s$&_%wNfw_`v!yOhM33`zY0zY(W`n9;y6@T5~O&&Kg-(sAlwB#8+?+Uk853MkmObr^@^h+%{gwMja)&tlRM>w(7wYMPZZ47QlpAqtmtJkf(blQF%3_bS~sQB=Jk~8KJ*}X zY~yi)U}+nG*fXLS;Buf~>O3*j5wJOG5PhYdZHdqQ~rt{KH`fc?P!L8ShrrS+nI zyHpBxb;k9B65n=g?Gb#anT3Ik6JKluSCU?{O-zLoQc1+ zw5Lrw=Y-2kU9eSaq1^gzSBTBRBaH7QJsZxJZ|4q>rk^`c@Ep~?zcpiYh*-yMtP7s6 z;QZb1TKb}4u}kGXoi$ho_7>}d_aM*1dB_!8kPUU(aDHIhdC%*17%2xFjupIh$0Y16 zj)RznXGL2k$W~X=q>^AFU_bCv0PK@WwHkU!#;+qTDR0||xLn-FoS}B(QZmVj6&0X% zwO_R~*Li_+Z0bU;C*t166JbEC`?)}TG`WHc?uoef@zJLm)b5jkUSdW_kqhpxxL0Bt z-Uj@nl_!Ob7WWqn&|oRtUwI-2YWIz95o_cALBKs6_Y6$y_jnC%xh-XyakQfw)XArF zFNoJh$THz~*sY($-^Y}7gWqfVza>Kse9^yuPQwoFOpL1Mrp8hVJ?Cv9QC)i_{!4t? zanAmpLmzb)kTUC9R_Gn|OT+{&NpDq6kBJUeGebDS8)z#y1EAsP`y5?L$PAHAMyU=1t+#4tK(2jopu4&iSTcNO zEV=u}f?2`uh>8bD#QHjn@9oMCx=TghlB!JiP=AAw>g2YIT>k9GNnu*Aqkq&?`$JWG za|8pr#h`8E;>dLzttSFIo^%*SdvXLWw>((5;nNQC^S&GO_V@iSNvG-o-S<*oS9inU5!W70*3TElpPq2D&9N^|_vWm634T;R8AS%ECo}9*DIs6*Xp=l_TyGt|f{DjK(^pUnqm=Kl zC{~TyDI|w}@2$oJmO2N-q#7HEah`G_P$WdrD&}LI=V_+7tbi-g5%)=(C&#(S$w#<& zAbMLko?N}tha*-2y?^#QGAQ>LN9(N$Hhr8lvukJdQji*OJcn$GNMN|!NcjI*)=ko) zd*UBIo<`-^XLj{hW2-QMOVaCjzTlPJl4}Fi*b+=H0Ud71--vyKq(3@ZusO-iFWYbg zmQv_mQ$G>!`^Wzfr}ovccgg6h-lEw1;s_bgG?pn+KT?m8wI`0Vb@1D7Nd|dEj_3*b zcICxMHue2o)RPdR6ld>Lm1K zMPY?z4AY)>Wreb_P_dboJ%#^IWL6ZSD@=ph^~vZjpB`pPrEj%euELeJA1ewOp-VUd zmjpXfa%R(UM?bL9Iu`*G*MW|Xt0Z*mzKEkCZ~rw~&aK%}7$MyiEI+nm52RI^%-*A% zaWp8McT4tYP6Unp^9{G{W}O^_Ob<2Ij%`hNbYB$9Wg*@haBR-~O-Cb*?rVd<7F{z^dzuc9WOz?IQh%8u)tg ziT0cOsBsJ84B+26Dsg#KV(-Mh9D#cbru90s?T*`(%NwA^S1`e68A^n+XAbtJ5&hKo z3MQ1_yC$TQi|tFslD)+VPHb^3=eNGY@3yc~&WAO8G9n8}&;`On?eSx_g2-1#v4 z{_?JjAXsc?xcBJ&D0?&6J}ll-jdL7K^F&sik+PMSxzMM|3jy~f+{cvlOT$d0*D>Y# z%cMh&y*M4XT-@LEM9Q-vNrg@Oay_vIczbR`MPcbaXNIkX_iLeFtzWx8tO*I;encZcbRNE_G-RO*L3bE>a8rJzPCCh&ZYX}#x5>VzcqOLtY{k%P;{ z`HG%!lT{8^`uE@ntPj(0<}%b(y(SSZB@U+PSO?CpF|F58v+X>4v)kV4<4`|_J4HP1 zPQw54^WCIstBrp=ul4*^iuL>RIy`SUNB{4BEr~C4vjqCsd5<%hfI>us*#G^TMVM zC2jj~1oj-$dLpr1l6`aYerjANnBYCHV{I$=ew#yk^^lnIoIJX{hP?LrdQvl_s!Qm3 zH95R`gUjblRvM35cI2{2MU7rZO8!NMJ39t)?Xd+sH)I@GA3S&7QeFy88cTb=%@MGU zUVX2og|BiT#j7^BV10TW8;iOpUm4y-y#dOFkB*YKr-!(aibt?YB|O(si>bFXZadm& zaE4S%SrJrM6uc95Gh7nv5E>Fn=dO8A96S0+_zEWWg6%g?qkNJ$OVegN2J?Hvzd7?rG&wfb0JWOP`Bsfhsc9J}}%QiA;fGps6eh7$*6Uzzq zO?NPCp-NQ=zF?m-WH7N$F2gW^r7WQqZndcbtH#O~?2ArE(CV?PNxMO-IRZ;5VT#*m1{hZ&YS4^j=|D+yB$tYAEGEw!5LpXWfcy4@|^HEH{$A*m5L z)+HkQg1Bx~3(_=hY1;CxW!RqGWy$aeB`@hs4oNl^1L*l?PXuLGNJnc+;%p*2V?x=5 zXedeFOYZH=u>Z2Q2iHq*tHpqY^P86uHuYC_E-Rzf@vvD^O)GDXz*7It24m{pPi)l! zzM2MQ8Rl9ng=xKxpz6`d-jDlm1eU_>1U>QGami}fK)T?^9bs9Nm3SD&T6A`I7hDUx z=P?%}=xcQX892Tp*Bfvz!L^{bYEJJi$&Fk2sFn`D$p z;s`AD0QA*ZUR5Yu5ca19<3rjdkI53$SO?BBu!Sns(7tifw~mvj&d!7DSGcBeR4T12 zIqm%}hrxM+b-1o@{a}4?n(mws8ozX{V3+?&90VS|8&XZMoEXTk?bs(cn`%=8Z5ESA zRet2 z&vhN2+SlsRmm{#01Jv%kk}`t*l&Vm>6=!5h!+Le3PNy4kR^fKW7Q*{Dki)%wy*zDb zR;6_O6v+n4t!!IHc#>O-@ppF&h~Qo=(#!WxO2d9&0+*!s!*luXq;WGmI6tuMm{zHN zEX|Y77FVM$r`b{5OK{J?KIwHFKOF8*aW}t`>I{DP*HZ}@Co3?l58fUCKQwFZom?{8 zg!3GGi|Oyv6O?a8(A-z6Nc{OF1m8R3l~lYE0$+(a9YQbF z>PYUytrD^z!i^h~ON=+Baw|8OR;jv&R+O`x&k8p6x^QcjxVPgvggq=*w6xp4#_Y+n zhUpogBfgwS&IesCUDGw%`X8~I@>=wPdNXtSkL-^55AK9B+Z~n$zZ@>)&kLmf%c`+S zb!w8N_hr-Zx+s5_+PYx`ebLUtC2_+yg73qXS}^Fqy7jdiuXGo9i-itFuPtIVvHB^y6l{*P6LHoz9b z{zNOt6K|AfGwfdzT#LBXu!WE_KyUYL`qSyouAgc6&J?eB@OP;%f%xI=p0;Uw21h8p z-SB(})9^lL>@>Q}WW7{oat#4nh0EnzFf}!TX1@<$M+U|cEQRTVP}Al2?yM`taxg!B;R520Dg*Tu&~F0_eCiSWD$!%bA7u zJ`EjWnXrZ6K@rw=4D6vDA9&Bcx+4mmKt+*Gg*0pGM-R+;>Vf?lF#<{QDYrg zihG`*ik}%yPcNz_JziT?#5#<@lER;xNsYVkE-(Bx=!0i>i$dhiyT-8&jaN&!EKJ~% zU>B>qmZlBr!Ayb}HRr$dY)LRF0`a5e4_5({{8dij_L{RHRr&)@{ z4vxT5*jklpd)IJ!zjrN7+opA-x1=Y7m)c1GrKwDLg5mt>9ElE0DE(b0LnezZB`EVb z?5ruWa1k0F%9NBlUc>VNOyH9A^We9#jt=kJjw`(rHW2tp1EwKE{(4YqAvdHeoI7#x z3THJqcIkE83+irvIMYjw%T+8itQsjg{^!U2BjI#^&o$!vaTWjZ+#rQ%c)Pz-1Z@>R zko{Pb!?1_pQ0@nltK@y=Nj4vT7cRR<-ka#4t`1EcMb9tWz$~j2a5|nrO`FcTNBX)m zhH2PsI7~~wE%YVB0tAMoBB5NvGbo-&3(?Xw zJTR?q!BMN8*fl)h#;vg6^%9;y(W@Q~< zhsZ`}&FVTs&494l|MkgI99 zudOtlPTv+GOo{5w>A-zyC+Jx8)L6)STnlP94Xny~-cwlUa#Dk(a8H~H#KBpn!jRn_ zK->djU_ecw^45wHUf;tbstgb|g=K|6@OBuxXmTE$7p3dY6l-1$?TJEkj{RL z4Tawa+vgKDMg(GFPO-+Q3}r=Iv@-6mn7}2eRJRWli=&JhOC@klJSK)ixmlynlK4+) z4AbzQ*X?4BspDd)ZM9h(fyWA_RjTozBOv#r^l^NUjHSkdj?|)LvbSF{SVDvu5E<;Yh3}uQkTIJao8F%WZfjj6Bp!S&GbiF zx%-UI>6pN=3)Ar4gj6i9-WVaTseXmaET4gn_JwOn;z=*Y6Lx9En)P0DWRJ-H0xlOv zHB75in=^|=&$`p)o@aLnSn3z(_;7X;8Q#-|@kClev1X?61lf1&4UWK36w@lz^Q>YK z9=pgnJ<7ry^1oPH^Y}<+9=C(MjIP6YLfvAOa528KSX^x;9eYkqR!pCl6f$9~OW;*I zVso?5B|IqH1-C4WsAI*N@Ao|AHa_(^9XL8;eJ~GREf#Orc9F??D~hFBfK{C|v1G)( zUm{QF;)^wo=B?%FnO!&n&jy%=%<@LDSk52j(aNX@dFtMco6BY_)KV;!1+8gVpW%tswdOGI=AYAF0r9t#W1}aeb5gp<6UFW*p*|nfj&+ZgUH3F+r z2A3E1HL1vWVw^6RthTYHo2xr>1kMvMtx|oyTr8ei=1#8;H>X(21ax$$S4kl8O&Cw~ zNed>!U~l-~E1v{R;EV&)P`iinG&`pR&_^S31uXRuqEGU;s=}&74dV$b7EEqhOr{HV zNF0H)7fh>EVHv?}%+WAfJguXErF!)n&DQ8lg^)&r8Bds}<%wf$B4~1S0l@^$mM{&w zMNS7ZT?;KWK0JYY#*zVkL|Ii6(h6oXo>=&+x3G4QC>VQGjjDcyVN3AS9;^@6WYUVo)yV!5mWl_fcCN1~ zJg`{Fc%u86VvSGT>9qCPT^wNvRdoTC$b# zgxw{GqM9M}QIE1RCUBOCX?QE;Sh4v0o+s_*Q(wkXTF~L1R$g#Fc#!c#&nv~6tF>Kd z&-GRufiqT2!`*g#vDnSLH4Vt@B4epw&~aGzn7{5S$<$e4zE z1IYS{8+{alZAQviYBcD0U#p0$ZI;S-Vj5(Y@n!D_xjOt){Ydl0EH^ zS*$q;&(`YBoWvsZ{LCQ5Q zO3&&!m*Ojb6NX$1zIi{_PwwCHJc$t{AeECQ7#N#F5oMe$b)gNChN$QBg$8M zu7FiDCk>Q^f|VSBrTDv|D!XAulTygA1HT2u!=np7xL6V9&?4^D@z2EB1;l9W`pKrD(^Y25x5_G z>me_AP$Ko)eoVq;VI4ET537{JWKN%>;74lJG4iAdnUXeV8b@F$ew|?yc;5F!Gr8qd za~WU31i$*xxM99f&$*K@TsMNt+wnao_77GK+(V>^?@Z)z8QwB33+v!lal)Vlx6axj zE#1^X##b;g0z3~Mae>^sp9Y>!-10#>`fi`}-ou9@uoRwm;avc?Og6$+U=0>W$oL8- zhN5f$p0Q{?36*Vggd1CW&{fqd66Yh|G+oZ=XBDGA;}2 z7!Q6_wf#&!97qN~)_@<)D~AgG%lmNzmg4i0iYqG8z5iLzv_>^cGXO&-tjr$uirT9G28LZ0x*^@4RTU*9gFu`Z9rZAshvaU{zu8olJ6-?k91>Svy@nMv6L#Sol znIo_i&b8oFm8fgNss0n_o6JBiKgR^li6ABp^bx8)k%h>q0koGYN+S-lB#~FTyWqPQ z{*FaiJ)dK8!gg1hn;O@sC)DWX;%u@z=sfESzdvq&NsK+tLhUL5lgfSYQe&xy zKukKYh?t!p#Qr7T9p9NWXbMl@xfauU9XCvBB~QQDM~$V-A+tzb9Ys8>DzkryOLwD_ zJa+fv2%MK-TCcxt&-G`ofS-PBmh9duN?`j(uu+AID`M2uNu+uYlOBXGWp zX}yj#vA?Y&^-yCeHR!0q$_ZO7uZ#Z@!@eBq7#715Wq?=^S3@W+ZqG2S*D=dzm;H@C zKAev4&`S*WPMH24h zmZIw1U5BN9fsS#tYYFRyc4Yq$wE4To_RFt(s4;O0i0G5Gg;fp_4AXi)R2|>jmp$Rh z5i5b{Sjkj4(sUQYw4R7Mr%rlr?!^%}wqsgPB#r2u6sGl7W2ph4qZT|-Jaq9i`9Gb9_+`f7Uh%xuI)ccmFCjItz5nsW? zCZNZBUqT9AZ2{t5l$QFutjZ#$tGTkU6t-4hyLDsVB$@kpt8uj43FThfxrhX}+sJmq z@5}EZ$+D~K|I}6EqB9P!uXwAmADI4!kj>)*)!!aY~H1nVocN}hONebS1K9d)?X z#)2i2qj!C3@m0GZs4v?xrsSMM4VtS1n zd&iq>CI*-yFx#DVM_GU&yB z9Dz%M?;GrlpyQYLYUZB5&M?sptZF~t3TfQoGDpLgXl#bcHxqUUu`jX(?715dBd%Q` z1-mYCCBau*7ip=qJ(NUjtRP|?n85l}Dw|28>4}J{Qepc%2}jPm;8Ty1@1$piY~~L7 z;;p`tYELgf?LHXGx^4)ZY7dM>Y1aACzl$^AlOu@(jb)>PJ+dLwh@m)`K|03y3F!K9MsC znGDlaC8=0Ua%UstF-?<5>v& z)^;)#$T8(y15e99x?p*nkkxOp)DmWv-_do1Sifx?flGq-?qEbcs9T=Y8|1ISgci!R z-ES&{E{)-6*n1AU^i0)_NLG(2T%F*y;dRV*)zYS+%}Hv71ss8;W`e%w)2aw2_KF|F zqhVIt_APyRx3LUMVQ+atX+i5|X333p-PJ3hEJMCC4}NcXP(|ogHHKlI^zG4Z&fP!SPJ_DJGQi1>f#eZqSkEStirZq3t_jqjh3cP zn@<*6_8>!`mjth?FW8)$#xlT?I-|^l)8Sz(9e&q-Q&(_3KOd~xRYprcz4RDz|%3F`}5m8c{(Em=#Qb ziaB7yoO2cfg38RaIj;#L=A2ek*0jdAE-dHyHv8N656`*M_35fk)zv*S-HP(bkM4cF zx|~G}>~6*=6?I@vS#|YlNPeI03z{Wk?P84{AgitwEY5G2v()aX{L$*ni*MPfW#x2# zvZ`r_6K^bL=t#&VSC2=lWpAxw#Ws(W2rMnqiqfKZglcnZCSM;{LdOy!fx5F=@KSCq zF+Hi72}_P;!dl289HUn6ch_5*-ct#)*BnU8>yORX`lz=aR^s+I&KoF&HTsKkda4!U zCpLOgUELlQrKUf(<0~#L(@-iet)pVT7UR8UR?=mn_&_=_>q|Fw>_%C3jA}Q;#g1QX z`&hFkqSW&ue9?o7`VRWL4KKuEDe`IC-L>DIi%m=sMWOjl#nJHA)UV|}lg zaaH}4S}in4;Tu2C);bW~*Zmp0_$ijkac6ss+B?ri^X;CTA%V4kw4&tiK2)9haHVm$ zXD$P!%#^RQeICB)$#G34hTa>c&hf6mFBYu9u^iXQs*6cBd}r`J4a-DtVDF1ihdp*+ zpTSih)Q|+q}c~^5E;dz)a9c$u&qsVbJUIm=0x{29E(xaEl{zoye-Zw)a`J(&M$R^t%;%$coPDXL;JUCt6J% zQ&sCQ_YaA9OLX4u8Vd*rmuPy+;;$IhCw8IsWaWnx+H zOMQII-nW?Zf9&E+85y{L#Xv3**fWq;lwB`l)SBl{m>acslj_P++KFeMu%ys|Ir`P0 zA0t%b$U4^fcAV56SZ_!xiu3$2YK_hh&B}w8Jf~E4jmkth^6fT4y9;+K1wa2F8uwIKS%x2(SV!MTnps9kSU zDY7?vzqJzmzEEo+bF1>VR)&5D-dM;Et+SklXz{yEJ{I)Z6jNU!uojTcBI-^!llUsS zi&R&YDc=zv> zj8Q#o+8SdWquD*0g|qjjk-(g?ta`ki`}{1>SSkk+m{S%JbY`G8uTWJYuzrxH@9tKP zQ>Rv1p}P-r;8;Is3DyFwAZZM~dQ;IzZLe^Y!qUpb>Z390@)|Dsh|9aoXfM+9sPB3V zieaNx*QC1oyfIR2*fyRQ7;h!j6-qs$I((~4Vs8!v5z*y*jQTlsLy8hmj-k|3l1ln3 ziapQON|%Xtv>xo9tEn+Hcba)5Y0p0_k`*`F==X_e@naloR;r_pG=0O{XpB0zW=Eq< z-Fy;(`+G<$iYv_@<@4Xv#;q)tXRARU)>w>DmN43Nr!7Rpww zijGmkD;zV=&Ob=ffi;c#vU*8K_#p3bjT%d<30%wKT7-63M2y<^kM&xJjhnQh#~q!U zv=+_YpUKiub<1j>!{t;Hw(~Zs=~{QEusLfB>)1|oYQ)7TwT*Kg2e}jg7Bpv8iu37q3^h);DA(=c}hd=0^-5mzoLT^su2@5yk>uTSN zd9saFV*TW^MJ&F=Eh%(=lUL!_kk)UO_=h52tM-< z_HK164gGu;;dbSNcaIh=Oc>YV%3>7JbBa0h=+iB!w|8hGgkfG$$61^+P(#s_V~3*81A3si`7q&)zk_m3JZf`^ZK` zc*!N($SO-+J%3SV|Bk{vOelqW0MDqGI3CW!58ONY58?g&y4R?-0Vb5fog&MwT7fz* z**T|6{}9*Pb@#44p`{6XAMPQ3BBIsL#capN14Q)rdyG1&fTv-9@VwN2%9HI2r^d2l z`&USN=0W8IWGdOi9b zJ34}Ois(XC{q@Vv+`ryvF~40uj^h9c%t=wgO51Cq{~+NLen=v^Qoe=GO=9!9Iq68# zyHTI)%(avHiSTEaBm&1E(sW;uyS;WbvXeNwF`tT3eMv{ligE0EI)IsU*Wo?Z4v& z-CncaTUS)ASVKjrVPuuF+cH+Y%TY}xx<9isk8`gj#$7c@#5HR3Y;S-x?biC(Yd1U` z#pjkSRg@Y_I>xuz!V2@HnoOjfi8ac{&Ny(2?jW#~yu#QXDZjOqOO7={w=UebGuu_L z6>fDpNIKA8p+0&erLMi!XT(io+4nH|O7nm5=LE9K&+7m?RVPxDiF>#0%<1Kh8awWX zO9Xlxr0LtGuVuu^v7hwQkquQmhZQ{c` zdB_7v1kQ;_)4c$-?X}~*zVo<)-Bpx|Bps_W^77SRw`ekvcF)dyoIKC%$W9W0YjUI& zCEd$j^DgYJcD-C*MX5ogquWYb-gxMBO(s?izM)_G;%5x;9wXi2dTd%<&8C2-{`$*A zKdfnb6Y!~>xf*#Mo4s`<9k@$@`p8pPv)2}-H&)~Bl~GZuH(8Zl+<{+QWUb3Y4Ee;| zty-!VJRBtgcfXLP_xj4&Yc>mdsSTQ@bCl{xI`&s_iKb1Hd-4x>g(1V%4ND~hSGy;fpP zw3_i-DnltV>EO$p`R!l*beSl)J?A#>+V@9MY-hDMs3wcsq^}OOIQ0iBeC3;kxHGk3bur3q1 zz3k1)Y5dJdZ!8fQe@=Gm+j)mNLj_8GARTSSzhQ04UDRcwwAtPqPvftQ%}9yBs2FKlpBIlX z76%mI--<=37Sw}jvH&3Mz>$E0X zA~0@8nr@J+I$Z2uJBcSW@Zx9{S|UeFZa3|;TYJmt1J1?>%r}Fq^4xKj#W`HoWgWk% z_U6d4dv&+GGJ((Kk*1TssN@mt`Wb^L5=W_zq~pPggDk4pAG%CbqW0M3Kg(END?%b} z!s-`kI*awLoi_H_CBv5@ag_Q-I$p2b%7W8R=rXakw!L}T^JhkxF(DFx>m8&OMSEzc zeK_kN7EoM`QdZP!OSjX?*XbY%P?U^P&ZMK?n91zr`Zc;t zl&)xRwxtpK^-L~_!1Wo@w8QenPTO`rTzsM^8KvAw$M4&tSlqz5x=hR{WpD08BlcDI z?Gl0OL8R%ctz7onq)%gn55>GFrSF_20(U}?R+P{J z_FAWJF`^1ZuqcJ=OqmFydC)SNzU?i?kQhnvZuagM(sa^os}07gbE??awwQ`5EWOyu z%#|0TmDgtaZCQUVrS+$xyq<2Cd~;u2@xZ-?it8mLFef?@D7kWSkf)>g)w-ob;JOBB zI)R2)GwOO25Vw8Xswj1uEZJ9lH*5N8nkEzd{dTfD2{()aRl_6#S1Cx-ZM1W3jRK9A z8+Lt$swm~Sccs3}ILzAZ3e#lbZ~;f*@}|0Il>ZUO2ohs>`M&LLe-+W2wHa+ZC_75h zf$JL7rzlmsItx3;Y9jpn!_0Gp_tJ^$MvYJ@VwH7VpS#ZRYuHKe6Ff}Cl}QOIM~jY+ z*%#g^$2zJrS@o-be(pOtN+M#Z?`E%YkX96f>dI))lwX-PN=2!2)E-7{K=M$v%z`M6`WkK<7tC9R$>H6y6 z+9g%Yw>Q;p_SztQ&q_UJdkH?Ik}HjYb4(LB*e>h3O3>ODzC9BZ09x(uz`Qj;--+U6^X$d;s+o|tx7^8MFHRUKZn{;ShoO#5!PP$CoBOT8U(3!}?t}rAp@p)N)Z++4E=K9aO0V#b?(EGfJ zP4t0I6;d4OxBuQIdRohew6ndBh`L1FdDT-QBq_@2-r44QACu(* zxcyIx+hyXEm9wd3N_DlPwOJxC@47*p3G>kMaJtwfYS zDU6EER120Eej~;3^o+h*E7PFFa{8D{QbW+tse zKO?QdXn|4~m7uU-l zH89^Hl&>Wgolmi-tmD53j3$vLt2$Qj{qkjusPw+6fl?S7%Ea^fH@$BDh!J`2=h09K zW5Zcwq2*~taOTsDhDAywRXI9VoLXClqZB@mkcsXsHyF)o^b;Z1CvlX*Xi_GklNTpB z3>+j13_2tcU8&8ppMM}t=YI6Rmy|KOlPJ46pA@~K6w#@kWnQvuBgfv3y>A!I3`@3;Wo1^aqTasw zM>V5HqspSUgIO9MC?$`m=oTA{fQQSBdq+d1agI{5XShJbr6%EgZlwW|heIDF`^51X z(Sp00nQ!`P$?Kz(JmXlNTKW!Nw(n$M6VrGq;qqK3SljtG^_iA=u;D^>`utfvmVVbL zu#x3Uze**y5Wxvii7q-f&8C#q&Eum4l>@a^q={t9hwvb1x@(qXLLq*eMa`hBHOEUVw|g?62O zw@K{J{2YG&hlmJm=d-I%a}%a$BsJk{7xr$|EFE*Ach5tk)XSd=v6T(wa!ezlTIX-9 zcgG7lwx*)2a)}Yw8+S@6Q)Ig|ds)hqJuhJ$DoTlcF>2ZN4fTEv*Qel^KuhHDQTf9w zZP@W~B6NBgjs%t*XD04OZ_g`naoK1pmOZ&H=Q*dlc6C^E8#0K>a*K7w79>o zo6+OECE{~HX};xyv;K;HpWNWgJ*QNr+Ff2DT0PwSBWqs1nuf6&5||TNr59Dru|evq z_PGrtR#U!DIu+*uA$xSBv-)n;#P43=mztQ?lGOXaQEZq;LT0OFdjq-T8KxL@!LU{O zoA1@k=s)%n-S@>fR=LnJiKe&0@)Wz}v{jj7&K^0&wwQQ0+$-UsO{B6oBpZ@(H@V=$XoNLIBQ zKb3tbZb+U;QEZmdiCjnW=^byK%^V-uV*)La$A`tk8C8P3dk<)0ilTg9wM}9#tKQMa z(C;cMPBYiQ2Riz$EUSWtOiJAJrip1ZNhP(r&E|PN)MM!P^zs*&+r?WFokjSb;a=yr zwU&snL}a{v!#ZBLC(&6%t-rVKa~K<7%IVdzbs(KZgv@SVYe90mOd{KdW10S4j&rNj zMEB4RrYU4eia8%&z44N6`5n89-j2R~DbuR|c~MJU*`KVP=%fXi=8)9bJ@&jo;0cMq zoamH-<}qrqwYSUxezSEX(5s<7TGvjER)4EsMGtg6EBQY3i88S{gYE^myWX7osAdZK zcJ${+XVq1!3FgEd)jF7PhFn2qYG1qvzxyarw~YUYjt)Hc1IvjgmXdp%+`r##mt1lr zFsCfyc0N1rz!A-)x>`p0KDBk^m8T@@NYlx9A7j*u9{W?m*UpqY9OjF@D^rI^v#suP zVa0FBD22BFi%=KMeYJn;=4Ph-WXY!#SH3fHk$#MR7d~H>52`UqKSIAJySnoDaZ~>( z`G7(@_q$aLGF_pRv#cCH_NJG9ntm6JE6q!{ijwH8k~dy4Z-1A%%_ZU?5jzW&%x$srXCjK8fQg6=R@0%7R5m-M+ zXX)s%_O;J|;07j?!ut6);nn`6_iOr^9Er_j)#TD8dA}o@|Bu=g+8l4cK`l%ug>8fS zvaEWx)6TnY&Bi8-&vCX)Cw>3hRkQTn8T%6VpO2+`UnwPfeznZbt^ao7)0({3EID~L zaN%w0J5rmkyi4Cf_TOwyd;EtPb>RGp`u?%X!`~pJ5u*!N(K5oblg+c-?T5K zEd5?|<^>x#BF{gyTcUVWqVJ{VrizsE}YT zo0+f{G2ef;pjEGSiNpOGNQ6bocWNFUHpyEe!7^p(=+xQIJFa^-i9o6HWZ`Cy!|blrxs)v8eqv#-VMW_Yb%jz$E6RFPXLZ2w zRHNmo^&Fp!I8(mPbN90jg_~=ZRq9}4FPmP+^5shhI(IkyL%ca(;82F^S0pf}EUT6$ zO-($R(n=}^5|~pKG2>A};?$p2CBl^~>DYJ|Yg))bLt0Tb(p+1nK^5laah9QWwB3p5 z_>>)NY>D>&^s6ua6%xlDH<>VBi&VwcE7|T-9W7BowO}_r^yo; zO5u|+nK-(T)`R&v>Yv;a%_xArhEVR(oX3 z{@`6;dQ%e;cBEtd{y5g~k0lz?SwwRiJMTsmGoX|e5tn{WV2KYe{vX7vun9irdIy=( z$cJYrzq1yrg7mxeyKHiAmOD=q{U!bGR<9?!Sg0!b_MUwQbB*mc=3EIAf6lgMEuVeV zjx>9sHF7&=cDUfIr+MAgu${83YL>CZ+x=d1(>cnkP~DC!%zlK9Yh2WwNeKU_O^MC6 z2PLD_FQT*8&bR3IrjA2c`l;6cL>UDS&+#_VJouSX%A^ctoyOQmwqu#-8~3``_@G1^ z;poVua%9k1qYFyd=(bc2EK^oFuD3nu{U^=NXbI|*by()8?#mbLYv$ETB2enz<#5ei z)_cqSAgQi!4*+XKQ4+e=aU!1g$Ir3gzM`A{og>#l}n$|}dD;lF%J26;+W zVK2clWf47EwMg8a7%KHd9JScrvIuMSH}65;x=OwTeIky3x(niPVfFF56vMi>+#Z)( zyRktVcWD)WyQ^WDvUHs7wlR^Ht1rzTIQQW!kwr{7TgtokefmzAdP(-|{DXdHM>05z zW)Yo}s(Qcc&{~SfFbc=G>mREMRY}^vSEDv-u7tYRj5R>)N#>mA!+2 zD^_|hqe+Z<{A4BlXT9-~FG2r-{+Pbb{6OacTwi34oE~@p*HIYtVZ9{KB{0z|+pNJ7270T;4&Yyldr29AT z$Xr_V)UVU;ac4WR-NCUmYQH_GrG~}4(ZiEu9SM6)tX}P5DdRlvO8V%1h94p3^n@5u zyHb6II?#WhK00mMI#esUB}!b4%Fj{i16gvhT~}77vRRjj&Z%iUY2^5nW<$b+%i)@= zyn8M4+JGk-T7@-2qdfHmU;8P#Hl088FQR(HFu#G-?@F|y)c6>pEhs%k?6~r~A&qUQ zpVRdF*|A`DVfR9+tEtwZ=C?1RM4j`w3@ka;DCVRnL*9gFws*pXRhgp(?%ZI$he$`{ z*FkJVKFh5=-=1_BrqrPC3i!# zKZBVNCJ%ul2lHJ=I_1&aB0C8ctp4%AJj>0S@f)-5R|7L98rX42Ts-Z4i@mXcMq-mYM)eJo$_IJi^o zZmcf47cooaKmv23XWLgow5U?)M%c1m!m{s^y^DkS&LvS$4 z0=jjStU>~FQk2SE%e6@+#^5e6) z_VT>!M!hH6TRH)C>Ygv==k#-~YgqnM9f5i`w zKf%0^z?|qA%dHUYn8`zZMg9b5PRw^R>DZRHD8HRxkd8)`L(QA)N~-tCJ78W&U{3T! z?!ypm{ zy{wlyk-P&&EST?M(qUV=G%w!Ja_9Z{lA-2C-8!ni}xqi@Ow~C7C3kiUp04>=sBUGxmlCn*qAyGG#o3<$_Ay(O0UDZmb09vKc--) z*=6r&^-^e0sT`;Sb<^!bw?oWt6X?8`%Jrq)Otb`dKj~YUnmx3y^tE^Hgh~ukkoc3z zvFlb@Udh~w$`SL0bi9aCThKT}0;L{O@5$aHrLVRMg=+Ilk5SLlSjQA3zLAc$w_W+` z<<%@Y(nHM8`;Soj(>O!|rQVW`>^(rbyQWyEMq^w}r?HMHNaX)~NKa@{lCSM&rnMQz+jed_kE5}UDMR$;l_oWCtg+?wCD24k0bUIA6 zP>n{cpxIf)6eQe9$NN_c+5B_kNr&Cd5c2|xr$5lhMFOSdeFjhWQ0*i|`HyJiVhR$a zNJqm$)7W~yeWXLZ8)BvrD_+pZMFOR)V84vs{csJ{EHV3X8o8K)L}AiV)?+j)Jw2Ut z^nMazZb0$0W#l4(Qt}RqpHrw7Y>C-v%&3w|qTN{?8EePl~50u9gUt zl6UTA*oSKKC}yYFons0TxGJXe06vD8i&1p!O(QpryngoXAks1+nudzy`ycbbvI`FN zf1vBNR+r_~Tt@1BHVXZ7sw;P>I!TYB-`00sdF9=f^BFcxcM!{02dQnWiy1h-wj=sr zC0Ab9d6AAe(HkjSrx^!w4^VGcUSwdLfCT15bM34HyyK|)Mzyp3GRJxLeiH7N$t(J} z9p!~*Jx?{EWU_(r4(dSN6af(N$lp_)l!K^4r{fVkA&E-6lvnRyA74*H`cr7^@?JIVs8vB4!e?CPRcf7P2bw zU2C3Dc&NZN2NI}TQRa~jyXRlc@d*I}S6fJ6PE@-Gs*8e?_M5L}_(?<=>aYGs{$S-Y z?&wIsGCl|NGl`y+dkKA?=+N%QdIJ_dz0Ao+_!b4DHf%Y zcc-5IB=-P;>t!TRH$~yEzZjcN?=ZB^K@#CcI^Hka$d;$2>PVBPrk)rV{nTg{)>+`X z9|_b=Z+}wl9=ra|NZnsj;BEvGn3JNcA>uv}?{W~{WYyw6)7X{(T}PUBCaC07r}&C# z-z$op6s2bG2qA&G6=f^wxZKZOya>2r;O-C-m=o>d5OJ7@Q#pthWL5ia{a8o4RXWm& zGL7o$aMKWB@0?=bE*BE0n|5(_mKSmD{Y9^dl?>diLjrT6UBnoZC{wkDNSK^oA_h@U zT<6e(H9tKo4q-k$ zn2t2PJLq0P4BA#-_~l7u==G7noai(}8}e6HX0gJ52*+6l3CxMc;MO9h?YVq}Up^mU z`C=gZ8w`BHC%+dS-@Cl1m*6LC#>qMsQVUjlG?W!ykxxf`^z?PxG@~r_^t#bcInJ+0 zptXuJm|8G``t7T0?>Nr-NMKGh28jqG;&u*V2U(SWDxGuIXN88eqO{yT&1geCU7g~q zV)TLp>ZWxR>4RWv#$@WG^9xf z)o$0yi})CdW>5tfQX(wohjj zQ;@*5A&v8b4q{(S1|M*unna+KrI%cZx96qfSCNhv%Z?ibmlswYztvSS1qoc^(o;(! z_CD}b*V>ek2$U*L@$Uat^d|?^60Y_RYGBAcjyg~(o~-J5%!U7*zW_y+85XOqH&$Ju zzjI7M0(TH7%7{H;1jbhq+OkU0S1IU;q_4#2#NOkE?ZM8fQ@wqX4$K#KLg;?ybADpl zS9f*hkOmTgQgVd6^kX@(J-MFxYHwwZDM;Xs4(+4{R}i~OH&7SbZe>WIlpIqZT6x?E z^9WZbUU6ZVf&}hN(fVWIapOY6{%X-X-=z2)rQ|4lv%@VTrpqSg`MQtPce~IyKOgdv z<&DgnV|XK9?dQJ^eX)MFOT@H&u6K|05v8b)W=DD{Uk~e(l2h2Jqc?LzeY{(3@%vRz)ja;Iv}(Y0 z6t4D)fW*3im(oSIPyoZRc zb3U;MaXm+*|I@)+G_L+d-xcU3uzs-K_7UCp<1W^DYATKM!W}$?-PyUuhu0ob?P4@} zh=|#@S263mmRm3?CB8Gp)hQqrr_>TCg^}JdBJ$6j%eqDgB0TM98DBqk5R+=XGf)cK z{5BE$TSl2`GSd}98TY9eM+ z9u=i59yL2IsYAqzd2`urm)%74xqZl3v-Oj4{I9@FPn|7=BdR_T$#++=u@fc|G56;$ zqin#a+VvB=3H;I%XJm}${{KYwmw~e1UEygfny-FroF3()q9r)yo03&$Kks5I_o-yn z>paQE&A&~?fmQt_&w#!ph=`3{4zr~b9EkWeD(Mq8qyS5w$3HCUH-}E$9PNgASc43O+lVoaEXSq zwxS#k|7cV@R!gnwluyN3tuhfET9n|g9_H3@ex!FlHcmG@eFm%d0tZX;MQ9Ha2Bx52IYWK-*`M@w zeA)r(yKSl|qJx{Wn&wIGEMQCc71*TfhBVjokK?uAPUk9qg` zpl($J=7qj1iF990u;PEuxky%ZZ2j37?y;NCbqx}jf&}_5+S3myCEUAs^ASrL3QR$7 zx07_7NqNGqUP>b!OM1RB&TepH0ZV!bOvyU7GO>Ea9i#rIG$UwWpg{kMepmLQ$D*zqN8c3|V^e$t zrl3caz36yq4>i?E}uBErx{_;R|oC^)j5iYYiV$g@E>MaXTI zRZ>q3 zQJgM6-ne9HsA3Av2C{GWARP{6zUi))!&FSc*`O8GZmls_*s>!(=oyQ*lfQ9jP&fT= z2f7c7S};5Q#JE%@HWqLYubXY;CEM3iah|{#0A~hzUVEdk*s%Bo|5drBiYYh);LJc@ zvQ{f4zSgi+w=Z{4F$HG;Zz{*(H%0iG#b;@b+J5f55t+(V?OA>mQ;@*9gyO_q5#pKq zYV)rN)A)qVzIwIN3Fbem|eSIbl1jk{tPbAN@XGmLQ@Q;@*l02TWZMjUd#vOe>Nu|2Y%y31>e6w$w<(pu4c ze(=*&T`tG8_({g9&Vy8s#jysK7Uy=P>1p4F33}m-IXt2KNGbNgeq3|;HNA`Rgt-sT zOZ_UTZv}0|M-!WWC`KYs%JSPXqQ)JyjHpH)Es~X@MVWE!-$b^QT=K&w0+WxN`&-}Z z7_DLo=DTX=P5tTJx-9qlZfbN}*SxH@3QaCl|JPV>Eu%OY&DpETD3@URuY- zM-3w#Ul-&xmtLG$0;MqSqGv4M;(Yyf4Hm5)?vo-iBvMF+Wwm`FbG7|n1WI8vs36Ls9sYdZyKEl`$l8xU?!lVh-tW{rxa=_Pj+UueW4^9@Z+wn6+=9M4%L| z!szCcJQcLvG5L*}+oPl%FC=D@4$JCpYvy{;_fb<*oz99;@taJbl)So2Y7%G?b4{#@ z5tF&*%w8!X5l1>KtJFuCtJLlPL7)__Ug=H1-i=HbFZSlk7LJzIwMfh(9hQB+Nwn`r z?*aS=fl|1pR+N0Mex`}uXZWbF0n%z4iN&PDvZA+{Ygy6%Ed75ID1|G1x;1ptDXqW< zZ?(r)Z?$Kdt-hgtARF)CD4ltRJ(S+;zgorgGEX73%a-=it^w*;O;%aq{FiB7e@PjmUr&{Zvv%oeML`~QiGC|rID)1c_POYB*JJmFn=t`Z^n6$ zjv2f2nhQ|v&hVTj5h#VLK6+bZ`BiOo<9_P6;a8;fAQJg0vb5}YT0hE7IQM-J}Zq}$+G1X~HOZDou-rA&o_1OJU-YH06PITAS zoZU%5oBOEM%HET#LQ8PHOW&*2dYiPebW1fh!coN(B#KcvEbH@|nd|e6{~%DxTUybd zcPN^C{dGDZaNqV;B!U2g?A_ypM!|A8!G(AZ|7&}j4dSUQ|;#eQJNd!u{zR<(tc!w z_&Rz9XMIYipp+F^)sC0sJ&wiaAl!3BijHr>c|O};I!e9tNYld)J8-2zA3ZA)~gJ?!2pV6!_ zt3G#|@ngqLJ+bafw*1pA{XAJ!)Aj7>&(%sISsp>ve?7S zUbXmq@Z&;Hb6`;~_DBAFW_qp`Gepd4{XpODzsdMTItFE=umNvw=OLiFl$+W~OJ`C7Sj{sV7>MjimRS-$;a|)fSf= z&OW)uOEm4n)$J#E%q8QBX_D?oHM%h-jQRAPrK4X#T2b;;i4jp^qduBhC!-Yl519!5 z5Fs7}bT$esa+Q1u?tY+Op(pO^nu}w92qR(IJC0rkrEs5#p2Yc{*F7uMQbX*0rP&$V z1KUYa&fn=QR)#M!+@GXLIxt`KO7uP)^^)7K{kd@?P8#QPsNR;3%+J4s&DP{mYnQs& zNE%c}J=(COiYZ9oXr}l2*7gy;zo+s?LHVU|j&TW&O?rYwMDVU-TwUMBz!6o6ta9t_ z#OvnSq~o|z6!W>R;?d(te8lj329A$hL|nZ3mGP3-a`bkaG2KM{rTKXJ)XxTv10-$Yq_?$*pR2N2=MG=U>`*SM**F-@MoOy?OYesJ8km9v?o264|6=Wo^JDvqYTptJ zOhE$onJ5Y;;tCP&M4%LwTqf4s3}%&vbP@MUSP4u)0{4Ivx|uZ1SklZS;yM-*D1~h! z6O~`b88PMRh-rt)2~0r(_kiemRNsAu>lJq~ptgrVDeNUOQSI3Wqg}~kM)_II1WI8~ z#N8G}Id>c>u{OqdjuM!H1nz{;+X=JcjS+rt^d}pooU@#U>z_Fr5| zpcMLAnQ)@s-soN*&nw!O5v=JYjrvy z_Q*{`+2E(PYL!pL6eMuvO(#=attt{<+pC_gU!|AnPRz51GAc5;> zT63NbW-n50)!;VmRZKwwSH<+~?ns*PZOuhK{$7xZQn*5riAitbj4A#{xSGG0iYZ9o zs+jr})m5XhLEN)cFBMaekk`&->As0FDSFEIz1>v2!Nan1Q;cr&Sku-jrT7bPeV1Q? zR@31dy=%~5)?{O*;{?8B&L9=@#nq&&WBAcvX1&M6>eAjQrsO2DpFz{RwVUW%D&0f7 zS8b4F6uglr)y)hwA<-)NDH zI&jU|*P`#?R<@$0HDzW6j zM#;GT2q8igNmWjHozb`k^9yw@C!n57Oj! zzZFilrEk@4=kie>(U(Y;+lQLm2}r@di+wt)u6BFa?|WiXFBw~H1eIe$yJhUJ-`DEc zHd(|1(`2tMkUgLpn=`>Fy-&Npa02t1NAk zy*@(=vxpLv74OpzTV}Rkw$yAQQo?7mp1UXN|0cGl4Nk26E+`rI+i>N5gy;@|)^x9i z)jw_C=yJuqLl(;fN?jqs``J@=`28N*L$>s*T~GEU&e_%~8F%Zpk<|H*c0AWdzZ^Sv z7Gg(C!9>2RRWe$F1nT>zu8IVC?>g69>bsV@%I>dA>Gzz+g?YzYVgHn)+2UlcPuE&V z1WKW`SvunOob!HOp=~m@+GWbO=7!_!aLxVNzgy61ZuQ?1cuR@En*MiPMTC@3bidk0 zB2WtTWm#47_=?2%s*R=E#d2W1Wf70`8D7Swa3-Ky1nJ$;Zj)>btxD$aokd}#{s`2DuBlZ4?42eJ~xhIY-@+S)#&{uTmc7bF4peOq3KUV>|4g0G~f4{ONjon^%fOL3#^)@;*v=U0uj%qDR*`#b` z2mHTDgdhEV0ZU=I4_zQ)6cKHS_~p=1#j%DuFel5-L{0H?Yh_^_zJy~BN7{pQG-&9#ZA|(#TFgrR#_~|guHJK)`R5=V zM^SP5yKXn1xh@GHqU$GbWAT$gLgj0W?=&Ww4WG++<%#;A^m`Fs%xd>vl*3ccIn-Sg zJdd8*UFj3hkwN+<7<>+I5-XzsJ+F4d%6q1#?FT6x*P#G z=C3XaI6CQt2bv`UrLcUo7rxY6d|9`Lxfk^oD1|!ypjtR|@&P-0Orw%_nzY&&)@Bl4 z?ATvm%AHkrbpMPDw%O)Dj@YOF(J~@=Ks2ASiAe-TNT^#;e!uD^DuzzyC5}`UD1|z% zkyQa9-`S${y<}By*LrHf7dQAO`WEs5rBvx<&F^_{%#8H1=Ruix{>w|;^QxhyE^cU` zcaDLXGo5m(Q^S_8X|RBF8=zmI zbyUf#Mx%%OwNG#QswjoyTqYKfPrNv%kCAYvn&f@Ze;`d~y%3SC{4m_F<&wM)j&t-9 z^wtZN{QL9HV%W;n9LMu&m^o$7ppcIBJ-x+;wR3dz3^?Y|OOP)~tR*5cDvND(;v~<2 zV_qgc$2AeA28WI6Gk+L3wsG9yc%# zRe8%zW*grBss9Z7XpBkjuA+97${>9QW52P@>6SO>0t$CBPRExJic4b^bs&K`(Z0{A zU_L%NQgv{*Hn1Ehg%;AxS?ao0`1gjQ<{LK^qYU(-=w0c_PoxbmIDDj9)EIAIzG%Cw z##CsHkwFxsf`EkwuDDOXdgW#7(qIC+&`_-RodH^Op` zaD@f)^@zf;e9GAf6$zA*Z`Ap!t=FfTNJgro!W#TudS zikzKzV9&nlgD0msrXYc3Qj~Xpk5g+DENrw>M(bz^N+F#!Y7ZM}`x^~wY{K(5@t&U} z)c*gweQ4@|b=r~wCDr2_0|nl-<4g7PHMJx^YBM3nJwKn_4znNp08d^&P+-1D)F#?F z(3L+lM^o)Cs`pdhJaC+t;rv*-od>0A5#eyql{Y#%g@~rD3K}=(j}`luDF*65LM}(I z6Ty7VStoVCyoM^41EtVHMHw){hCd%wOI3S%t0;w*$b{FDlUz&9tyb$EpoX_NuJt=5 zv{?U8zmdN0wUsy4YoDxQ{Sq3?)Y9qySAI?O%W97=b5Hu5z8+}8yif<0iFRv$9AuR~ z#T}^mKKfresszl`67t4M`luW<&VynX>EX9V7v8?ZCx-nV>R0@w zt$t<0@k52}vf3lNZD_5g6*25meMH@;nkwdnmS7!Ho8J&T_~sDqv?x@nT_ms;6s6&f zNHx98L_M(RCfs1=>GULaV)A%8&-;HjC*e&*-qcG@KPbo_=Z&Y;UH|y` z`mD1N!h>c6Bv4AecgZCqKn*I_)@X3vMIG<{Q@d8Qr8%r`s9!UmuUhqhiRQshv6=NY zX8!TIr|n~De0saoKuvx<3*qgG4!nx6-6+nnRZsg4)w@O`e4sKKc*kC5uB0{M~CKJU$q%f(9drYL=j zbx`m9ZYx$i^VBlE&q-nSiU{>X0&AVl@haiO*F8CH45nEJwWC#7Z*Q+6q zOiY&d`A3Jvt68jCL{_0b@^D|rsX=z5*(aOA2G$Sei~8t`!*Oox-MCWfy-v+CPt(o5 zv1~TAf!6L3>rlFiCf^2iwq$Ew)MbnsUo=|B6ePl_&C|y|VzZJy(kj)uLu}ZGw17HDtZf7nnRF4 zDfu3(N{`lQa}!SR4-_ln-B(koM$=<=vu9I!=eX7CXtyZtRH27@W6e#DmLSoG+FTsj z$(E(nC96)o4otqF%sD{&)oO9GgP9M>$40ux`k7`gHa~v##{9EFtlxycqRbwu6$_)k z(@yH&9kiMgfAM8BhoJ44uch7|#_werF%?M1&wvWX8&+FA`^H0{RY+h?^cL%ZB1VU( zn!=N21Wdtv<+^J1u>&9fv!Q5E##yQ>l)_q|_u*~|etu!7xNvI-M=8`H6He4i7C4UL zKU^m2Xgf+FO>gPVp05us9BahWjDUA);px4Vsh5lmn!?IfzDjlFNpVT9gwfp3A(Wxi zFN#02@2HZAfP0n2#Rz9nw&V+gw>WO@N8Tsz_)tI9_r2Mw!A!GH8M!rSj!IppWzc$a zGxaUBY6!L3eA7&3_50%-w~Q5D&|WXvJj^(0Jz7OekZ4BzDssyt*1h&iD#zc4j_|+o zCi7kkJ7=Dho_*gk5}1>s+;Ua9OR?5!D9t)pLd8-Xg2J^PC8G$UXN5?CfhNn0{ZBv)N- z%q@IDFSEs(wa%UD*K1Iy-?taGY&6Z`R~=)ewxPEsgYOt?0;}mRseM!=>Y4I0Hf(%i z*)W+_l$*51u`XDc+q;ZrSX#6MEu=HHV%*q+PR+z?nnP|;U&_AYtO?a72bU`SM;Hb32}CktNPj^e}tUk1~eXJ+1I#$w*a{ipdx@s?WI zPN9A!e7>67Hk_!9w2k${GEpQG+FDOla;ueT)3l5BI+zy{m=nDneKwfyIO`+|(5!=Xg;H1xiqdL) zdp+Uj@1pDMyaJ`r5}62#8>p?7&qJ-%ijU|^lsck>q;CMec>Tshny+1gB8NSQNs;Zlc z7~i%Y;--ZI)PtUOW@WRrK2FKy2W##AUqJ+DPNOEuF7UwVQoQI@&H1i}M&f>_HUo=oqR-6*{U7qJIhF{wJkT1HE|xrF)!4CWuh+>D3WPA zBT2tLZ9KnxO}TV_+M0j-i*u)6;oa0!G7^99I7}&ws0mkpWFJ3?IgWvi6!Sn2g zwO)Jez4qFD&bbqH&WlUJKExMdkE~YCG}<86?H^_GE)(np%s3c*O7|_OlsWiBaM@Xl zX^afLei3Uk-cb5H>}NczcqvxaW8&@%FR(TqU8H$^1Fu^%t^vRrGc~qy4a;pn|0gQSrmz{es&X%q} z(f8+>r!OnkNoAjKN&Z4477~AnPE+JBXNB&$rPn^5MLBuc*ElunvsI1&ck5(`>9i!X z*p2oHEtnyu=k2^=;{G-b$fe@aqUJyODP6jcQj@!PRanAh=e9w#Ut265>?o$btmtX-F4JaWzt&8D zf3BI5xr(2`BLkP6M+u9i=ZPS-;oLgP;6=3smz`UXONjSt=U3Ne{iYiK?5nJ@*13T; z?Mv}f;=+upnweN6_UL~2)xW~62C7qX9=0yRU#~^!W7d6LV69v}#d`JVq!{V--59f) z>*?X$QQOCg$?<>cabt$4oEO_T3wxW>{UsDP8Hqcx7mOV8jGSWFJXKpvv;!>H3ZQDLa&6((7Y+F@AjUL=z8+N{sl6&dFCYvzg-z?i1cvQ!m+;ug;fu>C^O&z!9yY-%ZS>4BH)S zvLSB-9Qn%h#T*5dPd`f=yZSbdzCIzF;`e_L4y`{>LYcm9CybjP#rg9C_0>)NRXG~0 zM}JFNpFZYuxfEOV;%lstuO`JzK~KJhNcl8RM#=u=%cH*B8KNF8dsyMTxFp9>s=L1x zP`;j>fKqjTA7LAHD_GrnJe`SPtwSi)vV#Sbxi0diA%C#DwNi)&zL8SGUAvaS&u9=+-(u14=Z194l&u_d=H~k z1$!4#{tT8jD&&Z?X5Dp6uU>G7!4f9oP^#opg_ZEzp&;tqkFYh~=xJQbTHHji7Do)8 z`1SZjoATzm?(wvrA!lb_t``tzYc1lem9)66z80IKrAACEBv^dk(xxoYI$x&Snr~}m5rV%+u(dRz{aaqIh7?(cfrQ0h3>ZbA=wny9l<7o zwfs=R2cw*nY|fHM$(>n^bsO`CQ{gTumx@aw|K9)+qHNA+Nu%; z+u(dBpj6UEW4nz>BU-s(Ow=(Z8Z2Q#rfYA?rL34COSQ3Yb2p5;I>y}}2!~cEY{+zg zort&PRtjy)t&e{cXz(b?W#gul_8t4&QosHF< zi)q5>Z(Y;uj%|r+87+DKQ}-Rs@7RXdFQ?TEPI4Fc{c8J2{eRlvd^z$h7VkW-mCIEJ z>7^HURyR(|slEMqyEVM&9UI#-+vo}60f=I02-f=On_@e%<+`=bZ?aUU^nB_v=ZkvO zHfN)Q_Xpd_H&?9No7}OnJu@LkpS>x!BlG9#=9bn!j(FudSu9=$l9hgVU(|WKv(akF zY1^+4E#hqBJ2tjww$a7Eh}yfBY8>}lrZB-;D{8E<_4%Angm;zosCz9=+4EarBN{eh zlvTE!HS&r=u)(yMko7n;d7I0mQN>O5;7H`Yf^WSnnWv0DUco55!`a9e=V=Q*T|!K5 zbjQZ_%r=(&yiBRNcz|JyS*9?-S_$muU~A=U`;mQT@HBc~9=o_txsEhlEr!R>DT%ail5@PgMd!u?07xFjAZtt?e;d#PGfD-}H+ z>(D(I7g@r@Jk;ZEr#IsMetBNRvYtYDx$Jp+WfCR+`O`WEy})8w5}Dv4*P(Lk<-FL&LX@h|g*W0rd3l!cUj%El zMX4mQ&`w;rsJh8@s2oXI!o(uj$Y1`0IDO(z*r<4}TlA(03+(lHJhOnPUtqpf#puIj zU;3=17#vW;S`i~3PPYHU2It!zrII#w+HK_cTGma@Pnf3+mN2mZrMi)vEQ+Scn*SHU zT5VuM67Q2Gu`)U#axmtnVw18dEMY>PIXU7OaaH9?q@2;@j)Do+;$DDtdu)C^I{jta zQuknWeVuY**y17XWijKhe?HwWErx~FvYoNdI0bYU|Lf)iT}$6(`Mqt*~-S9ln~|N z7H307NhhcIwuUWJYwoC%xgL90KGX|znx#xy(phDKwPcLdKl!Ikc*wYtHFwm5A7Dx#jg!;-%Latr7lT#QTH@KX)2Yf|X3P zj1WYM$`U4IS`s!p@o+@j=q=)Z{d`30BwJa})c)ZpyX^CwmS)qQmXe21}Tb(Gy%YUcBESPiu>OZXG?s zFSQ--@td-L7KYZnDAo%KouD`J`AkOxifV z(A_#OB%6+PyTKABWO~ou)1qnxIe%akZp)56ZPgHu9|(t53)tv+_KbM8_5_G0w-;!2 zw`Ed`hjmuvOcuSjoYoKJ<+95;@y|ZxwHp28x}+xN+WoFBs{5wY`CR?2tTqz_(`I7* zNOxqZ?UabLausySlk{}-B_@ER>L$Fq! zGG}cfIK4Kmuk=+}tl^S<3#$RBhg`RHPqb(k5hZNTOq@~Ot&P!oPq3Hb@^U@6cj3DR zSc`7?DT5jd8*=^m_}LX(1K41DW*c&3xZAy2)ZVA<-MDvhTyf;%8xRezDQ{-4Q9_oc zuG{k$+ishN-pTgNHgpi#=B!c1q#;<#zex$rZNVU0OJC`${zJ;DAwyOxb2g{$KgR9p zZ~Gl1nOwI!?3oE!k3zF6M&{XPwb#QjMzOEBP8LfL_Bc!OHdLH2?#g}5$PrIt4`SSv z`wxe`A8m}EeAA^-J1>*3xDCuU@^sFuW_52U+F_)=c%z&a)%=r76y_+lXSVUaQ)cye z{f44<8iKWWzhkky-s-IO`8ZK4iM<-{&)A-skiM$@Fr({noR@IF)$gm< z?ie$^G}S~AQG+e8T$VsSgSv5NaC=as9LR*8`ji@JQZdM z6Dwe&w!T@^7$$!ir~uZ9az?|#!g zbYm@UL5`SI;uY3#53q*gva_$4{%;#h|42A&a67XW+q19qzxSwR@Ov+hSt9ei<=O$X znoL(hdMWAb2yeT5eXapA5IqA?koi{p`(4SRaatd!USurfsM0k zrikHHU?{u-_??oVnQIBGRwbsFgBxc$P1^vUZD`E)~ zQLqtqY?gRuk@aZs9|UWyh7Czvv=bN^zVC5Z!UVUCc^}0DYjG^3Mq>Dc$Ikk~L2ldz zY=ixlN<5jRxlGI2-bAnsrc;S-1y4D*J~Gmc^I|Rb8&&`r#P`@ufKP^Oo+1jxb+SJ} zCDWaez6kFQZ#Pkt5A6!?Zu}2|wXP#4N!$&Q#EzvuM^D1oz7u0ROPII}8?8Q%7xPMV z1d$H&M;M5eX$aQ31sjs^uoHn%2`-~B8w|v3z!D~|!A8{UU{NLgudq>W#C4YuAcE2m ztaTqYB=InvBvAA3vjIz(xDFdvJSK_m9<4yMz7`>OUJClT!31kPfQ^4GQ^fN>yk)7T zyIbF^C}GsaT9GA8T!oEwrKgIwzqbM5`y#?N2>CC>c)|p0am(Uvd-(P5vjIz(xC9%H z_D_wg<6{~|X2EWoYs&|&$p-H>#ojqLJPQw- z2-YfzoLtW?5C@)S0Wtqxgtb2MzmIW|B}_E)Bt2m0&{>ZR|v@!5(h1H=$P< zEMX!AHqO*uDz;bt2pjRwJ>ANH7?Xxzt%|TAi86L#ex6mXDL8{WgVR)&Fu`quCw?i~ znP4q$+0?iSs{O#FZKrl_Y1_cj=Ipm`1lH7Nu%>1S+h8xG5(9qk6g8w~MmLr)!F9rY z?a7oVjBbV;*J%vu{)b>t&o16a!_oXwbGUgPvFaRmDwxd-MWa~c*O3nh%F{q z%L&Bv*O8*sKU+ZL!2RF_?3?T0evk>)lK&qrBE*|F8$m=Oc2(qm8?nn0CUV2Z%sczV zw0&V97C&0~J$9L3t=6z135%Urj!2Z_I%;mPgbDf9&Bc6?qEDCEu<>66Yqf<9NhEZZ zL_UgLmM|gHS=Rj_T${_cg#LeoLrdl)(|emq0yY1BOU4q;m)iy-14TO%ti|o08dvRR zR*Wo;oiLZ3eZ_PtaTKw839-v1Vfsg6beL=82gAjU+nKf49)4%^M7n54?E1hbCEg~A zm#ya8Iv_ou!UOU5yUDgZ@a|9ezrXi<_{x7p%V>-xikzXDU@cj~r~Pk>&Ap^|a}M^1 zo(DqC&`hwF{J$hh*@*5;tFkC9 z^}lTLjTrg=SNOlha_qV1_x`~IYss{emQg8P`8z&!YW z60Fq_HY71+t|WMs!4f89x>HhSaO0vUizIC4#=KWVq~1|48&pSRHX@USBtk4Ax?M zsWvjZ>~ooiUd!cWf^)*#9N0n5!^o5M?hy4Wc0c!R1(ai(t7{Ljnw06RTdHdhknUF? zzjEQXT38|f7r|Pek&`4A+KDyTb1uTjvj$@?OPF{B8~3D(LC8CfL!AX&o16W9n%E}(3lT@l2B z{~%Z^6KqJLx1E5mBH=3ozEW7i1h>E4yZ}$Ez zI7*mKC3a&coB=yww!!p|#E5SMmz}lP9^U$m^K`q>Z@d^YIn?k8Z=zj2c|nXjcGf1- zh3cLY>$aY=ZEEXlPoF~?-*12CCmuR`>Ys-Nnh4g~2*Ot5lGwKAB8c#2yS3V3A;#_T zK^og&t(LHN{FjTuX`Xx!GNEgksPl<|#@EH33QL#>hYd*xJArycqaGUSp)$c*Enp+V z%5$R5h$pb|^@g7?oIRDo!vj^8FtG|YO1qvF{ioS)mzwX^YKDcVe+32!CRmI8X0crC zTE-RiP~R^0)LFs=`^{pxv89RoOw>FMHRqCW&G(j@rmYOVDArcJi+b$e7%86i3)1#X z3{jb2Et%ew=bRYOI1xmRU3tX&QJ%_?*uWnMhZdI*_qDb>A{yG>qdj$&aK7exl-d<3 zt~c(ZF84^(S;E8tlxj})f5e5}|DaTx!kW5|fuClh_DrxAdjanieYhvOH^z)xfx9%u}9@l;sC#8TLp z-|o4XyZIf6YJB3P?2Y)GP;o#=@EVe}oZ`JsQXgbA5Gb?C7;FkPPF zjPCSYE3);ja(Auo4}?QYmiEoDhoaSzryv&iJQwlt!D>iEpuK-MB%Ck%4eyxT@zV+h zsp@3-i}PYF_By`Zw)KDggUimo+J(6C-Sk`}HToB&ibww_**~>^Fu__}LOdOf{^7iF zgC4$Ul*$q&eus?>E>A?uo3CM`O0ITRzl1>5b-t(01Z&B-YG3QAC>wYigzuF7B4}2K z8Z!fg zKZ!0rxj@YO);|WJf3SoJ_8WfP5&feq`iCF<#RO}y4=t9MiTlMV&pt+iPol#9*@EcX zaonO*^2(-dM7mPbui}bdK9p+C^PiNCiT=iiaxF~+Yq1ybly~`BVrbRzTEk|cDodE) zI$11kk$J>c^rrX?8x)o>u^FXWRPu{xzaj@pH9L8`t>@TKHAkoMf(h1QFW~#4+ct?} zt{arbFGdGYc@RBn3wqQH%s5Q27W*)@f1J_xx@2Ea!i}}q2GpY}$n!8uI? zYYhM)b9#lGaP}H;Fe)FS-L=*|g>A4_Uf4UfIIA*aV|@@8Zu^Ps=zj}cE2}JFqBm@; z*`Gz3b%sw`omKWs>% zh@C*Mbw#gL(Q9=kSd0CJF9>vcE=u}4sZnp*8Z2Rg{f21Ymq+Z0RE-{kDyv-ErHH-( zH?u0eIy-AzLY&-fiWI>&oQ#ok+o>#JVln8}8M7!MYCY8aLER?qWl;0_s5uj?#U;d= zdfg^b>%~YluiFNNB}|0DMuw4@m6Tq!VI$z)cAJ}TPPH(;u*w8$nQNYJZ+2z$ftGsq zB>@IYnBY3$9Ijq1v8Gmgqjt-jCW5uthpGJ|NA0f>YjXeQ#`$tRn8t6DV|`T;^G7n) zS8rD~(F%lRS6*%GrZq=oJdenxygm1u))eVOHJy|@7ki-QKCPc?zoWee`8$~i)_RVd zGPQD2T7B*ZqU5j7#jCZxMn8FrO@j^AhK@%B{~=S- z^D9Y&gw~JVg4xCu@yik>RM>b`C!5mX&;B6(eC?+VK>sU@@tq0Q`WH3=9%WT#Tl;|c z^u)eSR6k=q$`U5nZ&=A-{%DT;y)b_;!CLHfd^s}X4%@tveT_=x?kVh_NwR-@%%MCB z^wqddICb6}DVn2yEJpue2@?}Qdza3xWa~9R*5kLU)_f)IDf97t1}0dG>twMU+#V^` zVt>=Qe~@4a6H{QL{pV~-$>}mm8qto03D#mS;0*bA9?=Q=o4v7t21}S=kKniH_CyL- z>~Een?qjfo3HCy2|ERs+H?r%5er{ZL)?ylCd*j{O;x+Azq=!z%--w1Pud^zL1Ey)E z5li>3XH)85o~Fg&|HXG?S4M1}jhcJ32yyj3ILcV3ZO~c5L{ZR^7;h&IMOFA7?M$%N z5!i^Risxe2&4mr+rk|KFa)Umo#VC~}Oca8RXk>!5PQb>z zrdgESO=p2<_Wnkc?0@KoDodCs4jYmvZYOyDV1l)z7c%6_svONd9X4)YE!q|(Qqez{ zU@i7KZkMuJ#O@a3MTl?c5AET|mpzUB$Bsy`W@3nu*e6J1|BOVu2CmPhy!&&yHWca6 zN3$tUtIt8H7Ugf^UKp)c_~0m&3D#mS;CDvlPdSka zTH=qY<3;smp(cX0%-&5xKcBQ{lrbOsHI^{JK1}U{UHAD$`k@bUN!V9RW4ub&#O*HD ziT_}oxDzpYVlaN$_~+Hy??}JQH@$M}ql}VY5xX%sRddIz!vt%w7ck>sj%xR9 zj$#QD>=Ard4Re$;=BOu_qgcWOdm*)dWI5m)siJ?dgbA(_Zjo>LY4QvpANJ^r5e@3- zw_^Lfo!U~QR|LHf2k!3B9wM$DiB}@ta|def+~K)6jx}5%tl^koty{8x?0hQ%0``E2 zc;=_2NB+5S2EYVs&4#^}Bi{(`8+$=q%6d__kMmIaOdqGRgo(KzHjVpNbh;*OG;Y`_ zx-QO;2n^tBTyp4D8h<9xR{Mu)V7LyNtD)sn|<;fp=g?rw=XOE_Ql0=}j9 zZT{Ga`GZT+4zVJh@ZSyyMpxaaS0;Btplj}uwMVV{(=2@4eSq?V6AD$NfPf8B+(5cwd1sw zB~1JS8&huI5M2t$w+FgnwNx4<>VXv#6Rb4>He5r^E-!jYs)E~>K{?ec@D~%T#h%8x9b-xPksFkN7NblAYq8fY7Qd~L;vPmf8{(I1%ii@w z?B>dKUBqmbHTTKbM4tO7v(R&yU@fi_-n3Y~Nu2pmN!{Y2sw`om6>QAwctw0wBVc3G zsH@hYLqgTut;P!`Sc|=YH(9rA5=)T3{-Kh=5++*1MoaCQ2%RZ^t)PXqmMDhx+fMA! znP4sU8`gTm|*l&1$a7s<3$=)EN^qK%uKVX8rklF{Y)odEM33n{4 z#q}@~Ww6KDggwqb*yAij#C4u_SUeWHw7ZC<(;bhBUaNL#GJ5L2IVP43l93qOJjAs- z_BhS3N@fWY(j$`CXeSQfeAh9yGr?N&{{;^lV#+CLV^YD3TCMBr^%4U{sw`nb`szdZ zKSiD_vdz2UoVpu!L@N=$Ot98%5VL0*;!IsR^HQaQ&V^B(~JU$L?&2^eQ53VMwF-q{sRi;cgNBSkwr5f)O1>0|euXt8t zg0cu^!=Td!0bFw$Uxwb&yT3w{{K zEiXWxW1Zxcf;l6&AXr4*7$C7XNgZXej$OLO~oiLx{ey|Jf2i_ z>%`uKd9bm2l)Xpk8PoSQ5v;`?!QI`aO`;?6zwNR?X9*MRh1A#`_Uy?1w&6Y8xVEgt zbShB^gbxTVJJV)j@{O;yO3lWLIXJU?jQIJ-Yo%yo!VNEPAQfSiv8JiuuDp|MNz~vxJGdu(2Ry zsc`)|9K?c$ej1*|QG4J#g9+ARzu|kYnJl73=bUO)kM;&jm|!p9$r|kF!*L?qZ9tI5 zwGENccX@@l7(Pr3MEb=~E5)I)vL2;+T(x?4&uJ`fgA-fwB5QG-ES725(Ram;D07oO zDodCc4;%62!^F#pqhZ4>%MM!x^l?wzDl)-ZTqpT8-AJKgM?VHTdX_L@t~s9pu!ITr z0#0$BY`1;t)ZXZh5r_%aVvnTuk0E<~BfH=XfNRSH+rw=JPNNVd25yp#oVdfD`EHHa z_gt~x1K0jDT)c^O*Sf&#`D?5dtqV4TuflN}l>w(wDR_R63D(MloEE=XEk5070V3@7 zS8LDCIgLsl?NydA(E&D^)?OvPX7>P*`<Uw}D%**UwVFoCCtgYp7%!M$Em^-lN0*B^`&8KYtG)d$Rn3gqlO;^Z zJ8y^I;481^ng`~m+n7C>U@i6`z6XFE%XF;3Utq_={+W+>y*ho3xU{H|HW%rVWmbuc zUz?*;gDch&m9bvfj~fjpSc|=Y=Q8%@5fukjR&PhDDodD<_SOtuA$mABhK;u9QOnSy z-s6mn3D#mSSS;CaMuxjowLZ?sSi%H*0k^NyYbtBj1c-9jakGR8nRa-=VmXZdfnIC0 zL;pxiIJDR!sr@4g&p^gtf1b9s4ub8W=6E9IIL7wk7~5+j8oV-X6K7WC)uy1GW%?n~ zmGS>yM(-4r-xY_ics5`O6G5OQ(a=utY`_F-1%T+`w@ti!S_(G)i(st^D3v6x+KDc> zQA9md)I((n6V*Y4WZf)678QgICRoD61e8h=VRqsS_6F~8;*|h@F~M5w1^crGZt{*( z?$?-LE%rLR+dW1!%do6b%KqJo5Z{Pf$FO#9y&{y*nm=<`Dcsx7+L_O z3ZHe=>fAjienYCg!31lu7gBHB7vnbL0?zwb!UTH(zwAKs2NSHtK1}T&dcBpAPrG$< zV=cD9bwWLky1E^~GfUNR8z-MVUpp{XoT&Q97LLe}>13o=ApLHQE;i3k!qcBvmuPav z!MemmuvSClG~u!?LK8lLaKke!Z?IeGiDy_?!o&jD*ncfnWbKMh*gI$1VVjTJzS6kue1~e!i-9Y(HLOg0(Wu@X_+l z%Bg&u6a=D=Ey1<*@9m9eUz`jkSnDS2Ng~Nk_=<=qJbPtq!up3LOnjQ|qb;oJq)ccy z88(K0_SGL{a5oYgmsgo!t@E(4Y2J| zF0<#gb>nY^>qh?Btnfjd* z`O5FcZ8FYY<1dJEP2?>=$s#9R4`EI6Ggf^pVPX$xNmRBIt)sR_Z7l3-WbOP+VS=@0 zA!2IIJulWRlDC#6chojY`DQZ~pM7N_SSuK%dYSES@#6SF5N#gKQT{1@SD&-0i^>uv zw#Yg?J1L5km&B!!FSO&U?kb~}`kDyVng|<7Gf#*Y*<`7bM~_ohZWyixyq>7Ago$~m zN0DDoh%Zi&AZ~2ktyNhXqCOoLB$!|=d25-z@(Gdqk-Y!t|9Flv{pwgXpo^=<5+(DsgSQma30Yrl7P0HBjU;f`4dpN50&eSc|G2 z%3nkMwReGmD(AZlwY_#UUQCSMV~QBu{5&hHMjxuGmfDi2a9-RV-2QkMx%^Yxk{f=8 zZ`?G6Yn#@Fql6aA$@bHf77vH0J2K8uIA6B+S~SygPCh5P43Rf+VK>UF!#kW;D!G=k z*TWIvY{N{9?(j)T+B8VFBz7>ko!K6j7W4UnVD)7G0@{=NS#;Loe9gp!jzx`{M-%kh zg{v8?#ic5VkzwuOvm$tbyy0CrL8wiq?a}^?s-m)l^W~iIJ+fsZ)Jk#Nlon0@(3oHw zOydkW>h<@2Zozu6Q)0MS8{JwfjTxtIi?!nF+s@ht#I8)AMjE|#-BJ6KXAzidS;9nN zNzYy-ZoQRHE^p}7Pp>khzEL!$yvhV?@!1*rM^ZV}HLkI`v3fQuOPKh8s0`b;OswzS z7dGNgk5;4GI4dLYO=Kom%U5Zp4Ue5K;&cB7qDPT^%JKU5l_!PTsw`omB& zt}BRLbDOwL8ahJxa5=zWg0_!QqBy#WFlCLPmpk5J1IcTI?YG#mf?$F2@~A17E9$}IrJCF6O`%A#~Q4a z9VICizEbRV`c*R%Ddit4jka&p7yr@DUVtZyn`Qoem;onSOwQP*h0sVY?u3Mt; z&EvLUM0jNO8{*eT@wPyuf1h_xR6i%*^!^)bhJsi#6vmo?3D#u!M;rurc<+U6K8cd~>qs@5R&|Q>z;FFW=CaU@d+#6z?MU&Y_3*@2dA- z?Qef?+wqnu6HQR6rTcG)O?}?NM(q#2N|=8$<-@WuDodCcj#7pEdQJTDLGIONk9eVF ze%e;ugZY*T*7Aal$W~WH^GEW1&L=6p$|>Y;^J}KFgbDUE&Hz5z_aCYX4>Q49>~)J} zMyZ<0js_F(n_;6>*7|@Q#O;9VVv6tIwq&H6KfNt7Z9johUFa}Gzfz!?a_FZqCW5uN zZSXevPaTwYjRq{(%Ndo+97Y!>^0s>c2Mj8{YKp(?*#b7HI5P6z0wnCfEyjwzg`hRt)(Us_v;U z!CLG?-0;4vsCsWQlw5HYO{L;`u)Wm1bC)tTBa-V1H}((PU>YmSqeIoLhcx9upSv-f z*A0vY8EW1ZKV5iYV;XNYekyDPwLPW3zf)Ufg7ak>@1KtvsYa;>wDlD>=`3NwY$LAm zc=b)aSZkliYD!T3&RULu1Hz@jFl`*t&)g1)vk@b;0%N;qe}qPe)t%+LOTJ4&)$Cio z*tQjHDp;#Dv|b-I#DTv$r6Fcz3|0FrZG>kU!b}n-=EL6Dl9A%%{r0dScU}WF`bCtQ z(%S9*i2hos_etW&k$Ku}q<<=sBG#{6i1*>}m9%2%6%i|M$s}>Xt5w9NhCU|Z1c)NJE^x9jaD7kkMA){A(K%GT-*2kBJp=Yc;0vOzOQ*b>KE9Tg}9~CSom0 zRq}!+Vy`c-+i=jh&DbBRrqA=nR$l)}V=d{c9r61`aOZ_-hzo9^sz=_3wj~vonutFqeS$CsdisEXnYrELWuf4+0eZAb=6qwC2VB5`@0yKd3qY+>+TSB<)5duvsHX- zOcX+^&Azu?^lR8dV;bMZITEUFOa2;Da#an%#9yenPe6pQO&z8&jkn_OgsK_#w72~+ z`Hq#fO2bC-rYLcyO4~GqjFM_iyE|VS<>kg&^*{t$4v3ywo&SSa*0+pv2X`}3AHmGd1rmAhZ}4C3L@jNW8!$_!fA+>DWU4MG7W8q3l(r@B7@OS`y<_5 z(c{l@8q;_u?pmmt&S_3;sjS%qYqf`sBUNsSGu88^A(qG}*|);lcBPw%Xa?f=vsYqY zzp@(BxJ7;ts*WnK!K%MrXJs3*wl7+xh#f7RHKx%&l0((}GrL*mod}L$A|HsdQ$LCb zkG}SrJLqq{c0|jFo$o!}SWC9^sZ!~c=odZy4`M;{HW9vKy-Wm;227_$$(rO1)^4wD zR<;p?xVriAz1TBgLYlE;e(O;6&HmWP&A3WPlAB`9l!-cq**v znyAFGLyVmVk10&Bmbniy!4f8J5A(D4`BCWecrW$b-!AZzF%AA=g0;*e0~0J^A{I8} zNaT-^2v3qPI_bK$Mt8%f%@>^s*4hC=j&PGPKK?hsT0ElS9ju~d+-Bfwi(ByRL6$JV zBiej6(_4A#k*Us#3Fu_{$K*-tW1!kZBCRocn;~)~<5W9+O z6P7R`Z98UBd$fNiSi*!Xp(Ms&-nGZB8)8>Q?Aq($$cwdjZZ{JwVM6*%t_HSZHGnVn zHeKWTpzIJe{NOR23D)8sY$jO3#A(=&tBjWRRmQaA&Fakf8mi7{8xYF`YssjTW7iRk zT^L3GgJ3Q5coo$z-2S!DL-@8DOPJs>7|(tX!4f89f0W~H6h>{V89L{QZV=(3ero5e zGQnDTK**Uv!_4sC1Z$aRgPxg0^ahM0_s}LRVS>j>d=ZEUmN3ENqkaA`u220K5mm2a zH20#k{roXjPLB*3C0GF%^D2IbSdgQGiIB8Ii+fipkva7Efg-znqFKTON4~`(u7?^G zJ)&)gtDUm3gozua{k1FQu84Gl!cnT}8$yi_u{YhFk~(Qjuog!?&aYmC8gKXRx1L-! zw?0dlSdTj8e)v%QHhS5&nlCs%%{gjuTYEhmy_2Ji_Z#<=swIVnk7td9H$bo4dWtm=kSbX2@}sz zs?$$Cin&j`zm@9pxJHplRv#0=S{(VQHm>{mL^dnq6U`DPI4bcC2(-ti-?v+vMPGGi z2@^g)`)glI-xUkS${w{EZSH$(n{~|kmVyb^GDrKFi}+4ov8A!k{>m#@!UWIl7E6|Y zLeR#tHRa)7->yR*U4L0@<+b8Cy^!sLGvb8}(h0R_j zg0*BU$el&%Dnr_s{q)O$(48LkHg`yv;87yA&GoqS`_~oojAjWFJ7B{xO5j<8QQpyQ z@oijuL0M&wPK%sqZ|9Y0=NU*Jetl6Kt5h2Gct5#rBS^qCW5ut)3`;hRNk%1 zw{P8Z-)@C`!{472;YU_zo=D5FB$ItCX*kN;P5#ydzG!VQaSJ1kB*H*2ja%f!p=wIL z&#{wz2WnhHCO9X&F|z)Aq=8>cYnzl!3HoW0c5~2WQTgyXtsG)WrpqC1CY~-o5P1kh zBM@9(rp<&${wViRyMm2l_>w0RZBbk2QCCIs>4h58sV(^a)MS^PQPya#VLK4-o17N& zD=tXmD;Xu8x86krmW;tgtmhV&y zmeeUZNqhI`tQb;dj>e_M(^NBsYd4Q^#(;+dbS7AfZR2dI0lv%7N(irr0If)oiCWtN zr$waG1g$A-j2v-Pq+c^wYmRh6n>bO`U7i&AZ5e7T5?hqoqv|PK5+*n&L}G;yBPuvh zr9td7He*B{UPui;XZwpV*}rUbslGM_KE~ z*bO%jiuWgth4n)cutV46g8`HdwYF$re(K|tF%KD3xl*)t;SR{I|ahn8%cT06gpe1X%x5toKd zj!^1&+1uP9;e1sPRlFXF;;=l71Vfe-TUj$Y;-`jqGkEBYbVmqFKU3YY@FU-xGQK+k7K-NBTH-ztASS7bF3# zH4(O?f~hq*j#F)v`?xD|OG-Uc3vxS~iAG7G#=(tYR__G^tsJ{mU~hFrO*j`?uF3j2 z`VGErd_UB<{=~=naMD>5F&^{Papk0VSbVLb}JM48j)7ca!XvlYJiO6lr!aQBo0b{h@}6FTf&xO!J)I93G2wDiG7 zp{K?5unA{kLot(W_~*9Rx64&yEvE6EqLo-#?mc7eP}Wm0!CF7o<9OS}b@E$U*y}NH z=pL~vtA}ayF?)B=$1z5`e~0PrcWde#8D%jVh;;Ww$CrK5j12J)M;jH_)X~p94OV!p zEe@jI`b1%~j?*}fQ@z`D`|bUg9=A7nm!psCluDdxawZ~SQCm|aax6*0Q9sV#WYGZHU?8s|v8%1+@xz}?2FpB={8NIuguYNatoXYLNZO|Bd z1KF}$(Xw~~yJTtQPv2Gg(J>=b)>5FAspw@fHJ#ARM2(vz^~u9}sklxKaipa0{zAmYnlYc%J@w3(Q^@1YCUaH^V=P3ILW_Yd>xwZORgYLPNE)S%5p zO)Ft871I_=ov!}sw3taskDWP9!~{gXEc*?VooU=n%oI^wJ;td)4+ki$#bq}WvgRcd z-bD<@s*mfzZNoXG`f4{;mJwK4GQlf-rm=3vD!lu*UsvJ0Sc^+&CRoA*w-eTIS+?26 z&+KjlCVbK_?C`Zs8Q4(V3UH2XFt@O_yG0AJac+3*PrGtx+1q%DvMsK};-skF&q~eW zfkuzP`4ukvmS4tcN3SJ{rPjixam8YpnH1$d46E?+So3m8nC6iPPe+gG9rgEbenz`8 zvrRU5hs5@96IXP!asI_A@u0wRo#$E$MuwBhLy>*o8q-XTufw^`mnuxmS z+m2Z@2k7{yk7D?J`Oc{C*6#Z9kRED}&|5ld6^2&WUl!#+&54?sXwhV(QLN@pWp%5T zF-*wu!!cVjjr-cjfreUivl3T$g2Gxn1Jr}P%eUW&Z1^1tJWX||m0l>~mQr|3PnEsM z{$bi;xxC*^&(-^$vN)ip$`U5R(VA!Hy%dLkk-r5I`|@sVzUD{tew&7<7ly~#Hs@?E z_Ft-KtA;4~IP$c{YaTS>XRPcCL5fuxgM)3q$n+( zG*$QBKCQ5X3HAs|Rn=LaUaYygB&e9m5+*`Wk70Yiiujc+QIGwXT=iS!{ngPE8=1Vz zTD?L1JS&~jI*)vlwZr6>dd<&0)k~EZ3AVvn<`%4UEnG=IZm^mmBv@w&6AfU)+U&Df zze0X-vC}wL{knHAbxG?xCW5uhaTOJJS=limhx%keJ%c4on0kTb=Cvud8!@ix0;P_@ z5+*93R24To7mH`h^TeRsjr40rv#Dhj9}{8HqTYoO@k6q5!E>u@ zyy}Li^LH;4da*--wfL;hOpIRYua?}>PAT5HkirrsxP-X>*d3~li1ZZxpBA~Z7N2sO ziMTL43HW+|5?XJm#u6sXHCM+3tNETKiW16RjkWlE*GxRB9Hj0ano~)L&aShB32uLU zOD}$$I%!O-xU~__{7{TCVUCjXNqEYlO^hw`%c}0I#iv7NVr_lbF>;z3gX8>Ms1E4il`!y9~VlF{ZaGW;L~Anb{_S&&b#wZu<_kR$lz& zuHMa6!Qi}jhs`HC7R%Kpik`d41zV>vK?X~h;IkTw?-MA5#mKH7xcmA+q>&~LV6f;LT=f| zU58d>XbqqKyBHAOPD?{z=B!k6rye)3aedBL&Z3U}8Pj-LJz}6ywdiJjf3XSn+1a7R z`?IXDci1gjB-(!wdI-jn>~#v`E4NRy=4j_?19pp)z0jA+MCZ>VtetxeA zKB0o>8PiHH5^+l(Jf^3?vBZ(Vb;39Mce&{=dfn3#0(u%IEvko^h-g<|-%=)z(Ws}l z!4j^y*;mynr6`S_G&OD}oYq;w1hS%oBnY*5WoW6Q#$y>JPnp8JE28 zC@f*Z9J}$yE-N!9#F0u13n=L|%lQ zSM^7=>}Pr}o%@+iDN5r1@^r9+{d6$9|BXm_>oXGspULnkg_#)O5@J;Nv|o(gzCnz7 zQ%7?;@|TFYGgPaJe4Cs&FZ?(jnIbX_Z5PdD=bAH}N^~#wXT-YnElmXbhiQvtZ0YgF z(UG@ekNsLp;r3uc{{PJWYohcj*@BN+c)2BG-Q$Ny;V2mgEqQWR1SfZViibB}TC{MR z`0YlK39b{v{XNMr!&eSFQ4TnM5C}?raP!g`2Vt3r^M9q9bqG` zoWJVwdoHEtfnN4AOUF%BRcMv0bzb~BTlcOgvMTTs2w zyNqk^HND;V43Rxr5p>macSXfgT~Vr1CF>b~Dw&L8A&*SHV*l_NDc%#lnGzMYyQ#5u zTN#xlz0rcFU2lumM<-|lk*<$Z)nJ^eS}d>hiS8L6HZZPuR#G`%CO9X2XFG0EY}BA9 zx@DQKiQrgb+G4rxAMgIP?qB+W@WCd6Ta9V-DA$^2-XhrOWn>G&C;kC~WegzL~Fk2SY{diAo} z%|!4WB-7YCXG?F37$(##HL9tsH2^lER>q4*G2=8dv3s`7`Y8JVbWc%#?fu+Aa9?2>Z*%Zzo7-X=P9OqkBKPz&z_0i14 z-n{9px#O~`?R-0#2<~@Gt*zA_U()roOGz9?L8aBsAU;8B8U zoDNQjkFD-p%6RSH!eFgQuu-S&T~R8&vuU=&cRyk#xhKu}#TZr7Y9e^VVH)p@UYHnL z#MaN~7I#x;EgsL!MCOxQUHvW(G=vlc{^oDQGOz7ATP&gz`e*kGDsrByZ+A6H@%`+i$^sx zG40hy#VPERUTu9dl}AhVRd3jK%nUg2${e6JIonwGDf6?!THGFH;*#dC4w^MU4+_4e zv3I%6+0z!w-a8pox2XxD!RF2euW@RRsG!x|enS*b?xxj5+AIEV(V~ew>nj3cC$z6m zOwgDp2`z8$1o1lBPh%Qw4q_dM#%Ty%Au)|n^mYcd@zeyZz?RM`YZZr$-owv{(&+;= zGtup@R%&Sd!OCCwiXaob(qkIGi=2E&Npv2p_Q0z$0 z8>db*tnC}_Z6d0IINI%q@UGNPV>*@iJF3=!^UGSeaoL-JaEZPuoJuv(8X$cj!%6Ym z9Z$5mELD$NaS`s5yxh2Lnc$pKiQB_`o#QWfn~3_zch|KC;>nP<8q=vno#}apL{92rcf5{JFAL{6UE#*MYuqdyW4cYmmpSh$VJ zyIfoLbgGSir}S`6nd@QlE_>8WT=31O7KyYPi#z_Ivt-_`n%X<%h}iyeY?>A<-zT41 zFi&gIaCIAl+tv?6Gp`FGAp5K|QF6Y|Q6<>ZOKtc5xz4qn2I92-NF2yHK{MCZ(Tj`xOcmQ#y+%IMx3ap7q6E^ zSr;(QWP?k^_VE3yxO(~_?-uHu&?2UKaLt*$HWj*Hh7CTUDtEN2kA#Sy!!5W5_S z9J@^8dAQ^7ZooKWd)+Jww-mP^)7TIGRZou$En+M}n{bdD#oq(e>jSqdNhuQ)Cb-p@##56O7b!8>2C7Mc zD-_ns*~O}*>-=1ND%@8y6Khi9lzUqStKKb(TbbZ?W*YBQ55KJV>~d0T$JI5sZMoH$ zwpfaP=&QQzS*vs!zD8%Qwy162`nSb_HnTJ{k!f{iyzkRNRPWH)V1nD3X*@f)daKg& zLaep>`H==|-Ro@CZe_Y4vgE^4tYpt($$M|L^1kF-z0zVYpuZ zptHeRk6>eeG~QjVboUu) zBy1^SBF3Zab&CEeJUaK%n8w$1Q~Ik%=3UZvZW?9&JrfRqJ;gwJ`*`Nj)je=$5WN634Us$QWZ@-hqcVTcJY&` zdXjHPwNu4c3QNkOJsS16FLp<_NHa3jcr;ZR6_=#kYu8ETF@p)ScPoRKlcS%$z10Yn zTdFc_xFnnwFFQ3#)8;p{Gy1gHhK9N#gUZpsggFu$+s-H}8&oj5zAdM+go#41=hy$R zm^wy&b!gY)sXBaREG$(~Fu_{p9;I$GMBu2##+GGeP5qp;xX)WG#hy;po4bZ9i5Z2K+osmpIl?L8@U_W+c_`VnOhUTkT=5LXtrg9 zQpNMU#>80=k9I#6k^Lu`XnY-Jw6mz1FG4BMYq)C3)6m||`_azsxZB)bDnUd?H_(>A z_M1DG#NG4qeVoD#Ye&EHeXo4_xu=P61|g&5W*QnR%iZatKY2G%Tl`wiM7%?(R_}Qt zst;NMTs|svLqVo^L?#Gj&Vg`&-eZn^>Ogw=NIjeoetj09nCVx9MDi%a@5Uf=a zHY8ECNLoUF>f|!uSg4v%`4^1|ZV#q$G7+84PCNp^TJjc1_Ealc&`d1JxY6}p*dTTB z$5T2J+=5IaO6sq5eFI_*2-eC78?w#g(dK5NSY9W$%LiT5ZmpdSCgR{LIl|S&2*)&H zmk8EM!CNAdX!Qdzf2E6CosDOecX0y^CJw{KCXXB9_SV@N(|Agc2-bQB8FaWgHkddD8*)DX z4f8qE77G)s^$|8CG3p26{rIA8UyqeB`h_($m^cj^H}QV{Vdp6t(-upKQ>ERWf$#&t zTItZ{lDP5%F|67t*X5OZ7^4%DbtbODhFoQg#wvqpJmozj&NUoF9}ujS6E-BV<_BVJ z`-d(Y`Ue{?hvzjB4`9P%)*-PVY@o)p#li$@6@v{)#Qs3+=;9VNZ0I;6Y<53|iPx|p z$McyO&zZ(~2@$MS5jG?d@dGjb%)O`)N7@=iujW>n_yQZfbH$1Bhdni>@svgBCsBhz zlmfw8wP8aNZGIqj46GWR6q?tFU+-fgGGh#u^Wa;|gG}Q_aZ1JLk01{JKf2C3u8QY- z_)Cj{feChC7j+Tt?5ZFZii$1RqJmZQ^_G%-qU9;N8o&pY1o^} zJ211{kN|o2m$?$wB49(gBU=b}WIPeMV3l@asJUpiH;g0j{DEmf*yj*JF1#s`OVUO$ zob_M8ei_?So{`YE-MQHZPHM6ZA!FaWvib&1IpPrz`HfzayRQaPObbGsT?p|5!tyTy z&j6Sfgy8le~imT8A~v69qh3OZ%IM1@=iFeT?qLI#1kN}7S889k(V@wl(Y?F zft$;VSb~XJDdVY|^BW??hJg)rqb2l>a|Cn0+=gH+oX>e;Q}#D9ujg3ytKka~OE8fR zaSXC9Bz{L1f(@tUA*868A1m2%MZ{Wo2H=U>O+twKSO>QHtDS@;m`DU0yP7^F4N{eF zmrgehA-#ZD0R+~=zgY}mS-BKP_#-;#wk4Ix%Q!~%h}@C?8cQSZaZ&LzRp zzBeO8EWtz=j1Ohsu=}uY80^tle2zR;t%C-J`&XfLQXb?Q> zb={_X3vlkNHEsOWUuwDeoQw&ql>x-6Px-{k9riO7#x?e#S3ZoCY#V;(2&{$QvBGn> zW#M#m?o(Rjd6R63| zj0voTYXSZbQft~CqPF?!UshN8`oRRQg|hbstYCk*Lssk*4fX_UVH(bfla~@Jk8^TC zj6cI)&f(Pwi4aHewKK#qdkn;p^`|{-z%xu>t^Gil`kf|~LMH*Ss?8Rd4W>xW(WgXA zU@iPzGJL6Lzl8=hHWyd@4wbM36Z^nMZgv)VkvJJ_jAqv4^k*y9Z)I0RQ)`0I3@csEm z*Tr->Tw5M`Nb=7qyIFP5TuRLL_)9B$pOZ0xweWYzf>4hwrCXL6$o^x)BrL(i3b64y z@-Z3ROtJA@UP>PU;rADTweS~?@HIzUZ{oRf3VZkPl#C^qz}^bN?5G!x#mT){B*dTVtt>zNtTuFau?jE|DIWOI5PuA@SBk@-H= zX|p|d=#OOwN#hyHzG~sJ2dg-Cl^j)4j$y5$TDPfo{~q$#_-~@;ZA&p_YOpl6po16& z<@UI?nY8oTNPorLp`H3glJ(W*(Vg&nTX7xPx4|21jH>S=i8%?P?0rhcHX48@-x}>C zhd0$;!{2DNlS_ zVlPE(>nMG!P?ICfftcVCN!;yyD5eGB9uP+sIY`lIU7fKF966@pt$y1z>iDcssa^R- z;#Z}9W^E)R+AQYk3fCb#5pJ9!UOMuHxCj9fmV`o$%7J@`$K6fz4V1LB*)HPPXd~3_ z%#~SU)AdzY(0pfhW?D8q^el$7JG_C@!Zgeu`J2Xx$;UF2NnEkGzMISQ$P!;7#{nsp#)vBX3i_b{BU zh3hxFzmgvWzC48M<%Pe=i5TVlL51)hPVJ3JPmY)eT5)-X;&P8291XMD;c)hA+$i-G z^K9~>@k4sox1#vMdkOv9UYJl`+#5e1Y_xhF!J-cTr%gM0)CFr{8rv)LN-{PanYp73k8BV5<5SqJ2>_n%n@;5&wlqua_&oCis?UIwHTXLGuuOx3R>YW zZjpt1o6>`DZG7tjiJB+U6u6Gsb(TDv(ELxo8s4*J+REUC8VyLY;8f-@)$3AB|4W3_ zR@?vf7{U=)D;Y}iiOM7$&MRNCDv?LDFiA@vHeM495?_NWWcR}zbOBuZ9XU??+i#!? z;riMlMy&fOU*sx8^d2LJrHgxN7K5Zq!X;wUe+{Rl^w1TPWg;glZ)Mt*!j2B!9kls# zXFFrbD$p`Ekjb*J#q?kp#CLc<+2*5sop~!DoSE-vP1laNL9hf9%Yi=oJC(F)r{Be6 zR@)VJHe361am)p+&+ciYvTYO>lP-?L8-DiVwz_Jjf>z!lu2)|GHaf_ty zivAP1arJ|??|-^+1h#=`cwbu*!CX4d(-!?UP%E|AEj^bwoLNV&!k9m4@dn;H?4!Jm zNsl6!6c(uNoBvuJ3PhCQTN32HjU#YLf>2Tr!L%J3xHK{UsK(`D`k&0e)(x<+tA1jb z2Dh!!=7t_QL_QQXH4MHtRu30-luxG_2UR! zKbY1LHhGoOCQj~F7Kc7U>-ux;3OxFA1lE#)STz0%>2F-&4^gx%Ep=l;KMj^(VlNQa*}Gw5+$qcYxN)b^{O4`p^k{%*{Gw}`Mw(L2`0_} z-QwUAGUvi~_>LZGSGs3VM>YHgb;SK=325ni-v+ooKj}SjI~MXM@?O7()!Zgkpa8gsJP$opwQt$rOPQ=7SDAzPjORDuup}uha#p?!1 zo~WESrS!z~QH|{noORG(EkDq*YjcTI$v^!6AgnX)*=L^W$`Lq=Vp?azIyWPARYHFa z*22;9#O&`8>`8QQt>>l?7d(?;8qX`RzT`91)u**Ct2VAxV+khs`$QGw_Mx8^YTK8; zn~4cLFJardI2GvpSitJ*CzWbA(dbQfH=FU%lA-YWk;l-hlFDkF7k z@8KMw+_zP0mqhG+V1Hjk!!8~$*B&#wm^pK#sTR+**h5Ui|G}XV>~6yi)YPUP7kM<4 z8)KDBo}Cy*d7}J-2o^D_0zHx1z!{f|?@=(Vi=%I*#-W`CUVKBj`a2nA4C?Pi;^F#S z=_#Ult>4XR)wzisU&eZBumqQjOVZhh?YKQPqq{3d;2Om=JU#yy!S1O_GYVGk(tf)C zfX;8VpOp5fM58}HptBAn5)&IE`i~8%KsME+6!%n}27g<(eMrU!8PMZ!eQa+o@qAdD zUV!Thuu?i=rE6=_FmV}(-Cv&&^Ord~f)z%aI=U7PWCWx3 z>}w10-kB-#?$AI9`&)kJZJIH@fYkc>ON&c_6{d;9w1HO)b0mmY9Loyv6^K9eIWnmjq9Q_gYJpLtL0x8pYYb1n*UP6Kgql?^HJB?qL~g zRRkL*mGX(tnL;g3xHniW56;LCFWni(umlr0CP64Yk}v;g?kK&}yvn7~@jS02&T@1K({@^#2?6N`RnKSqVK zMU5_#p66fDVSdj^*X&Om%@a*4no#xHaCZJ$Hb-Es9pekB<)jy++`4SAu`hSBI_5-g zcKf>(!(O?Az5jZ=B2!8XC_ifV#g0|CeA1iUIcvqR7N)VcaAw$xp~R`skS<*q!Q7zS zW|K-timeH457EZKld$fF#(&w^G`RvDJN-L-@ivUJfoa~WllF~hyBu4|=#?X9L-8a= zEG0kIf7D`o@NWBYcIMeGL|Q$j4Z~W$9^}&hY)eU8=TCnT@4`oEU3_F&wR9Ws}U!IK(k<;9AtH`1Vv&*^JpQ}K4gSen>1m$F5s z;;1e$kQ0C3{i03mIgD8~G2;lVr2%5ilJerFk;>D-^x@yMfn6suKl6towt=-i!n3|3 zbt{UE&nW)~t=vsWj_V9|eQW|pV6DpFZ6ljX;#JKOAf`QAOx1%zSoQ};5lb*(qO_)^ zh4^-G01&6=Tut-&5XR=LHQ)%WWd$}ALKvbDz6nnqD$ELF(>hd=!s6t5Om6hAw6 z1!9!JR<$R*UD{%8Dq{&IYJgXFQY(r_AGiTg;o+T3vnkWrwtLAOfwhi6+r;;(ApWpW zc8B>=rIDQO?ZXa{PcqiRPt|y0<(?&?cajJfSrBfY_-%Sd#}+EpAejDac;-i z4o;&Dc}H3_4`eAUT*O-Vy#Y@cCrhj-wk4}OagiEJFu^~Q`Onju^*q^=wQ{>nF@d#k zu7ocwtlP6$hEB}x@GpubnBXIiX&l1J52-7^vHQ%u`N1*a=RvRraz`l3Xjw@fvM!lm zEj)AbMEk-}HrzZ%yRTiP8Yxny+O{lX@jkT~R*h4sn*X;#?N>)gSn}n?eOlehR2n+ujY; zSt5u-68AtH+Z%;5*U6hR8vQOI_-<0UwwYxpTHD5QG^}A+6U^p)=plc7bC2M1G0`4u zte;^Zmg}b6iz>bSP4pW(r_HV!Y-1MKsF!Le+D+YGb|<5^2j?`Tgt9`rCUW?iFfG=? zzGHi^%gy6(RyuUIR=qHj;K(t7OM)j8!CCY{g$ArwEn~49z zSyD;XE9!Hyn3zA0r&tTqy2v|t#5o$@T(7}(h3f}|F&0cka4;A zzcZ%cPXBEn`(XQ9{iWqn89%Kv22b{Hy+HbUUi#}VE|76dOm8=qH8#QOx2KLYi?&pmRGf3q+xe$5Z zY0cTdxcX8|qdYE-9W5WxM?;R2(bHdPc_M0~gG)bq*n4N)U9lsSbD`N>JcpFx$PRZJbek@|!FXFKOE^X2@p1g?cO~su1 z^kqyed0;(_HizGjW$Ynot(CPOGk@8!3%Bgpr3M9@1V0zAcZ|X@Q|8pVB5+PmS9hCNszD9Rhj0Ahd3(2Lz)Z!arAHU@k$<^IP=q@XQ?VcHq`@rpwyhMJ&NYesnGkou5g}o}>a{c&moI zW0kkG^8Hs4OD4e_b!6cQ(w3xBToOEIc$GpH&Yvyy`MzGpl4dYIu71xXU7`{x_Er$a z)LcoNx6PDZ-`vd+*aoKI6!1~Ta&(h{(j@;15-tmC%>@rvlpG_^)+%#t_JhT=Nc5C` zd)MFytcBYN{?|5pM4x_9N$I)mB`m?jPnhk7pG_jWlXrrR7Y#Gzm-RfQcL!g~n7~?m z3l=(8mj|2+kv?wAqfYSL@blfH#H3jg#Wtow95-jBkVei)V59l2Qf=aoHsTW7P^l*n zc|&#(*Q(nn?uopO);rtL&8O_doQokGfwi!Q(A%%{6~A{pEjDa9QHq0Ezmr!QF^o7$ zaeG9=@6&#sA;tSO;8j3SG9BpDL8>yri6d}Kd>qQXPp`|z?AQ0}tHBcG`sdDcVpA`P zvj^WB_=U4(Tj9*8)UE`3f(hLIy1R@Q{WbPp-UB!r)4@ikMrq{k`~-?=9dRW>PMP?v z4@cnkz%=ZCRS?ehQ%ZLH*HMkNuqQl`o3xS?n{JnnC(UA5f{ApvlR4E$LrS|Snc;5Q zdU@iP$@0SR010bh-+AKY%hT#J*QZFoYMd6ajZ`T2&dW41vF+i%BEQ*ZKRrFnpFOB@ zPQ>M6g10euc@=qG)?{fdJ0oKoSPRp-+HIHd(!TO34-I}Bir=f^cg65uZT14$y~v;0 zuq`59>2P?{EqdGf4XJ6qlxD(p+`bRw!zg9V_UVEY?c(7hrTU>i#Y&H7Xty8iLc3JV z)Bapti!OKXK`Z>1t(B50&}yC@v}zKAJAhTQ7Km-$x-yHUwIplJfP}U7f+tmjbI80#>nTsT0}%&AtG|eakmvO)c`&U!vs@s?o12J>r_YhF)?y&^ zE8Td)Wvji`^wLrBbfxKRtLnTq+pIf1d3}$zDxA}BZ&?>QdP$V_!juZ?6EE!PoHbh^ z@~Alr4ClH2-D?lh~AR}Q7B&MNX{eK9&S_sqd-L`!X)t1;b z;!49nhPCi&A)at??J3)B8zf%oI)`DcYv9$2-4DpK3`fcnQeJPl-Hp4lZ^&4V!0Vwf zEeIE8xvP|VN_aSnVXdoRLs>z!1y)e;#G@-sRZHMogZ*$$H74-8ZA=TokXZ|4XHmuW z#Mv;cbsB6`O)er$`wpQzaW;6nc(%m^IH&4>j0wEz3DYp+q{L>HYch|`y*o_CS~wf< z#HU$rT<>`GhP3ZwLv!HT z`AaS_TKDH^lyqojcYC>2e-$Q_R`R9So$I7y0=F8rr?X)?ziX;}`++Lle=vbd(%DGwJA)*_0cNy zpb?+R!J&j+gljYHCvt0I*qz_U9}*DNo%xtyPq# z3Txpu_?I|&x>nkex&2gFf{A#rF>YKDNh_zEoe5q^k)No&&4e~wd)x-C!rdofuVNee zPvlb8;lmDbMV(YPKx=7{Ozy4g$Z26(XJh=ug7jZk=W$+PPokluBXi%9F{a!8c-7nD zT3Xfb{$8UCMIJuV!YvC6BmuQmJ zJgv!^ek!cB529_}ypZg?yO!db*4bDY``aO8tefgEXzA}0Fo8?b5v`A|NqMreH%H*P z57Rngi*w4cPi;r3uvRSCyT9xe=`d|0{g;Tnz2cbnNe7NN1jL~zEje_38Ql-p4+m26 ze1>u+tI~oN;#G&Z0Ys%lxYzSIak{yl(^80T^f=jeQ+e;K5N^AwIfUFBq*8jE(Ebz| zGZMfEFR2{MV+J1+Tt)0u-+QXk`43(E=fnk+4?yI^y{X=o}33lAJa*=?zbkL)GYb4 zQdXMOW1&OW*6v&!*pq(=G4zhZi2L1Ciq^t8N#sWOXwG+RPv?~@5MzPB{$d-rBptDE z>pgqxVoxp(967EL9dS9KYx>7_ejI^)$Fz=E)hR#CsIu!n`AVOou(vv*)l_STrVjq9 z?GX9UF?Y#-snK*7T$_D?b0$0QpgZ9DM$Tno1#f6{gyVn+dkfQnWi6=BmeHW4&vr3z zU2y&ynI-=DicU%~*V=Ds-kr;d*v7v^PTiUgt-4N8Ve6Q{_HlN$pAJB*#OhJ$Xj$#Iks|lUF`eAh1s?y&Og`mJ!5J!BolW!-_N z=jUn&V&5sD^rdpW=@-fG4A+KIo|sZKLcEzYT51)4gClTu#x%V7`FR=kPY;()h{kHH zB|{wg`HCkdjxm#tPdAs&cW=S)>{SY0ZIQBw;i~%dJzU>7mP%^dE31%B=1df`@7@$| zejUSZL%I69iTiM^zstZhtfm?oB9D5cmVACTwk#={$vv9XCzxHM^dAzKhJNnDT735TlE0Il%^l0G85D{*i()M$4t);R<#tP_ zA*qheZYu1F3|e_BPmsyachVDZ-C)XDvPrG1fKcvtkDNV`;&M_fBlP}a`d^};wr#5O z>V6!7wbH@Hf|ifSjV*is*oZ6X;86dVJ4awG9Fxu~>j9nZuN(ANVF@Obn8IB@kuNVE zA~dz4v#SbAFd@L#BO!^eNYvtLe{5Vzj8A>Nrw2!1ty1txKQriTd`w%D8amNU#Ys@P zMsQuH=sIb7{m+-hQir!i1-9?41RWm7>9QF6Zz146;eYM5{|%HZ-8jEE`cl+l{QabF`7*GE|!z4 zjA3}j!Edulo$RS9r3alf=^4y8N}I^Hw`nPr00q^M^8m_4gu}*4ePw*T-S;;X!3%P_L!*_ILLC zN$(Ru^j{*&aCA!1@!lMPeaE!U1}i_!E;pxd*%;JEh$H6-%Lgmd+QQj=<#s0!Jnkk{ zIbSxmvtexaDGw{)J{pN%3`RkFY%|&^x*N}ApQe7Hn7~?ibio?P@?nlpGpSFXl8MY&;DR^_rK!#1!M zHy(u-73-^PFWRutj$Ij+U}6<`rDTSeWtkz`)L!-Qj=(yrd^m#Bf}a1saqesKkqj)g zV9_lHFg&&~F$Ln#R4pXMF;yUr7xzCC*>8!Qub#sZSZf*(p$8w4ACJv}$b-mLm5k)h zSu;2SYjI;9 z$sO7qOE576;ux{(ATgNT4Q!O${!G5A=SYFj?wG(@%2*jq_K_gBkw9#KF&L3GLsC^V z;s~t8kMki*Ler95BcysZJIltoKI33Q8S~2T5@aGl7_nzyI$Ihf6$(nSMN#1c$&f;cYDJxEqgQFe#4j8*`LY2>%YZ!yGC#X z*1~syf-vv0i>6=VBeB&PUkOVv(G%iO?nT#@-HX01@21J_a#&1#Hk~7|RwMAL{S`@+&SgR>`HRZ%BQZyhAysBmhW6jca8}Xj2W54o&z3lgVp}K}_J1 z;4D+R*M-Ut-8##dz*>BpJ84HsniVJHUv&=2Sb_;}u(7Lq1~KoTJZC8IpDDF&{fj<6 zyOkrb7T*)I>yMQ(gKNv9qMyiEf{8(3qmPtBF0EG9K(4l(Az2xDQx^ob0)H*d;s*v}cbf|ZpBe2#mAX1vYB}?xsPd`TN z3y|atS8CC!AUT&7`*Cn-9+5bM){AkaDu-y*87a; z)9O@N-_`&7!CLEp$aFFmvnMI{aBZptN^8;=ilN=_a0J%k^KR1DsZyZ*KCw!kt%xO< z*akLUSsI9m=E}FPzq%#;!WD#)#mZ56Qu6LDapRn1H?duvs&@#6bL>E?pvvTyYR9D%iV z0bzgf2)Q$$F%W@9b6|b2pZs{O14m#jem1b}K1w|n1&Bd`|E!OCfZ)1)np56h7gwFKM1S~!ElHw`EINOHa<%V<|k#<^A* zQR}s zrpl^W{qBUyJ5T*uMToqdspQ}B5%C%}lq0YfeoG2pjJ&jE5vo;U?1+{UUXzNo;=rDM zmsL3R&AKA1WN9RQ3TY`}Exe+QC#)Y|kuTM=U?UGXOIU&ly!#@23lL<rD_IxLUFhD}nXf+l(nYuIYE?Rd#sO?>5Z8+m=hu z(+Vg3*+a)uGA6JVerpZ)3|1AHc+o(56Wofkfwk}|UD%C8ZOg*Ft4fJ?9?Mt@zt!i7 z<6D-?Bj8-J*jY6sEWrfcuM>KEH%s>YO0<0TbQcM0;W&80+28^#SkaT+&b5}X1QWR4 z;EbvlYI)DTnQUd{C8DzGUcaYkH1t>fdn4sN?*CS?PP}Z+W}aJ1s~Zhrn7~>~pd|gC zkZ?}*p}lmYT z5SYNbNWuw6b(^pp!I9M*zfHsvOyKxnm3Q%QX{qN$(e!4bh_!HC@r1|57}+p(2%8=7 zSj68=1Va7jchJQvdEhPb3NO~oxH7xr63MN(!7E*GNrLdO$dX-8uPQdq=)Xmk%>-`AO6dG?^gSvlO~7YXg}Ct-kGOyF-%1fgZ}R_(xV;nHn~V_Y2Acb<6K_N*K@;F$R0>Trg&aOBIutN-l; z{VlCMJJ`)qin#nl##%Tgo)`f6YKX^pDaa~Q#1c&4dJ}|Xs4FoxT}-JrTvD=(e)mo# z2kZCc%!GQ=uWp19Rd2m~e#$IXo`NcPrumlshMqn?!7gVmkYN!;_<*XPF{_1xHO@?dzZlU~| zRR4jyWQ!?dqL4fn7}mxyFmHOp~JeGi`P4aN$bG6 z{`82uJ8sjrS53s~<8>!V{O^1N`@<<>=iVp8k-dG&?qu{5Oxy-~__cDPNBRP|3lH3T zKn^My$)+F45S4o$J%P0z01;BPyjb9?ykpUp%Mb&PdNa?wR2dUki{Fzx`fv`tan72R z`uAj5f{9$P@lq@&t~sNe8P>4-9J;n?FDYSQU5>z7xJF>F;+}KpP9U}bfhCy0wV-<& zo;`YKYTObp4UQITVGrTm-Mz-*kGI_=`)Di1l?(rCntwJCAKeV5n1(%_#xIide49x< zjGd&rNb5FSdq`&D{W;-(5$t1qar{Ll7a96VxGYTYUO9cLFE#|?D-c-g4%nDo$y^*T zKZNpx-FFH*y;Wt;E2%+6{Q0hv1=c3Xh+ir)FXC%$e;G#!3F zaq$P)JxqBsx;5~b_};UCd{TY8-_~C z?m2b)rIG=~0yTempZaUkNQ+owZXX`#yL%tX5o0DWr=^9Q1QQj3PVJXQhNYE)SJJN) zbj_DYd0q5uhIi<}T3N7z#M*uuQg81MAa08OWMI;Ju|n_|h9#K5-olw-T`$q4M?<9t ztqnvh!36dYc0w==lBd`AkS4`cVzMTW#-?WxgICAt>63Z%N7HlUQ}ayv*Pa{|JIfZ& zr$`SVr(mtX$XC>_*%{I(D&sF=@wW)JbWk_-kt*+8FoEs$*_cPI#M^M{IED5Yxg~-% zJoqiMrjIYhT3YaM@@x2l=XM6=iSldb$(3%+VGU-R%Tch0$eYJ^$TQ#1FTFWX=5pv@7g>^72+9DGl92D{Xy8C$Bt6@)DK3UMvp;$mf_Kt*kak z!dm4)>(=Tda`sr>0%+G054U`^*ZHP*t>^2F=XuA(IP zO3OE1l1*TTuk!VZN!J?>v?IW)_=qC1u*-Mt;))+=-=YuX-NTpAcVEsh5wE-ZOIv5j z93hcHTHsVfRz4}=Xjp+g#flhK8qI1JmB?6Y6xaw!d_#tveD)Xd#kHRJ`@p$NXK>W{;I3WaIS2kYZ9?JTu8Rt7tuk(1hGo}I&_b6ec>Z% zQe;9sfUeYD5c5bA=!r&)>q-;NdN5)yh*&Zdv~GJFh*z$eP+XEAcsv|JIyY{@%H48f z*pqQq-|5KsZzL|^y%y8(FLm}Kb$0doOb~lAEWyMupkG)Rh`aZifLD3uEs3>}TADwl zEyKPqj5U(i9sWd8-k8$denxVH(HAoCg7QAfI?t7eMy^uAgl3#qnC6KcbB!~TdySTk zT`Q4s99Ro`2yeqpYO4=iYAFreC`q_n{{}{KT7%zYXiy!BJ%k;a7E9DRsJ7I~qYp>m z8pSm1f3-VM-DAc+d0Um464sgmHik@v^9bB)Q=Yhdb{M?3o5uz}>?>jd*ECk88_bI$oK<}_%@er>7DumlsljbDpH zq_u+@$Wg~{P%Oa&U%UCWBc!_C`PvOjV+oev`oSf^Q-fbOIqc0=P*YPsb&Ib1{8eQ%sgp4>Y#L-s5fAYrW*qfO*!8x4sH z`1u!6?a~MB^w?mQ{c^O3wXPrhK-+p8CzUrp{F|6wS=(yTI_)etWo0v1xA^>ogcqFE zdciK;7V+1}EvvKIufKlK_>NadQl~TE)zWWfZ2xFU{rJD35|%tm{6>eozDJf=%UWEL zAY6QEl6m-d1iQ={WMavva1*&ycuFGICOk*!aB5bdHoIUBfKo=9Fd zk8OO>QnXDjA*Z2E8jFRbNo7a+qMM0)M|@8bdUT>%_&sjTXR=f^2;z8TSW6o=d5PGn zS&)Q@v!FHg^bK*PI-Vy*LF!?6B6Qpc#?UqtrV2zJQXh_p+7 zs-~c|DN;igTlb|IaDCc1mCX6jjVnp_WMZXHZO7InUK(5{CxG}o>^tdGI))yD>-aXX zW@3VJDq*c|PWXV}Q5gW5E^|*0!4VGXc0f?G= z3Q4(m#Y^9kYz;quU5YN zShhVZL#wI!o+Gf9QqtGVTw?Z3A>eBcHvRgrv;*^|Xbyqo^1VzlJ#rIGg6sV=j*#vC zYiJ5wk8PJs-X$*v!VY?gQCM4I*FH7#Em$ute~E}~>T&Hy$|~=1A3|8) z@hj9>XYI?p(p$%IT!E5at@w|;%T?BRX`IKgOXEFdyDK>yfwlI4jZWEL$ZO4ZAO^My zW?3_esB_m|B9>r+uiZ4CV5Y6#oG!{9Cn}x{7{*AavC$Ow80;b3y*8-9z6b20Rct&N zmS6(ggH;yiBG|%n-&}^PTa~q%-Ug;|O~Z=DSc;q~Vm}U+5LE6}Nr!v<De6}hh06Pt~NdmXK7ouk=35#I6}!1g;vGn^PF}R z)3D+f@>L7NBvP|@fiuoBN-o(x_9dBSXI+*V^t7&DMRl#`@OoVb&EJGR`(PUWc{Pk+ z)~%zpnvU`0B9v=u^@=!2RcJAIRsQZhvO;4-FTwBSHoqn1Ygs@XO5be~+B3^i#GGz_@^ePeTLO(m&*<}k=vS{ZWMZ}<9 zUvAEL1jO~9pGeqMWo72E_7N;^h7aj{Xd1ybaJdJeq^2$IlHFal0#VLnD2r=fSx${H zW_ZRagmQ&o&+@uqY#LbZUi z2hWy1y0Fybw$kb~H?>NZ(QDz^2YU$PBX*GVdQF`8DfgL-=Rsxu(8q*nc&fH8nB}wW zL@F4}5!iQ3!%1eT{%qZcQ}V|9jPw02*ywdIjqF{ugeol<@$D#y={6PGqp$5e)-|KL zd{V9_<2bH^*3Etw$g;*;DW+kU=KH~tdi5Z(KYFN)+g54+>wDjj8=p5&Obf!61raQF z_ZO|9^+06gwag1vMLK`gzctZq|ARJ*K7jz4xt8Z5yC z9%-;gJeolH{x8!@dO*t4{q6{H)W)gj<5nf~l9=R2ka;aZpT z+M+;n(Pd{CM_}Li$j!c)XrD%m* zUkH}5zgP>?@OCM`hGq_&h9E64mm3TrT#2*tSv$c0*i?~Sy6PZA?Z2pUU zY}%P(S`eJP*V4r=PE!w6xP-00S@e}ISp9?4+vH1M8-AtPM}LuHFD8Ij#?QjZ*fvyr zI&3OO;BqnjXABN~l(wv`hX$AR9m-X_$_KBMYxQX}OdP`+iQn#Qbio8J z7t`=n(>GXceHkQzEFL(mkP+c3v$JIS?1fQX41pyiqJjcj*M z;%GP(@y9c<(Vj!%7sG)p0JQe2J`mfqqx3k~uq`Sf-7BY1Ov9H*=SR@}4`;AzYxc?+ zpyi(No>UG@rkI|o*jrmfraVyIbB4Cl$gg9M%d;1Hb2c!I?ZH!n_7~)9LxwT-BTd9w zxLjNdkbO4ymK&V(V0C|0k+2r7AD$TJ-H1JXu9C`Wwum@F>*T*rJs|ydV}_`d?N~W16YzldkjHE2J?QOoo+pwMf^rtb)?BqbCa0D3 zCBsR=S}h?n)Y*_o5(57wRwkVxpZ{wnFANBg!ix>$(38oe{GHVl6SyQn=<_^6G7JoK zIWy#m`VM3n#j9Y&E4c2lD4Dp=UlSr zSs25SKZj@=OiU&@RcCPaVE%a2OZ5Q8;4~P6xLizQ4+Wv=h#>YnW1;*ru@YCixJI!( zcrsD_jcl4?$G(3lFP(z%aiQx0V&S`=hC(l?HRlkCUb=^#hu^E!NFwI>yP-YCM%Xg5 zCg*7Ddkzds{w6F(9wfmo3UO@70y6rLJ^K}JFKxfKmO5`g=i-_eMU#&1qMe;Kx||7% zrd#3nFr#>vlyl0LNN4{0N=8=oW+$ut5;1WUh_zQ!UEV#|!O`%g#klptF32!RmB}wI4O6re-jG*`1))6=kD z#;OI>=zO3wwZ~!+M~Derl5RGL>Eh#1^Wl6AmSEp;Ns!?txTT-!79{Oot+TN;AuiJ* zE4r+Hlg=JoOxKON+SL<^SNf6!At$E>={tV0e5zhhS?yv%?+LaCPqrtor}^Fy z(xU%XJK?gh@7T5=RNOp+6t0P2TTZVz?*BW0F3gY2`~rRHOX)zmc+=8M#}m8g4ETN7 z1WA}E0pj+Y)Xb8YEqF@Z~hRg-U8(RTrh#aN3Vh6(IDrXeR9wkEFk z?b)q-dxrhR1TINeyEgGs+Q;`3Rak;O!6m_0Tcxe&7U+e=;MvO~>**!uHrj9AH!_>1 z?4mI-_S#k5Q!@+U_sgSgwFg4tGU23g=!x&3C$@&3h>0dZ?3re*HTU6ZLHLjrPlwz6 zmbZTMmR>*O9j-jt6U}X*TUBAO~SisRmGA3SwSJN&x z(cZY!jHBV)r4=)%#nRvM2rnOo{lx?>3GQBZ&LHkyK2lAfFo7e-w61nl2OB#Yb@I~S zvas*CBskr1*$fgjV)OA5sNrCU+@pCL?Sx_5Xez`J=U79VylHFMwLu?S?Mb+X6+%r! zP5A1?au&=}m{6`2V(%Y9Ps0g$7e;hYW@f)vYmZ~CG_dgwh+ZL^IeYL_O^&CD-@Ms) zXp>MV*Y$K0?dE_@6ce~4I3xFbB{6;dPqA?A2!;tI4!!S~7KBAtH`3DBK&cpdJdOhs zxFlWe#?Ktm83sT-ZG*l$56W`a*sGnPTuk7S z1R>~DJOQuRuc@n#V$F|}7LHBMNhmgf$^&UZGIq^cAy}Gk=YNnELdiJTI zzB@gxEbl7U9pM_r`I&n1j(fJ!sXSYbQ1akxv5h*i{|$~7gxios3n7crKUoyp*gwuz zoik0BMfJ2Gm_Qai3w^5cpDe1ku6U&EEYlkRmS=GT9)corMi5T)uWBNC|Z{vpAV^_j;+xK`c)l6JIzqIN359cQy9h=Lr*CA!wu-J!)(ejoSuevkT*7xLogE<+b=H5S9&ca zN5vO3QIEZ-%ZdLZTw$Cygr2VSt-s6F`;KY2Pdpz_MnJ#X0{sg6tK>vIflJc$tD&nJ zrw2Iea-zPjuojLF=0V2*<{r92TxJm=uARS`zOk!9`kvTAr_S3%J7rZQZ!2z~li_-K z#$@gYW#^WA`-0iarrhHo$NR^x!KL01gDfG zM06p_NCjMUKw!3t0rD$_+ z*x@y9^iXyvG?p$w%9v$CrQ$Q2Rm2IfFsG5HB;T40gim6yGNv|X`BUqv2rQKWIc=^z zQo1@W9EfzU5M|cV$MSR2l@hiD>r-3RynH(<8?{r8M>aZx^TImpch6$UwMI%?+}eYV z<-1`Y$J3Mr4{XbD3MTTP99dQ-QgN{Guj)SxQIeLvl>=|>k}-j$nu3m9%Lhqw3LJrW z5iy0HEq^s-SkFfsr<5h$SE(W0c_fJGr-I6Wm zRub-K!|Om^{P8!}byltnOIg6*PyZX^+UABk=!nW`L%SUzWb(r{3YNmO+A8r3_Ia0` zxEG#5oL3FVck`2?zkGR1ul7ugU72muq<-CPfr2v(Jp_mP6njc1sKm<(9uS~Q%vo`HMK5g~ft z;Yy382iILyG_+v(iF8HfToPT?TK9bDrCI{9FMp|I@uNW*LR)17t)KaUBzIrK2Y}S2 z4`I^NZAEg`h#BnT<#1`(-)tGv8cn?ne|mdp7xH*DCCi|+d7Y!BJszClwo$i-OWb^# zwtW_F>*i@32)K^tk zV}S6<-6HiGc3V|%a2j{?ESh<4HX-jrIhL9Z#0U~CJxE9_L-YxcBDEKfSEgP(OLlMA z&06=eCSOy+*gE*_6<3wKu6lrNIJ}Gfv93X8l@lYwIOp!P+;q4TU{V!26{KpJf0S0a zWwOa2HDmBEDJ3tRO^4q#BFd4i8!iJ;t&yLy!MrbNylx6v558f;6|vIStZU34q!M0i zk(#|rVzc0Pt$(AX+fO(Uw%_VV{)0Nx#mAaZOay_HcpfX|997Y^jo%4LwOvejptW zQd5jGq-fhLhRZY&{vPI}Naruzgp#*{y4v&kvXprqM0 z>ML!IJ4$;YC97R6()#jJb_jm&kE%sRF7jcxW#PsXyFkTX8N{8Z%$Bg!EvUDzJ?oGG z&Qr?}Z?-Q|x}DJSU444Um`DU2J3-%gUk`?9XhCR?axM$`rKvp_mVytTu>ezR@*vH% z3~^&fQ)S1Ec1o*v{v1oC0Wk)8pU0O5Wr*$OIiXW>h7&2U{{sgQpLKg>;|y_y5L4Z-D#2NOZs3x^_Ol$%Gg# zPmt9_wVz{@=5UwZ=*I`S=nZ`5|yx-bpjyoWX)aCkNe_xMLwSNbOvKf#y= zpBhe0o*A=O>SJgs;SnGkdP(lJRg!161;aFWmSEM@NE>7Z& zlgbdCtHW+(W-W4PSUnl%E1pN;0o(u&0Mjs*u*FLA$oiyPfTI>miBUq#Q4?W~QWHDP z7Q($BQ%PFgj=Hf#FSQK_;g>W9zeG*E>fx&_8O6y)i|Z1Wx(Vf&SlLI)xjM59QGaMt zCH4mR?)m-%6JnMTp3^k&oG`7?bg&Mf-gRe_t$FVyEVU8{F`qlae6A+CZ3(2g?OKw1 zPYNVFXW&s3(-6OcC+gAi0%?gsOM>U3>7c{qXS~!l{IY7)h8ux^aIBRg)jsJ;uoNDh zu|C+_z8j*{PdAV@Uf80=v%wmutG$imrOENv%jodgK7~42ywvthd`K`c4y<}p>Apk@ zvKXc{nv;P6bc%bC>)}t!2$sS#wVId+y}fasok)>&6_{Y<|O%F(*5AsK9#QHBVT7Af_8AF-O#98`p;Y17RnCjL&xdbLoX$K2J1Q%$;*PIGK3OSjl|9&O8(zQ6ibQr_o;40f*%|$LtJdu65c4b zRKBnIOjJ@ZGU$CDwN=80iyCf_+__=XWZ@4kf3cK3Fx$a|*LP}A0NZhWDHGn{jPi@w z+&y71J9k|tQQJ@Tl>CW~lEpe>HlNR$t@TmWl~`r08yvu#7I^@XIowyN^Wz+M z+PyX09R}+C)3+us$LF@R2TBB41)`4l*MXo#o-huqUkM~-mTYuPp_=Bf4zp$&27A@(rub2M3w!W}G|5*4+Lvth}HfpLeRo?<^H{^$q6p z$C(kt@B3wj2{B*2uTg^!Gij)zVI>Sia@Z7NSgEf{hwy4lZ7TBnex)Ar=&DwHW|F9@ z{5N%^_27Ze9n@LDI)qpAGs1*_k1zF*^)#GAzFbGD?>bj$5_EuPLOF8Y_%JQBxtKXc z4}S$cTv#Z2{y6CQ(5=AVePy(bC(WJBFd<4Sdd5uX8JGs|6~?QJkBZrzTJ}_U$b*_I zY;ML)<^xY{-o{gGgm(rLV^{T(be7UE3v~3FVW7>Ut6Ai+28~L+@Etzo z`I?8Lxw~+O`F1+w7Fb}5tZI@>57^m~X^(kUJ*Arr#_vrhJEqX7!@V8Ob$Riki z8W%UBVk{ADZj@U(;?y}2#~zwz=vFM^*_;l~ChS4N=o1K|&)5G(pZ`lhInG~R#b(q# zpc}9BG`!>9$dOiwaZ*NmFDGIi6r;~K7=3WPiFKQvh8t+!){&k|a}__|11dtyyJCzA zhcOD%rTr?~cpDFEJ6kuO>!pOxAV#<(7~#}}4D(>o-GMwZVwBFy5YPE!Xmc!uX^0^M zu^5PVGd*>y2|a<^9Mcf944zGIF5SoXwKvmwWcvOiJny~B!Q37EW-Xw_E2tdH=G$J#19x1NGi#1j?ybPGGWs!rEZKe`^E1)LS5GeT!$i?w76&{-u}v#V*9QM1u7FiTU~Lfo-`YSgCA|KbtrT|Id~zA9SbiNT z0miD?|E&%5Qo>j7RW5@)arG!elwBL7o84!(3QN}pJuBxiS6aF@(9>|<2iAkXbE}h! z{k6KaL4}uvY;NVra#dJI*|#?24i%Q^Rug&}&dK}@P!@Q{NE`Of=E8P8AxhrA|1Y*| z%`z1YF@0Fq?&}jLP1?~^w<^+0iP|;USdLph-ByN}0iLDb!vZPWsdTNT9|!UHh-r=H zA83!!MlFf5rhwgteD&k2=vV7}tMd6%EL9`8MiUQ2&M8+i#4d$lDLl4geHzUiu*#&` zAkz5mDBapXKTjM29h;Y}ZG$s^GfCg>ssdZ}1=qE`CV;-=3beuZWt zji#{n5#HdK4_!L3ug-6u3iHy@{b4K~q$1Z>=WhqaGEBp{J{a5A-iRQD#g}zsiJlN+ zSAUqJK2_YIqQL`zlER7(Bj; z6_0#zvGo*;dtr# z<9|9FVEwVe>ZLaLbm{s-Pl$CwgzqwQKp@4{h^n_voqEQ zyZW$pUf#${9(-)DiokO?rood@7AXctR?A)$I_gT^|4Tfpv-PrSwp0^h{Xt>X%8y0siZl7@^TEpN4um0oSx#`YDozrPyGwIa&1uU|~G z7gu+ZP0U-ecR!Z7f}aR0me;UinG7oy(UTh+2;6Bu%ej!ry_^_x_uu zKG$!mq%f_~G&TyRF2s6K5gc#A9(%+vgipv_?ZRX3)HEL&@(=yNChk5Ubw` zu==eAzgH{Uq(A8?jQ<(J`1xq5!^!jD$;>ToPpyVU6N?CYiU}%CgXgi* zl&mZww2P?h4v5NPLg?1#1ntqpOzHn|E%7svGG9V`+RqD|5pVSf$Iv> zu&WR2!Gq2A@ZI-gwKJg&M10o_;=5XC!KZGuNxg@Y*i!hri1k*0STDSV4J99RWh0;U zV5^K%FtHg35xK1bky~i0c4n`d3+s_=Ia z#k+3c0X^|b1z(zw7$wo(jx7Ylrepo zjC-O1{9Q!SM?fSUPBf;>rMaskd6JhI=^*T#S(Uilj$yB%1@ASjMlQXLV+LU1ofs^IX^mzyl-xedjE{&&*Y$S&vxW(r z6U@#rv*_oewfo)n_UPXw0 zEMn6$iwElnJq@SAo=>Bx)AqAzZLV`+iHMjFzcEQAg=u(upiLk8_(5-;cD$N`2~i6o zLZ35fnTm#Qtgq}!BeRF|25su-O0Jhmfgb*2rx7uF7Ey-S2E8P(S|#pnxl#8-=?U=^ ziG71tXST_hhS(DHlFaJ%eCy6xya-xK>`hEsmY|Ztv_@mKbt=s;4dXf4dsW06pv7K@ z0qljSbsTS6k#t(_qU?od1WPS}a?FdUPW)e3F*Okg&qs4F1LZ0_Bbdkm9kZ)hkwsxe zGN$212Pk>yo)z4lw&7SR0|>E?vmEwu)WlRM`GSs1`Q-P-3`?Z|A$FI_!|sxr_yNyH z&5h~&@zL~`xf5b9O;L#b= zFn?U=N0V}@E7tNu3C{-j8B`M+%X!gnK7VioH?11>~-z?7}q~LYOz82Q`yY5k*)*hm$D^kDxbP$`_N{4vm_=r^U$wex7^8m4=H7cB}am(`@7BZ?d35wp=bltb_OTw{J4#ny(jhW4nmSd|SRu<}iwOWCvMp$|~J# zuSO$Tj@vs(Z6pvG+FJtfo)F zgqYPtOlE&4;q{&9`%XIZZUy^zAxOa~I>Iua)veP_7IUzO?rizs4utS5HQ-rR{Li!0 zr(i_c5&bH;w@ogDnx2-r zjdgmL2EQe7DudN|>FWDdq zLPU+`J`vvQO(1HY@*wvoM01=X#z#FN=3o&)8U>MbIK>K9(JLDXyon%-89+pFRzS30 zjOUL#*XEB4OFexNt62vT9XQ1b^I)dq9x}akoK|@H`V>rvSz;aJbRkpR-`*H>oT_e5 zw(Ogw^DISVq7B3^PD5`m*kQy?Ev_)pD@8P66T}?g9%0b2s9GgLt8CP*2lXkK5PqVF zg%8oi!V}g?w1$%xS@os9ZjGZ)!Gu^9iKx20F5d1v!dGdyXovK%=$y_M)u&)Wth_}0 z;jb>HKjL9?ns4@#)c;;d!8I!U2eBW~33fBowL5FXG^O^CXySHnt!|Few}J2J2 zys!@86N#NB6WD2jw>i>=(Z>4@blquR=7k zbe}VIP0s00jXjbvfu)4+BVw7WAo>a4?ORn*N*VxPtvqP0;2Le>Sv7U5qd9Y3v#3n% z`ohRC`OzU#C9H{V9VH^0Yap_Tb-aV;acO8Z-nqd)pkp!+p5D>q z@eAJTRMRjL@L(^&d0{EBdex6Hu!EHlq{MqzY8z#k>S8kb=NS_sCL^MTdmy$5w~;_k zJpXa4eE;f3f>T6{WOuu}tY+tICPoIa+ZUl58ODKCHpQ{*SZ0<^hdu=pV)POFhJ9e) zP@}Oqb5%;~8p-Wm&7(L46N#X2%b_?HbmIyT8y~>v^I$IbxYbrgU@0*sT3k5Atlx?K zLEoPNRQtx9PqrPZTc7JwFroGtLVwy&r*4VdhPT&^qIv>LVgCWX2k8(*3$vFoxx|d) z`7RIIV2$q@R;}U-mHz-IGaCof!UDpE^m@Utlx_E+?2w5Ub3OdA3{kYE2R#;%&78gM z6ihq;9gS?g*??1@WlWboQS63sa4d|nVXsziW%I!!k2E!5V|obB zGB6I_0&G&{Owe@$-CHSoDM75h;?9PxDN9(IhA0K?O{K{*4@g)_yfIP~FqEaro6G39 zeJ(`FF)Gv=q?f+OqL&iyfBcH_WN+av9JN&|P6jI(@41xJ&{p>zi=Ghgn=Gt6l5O@5 zXPAb2ovZew%m1~f4*z<(U@7tT$grv-S<61{%McgfW{vQY&r+wLUb?qZ^iqw1un!!{ z&h2PXhPZz`M49pSi*{m_`V32nH%9)No3Jy>8%cU;ExT_qJ^jUw%QKs)@_G#A@C-I$DaNhKSk>tKJbF8~3qQPjJ{RwKh_@jAz}pU( z5H<2Yt442FK>d7Hclhq`{}Sshf6Gyz1Je+>1Hxasro*2ygwW@Z?jTR}DAlK@Ax_;n zNI7-ah7~Ti(pjaK5-0n|#eYlPQ`uFgGsV{B~0W1 zJ?>SIoDXeKPrNadIA6Y|YmbuhP3X@fD_L`&&PvS4PV9N(p)4}tv+U8UH7juI&ol#{ z%Zbg~veVtivt#fZj{9Wi6Sqy(d4(C{X_9?w)~3<`mQrtX>hp;%to5LQtkI__sU<*U zj{-mb;#PQ1_{8yGI_7FRD_(R+l^53Wa56k2oyW1;hK8Wy{eqd)cBnsJuzwxFd0{E6 z8=jBF!E^w9Bu#96Q2Q0~N-*g!6}*m2jfdaMx{i}Rb$%{?1*>SU@zVUq2B70z&H}oD zxRDW^D-ld!DWN;abGXD-iE@m2WKZi@Hql}pnU zABR#xAFaVr96>)DaXK{+-XGOyOcEPQE)BXWXS_lE4FRu+WQ(ZR0PU0cb5$dRYGF8m{iZ4P~vYC$bs zx~A7w5m-vCV$F%`cpLHL=DpU7h8ojut{ItqDh6yaCE=S)vGiilPBa&L@7;%O+ zu*&Ty)r)zR(sa8Ev$t+089!N?(i;AL`&v(FOozO)u!4*%CX=1-OQwONDJI&1RBa%7 zPq1l^X^rMyBTpKeQcj6_5W{d@Pr&vK2L0f)dZcb_|KFJS$q+`-!#Pr#;!QAt^TjmW zIZ#qUdUjuM#x~K5VoUz}&01u7Ct(`)?u^>e8e_7~j)1nuDVTT*7FMxt#`22{q2$>| z=hO9OlUWnPFoLDpK*{en=*pA{yU*hJ3gU^<7s-0AHTCrAt6(WS`>2UUwyo*xIA87w z|6?6kN^O9ZhuZ*e)2vwo9|32}z{#kyPaudE^&(-8d_ z5kz1A{2*0&ctrR1qF!nk5El8D z;=38kVx}nNawB-+?|nL}^aPd?wQdo9UE6%61z6ST;zDX=>%q4i*&*Q+Oo%%CI_!?t zt6g~@_6!cDa}6Id&4^aIR@0|oLeyLR!b{rG7xKX>(dK>!*R@Z)(L5RFg{4H>tlWG{ zdn{d?*>-^1{T5w?<$WuyU41!3{q)*-NE@-frm7Y+n$?{Gs7)_h$$Zjsj%yUx6{a1^E_W`lU<)(hrbJb*FhhAISX!MUvE5}dA(bz zBE;!NQKM6!Mlr3?gl-B}=KV}(7Kf`!Sn3WCqTaScjjD+{&1NgFLXY#^A>A345@#+~ zLH#tyD3aAg&?gJ}w|^fcUAvTHDGi)3tr>nr8@ea23~{JiTP1a0HO0T&0~PTIbcj~F zEm{rHx?2jAdq?}6fm;eFu9HttS5eTztL>_#t1Hpluj+dHzenMHyHIPbdB6aI32Zy2 z;mjSZp)3*#_}ioA3f7LT`VJO~x&4^VX9%nqLOTqyW&QR+iy?cl)DIwpXV7$@E%d7k za~IQ+Gj`+v-0>@FSByA)V8jt^BSxY>FcOKJ>{efqm&fJ-!GV~WVn-GMfu&TotBB4n z!>HTFRC0RQErJQr$Hb`C6-G4`t+~^^trE%F5ZCT)DNezJsKfu&Zg_*f^i129E`P4p zRzwMfFLE17SO+W-9#R8MQ(0Z|Mxk)R8~l<3UmaA0s4L-xt?JQAMT55l?Xem>vc!Yt zif98d4kp1kh;?8Z?*0VgHV}`?5V%G$4Nq-NEsYJZ;!%&A(sE$?)j18MQ|b5Q9MIQ& zYc;7!l^613`2E$+PWpH26KD^+FD2whoR{KwD^6?wJw~oDs6;ORI7WWiHcGy_<&V5; zj3v9iew%F8=!cw>69dHF32+XFADZP!eTo20hD6FQ`>GZc$OhZg2e1SZFWdpj+ zx*NsXalT(5r&cF+Xumxj30C!o+MV#Ek4sefb_&k-H%R4y4qm}f7QaIl9n|_-i529U z+5U90)e5qCcD!^mIa+Q#&y0;IQ&+eSVT8LALcLv@C0$rkLlQMwu9Ydf1~rOn7v}_f z^r0b2H@|7pzT$(j=nZ-15!$!aTFJN^KjH7$wYO-~Qmw(NRu_VmMc2+smtWVAuoR}% zC2zWH1z+4XfTnbC)GnyMP7b|e%-Z}{4!wnHt7gWA&_@e;Fpd9St;lQaksWgKn~^#T z@0di$mF-~70c|s2hy{!2lnYj^f?A!OTEIi&%_%0ZlxU|B|5&mSHAOE84|i7DhC9>s z%_AiD_%J!?jRA}Qudeh~VQb-b<1Zn~&O@oE?Ha}F$|3shXXvAtRudl3=7tGhtTt_R!h_08A-X2Z})5mwz6Bg?zyX0$Bxz5|3tP0;#ZLaJG-kU5JqVw{K`@< z<)&402|sIP%b_oyMzia25G}XmuQaxxsw8SrpD(UmwT?f3<|(kdJD14w z+{0x$^bE9z)81g(srPIaz3G^=7PKo5i{;Y|cC#?}E$+hE0(aqvI|!S-ugt1%6emoh zoP+7d?cOYULbimZc0$yVb$uaEsvcg3xEbe9-CC{S@zo-vyHAYamXm1tCs=~5!q&n$ zna=^#+`fr4%zF{P29|VvRxHyib=X_5WKCgZ*5u#DI^QQMJ6~?_us>D{nEix2#H< zU6?0r0YXInPeSBB0)C4ffd{bDAl{I+KR%W{zcmwxW=s8O;L&Zw_C%tq=_+IPH*deZ z8|nmGsJ3eSfeUd?@*7(^2gA4RJSB zlJ5#Kwsrv3Jg+HTerLd@`|gu}Lwn$o;~IfC^%5WO;h(0^wIgS`;Jg&DMC^r3gB=rG z>+pu#rA3NytP5#$W|fTV1k-9_8jRF7-2!NBKO1>=gWqyy&1iWcvMrAF4O^(T>bUVVONV6_(BAMa(>h>9~FMs`+NB}O~fx5e6P7wV`igq`XuCbW^)Jr?UV zTuFe^*2vG-uBjEp)&tSPyn^)gU6k(rGyVOL@aFy1mE7Vw+(I$PpJD>v>L^B^rz;0Z zwJgNwV?SX!%`5R@g=W_YCa_d8=#H`)CE40V0+9zLcYa$!7Hz#FPlNg?AN@yb*6)mr zYe8LdOOQSTlzq@$?Fr{7?X5k3v`J7`n7}!KPks6Ucl|U)S+I8f8LVB5AL4exS8zL_ zcxuHhg12`VX!Jb;;wwC-J{rLP};dmpta~)3)1UByEGb z!UWCJKrj+_@Cp zj-p-)*8;vL7wQVuP{Y5J@Z-u|7OJfZueVSsp4*xyH>ksLop7*9+)mhPuuGZS zTOHfvkl0aE=rOnTE@Br^+`nlGyP>(z29~D}yWUyTMYnG#?j7{i-8)#ksf1q~>ZQDR z;G?Q5Y$1LgVU@Z+m`*Itkc_TB(qbKAT+!DX)(7WH)@N#utbRy>2gcbnq?>e{efcdIGx(V&&chR_>c1HtjmXLb}!} zSAGe9&wSt@xw)i+j!1|pJvv!H(vO-`EG1~MCJ(9jL^g+*wO9#{eIi!Ep-a7J0z6Sw zS2UM|?d^|+X;*;l*eYx-d}$nXfJT&A4zQfdqBu|*}Sd{}-J@+${ znokPX#z9?S3)NOdmTOPkzSL6&{_IReoro2^eZfds^b)Zq53BJ+#=2ooxZ6~^r(YcT zyCjr|9w*kdDP7a$EyBW?4VZT}#F^mlUbSr4sD3ZNs+R`slpOe1_*koJHT^Szt-{vA z7d@{{R1PgD;H?*Hbv;o}U@7(Uu@O#%J^ee6Sw{E~YzZ!h+NwhMDq_I)Kdvi}zth!X zCHt>vY1t~0S>S@U) zd6dY@e#K~i+!el0r3eBDHAxM3 z!6}%)wGO*Wbpq(T87uhi>(zBD$P+`twS&PD;j!wi!q&pA!1p3j2lS~Zy?ziv@hJqn zmxfO*z!}IFy*mti(S~fRy;!wVjd#YyK81eY2&~%qk8F_efO*g~9~J8Ki~8nZ_Y*JY$_ie-N&t-<)mSQkm6sS9 zxGex-w$}Ra45fLW%WT{EWR8i$;3uqaxZU+u)&06R{kxj)m#US|0Ak8hXJsS&bAHlD z!p{V*U2HAfBW&QMq_!>LFB+D%hyHoSw3=wv{|~=8VGh4LW0-I+ebzQKO3+Mxh6ro+2LmY!{;tvd)rKg0POoMqg>@OOU2#i+ zzD7gg_w8KxX2i!#sNGLX`Y0Bomhd}|EmY;eQo%s{+0UeKiyR>Sj@J?9<3eMLGXhWY9(#jf-ROJ(2&kmrmQ{h`Fml{eI>Cv)#j}mPQ zs2^NcxDGWMw{QM*3th=gG>xTtuw#-otVCNK=2}dviMjA~qplZ6@lSGdl~tllae1=j zY4((13*ly?KhBDyxf}PK*-}N|dc!oFfLPsM+1#R@wCzI;1=o)`=-7JWo;0M}bB1a7 zuI1hSO2n{AQl%Ygq5=@d9_LA&mgF)_Yc%J!j#cizNRaaSf8$sOZW~O)mroAAA+f0w z>DI$Lv@+}>ot*qrYYLt)t}9%JFqS|ZZUn^POd$^U>D6Xgtb|)Zdtd_R1TmRSlN9N? zF^O@1pz0;KXNcOJ>GD?^)b$bclChWiEBAXZAj`L!DL4fa)qn`uWJDUixC?~w?~cl; zx2Y>R(GX>Z5*jTx`KkW zW2>Bc?PfjGEy(gmm%yr~F(sT$txJQt*HP@jUfX__q@?6B!%~gm?>7so65nJQh&0Jf zNjPgr_b$H9aSA3{1L60sCV4YH0f-6}`zyU>m!t3|D90&r@Z32@Ta(Lh+kzNJF` z)fap66>dOgVwiB%V z1Jv#&yE>%6*p96MtKOvB5RIic^R4Fd{LfxRE;g+4o8oX;1_)^*mCZ6WU5E**t0#e}!Ymj61f*Z%lWA{W74k%)_mlN|M6FTL@P7_B+%k{84NC!EEBo;cY( zoF5xfgW|lfj>Dj%Tk?LXD3SnSTkRshZ~2ukyV*zO^@;iF!iocuU))`l4-XNRP2wc&lU$y8x}jjhGu)f~~^V!i;0>q5R$t_ttVll@2S=q4(jiKG+k6S#5U3qvY2* z3&jb|kTyU(X=+XatZyZIw0)o9 zq)Fty)T{~NT5%#}GMs?GHLb2)lgJX%YN!|eXS}Z@+CZGF=m+hA37ix7C0^r|?~b2H zuxGf0Ex~h?+A3pBppuj~gfwsJ&G1}{OO9!H&MWQa&*SD%*O_}$(_in`o?c%;3O~zvv)YajEN?ODQ5^P>hMPN%X4L65`tDT`SV}#X)CudO+;&;VA9SopvG$r^JLwc71ymR( ztH+Yb?fWRtYHZ~2J`%+#nAmoGCmUWjLfY!E7Dk`5bvi5QQS;cbZ8dS9s3v z&Og&W;miT>GOjMY&U*~}D_vMORlzA@?K~E4#oRJCzRddk)3HuUqqEbbf{iT|EY%Oj zm5UbD z=~aTK90OK0a9t)H9I#flgnHZIxl}q-b1RhG{i~C*wcjPU8O>SeWqgWTBb^<&K_!K0 zxF0U61$VsHm_N9(Kt`M2Fj~7c^&tFi{LV*u(S0z~?we(El)D!_$t}O7 z1WRH1ED)8y_LI(zX#vmRfPd#Iyt+H#l>!M)!9*tXn5NdvB*WU>;O&9ccEgpKv2)42 zJwH_hmSUj8c%&p<_}Ur>qpZK&D!e?AZ+cRkf(Z_UctoJV_79~v; zTqh!`7CSJKJsg%^rgra5>Z;V}(D6)`heB2!z^ z8y7&9Ra6tgt4UjWj9CO#R?)B%cdxH!GO_9In<@G@H^U12-pPp4uU?#u)a+4A%osdH8r6(PoX zef?k>JOJ>J*F3t)96H+QJmha#&)M8-M^rT`eC^(;g)DjcO{m=-V3pB>0N(cJ5SKHY^|i52lXkKcnD>hz2e2GLsUZ-5D^5Vv)Wh^CTXYG)h zd~U8-4?YAB`4iPDjd#4&c>wy9oluS^b>M!4oyNK~r*h4PA8sJloM(afTdTKn)FD;3 z=G3QPLabix*4O2&o`|)x8?=YZ$9BrIoCuvqrcc4dQ7Ff2FFPLnwH*+(;S9i5b5F%- zk{Q7%L15L|O7?tc_5j^l-T#(7Uocaw=tIG(^e$dXMyrK7|4N^N2@xBp(4!vT6Dr~i z8^Ld{7urZ^(bJ6K6ikSS#hZ`z+~ux_W&CmXQI;G|<31Mam^-A5%(Ua*k~Zif9(t+1 zVBwI>HvH=1SRgJPfPGG1qId@8>7qEF-D>kCZQ>Y~65i{Of|`7tuZR?VS?;Q2?Wv%= zjk=|a6zNkiu^ncHhP(>jefBI6kq{RhV{54_>GV`ZU?~x$TJowYPdhK-SIdFO57#J; zBj8KNCObN(1$YU2i<~RittHG-3<&AlO$4wxt_Ks9~WykWu ztUD?KONq5XmqzB?p}rtYJM~j8UXJGX@03$;3MRz*tJR%xt)SjFkuV5#I4{O%l#~f$I!37Yzb!t zzG=GHt3EF*RRMI|zMIFKSLXt80M=^GPiwO~0gV)#f(a3IPP}}NJ?#4&hzYP(i<~n~ zdNJBd!6}#!IYlI2V-^d9jxj(OcXS}$)+FROr=`X*y>BqhHT?224O6TzSBo}yY`fd5PrLUT*0(Pa}4H>!oeAA*@XJ4ISS8% zcrJl4@!zS+lGLHhao=s-I!ZrVVlP8Yv`$&5Wc9V@4X4@?Tyo+2+RiA?5BD4=<8dB* z>h4{YKc?~A;DCjyu5iAXhTHch1u0R>%(-KVlZ5m70e$JiL~DNIqankiHq1E9eU;bm zQ+buVe^msQ!t;to^T9e$X}ot7Z&LkyGM2gpIwse#;}iN!)t&Ml3%_k1h*REqV?C7o z50=W5T12H?tjYCK>iMJD#>vX9KiT}3)mPP=fr$e^FTPfjzsfiSI%ZD}QGP7HEF0Ea zF5$ee6z)AR?s_g(-ps4a>vuY%nq@G7M{Ti3KUe8+`>0&)O$^6RDju)IKGo+5*=+3h z$6(c1>kx(8C1@)&k7by^QuyhD7+K6$zUcF7GWcj`1^dzXNmW0C3!(4!2`lDTN-|Y` z3GQRKFTk6u%uX?RX~(Y{cB9yLmf`sjZx)-)+FiyAk4qV<(06m6~c#(=b~WeCEGd5miyaj!CzVs9IdB_iTI(K`%$#xU^6 zCd=JPu$?dSQv!8sPJN14nHF|j#$JwJTW0j}_2{ll2-?SMo~lH#R2&e^jOMUZ|EY3i zDAUtQ0c>GM;pubv1MlnDTqz8#O0krPAnZ9YjeYIfqYN?dmmROrbbjjXM{p7wW-tA! z0qaxi7#dU?Hus-l)GOZOquhz=ERku~Oi=}W)!x!0x&Y}L_))Vjd zoypGnp1RSw4~)*S(QwCB?p}7O>Tvl2-0=6P(;jB`&R>+g86(5iZzes9;f@qY>9Q@9 zwOkV=V_Hp2-rknxkNqjN=gul(JLvPj9LnBx+n}Q1UIQQ=?;FUE-D{;Hb_21=I*_HV zTPkB3PPe^n!j&X5C1{_Ainu9k?=c?kFqLFX!`Z=W7PR$TD`orL+7wG21RbIU@3{3S zL&UXrrJr`!Q5?oc5lkclQK#p4w)BsIjA_tu<~3 z1Ldvo+qS@hXN``8zMC(-BKNl5;DxK)Db|4roD-}deZA?hp0V6=^In4US_=6lx2evX z&x1FLk#4A6%ZW62{z2~j;Q+x>5m1hlA2s;ESKrGJ%ZFVgQw@hJ8~(XW?9+#_cJXz& zue}4C20C)xZMaXg0UH3nS68#;KbDI(s%+*P(r&@s744XFq&sLgoK}nP*=(R9a89s} zaw;MwLpv(|o&Tz=!a8tH@SKBH{_DJzQ&Z-vtiqN!fmPjR*z?du-Nmd{V=`St6wt+s_1?OV&YK#KoCOTN(SGCKk{4V|BE!r#MJVsK7y*Zn&W z>Ub@I=Vj)qh)|%#+Nq@8O%)As>Xgy+V#-b4Cwdph`C?)WSlF$cF<%lc?t%QWdpsRr z`;B>4c*|!%zK_m)WW@I=TXJOtt9|1MYx^*l^#sBLZjKDU@C=9}@y%)dq*u&5tCNBW zEENG|+F|#SrF%UA!t!|~S|`<>q;?&o4DcJuzRo+#66WWyX`t^!at13($YrzO_l{2~ ztZHvTL>jiCIh*fDA!Z#EoG&JDP7qJL_L*d^sV&W%J6^%IV*=*{BV0r!I^~) zDZ?R>@(Jq4e3?Brj__glxzT8j+kGQ{?8Yf<@hXOipHSN5?e_fLtyL--ZfWk2KvoC8 z<^`^U72IF_fw=9j;f=39(AE0?`tIJo6KI>O)%fPsd8)n}1MSiDqK5wny3H^R?}kr& zK!*Q$&0l})rRux8ftWb{H~VUKk6{|lQ`ebDPuaZSw_BKTYf?-Oiz_^2Ia%CW5f zbQ;*|Dqr?6jXeR|ou|VY*a_PiCU8!0FAm&wpBa_Lzi*wRBHnhEBd1H>8O zr=y3E*?I3sh4-TsEQQA|tQ%tC2Nuy=PMszHf_5AeabU^K$StW+J7aWrp#M+D$;V4r zw6#A8_!*#JsUol>$nb#cmdnv)2ytR-_*>tkr|;{vy8@-{^Qek!F(H=Wl8f3E`;l{C zKN8lp@K%ZgolfrG8LBD=CU8#h-rc>*BL}wtHl_7AwVH(cXY8KMvd+c~o zyVhLv@Nbs;rC+PFbUxKjvPYT}f1P0qVK2332o21zVmA9iRoXGFCW_&yHD4CREy@qn z^(%eJu_fY(5@+@|z?prGrVe;Z&J(xrP7ytIe#!ntXQk$|a+nwm8Wq9p*>`F9^tLsLe!t%z% zE;NhH0IB`wK1z=!KGn^fy8|`E@!|s@Ud*jd{ikmxK8@T|gqUUgmX=604DP9Dcnjif zZF=oy5z$KZRK#-7k+ay8{OfUx2|xJl5liCZaT#=Mjkr(z#y=n-^ZTg?G5hE(!L&wG zW9(pRd^DRx#-`~!WPM)3kKT8$I+<3v)FZFrQ;P(qil|y(`Z!uobByHsA5jrv)YeNK zf-=4FFd-wFioFTz&%rcsahP;s?HrwVua|lTQbRUXCnGYBFg1|?v%%Y&U1%SV(%C>y zh@RNzh7GYVjMvTcPkn8P?{IO;W)iF>_Uxe4x6g0g{GlgsIWP^L{z-2dIp7&FOn9Qo zOL!JlciNMq@TFs1CfI}gHGxi9{fbmOSirDUEAaYG)wUxAuJg+fd9d<|8rYHc>Q}n* z+Sax@ncDk`EN0Gz(`%7NA*JiKa{X;c)@lPNM=My@Zf)|LXt^U5Yt9P=79`U-Qn#*c z6m3G*>>Q|DL3$V&lRk$Az`Axdn?!qldm`C>d!$=!S3LJYsy8h?_5Rfn%=21~^w#`f z>SM6b?p=sN)7q*b&A!_u0_>A9?MikikL|FfKrrhdvfckaT z-)F;H3;iR-viRsNeJ?7r*^}!i_;z+*)0qW?-w;;Ly|4b7(BEd0>EqX@V)?-tDpF^E1CZC^Z=(Jvg?DP4Pdc{>ITgh+adQR{Q!_k<8y?e5&pQ|tX8S`;l!s{ke3r2<>h1n&W61*NbT zM)@`wc2Vf+d@EZk88pgQ8vM#tT=s0a4c#!@M%6QoGLP%&-LcpIN1`S?dU@y77- z4BvBp-$=K9PGXZ(epgCo*O5}Lz@1|Ktxp9cP>PSp^*WhM-*@+xER)`f5w&xONT3v2 zguVucyG#An91?5gNm1vo^u7d3#b>GXUWvZv!bmA<{b+Glzc~hi-$c~VA&*#cRfM7M zqTigizKECJUZNG`riQOGwhU}BbaU3v&eEy;h2#Yv@~FSh_4bM_(b)S`S-+ms~oc`?05 zMq8oPDY8+yPvS?{K2jGU!tgcVzt#2DhrXe+8Ec11_Z<$3^CAkVzl8O#3`*g*#ALd7 zF;pr&w}kND$8t98Wj0aU{VU8Q?i_r9VXGt^b`7MioBxpP`>s{zsb^4J@L|D%`u*U$ z%?>r`VB>SvJYIOZ8ZX>>_L6wwcnPWXJ`Z&+Tqlyr=Y02H9@_oK`!SuSo6OwY!~-X* zOO1NhlTd0MNqIgG79QJ8$wt)u;34gsy-F;&v4Vl%Ujx3|(3y4{B26PQB0A7+!?!`6 z27=H0^PPv)Xy+l)G$*s-f;CU~-m?F}Nd|(iN4&AD6Xwgo>bikWQ-r39>*V?iD#~`p zM@lG#-zd~)GOcwOAqAD4EuS&Z6p=8rT`Hmeg`@pG%bld9_x=`MENHD@#BYodZ;bw3 zI-{ht#Il|_=cG~%%PJLW$9#*EzO-XeLYJRcX|y!CqMOjg zE{`;$ad%}X#VqM2t`%>Gq@WIz;&;30G?gmQiS>J) zTM7TF={Ra#%Q8;J+c;79XcSvf^jfyN=&B8L5yqCkEqhcRq~NVRNZ?I7bT-4!g^f$u zBwMeKHr&C31h>M~)6-de!V9W-(GzQhyRlVhcfu3{fl_#b55?2>^)-JfoXV(ODVTx; z_Xof8XDr?MLuVQ$_Y=yqXx8_gkVq+Yq8E&cUL?tP{v@Q#Ou!Er$ zXeM=2Zs}-#XQ|hL(gxx-eWUcdERi;uDxO?zEj!_g?fus4E2C-9fhM-MEdp?UZo2Sc?gUNIDpA2jl+G$kOAEV2XGu$876o zAW#ZpBvIU`e`DnQ0V5Uj?aqeyJ}8BedrYPgH`-e5U44`(SL#R@LkMF!86&YReNskV z`~HV`p=5v>|4P3<2JcGY#8T8cks(GV!8|g-pU@2#za2fAMsYp`3DMM|oqZ?(r zDZta=e#!Rakzi9d;-02Ti=}xBjXns!xrFir`euK{f zy64A8Bs$C$BbJm?F1@lU7$@@p#dKPm6IhcWt$aXHPxOmXl9d!?_>Wse$27(Wl= z>S0tq+6n0TnhjkYB8`cDMms!zl>{Sm9}D}7Rh$08`tzh4wUSbmFN$YcHj*MQL-94XJkM@mXSX%n+?6jB#c1>njQ3O=}<-91KZ`nwxdohQE zon9Xf9b=7IW zCl%h?!a%Ghx@qlV!oY4d4K(%bt-A~UNmZm*g&Ii1Nvhs)2jR6tG~;C-*CvKI|5g>gJclz{KGOf?I(T6Nx~YcIjQr!MbhhCA-O!q%|bfs+1%9 zbgLS}`_3@RDn&!wIN7!;mn=8fJzPNoy@@ovgH5(tKWwxp&kENv5a>;$>1*&uJ+@;~ zIps!D3kh%GLx13neAKu1a+PmA9HbOq`mc;qJgQ@#szun9l%>o_EMsXYyPOt^5ha49 zAyo4@r=DMPQbL^w9tZNE;v^hcXpus`)ie<38>2r?FWh9?`_&@lO{l40 z%Rrx3r55w5n4@r+tZp(*^N3|V>;_6cdGCrS#eJ~0P7z`JlB&!|_~&V7oA%*|EQbt} zFp?uLd$CKcg@dz}GJdmQuNj?%jAVX`Qigomdg)9j%(#^w9=eVF@wfChgw&(%w3BSV7B#Z=r@#p>MEG zwA1O}IP0~tQOR-X6mJ`9o1OUO!6|<_Sw}RhW9|AiR6&bkq|@iLU(~yG2ccyy9`$s5 z=e;&@d237Mw?+b`jQ(gb@r*5V=FkI?FGCef$xf`E*Y~` zcJiASdGyY|D0(N-G|KpyWczlilhV_(kb+WNpPsLgxIMkEJ70(N>lB%co#ZZ|y=G`E$0LnirrdS8_w ze;5dq;+EF$>ZDO$)s=~H(}zhOUyg{Fg13gEZaQNE1g0Q?F}LY^UZj4~1$xIFXAP53 zirYu8t&s=@0#lGcyHS+1&3?SU5|4xoQ+=-cnSTNFTSJYlWczKkzml$1E2Llw5@>0P z^>TEzH?ITLMMf#Ku93*U?IJs{`;|N)q_4uqZF&rKJ_?H;|H4-CtQ*6a>(ttFEAq$8 z2h8V2kb)^l949(0M*${z{z>n7@bbc9qKipt74L5#Pzqy}(}=85G5O==uF{(WxeRg7 zkubg={2liRpOsw8zv6yOIYcG7M>nian_SZ{0;CmpYPa1Io_mM4N;l)!5DA572fG|> z=O-R1o$I)>B|M=(cn~er{~ArA)KU8XyU(9&`{+hjjad9F$g9?;fF!gJ(!Uc!FX#3= z{bxf1fl@rDXu556;1@oo=B3&->6^z>o2P+5DYTnLG}^i*;r7KrNtl8J+E61NH_Awe zIn_1^Q;#*MqCcR+AgLi?K6*ibr$!8wixbdk<)BVyB<{I>#Ql z_uQcprXXP)>6dpZp7gn5QRVXe4h90H@Rx;V-Nldkdlwt;mV{+rKxOCmEeF$m%cxHy zmR`>3wQESVBuqhq>-(JlyKT(^{T}ywN1Mb?d{^2)pcIx+)6vRhcKqxbU6L>biAd5B z@cxsn=xIK_;&0U21051RUhy>}fl^pMjc^(lpD?O;s2Nj`h$bDT968vef;_@FZ|zU6 z9QBg^nQpKZN}(0#PK!scm}^{!jP zrXUeTbY9o*)-5x1e+>H?>=p1Zz(AlBT0zq>?Lvg-u11~IcBR`rJ28%Q1kKaiZa~Rq zo-3*CVqW}NmqIIOIu<9J-ObNk)Yh)s9SQz?K7xLw{!fR;{AP(B|5p8t(529Znhw2B z#1zaI?PfAv9=(HYs?%Jl;qRj0$eZ`5`fnV(lYnlvKKp<@o7O;y8eB=i6eLa%UEx%2 zVZ{8h)UG@&H-+985@gq7!wm#V;jIF6Bf=Ixxp2-s;HjtQSqZS{u}>Q z#Cy0dYd?EueBN%xyikgd2E=?hgsShd#tc%i<@O1oANv{zltOQ6r8>WQhWYxM`pKAr z1X@8W)sYXe`@UzkHsfp*&eq~wrbZlm65<)|>u1IkB#bv(^P0a|+B+^Iv$=slDdXHL zCq^yo9ru9<%oj_@pMT9Eb7C41nM7b-yoCDvE|%70daz(Aiz^o@4UH%xpbnW@pMJkL zmXIQ57Y3B37taO*j0;V8=s}8j5 zC9s_^Z&Rou$_=gDKKk7iSQ6v9!Ivqk*nB!WF=wyEigU;~BaE}r6wmUQVy$iMs&tx| zUyZY^-&&66)$rDFI(PTrZQ__>e#*mHjz)q`HR`7`k*2lnZB>#S8x>W8&vcORWFg)y zi+9e_eRrGx-vmk-&y0TG-6AP=Rcm?ZwaF4n;mx#0!Xfz=fhkBBz3 z+FM)C$+~z`Md@U<#s=a5wGurx5z-XZ(S1*f@45S;hd59|DU2s%Bu-a#w;Ucvcazr{ zDPal{c<(cTa>Mi_y}NKCB! zr%-6h9I?clV8ea%xbBE|)0<2}US}bu%N((FOt4|q5(&Jgo>q9PISCCS=g67!G(ulL z#T(^~YpKC*e+tI~=g2kY8wsATem6bRwEMF}W2sy@S0#B&0uoAgx-Zy@YV8n2crvxAS&IhmL0 z9@S%qi>ve@vbxN5_}2Fn&UNjsmP)6&j$ee!K{x5jp`-G>plS-{i?oq=N|8K^hKGx} z8Xorc2_Met)*ECEEqWoP4L$cU({syto=?67u?khDSxdVf^rT1#%_c}sW`>KCz0=KW zXg=v!^O@FhMT`XIWHPO}T~{hVe=E+H6_J?MV62+&)sT2k)JHo^-_P_Cs)s72|J%rr zz>*+sGHu#5UMaS1rX1n^OhD~OU`{5}tM5IOkJU28hi5mc#3HXjwq1W-NZCtuy3=f? zjaKgyIQ_lHaNCZWj}mCrl1lWgOtSao6B`-V@wws*+urgZ8>qx?}zJzMfJ^hq*q3Ns1jDZ|g=nkU-u4Ba|CKy^>Ko z5}1?8G^KjD81Z+oVt%_=t%qJ-tS!5KsugS zP#(QChIObk&Gx|ULQ3=2OS#W&i_CV3Q|SNPx~?wY$hxj82C1{PFKM(g6H8SOw@f(Hfv>vtOQ=rW;t5iCHIhjn? zvsz+pYKcf-*|`p#rkJwSuDFiY+cpYV4Ubip`dlQRE97$#wIhM0r4u9lwDpe{wElqvmIP^&>Fca{>`Xhl(R@~_4fhD* z?J9g1qQ0k)PW^Va6J765rCYkI8wk9E1!-CzjCPVYyG@mrEZSsAbaiKS3i`4Ae=bSE z-Hi|X`!M(R?O3I^gUGs@f*Q*uT27JfyE<5L-y;&3lV;uTFQ$0)^K4~CsWnvgx<@3| z%i);q1U)AtHek0(dC}Kkb7rWNJg7s8TV(C}NT8IlRIQ0Jbc}e} zfZY!LkLt0Sh|hx>r~L4GR38bHx<$mIwN}>h=~f~Z5z#@ao04gBvmk*|FNi4SRGmHf zY)26n`7f3!eQSHw`peghDM;KPBJ`d+Tk^*d(!q)P6FMby8rDd)mG0Y>Bo)8jDirWN zZR2+P=YhL0G4m+diW5gJC3}1y+t!S=jU}mWWL^Io`)oVu`TL97tV@$s8lf!cn#U{d zSj!}CU0ny}%X2FKy0%a-2lofpap~TQ_@j$js5_{dBUJR$UAC@V6Za`(eQpB)HvL=JphJ z@8ka1{3TS{(`2@#>&6f(5-7#3+wGVne0z8}%eo$yHCu6;+(~XAj54oMTc2JhZnsdf z?zq$YvTB~u)!rkZMO%Xh(QBuOxNRF`ne?Ly5%Z{(_%`*cf6i%?1$~ZESXz^*T1Kd} zp!b0NNjpDTPzvp4B)C7Gws1<{X&zp8K+nGMMZQSY}{|rhA z%itd5)_uF@sYgVYR%Vn!8ha&*Fn)EKGS;&;3)!+uKq1WWvy{7jDsE>B(4Gooc zPaVrHU9)3&2O!s>_Y&ADH66vPl#SofyS1T}VE^$uQKZf*kJus;RqJ+2VAiVsx7FI} zI`Ec3T0egiLZ=hLtWHu{5mT^KSX!-At4rL10 zA%X8E{kr=RDzWd*mhtPWSy2ja`ZE&a?}jRyCr_-u?sYE1jfH3*BQa%nM`d7>O02`u z!V16jO~2g_3Dl?6V?LW47gnN=p{G7iwT)b773z&HV&l&Xs29CV&l+(q*Oa&!S%m(k zB7xr2h{hwzByL}%eQ|UG-#er=;$YIugySpPn|G3Sy$9G#&p{o1gqn4>+jvXV`!0<* z9vb2O*6V{e5?o5}osrgvd$~3y@0wEAP;>mMA*~Y1!Bvu1xmL}S@IBx?r<lYd-g-k<5B})(G^uPMjcO!OPlgr?Z#ZN_1KyMx;l0B|5iP zt*c96PlVq@jlfo-6DWlx)QCBIUwIUp+}w;eQy!sG>Akk`{h(e{soQzH`-A)eNjydG z!%+%pRfkeMwXfHhf0`zu6qX8g(_HwRvC^j6XKWAJtdTJV3B2i%&J`63l^XBZDHQT= zXGJNrm670IgO9SWcbe2vwXW_DZXexid>r&^^qQT}M=zYv-)&ClqchFA_5V1w&zru^ z=x6?R>8%n=s1c`YI47pv9cSh(PH)xN67lOpyFc%=PAafT`*j!lb{P9Gcd;d9VM$hx z<{4V7+GdTW+c3}29wz>LhMwufx?9Vndu4woP>Rz#qPE!|~fxM=n~kH9Qh3IQqFmA>_hf=3mP9?rZU6#}7}pi3CP_q*2DQ zp|)hZT1xc;773*=4xo`J7nwWB6xc|~wWN|EawHPC>OjA?CnY4#SwBGe&?QyG6eNtR zGL}+J%_Z;55q)wP$m4*DrzM-tb9k1RCA$=nrFbm^|LgtToE# z7n9daHQfJ!w}%*sdx^g0+tJBFhfmYgm^FHQA0+;z67Kk4%$igpTDD4N3Cj(k}v2kid93bdx~u=H~5J0_EKilMIn`kU+c99(o`!1qq{d+tO)~SHn8Xmu{`G zy;@S3?Y9M{%>J_xtFXQx+kIj~O0oC-S^Sg&%&kW*+qSFC=xgv~fn$=Aqn1?Vm_?1x zpr32T^T)=uyJF_bawCV9(#^Y03Z@`|w{B1*Xm{BXl>9>MIHSMeb`>Oe@1x(eLb0hn z_#_?PeoOS2JV-(*JmYL6zU*w36q1=wtiElk+F$8;A;Ei5{hk(+2?>ZH;Wab5kSI+SWBI=t%;bB?`K^;{z(jo^g$`4yV4ou4wr0T<0379g4^x5x7u#}jw#GsFM%8u4{VDnO;cGSmL^?9j=sii93d5BsM z6A_q##9AVFo$|WOqEemQcAz#N!4i?Imid^vq=Pi#svl}Ks- zV=pJD<^}?#c>NCVicPVk@|qXvJj7ks!Rw*t%S*!Z4WxXLHkoFO*5;`*NCy(UPMmf- z*P0cyR)+qc(Z8@*{p)@rTF1Dv^~1vDFZm}(NE{_%;KqVt&_p9mZ|z^p zg%f`TOMll27t2vzJxIzw-+qP!=0q!4e=TQ)mIq6#%ZAHHoFN?^RKm%7k_|Mi>MwQ| zng@i-tqM+1kifDdZ8EtO-NshG?xFZr%#=|IYi=ZXOLw=MlMsHcy%}|2*)b=I*XQ0a zsmPRYv2=?G(wq3Pti*|T!cvNowT9|(sregW|F^4bH9hnH&!hiS6pxnelNL-47i(lA z(un57aUzhWvrDlzygd_pN>{&R%AZKeFZ8Xj$L*3q3TcXwvUoYGMtAqsobIV0!Q&^I zs3gOu7-`z|GVzH#E+$a=mN&q5;Jno~s8?QLS-D1RS9~YirJK2gvT6OZY@nv$b<9bGk$&BZ2loTKiSxR3*sk(R9g-1m

WgSs3y18sqIU7gTeG;Zwch+hq{8d4-s7_!`zxzWccx}C@RP95I zG~GlK=`Jk2=Bd=U>#1OQk>FO)bD~xKjpORyP7RgvRR3r@8Cb^R@vX4Xf;@Qkp|@9y zFNK6PT?5(jTuv$HG71Y_>Hj8Ea`A2K@3NuF)3oSh)WQ9s*B13@{y4g-PuvsQ-GW`y$WLD}o+FWo-Pwd=&+RFC*G3VSr>vOyp9SK}rLtrlg9bzAgQ z-;XJ6Y%FueC58m%ME7%ct|A`^`60jA<8L5%E78l2G@aDjlP07u8Lv!^nJHpEDe zb!*l&fAsVU?AXza1WFl8mEF4cCcI@=T4~l@q`YIM51Ms5HF(2{*!{n(+bquq7M`M6 zS0}h`Jtta;+mpt=FBvZd$IO(ucAelY;}hvCT;q~zU7e;FjbvS4vaUy#b(^}Uu}3p6 zsj**m0&}7j-hPuPu1-&-|01o2(+O@Xz3iy(ckAlqMS|N+&*^vT>I6y|OI0Ffxj^r^ z@-)m-;=O*&ss&|Ny94TX=~a_La+O<*oum>r`RO1ZY?VT7ca~daX~xrrQl36rEpp@? z>#7O|thec1v$RaMUU_iS`jXzkLDM!^M>cw8?R1HcsTVXWCRzslly?UONKT|9sZU`! zD#m8efx78V)<}1je9cqJOYa8~yd>)v6qc`3N%(hHFCn$|IqrgI!3k3N9^o<){0n!E zqP+VR->=p~r)j1rwX2kWPCm(Ve~4|*`r9a zDfEGn;NSD}E4w6g_3W*F&vhMW1w&-bNWAj9z@S{_dvloHoJ$X(z=VMgv1#lc9wZ2G?!W!XgYnCGfp`EbEbHw zXRv{2LisL;dMq5fYqlY6GM(;TMIN=&Us^K%hlo;FNylU&ZaJ0AMr`R`MZB@cU+O`9 zRvXH94wa-=qP-0X%*kZhK6jin*L#^*F)+r~*RPP!&Ox!Hlh5mH$}db=X>TprJ&<8r zFqwwujAKs=g^N)E!3yf&vAnO6-8MKEFzBPZo%)1G4bol29xW!Zm#+#57kb>PAOE($ zK?mwqtt+^9@l;~T!f1EYfx2l&$LQgY#5cL^t z#oLwr<92bm!YpRgj#5a|juhw9|7%xjO3_n7tUHL7zJ z(Qd&Hc{cf-m#W{ZBf_Z%jSU3mWHR0NuOjaY`60%U-;v-o&->tzkUPw%kItobt0MY^ zhe(?)#rPn>>(q$!wQ?z-wq2d36QFi+Y;6xu$)9|JQa4G*-1K9@wFCCq2vfI`;)h%w zN~r=K214~mR&9}{-sfd)bF=hJxj4OtSVJUGx5;Er`z)2SN9B+q)eJR9y3f=xY&Dhe zB3YecF8Avr<(&Lkj#$2>{)?+$tVsnUZRKgkW6mmjVeMl-TL+p65o9F>uZ9wDm);yWL0i%17PbxlE;rVh8qCT{UMx+N6PnbZx584N%kfzq2)+w<7 zwUP*GB|POqZ$DEx$#Ez?BpclrOXcjK+3TkdqBafu#EEyoP80TE|QKV#8h zEwpx(MPN=QQ~5&aEbWgBv37|b5)x`F@qESV*|OSI7EN;*Q;H@X&EX}v<@M6q6-mt@ zDI_o_x*;$AtT%6k{9RXTn?8H<$XYl}2XuKJ~Jsc>nQ^>XiSB z*87b8ACW+O#!b&DDa{xyg_bveFq#ZG3d zA<|es&F2Tm=Oc8VXO#-2kf!q=T2HMk@tv1El;(F1esZQ)ZY}#x#3^c_y{67d@c1{!}0%u(^?R!D39cu{F!-1*>UW~>L+)~JK~Tqm$pD1|ib-^~}t&QmL#O(VY= zRND)O)(TfC_B_7@Az!04!upmcm`u+y{olOj5P5K4hmzuP`m#_bOSRS&*dx4;Lbcu5u!(UnSKB&Z$&)kC6s$VhmRj?PtA2n*^Q zRO_MB6z?@>I-Afe(kG7k-t1C(ZBZYMWOAgljHUB^_GJ;z8?F&1XXUFCm=i_Q%^xR( z(m3=4#csozqeVHP=cM`EuKM7(#gE#Uk-&Vhej3rJZojzg{|`dX7ip8}S=$SVF4T{d zqwj5P(%#T<8T)ehi0X6wR*C~;Y5xD$^nV&<(5UbGd~MWMm59QYHLN<_kHP({6POd7 zT`CmEzEPXnOFlt@d+qUowXFMjt&Qn4^$hlL!i<1m=`)Sp>ynPoBy~Pf^RrH1PIPa0 zmn!lp8dVmW`a?$I5b1bYYZV)|O;KBkPSbqiP*1aLXOec)NZgxraH(LDLIQK5^9CJ? zn-AykQYz;4G7xAVq>TjH1PRowdGK`5R!^C}&R9dFjiuu6x%W|TuWQW8=u@r3#0O zNMw)>{VpM-DNa$rIAI=*^jp%mHkfoge&r-LXuFIdfjLp+dh+=t@_8)z9EqItHQ=;& zHkxKqD>OHk9Jo|g;>Q^Xv=!2{zhv1J;l$Mt$s_u$Q0@H|TUeQ{RxeLqOO^hIY{#V@ z)=wV3mOC>NY^z*5S_|7X zz6Jtw(n?i2sbgG5sKt!s#S$7zb**3dq>j|{6s9qjJ$aDFg1+J&L?BILYQGDK^czZPMD{`{w2zS(Iyoh=01$#%_f1ti>1fA5o{kW%3`4deH zHAgAbM=NnT(uGOQB9r%)ohFqa`>dtt=)TjhF#hcD{HqW|&wN((;o$E=6}oAKqJFAC%fkI`WSHDU9urow)O_x8U7siBFOosuG>(W|*{R=NJ;06WyG($D7?t%#=4y z?P(w|Mm*9qBBOdtpizch;cyvkg#_23>!ukm>UWROsP6`Sp^@Mg)$guB+GHA(GhJ|9 zHvcz&pbwDNdIo(YgF3LbXmyQfc4S1{L>kFtC-kx-Z8E)~-ybb#rYL1>j88GD;pa)2 ztVsTAj7vFA&ZHaVHGk-L-_f2s8ihZm`N}BzMUPVa*0-5--`&yQh$sG4#FI2`-$rXJ zPLyxe&R^MGxsCdk`74D=m5cVE_hQ9Cs7Y47bk*C?IbBAFelobFx=BjUmTgfI0_QH=UlV+ z0lVvS-9Xd*waa~zihF1~OphnV9&r9P(bBx{0BeG2tVK>adcdyF0BfOlah8}VN9%v0 zXOrnH&1?^&HWf==kx?r-(0ftx z7;5oIU~Q2$nF44Pped~YL{guHQfN^laZh%W>eJcqZge&rb?}~g2U)r?`2cgG=-*?e zO0QZL5o?F-GnZXd*}81TON;Nd)0V>Y{Av12%jt({mM4cAT0P>zQ*vE6O=F)Q)UN!7 zRg+E}JZkVD=8O91J4o#+b#OH$;>=Nlb1 zx2d=AXlrY`8>cN;LSw03Cik(1#`TseJWdyTJ{pzs*w)zUO!YtlbE0^-PFxnTE&}8c1T{G$XmrSt=y@x0@o@&eEs`a9{YDU6o?J{}u;Zjn7pP=M8;bx0@ z@yRmy%4rLh&{!&`6}{9sfU&`gd{76s=w8xMoFb#4KALqtJV@{i=qZ(m%#@M92xdsr zNajYGylui4adk&QT6VahZS>cP$hf5JYF03vr)$- z>U{#J_i><>f&}{6*h+#9R#kk;ycVvs7nJr&V_W94Q7Na-p0;2Kjiq||B~-EdJIq?( zif2-9A{xCImEwCd%|KvIwC`1}Ds-Gh>rqOkh!GI)kaZUn{%%`o@6I03b1i4uw~@gk zG}R)a0}<)j2#nE)G@Z_TH__H%%%bFxbgnbIQ~*U;+)p};gu|Hj%59J0N@Qf4Wq# zNPAMFC)&!>osfmMQKSE%bVt zp;TB}x)GWPnG=tvC(kCrhltG6r!7buiR~@lTBE2Aw`)u=lnPrVmXKlsy1cbrdF`n* z_~@yi6t-6*k?Pt=GN)Ejwgs0+{%dbV>!6kQQx4Mmfu+LI(wf)KrqYWcC6p^wX36;V zLfS~=G_^7Jp`D+6+{Dj(Oxc%a>$>}$4bNuqdrbKMx6=P<6y7)3yzl42-v~ULfi!t= zervOTcTEST;Qc5@9peI{1-~u9ihZSUaqfqytjLdbEIP1{Z7Mx)E3kphPG4l>Hy_=q zzm9Gc45m`mjg+MR18a&MJt`>It~9e=ej0nAGWCgQ1^l+t>MN}x^WLo+eFrh$1C%e< z(d;)J87{s_{u8wE6%zb;+|JGH6%k0&NM=|xyH+t=Y`i5{LMeXhS3S0sJ=hnR|e|wg>Ck(c)dngAIdL*hU2mQ)0#*l`#eVZ}fSRzn755KU~htH$g!Hbs(+% zR_nH4V&e8z-OQLWhidL&zk$VE7-DE+8WFWr^6vMhs~LTcL>ST4>cz5*^AS`JdXuD0 zb{*r~nph14N?}{jh|E=U;?0pwRYLbU5;I6g$$gvIpSfm`j+Rf(2$hqjDdodk90=?c zVJS8IgRR<6U*_;3+>$!!gY89fBW8X6t^PpEC);1ATF`fpm#UQi&V;m4Mje68Ai7Iu*r04CfVeJ0cVl17H z;lhI1?TZf7c4t1Vo%EJ=AjRyVeHkG2fuuNb={KUt#==P_Y5m-V*3XgnK}6)?S!^Wf zL)v7DNu4ChKf6eaTcwLg_>sObIcBkKi*hieX=U``B-w+cU;gZ(pj0mUTE18}nH|3S z&1NLb9!<>47KDq3n@&(VP`+I14oM+_Inn5~(rNEyv;y#iYL5ik4QcXue-HWmn6XOf zuo*H+p+$`Z?-?F9+_bM+amkE2uq6ChIy#*N&g8cPbK>3vrv$k```-v%itE0xZxX9P zmez>-8AIaozc&&ng{9R9r*Hk^*3#GkQ;XY$(iq}n1)zqSv$2$!#B%A+EBN|=Jg zC!#Bnbwlp*)}G^KZgwE0xs>mPi-ABXW2x>W^b}q^3zq&22p2I0iFDG@?8^+6^xTeg zxF0JgoL+p-Vm%vbXuBw7^m*ZyL#^X!6n=w7;h2KNH_~yLtb1sKiFABE=)xk7XUezd z83~j^8&YJWK1IxAS%q5|Q;i9vns+cc`Rckz$@n>;&ZJG?(bZk&WENT8)@mmZCMKGN7{ z5RFZ+BxtL1^wzqPKOU;3@};rQdK&xeps@)OD0P;ICmRMcS2MTn2pap0qx{oo?1KbK zVF^v9{&qvH)Q?D0s6W9JB+iqL+s}iTbzTtZ2r4tw=Jz#Jx?V2E2MLri)_iRpf1%u= z1wJ1(gesVlozUBu$+XPbpT%#>6wCDOsS@>p{K5sBh!gpYJzQsWvrB zWdVw< z+>9wmpr172&6GNE4boi9n6i;{d@L8n%GKMh`d{~rMjTDMo={?dpGxQ{NNgke!GM{p zo!Uxxznl6bzj@+?CQ0ZIl*0OHIwI_I#QQup8)}XO)`?C?C-xMYy$n|7vtNbuxcx%ZcXze+KaQ2M&d}Il(FVZS2SjhRH71R zJrztrVk_w=>JrALZr?~XUqIulJnu8*3UNIR1WKXZOs4z~bF-muLX?`*O3A1LrO<|S z7Wrb3`VOuwu*hd9wT9XUwz9IJ=h;|#Zb8o-?*6N;5A**!(En+5DKMI~rn##^mBM9| zil^1SzqV~=Q_r5rMtBU17QT6hi(mc;R*;xLI!@=^z{U}QG=0^2N3-OL;qm~Q??b6Q zq{IH}I_5~FG7^b2f8{`TzRtLvDUYOl&zsk=yt~dYBrqph?du%F8Vm|nwtkr*v3S%H5X;9Tw3UuQ{Fu9auulNqYz1)+^*aIAow1rLeZ#>h-*1+27ayB@go7YL;ys z;xd9f4FpQ@oaC6lS#h$V$yB}cLNTq>7{#x%yWC(xZmT#nHw)N1hFvUavy5iB*@CWN z%*C^vb@Q!nw!59evUFIlj)*%&ztyl*nD6iP*cH3Td!B=v8B>rLLZw%o4(GLg3j1J-o;jc8c@P5U~Uhn>9OhE#@NxwOt z&k_S;2PhSS5@oC{S^<5d>Bw_mOnCA>%#3-V4)i~rkd7H3gyjxYI(&Iz(1H0bIC|-T z>xMimp8QX@R95g8GHGm8JvAyBy|#dQHQxI6Q|p^e&o1=5Bbv(d}h4rRi+K;bhirEQW3awx=J!M@J zw>O<2HC`AlVhZLvpLB4a-&B2G#?sR4PqR3uXch+vlrma(Lam18gGAVfz!W6VZge`+ z{-pO}`r5pqc^@QD3T>l&Fp(f)!Le*?$k!jTkfzouD8^k9HpM#W}p17v*y&> zb+o_Eq7L6DTfL!PbSECP`1(!Ou)$RWP3P{Yr%tE7y~L(q1*Q0Y!8Kl2 zSjpdrjL=SI{6$}>VZ;7({5a{)oQZU1F{to z%cxYG-ky!7_$6OYBvLP}@ZK7U_M~q#m1;cgD0_k2k}p~Tu#2AZ)R zok_>LepgxZFLxNy8Zo=Y{J1T-r&)1P~wUENkFg>|A`-X=fqk`(Qv+LUk^ zQ;?WWI=H2$kflwgtL^HWZ~b{dem`Y|f&@w#ZPol;8KK(AOgV5tPs1C91lo;u74Ps8 zMpiDNybNxq)?9yUQ3`EH^X-G9g=RFe%t<3l{^hKgKaYGb?7TV(t4q&z_y1)(esp4o zhUSr9?dIc>u7je55kx$xU?lh#&OfKU?05czfu^XyM;)0Tt)o_2Y=JWG~WzG@a)>;>h?q>gq^Mhc3m(qR~}z$~W%)n~nHP z_28r924<}u;Uu*$tL8d^`lxSjFy5W_pp6bJPUg1K2|k+S&l|GQbZ*<;Cn<^g!@aa( zf&?FHou``bYOjr6b(&6}`8zSUIz6S@vrXz)vEb1ad-x&Q7M4b{3I zhI=NZ(4IRB{VGBNrREUvM{aw0LdSFDkNGrC{G8?~t^4e0AW#bHM13O7s=cK?cj}06 z_4lA|MI`vhX+=2CuP3(=YCiFBqKiTgyfjr>EtaCHYmn)<68 ze(EXg+1Us_f5C|dL?BHb%xs>NSYS~ye@{?~KYR3XlE3~&xKV$V^V=-ZFECgobg9)e zDs~*~ESryS%ci6GsKvI8bEiuAr#OgccO=OH$(LQsn6jDj&E4NgKCyf&+fC1x$(tj0@tGn{+&j@Gp){>pB7suqS&b-^D=FTG z2uwi&{iG3HL+-_Ipk5SHkl-bpzu*sfCza4-df2$6v?*s>sdnH{p=PBOmL~V|vf_RG zSm2dYmST25m{N{-faAfZd4)hQkTo%G(dEJkgKnD0N-<8b>N zC;J$6xb1GtQU-*}(|!g^n1TeKjSTs>r2OA$J};`!ZjmrrkvSC>E+T{V`iv@44*Z+)r9C(9N2%-Cj6UwG*qcxVl%DLP~~w@|`yWvJt_T9R&-GDxcoUl#$@; zkqsV{k`G1E$`#Ob5=q;or-Vl@Nk%CTk~&X1#?&31jX3vLjJ%{wJ|$N_Uj;pgUduOs zuQhY=O>3cQ6pPSQf%Xn2QynIs&Qw>!^^&}&Qf;Q1m+3H`p*||rEl1XtW>KAJ$0179 zqEb1NeFk3%&PK39j>5zD3zJvUjzc8)^Fn7Axh?5Hn%3yM#;``-UUYY#hf3&DZ>itS zKf_hFj}FR4EE}+x6|j0qH|}^SD23iMdN9p@iO_ppuw>^ME+T=YLRx#z9W#f-6{67+ z`h!0w6)YoPBM)NzG-6cX^n_&-JDM>CiBCkABfIS=H-`Mdd+J+dX2m^tGSWbx6qZmU z63ZX+a-ZEqC3IUM!PgB3mT{5YTk-Yt0_~>BF+FC=GhIeX*cz~vl&kj1TDa;wYnu9= z^HS|A*(kwbkWmNb`@603(wwCO%~@g!68ILV^-wC`r^vvcpL=5p5}8zwnq(`B9bZf3 zrP}ncwO4`e-PN4~`kRVU=qHW%yt{i`;dYG;9?VYY-lRRk)Qi5N)$rZ4T8&=2Kz-D! zre);XWKq5bJ@|eZIiJYaw)a&?wT;M{vqS==&^I)n`1PT+E9IY&wHjV7t2H3OS9p7q z2TR@H`v4MOii)_ajB-6bLPigw*TOy1tylMiTjSLCJh-|)%hR`~bdXl7Q9I^~mZr#G z5!$Jg!pU=dFa-&21>UausqM-F=g*NqDYP_2b)>IBN_3>U;*Kduprz?Vl_}L`_tsNc zO%~2h=>9;f(+U>#?TNHj)ST9e_+GVYeVyc>7vF4rM^e8zCFH?Na0A-r%1oS!3%k_Px@owiE4l1G36q%w^469A+UFG}DQ0t*f zHNDW8*$r`)*O9Hbj$eeWl@semGX{=zXl4zh&^JbZ)bG7SIPrI|bn4G=83`;E(%O5T zvbCXCF!fg`)q?8rgvL9arsikA6Zg9xOXwKUMBSgLw-O|{XXDAz|7_uV)p+mor0q?w zJa;1v1WI9B&K?1w@fM7dzC%um|vuc*{P?^mkFk4ld6!nu4m z?y6(znwMgCEmOu)p%hx3?qeC&(fa_cMV(y`uGU;{qe!4{Os4mR{nb9vwdb5Cr#|st>JyRR=VKn#wUb+CE;7(`n!Hc6 zu+2MMF1IOI-F2_)*iS^KRk`E}xnk6_GCEDO21MkhS=3_L2!6WaUptyfBOORnyP7uL zd~LaQc4^1rpVpc0$J*-F>%!0<#&^)0M#w2No?b@1DCW!0;A}6DM}9(9FzVnZczmc| zFOYSDM=!}NDpj*#dE|!QwG%u#O>xiL$FNp|f~6f_W~t|Kbg7xtqu!@_bo%6{p5XaK zSo<$#d0Nkqm!<|QD7A=m3@2N;zG|7xy7QaXG1sNU9Uetm0z?`(6;rqX@<7245LZ73K8B{`7cRTq|etwRH_q*G7C&qiv_A?MDg;v-0 zK+gARu-_K>cRfr&g6sAtE9_W4Crig08d(;nktGr+g>}+O)vu+u*K(SZ!4xFskd6)Z z_VSSX`Z<;er>fq48kaW^D3#4t4$tI>Cw~cxhWA&n#bIv{_>V~#n=jCIwFdun$8F`* zU_e6X*25 zy*cko%3sUP-b^hej-lO7NT8Il=0%S86y~=Km(8^M3{#NcCseAC75b|lblc}8jF>xE z33z!$J#nb_WGIC;qG`A26*hH9T^o;?$^ReSzW~+z01zm3fuuO`ZE$uXV|VMM5r?#SQ6%`Ya_c5*Hngq{ zY1;cyZ4XOclv8;6Y?^X=@D{5ultrXT4iveUJi*3q~j%(YW%^I zDM-_}eN?1;&D2HQd~2lQ+GDl#dHQo(ewwGm+J-e_))gKXYz5Uh%eR4xndOm(l<4K9 zV7@DNAzt#^ezl(ka*@_D7iGv4cIKf^V8bFr0R z%RriI#FNXeBD&1B_9lZA`++C~7YSx{_2UgFB`_X%-fj}vqQ}H90*vXp(mL+;KC^*9DQwdk z;rdV`FeN*ow@{7nB^~!kNA{L@rrj;pk=hlf^;W47#c8If0L>I(3V+rKZUxJhVN+K%f-*#$@_fAl3SV zW5XNbP)G?@b?CIo)SdcvPJAT-rTFP?PRy6H6ZXx&db<|&l{%!B zR<_Woai1ZvLLRfP8UsKlFej6#_s9~gOW7lGg|J};f{&cm-`yy@+O3U{f7vSg2w9gx z-|!LgFXBj7FS^&#Q|flb)1U)Og8H<#*89fY_<1x!#(d{dskT$8`poWO@V`b}pwpSf z=)6G~N$DQs&z{pa2``f))D!EvpEM$IqEo_QI-QCBK!TU>?$W=7{bXs4xO8HeIv0)v zN@1NeVqe_Axb;*IOhMxJnorC+orx((pcOP7oAM>a=b=?gBv1-%Xfo~CUQW2N_+Cou zv!UuQNZmeYH$Eb>#BUbzy`D}rccjx!`)RzpC2PE^6DY;UrQPbs3Ueq{1Ksme+n=>t zl_^f7nFF*aN@1P;w^LTSle$=q&!F2K2|g|rNymf&{5{{E8Yo5`5v9^MTosS^D^kAn z&&$5j_@n8!XxqZMZ*6zzd1Cj~Ha=dNP2&}lsSNc#W3qZU)QF2>hfAj( z4pWfeBiR~ctJ<;rH%_U6Q#}?=xrAXw6x~) zN~PK+-mrI8XS`+}pDy@K&cRwydwqR$mf%u359>(JdELT{iu^x_wQoCke4jqWKybRutYD$VzYYv(O-G!ElSh?FUIv2Ke17sI+Fh52A*~WL z2Yxwu)%eCfD24X-q9oBi+(SlXXAUmIl_iDn|8iQqa1YQ9o^b z?&K%Uo$P60$NJ4|Wt&648E6*A*!RBDop)T;$kV_d1wj!(MNzPq1KU|>kHVA0 zvtSo1sEB6)MZt!OiUmbPY}mz$3Y;Q(id5yvCidRD*s=Fs⁣eAwMSY{+Ca7zB{|K zo6WY_{bJr;Po;2mQMH1Wcu>TXRnyUITdcL=qxn8e+Ag&w*14gUQ-G<#J39A&4IDn)Z!oXG1i+^yoPp&Ejw zozk!u=YF6vnkYYgxw212%{e7-pA5biz#=+bY}3DTz>h@&KNe*dl1fl1nm?Vcsu$eD z3k3MF2sDHexFZQI@;BHG#!>#~vvJi2R(~`EmD&b`jX0HirPyk3{Q(U8iiEfNxRz80 zm7z~>cvwsE_GpfrpJ!Gj0(o&S%ZQuv%uj7SC#o>-W_Drv4$_SPFWW@2*iu=hB}hwcgsvppH_^|K(HMIfm%uO861j zz31Z(Z0D+j-KajervX-FR>R(?m#~&Yi4j1{kdJq<7ZgucmDcGZ`Y&hhL!+eHup&;S z&>QpC}9LK9ID_F3Z2Od3K7eC}lha}NL0@!&|7TLi596eU!t;yLd=m~*`Y=Vj0k8ZWKW zu&-}!U7_ZUgVLyaO$1thXuaYW-Vp08OE;J+^$K(DF`{4ANxe%%RJb z)o@BsDVjn!h=*2=hEM|cy8jWqmHT)BYvS61m1+xEsip*#qWJ@_6d(r11juE9pdpl?cEkNw z$2{P+DWNH}iT$C*wF|w#jc~|QJkIR6%Uo{DD~fL)zW0OoI^6?8p!b<7g&v3aoLY>) zR+M@*ssz$^?%d$E06}SGx4MR)Quw^A7-3z+tMSI}Tbw(j7voh4s;{^oq)MP)B0m37 zgf8v}sS-UQA69p7a1Z{wqu5HN!P_aQ5*vTCv;62sHN_87mFmB-FY}MS&aIno@|-Lr z&V^rRwQD;HPU|}hR0?$nVBH@DItt6I8u|=Wik2qksgSUI^}sOy=iylgZmY9CIGVf~Ra?0Ok9@ zd@RTtq@3MG34B(i=yzk%v8iNLcSq}gC3x3;53rna2m;UIE{ps2bH3B)9L2Hd}2LVUome!S)d`5 zKu^sL`paCth#sK!;O*1|{sh4=dq)W>MePPFqtLU2^DG4y=#SD6N}#9aicwd%PfAUU zf!UAC@F%c?*$+xkDQY)3Tcr5_?$UTh; zs14x^p_tbC_|ygbo-yGv{?DEMEXl8)d`{_w;d2Z;Yj5+gzBD`yYa{kYDKPuchLvucie3L<2XP^ZU(BUZyGyGpV7=I43=v7Fuvdib`NV;d&_x{?!qa zm#Ip_PABkCXaXJzF$G?xsuZRwx11%v6jDX?!Cp1+?r#kq3YWk`fyRsdxxQm8`KYa? z^HNk=r)zb4qge6f4EbofPU%ytQmLThS#L|eU&FJCe{CTlhF9U99Ox`x|6NU>Qd9@_ zYF|U1YR$U<)=jGOg&XGZi}$NCP&p%I2H0nK$BT-WsapQpGJn`@32UA2E|+cND$|mp zB}ly^;8v>_Jy}fOlibzdnF5WArUd;tRoyyWIXH(U49;QsInQ(si<(}V4=sVU&@MFF zJ*r__rH8EAYCOc7TH1oIZFY*Gx8oGZ-{e=Sm+6`>e|T&IFH;&Xl`5{|1Ds!?dYP)} zr3C#7OzrOZ;ANRN3%pEKi&6r0m;6?ePlfU~5tZ)O@|e8Hbbg6SP$~Kqn25ZgligQt zaN=r*_Vc2NGv-RH-M>mRxOEi9h^& zo8oI(NNhZ7&n<<$?ZZ6gx5OEiAc*&c!#|7?G$v(4&tOC^z=&Qs|4Jp^fDRr~VsDkC zp>?_~H|#kdNRcD7i&O{Br0xD@&%f=M$S4ixejKo8b{`hE1aBwBTb4@I11tP2lT?Ig z13KYKgJn$r?~L zMtVOaT%c04Y|vY_(7IdwS8~}~;3PJfYoG+xM`^g(VPF_LJ1J5=zcf$uPFw9M-hL!H zmz}~~=RVJk*!NKMf)kev3v0sEy0p}`ffeQ~smy!C z;SA)Vp_{p-<7dhPA`@7JB+)CV**)=Wb~K~fGFv#`c;4c1s_2qn-8Q%_gn z|2%;6qDXibtg%pnN>RHNqzcX#eE{>+G=vh=3OZdhteBv;(>iDusT57sHfT#4B~;~) z!1t)rwbkVt(A&us`lFPfQaE#a2)>oH7CV5*hOmK`@GKz zP-dOg+CT}M7sdD8m0B`k)G`k^yF|b!cYz9+eJAH#dd-QWxpN>C|kH=XWU{d_|Q*zeOF>_tN;LG1>-67b9= zDrE+%$PFM*UG#&C5ZyPp=;8c!VL1>~sx_nviAKc;>a|4))E8N=Hvjy($s<>#VMGu6 zEVsh0%r0A$OxlWZt>Bf?7hG^GQ;!bGEXiKDR zeLBPZ?x80Ea`viUikGPxFWPMpq$;wYJPJ$j4wPVB@bhwme<78krHSQVNKAd`z~#cO z%vIZ$@1<#{d7?3yT87x4wX#1f=&G#OswtradeJ5M*5VI=6->mY<_THdtxP8ms|1yz zDKrsLuzTk)oUKknD1oUmKxwWmt@^&kH%oSpfZaQkpi=m()?<^7h`?mS% z|E;T0`%o#GLP!;?#Kl4UU*J2WA(X)NVYIG~V%;X-0gCH(cn%#Us1&aD{t2n-|0)pb zmG_>SZ000Kei+OHP=ZQnZIw3Ij{hnQluPvg#?uf=&^o5mox50z1AhbgF`TJSLnuM* zrqj6&fs>|IxXBk6xhZG%??36lTh%e$H}Uj8d;Vge$=9;q(5ig9{PK{GqP~_?YQnP0 zd^kv!^vJX)U|wx?*24zo!hK;b zoTdc5B?BNI&ilWKR3GfEg>&fPP9))PAgI(5NEH%~<)Q@a7uCa^NXkqqCGfcoSo9ze zl!m=H!GYXdOB-ortr;>sUzFy9<`3p%z}xA|e{-cVfhMnCHD2@|{bQ5^?-W^rX?0u} zwSq-JpSla2;7X;?3TpXlOR(Zg2QFfMfV}#~Z^bWFjhE(w(x#SSTzS#`ML;`cH4x>gc7(5=`z&HIV)7Z)a&D8(mucm0@S)xil)${ zqbbY?H-H&o8bXQU`LN9K$QqQ{Ov#68A4*^ft3z-3_Xx$46?(7RKE-Bx%!<_zR0_RJ z)vv&mD(YpbhERf9!9*;-AL}8^j#a!&DWO`I)@kMLnw(!pOt*8HmFEG%hMd?WWTOZEDL-{tg#j^odryGu5)C1nw!T*}$Hk zKN0t;MfDhE@SL)|W!L{qcXOx&mBQymr>gKF3Q^PploF~GwMcOfP_=AnywnOh-Tqow{xoLMz%sC zX2c3+KQvsvXB8u1ZdJQef|e7k*S>Y&UY~&SSRA1EbE@%DeOdxXsUqB#wz=T8G_}lQ zA%*oVE%-qzO}C|~m`K`%ERM6fGwcad8XpeiY^z zXb2^!-Au%wFQv1Ges@-OtE=TqbFQ^+qiXpg+?gRSg7Gs=J0);;bQ7?&nUasEFw2>M z`-uv6tE*O|Qn;(!^Q0Lcm5$a0KNc|#;(r0-bE<<%(LBNVaIimd3&j5vR`zKKC2;?C zDp>dRD%=--abHbl*L{po@7F$w5>!fSE4$fM`73_i<@Wzn)YNuLP%D^jGFwh=GE-|G zCGZ*F*HcopCNe_V4~O2FG%hMd?WWUR{@mLm2fX4R!wxs})bZVUi@WDsR`JNh=Ky%V z1z%dN7dN>ztV;lf112ARl2x8rz(ZslK6bINl^lQEro(RCuzL+ zEVjDL*)=u!TB@|kJChPr3ZIuks;E9_eTc6mjTfzOAov0|v7yO3Q>BZ0XR1=@qlnM% z8WbgVf_G+J=vmr9&yvQQ2s)NRs>*dV`9Z2Qc+tU#9!B#5j_RotdQpa1UE`8mO}>_e zgb_|7X}kKDv<=4SR0?T-ux^C+aig{bBVm=y31)+v!+(mFIhCR`tc-%^#O_0vxLQz4@L8=3Cc^W0Xqt6_ z=cF1!32HYJ5d(gZr3?HZ)tW&GY6TOq`@BmUk9Vbjc9oz~)Y7mf3@se`LGsWpV!Wyq z(Npi&y&GJkY9>EO%U#zw-R(MHT{rN9Yz$s68w&g&RRVn!RVn)26#7B>7WhG`wxR^h zQ*l2?)uNO@4@Z3e5G-BX4^kzl6#6TcA901teeo3PRU(|XvvVm~Tk2z{wHD?cYoH;h)HR?Fzgo=oS@Ri)GaH?SMcJ)| z8nqU3X}Wkr!1JeK%?lBlRMFJJDIP=zjf?8=fmET6JMpN)>R_@|wn324=)*>d>Y(vX z_e(Y0=zmwdZ7~^g{^i6wk25>E3wtV7k*N+E@0B>XyXHg;=YPcph-&Ks#9i0>2$x)J zWGW>y+aewx+Wm=;C^?_nt+fl+l?axUxgc3)=R$Cs=<~n_?4?6ZY&+-@xcSj|M z^g8$jMnh;8)f{tBBCvj(H<819N@G1K4JK4iy z&H#;lsNL}Sw(~);mhye{Av$QhpErzE;$05$YIT%d=bIG-sVZ$B!_g2*Y=%^w7%-U| zc6>IZ%8MJI5H>(iseI6ZQm}WPX^Fe~NcrW$we0unbOSACn)djfTMfP1i{iN+xT3gq zOWo`{cGHA0*E;YtE~+CQQsrkmopWBlxClX|&O@qDstibJiJVV!v*Uxqgc=)?c^X2A zIM8wX$!u<9skNYE;mq0D>wvHYf=V&afl^&TN=vvlPS2haA0%W?%janbCFX*T65Kql z(Um07QNG9C?1?}e1%gWL1RW@44N_X-F`P8*8WkYNxHM+eiqyJ8yjK}IJj@ntlv?sW z>Phx)Xc^XXHUf={>X-qkGQL^NmAm;bq>2($Y6GMSrQYQI3%6NO;{4xba#AO?7CfM} zrXiFF2O>Rx71#JhHt2AQNEGK?fzv|kxCvA$3UoYZoxpACEio-oDMj=gb*zDa?K=&j z#8}Yb@F9V_cv}J;$E|MXR`swE;&1m6Xb2@n0nzfm6wYPo5g?*lbY?w=M9Oz}bmU^E zL>acO&lOk0S`oFh*1C878{{~8+6s=%`Uo^Gs-r|1KSf7bMaRdc9yvQh^7%2)l2U?7 z4Tn@UIFZ49dUz62MF|>0iT_IbDa2WY7<=DU$h+q%&zbT_^G~ID(&i(&f9o7!VKP4n z+Fq)I#ybpBwb)hW4jjgvH3O=L3#)c4k`~9z7wJEo>d^krYj$j(Qw4NHfDRh(dq_LR zyB6Zr>S)uqYmQrH2Oe8%8bXO7kg5?Dr?`ZgxbtjIs}4DHfLI3vm3jj@P--$rX^BT^ zopY+3oy%csO+zR#7<4=saK!_rK*CImKX~ zQSw0vDuwz`s%$|%3W>%!9djc8sv)iUJYC6$8bXO+=rcH2z2Rco;BKnC$Ja0LP>C5&?C6A5~Xb2^+_KfcJjobGC>#mny>zuk9lBLzq zl2R!wf0SAdQd;6%V~?E7Y55Yiq%?#Q_}$nqgMFlN_|>ks=9zO1h;cwrDf~WAY79te z2@Cz7Im_Y1ifm{XX$U2-#VEbflD~Bm+mh0Rpietw2L%^ z64;Jat!~Xfe2Q)2F+xx&2hf31B1mb89s|nc#7}E2Pk?rjhEM|A8flBE?$NDjLe9MbTOiKhFa1!5F86{6|bdIMXl)yjgkE-_k*pm2nKGkM#cEtK1 zc?z_oRH_r`K&cKOr6m@Gt+3AG3J#OY z%unX2lt1XmFI|<-k6+BRgj<%A==f^7+~#%-o`z5YdpH-|9r)%)uz%HPQq62=tK^l? zW>KjzpaZ4KfRvVKx4*o542e{gc7NsBXOMr-+vnRECoVPso9_drOJYomM}lj z$9)*+7-}D*384h`ch^G-hlFAex!)W=g%}6~m0AfpP^uzGX^F74wLS9erpZ~?I!H8x z5)5=q21{Q*iaq^FgrHK}KnF_A2PrL4xl^Q29< zK@kDM(fb3raPPh1!Fx9hGy4Uyu=)MPb+Kk#uS4V6rgHy^ndbQh37%n|VSg#Pe3b!$ zE}{b4mDxwUc*C5l@n)EYpfSPi5gVdBRza$oL#k*>_CY={C8Z!G+Elg7%fy^JQhen}!jNgP%zVRjqd3Q!d-PhHDw)wkrAcibvx10rJq=rDPgHiQCXJjP6*Tf7bmIjObGu zIE&Y=^pTBTHZqmE2|C7AD$h?_{8`izyJDS0?~bkH;fc*<8bS%2l2b-2jw8qgqY4c(3d5B+FHdL6~E0&`*j?!A-@QP`n|ht}d;vkF>_7)f zjrr9})DoAIy6Pvx%m?(TWg0?>kDwzB=E66mcLg1n2tlPPfew@!vZt%4CH#T-uW}3r z^BFP?p#-c@z?MXWHox{anJoO`W8ahZ;hOkI?#*T$#aH&zl80dfGdS|E*2t z2Ly%5R0_-g&!ZXKsZmj)mWZF_B&PNH#1Gv)Sf(MAz&btpa|-ua#&0ltc1!(En3b3Y zEh&}4dW=&2KuSySy0e}R`x*)hwhA(x3#GHQqhP+QAD_ToPtOD$zXs>!E`nK!P1j8= zgF2^6S+a6IRM-Odo3iR8tPu=y_DmLnEw$i%~d6~e5K9JaAn5Dq?-QYd!fH-QN zgY6--iyDGTVW0Y+XN#HnJ?w>h6M}|N0%t{#cybqsJ87>py>K-yDuq4g14m-m=xW#t zUw=`V5th%o*eEkBYFs#@(_TN19lv4fg%=XNO9Y4wY)8p6+najfY6vB;Pdz7pHv3ct zd*Kl^)3YZ+dl(D7a4Lm!StxZKq_o7}<7a1&gVwDV%mdI6O5pt5=u*?!(oNV4FZpzC z_5>ijfuK@2Cx=pDAf+X~N7v29)(vM4Xb2^+=bX`VGRr=Vy>J)D8rcazv;~4n<%15C zS_@KIqG3$0ENtC|6!gN?xG0edI>t$p*zg6|3y0ZSg@74hj!NOIDoQm5DJ@ZHov%B# zZZP+%384h`oEP?*%*IT^UU+#zP$`@pMk!a2(h~b#)bh9st=ou#Ubq?;C9vo0U^$&V zx`MrMkq}f0=fzPf6{NI8o!mJdF!w4~F6f1;aZv($wbFyxY;cJ`K!?qbYrJ=U2Vv2d z7yLACyZHKpQT#J{Aq&XfEM8gvSR8&PoXw~eC&sV*EM9=UkvbjKLF2_00gU$#h*zs4 ziOcc`ht^Fh=u@lODS^Gg{Fd|B-67bg-b@H8g=--wl?+l^VpsVq9+}XyY+KN?RO6xq z_69f4Snr#hq1bZwU4*y?qnK=qv7WgF0@?T9Fzrwy1{<3GCPLOr>X8NQ@{adk%+Q-@<~P zr5ZvBZ0EndPGB{*V9(M%FfSMTaH|V?eQF3Lu+?_>l)^S#!#|GmxQ6-~p0;w;W_^_Y zl^Q|`Y}@hu@2g1A{uPajN?|Xm%#jSXJi2I)jD}DG|8_`xnu7%GUr~ZeVGm$TGnpN+ z8VOz`O*^#~?ybDb$BjI^L9zLSi2D$O559hHVy&ixOBKWgos~VHL1E%13tm zUmuQ2q1{lbWqDJ16cTrq|D|sNt3E5C&7yHp0_#He?%!C{e5@r=XWQsumXpW11}cTM z1f?FvntJ+$1npnZxF~^j+Hy%r$@UJ`_CvmUJ+3Ulyr@#I)OfM(qEy&zQ;)2WSo5W! z9%eZOnB`QyC^du<_|^Wm%u@Q2f?w@ALQp9jg`v~{kkS&bcRT3Yz^czC7^%__N?_|# z+R<9NHW6DNN>C{rO`?=1NNEYjV;1^ISoMi3Sk+hKqQo`OG0?8OG$tEY+$lk&a2$jM6*v> z9+P3!CkjT9G=viPk9uiuFZo*He~=PX3gK#3s$PtxF~_6r6Co|ODpnm zR743X>s z7g4Gic&xSFs&jN61XOu4I?{j zvuIqD7z{d=SzKdB->9p|DnX@iwHKu}fs~fOHQ~Kv6Q5@=-`!?G5+Jz*rFX9uskjif=Z#?P^vRXX^F!x zJLH`IxkP%CI!Rg8SL32Y2(-HomSnJgfu}%6G^|v=TbnHP4>GMHtMOv_+Z@bbRbQNB zTH@b4Co!YfCu!jB!2%7T1lIQM?^9Uy)%bl}f_3L)7z<7>SVdOj#d?fVpH`W^k3wQ~ z;wewZeGTP>TLpp6+~Ak0&J^L?QY+5{*04W*=VMCT&W(e0=k?IaQ7M`dEsZxUj7DL)fk!_cc%|uDJ(*efr!jH!EJt?X3W~Oj;+c*#vN~&W!wkvPyEi|VxGT*{ks;H$zIu`eWb{= z2!V!BA_M3qPjWda;Vux*hj%v~x{@SaogXI9kTj4Aj@re!cC8@Nm|%TyfV;uV|De?2 zVyH$3C5{~L$E>}#aUZ7s3AW;Y&G7s&@3wUP)Np}H?EoF^auT`ED|k^$#HExqe75*0 zIW8O|&=5+jgPeD?TE>~Ro)0=M{N7^xX<15+%^4uj5K6?KUeEk$EaO(!TL47gsj`>* zja7V$6BC6@h^xQtZ?1K`t+)qL71-rF_qCC^$l$&8{#RU`kte}cA9_okOFzZ&V=hb* zXb2@Tfo8_nob{tKKz!e-Go~Cg=MP++A<&Rl4K}c2$L@23ucsSnOfUzK^w2XR_$7C) z(@c#HN?Zf$`k%PTJ-6BpI({V2Hm>8Aa?(I(sY$%qkdkWqFLQM*lZ{%!ce|V6+_8t^ z#QaEshERgmH`r&nriyVAm%@70jnvdcO3*q6ebM00Ue#;06guX$5N3lF<6SEA!JUqY z>mXG#TG{c(er1ZQ;r+p|A*^qJK&Ac#;(Cf1?=bk!BE+b*R)!6EkNEOZpg`lI1g&pyGI#W3WD0_J!YkgpsSFiBL zhRb&sLfbwu&fjZb{3zl1r_<7*I{vKl8ArbM>lD@s@^QO;H9pa48@mnf?}XOmL;cnO z5wj-QE2P>eVVd(fiH1<34bXlsYVh@&uLoji?^I*kI+KO>E9XiyBpPbv+JsvCfE95? zbR?H+lbbhbicmH!T%&^$|3Rwk*4O6$h4l&epUYp34KgDHR>4Q2QhtzF!Kn#66j#A(U_h9lyrZ<|_uZ2OTbUj)sf@k%F83QjSW6fDZ4AwfWC}K1@s0 zZ!zEK)@ho+FKNqDsc;}7m)GJKZ+9<3Y|)i5BzsO4_MM65XfmD60T$8^(x-O*Z z(Cu!K8m70Y*7T4hG9IMW>L{75^qcp5^9k)WewcSrt0YzfeD z)T5i1Xdf)Bw7JexsrjJe*-1xUXIqMCiEk~d7*ksJ7fOz@6sXj4Al&*^;VWg|7PUmb zGiHXa{d)`5#+Mgp2qkE%1oKy(ON}>OItVRJ)z-9El%OpUc<}tW-|NY$YC?z3UF11X zM{iCq&41{9o;gCQZa1{zCs#eoR>Aw{J8k)p-bz2Q`~gqn=$gV9`%W?qp+s$ZZef}hIr3Dwc|r` zM5ZMk>{()*?A2MQ`nkGHrJ4gV@kJH>*^u-iM9kB<((4%kQ9DTGD*Rk&` z=4~u3&RF@uuweE=mi=cBapTKxhAX{hL8_9h%ngGo_zGi&Sj$v9)j?Y&xOp)qh((tP z6q27jmh!(`^sK(alJhB|gX#wF<-hHX<4*evB4;MkxTp@=c7gv#l`md17uxeWj~Vhv zu;Rh%x4EX}?z6Ix^If+daGta7vC;58asL}GZ`d8k$Jv*Ox$jf-Jbz=FOhYJ94rsmc zEw{!QiO`Vep6eQK;urLopdqMKIOy0Iq2n7Jx(>v-cF(*{_gKT*kC-S^sqzr-n3g}e zo^A7(miS#R+!(g_B0r`7NSR7i0wQv`IsZrg>vSs} z!i}j{%!N5u2WV$@iErQ_r^HxDmEYHW-10WJAyqvdbTx)9TqoVPnW$J-jTg&i+XIpF zFLQ@!iC2r(c{TggTJjt@O{O7~!1}gGKE++xaSwESzWUVo#IJ^A{c*Zd=4!lc;Lkbn z^a(Dk^gX5}_D-%P##fiwi#s!ADrE(!T7Bj!*Qee6B7|#AbHfq4onr8tNTs%`+KUqE zSD@34T(-pc^~PB4d7Oz*LnuLOKCHf)4fHxv^)LS3h-r$Bw477ybNW5yi&~a*g4s;D zr`T%k+kMQg6I%DkqBzMtX`&F{>j-N$)m)r7)SP?%Zy2NBwze%9dNJ9{bEtt|x7lP} zH7-nvssk;3|E9>k*y1-BeY>l1>4tTD18dV4rG{Xc4;hxm_EgU+lB&-_8AHgt41TjX zRw+SM2PLrfB>YHWwr{cSa&oLOie2Vg<^?OYM2#0~Wse!j%>7?e-7O>%o89pmv|T5B z_X$vHq8dU8{BE}PSi!P;?;FO4qOEoeIN%xGdX3aMWTMhusUeg=>yFQO z%gmc2k@_()w^WQ?x|}ynsk>?jmdC}*513o5sTEaY(&>7ewJ_L~vy!g=Gee_;60?r= zW7W>wW-d4I`v}bH?itl(EGxS-Ql?T^6ElxoWjDIqXIkQjt-B$vqMacC&Pbsll)x`a zt)V)d-%%?=d|HIOrJE0**(}Oyz?V{N$j>g!;Ff9Z+|7c`hG%-$9?Z#Xe8Gm@>nacW z$6ol;X{}egJEfW3U>`N0`WGdSSc)5HBTYOwc3yUDC+6o}~~GCV!~;NI7Ojv9hW%>(QHX~S#E6{~kr`Xy>y_|HJ8dUek-E#Y&gslMY`b2;|r0GUc*Z9fucE{%S1 zxd^duNk>EO^Uu;rZm>+_q6Gf!)UN>ige}93jx#Pw4FX1Lz7I;!nh&;mJix2h`e51W z!WABSmiM|kN+Ag)81_r$6OPi3`lXZ}a%`oV($_iIrxsc#dsTM~meYS;Q+mj12qk6# zU29PdsoCx7K!hwxH6Fh(N#|4x-hSqR0yOb{CsU`${5r5qmXdfamTCt-I?<0H8Mxz zq6Ch8%6iw4{N~{}YR843Ed8KJ`Rw^69F@ZH4oYnTDJ`+}+(h@Fj*;>_m$jM@O5o@& zXH9MC#d#bLrc`k>_-&1pH>dStR0_v!&)(FQT3$Ad2MdW?R`ZR|8cmmnOldArsjfiu zKUYiolpUvx6AOv>YGn+w$4`-c&WB4>J0)<0>^7>VG-oJ|oqvz(W<2w5qTJ*1N{LG0 zsCd)U8d3|d^~y-NkcjHG&MSPyDEUXJGs;L<4WR_~YJE>SN}s=`fR0=F-Mso$9VK7a zpHoKLYP{ITeb=U%G^@onrX?JQ*&B_={N;r9W-^s(4n&`)RiuTX=|u=POLIf0wXggo z*jnjRtJ*1n{du*GfwQBtml%Jzcb1)gR@byXl%VYjoc0zYdv(vOB0qNRuFRLDZ?u%A zJn13gY>QQoGE!=rp~_5A&8Iffg@HIz6gSdbtS{Drvj=w`cdxiedQkE~Z(CDB9jv#YdRF;}dI0iZ_ z+?N_-T6U0|9`c#p^?%fu(M7eWjh8}}@%ST3*SH_%bT$G?~4BQO}BjHi) z`^$reS}NmOwe_I{ZCBuyv2LHep7b=6O5C3z?1%IwpSsEFocPC>4XOHc;XVsHu~V6W zTqnO`tzY9TXO!L6++MNur3pKyD>IO42qiLs?qqz;az>p6VnVJ%_PKG>6CTB8@sTNtsDiwd1_l`Oe>2ukq%hmPnX8+333CgtW9_j%_0AGY?FnPYQ!{pn1>vO{eDwPJr(b>D0&5Q~~h^Tv|4YlWryl;sy0@Y3l zTm@+VJBKam`3lOsUQl=A&BICjo<(8GoW2?_t|9DtoXdhN?&egI`ux0*xKu7GMu3lzceE75J5z5+x8ZXW?H_JZ8)~93{wZvbo!;F=j zdU6#~BLymj^WxtRTxQH}M-ig*h6TA#{;9_$oifdAtJ*0+zZ+Nu_-!Tb8)Pr$e~Z+7 zQIw$H3ba@5O{75srpuNN&5iUspx=k}`uWClJ|Dz(&>Ph0j1H%=Yh?$>)!@{VHgE!s zdWZ1GrK6SS(Z%i)uKA)_PJNKB4ksv4;s+4BN>1V?!>ziMhEpTXtd@?t&*1ZYLNx@v z5t!02bJsAAKj^~?$w#WmRI2Q<(d@yQ+1&i3=c1OFsy_-IKmo$7hrcCC^oBgCH#AdP zryH_j75{K%h-~?0u0*BGLC5WGa;jQb^2%+j_Nx5N59*r)wggSj#Em@?&a_0?A+G$fF;To>(gY2GX9}x#{Zbm% zib}1Mg2THB;djlHvx-$Inp-WA;-AbP9MVg8Z1zr~@#1;Es--Ed(=~W9RdVh8RhskD zS2n8UoLxSMO(~v`#lS ze-ZzEp^Xrc*ij)=sZ=1;n_IQS%RpD@T-XF*Nn{jHr3OPvLSw_ZH`V`PTEYhE?ieo@ z!5Zo>CGdoK^_E*o!#v#Ib^mv^I+Y3n9Y}nHdvUeIh?98$VC@%O`7F28zo(bITo z3Lii|E|ju$<2w_~}IsSDeD~YC;o+m^t0z1#1MF>*U`uuADH;hWzK@0ch z$WqSt=M_;)U_Ras_Rp|{Q_^S%CA96;v=9EmE^eQ6k>AJDKMVci(0L70c|4V0WH#OB zucvWQ9olv`{dc5r_*@&~!jZjmbFPkNv6CxsyIfakY9Fv$`|!#q6-&z8}F5=2dRo$xhi)~!(=a7 zwv_GzbRmJ(<+nA=d~u+sz6XTdn9>_=Lfoy%M{(j<|0Zrt26xmDD5bVORJTqiLq5jr z%QbXdeB6tsWI7OQW6Zf(Q7ahDlc_wu{#n9x!y{ikwR>r(C4=h*a?_LE75UdR#3Lxl4eC2m`74 zWlL}wCDv(Zn1>6B6k;z1vI-&f*fo$k{h*#9rM(Ax4bKZ+CVBl>>%eTl7bNRLl2?l} zT?=#!uJky=yE5$XCsLHgFKTVc&jzb{vPQWZ@T$t2r7kEcx!xP@ZRgpLJ52>{A!VS)9(K#R4Hm{o$h*-8Nz#^6d&_!Eq4xfX8An- zHz9?5nG)RBx6K)?VarLerrOz5J@K=V%Be zxVC+n&7S+lCyQ|YYWej@VPo_3+$LYjarL(QvVA@)jE7vK8I__m?4iFCDKu*NOFS{G zw1MiN1m@|=q)g-I83~}H>+49lP49$#v;LMu8d8){tzgReX-9LnUe{~tDM4*TZ3uVp ze2*0N<_CsHghP`!v#m{3+=dTkF!gHSICOD}#T&&r?FH5xyU|u`kKwHx5^Gu<^ z*TJmHqh*W|R7$&d5X)n?yx2A4TNgbgs1)6KsMBqNf7JPkBRzF{`Wb1wG*x(FcPqA? z-P>1i2DY5?z{Y)N6~7!Rl?zg-WfPhASJT<*g~Z=J8GOAG{&IAeLp*I|vY_>;d&i39 zd-}4Q!6^oABFMsgYl#J0<(cR69-8EN^C5 z>v~=+2Prg_xy80ydrqbH(_e(RCX_$P!g8FIGndtPQO6&_7ud34>Pfd2cbqd5CiK?R z5IoWNW6R6zTd<2rV}cP&*J;Acd#4OG+y9c#&r9`#qf(THSAv9j955@-f zX9|D2%w!f$OE^5I|E`&Z)aR3rxD4Xm_tjqN@#u^44elswDLvj_&@u>vX4+*XoBL`~ zh3$tbMQKxcG`5V$bSl|hLr^Ka`J~y>%F^&Jc-swp=kh_<0QdF%yW~)*MIbdawvyCg zWeMf(8ZEKoM+5gex}G_ByF#D!=2Ct0<(jlp8^Y>q#7yCw(+w8*`lJExV=)`)AZ>zp zYoGLG?kP2-(AxDB9hHVumDVV!>fLvy;1qD5RbTnefaz63DA5|;yX>hUaoq+(KKivW z2pxi~<=v-G@wAoMx#Fi`&ie_XODkU%_>Yd8P$p2k(nP&Ox^%Okw0U#8>#0qsKCKRH z6OG+lx{o{6NkdR6ye;ik>uS=i*Flh~jgMvuk%nBBeRZXX_jy@G)s`%lg|J`nw|trI zC@meZmNf;!0rC-iIUI;4P)i2YUc$~g&1862qkXW0q(7Ru=l%@1?_i5$s%lP<9c2< zJxwpAi=|3Vo%z-M-0F}V8bS%YhuOu-QZl=Xcd}x6NON5>2OsUM*h;l1)kkA85wAb) z+gmfU@;(}Z@h)pvQo4S}bhGuGA>Y~Icevt?I{eCibvrp@u$~erK&Vnl@ce1=TV~tj zVgb>8Y2U1GbGqoM6xD%5!$Ugh>kO4xezk7a61ZQDN+BH$sY;x6juj_Lf8XWyB-~r0 zVJIZl4ZbRTeM4dx@iq9LQZ-8nH(BIb>MTK z)~{K4vjQD*=&7qN5nHL6Q)t?JvSHrK3>FVLOboohcGS+(SQ=~3;ad``{$8z#!`n7>^XS-0 zPYEiOfL3?E%&N3TTVbj!JB)Pe;@e#*^92D$)}-WBhIO}D?sjG!d5&#?=giYGdk}W1 zfVg@*(QR)>Z#@m6L?#fcQn#@gXVf-vQ>iyDJ8$}E2r5-PRYyBIxedtHYX~Yu^8{W( zha&~EYHkMh*;)BIRh#%s?8`n*$Ytr1ZZfpAnm_oTABq$vH=bx1+~E&R2qkEqz>988 z1))dJPC~O=;ZhF7^)NR9_G27TZj`t9Zxge>eS+Z)?VCy`f~Pe4C?3m$Uf)w2@oMi< z%H8(U>aJzBKF1iPwFH!hoG|O4`-`wPIk}+YFZ+1*>fj*_eE{A+X}X?;rplnB(cBc? z>}G$i{($j9n+$6%?EY8}`QWbh2XDtw4qRG&}zO5*Ia0KPl|+31tOw&4Q98xP-tTJr5( zWTsbQFO3cwuQnf86IWN4T+IVI>1halQL5c;!t<3CZJ4xlH|WTOo6P0X*2cp_1{>&@ zoJ!G=cR}m3Jk&+sqpLDLS4ZxYp!&c=Iwew`*r+QvENy@RYs2^h+qvpf&ne~n$u^Pu z7JGrA4Oi^h#w8q6Yr92$v&{Mh-(b7Y3!I-r9_+;I!|b@rTx!cJN)7G&P~yhCz^`_9 z{6xWf@3x$Sb>n#|h0k~H+~Af0fi2Oqg7cSky5#W_1bb#V2ot^z{8{vNlg(@iCXDs8e=hXbv$W|e56A>x6!vHKRxK<6<^!%D** zmRSKVoMn~O8b3&! zv3TvZiCZXzn?}NdZ_HJfT`*rl{T*?>MD?|#F`0Da?Hrxya?VFj{hEDxBo* z&2-k#;OF&hx)6SRK6ATZ!_#;vf#c}HTa>VtJT@HKrtYvLUvjE1YEh+{7b% z{x3h7wu!VIq_nA){Ca%N#bv*jGBcs31g-mT^{22`tfMkBQJ5;sN4@rAGA0~y(-1W0 zlvZ@eZI1XhcS{g*Xm0UYEVwy~(xy~JnLD{vw z_Op~(9My`Hpmo7yt8d{`-Np_Taun_EFS)7_&dN8TmIu8>%S4!!|Cs6hVxWegQdFN# zR}n_SJ=VT6IHzPO^Cjwyg_OXrw(wR&%*V^>o87LN`{}6^&Qhp%P8KKfm}6F(tt}Pn zs%fVLjS0LnVcsWq#C=1>gv$mhg|i0g{l4_hSyRrl8})J@2Xn7DbEDoZNmD{&g8jQ^ zBIUkktXSI-n?)Kgy{%WPqx(Fk_NZ8j0_sVRG3xxVlH09ja(Iu<5Z+~UhK#lh_NU48O z>;XFb2{(vd!8w47kn=T=^WTXbWw}v5ua~ygoCIwjwL%2{D8 z#_FlmG9c8xVKG8J+qa4P)j`9R`I3trUUU1tT~X$GRDCp0rtf2gZm4_rL7XxYRtc(u z>Mp1yCzoVC-rQNEgT_l~laBo(&bWRK@=@k8`er=g?l(8heyI7Nw27!D3{Nwx=&7V? z;_Tm?Jy?&3N>FK@jx*?JqIjxmKK`6JGjN#Z8>9rzwy60tIlhXU7tDUUC(+3DDzh;L8Z_NrGt#z#_#G}M(x=vGOF$Brr1gip@epl-FO0ypBOZxaLGeu?EY~(g~GR+!n-X71rIB`Uov;L3Y#090CE*KSc z+_f&#Kevw_=XBK&%*P2BrS651DYjQ?Os4X<7PK?drjL(C2PGsRqyq_@e$Rmd9dG{$ zOH1cXBYHJnYO7*|yl_W&^9S;P91MwrwEIC^R0`(<)I6C|)#2%7mj(BF>8TXekpP6I zmI&GU=57l<_SNGkzSib8obTe@$_$GdFO3Oiao$G?yBAIIO6{`6Kna{dm|~Id6%6|e ziq9GtZ@+YL@$aG0L8Y|$DD`@#V4rzF{4YI|qw#)+6sr3qe!z3wnM|)EdAI}O?UYF2 z*TWgyu~+kyy$0&c1f{h^%?4SLbn!DE)2y53Z;|}Be|<%PjYlcfu3{s7E*Qni@h|ycOnoCd?6oF5O?&#Nsfk4;u8>G-#bVz z-s7GLth;>3bGOxDo%NKUQqO?+u*X4qvv_L(VHvt1%Y0i$Jq@A6FCf&FCfJ1(J530B zYv89II$)qF!M>KdYE=@RAHJ+Ad3292(Bag&h5NCbZc2|#m7=Rw#RxflU(c+o(BE~1 zxX!_9SeVOr%{mv=XUe(Ucb|Lgjh=cM7uBK7NBo8g!p;`mgmqU8{2Rz&yC|$&o8gc+gssDg;*Z7CtlC02Rk5W z2qj8D{)U4N%k!$OjP5Voe|>JPA*htLf0f>RkPx``GoKjoRoMx2`@17=HgLTrAI(5V zMzvb}Q?E${srs05B~$p)RZru^??a`v#KWeGrTQr&_~eFTg%P@vY~MsbLk84pTHA+x zc_z9CY%s(?%{S$|S>aX~#by>O}zb)4y3ov&t4Q#GwqV4DA~PI?+rlqk$c?5PSu zt+jE|uW#*Ts-1p!Goni|oQG`$bF#4C=USv-J${KHzS~!kmI1Dks%1{C0AFn~>`5JP ziVLifXP_epT#0pzuFc0qgedFIg(DW3MG7CC|1(-lbJzS|=^qDY@zj|~oi1Z%q|oMN zhNth~?wZ+ix~4EPqoz8g~rLF8ee{PYK+6{B0ea zzw#tVLz{>($4{{dTkgB0ae1)jx7V>hp@_atzL%pGZT2xDH z8Zt!~|7o%m`fP1BC8!iV%O7S90=f%tD^!*fPhMj*gc2VhRXb|WVizY=gjB_kn;=L2 z^PQVKc$q|N1Fa=1U_a380k+0kut!6uyPE=MW%jJhu63%c(Lv+=0Xmi(oXf^Gw*=zx z(+FWx)B2J{@EeZi7I&4NKd_X|v&d%JGRL+(v(67Un@jC9^@$MX`@(5DyGT^2U% zMW!|Ep{F5~!2Pg?Pt0cDZ>2%1O2P?($G%S!0~_aw)IKzYwC0=2{AHE#8IQjY(9~U; zcHCilKv#l&GQ+-)*QiLr@zM%In*npV+fe35_9Pj-Yt3c*VbA{KgZ0GEcb6zTm+$t= zGDax-!jHqskE2x+G5=Qu1MaO=LnwheT0<8+Hg>It`$g-$m?Zyl&`Tdq_2+2`(o#Fq zv=p-);x2|MyAAU{MG6n9C3yxcTVkMbQ62b2`M>`pem$vvQR{bjxDS}>qo*~TmN~Vd z$yV3)1*M&<-AzN#77m}CY6h|i8R|~*&!tzm?a1#~j8LV}JL37K2zK!HH<;Oeaz9)! zu8z;CIeH#XTL7AN+G6N*?%$>geh+fQp&R^p8bS$b1yeq3;;*&1nAJ&7%NBP^kNY-} z)p@^7X^9HU1M6-=_CGFO`E4}>wKUZSw>!dG(IBa;;qR^W*e!^6k?nVJokeqHH~-(c zNyewJn_t<#e;~=2xy}K~9ChT_mvzrRUSCfMDs>NHYU=P&JpQX85KrTs<%l`Wq>EDx zGOZ1?mi%7&Q^dVkKb7zN*^e25d50wNkKaEy8W+{!1^xyxrkLx72h?&#uZt_EX0yz!=c2aEG3We`9_~r7znw~C zrEG15tN#ztsKFMOny|l}#zhHjdxbjg)miIWI@?d#bzj#pko~H@TiG{nx7vk8-!pl* zspW6V$7+j?ZlU!!We>d?LTe0dC3L#rquZtBL!%_e#lZqC4_XHQN7s4B<@ElK|0J@r zGfF6XM&nNR8MZHr<*Tv`e z-+7$t^}JrM>vfHD?K6GACi%_xH}b;fbc}N>P$x}Z8X-(xHb%xC#Wm_*@78K_^6;?o z-p2OITt;!(rER4-O{R1NHMMYF3MXH1Ye~=Mn7x2$BcV2T@0(nE;Anm0!<)%MM>n{O z<8@j+cpl%Siri&poS`l}Z`ZX|4&Q4w0Fa(yW14O48du8ui-+mKL z#do)AZ`+Fu%)GwM2zb!SdE>5$nM5+JQdjoudtPxkkU!;nO<7McZ;TlMXE9 z2*maYwsJ|ot0rGb;{sBWp1yCT!Fho7{X?jOJgXkIsX0`SL$D6)X_!5aw^7~G>!}@X z72%9?4^F;#5Juj~mv0ja9XPxA}6K9g}wCLIU6es_MF2Y0N4l)3Cu zFAR9(B=mcA!ayy|Tvk=^NHLd0-9y2p-QXGwfu$(@f4VvAPWzS3w%%&H5{2UFSL+SM zCYB;2dv|9_#y`H2qVA4O+IX%Nljk_ze^Y*Hd>a@3aaTR|D9%CZg<6YF%ky?UGnFef z=9)!HzXx7=8q&SDHCf^DSjO}}g!I1A<&-EmT|;Y8*DXBhu&lgX5}x~~OQh-DB)KR& z*Wb*O@&nHQ)^YjEq7*r>haMB9L26tNck)8q&(Nm)C_N|8b#g)%y*)_fa{cF{leX2{VF+L1|t-{uttP0Kzb9LC} z%Mdi>10Fb$-FK2?Ov7KNd#_aXzMi7`54|Sfyv6rX{c{3TJ(c=2wezZ0j1DW%;S4(V zmpN(lm06$BDk;;Wv|Ht_?KRj}IJKCDn{Gq)D+T!z`O;34q=CPA|flvA4qGX(Wj_$f&^cHZPGGi~y2?_)chx7_s6*9IxwNlA#$v^1vHOkmw`zt72B z@wL@3b>OxCj$neOb_eLl_?5xXuvaZ#r&?C?;1ldby+`n7;`=2)cyV};j0qeQe4&== z)GaM*@FCWd$Tui)bAHVd=HDnoZo>WckIzO3gKk=r_wb&3@{+G{lioB%ziIDEQR%%h}5pODYXOI>v0GssNY!cZW*xHHK9)r4JNP@&Htm2HzhY*{GA`3^Gc=~ zRoVyplA7_`xU+*Ql59esGC_B>$q*@08oj z@=xh-VLC(Pfz)*vXC9B`7}}Kbrols8g0^(hV<}vAu|5;Au+#>ZJwLn{q5`DjVc8He zqjlu}XnhtAU+QWIbYb!X`|Sr<=mR;sC6wNcd;6zO4ZAW?D=hq=#ZtJ$utY+RPPH1b zSnk#Rg$I@@2UgL&So>fv7E92crDyeODb8zqG5LY>oGtC`!K$lO>^v@xsKR3@ToT_v zI^4SX3SLENPv2ovm^#p9k}&deK2u&*=)LHx4-l@jb0aK4%kHDbkuL8Xd+1+4Ty>8> zm8Z3HC77w_S79Wss)3{xyU&@7qeQP_-!|g=td` zrd8uo#&(>be+R^b^N#Y>bM*+OSt4%v0R3aDs3X*8BZow2YmEOYH~#C~EUg$lGw}HrhGR&CU811ZA!Vv`j&^9EbPYUz^TPF+_(rO@tD_l?TW0` zS}JwQvnl^^OEYo|+C-aCX}rb84&*4j-*)vW|M>ax-=*Yq+(_s0*V`LQiJ73DHv8=# ztJE#^l3X&px-;p(sXYX=RuiMmHLfnvvRnVNwd=fKHsx4~KHIL2F#PzxGrX}+eN)y> zku=E=V&UCNKDKHtIS9{d_r)2ipV~qccs_7(lDzo%5=cizp-zqbvCN>jM;SIkYDxR2 z@~A4y87WM2+|%zmHSNuPkH*g@@R-0-RCkm26-brn-)j@9|Kv?>L!W<5r6F-{RpbP) zDg~ai;JM4p)r^IvJda;J!%1GyM~{iWb(qs)Zb=&iBp*|Jjo!GM}|14#dQODQX zmH2)O*BH~ZAbS!YdW@!=dbjVzjmc5Y?e&L&uzC5CUtE0y*$>Z=_10;xREqr{dH(+P znbD|y-Sc>}1 zoF)@dq|B0(f>Ay6v^3Dw$t);8SPIi7Vnn42E*o3-Vsv1?;WU|uB`IM};mP9|9k?W7 zeI|l?walgPR3AOfwKncC+H^RdjV)xYDt&O4T6J(WaqR<`iHG)l=$>ze%nDk#lM}uG z=N#owZ;i1<{nK9Q+l`mnoHQuQ4(((JT+eZfVX`XlbXv-u4c<&0#I*>QO8CD4-1FLQ z|0~1QP)~jnSkmC6k342V6jOF-3H?(NuSh!8vGW39P*z<56IhC^gSQ{))Z#7=`S205 zWt>|4U7~3+e~I9xsh2vnaocx>+EMoy0!v{pm{Pu>;+W)(!@B8lyx0;IboBH*BCm5_ z4D~}P&`Iul;oNph>*a|}3zI9^PfygSH4J)GH)?ZaUU zaeofZBHz}jK|$yE;seg{%wIzxO|_jY701$Z<*M*(Kfai{&uyL z;avhqnCE7)q-<@a&&}>62i}icRz>j*D`jd$rNBWhZnuYx)li>&7*S2R_|cMN!}Cr! zS?rln_Ag@NXPtWfk&mJLvAsP057t5;YPrRc`1zMfI6NQ9{Yd({+yfnYC?(--ZhH96 zudT%dmRbx%P)-r$1DsLixaqcVGsW}9WK}^7*$p9&N6jMvFq^#tp3CRXA{Wl=BTJz+ zoBt;cw}n=mAsz2jTX|EaxsrWru^|#}X?}IJ4Kr%2;x^3?aOJBUY}FQYbjpJ|xTTof zbyi~@$HnLXeRhev$=y=)pJDWiGw4HY*V$4peKdsh-?)reWoMA3ND9*?BGKzct1VtV z8G^PY=I<;1CYp$irNvfXKlRY>0V#(Sq2!UzE`kZH+ekt(un$`;h1Kk!!})kZGy58&yqo3MfTB z!1Kylb}$mJWo#M7dzKg9_|Si0KZD*YBUN#TwtUjdjq)^1M*ovX`6$t~UF-8uPs4nK^=A)t$!LWi8JTKEQ2w)YBs> z1Pb@g1VPH9uFh1~lxii$To(l#LjSO7AuJRc-;5(PXU#EjTqF>&K*0540uI5%P9R3* z&lRKna`^;}9#E2$Z5lc2!_mZIg@>^F{^2t9x!W!D>G2mj&& zpk!1p^-+jucbU*OvH65zV*M~vn^+J_gyq(>O^k*%(cZ~QYZKI2iwW8$nxz)Q^R@Ngu)}yhGEbqE{NztaQlew9fhwNe4WDz6Xo@#*K2WHG___On<0Hpp4G(cqx9dh zPX`WBLpMc;Un|~L@XQ_7$Lg?$I_O?9QTzQ^f)>Yxb2 zhR&l5$3gp=;X%B%Ogm$5(mZaX{UCE6p5t!)n5G{7*;(n?*-NB-xZ)pt_&GsQOuwD> z6aVzWXY|yma~BuN6C4%_I0W~QH$cfR^ZBSYO`zkCaT7+U%Ravqle|00cnpZ8Fm0-X zz2(NKk^O2hV@^!J2CK}Ya1$}vzqHHTNuBk22-#46pkQAs#`wiCmsdRYF%nY6a;HrrE9?qf#)ed(U^YEmzjuz?*F;kp6;fnsU2EnIH~zy6w?D> z`|Z%~O8#fEUE=S!YiP+Zf06N*ntJzTYyhdPp?OYQ>VrjAr5+w5>2X|`#=1>}vTWhu z+e*)_QO1@f@eiI zuEDusQbJ+20<}Y5bm=tha%e@vA4$eL`pozB;d}fzF04bibgBLc@_p=L0k03`Li=&O z_zJl~trqNR7WcjhjH6;|2ondbAo(Dro4J=CSKd(fs!m9figzUb#uqNE}l1`0@-6~J$QHtOYy26)`eqDIp zsPtbw%cN|b8g+i2yf42hj|rO3I7JF^HiR& zRW2vj2Dy->0of8L3(_BdxL&OICvhmpcG$Cd0EuC^bYAUxZ=k@<@bF5zXq&euMj@l}3%g#LTr{5kj|$z49xu~v=J9iwO~dN^nK*{s$w9#hdY<&!9RrD`w3q*TN1ym^R*dJKf0%RG5S~?ec$TT zt+Cg5kA_|J*e5u(IDMx2G32l=u`qq4h7$XnEX6DsHQ?0Zm`ru>QQBdS zclXaYihd1Vg`7!EcIe9xv^_WXWHAl%CGf4C)AFR@MC3@r1&}iLYjK~E)o~r>eJY=+ zE?-)x@O2 zMD6{Hs0BUbCf3{KN~AT9r7+F*UNb)F)Iygyxow`6ah}1f1E+%}=(pB+&vVzur@f8i zk96n>C$`+rSb}xK3`;pbDcy0iQsUVK1+U&Wfxic&I_Ar>TXkl7{T#P*YAtE&`#Ne> z{W}r&+cAM-GL=Ldj~>bS5&vl-!9R6iT;qJ@tg$a@_Vhw{ZyxW!Zd}O0sk4t6QqE7* zj=8%NU4ovq zVbXy|kYQl$Ce01usZ7V5)K}IoBVBSnjbe0QDNLJ)T}x)UIu&cG$05|JYmavbz8^1> ze@Ce=Pt{JoH>oGHDuc%y`++vE(3o`aV=B8g_v&q2n=r4RVW~qvu&ZPPkCaHQ)w-94 zhM0+i@N8bEz_dxnwf@^vFRfZ*)R7sSZ0L2*w8mmy!TLvsnpf&klGU@xM#8Ke$4m8@ zSLIAP@*KA(=Zxvd=)h8RWNFrCB&6o2;!;beS-3|-hFsdlk5kRu+3 zxTZ(^$IK_v{4meGVjB8z_jJEcSoR;?6yAi5airw)4^jM0vc2$a5DIvWs{SU%_=1UiwDjH)Q zG^Z95v=086J*VG~S1(#6R%~OZ!6BHSUbq4GC*H|1=Xv>G*{KtUk2TJ!EroQPTDR9Y z-)c_Nzv-~Nza}~OLVJe5QgrTY*4e7ci}Szd;iRVTW+pbs7-^iRE(mJ8zp~!0}=!R>zhCo%+^)m%-p!-q<5Euh-yp9K2csJpj;Q zdwwk3mK9;ZabX?ULXJyKfHjs=?S%kqU!L|83+me_%NARZjnMOcU{^zN+i3OI$`7qk z6|Y=%-3F}>?SEE;wXN;9BNz+uY8JE%Fe7~Ykti%E+e)GRTJy@-TNu|Ck1nE=d$`uv zlQqW#eNmVZuG-;_5Z^O{U@2@n)@>{$(!1}6U2I_m3v0*vXb-s|tjdjeMCaRY(SG9N zp7N@%pS5(9;(RKP+$d7sI3^D~aECaId}AC(UFeZXs`=BqqqoDlTK>-ew}x|V8_jiaLaNxO-|HPaZ!Yza;u$8|WVQx`8P#!Iyt3p8Fcfu&eq?R%Sprb^sZb zTxcv;X4*s~ZY!P=x6;YD!_+KAXFS3)B=WgN`u`w8KP+>eUB;Io{@x>QrcFA^CHSWV z26`LEgXUd@cqd>k)PM6Dl8I=rUr4?X+f9$9Xt@$S;)IaW!%b|u(a)vMy)cRJ%B$J zUW2vN+V=9#F_i=?MJ?&Jl^0H=n9}iwIPMgpUOwJHJa*eh#01`-ifP#Q3bW^J>;~|i z-;CB`DO#h^2lN?LdcZg=W*2Z+D@)E4&KHS3g#0P zIJKBId3PyUnrc(LEi=oB30B9Q&6CyOQpqIBdb5JtSG;=zw_O}(cL?VCM0=97E|C#liDh9A^u}se(s_-S6u$^Kf`J3eO;MT-*CP z_1SP$-YBU&O^1254zEtrlK*FIyGcZ-I;g`Sd5OkXx!rs-nUq~YsFvJ_*)RGAto^e` znC4*P*72`AwTQJ{{*snFof}vC&G4&rM*OCG7Wh)EtbQFDe~FRJsa4BCC>bwJl{^&_|z#*0Pjqz;n!@ znq+-SNzidSrZ->Bf|KsV`!NKTqN@&Xog7HR6k8x-e0s}04*5yPzWh?K6t;>b0y}yV zxA-^8#EBzR9D)g)K3GeQ?WWmTez&#(tcqjXahk67bSIrHH_0QmT7XrNNxasfSG2nU z2rNaPo#Awzr=6wD688Jor*7~Yuhz;?#V;T=G=9CTe=|TX1^%JWwO5FAQFP5uJvQk)4VMsQsPqC|HX6E&StVx&FNpe-Y^$#_(rq zY1Pwvo2ytmCYX~?+}P_{(k@sh?OdWII0O^e3viR?C9QC}(r9&1je8;v!36885so$W z4OY}uH&^Sxq#XP00hHtZJIj$}HV+^_mL9YFKLShL2TxO}{#75yEV0`+IW@3~ztlAJ zv4~4Gt{;@HY*&le#8MrpBR0wJUv`peSFIyqse53FU-cSfp!ZXmC1PA>@U{utg*#1j z5)Q!x2kq7Wt?6)I-i(pkoeWWAzv&W|Vr*xK*hovw>}nm`R8`xX|}@|EB{>Wr9a3k@^o2^w>?4d+decaC)SQ*V1UIbUxs#JqVUitLSsJ_SCA$ z{~rQN*#JS$rN;QsbE&p*-85EpOsy!^fu-pC^fGJHt{G3VVggIiXDY>ax0hL>^#eCe z;guI+jdW8w%yD6YrpfGSs2@EvnrtBKfxsb{VDqE$XFHA0lDg^;`wm9J>>uh~hpY_# z+KHDk^*VhX49^@_@1&i^8;GHQ5m*ZQ4gNT#`=bMgV1kyOp_L5$jIf8Gqwwk|k9*J_ zR_c-OLF>omJB~s-_jB?^Xs>*}I|`2TtI9cG;f>pl!nu|%K(tu7$S@t|8lunG%D9h% zX_k1<*G)fv%xkf@?MUe!#MN<4Wuak3Q@wNBTTbXw)>O~wv#t!SwOw1b5cZ$%B6Z2M zRWU*9hgoVRSg7r9Eu3xf7>MhUu5!$$ZN$5!PQoFS$gWjOXt?HqjAMfTk~Q+w5Bc6( z`RX6aScM5%2Pyp(X!xp)NJ{Nh-Cu1o_OXbiaLQTY>1!v_MPEkky0VY4EiuQ13G74I zIdIZW-)%`O^}n zU!+Y(@GMr%OS$|ycQOs0L*D;{72d*WFSYq2KZ(A@h8w?}W&%s$eFq#j zw9F3K`h&BSSi()kQnXY)E46~}U8x1LQ-R|=vzNL#ub3!VR!LBBT$rFWjnZ!`)3)S9 zzxAo&!0}T04OPTa*gq_hfe0Le3G6pGeOA|7;|YBR>M!h{zy0ETH{N9d%br9F*30CNZ?u!S6#v#+CO^33^)wWq0{Xto^_)FXe= z(Wlx{ehVKWom@Cy#A6ve#<>BtcFd6$LfdZimI9X=7gIMuKk>08Ct(6hT?T@Vysl58 zBd=eTy!Ejj(Z*ABID|e&!w9l9Na2{^HWI6)e9FT4%1*EhhhPGa4LR;my`}P3F+}wa zo-bmlJD{UKoafDZa>6(#XC6&*-1>S;`K^42ng)7sT$o_ToM4qaGI+j{1A4GjCg|{j z)FveDHL%1n%~C!QJPRIHaR?@`r#bGx=W_DnB|K_aq8n};f6N`S%pISp z#b<3dgN5|0?Q}So%yG>(wbWa}zvAn|zv3~0rPwpPi!@8+vEbP(F+{>r8zA1~ZM;yr z>-oRV@P2t%j^9;;Q~eYCBpeqe@CjGA1qyNy;#X&a9xN3HI_N3vtaC}sX=ym~qZ@8) z6CveCa9o(6UNE2G=D3=hT539f|D{w+^;5CbZqPx`gE#wqn*4tgI4(@kllOm4lh0e% zQu77s#_~gcDwd-9=sD`C|C~R^1da<6I5**rEtKat1QR%);Lp8K&*Pvr?SayWXEP~n zzB_>ut>7MoA#l>4<1YP`=jITaH;$GrmE9h zRaMdrERkEcJU=nPPmO{$3x{BWw&3QOTjMv1`5Ktx%>*4$;2*D7rmw*t;_t74IRq0p zZ~pxnnB&Fy!4hTR?zRR6MWro3d&aH5svlcu%!g&T0}wa_6KT-bqJ(NB{Ok61I{~v@TO;Qyn7~r> zPvhph$v6%ZI0O@^po0>Q#v24ui+0lZ{7yNx1gE@FzzU-mBEbtB*QA9530ZVN@r#|P z;uD~lW(mW#eyP;6eP_-W@$GwCz!G{B-$*!9e{<6WvLo)Op{PjD8(;!UZ2*EwIe-*P zqa<0och z+f$;qTP4pBsSEA%LTNDncb?`meI5t5*3r_l>cvrQax^W8^PZfM{o$`6r#BxVSPGxb zV2K?4P1*0ei}dTWi?QsQW|ZBi{`2 zgL;>~Z)VK%m%f$s*C4;ElyGGTEJaHXJ^8Z9c=81kI0O^4^!zz1^HA=WN=pco6cH0x ziq?Ye1##N9_6r~#n7|>JptXP!C7`arowAMM`4<=83SMo)jU~~XLY#71#zLlf8NC3j z0Ascbr@cB0onM+tqWP2%P6tbzUv%2Ayg~`GB~vHi5Uis<7h(k??u%r77oS8avarFGV`VSA#N&%PTI&aEh)~7tQG&CIUjJDyFHhsd3kTMjx)$Aw~j?g z0ff+a>2u>gEDbB8Q#xp5%jHI^uoR9L>*Kgyhb%SmFt=+1bI6%cs?9UBeZea8{4Ska z{&Pa1{oz}3!!q3^F~CN}Qr&@gy7Y>ichz({;twG!yZN6Lr%BB>#V9x~Ok4-uvEJ9^ zF0G4!chmBox!#-`CS99ktzaon&_SijffP$zY8aW?JZhq}wO)dVLojg}bX1PGAQvpM z1|68dQf)v7l{yYmEaB0nn*Ne!6G?3=N;m`)7eNQT`?J0A?oSOOuoS+jk|lJfJLy;L z2@wPQr%N~l6Bj^7Je;UH6I~V3fe9RfiPn%NN-Q%H>d8)e`Fx1tK61K53D1rD_zSRR zN2TcV3V5cvb8Zs;Q+;}eDJHNK)j_3FK#C%yD6Y`p|m$1%C7b znje!9fu*S5s8mysVhLZ{$W(E~MDz;>_&vl)A%XJM9wN_gzSc;b81t4|sT#n2V*Ggr% z)vVrKO_^n*;t)*Gx@n%@hZXm`pWGaQI0ys|!33?Fe^voj-tDH}+Sk;IhFzHg_fSuh z6D;4Q%-p+@Xvi5)O6S{H}>rsXfif2QD= zSgWuUwu&WIA*-;xt}yFJt!j38Wa|Gv<(R zj^llq7ii3z_-4-_KenNC;1En;FK}EuBCvKWg?$L;iVzXrW(rLQe{)u{%kOju-7Z?V z(U|D_70I41Y<^(kw^f4I@EUHI=C~!G!|W?e&@|C_ZEGKM!L-S$|3zR+aGKy&E|d;j z+OgkQVm2ahyx8{NIm=rGwS<&6&is=O9P&3|t_2*o0qMX}zn}lFe*7V59o+W2Tw!~$ zg}-yqSks^$Asv{&r38DL&2t=r2{u21PmCtcgZ$JQ(Z9rda0jwj(n9$D$%#CJ=d0z5 z3x(nJ$?@5%$tQTunAQy1-Ox);`q!46x&~(Hafk|1ly3CdiQt%^g>$-)x&fr0!5kJ2 z!35Q}zDN%5qN@)&rabIU%AazP#$Irdu+$0AQMq0=pPbjoXyG5i`s`@oYw2kBf;F(W z2*vd`VNMg=Qjj>BoZs?GRQmdx*$SH9 zYWw{pOkgQ`=l0^#7DAE*y@B6y$#i~yshA_d-(f8W#YLZ|*3RbxAzqeP)&7%w`h$zq zCfh~AA()sBI`%cn=4V8#0UdVoXraVfozyCFxjU9x4mwJJjy-c@2upN7G@9H4?;Zi~ z;t)*CqWJ_VpA9t3On80bPmi0gTnB$)DeNnjaBBQXUJ3b;3HgCTFoAst|H97DsT+r; z${sOQ$g!9lviZt)V&8uc@g15&inO#)yld_u>G1yY-CyKLS$blfq48CB{FM+xN_@Y#wr{y_JV0gQvLc{=wHz_RJR4&ou3`;q2CH2uipG5;nf2e0>@+`zFIGHc~{3r zk1fGEa7-N6-K#8_-JzL`iQ->Akv%?TlzAR28GRh*_ClwoS9&YIjSNl01ojW6 zp`X|-Ozk)86EQqHzvj!O>_6yKWoHKetjKo~QoE37GiMNN z`;9aUCCIjr6uM1^JpU5^IhhjgcVzH51QTPv6;bkYev+bt#sOi~W2=!U2Rbl;r7VUO zQ)s#BV=PzsWzQI`TKX4(r5cR0P};;6lFp@8f{ytM%DPdj68=iZ4M=9CxsNoG~5kKu3MB_cqz`4nBKAE!7D%-z&g$W!J z%q=YmSGPK4lJB?bYq3XP|NKm(M|nh(JeDby9QUr(1l6i#s?y43m5hll&%cnCHS@@h z~RF!&gS{hhfRp+cUsJe43uzOm}ZI2g|N@( zk&9v8x_jDru~6rB-y?Od6w2Z7T<7Tz5;&k5VN<>YcF7J(n5G@*mw5yeSZXrRL%9cJ zYH#y@$%eGHcP(NoYDPiGkakJrUBxA206g1tIYk^t?IbxN5Dp_=@78{XHW3e9R=G5J*5)5#bl^iWZRvi3X%pcPanR-9b%`OURXenA zNy{aBjD(ps5o^C|UAheEz!22-y0Q6W=UrIiM6`)GUGz=Lk|tgn>?`b_F+jAxeudof znf*KEWu7Q58_IS!5;MFnlg{=W!SuhxK-JwG)tU^mLbV0Qz$XMq2U!s*|kg}H3G(wO`v01{X}xD2>crd=`*z@U4XC) zYG}amVwxpFe%&P9SEb7#5#j1suxfRaByxV^SVEuwtDZ=f9Usf+gTGpxZbE|nPAhql zfhvv{)7V0e`%x}jdf%$8A#i-YFL)_WbQ>tsFl*3xow05A`HR3(#IcA%t@_VsRra3EMxrkeI0O^8rW{DwWkaeHh>7kK-zw6#{iC6ShPbIXZ+ z$Z-=sSo0}xBCtdCJB)WRfjtdh9A|4WbXb_`U{^xG+OgEljaj6=dYF`H90cBtitSIH zdg|13HvI)$*RT$3Eyt~Cbv>2lIqmyk@8XnWA97r|!BsVs*aCe9O#EFE%_S5F-8y5r z%KIw^ajs#SuHq0(v^{3Tb;<>R+4loz|+ zkTvV+T= zL(j5!XQ9kaoz&TX7emlGXzrI_eX#Q5SW38kQ77H&8!O`wOyKV>>;(L=%Y|B1e`khF zTZ4ed`6Rc+R)Q_OHt7c`y*!`Pu1Uu@{=s(q5!m@syg^-tz&bDuClnq&H`I8glcr3} zl&decP-;K;K}H|3Aros^Dp`Af5RdX!q(*WU>DS>0>Fo6e%9YEpinJ|}ih!@Mcdj%Y&x!N*kaUi@Gq;d6!rqF z>JQCRuEh_M9QcH9w;`c^&qNw<7UsW*CGm2q5H2b+#ySbH3iGFc2R z(ow)6I9{v|<}BgH_qO$CyJvQ3DPsal(dR#-qE}f11dC=rMVD$rBqk5KeI;{)bI9sq zvBpu6xdwCG{`1WQmV8Ek6Ff{7IzwP7I*$4?Dr!H$PfPn&>U*7pL;fbr<2G3Ta62MQJmsmbs#nvf z!#oCTdM1a2_-BxVFdm$7B8Rj*mrm|&+XGg0pC2Qtj5Aps6DJoDa<}Iw(_0Q>tin>%>*l@|?4Wb0F83K* zQ*HIoi_t-I)7*PyiOId~#60&JQr&1zwfv4RWWb#?!WZ31u!UXNF&>_l1L}e@nxHV#7{{ki#C2CeeD%;?_x3#<#q+CBUT0p z0oP6{>maVi&j?x6Y(K&AK7~B5URx!rUecSOGe->*F9%N$yXq#ZIIhS-==nELh-E=4 z!MdThw7s)9y6YIV-hrbcmP-Ed0sb3yl#F|w^cS%^pinqt8Lkfhv_y+ji@m_=xIU`C zc*7}Ftz0Ka#_?jBC6r)}>>A{%xL=YS;5A{;(4lT(L7lA0S*+8PYtY&D~ z1G#v-qI>SE4jWrkDtY=18F_p)88j!7U;^ugK10<{;u_6hb!-i9u?i4{<5!ZAlV&jl zj)~*y#FZ0YO_;2{`4Gbp^`Q^9`AZDxdw(`VLrYz1jkr8*s#-iWjK@0afWEdZSCa8H zhZ0P4TvqjL!KZ$(8Wj?zV5wF>aOzs}B-fc}Kwsj87_y{&KgdDb%Ik#MSNp2LpG&H3 zK+1i59ND#|9HD*c$A`9()WvoL({LZM{c$m;NdvV=?S^VcAnx_sOJc5BG6aqZ?%BS6 zPB{IESKj)DswLOIC2QiZk{0t%%B5arks|XhlKKAU4=+)yBHl##@fCxWHHq3uLWU@1o^ zG4~IaQJhoe12I3Urr6IqM9OVCK*S-KCF|0!wv( z`oH9Cab?BYEkJbpu|Pc1qk&X#$yF)~+S}H&QZj38BUs7{+WEm7evsUfhk)4OGDuu~ zw1ISVMr#R&U}6_|`utN^G240oi2RQS$kLP_;)U@;7y?Ue1LDh<&t$<<`u&L9pwUM^ zc_DsLMluAJ>I|ia5=)K5ph_L}qdzPclNL^su+%1qH{#G!;xOVUVTo~@)@rX$wiK&B z36rptZ_QVvyw_85W$IC~E*ZX$E$$QhmT6#BU_fzkdtq_$bnr|SOD%!grF(pj#P}Qj zBD&wTPy!ylAt%IH5+?8$0Ml>=>yeIcxb6f$?}d&bsD%aFE|KXEj}lCCT&r#G4GR-` zDY3z!%+~-*VH$QDe!DC7vp+8Q4)3?HsPA=Cb%z(`@ztPj#q_eJ^iI6zL^Rx z?ft_nmB-t%iOcc*1jht_ICAPBq}$GrPTlcWa0n)PK_9N~!>`0;G3{Ae#(D@fUforC z_>EREfu(3~X;aS+q~d0Jm)^b7SGB&^M94WEJ#k zEgIb-PkU1Diq(cmJ(hkGhj@evxRhW^*m8AuiLKgtOBZRoJU+dcag?r zK9fHE3rMZdeS{^feP*e>UJ9g1T73~q;rhrDo;$;&=>Aq>%$DK=*Hm2ZaD9ZE5EkjA z#y57z{VR_l`(9*`r!Rhyf`@wvwh-%sdp{aGs$aMKP@0{nreXq1VQXP7oHQwQpnnyB?`MdwJjxT(@!hI4&26=Lgl+4$T)c1WpI0Iquwco#c4B zt6)7oPR1eFSFDZ^bw{ZAwcd+^*X9^-yf_^=Cg>qYeHLz6jLCg^kX_Lqp)I~mGu z9`{w-!eW$UclEiFef|M4++9iTyjV(Jz;kc^O{A>lR#FOfTrA3rA#SasfT+4QNq!tX zU5d1v$`Dw}28b?AmXjNS;gqBUljvWs~#ftZ3?wC#* zeV`n{A()8u_(Z%nMw6N|hXN6Lq!#~hflkVjgN3pXS6hqa
#p;;m~Xr0_Txtt`V8l?V-GU!tJ&4P}VRVF`luv4nE{x*Q(vtOks6V+bsD9MbV@esRUUN<}E`c~(vN6&E_H)50C32B4$p z%@Rs(mFfiRV+q|&E3(95m>SV3SHuLCY6(bW_7Kofq~jTWE)bWlkLL^F3$Uzs zIc4bmaDr);$ltbI4(JoA-s{#!$pIqsO<85r>%|1qEYac4Kr(7ZhLuu|8CX&wUEps@+^QNU+A&qks;YbZ-#sk>lR%MP#_-YLHb}h+aYeTHLPBdEA(&Dn1( z?$|(vz*7F8!|(n(GRTjPYh#YQ<_`{7pq#S~VF)aB?ASwcrQs7&gwQ@i-zxu+E%%#> zzp`ekm%ys~^G}ijPXqCZc}RTTTp{+Y2nhfkoop4t6&wL#e(Ae>JEv6feZ2_`fu$a8 zxla=FlgNyfH08r?ewN)YJQrs@AF1LHOpFH|uZ2WX*7`6IjfeSY2VSfo-3atm?|@ZX z8}27Q!3PPZSt4giGZK){R5}*VGX$2(gHlqY*;bM{lJ4KVw>gskR;9I6>XH*fU@6>l zf^~ycj%1(pP^r_{Jh%z{PoD}CxaS1tQvE9lhdgGBi}#19IJMZjY#(mQr?(_Gy`A`a z!whvK_$2e;4RU!Ln+GiMbo_Z?M0~njV{f>ML+G=)FN$M=RsAo;6`S|Pl(+L{s<>oe zDNMsH1*IZ+@zHdpw%2qOmmf^CMD+NXYMN&|-rlo~h`*Nj>x{pN9GA2K*3EAm6o=0# zE8%{^1=!u>CLbgfyM2){4JX_z1ohhb1Z8o2WeIsK?qd zjlZHMqK3zf6oWiWkLxyWOK?lXal!q=)WUBSm0%4q;1Jv<;+@hQH+t$!)v9b8C9pw^ z7E9r_oh62Bo~0%}tEc!6IcUIA_>0357dkywF2Crk_9**Y#8UV>$P%U6Oj4(g3R6NC z_=`9M6WG%n_i06#n)RuG%(V{@uoTV%mT<6jPzNQO_@&APfs%uV5)$c3HyU*-`D>?UFe1Y=MZ&71Q5EWemn@M`2&o*?eAHW=*gZ z?uFx03G;BZXQ-Wfw-;Z&wiK}x9viTP91J^A#!nWuJi5tasWo6pfBzLEyJ|RLi5iJx z)m4kmi?3hQ7BGRwIGBbRmfM5X)WH^#O=cpGrSQm$C0Y#gQ+4_uqDPZ&1WVyojU~i` zVQPsxAB8QuBbc!zZWCEz=yjbstb7$%_c(39QaJxv;>5fmYQXDjVrI!m1xw+4W{Dk} zTPQpJtE4{M+fBu_c4qt!68kWh40@bI@K+Sd?$qz3(%gfJvL{HzA(&_g>mMl*FsHnT zuJ%no)m^!FC_~v5Q@ylbJ6!q1B{-i%do2qtEMRkWUeGS>6Ttu`8b=TwwhWc8GA ztB>nMVq8AySv-M^O`$hIA8{O^=o{P?m$&(kA+Xep_zhX6 zKA6wIIT!VkJOK-pF`l=%)~DZKK>ap{@06wT`-rLgBX zhQLyI9S>Gav?~;)vYpyARA2}!brISw_FPf-=WCJzX7$kHT*Eb$-6Kp-B7JcUa~`;} zvmQ&~-OB$G+e*Z_bb02@5cEuxkLD23J&*fqcQn=UZbfWr;W``r1dw{rBspV#-9{1TxK~6eERcSY!G5(vW`#W+eucV)mG03t7Uka#gyERf^k{ zA!CnX0$U6BMol^3Oo?(p+=cy#kFpbp{CEhn7o6R*J$!AjtjU61da)~*bYPk#de4|m z4v*GJE-&vg1l^h2JuHDZ=4l9~;ZE7f>CO_IGZ~ig(SUtL_it0891xi1xYtML%5&f7 zq-}2dWLy$4fn$Q6<;43&U)6;jbXW@0Y)LG^mo^fx51ApbR2Eox>tg~LDEL9UTiCi0 z-QONe5qcXHKPH9rW3Jo&tJg*LKRqcimOEy`!Zl_(BHq1*CJUcQS4ba4P|`IMpvG zE(Z&RHJbt?+^X%-6;lGroF}K`hw`xSV#?QoE97wq-OmvC?u0V9T_f@9YnH$*HKt+p zb?h$Qy;E!H-fAc59MtpG9Zr(o`9EYVbs63dNIyr0zk3QgR$X%?s#jm>=ep7iF)Xy0 z@+18e*;0(9q1Ns!;Dc8y%KPc#8DhuYVoJ;1Dwz}YLB=%PEuuGgwDA0*W(Xv#e z*D*5P>7$GZY%QGBJ6I?`oHkIJ;$BR}wqFA}@y2PgFyXSyreollGD_B|6LMa7n2P;F zi5|`;NN(#ZGNxfa!?2A)nbyz65`9N9I{v23`e0nEQ&;`_$%b#%QW~OeY=Lj z$FIA2OkgSOLyr3>cT@SyYU(2oop7sTG38`@0eSg#5!navS`PY2Mii_k_|zV(t4;G& z$Eg)m=|DTfagaK7G@s0}b|;v|=L(?*AcaHxABAyi;lCD02acB|-cHh~Un6G|yV|k* z8PIWQ);Cf;(1u_snx>wwKatxRUm)dum+REa_u7+y{1O5t(m|?Ya6SnRZ@|zT*Sgah-N$$8M1UGg=lG@=A;;f92(w-&w>ET@JW z;vi(&?8D^h>(vCewd^-))eXJkqXemgYE>05aTEO3#QiWibuogW;S@xWMqSaRm2`VV zZE_5B?0ua`qJFkvq%aLPlES^}qa9jkAFeI0Jq1KVy`Jdm)nbSf@IJG`Au`i}uKf7G ze_ylOCh@(RpKpyra5}JV_nE1pa7TU$QXe+|AQvn4BKP3=>gjy4WbQPA^9gp=Y#XaS7vyygb-tYxn!;|I zK9gjNHU!fwF~Koh_1>IKiYHIwF@Y__G^}%K!d0JLA4%#IfBq2Y7*isLd^<6pNjZ** z<6Pn2vZ`SX?;7~t@Dltp>HPPBfKRmQ@zMBcz(Y16FJapETm&J{L`E4 zbrg2@bd)iHr7|I=XRE%E`jKHkOn*B|RVOSXcdnEbuR_T1@^{Gu$5mu6SXi|6b+V?y zT5=iQFDQ6I`mR|A#EF6cHFoO-rF7HBBpIaMMjR!uS=lNdwzmO1vW$Cl(N_o8y*u2~yXTUnY)yJWa#| zwgmeS{=x?*us?2J&NrOgfzg3ei}k_z!P`1DB5*a|{%tmowPUGNu<&B#`=sb&x{BNl z(y{t-H$Ew0u@=XRy^CoWZ4VixhIk|@=MF@R3E-1??K6l~izVbJ#Or@8ofJ=sV0;L^ zvI$eKPbjB!oi|Lt-o*sfXZAF-S685(2iTF0@wE*&9oTlP+tk7x?%O+MLR42h_AaKe zr{VM&v?WhlSZizBduVCf_uu)Gq?l5Y;BOReW8gmhZ#wn*xncZ}5^ZJN!r^vsC&ZMr zije;<(Ru1QFD9$&$Bt7H69+4_>=xuFlbzEg@)n-o%vH&xw+)$=4|X9X@ZyXRd(~rd zdlgIJ7Kd%GZhi_^ufJKS-SqA#6EAMNFm3XcZI5eimpW9`Q+wxIUm;~0?jSf#^m$;n z^JJF18`43x!CKT)FH$+>F#jHG-`V#yDZRGVKW(D9t>m~(GvHtGhbIUh#@&!{8--g@ z924w4kC>^p@pMz%V}~%`^LVhN@Jt@rxnc$LZHJZ7M4dWhNE^YqMxczP&Vz-$MrV19yj)UPMxdu}O`4$tOZ4Xn!C z(5ZVyT98Lst9jZwU#fSKWEN~7m%t0FG9Hm*E}O^!c%Ly@A^!zMgO0x^EZPVwCF?hmUGV(V{}CzGW;?k6G*|sC(Vp4%+p6xRzPs%yen5|P90a2L(8FZ% z{YXM%Dm_*u>&9&OO?)JcTp}7f=yAMQiuEq_mGy=Wnu>`Fj$i`o!!-06D!?5n>8pfq zer`;;!fh1x0^Foy2vv*hsiefMEwA9Ri@m_6JOj>zyR~XW)M@98^}t-(u@tU1raaHP zUG+#`cZ*c)cid_lz*j!glZoDY;BQ}L4nLUst9uhYCg}6-h+|~m(5Sz@2Gm!bH1?^# zdiK%dxUdcablm5oq-#9g<(+UNOwDfaQiz+h!1xU}mlCXx?I*_NZX?s1>m++!po~Ls z3y1R`cGlR3tC!|y3QeYsAt|8!hh;LcIv-+e8O*&`tPk#!@ffP6&dU?KKMm$_IKrq#wV!QAWjaP|MOb=F~3Eo~d$B7%y?!fvsS zViQ|o?=^}FCI%)db_*&Xq5|7vVRvCCVu1>X!kSqg!R|ycu)90)dzKuo_a6PO^T*+G z?%zC<&%|Ccb3JUgd0_Gp6+>_YKzjzm(Crg7H@}KXO3@?y3EA*&^^zOZh8$;lvftI~ zqeSVai8kW`ld#-zzN7crw~vl+Kj(&2A9s_eT}>^+>8fk~jBL~_c#HS(uKH_MoHGLG zBd2ZTajy7RA)?aLky_xQ@=9{EJpxm8j8r)U#zb$?&9rE@oICP=-{&$TfoVsYPQ_OX z*QT7yBhpJOlIChSvp7z(jN%E$c}hB?R1KxKeh0bOm^Ky--@y&w1{Z6@Mbo@cyn&*)#{dCr)zp8kED_!lL~>ZjCx(MRzk27%$So zWzwtw1TX6M88^0zs7~1%1V#Cg}lTMH- zzS0R^=XL>(1g?|u7>*Hh`RW4wm>Kw3VX8R<1it$Wc`TUOoa*XeD`QhXYI zGcPU_A=#)!=WD(AQU18;Ef)w#O01K$&D(J%zRw7*5CAUa;Y z&b#K)iIVx-n*97msn2O;j|8f)ZfI>VJxR6qJ7*rWN=_BhGO_nmd)2;{syGx5kn(}$ zgL$I!A7{cft2L^+w zO$2kE?78H)F|3JZ1p-R4+>Td1h{A|t5N|QQcq|!wdrjX8a z+6`0cE;_FS)$h;n+yttSrjheysJf$VMKK{GjNv(IRACC~)UW?N@v=i5X4ANYh6J80 z#*(J>M-4A_q0~E3HSvOiAy|VL6P+F?+J=3N{whlO9Z*n(r?6$h5cx!@x6x7Sey%t} z6{ZT$4AbsMlM347XOop~Efoz_NTY4?iKaQ~`{5lyR(jr#wGO?1|>sNSv$ zy(nqg<>09fp!-FUK-Fx&JmTe)>pZxDPE;*E&E2El9`{M~OBoWV!rG*7AP2rkS#Leq ze1m?6#1JH~Khns#yoGsGXerU|Y8bzcrKX68X5$!!Ac3VoXR7OU&>Dp&245Vyo!S7m2%UGp{sju@w-cRN~f#n^gzq~=IL+Bie(=sN<9jD z5$2C>(iyF&^NrK^kDi2C1lt*hH;^nK-;tf*)kW~)MK5JRMMMayjTZvA6(FSgA(~Lkp27-Z^D}iFokle zzHJUxb}bEMJ`*hNc#0nhjLBe#ygZ6!e!gf*Sh!bUO?_GRlCPX_jbDl1&+&|z!7%3T zXr<7(Q0=Vm<`fLU++xid48`e9j&hxExebi;HKFP|wMzBoLB1e!C&v;o7-oF3u&&Ro z-Dho_Y{C#E`{W?)E$!lWdsvHh zi3fSV^}jrIw*jV=i~W_BKSDLMf$<_uzfIgI!9yHtDnn==3spnOMnv;#yg`>eTqd@( zoa#QNXY&+Cn(-rn`9PZPtu4OPw2N*8dVH%aN7Zdgdtu*eJf8lOiSIRfn&yA7ux=?$ zO-SfoG$Z&LPbjgUBTcW2z4mY~blt+l=e%aD10*me@>kAv%(?UU^YPs*42fW}vEuzH zp1*g}FRz_rkG>WuUOu38t+Pq3eyKj1gbE# zbOLnoer50YVIqCj5QZwutxS}!kl;eAaltoT(9au;{N~0z zH>*me1b+=xIG)SIJ-^1hUcYcQVnu#|A+sE5ZAdrXY^ED;&^EnbfB5mQTey(AvhzG=RUR#UaE!eTQu7Z z^-@sP+(N%QMqKCRZzTM7uR-f7{nh&!bR&DeZzi0*;7ku=qS;c3Uc&3|5#mIyAT5;2 zz1i6d+^d0n!vfl)n|Ega9WW@)S)v{$Tr+FY?@43`Lu7ipTkK6onXw%KU@KEJ<| z56rDhtgBUAt2;SAo2-=8&^oHH{^?G@I}zIAxP0o(fx?U`v>_AjDHbh5O82SlDSUwO#hPkhVx-5hUspxea)t(6h8J}EI9dQ110pbexAhHfQN%|)$;D3Q*g z3{}3Cue{NW+q`tS{rvspul(WW=iH-pBKfNmyL^-^-;+w%qk$5ED%r;DTaDD~pXt}p zcV$()Z2|9qkmsU{>W*jqOk2z=)Se2K6{;|`v;&!FEt0OiH#hn*k)aCnArq@ZgIT9G z1%%tb(*>pk@3MHbBDdI)e4F=i*H3fQTUK4kcpjjAdbCNw5VV0Y(KmN)o6TyI@!G77 zz6ypQfvKfgU+MEoiSa&4r?mqZs?Z*mG~E<(`h^m`eV!89up7hHfGVU7hAUN1Dr<8c zQcC9S%CM%8z?ck%og!9a%k#jUPq7!6hU3W7{{-PTOQ-(-lZU4}5sEtY5?r7Guz61pX={sR86 z^f>KR<|G9PRAHXz7n26F_>vp_#Fh1 zWfB*S)+=^v0vVq9!FZ9TJ%EE-Tnk?v%$&O16!^_QoJjmyNCVJ_yqt>^{GlM8;e#GJU0z&z1+mNrfK z{`N!I?ED!Dsz#Fy-@*I%*$J`IZ#o9U`v+F$sP{9J8Z$!}s<3=y8`m`<9+%5hu4^4N zEM4?)GO_WV8(&b}!rb!B;&`K+YrA*+d&Sqh#RV%a|K=6H(n>UF6vE~g3RRFmmHf53 z`$~5{{q_#={Q78yzpJ5*=rf;qO{=GT(1{=PHSXVkO*ZZA9m-zq7^h&oNMKCVcJrN5 z%7x}-Y9Xd!Tu3Z`{)vn5mwe_({kG}4orkmO`QPy}R)+u11GrDi&zG?*1YcS^{XEax`h<#kl2bMPuj1U}dxVzZ8f``be}hJv_S;|HOST#u zp+)Sy&+#+|(s<7$y`kV)L}@m!gI4%mA%;2JLiYfkm~x3nHO>01tOlIgp;S-4Cyp)c z%<#^3BrqoWvVZ)^l%6f_@+tli8WMOfJks=g)XI2q!qv`PWAP{{Ral}$)_>yR-!F12 zv))R+mHMd83u>rT`7}|}TZZrM2mJj%pH*yE*ec13&TuuqOinQ;Y>$wL1N7U?$T=7I z$e=e8Z7_76nd+WUa*cZ8twlrYm@2eKU&>n2-SYMrrv}pc00~r~J=&q)n`uhS6{8F~ zFh(L!CAX52{EK_N4ULti2PbOiqiRqo)J}QH5AU%0&HGF$@X|f;R*G`LAwWZqgXM#L zo@SQw&$_wwr5k}a$OPIzn(lN;>1>K{-l6O;kI_(tbt4lO`d4AA`+TN(dui!LQoQYJ z)~&aEtLHneYZauZXtQJ*=6Ac3_> zw-kgqh~R(2*wRIg?ihl^!l~3MS6|>6S2HM8cAKj4=}8t=AS_Mlov6Y-PknH{9e1Ez z`oZ@~ny~$#J*4S(=L=b4aLIQ{>iNcOH+h5R6EE)mudReP+WM@1h)@2gc9 z#m-gQE$pYI@c>Gdm(^{4^VTzoz?kTp?Pnv|hDJhpF><+-cBHdtR&y@v5nsJjKka1M zn3rW_R$=KOe@SJ9rGT`-kSDznSFb%3>s$s(qXDYqocpFvWUp%2Da`$~ln=Ba6Jena zu9fU3vhEMP1l9qjJzD>*i1IP{S3Z&o1ek}E4`Fu?%#;XJVg1wlINifp?7XIG-$g|g zY~k2;<#v_ucU|^0>blu^bz=<)RBhK&b?XJU-Fu5lH#$C?Ex4Ii2@CF+f+0xAEpfoN z2=;x|HtsOnhR0A`dMg=DtpxksKx+B>t6t<)3!NbwD_2`s;PQ^ zOM1C~hPnT<6)KhqmX(~USCvPz8Z+_+FdvvgIaPLc9g4#=&AIQr>Yt^U*aH z4MUK)MK%gMQLB8ZkAt&nEHRfTOTWk*ILeVgmE1}^PTuG9%6V&lS18VqKozzHI$s+e z!A`VTsz$%eFr#WR)xkgBmw3B>Gk@zJ1D*$_q+YXV?Tgr%F(pV~Oa_C;+6Xo>bhbKl z-FY+CGZI)g^p)QGy~?+}9n8s=Q5xF7vO=2f9LRH9*;lfp^0w#z4OJMgOtcw#K*`J; zuBfesXsALO>z`(p73#Ck-;av^%gSk3ir9Np$cjG6~L!5 z8xe3*d0woVv^KyQfV}c5xNN9mTY9`!pmtR=zNv)-u3qT7zAg>TkJ6iK_gYtBxRym) zCSI>wAzZoyvo$LMOi18}j5N(lmiJa1mWQwt-yIYra8-mfo#uFdNomt6(ljJ(sD>dp zTf(=!Xy?x5tl~J(sO(!XNJACwU&zF{Vo}M@9e1kXbV?ILaDS#eyMF*!qqIgxRtdC$G^UVt&(~I9PQ~|_9^Pmv*}!;ZBI1sZX-e51rnL7KX-(t zgQ3fPu71?$)K=v(96b*9VA+=x+h0O_YB+(}9xbb&H$WBAG($cyMR5*UEPN}EWH>9v zSvaol>8|3di}^01&{TcbkYadu;Fi8X?>{u z;%iCxijw^9QpM=aN}oZ2+Sll-?)Xv@s^qtwBDY4c^oMc0Q@4R;e3uGU_$C&8e|7Ga zGT^73_H0W7hA(8HN`7l={n!j;V<&6P@WU*PGoe^`3Wu?Dj5ISoQcYYsD zbB1p}Eo`-wIoabzYGYL4+q*K6MTFh{rw7gkY6pg}KoR_nZreBeJhOt97kIc(D{xtWdc$ZvEVnA%JuP+$|~=OnFr#Y9dC?fl855W=(LaD_u2mI)s6qvN6;&ymfo(krc_E)u*G2= z)TGx#`ljsRY0dR_`$pIfqVJ+^DNn1=ceL;-9;(nD?bg~;|ERr+hrCQPBY~|Q?a|D# zAAP&Kp)YSeudW$Y*v4c+ua8Bm>n8U7;BV|pxed1*CKP zTj9S0#A4)R-5*C~O80$G2uQ8p=+udAOf^*i)Lbh@9uB%e7oPMvlC zvk6m$v`h>>ZDG+L^6=`t_DTe*^c7N0o@kZo8P1HKj`ACCZv1-bEvLO=ZuMQN|Gm9@ z)yl#q*cCMw?Y^0#3geZD=)SX*l=_ZhNphfuZTI&Vp>z5p-K*AQ6!W;3D7+u9P*H_% zZ`ZSV&9~%=<&CwG)UK{=o~kTdJc9@B2w|wgb}SQbKlwA8@v7*$XS0eSdJ1z=g0^Yp zwKQ0}61r6M^mR3(3Td=QrMqdE=6>{?s6O(c2}AVvSaM#%#1=#QaBJvGL#^%=^~9YYv~An}B3*zeoTr=8Sa zoH~6uUes#bfd!3vA&@{7rjUMJ8rN7!dp4fg4SXm0B~+nbp>Li4EhW60JQ98D_0uo} z3Cv%%-+i_&BYt~zZzH}LhOhAHGXsxOc0w88MEST;%0-KFvJuBlH;`r-tEhDQ+MnU2 ziX2zvc}ahtaP4}(yUEMe*b6U;>(ms^i#_?F>VG#;Pw+dQKU5r1X~gji*J@3PPj<*x zTr8n@V`d-WRg#}eDx~SVr8i-kYj}APve4etoNkty)bS{PQ0bP6v`iS+S+vYa^VFhe zI&maWg?XY=5N#~l$w?p8fIYJ$0#!I0pj5e9w9!TCaJRCNW~^s?lM`n+2E%!Gi`Ha) zeST)t6p26;)+W7w{X^xVPs?NKRzaw|>h6WCtmK3M3GMVr}RlRAJ^ z;P@^swmxi?bPuFAeZOM6gg03<(1fW%0#j%()c6>tO|5PaVWan%QHAzoB6WwI+OlOB zI~-F-T&K4yW~{r*{bLVseA7Vwl04~h7p1_tvF!O%v-11vTsbdt=|s*;j|M~Hk5OXj z;~?$Su@(Z~e?XOPFNZc5DtJ{bzt3f9{=xA{(;V=VxDL~xb%9>1sCAC>?spS^BbE*AqS+W0@C>B@!l$6 zPu-Va7$*w#50z4dDzr^sI-Of*3gvV*!#O)2Ij?vQCciQv>;=zXJ&B_|gCTE#t4J_& zWysiJtm%ggKK#v7ZudP=QXx(A_VR^Agl$1q;8{n8A=uA{lf728KJXv!^pkqEwuEWr zuiB{9@>EmMMvZqFyi1zkt9He6IUg%(RMYm~ULz`gYABU15?Im(L&p+zwfW*N^UN@J ziNLZ#+jNF^-gxcCL>^8S$cX&Iq;ZP3hU9aEJ_^*^tg%6m`Jzc4)@ z3TY3P`e=a?6AC!2H8~myF7H*onoTF+F{rjT0)%<=T{l=_f>77NU(>$ehnb9naYU)79 z8a^uTYL2u_I4cclKjx|8IAnlCxGs6Xrv_}{mme;dXu9#e(!S*U(?i()+_MC#FjZ)e zc2borbGfs{G{0NzSRIPj5OaWkw8-Uyw81cKPdj0K=CPPm*-s)+g|?}GR6g&1=!u8c z=R-A#KwpccPA>_p2obTxZM2?sJ4ytOA4t;|rlZ>{OK*m#Yqm|0h;dZX6+<_1>%1F( z8`Yk>6%!%FJDKNy43pjsM;k~}SyiiKE;F!$7Vle(p?^gmg)Nk3eRg3yw{wKHsZ$Hl2<5rgIIVb6%R(_q9gT zi(0{@{iwB%&P+8QZR5@+ov5whE4PQJK70n{7IW6w{`Ru9`{o8p?r%j|YI zCSRg-OlkJ-09O6z6XostE5BZs7WBIG?vj`JopX6b-3C#=-iACf(^iak*WZwK;`{d1 zxI2I~Zz&V{YezXMe1V#F4IFFlTby?Sn|`9FWCK-LB6PkMh%8E#{;u}uPZKz%P$pd0 z?u+k6_gKVKdg6`*s^roQOHh9i>xsy>;mWUa??UB{v`ie0`r)#g-s~G3T}~i@Dy&WV zzFl3fW^#I|+0srFBOA*@3W%WdO*zssF|x#Z)1!bORFj;Z$t8m=|d}Vv?mjfFBLRhJ=L3aTlZ5UP=%{7gCVTJ$CTynORy-^e0D{-QD>-R18JFv2(j1F+te|4 z|JFepPh-^G^PhQIep{~p-N5N5FOp!((H`BtSJk4Ox7%VaIj@(Bsketx2V@JdZ&PSo6D$Wjp$%45=H& z=GU$-&_-P%o}K>8%h$2x2WXaY#_KD8=TwSX;=?*`#qbMu?9jLRQqEC@w)I3OKKVN)8)He**Fa(K}G)D~$$t|wB{6(p1eR{UCB4#Y}_((Sz zLwYeEY4q>?-M{e9B|lKx{prdCi;ra@p^E_TtYfs*t7{d_Gr*ArHj& zr9CvXj(reQYcP2FcNIG;JrHjf`e~@b8kC88Pn@;Qg>2cXzHbEDczrE{hdrUYuPvoG z#-!h~ZP092cxxwnuT@Zm-asbq(;JNko3|IEF1u<-R3?vlGT2(=D(b+IraD(Yh?YHn zh&DluB_f_mbc9zf@ugEWjx@d2{N|)68}>}}so6%u5F|c~I>Selv=VEM)T0{AC~Y#c zi`_Nb<+c)ms&_;TwzC%DE%n6^;jCVTG|Lo2qSXxg?Rk4}fcwOrd z?VVw^f&{7-5V8MmZt=Xa2NBz?pzMe$nu6syz$~{_p z7Pm*i5G1gq>4d`PN<2C~SaY&pD&_nr)j_{wR-(YTg&a$Pyy&t%%4n^(W?$){7((g& zyKOGf`TAl>g*26w;j}r+s;PF-rMk9^YR%UAEAL-$Ek{}=>})oP+_9Ckq#G_0fvO}* zVaJCr`L1w%<+W>CMWuoW2oK+5qM>&g<^7PMS~s$B=k8H{W>O4CdoodsQsozPMwxPW znAVdBMN8pJt8U^*%f#RU!RG$$O0$6AwptXG)fn47e0if)9BG+wIuIpFy{W@|`#VYm zs`R=sJ&EDgD;7{bGNx8kem3aDj7tk>(PZPv%pb$^op9qw%f!(3LFW6dIBfiVchw%RcG8eQl`Rol zhg{%eo93caMSln~CwqseCi?aA4z-dfx>dYk8!L{qOibAQ>nOhyMhF&&>oFZ zpT_d!!095APRk;JDr-uW&C=(*=G%OfsvWKWQR=r9qE`Gsb}Z-!Kcv3lpR}SJX_+W- z?Vfoa%ddT3*o9rzTYKIgeEs%H9BG-*x=aqvjJ)gyp7@lb5ij^YzQPpte-$uC=H$bvZ|mO5f1$Ud$8jdTOZ^ zD=}0d9ZIu-H?3_%ol&c)tn^>1S3E16FsIhvMl8|%RHD1m|K;shzg6w%@AYem zVB3}Y%CA(t9BSn;G2!!o59WxNa|p{*!p4=5fZ4>i^?$omxoI}qP+yCR`^dcma&z=J=)1CsSzoMO)OW5%y>I8) zn9gI%e^il{3F{|gwV(Z(D|HKb3v9d9L(cM=K2f~(lD-^UKK(LUB!J!ikZ!t|nxdeW zL0{rSv>Sa*Qqcc4c^~CVDBJ5Epwu`rF$Ha4+eLfytIWetmT}@hO5dTQ1lBp$$Lq0Y zdB&&neCD)xs`HySg0zRz`-zPoyGjJAc2VgL54p;Hd+NWKY^@T)48AiJ`_5y{m_tkn zdI|b+pjbE?zQIO0<-3eyYsYxe9?dMn!`Yi6mAIX6K7j`@hq@)V*Phxq*j70L-O;6iBrSbO*&ZnVzwQbx4v!+OqoASRH?JdV~fAcC8 zD5dPSKn*>>K%%#iS6f3~4P&A;PU-KB2Ct1&s$CD!(0?F-G0}}DC%hWvo={X2^b41W zA!NhY=LL_MAIFiV^HEh=D1ni+h3&*~8v0r!&^Fy`u*^%@9rai=nc=75$cY5TMBm~> zdMO#J9}DF-VkD)i$Nn$eQg$0hnr_T`-9o8*p^i4ay^9t~sy6=CqJ7j#js)7KFEayv zn1^p_p_PrQ$Z(Ggy{PO<^f`lPmg?g1wY3rZ0k-xtWV@~PI_{dP{x_%I%jP9aDA3M` zs;#8@w$#G^9jfp@3BOs56867qWyBn|C!*@UCw%G4)7+c>&RltnmqE8E40>BW59q|&{=;1myX z>i=IWiAbFmf96U@i9nS+8t7%UDP%=_vG(3Z47o<}9-H@pfB!t?w=qg50&RLYt=rjA zBG3lX+4=DM_h$Ur*KLjHqpJgM|}%-fS%q;Y5#pTwE+` zw?v||i7MkKCamr4ZCpyKQL77yS4&26B+zy?VJY&~sn_#160w}MF5R3EB(TqC6K>4|6O|}0BYI1mU!5Zxl}^!%iCy;o*V?B>?M~?F)zOG5Y<+(c z7auNiUVN~FF^%HNnZqH0F=eOfdCcvGeYdxjQibuxQ%r3l^NWQ$D^uIOe#62Z9bTKV zVY4;IIHd8TJ|$+d zihZ6|EKA0)Tc669ceIHS7_w~gc`gEO@+x~hR4i$_^Q=~HcDmqb#na`!z_g=k2GL(G z*@zNnqp8jh@?NYl{_N5pS22kauze_LDc>ADp zL=>#&&$d^#7nz0kN;XhsM?{{jTlw6DM~G<9IF!|^`-DG_>n#ze!X8ZTRQC*KN0zS; zewk0*v0Y)`?npK!y9IH(a{AXhJ2Y2zDpvz-dZ&A440%Q??BSIs@COGLas#dCU+x^k zXC2k|^iSA3vzrM{+I*M$5`i`(+AwK@Gdnw@hPJT!Yz0-f$j0K7DZJ#d4O}MLPU*&u zmU}7E8_$sl%q`M%hId*k7Sq65`+MC^1yvWx#s+@7r)Au_wXNUGmR%#uFDr|`|u{WwF zJCyNS@pCKAP=)O{Rj-@obc^A(G_tWhvNkKb>xpuEe=&xtGE~p6ZWR=^4db~?Oq~(J z7PlOtWDPGN^$+Y(NYe_koWeZXRA;#}t4n?G6{WnTSzDocxVI?~F9P>=5k8P8Lv@_veKws`68NE!(b)IJu(> zmkC3xBV*}iW^c7ZBGBU?O;0aROIP9@2e3S|ng~>tA{&=1r9|l%CoU7MtsPlW=lZP2 zsRa^&9u8?*v0Sajc04b@{7&0ws6sE=fb88GR#=p~`JDW&?Z!H6`LZa*IoVM|6?*Ds zL^yZPEp8TAL`2t(&aCzAC}q7@RSi|GNR{>GBUj1~Q)OcB0cTd>gjrdYRaYW#{6Ly+ zz?@N=t+Y?#HC1=*Ci&f*nQ$AjaeY!MU-7)HiZtCK=;+R#_R1$Tv!g`dsD?DHIqUsY zV&kTWLT`OERC$q&gok^1&w3%MOr&U8%7h>3A~>&yL`0h{HLy1` zCeIc{=cWs^afb4gvj#+(>f>-v<`s28JiEMFpvs9-HR|zv?({QLm5CK~>aqM?v&5}! zc{L<(27olZw>>>w$y#I5dIs5QsQR01_@_8;qM&jmH*$uxngvScIqco^?U_Z`SYpXznku{y5Wrv)Aofny2M^vh`LzO0S!UU7K! zb_M+_`rYH?C9Il8@uY_;c{tB+Qfr-QdN}*ui&>zY-%Zn;{=WXCyAJBUqI~2I6y=O z<$QQ&CstN@qM!;#fGb33M~aBpWc}2yFV&z=?=H-)=~o3+cS$v-Hob_FvWCmVN+O&N z3}v~OZj}feGmxftEh!&O$~v=+OP31tujo;$Q9B-3tGGy{U*Zjh7UXwT^1H$0chSG1 zM|CG+*O2_;(duOKqV0&-HKds`<&;T7--lkUEfId@AM$ygo+4YHqPuqH{BKqUc^y_Gd-E;Qzyn`voB2B=HZ~=T+QxDG+)Taa!2o( zzs(a1uQ=v5q9Y!e~SwpMctf@qx3hj}N zdJd+fD%V8Dg&_>%ML&3jY((0}@i`?=l8sHX9Mrm&Tw2xhy(9uvXpeS;FLg2{myQ(i zk3u9bihl3{*?1D5@w(sib(A*|pY{iel-N*-KozEtR@-wORGU$|MAeMZ3`3B>6w=$| zwH!<(-_PdD23Q!T1byvUN>!c}=XheOz8;)1-$8YJRYe5Hg-Hae&>nq@LpF+KyfC+J z8o@AL^xEghM$<2M`0ehxjll~Y)X^K$O!uEyBmz}v&tRBa+rcz}`o_4BU}-eK5#S=( zDD&+t?en9v10r(Kw7cjSaOwYL{H5ng6xlz zjlD!%?f*fEj_E5AsKOM|xm2pb;p7$84I9ZY1PM$bt+rhpOl_$*xle1!aP-Qgl)OHf zR}7+cIi`?KbIfp1%aT`k*uASX4kCf}=v&UaolIq)D9mnpEr#PDj$}{B-bedF!g^jj z<-Fp(PNtpSrU=n9gJTDi-Jyf^gk6XQnGXmD{H z>&Yfb1gg*;{Yuu`!Ss-Nlhx)l6<2ZPC|>ibGUAHukl$92bp|-7i^wbFc|Y5XDM145 z84PcRIGB1`lyJ~ni7P+O8$h`UB7N@?8AS<9jd?a_E1 z=wMn-ePe}hn!q`Zk>XuzT~es6t8lbO@9?&FP(#QoSne&CW=lw*J^BsO!N)YvqdPnE zKCiS&#hFucvgiDvsGt)7ln>7;KBgx9IktZG;1p5 z0|`ta<$U(9(OJ22VTd#r?L#TK{5^{=xcbj;D|%x?2la3A3boJo(lG5vpglTeI^V(6 zhkDcKi{mt$*A65bK^tE3;!8TKI1i>8tmB}54A`YOW{j3ng#_9ozuU;iBv6I+=*E+I4yI|;{{m?S zi}B*De*oF=D4xPUPw*ofT__)i$d8aekqA_wJ%d4=}sH=--q3kzM%9bd#zKKj)4 zF)hAZS-aKBQzB4>siogosO^?`Yp1=WxjTj+fhnZhjeEUvO@Gy13-KwgVM=iSqAjIL z-=Eo&rQdaL-MpBw{)hV7gCC6~0##^__C@o@x~i9lXtSzc6BsY9!kUr|eSb!w{TVq` zNT3SsQIA^M&UOBkaoV>glcd!huFsswhQ2>jnD%GnRAEX`h4y3{7;g=VS6?-Dpj9K% zw2RX`IeGtJI-mG~zG#}NO zizJ+%<2?E^&14j(3%vf6^^|j+_}F4|h9L2iY~0(c z@{>oG|7Rn0XOh#@gKZ=NRq{GYw^7C_PyC@i-bomOguJ@bi7ID(5~2@wO~Mc)P5Un&Huh`c%h|V-2vo^yXWfR)%t!GHdbCf%5G1hv zv+E-*@Jsy1!`?|4g2bP7eza@HhLt9FO2QB%DpNiV9@xnT6zlb0KGeTY#*e7xDG{iW z+peCEvX^H#-|N>g2}6*O`-e_=?eIk%NWpz12c^uP6>o{trd z9h}x(Yn_B4NMN3_Q>A+NCD?asDG{i`lFlY#woXhC2R)N=QF?P$CVIQdSwZM6H0h^7 ztnM}HzkI}}c5yCqp`%2gN?x((`6#vSnp13Gha?O^0`rues*pW)30dD;N(8E~q_c@l zy_Px!k7<*H^Ff@qIZ-~W4u0Sld*~-X^;DJUzaZY}emjXkl|0|o35TJ}6MPL_lQ0Ac zc^0k{_bN|Jm>uGsgds>^DP*VWb_0vkx73yrfhu|Zq1#aEy^255t$h-PAR(`cbmCdf zC-Et%-bomO1lE6cswz|&;JoQ_yCj?s;=Ij7rQ3ef9Ujv_Kew&hSai}a;pDFN5`ijt zzN-^2ht+fnxZgGjLy*AQ%(gLjXd&lUcUmW52ohM**+lH>`w12Ac_pD=LVwkO^0DyI zK0d~;;eYu!axt&-(371c0#)+dN6$yeqzZ{XqD>NpAR*7lbYgLx;x3n-wNJtjB;=W; zPOMtwno!_iha?O^!kzL_bTr+P=Uw{0d|W-&HPPF@okXBYo+0ZtKISd&a$`^1Bn&|U z>p#16qmLhQ9-hxT2}6*;x}k4z+I~^a`FCbVR?b$iZ(~b*c6ST^@idFSzcZQgQ7PXL zw)N9#rO*2E0##VgKZrQ=>?dzEsXGy^zkE=$?o4DO+B-`Gs;=!>!(Y|@$zOl$M1+U^ zG!amF9J~62t7rpNM~SGu|0i!-c@h!E2hr|h&xEih?;{l?P$lOheo|5XF0VgJnSM~g z5F`ZII5YekcRnzSY$TWN$Rj=IoXMC25`ii#Lz+`>C@jwQX~_oEF3T_ki6pYIY503S zEOjy2usQb3d}?_~W~tp)B2cx5hy|u++;fS3r&FgHd3kcZ>g@JR4~ak(jy|*pu(7as zSR+w6xMw885F}#B#+`Y$`JnCkoi%0ecQn6_tfIvA36ls^;Ydxdj1`+ER+g{F2Yv`) z7=lC`*(mbjIA6bQ4cYj32i)VceB^$9XI+{HeM`#VFsb(Zlh5pfCFjN1q+B8-()Vswo z1c~cp!@*%U_y5p_Y)t;p(QI>QkY?|7TOffd^j);_DmqOJ2yCWh_AIGk2og`pM)6#N zUvl`HY#h4q%%UI5vW4{NGH~h7)9Q%KCIU_TMa{yKyPO-404@m z?%!b$o1E*8Kmt|hQL{&bK9pV3X=g|hs-BaL;&o2)_x_dnpG5G9@Wf78 zT_plrJJQ)U#_jvtMQQAvguUnj*?2N=H;?GtpCg@36g^x#armKj5`q03>1^WbOULJPw#d<@lUruh#VD;CD}Iq z?zGA|(%3l(Loi+(8M2A*XA18-snq|Y26M(GtWEtF#V*>w-37D@6(Tv-N291Hx^x&OV0##Ty216qtFa(JTWJ7Nyn}4;E9WTZw z&Dfk~s_??XkU$mI4gHoH=$@3d<$pv@JtI+`Z0P^q?^i1sajaC*=Rw7^6;U02*~lSK zCD(bg=ef0R(RNy}b4`XJNYo`8dJk?vJ=kCvx!q`V%;zokrB2Y0K$YA|+Wz$=v1eeI z_QblDf+0xAo&gCAL4r}Lbl(+9zKhH1^IcJ zi^lmHn{7!`sg+0ss^rn&AP^XWg#NcaUIo*5WiYfk>t;OCAP>vC&R6@L$Wh6o+MtS+ zjHigOB?3b*-VS6#A9w50xJz#qKi}l~P8rNrp3M|UpbGmu-KXzRmgQUbH&c7u7Z`#> zE3z@!_AB2tqm^#sPLkNPas;!AtsoJo!ao1Y!?CXZTV3WIYGFiG3yQZx1-QKTKXnjNtA71K9J5PR$S=pyuEx&BdYw!M!hX} zc(Jec{7>TOt!fE%8+%Ix)(6trHa<0RCBf=O8;QUkg>*Ji<#{b^X^?)PUC=KtGGvVo%-(%Hlz-?<5A7Wf)brP~V)f61pRtNEYA%VT!& z&DXd|1dh%~XWI~ab|&tdQ{RZHT4dw!k}MwCYc~IX2wpz1XPl2jp#MNR+eWFLmt0;Y zcQm5PL^h)GS&57R!}y=X=J-J_5!THm0zD4Ww9l~foMQJqQw(%!$FM)QZMvR+Z1;k< zc~$y%UlQxjh7Q;$(hGYk=w*V|t>g)PvUrh2?!S4sMQipe9SRNA?7#IDXuSs6D6qjw zu<>Jm%ZG2=IYl(8sa`DcVbgRmvE(2P%RL_vW3N5o z4O*}Nt4@2WvUfhcP z=6z1>@@KCiu9$O2>{HP9O(h%s^Pk}RD%=0&MW@7mGjCfHu8pfY+KlxPcwz&0{E zr57@>ZfHO8%@*ak*C?&^xZ(=7B_uE=+9_IGlGUGER@*nlmLZ`~K4K1J@qty{InuN< zk+sm=@Wp8Dy3;nv2DU4tsegQ5Xg)Hnu{J8W9zzwjN|{J|x=($*xW4vx^TrHS*xF?x zqy!j=Kd4M%LLRp(sVZCL?^bqcy9K1)C2`vMjJ}| z+>3(msa1~4#EIZ;O2DSa%7_)c84}pWkTw`zQO*liEYDK!doWbtXekq`AM8_WQ(e4T zT%Vx|Tf0m=Yuiu?3@@;;AJvEBr~^FY?{O^4ae}};Sc+5$ zUE_H0x49f?gJHGRBD3+uXcpnLO(L+LBTXl&@+>kRo7R|l2iMb3g4{9>_=+@*I4^w^$FII(^Wb0& zRp_Z@;@Or|^Ut+KwYDQWNWL9M1ElG-=E_}_oi44l`%CRLRN+`sn)1{${U={lU=FpC zd(VB81lv*Ch9ye{s?ZP0gzH~n+Rksalz_Kg%-G^OQLnWrv7H~@F_U9Erk7}jj~9`d zAxwL6(TpKTj3+v*a~$sx)qqk}c5{fjOxo7Pl7j8w}$L{ax_|y)CnU zBN29q!?k0Twg{VoVPo zrZ4*`=gPJz!lT+O1ywj^$V433m{hWuW_|pnMBvzmw88LKhtVv}d8hc^VWk;WSm)R( z4Tj3KZCDfg4q6$P$pTf_Vq{{;nqI8+n5E*h|0RJf1ACF&N;VPUUg92K75GCUu%{wT z-*R?xWMxl2<*VMfYiI-87}7MJ&+})O&%~SU#vTx;LXRU8T@H+9#fOYmN;C=+*j~|d zB2C}7k8Z{SO}5O~Tu21=L8NJ~c2OIqtjopro!Bl=g=2r_Jfh(T`;lM?U$uh@Gt^q9YNROIP#!=Vx=Ivx(6iz9n4w zKeEm{zJ})e*sIcNhcq-ZE7p29J-F}S=)HM@6jB~^h?Kr$`un= zy^>3gy$k7IME@FF6T-%M8&C=@`J0${s)$>;H*(35z?|q^AMGy*t-Z+dX#H9XMty9x zI^<)0U+>^SL-SHy6?$xDL(9cjD)n7sK`CrCnXr9eX5;1;v|MW``z}hMA1g}sNi#d8 z6|iJAFVE52(L$sZWz*hx^}MkQORjlcYe(}BE!0XI@WO$Qr+NF3T{c?(n{{~u`oCJy zeA>}){cHH)E4|h8IqlThfgu95M-g$L$OG=}mTBolgrVSb9_690z!p7Tn^qigHo1SD zED?Q3%D-L)pPBoT1!NMG0I>D-v}D(Ubj z(OE6td4RCZcU&z;QiYx@=ZB8Z7z@tXnbx#x$KTz}`3Iei%~QAPg>P@-F=YQI5f zl`i`&Xv&V?*{3VMWCKs6EE%Lk2OF`b0$8 ze2@8?M+rO+5w07q@FpEnh_I-B>h(Zx=6@<5D^5CU)Xl4%Tf2}qA=?|R%dK@Eu$EiX z|1FB=(i$e}v!$H_Tv>~SZmiM0SW6b!Ub2RrR;XkM?@j&VcjT1YV;&J*F4SlKWs9mv zpgyD(<;vrpEMZ=zYW>eb6{XM;?7@nXMufdsrC#oJMn$P_RC1qP@A!^`JGo4J@T$+c zr`U;g&RHtfF1Cl<2k#H-%qk>3*U~GjQBew`flM4G9Yb?h6}!%Fk_c>nq!s1u})TtJ=pGTLT|v<#2Bn7 z4ey1rVFO*XC+`nPZHuibw@1M@6WHL>GkA!nuZAhuf*30mr4$iWiCEjrS3@a`b~0h- zGLSju{A8Mc<-CR|7;EL3%<6HTtiYA!YRBn?1xj@$-_0}dJAZ#F7nh01ZXs-aRd>~< zB-2m|M+TWV(>9Eq7;)0n`oJ(LFC@@I>1H6m$!u$KPW92AnH;4ss>wwETU*rEnIl-j zp#{=dWTIH>bKFjg>@kRA+O+fjbUN>sUW=_OZekb{QOb^VZ0q`-U$NOuIzIl}Nj-U}7#kDsB@rlv zeUrX(F72Xj*tkm#F$`vyf&}(7ML8K-ke69KQ62m(MCyY`$YWGG5tkF%Xyx{WN~0P| z$>U%@BCNKR64g$%kw#9GDoG`;lw%_w@N);x%$r+OZ^!zgRoN;Mfl?UrX*|!>h*ya3 zFT}GaQfx;;9?z}qI;(@`PZ0gg8>QHeQu;H_sp(63k-hqvXXkvQOlG=^Hz?j#nlqpj zMhSYC;jq*+Tr~^R&yyD{U z4$_D-g!0{;lEU*Bd1k?=q$tG;c2-@gFV`BR3>TP!gghgQ=oV}8{@zMESRz!K!=cnj z(pMw+65XGBiso={mz`FJpL=0)jv6EpC?(Gm^Bqp-!)6~)uRR_jML3iSBpoizfAFEx zb5LDrUpuKzagS9WrME<&6h=Np`LL>sT48T(7VPXMFa-&WWAvq=)Kb&9`5x@LsgA%D zB&LxkR*bRI3J!1}tN!U4Wg2s<6RYvvP9jhWXXLcPv|E(v#^d3vlv9F+DZ?mVL(66bNMJ-&lumc#t0$UB+9NUJX=-nTDNU_S| zN=j47uh0{brn4qVN83f+gp=Q9BlaTfwJoRx|JS49XzfeOb)hV2T^nh>i?(CbRuunh zL89)nL+Z|4MKmle)*I5aDvSv09XnLlqJbK=0k$C0bS7ZrB(|_sb?y4i&_-ylZpk>? zW!%%eh&wM|!2>Tx^1crzQk(0~&M&4%xci-I_w(EK? zThNW_8MVQkjT$|l#a*Cr&2kdBc< zthBlhV!1@?Ehx+va=8s2>YR)Oj zjV7Xh7Yd>9?-MFl@E_hT^|@VBydzin#S{76WNcMt5UZYYo(#oDAIAiUOL~m zKFuN%#T}Pxxm~QZO5H{=Bru*MO}ilKo0;SCx|SvH*PBpk5Vd)yka*tj!ZV9Zyed6} zRrff`clJ!vkiZcDX}aIpYBDR;h~yv(YY`YGup-Q_Pt_>xJJady+gHem(Qpum7D0_u{{?N2OeAagem&_t9pq+ z>`ZoZHIHqIim|T<5x-+%ej*m$&Z&8q)z1VB2pG@ul^>%vJyTQao!E;U2d&^X{R(K) zzv%B1+p3Q>zh~`P{IG)>O7*0CZ#}WrzE&y9Wy0axPhd*e6DizIi8}^0DI&(Oh%}5oc2jmZK%;lnu)FcTYtRA4$Y6tCL)r zt=}GzV|Q~Fv8Svsw=Az>J7e3}QOR!vE#Y1{^*z<)^D=dpPpD`%`!L6LM!I#e72J3F zBEE8aS0XA`9?3eTem1=-x?V$jhms{t8+_y&3Sa#rmiSI>qwWo9#gy=345NN|$~Wy= z9?g7Z!yhBg^ipq3UDmZ?&#shW*v?4EZGPTqvdL1Rfbi(tiJ@PiFUg*`&1b2a$U*?l@QkZ)(5-5fG=xp3dlZCbKLQDBQ4jRU#U@FJTOWSz<=udyd#Ohz?YD?Z` zYE6@R3G^i-P#?`+n@<)+CcWZL#rH~)0iyxZbboERK_cYHJS{`SXc);*3awR?4rMBe zId@DVedaI?JrTVR^(jiNMrP4s$sGP>e0h#3NT5F2&sii)>}m6nSE@YQh#ro80%=9L zNasvOI2_@YA2Uqo4d^9E(>s~FL;1oBeqxEW6+;50us_lhOUW=XHgBwDcGP=mK8Vo{ z72XKCv=wEPvy7=8P4GEOOUO*>co(~hTZyTBxUEOZN zzJ`4e^-;89 z;%*DJS~s#JE>}*?yxsMWvGxSj)u|KXjk(q>PQ|uG0?R}@Ss$52WbP}*HBa*!kw7V| zL%LaxbbLM8)Z%icmJ!6DBqNc1Be_Rb0X)tEA*<12Y$z!hKP;VySlkw7Uqw%2-L z7NxJ*Tikc2S}+BPp`^n*?Go=$CnxD>cH1o62XF95I`~5(Pzqa?=Iz;LvB9mRan9Iz zQkx@ztx0pZn!{MNOre!I>%g(qVy-RY+d^|`TVKxPw(FPj@r!b3pRedMnYfF6S-CA2 z)UI{|RU}Xfy^`Lr99W@_FL>3o?&2thDIfn?%7=A(%5N;($YtL(_A#?-Rp*(qXO6UB z3KHRD;U|?=1$K!es~)$n#_T`7)spN=Fznk%FC@Z$Trxk`O5aC6*Si{PGo-Ny9QTx? zFC~#wko6`$vtLh+?N6t2UFj)Wv^$|K-nc=-Rzs-_q7ADOdGzM;q+=K9IB{#f=HlTd zkhr8vtxV$+dgkZYHguNvrM@gG??ClP>;(-|8dDqeE|tX#cPql>7VNy;RXm?qiCwI^ zL31XlVjmQ3m4|`Xrr#Bw=F}Wsw)lf6aVJ&_%R7i!^_i_gl_>Sp zowF*YATghG7wGkdi+B239Q#CP(LYpZ<$TI8Z08T;R~}!}dEtOfTyFDg$5(3$-&PZY z4%TOwl9Q}@=ewKRep|-TdlV&nUq4Z3;7!fau8xW+NTBy9%CH1yQCBsHij7uSFr^sj z_;O?ukMCpV=wo!YArU8i@``yk-fHMe^@teyaw~TW^5C*xRipNpcW#zesQ66{Q_!!_ z-{>9kwff@u=Ky@w(LwV>AF zhnmToNwEa|3ccso`x4uXV{W4Z>KHIz)Mq3Mdk^@R8}sQWAyA}d&1|+OY%4X;fKphF zW<*ph`j}h$>gV<4qWOiOrqe|M>WVC2NULMN;G^b!NJ*Qsawo{;(=_B)KhiZb=! zp+@O-POIZ121{OoZIJk&A1^rb6%R_br}kJq;r4$2L-|=stTr?eP!y#+AL;n)T%crXaDL zbm-C5pQ0PK$b&-`M+7+(jw$d_}2KyM!fjP7w3heon&_BxaHhpNL#qfO~t= zkuklE@xzM=%-FY=M4*)1qkLxVZsa<3B71JfG)zHa4Cx4tw9?wF?N2(|cuu#3?lQ9? zLX~1WO8FDf-P20Dmp+LI|H2+dUVJi3jVP(24wS-?f$pd}xyq8YV+=dlbeW1NNVFpz zm4@Wh5{Bt#2ra80-Nj!3KHc=$HU+o{P}+UeWLRd8)KQ$z0~+@nLsIwEA)Q1(NatG zF^es+&&&){kkEgZyK;tmPStf3&pX3dIk1kFuMSrzWLfPvTPs5Mv0w`3 zTbXpc-+P!RR@dvQZlG$ko&7=^oTtA;pcKvw=>6_R)nj6w584P1e`(HuL~YWspyqzw z=aGI2l*7!~mVav17A`?1i9o4_M6A8Mi^mRIM#O}^tM{MmYY?{Uoh1ULFwRps*4FnZ z^Psahy2XxR3KFeJ$H(Vec;e#-(h=G+)YyBjpZM;XTOv?O9zP}=E@v54Wt13RVzY`V zNc18dZ!T@(YrdFCN5Mp6qe*MWiZ0z3N(4&DquMO1x%*vQ%;Ig@1{0Q87*>)!Snqj0;O;sM5mFM*I0b3rD>lB4;7e#L@MbREROT<(YB;x*5?C_ zA~sFbYF8UC5hx|kudFNuEY;2x(lQ257MOyBMmpLWGWi#KYtnJ8X4w7*gYWaLgTo{O zrQ}&(|7IzTLSt{6K8J(}OhLjzI=n6SxZ4GNm3Mga8ODe?B~`QiWQjm2oCnc+pVTTA zhvWn`bXu^$6eMs~^K-r{;;TG!i96Cd87;w*BTe6g=S>pJVybBQY(5)t496KjRH*p;j!AhP3=sWg2XV=(XV1I?ZeBl zq$6#@MB&@OphXqy%aK4S9I5qFZp@>p&sn7)@{5-B2WtBBi+YRAxu0P_pj;m zurd}*K?0*4&3E5S6ai)zb@kdC7ED1RjI3IDI+h=(t?y*rnSZ>P5j|c_pRSsaKq-uN zbYo$QFcI_SqNxY(V8Rq6Fm};5mQ@plb@6&?TA?{6OhF=stcu#Vix=~C#S|oVla7+@_wjl|^;2%PeFzc!c?q>_a2tt0 zDU5cCvV72F;d7+7$-|UK#S|p42h$sti<3lNuc@Xp)%`;itKlPS>PdH@46eKWq(c6#nA!3Gcuy(G+d5J(NjHrsT zqESt?TGS1b*GD>O3R)^L*pE*=^ML1DQ;1_NC`wl%@)6PQ4?*x-@upG@69&b zf6=f;Q7W8>*fTk_cNTp{7PT^3ReGD4&m9MW1nNVY-gp_Csl#Z6!h|IyBppL2-#ebU zv{8=3IF1aoYH~&{b)!!x^NXq}5oih0igNevcfR4;c&2S@qhektNqc*XZp~MR;ThZOhKXn>8QWr6Tj=PKTY`Adx)_W1bq_f<$%FQK9-XzPR}Y(otxagV=vwRr{^?k_eP4N4@rc zPmsr^cN0Ur%UH4&*)UA`llc9lM|V_J?I@NMnXip6pfG&es;IZ%<#U{tb8#HC>Ffk& zdogQqAFW=oMP~u^tSyqf~ve z@ZW>`cpex1G{lTL;p(joBgHF^HqtBurEoStqw|i6rgiBq!tawC!xSV;q+`X0-CRu3 z&qE%)GFq$Nu(x>Ze^|va9HsgaajbA0Kk;dTZq@Q=^?NUq$hhOckU)J%E6UOzuldm` zVd7PV;}#r|G2cm~!!j|BKm2*3b?l00b$C{=unkP9_>(3>bBa4 z7cF;+FPmTT58~DyH<6jPPCNCYqCn#5T0d?GKf;Y}RXNgh!_n)J!r9zkiD(#waq{-XA)f409CUkH?Zlu*1w`hGUJ}8n9QWt$qB}o&aHJI_a!;Tr zzVNha-K)A}6Wl@gLQ9ZVloye{V#RHR6{$Q`Ln(|OGGUutSWKDIn8kQ)kqC?oNYk^Lp}EL2^r7nO z@kGNoi22IIp^nwX>oSWqG0KIRseUHVNkg4dqBs&|s1BFrE7=MNLl9v4(E zYP&R)LVYqZxvm9|D=lyg zM;$T|S#qR!^dm@p6gEj+NcJ8+@{u2UG)F22(uy)Wpq1G5%1XFqZ`E)v;zhNvxwxWT zo;8c3Zkq2>$@|$3R&NzDs2lb6nE8!QY&Vf(zDUzE&ViiF&b=L5Q~Do?Knsypl`YP0k(VrYX~KL%gLpXEeyRR99&WGlbh7a6qc7ZVh!00=Y0oGT zQ-}yA0(BrQ6H$I4;(YOG+8OtHCM3|3aB9u}&37Fa3==)PG%fnVLn9I>h5D!*F9XE7 z0voi}xnoqEc}G*3UQK<@+b5LaYe>icX5p(__=|agTeQ(pdsURed}X4jLpSlbw?$pN z_o#-%J*unw#w?y=YaOW$=_>%mcH602wT)G(FtiGvKQJdcq3N){IJM-Z$@=I^6-O@| zWm2ddzn_p4<#x@H;@=vPmdbOsshEO((kp28=5hgXxY#@{$aSJ~0%1usMJcq9=2uf|i+>$Vti|G`MjV%Lgu{`Vo>I+`YKxY& z)tIc24D&^+#?2VO$5uVduh-Y#eyn4@$;;wxOjE9#B?6^Fh|o)(@w4P9JK84ao@drZ zJqnQslp0M$RJBKZg|+?_pj&dd+P~U7PEDJ+wsSdZ~F?d~(2^CKt2E5F809-TF^P{VJ&z+z&zvV_ss77bve{z_3nVZy zAWieDypdX^_);t&FB2&BWBLGo?CDXyDDNsR6Vs+es&!k|)?Bm5>#67bo`2xHUOZ_69LX!&BY>Nr_-^5ZpaqS8|$Pzo(nlpdkJrd@r8i-%`ZG|U%A+=Tdz_v-=383ZNCrv(tVX9O=~8O%~E?TZzS#S=Q34O(H$lPKn%Tit?BT0e*sGWI@no4brj z1hyK|zle?1rn!aQ@05&E2GS8c^b0>|Kb-$f)Vh%)v3+eHiNJP7`j-xCPrHO=bXOxv z=`kv<&S#!~S~vbT;cV5%z1q4!iReZ|(3$rB@}58*v;bFrMGu6Ts&#N#@xbyr@U%E%+#~hwI>N?UOMg zH=}YCG4AEn+0d(ln9LHNYhH$>Shsod?R<8S;vS{VN^dk z@>ux1_w%_-#Fq{fONvMru`oeCyAB?j+suD{2+}i*te0UdAsu`?Mr-T z_T=ewwZzDQJWts~{`N>Oj;%JAEL?YfFJF`GPc2yWpp|x|&secC*EF>h5%EzU`Lx-7 zd`_e8-1Y4zK6z;`E_+GNVv|Jgg*mlJU9wF`pcMKTeR03s%(B>NDDxeDL`82{xV;6h zQZ67hO{0-w3dmm{qxlkJVBx(kPjE-em81o{%v zic;qNWy_W*T9Go{Lqn-Cq~m4G9)8CFdBaE5DNAcQYCCzB2c}@YUnjTZy&5O*77z8eYWk{Tb81buusTKqO1Y2@ zedhF(-rO{x-}+o@2F*o?;bQOjzk3_=T_mN??h|Qtzny;T^LF#kdHcMn zW|p(|IAfc%aU3m4Bz<=~rt^FYB6&Rh_K3gAxAl!89X_qhY?q;O>g|0ixGUwQ&+huu z><(#}SP*1pVpm!I-8n!aP)aVx!d_ zt)Wyf>CioKH+iB=6wSRjsn76HEMMqG6^R8zgr{iy*|+8#X+;@P!dK*BKh*UvW=jOt zF4AglidhZL3Xur(5~LL+y<3^&*6&Vg zx6TY^D21LO6Sv8#Ds$IreeAPUlnN)SUVeYW)62ByGVz4kV`GY|aP&SR5$K6X(^F9i zUlx0zkXT&U#sj6gkq$l9cBNP=69szMyI0;aNj$h#MML5!L}#QGWzME*hN|{X;(elr zK&fV=W7dTG{L_s^TqdqL_=>IG|7ew-z0r`sD2g=ob1KKo=kBH{eF_PbLVuMBeRTGU zHM+ID-O+&BQEDVv*xu?bpVDOTeAVHhM|~O38Jl>qwY)dhgzHUIt7-B7$^W zs`8xgy7%An2g|z9JaM{jfJC5_+~&Ft+g!G;n$p35DM+j!9X_|N@s4f(+sVo{7B1&n z?S+p-pwvPlrbHg+i>5XEujKtMme}*}_qGy&QgZ*$t@2M??outbn*mdh2qPUMK3n+C zXWjnOQKtBK*Ykaw7_bezNoxF@6Fh3jT;7&`H^_Lv%iq=4p6fc==boG3e!izfV4EZT zi?}emZQ}D=oee035$A8>x>h#nN2J++Qu=St(wxueJca*Fq&ie}&y&|*Dmj)mnCRcp z?w3{F*6dDLaMR0xDM;uZ5mKy`b%b>3R%K|;1_oTbeE7JHAS9{z3?m~x7AB#q(Ri`wHu zcOySn<}e@Kb_$ie#*}W%zUW4^eCRa|36%1ty87*7iqgNBk9xG5C#!e1w7?W3UXYH~ zO^@+S$Mln+-@PcslwJ4L<#}sL1WF~5h25T<=O(8GLbIolUaVkIjnSlQJY zrXYc_i|&x_(w)7H%q{jNZsVAO#0#=2y25LIqK)3qSA47}?zJewMzm(t2vr5vXp{il26t2$aHTM{hrNda)CI1B_u0 z%P~wr!jXExuAb+4@B~IW+%Jw$_higdlQ$2S2$aHTN8ghQob{Pf4U9Q_LYn9d5DXJ*grms+aD4&+E+nX=d{pG_(vovcQC%fduNNy#RB} zY;++n)A^Kwrov>^y#@#Qt7iT`t@`a5=rQz^N~eqUaHwLu-J*{~JSShOx52^>zwIW` zv`c7$i50(4i{%`+m7~;sB3wK3q{GmCEGX>#8=+JfT;Mp2COigNm6 zM>aXhiq+j0q#>b4iQoC6K3dBeYG&U}(@b%-B0Z2mDXbA%x74$`=I}m*8DBFM`vH~- z^-=W6=WIy4XV1QD?I2Lcoq|n%j)@OxOq7WqJ(KyM)y>3#d6n65lG4YCSQ;m=7MrD05i>R9JM%$*IjWFL=MC+~jmReKR(LeVqtx(OrTE_eyB3Gd%KVwD} ziWyNUh2Y;vCGo}kCXi#^L}*F0@m|D(R_B;~tv)gxZMz$|{4e(SyH z1ocO2BD`+h=2!FU^Q&6D%4su`I;gdVg)o#lNW{9umwCmu^Zp>7w9ihK&QM(WLx4&obI}FQ=W!H$c3blc{0- zd?p=7Q`5Mic?XWPqWtJuPGc9HM3*#ofl^p+ElJ<@;1hhy2Tv+_V0;_vcei>nBbcFA zBaOQ0ZLLi$gWt6B%-_RHV7^GpI@&PD@@?jQ6w3VU8qowBqhL$5|}w<5nvTY8z- zIiugmcDs{v@}um0EUHHriP%D4E%ko)i2B_w`rYdNBmQuxK8New-6uK5vy(b$M5shy zzDVmQ2sBQvOT=^{P--*ft6S2LERl(c1)3&Td{bH5xMz|?#1T=k(HUNUOaw<-QSO|) zX1Q|1n_X;POo}CFdn(a!51;etCG@Z1EuwB%=K2?B?uERiav*_GiS9nzded?*Vgx(A zDPFxqeOsRaxYG;(^PNCne%|@Nru_L47i>CH2#9CvJ9@*Q`3k&ZUIu34g6^kX{8-iTFY~_U(AWy(7Fi(lRk{>orUA+3GCIrHMcSrJj+FS3B?V zb*J^`^VM6fSq>2K=nn#=tZ0z7^n#o&DGLeoxnTIUZUO%_AI8UP+j7unm5tY8NENN@{H(|Lp$Z?Fo z6eOOK4n0yI`WdOOl{Xpg)9J9Qh7Oeol#(NLW`lf&uNDun(AG&{3KBRx-j&tE0Ym zsr314mSk^ zXl}3Nym8GCRy)Hi5h!(!;@HipFZq-W`sy~;Wu|WD6hj0^mxFBCjsF29dji10T(C=o8G;R*o+rz4onI$&2 zGKQ^=HDRkEEfWr>C$M^-i+O~6=%ecKJTB`af4-rYGy>rI07V&eWnZ#+dz!J_OZo~+ zLTOA}a|rQ1A$z5A#rrT?yfDS_91?9XMQO=UA{{Mf%y^vhTidIpYa zSR-_*%7gB#$I47?+qn(epTzHa!y2KTVXr5$E;|!VX=fw^4gDtJIR)7jf7tE^cx!8c%$#46V~e! z$frcLO=(8dfl^2-%8h-KMREF4)lu0f^@Bfa_kTJ(BQsK#tWGmlq>|^RI?;R4QR+n) zOGZ&-s8KF~*PN+aRkyLbC@|oG`rxW9!xU^y%!$6rT=Gh;Ol8pf2j+|AklWmTTU{}r zor`Gd(CVjO{q9BBKjam3`?u8=S#OM@MVUoLltO=%d+qdo4w`G($)d*iLlS{2gpj89 zKH+7!BgJ<2O%A*O)m4L)pSW$|U};Se>Zb3tWR>q*BiqduS(eqm)o_-F!uV$6{#1Yl-wR;&u=t5CgS74D;%X}Q9Ey<6;x5Qf=VXp z#rumTnRisb7*7q``RRy(e1O@)PyUFIbko^Xi6O$Kb_=cKzg4C6SGaZ$93qm3&Ji;^g7kVV}|or6G~yeG7bXd(6UxV&2VO4Zoq1jf)RTzQ7N>D<~mW5lCwBUQiZ25GGtN+C^W zSuCBCG&DNRSf2U^dfz;X21{MC__C6}oPm1{wt3=F;rl5Mnd-X^_@m& zkM22Wvu6G?9Z65Ohm`M zPY&3bW-LRN{i!3F#&dfb&ru)6_DjxoUUOC5;#863c8lvjDzX+-e+`+3KA%VF_@mu6n~Et&$R%$vbQ%vE-kbgC{zWP|wg;Ap*4AD*WGPhUo26EUJio%Z z2tK{g`>V?{s#D#$^+%ik&Xn?hd^BtTAk(anM z65|e@P^(NT$o?dL&)cwkKj)%`ArwLNUW<9*{6Qw@d!N|+UpX*RW9*Vg1D$AEa799a z8_kpdBz`|NB2D}59Ln=q6UT_7bCzj1SHo4Ta)gUMoM?D!J6>dToUEY~<|`AmZ)BLf z--n9!>2)LmSArs~D9tBCSlTWhEnGa-s<^TnON(nf>CHrk-ll-6L&S&4$5c$gHGY^A ztrs15$8@Djm>ALLlLak7TDGe9mMcb=Ou9`VD$R%~NT7u@;!Ho7`X#E7DBhwjL+xml zyyCaptFA_m*MaQbr5h@?2ksKVTBoo2Ij&f?9UI9G?~PS41&M*Q64>kFXFl=4c$&i% z%)V@-wdd@?bPpA!aF>WoEdG4i^6sFS71#2cFa?S6q+^2X7e2(fKj{eneAyV^AdEG- z^-S7*g8NEjqD=N>%bFY^toh}c8m1sIhjd)+^^p%$^|!U3b6zoiZa$dBd^)Y66xOs% zTx-6Z7q8!pwO>$0V7;Rh(!bXGj3^qL82h!Y0oUUPlO_6|!7$o0IF)|udlX0g+@q+k zblP8~Nm8emO%1rZ9tq6pmyV(%tdhd+`AS54%2(e%7)bjEk^U7Ed)tR6=#@zS(vd#h-SyPI z4hEFc>rLOCmydSm{Y`v+wl*=})0Pr}UWxQC9d;?N674fO8c=E}>CkuTaoVZ(H<9Ah z!#&US#u9;^i1aTVvkv!l4O`RFfKt(2^Zx8c}GVXq52N_Tb`^4Ww`-|n1N_VX-^(Z7TCz@Z; z&f+zdxK`zCKZdp&mUQ^JZ$hJe6E*3#UJF4~3yN|Ic1Z6cdw=h)Kmv23dm3ODHWFA1 zNYmG){o$J7ZWT4R|7eC%^~sXb<pnsAwji=D6DZsE&1=liN6fwhY?-O2iFh8DJRD0|i~QbnoH zi#u?)13UR$_rY8y3I#ct^c~WVX@@it7^9G;lUv66@-hb|v5bt88cIDR9Yyx<<||4} z<1#UJYNUFvYY^*Eew9RE#6g*MXzXI zkxZly>2ILj{VMJ5mk8W%g0!N{OBrlyKWXJg%MRI)Z}o@=WZ1(*nhM@sRLwH z<2R3af{|`>1q&5rqFtm~#^$;@LQq9qhp4q7LynM~m?}^m|f+8@y5p{Y2890j*g4 zVAXVEd094}hzj?v^M=ME9BG;GcN@u8S02Dum)@dbw8W@}G<{2b5x|aZ9Icipb4bOM z31o?WVr#{r6(tMltm0imS*`AU)pkw(k%&fb+wumEDLlfrK1Z7F;JN6 zPzPFtG~F5YwI18!?Z}o)j!*}ZCHm=fsdPGBU#f+|_jmAYyVkrN{jZ;lckAcLcqbYT zV6WqLs@GaCk_gNfY3k?iJF-&Ix3q|-`!q~JLXOmdhuv6)i>p|dwBDjnX+2$b@br`k zl2xCnul$blv?kSk0`n<9ST!tv@8Pkh{m*m9&e6GJs1I|ZTSJfZV`uWcP>))=nvlTK zO0-fuvm5I^JC8^_7-Pb`&=NUP|GW1eZTOHpYPE+W*!PskRR0gT`OI0Zx!vkHsb{>i zEuP=naHDHNYU_4+_*D8$t0sd~-gLkRQ__{m%3|2$pH zXcxdvZkVLr>2X*h6!HxHwCTol+O$L~9qA^Ja`jWxk4uLN)baK}ho2{Z8R-N}q^W@1snWxR|QJX2C9rKk(oO^}xu=wqTwFP;)3M4*}j)aNN`J655xuj3ICc=e=@y@>Z4t`((x ztNr-SUyqOENITL0J|}W&mX%@TR~co-u%wrxw8K`aM4%3&X>Z2)evEa0ss1}Thp{7B zHEVDVtweH9Nryas93rdwS(Ouxd1_l)llGpkb80zu_TXrVtYa?`V~B{emI;(X-E?xx zkYOyVBUg*~2Xah7OXLw}Oo$&F`sB6x^}qlPQ^rx5GU%Dy|9m|uCmIbZ^k?neFKOXD z+o&itfXYJR?(NuxiAt1jvo_=(9er5Mdw9hPIP{vtrrVEHBg&> ztEe>M;3$JM?X-9v$Q&(g)R>BC8tTA&aU`O(gNL1&z3qH8uu@HdBP2>8P4}^s4q`=> zAC@ee3(}~DV+rb}Q_>ptXU0dXwU`gPG>qXG+i~=v`|f7-Wj*pFs7V!~Rg}WfM;_Ij zXskV3ZKJmHb-Fa$#^{W?$xCQ7u*~&SgQMf5*jIwu{C7;mm`|%LXf!ybWU7UGw%1U~ zfm+bj5YMlaSiohXLCKM9&bs;9g5Awji~vYuJf?4VtsPnY3_G^}?hi=^#zE9a_x$|R zneB^mGre4ECq+?=K5~RxSSpC^KYG>FeAX!yqZ;;er0IO00j*fTKb5pw$t9#Hii8}m zJR1&T-oXphUAs4^7?+Sh-LxjvVHhh&&pG`YPSsEfV;9Cp8lz@+Vl!VA;@LwA2zAmt z4^HEt7mb_=b*Fjw(J0!NM$3TSvph--%eK_|Ida;NmmIFPQBD4uZo+7Qu>`ICc@89t z>QGeJw)aypmS8`}I7Z(fTRAf43_J1U{tqcKU{6Jw?%*LW30XH^9k;EShJ6tG9Y!TZ z=~b|yVa(D2{NoC7TRL=Px$6*^dts6*k?L=Cvqw zis-O0H~8iYHZ&ScZ*EZwq-R6X=yv05J2IAxyxwP!cL)han zLLyKK`y+iLpoq^W+geCcl2h?-)Aw{A}4>TAF)5iIAjdy!t&O zSCq1?>atHkoJSUJ$Z(WF!kw%daZd10+x64&Eze_2A6(o;#W-h)Kq)KoEB*ZTP@XF5hx{(YSZ#;<9?O>#9U7+hABuCBOUs^GE0BnEAwyh-fYO+Lt0JW zjVg}9DAk|J@wz}9e{*jpm7_=GH1+DZU~%GfsERs}z?|rG<5HE`w)#!Ptnn2j9hmPp z(oryc6JI}IH0hXaTbrH9@DM&B8PXFZO5xKatu|bLMxAybNL=dSBt2ClF_(0Nmfp=fiFncx(sUPJ6;_9IgwmZATd!M-;^Vss zBv5J^`R?!cGm28aR7G|<+*S-aRX|`05*E_2zy3acqlSL7b?3S})QWFkX{Ve!NCZmZ zC`$W;qo1j*zdC4MUHzqT5cSE#<+6iWg${f9Ny7;hdr{9gPd<{L;pq+IIQA8KpZG11 zweNC?&v43=2<+!bE6R)x6PQzIF4NZHfhxuij8{l2%KF0ktr4r$jgxE`N?}YKK^87- z@`(q|*Kc;XbEOLlo|&bVeLP>q=)9Pu`mM>O^$eKBk*1R)XJ@P90$f;^vNjBfDs5Zw zhO={N?Pty4NYhDE4?|duSADf~>nx7Me$rtRZKdT>{W#LJZfR$0(PMvM7XPT9WEGBT zNRyYO(k%SmX0`b@BS)$A`3?m zQ~$X49Hm}SIkNV>=j&^f;xcj1ses!0ST~kuR4#!8&P$M{ReHl)v+@J8)D!n`GUqql3&d9!zh0i?;U|(RS?&lA zC~e1)rajeh?byzmjk)b72Z03k38d-vp*jQDr^CCox49x!jI|M@qeFNcKeBl)$B0T+ z?HIs(dL7hCPaP}~I2s^LJN1~6`ERfm|Ms||qSO%5F|11p&mO;y%S7$ufz10{l;)7R zP9m_UB28zWi4cBrWt#T!<`9Nb*i&V~`Nw*-Wr~yOTG}Xvy|Wit_4NEbp1XG}N19e( zr!{5+muaSvhpI^g_F$yx9Iu)M=?;Y>s!zIy)X%YR%fx3QT2!dd{>gZ%Vt>Y-inOAH ztjwd{&Yr|x?20jA@5Ek&w4!``d{1qCwF^sayFtT#aG6TJi{53Gnc)6MAM7vsFyB5Y z>JsZ%i9ioWT2V?l7G!0-V$`+|nn~V{9*#6UtJNyVl46p0f$tp!dNukh(xjtCMYgcj z5iNROZGj$+;|J38zNFF^wsBPw|51I3hEnxcd-C)5_VG0j?YT@iXAWfCdAZj9+G>fw zQ4MK|K8atomX3|Y_J;2?lp3P8;E#<+5??1~&sX!DIi!An*jIWU z#CHq$Y^W$Tk2Mh6Diva%?K3odg0#z?;c;(5w&ht$Q$9vb@UUO>#!~U;n~CRnONt&} z*Q>+RjRFaj!gm~WBSMGCY*pqp9{nO+s`tX=SNAH#@h@*0{?X>f?`F2nyP=2U>zk?A z575I6M32Axg2!Ie?=sbia8K|39!0ZKQ40N4C1T~3^E~rt4kD7*lw==#SF46FlT=q| zJJuV`Wd1R;kFWjsxnd4RY$I4QM}<8BX>+CWl`JE!uw zxnsCY%qAUo;_7hsNLv#ULtr#On%+j;tE?LKP7=dATx^K;VtZg~D$1yDX66#uJN3iL z+(yh7cHMZZ_4= z<@6w;M~T-SGiH}-gi<&f+#%x4-Q3!Zsv$&Fm`W{}&)e7|c!CM7LQCXwR3pN{T-9`A zQxg+fg_a;qJMW2j+;+I>`rExmv+3xkq`$JvPQx7@}Dhm>{eo#(FHI_mp9`8Gn~KCv_hEetfPmm;Gub_96rW(2EDPE=y!p!Nxb`$oYdy} z`dz2H3ll>ZE=)$ko1_khp5gaPUA6eo@7g;~@`wKZ9uV;@%|;VnMslQo)o$z6#go3j zX_|~FNZcU$!xI~=SKmqhm7~!4k}f&R^foM}l#x9?^Y#O_bL@A^=>K-BKk(uuw-T}H z4>C! zuMDQ!tVhR7`skb2N^iFLQ;N1^+jAAaZDYQu@0X4=&qK~@NmZ; zI&`ZJtzEt6zS2=5W)X4z>KT6P3`;0waDzR3)!}U%>A#8Ax9wfK@P3k2 z*qS=A{>vl2_VdpFbnMLg#&!CI#y@-QgQeHGHv6unD|vgtWtn_o=_8g7^!w1XJ3RN~ z3)Bbox(dwykLx@SlSH7D7ZDz#Zu6(@^DCUScXRoNJnBH2D^L$%=_nh~? zIotK=st#3M-7`C*c|#@7?=EASUH$@rHRbo!$sWV)uhsHs^?0!vCeeTvF?{aK324!ljdEcRE$0tS8(;A9SadL(JR^({oAxHN@2ti z3F8Qk?d4%#V|eF0s|r?Oj5y*tNQBz+#=F)-L;9wqlD+Yt6@uYE})_&irl9sSU&EtVjG>n=ULL&Ty|7HM^7 zTC~LyByf(=8~6`=(DyvuRQ=q$oQecWiL-q+Wv`24N+>O?+omCbQiU^slivp2KCgGx++l5#drn@RvX7+Vxd|`(b+wSaVD^zuG*8sqCv=nr z0;N!2{s?9*9+xmIuCoTEW|2M%%0&(*CNhzzSnA`U%#!o@h#|p3@8X^uM>F55i2l(I zCp9i9E2-WC(|$4~bh}V5>dUvP(V|&)6|%J&<36L#if?RcugwfIBys;?>|N(Z%k9Eq z{uT(765C-UX5Js0)cII@4O)fz3KPdlFHCCV=OW}+NEdF$t3@5`>qY4WkBX%>+4oOm zV{Aq5%5S-IkeOr7=dl`;!W>1+OZw11OxN~d+P9@9XtAUwW#N9#6dP;BFsw)3ID1~lZ$R`ArQDSAWctGRSK8wGLGwxsjnHf9Q9$F=xHj74B3BOYAX$E zEUY*f=S3ZkHNs`7cy)dJNN)u*7VHJFY+*5FtAT1IHKZMFvdVA=-J5+Q+tI!h6GV?v^*R*O$ zW(mDCIb>D&)-_E&4kJ30!vz=}`Ooze>)k@>j}t zs@EsyA6D|I7el%bA#eP-z`+pju90YkTyGh}o|NmxkSKaqW!wtI&1WI8q-`63~BjfV!MEU8UpOgFQ7?VA0Om-O8> zMQ(RLR(F2Cm%ctp$&WX%d#mcOdUSm(YAtgqXTz4$+&z%Hnr#fMO>@_!g+YE0ZlRl! zx>Sccu;n6AuV|PYP^Ymz;&zBoFVZ6M>R^OA>XFJE|1r~{RVamRk|aO+|M>@d7hUu& zCmog`kwWe8_ub3dX`WN|x}->`Z0O~x4?TBMCsS(!`|M+$CnbioNEkiJ%5hp!nLWKV ze-TkNbuX)R-IO`fwQJ8rmQcg&k5gwO5mvEyQs0^G0?~?yg8Lt+FMkB>%H=q0xjjgO zR-rzTP!q%Dz;$U#tHUMqxX(bka68Tzwj~T+rPrYCxU)bD^Q{WqQa>Sbp^HGEKBVac zGMoNK)>_uBYPeQ7jY0xXrs&_xH4XC0xmG%V?MfX=q3t3uc5{ThqQnHD+X@6q{Z0D* zcWMyG404B%hHOo%SjCM>>gPUW4@SIIy3+MK%O|Y4$!$d;9jR@>s^kV`Gky zRXK4H^5~E{tig|Tfj}v=ke+9twYJ&&nTPJY`#TM@ZOp=PXPG~*M!nx{pBvXtgSI0r z5&>r;WUIHcm4nX5bk5YH@2`Jjn;QI5kQS{vxiUh%xNs9289tXGfl{cCe3rg&bni(! zW`1d~4oi@TqrO_@Qj(j#u1qn}!7E(O2${_+D-_csfl|05qbHXuN64MmpJjV;qjhzu z9R=sDD1|ib)rN)3QJ+ot<#3_GJN#OE(~drFh;mVW1JkULp(I!Xss=Mqa?4Q z_7cvGv3>bt-tm@ylI7{H8mt#-kyu$STxM=&e55)3o0N3?iY?7geC^H9!opUaI?e4e z_qz#JA&n(gcs}4?Qm+AW9)6#tCt(mOwS-4I683|7HJvAtW`%jS= zY-NzU{yS1xSbUrA7S((5a~U2mBSNTGwCco6gWN57DvOWo?}T;X3B5=d=atF4IS$R! zJp`*zA6h6$dtZmknMI58Z^QPbp%m6D5_b;{mRBuWtIzn!`CMv8M8gMcM9l+iCS6y5 z^@M4wC9@a0j;z@17p#|Q8uf0`p7afc{b#in>*ni_K&ir~&NI?mCD!ilroj?Cr!Krp zwI08*wZ~|!1}#BaBrG3>$;+m@Dcvtvb0km-Eu{B4{}mx89IDTJsy}35)Y>kg*V*8X zsmwsvb>utr_2h$pv^+jwsC;d}c4gJ>w;Tzq_Zjt7cXo!|^Hr#?nphg-$RquAn*(Pu zyt{z3NEpZbY3eHbglqIB1hV9|=Uo*T zzE)t>iYWlT);9U~bSBOw2R_K$s?}IjFKGjtxK9dbyyid4ygS}4wX`uBZ zxArMz!66GhuKJkC;M$(wyAkg$+L!Zj6;3~Jzg+mtGGOJwM2iKU8q88Ln=DW3O2IQ4 z`8p~-uWcXlwWkKpckrah=(PoB@A-t>Wqk|ncfDo>l@#2g`-iRzo*Y0rpJ>|Vjh(H# zp9aVF3C-6g4!78Wp^V|!&{x^br^;4$2kO@NI&&;}L&WMEX)Lw+K_-sJeIni#EyufA zm*MDl7;%0P%_kJ)+i&k8|F}y;jbi0^AQ324p5nRlRa5>Zc|8+}Q$!59(UF^-P!x=6 zdLoXGGv{mX%_@9nR9@8RPEx}u{WO>-%qC)cOEaFku_eQ`B)_jhZeMI&I?O|(kW@jI zx`(cVz8B>!M*UQ#R-%hc-N=I9n^Ma;wd1mryI%9{M_b%A z;;Dfj5mj$RGp8-ar@Su^;jy~5{!7bu49|CP3`!GWn6ZJiT(pIVv72+1pr{u5r&YpK z96|5BL)d@`msqoIj18viM$L|~ge|E=^uCd+{rP@|&dS@M;>l}sVFs;bmZ*($s!E1LYI*w;M*{s3X}bTR z-q#*&K3ug9$r8MF8|hd+uq?miwUCKKN_wEK{nOFvrBqcQ&})&Fq-v?Tido+&YHpSv zN2$Z4qn@P&A2uOJY`u(B-At|>E-=#Z4F z)wu?i<3s4=>Gs-m1$)!uvq3He%iYwe682 zG7=cokfxJ~%v{ByO&9gVwQ4d-S&@#nCyI03&r(bzp6|@n9t(F;SJY`P5Ew;~rtI}X zu5xm5Lv`bjb}~veB^~D1f3cNAUnwF{V@IwwV^?`KXkZV4z^IKhy*uGbuF|OCM}F#o zkBm}nNXIcvHuK6nr-($wExB6rYDc-#vC#s7c>>b(f6mM8Qsz5vXg zO)o3=Xw^$bsRpFup6zzF>S(Sa67^{At~^vvKEKITAaD&wT9PiF&s9=Nw2{A`ZY85s zCDL)*FPS&R` zYzb*P>r---`x_(Vy&X?8lu9NYHV+oFBN35IBq&mADN@T6sW}q%lv5Sl6GWQcbxb7E=usxCHeKYzYt;k-b3>%*xxQVw%Gq!yd48SdDoTZrj!9Lw(O39( zGLbN$+~?(@nsSU|CxO6R6lr?X6y;a?edXoBLwl$wHIj6!r*A==IG)Hvq6Fn|tKOK% zA6)wj1nxhOrtfWU$yL5pJ*w9q8?B-g=C~qp?P{*J&(VeY?{_8%1m?I%=Vkh;W&IoW z){O?FU<}7tE3O~L)2Nr8Lk`6Ems2nk#*DSFj+08c$=iV8tTesbXWOOR+hdN{MWvWx8v{77fv zb=TWPS2 zB}jCdTOf0Q*@5r+ffnd-0vi8QjR zQV(;!`mym@PB*e@`Tij)?`f_efl}gbqCRJ06QcEZ@6zmP@?f9$T^QK;{)mQyXt5|}B zxP$D`X%g>OvX<&lR93MB32|RL_=&BW*7XQ)>u#fB2@=Do9qZq|W*0sjq;_z!>e}@4 z+;W1uK%kVkKQBjCEoncEht?UVVhIu$gXvusWL3tSf7q5iIu%Qh7(`YrO~_=y{~FK2 zU3)m|>+PPVd-o<(AW%w-?Fx$iLR@Q|JSOpm){b&jo5m`ZATgI_NkPUzc?tE^;7n`z z`h`mzOOV(??KoHOAC~PFP3>@xdCzCgagmQbe=HCvC1x^HJ5S>6yN;HBR*d0Tf&{LK zlGL15gY?xkhS}1Cwh5kP^u!WeKQix`Q((!tS~XmUbf#kStM|cLONeZe2Y%@ zGkrQ~P|A^Xoc5tNA>6*K6ee0!i?ENXE)uvpBb~3KcB2q`ucmGql=37UL0&J|$rWpq z!o;oQrFP25P6B~h2GaRD7Ju51kovT}2Bo@?j>`X@V)g6BD20iM6U`FuhjkE$wnWUn zvV)y0dqzPzUx)Ag(+PujbP)*5;gJ4qRryl(nK_;slrlH=?yf~lUTVb(6YfEGT0Qmc zBoM!7UOnr%fR*3Wf+3x+BSBec|8PrJfxyUsbUyL%-4^@Uy7WIUs<$BXK26sdEh5?a znnA2E!Hc=us~MgGae#=6F>~1ZJF^+m`8xc|UbK7cBN73khyo15BCEaIs_sX)^4`sX^k;azpn3hw;m#pHi_D(6W@=Wmtx ziiQCU39O0!^}E0zTN_5|n%A4F%pu|cJu}m&&Ib0AY+n>#me)Fx@W*Q4o)jVPpSy|q zw+LoPpe0C4(veT$a{Bc0?AK!Yw+86IUO+m3%)gXAY_~%0u31XNq`%7Zh5oUEC1N{_ ztF!jWze(FVcxo0CVRN+mnq zKgnr=M)T(w6zCI)CiMd4ht<7#iH=J-wif#b+eCN!?iu9Xe&3Z7oj;~IQ(sNWxy4Ri z&SdEGm&sS`pS@*M&Sa9;j*6Qq8_wn`hnlzLNT5_E5e?VT(*gzIKcaOW zL{xCP&Z;GyVi@hPP4tGQjRx7iPo(x(wQdXvtQToX8scM+8(*2H+kGHPiv(JTv?MKG z+*`exXew8TE~fV;tA>2q$!fIWtS4Qk9oxa`)juX!NN;bYrzY*Euh2Pvm`3jv{2zgq zh$~L`n^3u8|D(DOrCM{W7gqqJ^XHZ8xeiG=Ns*deT-h^Cg{VJD4$3k@Fd~V zu-+P@j&Wc1v7bMWGNcO=y#rkmGc(-<0;SNxd>!3A%h`8t-cf@s$JQb(Ntbj6dDG`A zIv2NjERw9+F=rktK4ue}PS>V;=Xb~_~R-^&mC$=4pg(r>vljU$0l z4n*Wkk6;zEjPIJfw89`?dp=w@b^g9oV-(#uVIDhmeVw3BByyq*a@0s`-OficL)&o- zP#^v0$Bw@2Xj4yDZOweacBDnZxEd6__{M&~I8O~)g&C5V$s9arkXIzv)2-Q`uAHED zOsqYfncNH(aw@SMw<+#sTaMD&48NwFBBEK&RQ6_M5JOrdj8<*vYLaxOb#KjVBJ|Cc zur5x|@5;5SpL4I^LO>xxv2?RPY>Wq6q?lQrHW5hW&PCqT(3(uJcU~or_N!T_qxptysj;hgW8)G-}rR zg)B(URnF6OWQo=6?;$7X^n7oOLGBYfjF~Ll*A@ws68D2AUj)mcFa7m14w&iDDzpUk z(Yuf+ihe6+quV_{N>_!f@*6*&?fO!lAuSTmA`NnV|9=(hjst{tAT1Kc$Y6FQ$NsWk z7mZ9he$xB%=tH+kJGy@6yPLIXb5JR~6K=C_m3`0k-2?)q#FiU%bZ(Yz?{mDn#*ON2 zT4O7_HFbxA`b6SxbAw#&Zj>%Iqm2#;l)|3QpSuA$Jrk~7=%Mi@9Zr`nvKsTpDLv`B ztn+2o`q2D8P7OS77-avA>00-oOf3?4w(y$9JUKI&oeP;tW8NT@#yow#w#x1nI+Vhe zi$vNKgX~ga2J86ids-*5r1IyTY+3py1*MSA_u54{EtBT-=$3+GfV4wPwm)Xwv{a&6i4k?@@lH=*{h3gYeI89){C@Ays8{7o9vI$MJ+2W5GaLh zGCrptCYN|pl_jgq^#iHpHhZtJ1y+8_C$i*-{Y}=lZWrYRU6eS<@j+YOmYj7?hEfTeyrpl39it4^gE_$3-*gx0{^sV0x!SeO(YjkhuPu193q($OV zOM|>1G(~&NI!>c zi}oolbiJ*y#J7!3DSV!&9$ake5ERop1#L%KJb|2MZIE~5#HVFV+^$0cM-baYcNCu* zWb>3OO7{0!LOT+vwO@9Y=WQHJn5e_pj@ypY?Q4wm(xC0w3x$d2^Zo2L#&pr3RValP z(*A=o8M}uOtX64*4(r7pMGNz1;*G1-lj<$+t*K5uYS?bhe=ac3TMY_Mol##t;pjIf zVPk1ejTI5Lt;+G(i=`RTB9XK37W*Dd{~MitjNXAYoZZeW&zl8Q&LeIfE6)!&n={d> zgnkC~^VNH)QOA}rBv8t@UKLoFAK~2NXExa#S-rVuU#JrQc0s^Hv5m9jNM{kZKtFGNlQKI%&VP{E4?!qd3 z&x)}O^@)U@bd0^yi}(L=Hm|P=EJ52*U;f85d)KI=;A~MmBa5Tn&7Pg3 zEp~25o+SlRXrX9TWSl`xIJ-t!+rOu9s)FY*cy^L+)xTwnBu51F)8IJAQUBQ9tIW52 zs>`rV`NXJuJMGJD?4m*K&578$zX~t%`JX>dQjO8aWkzh`+E6b+2S$c7L@QOz_~#*) zC{jlU(p|zzlXMmRBIF5=cD4;YFR``pGCk#==ro_+5PD^@{{MKd+R$dU31>gLXmDNn zK=r;)J;|0d?jx+!`R%ZN!xA5F8>PXuD4U3hF)!I8KJbqf$JmappHmzzyZ6*!jysx& zf*su)V>^n4u~rYAXeJtovEhM9dn|fs9H^vVua7%yOZt6E!zgzD)B4}U0q5!V*&94G zD1|%vf9d>c-k>;^am)CRDx;3cTPE5`#XK}9g{MPTjVE3|QrYdr=YA6_=iN=(d)r2X zGXqcVUK260o+*DiPbH#8c?)G}FM~Qba;XkywVUlKcI{&|Ui*V5`-`qSkq;hz8c0My zaSLr=(+G9?f)6^JKS*Fr^qhV*3+20Wh{mZTDOERG~HtCZacs+@ zR7E6S(cE26-b7v{5V#*iT9Q7uuux8zImj!%+RG?4igZ-`7|k|Je65H?#~0>WmAr{J zq_30Ed@VQ^!LtRV=?h>DEtHz3Uh=td7BWf=A{`lZqu4;_icBOryf@e0BX64BvbaFt zT7oovW2BaavbRrw95ep39;N;^_ElH}8xvy3M51Y~xwbEP(}{}*1OnG3r0Gi=l`RzB zAXE+s>ZeC3SJLslbO;-h)QgFPOEC+rKY3H@RgDD#*FmJo2TLDG%S|@OU(d)ol-l}k z1uJ!S66=r~$V4J>P6w?wopknGpROQ*r-Mk-KPSH~QA~!0%XOcX<0#dL+Ht027`wcA zArpzLDi+!=<#tRvUYMta6=WPOsKDTS^66Ew?lMh_CI}e`q9EdyNbLi-ONECFc(3Z{!RYS zTzNRKx;#3^Q$?xojaRX+mA0}sq3KK{rrBF)FOWA`ntBNYW;ICDcbD#(D;wkP=@+^C zt0Fj%RYanmBziWv=;GP3%`oCJYO?-TjZtClh?|RJ7Q|PUW#=Jd- z^7gfKZQP6OqrC_{g_Qm^+2*;YYCWmCjM+94SQE|N7By0Q8aGwf1?vO?^Jt{$9(|_~ ze4vY^dZ}`I8Kue|Si??u72~G9@rp=fzAw*OTNPI)PVFxcm`5W`Umxo2#1G%d;wOd= zl~Jl9=~!IkGyCU@K@kb*LwOdSe1Pvg6etjwMZ|OItI;3*UqG~86+ZUUKQljNYj)3q~r4HuKIhe#>kkZRv;bia}Ti3kx_qS z$d|Iqvwe}L^=6F&1OoFce; zdG+DIJhr8S3C*iLy4|`}9ec`~-kQrOg_)j6RERd?w`_*WzJX8lDD`^(8g}~b47PD* zJth+Tb$O=R1;`maP74HPdPvhVEQ`!|1?xaLJ9C>JrT!t?ld`9<$|GHwNZ2^<*2TA< zB6r)($*GMSaFG>eIZce^kiUwX3qc)dtq zriV0rBRBAsu1CmJ`O=K49HlUC6Nw`W%y{jq6Xb>EmU5IzqTapIeme6w{SOlf`{)_W z_4zp2y7~@*z`PAPFYWbJ;3)!UNyO~HNXYXRGvIfg5R(=!+ z%-fKrcVGuB*7fypmW!5bq@omNVIr}1q?6`y{5}0y4}TT&D9m@9$wFhU^)KaG^c_Wg zC(Z7Wk@`T75EZ2`dl897ncXzK_bkzUr*n6d!dyg4I*fTxF6BY=Rg&eNnzV`S`1N5^ zRg{`bd&I6F6{Rq<5DBj< zj+&1lpLn_LJ}OFKp5RXHFy<&rC`X}P(c0RYr6udBp@Tc9D21!ONJPFo;i!)5plN1D$1W*v91X&s@CPR^#&l>cQGxQ2^F z+RpAt<@*}c+q0JHP|A(yf-}pdWTEl8A)Q~+oAK^yll|L=s7>P|^(ciWf+7)pvrit; zk_eQ-JV7M9>Ln+C)cdQ8&)*ZW3?#57dM8IfgnF#hBVEZ&woVxPFye@Dw?=;}HG@mC z&r&O4#laOoT%!_cRl7ke=Y3i^aeYN8ajiW?MBm@*Ij;IBC1wDzzufgXK@(Jy(lhkf z+Rx;*?!zkahFPXe?5jRqH*tgS1oc3<6a_~RrNl9}CE`P96V+s76Tv@lhKn9G+jRsV z_4y*ts6SN267+5KX1cfCh4RGpwe<(A0)=>m5l4)0m)^R_>Z8@VDwl19D2h_^s255< z-odhhGiWB(4J#&>TwP4|zS}||Pzs|qt!mlN*?}dF^0$huR4hS4jP1tz2H$Gzw|nX8 zq?tk5e{RlV=H}PfEV_=EZpuq7yT}Z5ZD{k8&3Ss0tTGZM(*CmlxXV+6{euM7lux*u zeN9-@&RHN(Y9{H(n6;6mH@xy&M~~8336`I`XmDnHCn>v8)p^;LpOy1;eK*OHubmU{ zn>gQfb>fM;T{SzXSJ56Iq%2JU0F#_oIf|adR!3+52-_W1ob~t;};bZOkJIXpBVkZ}O7i za`vc_yzhhM3<;DHNAM{RF>C^!)W(WjI6&{ZhVMUXJ{(0!IkgOWWOYnyyPO=4b zT`s;D|4Tm2aE?jRxy2Fkk+J&~w`Z3b5-5eSlHyhOiE65DrGEZ&2O)kSEfOvE805N@ z8nbWXpDGwXPzrlJe>}FVi%N{4Co_>isYTSL;$Tvke-oG5L}_MIiFPi% zC)aRZun^mnuVawq!UI>%d1|nKkSyKf(4_y8oNdUaOes9j*}wlnN(e{r*H| z*pc;{aGdY!Fm}^Mfj}v=Fu&zFTfGyTFZLH!16%@@y22H5?9S;D*5nf7JK<( zJKIjzJ@wPsn^Bwp*cDy85+VBx?EO)8q31j_7-djjVWP#5vq=>qTs7EQq_Iu;y&F)W zS3)R#Q|}yU|6aKdtC}*7ouO+_%_!DIH<@v|ULbq3i{Iw`9*@jP8Hw&sJT(`oq+4r0 zHlz{#LmlYbbR9RbAM@+l`8N^TtC)lPk&Xg^QZI@4={}Urx!>S7VP~>7>1_#jfj}uS zQX9wI5Vyk5?hCvULkHVw$`P?)**f-f>0$+G zkw|_^|C`v@*+~gZ)gpmX*l&`w;%m4(qe`mo#L)dZBv1QG&#%P+7s?>?l}qw8jukFe;c$J6T5bx_b1RwiasT7Em0?x}O2XLNr}O)B}a;|6=y zsiuNbHuU@1hR;~p=#<~Yfoic15#758vjpkFWBz$tk;D~$cM+`mbB+~^f4)`azIwM_ zx~-2uU@z1ntL|Li%QD)O{oPk7>`g+SDNX``QrHXmI!Zt5VRtIZMQC{qs@J_kasIZs zlQ8r1iD%Jit#)~O3Pf!p(guBHbz1*SLpq<>;%RRG@c1Bsz#c_9pLm#FG3jX4fq5R) zG^i+d{WnTDl^1v0Mju>p@@?XTmt8eg$r5Q!5q>DkTQSb|0=h8q?M|EIj0>5LNT5{V zc4WA|OlVZaJv|H8y%`Ma8(!Jl?P} z|KXF97i$Y>k)YmH&rH0Ucr3{~t*3iiuL7bf`c48XYd#iZ5b z53>XF*4n);b$C->e|D69H{DsA2R@zkdsQ1Wrb@E+z#e()d4behlKQZ$CYPGkWcTU1 zbDP?HUA=a{iOKi7*~QWmjm9;+fWX~0(s{F8UHYSK!Z>%26eO+??Hy{xKi?U|kk0oH z>p|U;GIw{&%K!@6fwm_Q{dSTyA6RqMZ>#)A4s!4g?yAAMuowOhqVY+Gb(Ccwfl|0P z%(rUvz-117yNd+Ql0q$)Lx-+STxQ={gX4_;QFsI!jgpe=U%KU;mlWg%m@^b!4UV~$ zaG2jzmzRYXWZRg97tTeCD)kZ*yn6_H1Kdqu)}P<<^CP7sN3sg{XSiQ3yjLr;>XF@t z30@kE9~gba^&|d9xZGk!8oN6@P1s@M4ifj#lH~l=SBa|>u0ESro#V{7os-IHHL1h1 z>rY|l=-TI4E&8^G@eNJcMg6q1gAMAQiPHr?z*&hj{mZn7pOW&_pl)27u0^R=RPWsP zwfUu8J();Yz4cW-E}5XNG;HKJm(UWGXs6>=yx*O5WYy6!e%iR>lhs-+#|!O10&6lp z&)};B?ekF`T|RM~qgd|&(vjme%b+@|58uHv=ppD0&Ajo<6iYuc62DNj-B6MokcOD;4BpD zT~0dc`4{8KHLj74VGaDWZ_ig%e^%=%ScL@EMDIhs;H$W=O6A!D$Evu)#(JYk$DqES zSn#{sq$8x6pSE-0BVNVJPp}FJtci4F`YJm=bmG0TLsi_lW4#MV$L=o=+1d5RbB0Q- z{ImypE#}@UCka*|fi+3e(zCwGUV1_=m1aDiUtqoSNk>iX1$yS|0qLmG+E3fk?-A?i z8zESQ1lB}fT_7D<^QzN5gYZ0};9LajT|_!YCo(p*!(GzRz}`=LV&ZgNBzZ2@g#@0R z(48OZt6heT`cLGC7}c=erKE$s-^p5bx*wz3i*BborzY zCO^bziS@>i4u^BL#zu4tcl)Le8X3najKTwmi!RoIo7+8 zbez4pfF;HrBOP~b{j`sGSvi>e5bHt$Ym%hYyS_@%%Fc2G`5~?oSnnRv;U7$Im6)GI zIznvxw5MZQ%KgX>u`VRACVCeu#jAk%{pDTchq%MWdecaUI${iy<{RJd)7#olTeNyt z`8D|=)`bMtM3MT9ukvo-Sh+L#;a>9df}K0odzy4OtAknfs>?~oL5hhLz5HZv@`-|J`62H0vECb`V|o9+YHPL&7FOE{G z(UYy#jiUV1fr)|ip$sc{S>yA&Bzqc4K5GaMG zM)cO~a(>FYB@^TX@?0!I!sK%*J6C2Td*@^PB3tWMzS>Q*M#)*^RY;%|p1jaK`f7g0 zl~Zm)o{J?&lqVezq^XR5Fn&RD!y{j9Sp8n|J@P6fPztj%NorBsPtksJlS9aJu>^^l zq+_VvTvl!99@6nW%U3(J^ItNpY65{$V%E2=p`Q}ky0QGLlCz8@NHioJY3*0CBHO2s zj#pQGweQYXm5Y&AA%Rl3^QI?doBAp1Iuw@!$#by;iRPrEs_RyEVO0~-G3uhPwtL_s zeGT#|Bv1a;qy@Kd_2O4Yw4&&3iX>`BLul!I*RlNWR{;d0(ryS>+9y$^X65-25} z0hqS-QxZOO(sw1##S$bmq+@T@4A$=O9?}tU&Q~k@J<|0huR;Q)@a#mAwvmqLb?Mqf z`Y$h*AYr`LU%A7=7H%aSL8Rjn<)QP)5C0?zr0@iR<}T?tN4aiHrEnQbuwDn!@y`2S z)_2ww(os9pSDVvfJl{Zmhy+TBClg~^`6&k|bA3&Ih$Tq0Bpux>itrNkYtWbvz2K|8 zLRlrPY65{$xC5YeH1jjAoO~SlA(kM~m~>R^REqchI)rrGy-YeNtBfQ+L;|I7Pendx z>!(bl%vDc*h$TqWCLQjv<@mT$Ye~oRo4(pi$|}9d50OAAaj!PHuAfqjGS^`8Lo7j} z66yGMwhF&m>IUiXf8eW?s&`eh$q$i0DcntxRWlCmo*eeYNC&>L&6- zBv48`HE=BLr}UuAbuIZJmLP$9Dw-v^zQ$Ee)si3L&I@UgIM~TgbszFj@3q-g7j&O7 z?TdbF*==yKr2?k-(bhp71XE9+Ia<{uLh0F|$AdYa*+NI77tGKZtf@ z)!_M)+3s4q8PaqbMOK~P&_mV*Nh)SYNT6;>T1h%wk}Aqutct3bw;_QwNzxi3bVRKG zgJ?olJ>9jO-M)N^AuUN)w$0(LQVsbOcUCd~L;`iwld`0v?`lQA^Hft6vtlH$CP|7U zB8rF;e-JgvD$~kIZ2Qbx3~74LHd$5VpEde_&x}+T(X1}mXCQ&PX;(x#JZ)a<($~1C zxaU9uYohN*9c-rBHNUJgZQ52KYSHXlc=rlBIp_{Un!MK3N}cdDRyp~^L&d!l5~!Q9 zzFW1_u$Ea$`Zd}cP&*3teKn}%8NXgJyPtO$(vq~8T7Gns3s>%pS8)%B1lA-;b6XxKh zyX&cy=CoDqf~Rsk9YO+YqPHO$H0sXIw(7A8y#>OLW@6R>Yd-AqEQU1wL!nu9H9NyY zEn6i=IN3r1bxTrJt)sg8h@BeLZJctO`l{gUZ7S(#`oo$JHT7ahlh-z|Q6~&@RlTpS z&|(Zn0&AlG0+`lQcNp5KaD&+Nme2SP8@e8jn)NYVu0utQpdh zGSk-(bh8`4A^C*sy0#1^t@n}0=K zw+vU1mZVU!DxT);tqS#I%q);V-I5eVI(D*8JmX|_8S@<^uqH{GNW?KBuKhtAB&*VL zO?bCM?G>cy%kMkq@LDu)(-!rWF>gZxb<@3V(vduIDnB*5t&G_u5?B+Ri+*pbRy^62 z|1@nV5Cgs)WHz8Z`}<1vj87vSF|p~qW8ECR<@ruBmLSoP+VQ_V=Qtux>a1k{!L0-W zrEtee&*_hCt-g6+B3JeNp+_AkwT7&+GYw~rH@_mQ9>=8fhCAEH<_jvySb_xZyy=~? zM3{zklRr**s7C^&@H~LduQHre&*<9ngrZRbfl^{-x$9FMb=5s5c~-k{J(eJW=NgjK z$j3$vSs}|i9Bl;xrNmrxS$sO*vTdaN@PfG>OOU|x8S;;R(&>J{XgS((w}J#piP`JE z3O9MpTQSOnbHjz1Xq@4WIpx({bI>d+64&}v}4`y=!Fx1u6? zZHuj@s_iUO^+{Y~8A}q0FuhiqyM0>lNA&4Awy)ZIwu$NyR6>u@atRSfmss+0HU5n4 zmy|B**phE~R!h!tz3W88!Zp>n&+$K3=Uuwis=sv^c4mP_#T@5Q?qN2_#@z`3+dHV%!H2<@w7xVt5lT#k+<8< zy3aR`yREnU*h#HPzE+S&Clayt*DjWuaOsbnI=6zodN8OZE4|J^#s0y5+eh^H$d7E< z$m_K8GVk47%^BX4H@R&m^e*OY$wZW8MY$zC-$LI@P5hVV()VkdJa<-63Uew>MCRnu zeAZ>-^P-*>3%F*8yE@O(LPaSY^UFjWR;qB{XFG|YZ&|1|OJ4A?C9ZOm!Wna)h~oEa z@Ik9%iP(O94!3Yiiu%asr+z_^6IrpIvJ(V zqjW^vu4~2@%w9vp;^t=RtwzPwu4fv`D24vmfrvM8Cj9FA;Y55eN#P6HMf12CzJk}H zpLZtW$Ko$6b(`^Y@N1(=YI4Ur+L*1~WsD!VCUzwvbJS5bq^<=K8@g9kW2cYO51Zj8 ztWh2$b?(JJ)_wF}3eu9~_jeIBe&|(wOh`Ln#c5B(_zmk=%Ti$q6IRZg(Vw`op{{(X zh^4T8v?Rjx%q%uK^uB^CktF$SnahvX9WKWl-6=%sDnyvXjbc?=w_>=iP=4iXqH0cd zm2Zz*!qK+}k|hP_4CujDmS9Z$LG3V^X3dYDH@;oWYTJ9>f71~4#ieAOc zc*}QM8A~uyi*Z*b9d?>wywBUAGL~SZ?nZsp`pQ#wzFtX+yA!K9^Kl>Q^S_HumQf1x zIg!{|)Crlez* z*DyAtWG~W@M9=XA?wTr>-f>HZQkYqa#Fj3_^f%qZ)uWm7b?8y(MWPReJ`Cjp$fLaf z@F?^Zq$TND*Q303%XsDAjL~`PdBL6>*LHE1c$_}R0|wCj+F5a0wEZhZgW5}mGVQ7< zOl(Ka@<_g`@kCkUV#SfbRTOE;mNrdiKQFe@Utcj*$TDzNwv4^X#{P4K&9V4FcgfO6 z*eKr@MX{=Z27y4S7DO2R!`a5@A6{vmDFNSBu@~+lfl^}2CmwZ6S>`vIE0yW}3E*o; z#O=Pp9yIyLl0)i{4*x~PwP!a@=2N{U3j|7`H`DVz+pZ`d98Yqd79jXJ5)G&w#vHC= zwlRnMX6}^oyy#^fB##sbl)@N8Pm8>7l+tlhd9}gz9zyg%!kTm#Gt2b6%<}t$hAHku z*!)4D6h=NtDq6E#inC&`&gE; zq(;J&bQrU6&%7-BzX+7VRf2Q`?oO_~a=2>Q>Xsf$kQhy4?s~WezaLPG{Jh1s;@Wx7 zN2sPDR|Ep3&>!jU>#8ftgb~5&X}fvCs)oetn5%g!XSckSQ)%BVIlyMJI_l_Dfj}wI z&yQM;NLuV`P#=9>pu-X*?vM`SdVV)=J-<@JCy#jW2Z2&z^vOQ6)?wzc2-U^(G{X`k z+EHH}x?Gb_TWEZ8`SbDO+7@FX)M+&y3Is}F_CZew&AXz6ehF5sYDaM_LE;Ft!??Q} zowvLDes_dpjOQeE;nbx9fl`iSN{)0d%%pd7~lv^cDV2>7R_Pn-2W{HFa zjmK3-GwylY_~hBwXT`M>iZoLL_h+>218E^4Ec-k7dj zdtnexSddsqI*hxbnt8jT)*+oW&DTy+HhvKaloIzi{v|tU4#ZgNYrhCnu>^_5q{FyZ zv&`G8dH)B2Qn-hs=a8E^Yl8c3(>F~YFYNA+SWY^O=S(FNFHv7@{SN}AaA!&PAnUc# zc;tT5|GGIy*mEKgM>>rA+JSld+CBe4pcL+R=^04LT2sD99eKuyj>1kDiSpzh=7CFD z>vBh^9cP~w*ETs^PYy_T6$q5VUAQE5HC$2ZmT;E$G-)jC&ym! zO_+^Rs)AW#a=2I#Jg|7pj#iG$=VgMV-=L4uJEDCznlT zJNB72UT$@JyKt6)LX*w4T2+$n(GM5D1hK z^W8SfuPBecPnF-UX|2Z+Byy-7#&f3Dbk0Pxq2`9f+ zI?lSrK2H_jT>tUf+_VLsi?e4Joteq}NluIDI^v#8yYB#=!L%P%VEM!7zta_VLT%}LT9A( z1jH%Flo9_2fl{~&m!x}hT~i*LEZ5I3KS|i1BVpXV7*A_2=AG6qJL{5ipNIv25GaMa zF!~2iQ;!rW;<>JW-w5H<014cM(Rt$Y@oMKG8~ETun{-PL-C`G_t$3v=lUaB2yO;oL zp0UG^9iiWERISW4`-{?es4kP$IWZIY>LH#wEI|UZWqNacQEzpAu~$6Qdy*arl=5tL zi=_^$$WzBXqTW3^C`|p<^#^O9doJiescU4_uePQ5kcY+1U=sIxPNtU|3zA~Jw>co=R zle=w5hkn{PHEV)i|FZuwJrXFjocis{x=qZy*(f5~obgc4Pdl#v)+k#bP^ug0hWsf>kKBgDkArCy)hQaH8>OL&R7jjuL?-NH~&?$C2Zhd#=Mx)|>jO{{NFmzf+)`?{$PA2R5hfyVbO8Hra!lshOAD3wV>pTu`;shROE*(!@s z>fxf6{6@dS9Ce`7H6qgbn((Y#VXGW-ZTUBIdqQf)V|jr2?R`z$Q+>Ibv!6Lt<+Y?^NTZv~zUi+t z^m(LdmMCM?!HGZ8=%q7yB+$>1rV(7)L><)ZlkV&cCmDSk39N}ypY{G~rwK>&?^62f z(TmUrgUQ-2N*FuX#gs-c(PXOH^NYLw)1{a+%tg?PuqMi{S`SpKUi+#qKkWx=L3M4d zHJ+8b5i58U(vp<9d!XvP>!m(c>cY|2&~J@M}OD$2QN-mdA!@k7OuV^_&nA`>tNa#b@rZ815aT9gV_ul#j zdPfy~8wu1+JIEV@)s`70+19I{ITGJ@-C*CIU17S|EQUUx_m5oFyiaV>^}YjA(C=zd zo2*Ay=2f@sW#}vPy@_hpeCFsd^pYC_j&jwM(xo@>zQ z;4L5B#COBg8$QoCmLP$r6qF%%sL0RE8K6o7zH*epc8J7;|3}wZ$48NDZFq1Ku zzF2_B07-WvK@%Xs-Q9x(2_z6$+!rUf2S^}9SeWWY7l*|I1X+Bs#a+I)W|({5=6?HM z|K^;h&Z$#gUDK7)Rhhan(1@DqZm@(2-lecuTuN-#FQ-;B=6x(-uolP7Ow^vWQ19k$ zG45OlHdu>$QQkqYSla3-`sPkM^p-{27%X9e_XF_%4-nBHnt@;~E@v~b^YI*glu=*z z+&|P{2@|{@fc-?{n!d7YIz4@nUIuG%y)qLeQ@bh$+a0zA&xkZw!UXRJV7_~AwU{>T zp3-OKc#UVpe9zPQzVr7L&-~h!F{lpulC!y5>H+0F)INho8NBZ2blDzGSq$2wANW*8 zJu-T*iC`^mHx^3`?-IsHB}y&k>SrQYi}wStpIB;z9;u91wG{(Qt(IG=naGD&WncDL zeKV=E!4f8TKLB^7pe8mSpGC`5w1L4|+~b&u=VMRnZuP2bg)BJ@*5Y1`*XkC_uqSi$ zi_xvLolRcrEMbCI-nez)uYr0U@77wg;@?dDF88%&;`7C>N~w~e+U(_9b(S!}D{qVC z0&?DGR)6iU4})~p;t{}1)IHZ#3F|XX>pZo%&JregKbdJ6+u&4GUBuQln6THU7EaTolJ^FrMEiq!J zX{_b()l57+)>Sb!w$&bN&ZMz~30~vk-^=}X>$$V3+K9@zG}hwr+)R8xK0YM)X!GZl z)>y&>uUN5L>+5QS*UYM|J5)krEnXX#3D*KGb&t#iw2m1YXe?oZSFD(2Jlbd5p4AY4 z|7l)r^9q~qjKhCSj&xN9o_VD9T+l<~wAco(Sg~I+V7Fef?M^lLeP@lec;;j#);*h} zuPHG{9o%Ao#u6rY#fpA!C+{Yq`t8$HgeyJa6@nv3%M(@e~SSIdW-(PvfZsj(K% zmif&eZi)G$t5RCYY20tqTw@6n{2mYcK1VVbNn`RFpRyIzSc_-gX5#Mt6dm7dFuv6) zrLlwwevgOmS)v59Uu|T(YnoMK2^0KQ4rjIxT+=fh!FRkPUZ|`!5GCk*UuPyFr$5)# zeVvS3O>3yE#q%qEV`i~zcrZ>m|1iP`-91ZT2@^b1bIketd(Cj8c}G)?lS(3lX*QD2CXW)UG%zNR*8;y_S$_z`1$Pz;q@)j$dPzt zU$cPO`*>d47h3fiY!yEDc8d0IuZbSMi$vP3i$RR|5@~#CmC3(Hxw9sMwRjHi@M_zl zCA0RA4BX74`9Ht#afg;}C(M1|1v(^^axYcN`$UncfFcUdYcQ+=L@LzOvsUO!- zuDgptdp4OR^iuMynv8DEOtZZ+x&$UO!CGwFLG;z#63e`6kjyLh^GLVgiU%TgYrKui z#zCY6ukl`SHN-@)7MH(+SZHaKQ0`UzWM22P4YutdZssh!J9o{-CW6a=X$P@?eGTt# z7tGP+oO7fd#NISzyTs>emWIf&aJI4vePCH(glULEfI zRDGTHlFDgSL%N@)ZWZt5ezcj1-0QvD)-5(;~8pFm~W*ZlgkB5uW>+P3&XnwFhMtdQK zC7-ZyUDELT+IH7Pw!inltF*{R|6GUl!<}1bti?3fd`GPA9yq8kUj13EgtTT3&Y;hm znpv<`b^IRr{-X#sQek7o?tI3p^?8l(m)SM$`cG z7kJsi;L-9Nv}Sp}5@QSR5&QSw6n~ccOQaPx5cf+Z>8Cd(+wyo0F<8>{x0|Br-+ziC z)r2sQwO&~&89P#Zl;4{Bn+Voo+c>Ac%-e9kTvo08YZZgF*v1)nm^%50_|kA6yjn16 zwXWAlR=wMGGgxwKRjSzedAAs|AVKs+teo>8thNspHD0&aqTUYkF%hiAwk?(+7rl&` zmv*Q{N)$6#i*2O9tJUSUiKbz(@M@CQSe-P=M|;q=l5roBmc64zwsfmavoJI9(7&;I zXVECFblOrn_kBF7y+KO*t}YNM_h-V!H>=fX>Q_+>0`ee<+-`>V9S7l|t9Y zYTTZ=1#^#q8>i6w3`RRoMLXxV%`KJNBW}Ss>}@Q{nbk-r{=n4ExkYh%v{+&aUexb& z>uz|>?Wl6g;WlAzgGGB~)RNp=8N(L%m|7IK6>bG6^CGpiZ*{ioH-p>^mT;Re*Tg;` zGS=O$KL){Vg0+~&o6)vajKgWmXlei2sB=ki8E{>|8^yfUj7>o~HTSW9>0BF_;QEGf zaAA2ps6>LYyFYHvqPYn7?dB4EWQ1vjU8d_CciPeT~m!cVXe2YcPiT! zajdmGh4iptDZQ?>v2k>AevPd&!6{iR4YKFf50-1L?G4Xnvcc(c{_t<|j`3=d0fV%X z!(DZjFu{4k$a!UycK5(|eTREqg*{;{rY)9^Xw=}uxkBCoLku; z_$&7K57y{;%Jj-rv`bg38!XB9&t`GwpUFabVg7zU&d?uPsm^acRZV%*&){#}Gw~Yb zQS6uTqUM3kh;EUKal-PnsS#KtuZdtS_SRw%9-3NB>0)%=_E2TtnaBkXj|NAH*HdLL zn)OIlEuzwN+lZsBOgU$QQ^Fl??<4e?bI+@r#&p$K!s&8E@L%LTvC6f{owSE{zo;x> zf}?=;@o}7Xwqa&{|C|+qJz*`T@lB`wXoDXM=<4NeI)A%Oej~^E#s3#5%{oC{L=X27 z$oZM23&ggkd-ZLr2Wd>O)(OzgTLo}>=l6BCz{ORx)%9x_l5l=QUqeLKOdlY&uODdo ze!s=CyTpFw;mRlK*tFdZ_JoPrpySJR7nS$-fmg%Ub@p4gV~kO>M0cG%VJ$xp0}gc- zEsQV_EwXC#mJlmbn*#;AwlEvaDa_S{Q4SnFM{u)a-U31P`ziq8HP3WLiKlhKy zIcF`-lf@Es#ZV_T$gQOqnBY9&{rTbrV%`1*#+K|w zP2Zq%-?K`D{vIaWe{&UlH;=_qG-9>roT;m}c={WaCA|?*uc=YO&Ck_-qmuLc!kF(C z2~j-91)A9B1*8)KUvfqm-=fgVS=N8(+TKz%Vx_fqV(}Pd%{{wHSe9pD>{g+tVZiJdjyKkw`EtI5tg6qx9a@~Am_y|}xvC)PMM zLqf!=F?qE|{hJv~uoi!n59g4tO;W3cRWW?pS2Fm%0VX=b#)t;1#pmvmVB<@k`|1g6 zPvgdi`GV78f>XkLw{TXGFnXjBTX&wy5>A&RVzDIeU#Wh(;iq^1IM@^`CO8Tf%b+>o zTAN=p>C=j2(Ag8#V%lQqd3T-da>zW@ef~&|Zz!0J@~ArgvbgL~%Eosc;0=~Xh}xpX zSS>JIQCPynAjC?1yez!GKf(WsrnCwX{mb>!!jGNPnP4sc@*nzz`%lG*l6#aC|M3Rj z?7+kVc-VQ!IgvTz9oQ(E`LTL3)XS(-HmkvDF~KR}9}4>psKM=f7~NO>s&dX*i}Qr@ zi6b(pzF+Gbw?-7!Sc^R|6P{=vM~gL5)0Zr&vnQ;@G)^>zmr!Oz9QL2}d!+sAd(Jxz zWCiZkbwIK9a@_T(w2@|p|%+*jQs>$}Tr$dN1)+s`J z^5nF_1Z(lv1#y$|zKyzPy>!~axq$}Xp}@p+c-SyaIz1%05p0w?bW44>H&x%9x3R%# zF~KR}#8&MdYX9*=jL`kFROyv7=d8tf!kMDo%hmM5LXDvF*;LkIPs~Iflt;pW@oL^Q zc?EmIT1;bYFusIxC*NC~&FHGh(ZG3cLLcNdUu0f=NxLk9Z%V)nxj={-{O5i36#6Wd zFd_TO(uE7?#|O#rBX`dbaj}0hZ8iEVCRmHVV2Bw&OPe^pp_+Cy#mA5m=gkgGG=Pm# zpY!Tt3Vc9$G)H;NOo{bxT@^Rpf^goUzyzm++FrMZI(W%2V|~>DI_I3VI8T_vovoqf zwTw0b%2m=?i#;(DL(pISUOa>P3imRygbDW0Vi_}Qfmrl(uX<|rAp88vdF#S^%=8NT z6xHuqdI-Kx0pBUYS}o7V0%~$eY%F4zFZCC?Sk_5nWZybCfrdTTbmWpj}OJSoh?%y{jLt5aZi8UB}C&} z7nooVaaUs@O&z9%Yx+%Zh5hAp>%qfDJ&NdW-^=eIHyk9rlkwsX6Z-EQs7LJe*fA|6-%*rUZ*cD;T1>49H}7-E6M$Jq=8} z#LBBvDYQXlD`J(uZ;0@EdRo}fFEYVe{4IZ+fqec{lsMf?3!a@zlU_OR=VZbi9%esP zQ1?5q0X9-H;Y?q_7TSxAF{axJnBbIfPs53>>h`OK?S1SRgLBSWoF|Lr?=hLwdZTjd zTe64S38z==iJAEG@+hr$w!BK%k?|@^m|zd_79e$$_UOYF;gJ%m{)(JCZxZ0!1Y^-2 z!+kU94=bET&Wp@lAihr?ryUxXUuS}~W+Nr%9ggUI#?DiMzRuMzTkx+#lE@W(k(}xE zE4JgNn;y|K442qBQ^4#$`U3npqAte%Amjb za0dCf{n=Yh)xEUN3#(}CJ8NA5F`{QC{bj-l5FN7gu)S`0TGb=^YixrFPRU{^cz>6u z7CcUyGe3{c5>A&Rg71-GpP|JKKlPsvgH5qwg7bv+Ao|@|lQXHVr8B7P32QNp{{qPU ztBN(XSg%Yf-#xGv2uh|}`EiOXH=b5Wzsv2!MZwK#tm&p&yqhm9%f@{_|f&MgziVPpH%R51YG z!oqn`tkt620yVAhO;fCx;FQq&_*B%xc7|&o1}{)p!s&7hVI#h{8r!#{_I&Ppoh3|g z+$@$IWk&CN|Eaw=yEf9`_^{Ubem1e$BSqwYEKl86`)i%jJZhZLa#n7Y3D)8~p#-gM zm80`h8=drCXZnTHCIk z8cUdv_Ij?lF8blStQO1llOt^ZtZSuR`<~Tcg0(mb$j9Q$%IDmnYM(8m4VEy$d9uIZ z)vmuOmvl6svh`TTn@YR3lj5tZJBi)a0Yi<79whc`xuX&*<5 zKk)mAViQIBt8(8bdj&uL85<7!U%{;iEMY=E7kv~Z!cUI`QFMl%ZGZg?TFu$*|A%mD z9fysRo|DDe!oxv)tLNt*2#*>Dyj5Ak>B@P@w$+ox{wR44pjIb8+hurUU31vR1Z$mv zjUxpoi!!eVfbbmS=N|-*Hq_5xu!M;}VdK+*D6ID7>77wk{cIKBQOo$QCW5uj!A9RV z6Yw9Cz91&g_w#?V`mpW7qez1#OvvXk?IJ{xdD2EvFF)H(c+_Ba`~M-FTGHF%C&I-r zZ6Jt8VfI)V8cLBRoUY7Mx5s0})oU_VySvz9Wo*GMN=&d8*9H7nKfuqwK0Jy?DYAqK zE`LW&oHcN~_pL{ztUs5U(-V%ggXlbDy!VNp2u_#nIf$`2b?+XXM%nKrbJhmd;z&D) ziaB)e01zzsnQ%thVj23$Cpn_wTRme^S8X!l9y4u*$S`Pw{f=DuTo%t0@q4D&*uJ&jTSFYDDo`Q$g};hKNGCQk;aHqZ?&BW{E1*KE?Gw{sh?+Z!W{R~R!*0_ z;z&D)-I+p?axZUVB3O&BEbnwc%)@iRzjugpsfQ8Wv8cPKA-b$7Ot4lkQj$cRotR*$nv5Ev$(q6v zCS*!OKkO9Wz8!>(rgswj$HJo$sJkp-LV6h7cbAx5RsQon;73ng9z8V^tkn)S`rp|p z_V+VDEY6rHbFPgDs9~^#iAAuHRqPP0;{}Mh*Ai@=Wkc0ww$UbnwK~8?x3}AbdvzT| zLWV?tv_S)H&|nD@9BI_uX9>1Iq+bhdoe9?Bs5{EMRCovPn}24vvKHrq(6fmtq#;_FU}X^4+}u7hW}0yt6msyNe5zJ0BbHPKcX zd8m*6iV4=Lg_K6VyC#lakn4{+UVi?YFcLJy=*bc$ro%>YHB}TICs$r)J|@^2BYh8) z2@|Z<5H>u@r3(GQaS-+9F840_EK)0ruWYb{iJ7n=iCcCeW=>tJ<{PSBJUQB6g0&jM zMlQcAqCny?*f7EySts~}s<%O~gbBHZlSEBB(VB&c04G4LwxkE7CkP{0WlxX17D}n{Z7fA!4>tYMesbe)SQtf zg0)&Br2^sU^uEvKS?77^eGa1c$uz&c#u6r^JxR>46LrK{!TJs(^P_p~4VEw=+yCBH7JXQx%*R4YRV!j;AXX-VwWPO_2(}Xsf>tMZVC3{o zJnYXBCb%>$mP=^0<>rhu8le=KU@fi-j(XL*wOi5()LkwEE1}q)xlhIVe*P`c zn&gUtB}~M^M*bYR^#}J?fv7_xCljnS4>n4j%B2@9vJ%8^G;*?piCwTUvPMoluJ;NM zm^1vRwll$63t&SMv+cwv)I?|9WeF4VuD#>Ca_HRxq*r79g+*5+=^UtHn(U=>2QS z^Cjw!x?3N!J|RvSfBf1hH(t5VU{p)0X9VE{QAD)-9QY-`n(KU zQ){fxnP9CH*myH4pT4JdR}lBHK5x3=u8_v?SSYAAcPQcv9z!>Gv1Z#0!_)< zh{Q<;e5~v{$BJnOabepU@5co~?1a;IrvI1N{eFAmtt5XdmosazJ#*d7J+P06O31E{ zPR=V{BDeB+AD&;}xoQJ9{X!XeW}9m}6RedJDM@0Uop43n^=OnqJCC}{5+aGjrdRW` z-9p_hkGjhQYf0OYTeIumX32bT-DL?AT$<*(%LHq2$vSG{fKeU1Q?V-Ii2huH&Klz& z7A)J~-4v@LCfEi?!9k>(XL$Lk!B&2p1rhcn!B!S?lK#Q-bS79U z2sQ?MvgrO%(I9eUOZ3NjP{n%CUV6Dcm@ihNe zF{#En5cx;_ch8a~Ot`{E)-7K|^PyWoB+;HF6RgGMgfH-8&$0??`b9*TB}{PHIBJOn zGl0*S0k9{WbEX}HFZ$iN=yzGd#Q)lOvvrO4HT1hI`I&H*KlZ7y?^6uB65(>+2T{yc z>w>8E`%GIN#HT~|b0Yaege@nYS7*Buc zhz7eolRskya1XsGOPG+SVI+ZDcR;MkwaVTnHb$Sw1Z&CjWiK+Oh>z`ufcWQWf~^cZ z8ity}1Z#DISEb@Ei&=$wfoL-mEehkg+;3+I6Zv3c!Cx1}@>TL?(mJS#ZIFIN)I=s& zs{?HKoj)hsXAT9?1N%Nhu(J?yzdRIe`oOZExxaT;Td(-@`5 z5^2LpxZwHd#T_Cn?Jf|9sFpCnT8&^M@B3}yx5FDiyxM)yHwE=JTcZpHOPI(C8J<~L#ZkBCJPA2BkaJTBGQp+ks3l{+eM}tHt)`W8%dukGL5#vXmZo@P z!oD;8zeN7ruM%Tc^ssU{vliQP*oelvqMO(YXMdUCl<+lnTH|C#-1Cf{CT83$B%Wiw zBcD&>`5B&vt(+=kh7Yth31OR?+bv?XjQ}nYsnesp~Z8=;XZQqx`9?jEMejmY`j-zi@20r zAmpm3EZU!36*0kD`Cy}0=uENwLrxHnu`2rY$Et`WOvvZGTc-spxtlS!@%VeN5wapc9E`dxGK{}q+t8wi zIN9Njh`4axwi?efd~b>)<8Pv8*bwqel#d!~Tpn0iXM(jFA|=0Jx5UKP@)o{4O`jdkN>*2R>Lq-}nF!Wu02`9{tFI&$-bG<`1y-4<P(5+*oqi0+LraRKT3U+iNdSc_wbF)C|}ZE?O*#)W|a8pmg6sVTyv%`MS&%sm_D z31P}j4Fj}xA4>iY;ndJJ*U8L#D>*%_4^wL8uL`SC5F8 zi??mTc&@nPqzG@6Vq1@T74+@6SXBNJaz5`%8SCJ{+{UPGAtr*gR)LTyT}Mh-6-CZU z3hzABI9YzD$~IU_maHw$QE|MntnGik2ou>YA;zAJxiuzOs~$XzK6FgP^?L~-HZ@F{ zu{KEwoD`w4gbDdvp!g}_5&jfJczC?{R=9!|Q9$`0!l~5^HV%zFEAF~q1@UA-3Dqa< z7|qtLlFAZJSC-RI{gepnAp4T#(+?<1UbR=2j*BpuU@eZc#d0^jMJeQ3O3U9Rz+edz z9BKSRdhG@!zD$Hsylaxe5#5FQ`n}&#k@|b8Ef&wGY)3_K8QEXOSE{PqDmBztZ`r9b z!CD+Qyiwflri{3nq*Ol_VQ*2+lKPo&#tmEB zMi?4u+>kaqMbJ@;Sb(~8vPYuuFuvR7<5~XR6TjnxY1J&g#eBvYZ7_x~!CEsx6MH{g*2`hk zVS=@MVI!bLg4pdY3G2=8{)O`HRQuE#sbx+x!I@qY>7N>GVx1#o~Dz-~(%%4_l!n5b*cu{wN+<~lCuBy`d zLrG&XMm8o`i|ygR0MA?aH}>nR#kReovV;j~Z{NNIk#$%a*hv4hg@0QRqkbY-%bbsh zKirgTSCd5fa}fqhnBZE8aS+7$lq69B1WTBZ&(0{|i@o0Vp1~*->Z$)sIJGz;j`Bz< zJHe;WvTD|!bL%A79%eGpb*-<<@6<Qj$a+I}zV$Zqg8>?^*%3rICb*g7|&z*0ti-J)W?^1WTA00Iwvm%1*$m zWaL9dJ~Sp+YY+(6OdEw??Mkq5;kaM&ZV-__5v=6_uOv~@PApzK-FFzYzad^MVS;05 z&xbE^t|8|-OPJtDWAAlaqO!pk-(CK@vd+1UM$PEkYpw9RR#Gg*vw@ogE-kKzeDqHf zW2+J})Cek$+*3)h7DoYl$Qu%s3S;8bcLRoKEMbB@#HPEw%CW5s%B98X4;#Q2$=;DK|>^l=|&tmbu6(&-#F35~onFY0Bt;ce4->sQw4iA^s zSt_pfY9_uc4-j47EfSd@$glNWZ1GHy>!>1FN3n#7hM;p+TO#tW?Eqr%+Uft9Co;iW z?_fg`-`7au4C?MR)ZNjjTP$JX69})2D@ET9Z9vS=dr2I5pQyww8LzQ~iAL~hkQyy& z|K1+NrXS-+Ym6UEuvQ3&s1qy1^fkdCPTdI;avk*q@nXWHMKQ#jI+H~S`qfiioOhfl zx=e7~FsdCm<^QhOIKywYr_R2!)(q6dlhI2>?dBoy>RXS!O7sz3t#u6r`!N$7#E5w^lvX*$> z4DgFV`rFDquUBJOtx8MUe^46L!y2!$iGxNunX{Ah?1W_oT%VvA+03k%H$2U86+uQaun^O(i9L& z0%8>nE4!If<5ZR~Q4BVc!`ct;3i_s$YUU?VYLA1dt z7}5Ho4YGuZ60jkOqILrL@IgK_;U9nPS2@@PQtnOl6)ER|( z8-==E(mA(bD9z!x4I|{y1Th@X4~Hxj&w9#y2#g=qFn(wlKbT-G&J(_^j`5>E#*fDs zKUl&9duXwIU!SOS0P!3IOPCk|uacHUiw-v@!K<<_w%RI(4Alk{->EafTIQV3!Olc> z>}4FqUIR;*;3!xu&D5$&xMin)9cw}+Sc@a#Xdf+h>t171D_B{JZE&9OrNXw)lslhd z^;Bc9u?zKQV!t)wUcqG|0nh7|O`_oY#Uedw$%Cew#gg!)$oZO}XCi!HWwjQ@5GGhF zBZvl7*9x}*OF*=LWS{999@qz9g0;Ri?;)yfTq_2SiUyI==9$=pox51<+%dsg+u&iL zN*l!<+?ZyuJjFi4!8J)r5ZVVzn2^tNc5M<9(@7gw8pMj1jl;F9A1bRq6HYCT0%jQ? zUV(UkH3&;MU5*0o9zeZXg_%;aZ@9*ubVpsvJ!7p%S-M8Enhn z$KZE-$E&)^-NO}_{Y)HR6R@_Xm);!o)axO{qyuSm)KCI}k z=h>+a!-}3IOx%TyEUov5N*A|-xQyEV4{Cc_v=1g&i{pkb*T0zKgS`^%KIRN8Vd5!l z$Vi_8ioW~9u=e zQZ3n{s?&(W1Z#2JES5jw+?3ZyU%rQA2@@Ozi{%ZqL6$HfJ=~w~q3C>7_M*wu2AN&>AzRma+mM|g5K}nRb6I0Lz7o!a(p$#&@S_@z! zw8JOSw3nPMEe?97jKhvvov5)IOPF{78&CIq6zPCZ` zyO`#qXjfyikn@MNEkBB|i!!dx<=6mYavg7PCGG`Q7i#@~%A*^xU;H{+5fDyG(?Zqf3&hE^)eTVdG`=7cuLBtXJ0CTW#6r zd#d%zjAh4$yIlhfFM=?AD4kBf?el1n1}Yjtc(fP+6fzy$Yv+7y8F-R9hNYW1~z_+%BY7f zUJe_#+CCHIKF6wOjKLZcthF09;t3)~fZjV#*Uhpn_4*?s&g=KtoW z296iS@w{umO21zwjTCc^Mfi`(_SWxAk+H~!{QmCE_pv?;GPJOAZrKKVXnxO`iaPrK zQD(hUw{fBhYG2|K7d`jmF`_b_xn=(ns{^+0!-kHW9DVPq4~U8Y!DsGR!URVe zEedOc?wB3d#Y~0?*5VjiEDe3CDzP8J4R4GF93L)^(Wvcnn`F_Gc8!NuaX6iD9;Xv7 z<%m<6V671#uDH4AF==J2-j=PZ)W-UM3r;66!CD+QjGWILrxW6E)_^5UNPC4nT=l|P zrB`#F6jqB&%c*s|-Be?OwK#4TOY8de{CvBGXbo_Jhb2sK+$@#?c)Nsm!ut6ELkyNM z!EwWvJTW?_{c!?`$5;dJN1sWh8h|0=CEnk zEPBeMMxqUB-}xXHJ+EgY(F)IbS7p{mZ3;xJX4Z=pj~j;@)jn3%nP9EYsEIBqne}`| zD-cn47bbo}-`*O1J4={o0vnR>v=fTfsMYkh)OlK8_; zbe@+X**-hQILHzvf?>nspsT)QjC{{|nNA2X!CGk$!+YCZ^?^s5fXMhVOnHUbG4_27 zmN3DQ#y@g#?)5I(cukypWrDRh>e$n#k(1-Y(VdQ3GWJAfJ!9JD@M=!<2BlBTWj+0b zJ{l9OCErIr80@0|o=ujZUb?DM9&LOtcIla5Esh&j6Tehd)}X~U#3?$KFu_qkEqQ%U z8NOz$ws-J{tN0) zsm>Ynn$d;CSVUn>XnMW!%R-_QexDqePVX360y!TvFM}0lwhf%wHdw+$7-&h1v=e!8 zLTCZzqJfx;GQnD*AUgh?P9IqD7uab0DolL9>=As;#utRVNd2h_C-5lUz7>f;wa$cGWKMWu_yBxdonCx zf}?=ijy;)`Ki&c`!CL0%ey>qgnTI_xoXEA?aJC61IEIck*s^Mtq~GwijJ4P+j)KK< z2dDHdpiYfN8>xdj+I;U@G40+b+hWwEGxuE!=4YX<&j=fJ@!t6w-Z>9X zUs7X&wQ9kumsdWE4Q0L~ANyK9QyyUT_#L~#EMbD9fEfVhiQ_R(#7>dH1Z#0b5UV|I zN>%JJ6up+DaBjDu_D!7hPWb)$)wTuCO)tL_DIYQ*A2D?1jtSP{D4@*o&g&^!6IzwV z5+*oL=&z!xsK=(%)=tC}*I2@Y^l(*?Pa<>8FNjqkoSDE$4y_H&OfbP(90i<>ic3_o zV#K+E5r-vAaQ<+15VO8cKW2R_VM0DTQBybZe_>oDtMNj7*gfBh;kX3J1< zAB21!jA!gjl$q&^Tx&A-EMbD5?wCOB@`lc^J=cdppPnB2-u zV+j-Q(>4&L??#In%jI`i*41yL7WuSWUp}LsiD0cyAUf<_B08;+-!G{?Wr1x^$(?F+ zOPt@OvSlqU8;j*^+Kk$*yREf1Yx1frVS*!#v*-KL>I)Yosn?$lG+6Q!o}@NhD1MI| zDIVc@bLcX$Xv`RRHDh%}<6XR$@%==9l?m43a>AL^l7Fk|TJ}-jkL+kFK_)nE=u3Q7 zsxEDMXdS)cOg1>>Uu)9Q0HmX`C)=jh!DT2E{BA*G3INtR9EB8Wmn;G+O5=Yp@pEFcZ@{4A6$Z-lsmf z=BBcQ3AT-!Xi#_Gq27Kj8f45xJ4oq&S$rNIE0U)+7l#*J6#*4uMI4?-k3BC6R*>)2 zX8%@H-TJ1u@zJY}iC`^$SB!6Lo!hIPKiS17lW~K}5+*jm#+D@)#nXTGz{abc&&B9f zC5*t~bxrTKS!*1;Z8G+X=u&?#h`+8aR6kystri;IUt~p&H3w+#j;&W&!o-?k^~L$N z7ewPMiLl{2(p_0Hc9_;A`+A)T)|vsY?$x{~JmZr=oOlxEKeEkG?Oy4fCW5uNH1W-v za>44Vk{6Yk+8Bc+OmNx2h7qI{KT|+^kt<4J3CD^fjWc)aBDI={d-eqsXs2*)nczJA z=ot#nOE~LR&&oE~E2eRRuGvt`*YOVsx6%HbRzCCwzxKE$ru>>Dn8rEeLye7@JrApK zWnQZ+VZv-fOX;jlXwgfb)aSO&T5Qiu6h+P{7 z`m1!E#B==KD=Cwnf0&#Byk3{aItHuM8(5{Xgo%8hB~ijo^msf!Y4m}?#@Bs&R3=#K z1!~EP#hLYH6J(z_sqJsd2YrZ94lS1n*189;z8=o38=pf#WUF6BQ$EhrL)Q6dEMejq zY^15+s#hF49K@}#&W64>w|b}5E0qb>YOU56aqV;HYu*h6;aXsq`o3zST76_^jU`Ov zLeAeE%BH(*?GNI&9?h)L!(-K`*r5g!to0cAkVJYrp;lh)i&$xhmCh0-z91j_?`GBi zT;2^f`fjaeynd5cyYS__iC`@*S&W>IXQ}O@GHb7nnai9BE=`N2obMCcKk4@9uEz#z zto0q9v~T93zh2YHRAaCwgL`;mme$gm-7BVXT1;^H<6jUhzo>h!HPf1Uu2EUS1ed0H zJm>gud9b&RR=ef(qlD{OTUuF*(=`)wN+&A;PX`&@+b8R+#a>ND3m$Sdi(dYXoRK}* zIZ)fQe~F&G%t)09)*1)mX^gA>wag$8qn8ZT!d87&{I&HuTW2k{hkw4HXBdW_Ap$)E z+hBrI!d!GtJuQ3luj;p@r*!s&(`DLXiLN_OKOExkUpacD)&^_K9E&fDc^*e>pN}>W zOSW7T)7*~Q#-XVtns*xOs3i0yuhExuKwrWHYw^FDv6K3>hh7HS=a=TtSTY#t zzFu-pG_3r>7698z$6gdUr@e)Z`eKgiVH>61elkd72@_A@VXa(OMVA!$-|)1piy85o z@2mN0mNXHpCI2&iZ_#z3Px}kRh2yW2medZ?rZsoB|C`(?VPXV4l)qoJ6B%2~@C}$d zR9jUvPUo~(>jS)c_xDv%qWoFd2xwKz7zdBmY`JeDSc_wb{{ocHr(MmzNWBtP+Z0_U zxNPvBxYop) z4|_66gS0!FGV3Q=>{3~a)7_80eZbPoqCuncD36oxLN(ujP3pQi*%T&N%WNZenlakk z0R#2-#g5z9cP7{#b_X{`X!jOI*@hiIE12MPnZ{dWzj4}-s4%7Isgml*n(aig@=4?> z8zwT3Y%dDnb5LH}@ZAGES6}u~xa5>0=ioY#nyu+|+uw2XO%f)iBPH)wAI11Zoj?S{ zMrxyquiTq|XpmqD6VpJ1=6xm>dvyjO-$$wQM|%$#)7bj=P<)#v(k4!RpD7;Vd0w%d z!a8BLa1HGvO5k+R03mxgNhEcQ@=oUxWFk^P++LC_(i~cBqOm9QK2lphZlr&+Vz>R+ z#(cfEs5$GjSUP{1U>dv52P3tWkz4(f{X7I~{Q( zw_vR^u#t4&xo8p_{S$HEFy^8guG#X<&SWC4ftZl~gZS#ZNH7f>)=1etY<{bjn+W&G zy@d72TX8wZbip*f#Fi#P>zwws_;u6>!CIeTBW6n)eO}arpNJ!Vk=nUYE5-c}8Es5t zM>!V`OshBV)K4&t?|2=G)V_&p`(|#cq%d(1v8v$rQOxy1-6b0TKKl#bI?Ff7R<6}W zf7Wt`R_wwLB5GRup9p(RynkkQ0VBl9T3#Sd{qt2cb@%^&i07VT67IeXHW3<#>w))0 z&+v+ZX-D1lQwJv;?GtQettKGiQ=f`_b3FbZqU594gv%*SO++gYEPRQSw1cSAar5pRL4j7*Dgq+25hGUS zZT%+delDZl#a9;{bm@xNn zOt6HB4e(0#sOhYW;MJ?CMXg=87c*uAH87Z9t)(DjuiXN@_P-OXW$vlJEf27wEOc2W zEMdYtelWojCg#8^IbI#WcxACHH3F?D3q_U*6Rb54gd7vEV@&*ag0;-!VCP$2R+NP* z%Y-FNm`7(OSi;0QcqL~8nJ^o`m!_gER+NP%%Y+Hm+66++I26n{{+(bgo}=K4C;9vM zqAaw=C=-@2!M%i;Uy~OUZ^O~6m*5dYvb<~SUZY!wmO*^$djx z*5cNMUA0@NC7;*%Z_9DQpCwFi&By;H?nD|RzAW_LUF(29OPFX0uY$gx6(^$PX^|DE ziJRw#`DfZ2qAU1B2^ohpH4&`EeHZ$~dcnyRetbKcBRVy4qP?6iqMYS(k%p<_ z%oF+jU6-N7jN#?Bs<*d!Yd;fCEsiw)Iax2*>ha?%&D+zr4)3;4ci);S@1%@<5N$|JhQx`YPBTO_l;EkTUFbOZYU^MA^@Ec2tq zC;608YS;;9OqgJM<`QHH6Hn2%OAq(JLwxb%#C1JKqfj-Dd^aCDn>V*|nZPi@lZSeP;Uh z2C?BMg05>JQYwEOr&L9{()ZHvJpj+EPdpZ%vkVb=3rrM6#Z|G-e(FBp z<#=OLhhQKtyjZ)^iOi#Q#9Ed{#L~83e}=#i28Vbx#5YJXz6Q; zf}|QnZip`aLw2{Mt0>c^l3o!}+#hm9+`rRQw1f@O<+OP4w!Wx< z-{<F62}B=bQw%n~L-K)lpWimiInA4Jn^5ee&O1t)igB*TC=qO?)bR5o149A5ctJD=Eox|Yl( z$ffqb#OK_jy?nDZG1bJfu-EY8Q&Hsba>2FIVPkcJkJZ=xQTBJPyRuEJsd`g%ud+rk z?I2F>{pP(Xxl1xfl*^+g?5!GfRys#I?s zn6?JT%79mLE>Z<^5srw17||<8a{ZpE+2-mj zVM5y5ck`?$yI0PA7Pc8{ynEkLf4(rz7Ku^jUd=zn$OqnnwV1|RndnHPOM!L%s|&PH zm|(5{&Bxr$!n*_J4$a`NOL2>SIcp13@8gZ%oxKwNefDvLQRYQEy;ilxI@i8Z=s))U zdR(-9+wG^mq|LTr#=I{<`p7NgRW5@fb6XGV`Xx{+ur7gIh5ED>E*0QpTC%j5|qXRo3DeIorekoeK^(;)Z5Y zdq&LHc^piG7FECBK`{XPl;&ARG3y}1hOctG8r9fD@R*n#bl}2W!t?no)I^spo%Pe%%$-aGYni>;Qs%Q7)vAVet@Q_$B}{Psa2G^HZ@tZVZ*AFB zPmLu^{0gtGMeP*7-m3+#>R<8IIzlM9I7b~bL%W&q5*7puEAHo>Q9A@*fG9(c$b0N;Bv7hg0;-GFi{>}-R)}=+Ew{a?_)XY=-)~g)5?h2 zCW5uNt)LBl_@t_hebndS?G2VNVQx{bUe&FGn{87KHPm1U6TD)zSbWBZYat<7)Wl{P zR4z3xbKal9UdHCm>fE-2wbxk}n+VqGZz}V?*+Vs3*BCW@_7K4mCOB^BccaH?o4)o_ z){XK|xlM5I!yZ~Jd3Qxvtv$)xJ2b_B(g;8qFJ#Gm-$69+&?VS5!cktCB z)iY{@_U(eNiQpMB&z$l8V}y@3daAc(+c3k%djPykVJ7N(SbU#O8>jXDyR6OxYw>;n zzLPpGvoFRd?LksmozvxA9L^I?q^zoAoj7v4QZs*~!D+D#-c2wQEMbCI;W#6Vad5}b zOnUq9`6|!bHH;bgHa`)$@IJyk_vwpq@UmF1w;k5lMDX0u3v|wLU&M4(L0>XrQ)hkY z=>A5Y1KU;BDg&)_4btdOs&y7-qCUpKGnHfXd`cd{1ka-l)-bx$Y)~S#uXwnW|q}^ zTlAZm<=fZPn9l0Bwu23itcy(qYjpq}-7k$kF=+&dR*t?ze_uL8VF?qFASw<0E>h++ z1hIYi2<=S35dBV!pSl8)F`HkC4t+}t*5X}Nys6&XME_!J*H;f2VDCkp?SShNM*-g) z*kRQt^xCC+B@HlGi*s%!qFdI~H$8r#ugKiVUSSS)JCZhS9&(2c0EMa5-5l z8_Rm@?azA~H>P?Tti@$xCc0np)f4LCABVMZqz0}>8b~3tWt7xhvOqlDH zC&u&YnL~}wk8-Q5#pPipo`?JDW4jDAZkCNzS;B<5wx2q3MGY!l)bP&ui^dWrxNTZ2 zCBII#`Sl3-K z^%-1`%|z$95!%?ZV@1-}oq{Dy@W_BOshDNF`Pxsk4)xGki(9anh;BDGsV~-?3$W(o zH8QU=c@2k&OrF-sp(D2oj5r#v;+Wu+&Fqve}eFF0>MC4%$BG`>%rrMt27_W}BVapz3C zYI4W(a{dcq;@nB10G_u5o)+VSJJ zJFe&Nd*CmL?3KMj_Dt(d^?qG@tAsMk$R?RhMYhar*|IYmZ}dK|Yb0bvgrvwPqY!0} z{LZVqAK!EN{nO+1=$z+0=iG7beZOA!bzceEEf0pvREs`csDU)n-^3x;O}l*YQ6KZ`f~xkEN; znIA{B%+W@({QuywxtAuKL4O}VNYcGDsyaR>Bed3T}Rq8nxnmr z+8faQxH_Ub9d=N{VjX#;GIwmNMYf-;M`<${r zl&f_-1cLTHO5=G;9nQs_u2f5js6UTUEjk`WqU5O`_6hH-p{5cn5VRjt8h=L($%;F- zc&+TXaZVv&c-H8F^)v0$6Sy%j`k2Zd6&jim|fglnS55_vADMMNL`6UH{_Hat$Sug80#qL`@nH@E|DN`+)QANUb zo2`xd#p$+c2Era^7^!ruP#XJ{#~FRzxImU4-a;5rG|!8~6QdgrE&GmRy9YfN2s(-= zElJK>FFI^W`6W-(x^t?v1na67%fK(t3<8ljUD3!P=z$qa{Mb_<=(wXao@Ft-lKy3B zy*#y+7pGb)(8kb;kKk8JClHCGp;`8cYiGzO;(Y~zj&n-mu9v7EadB((aPnmkr&@I0 z6^Xkx=j<&4dn@t3`~`w$2}X_K&3xR1SsTyzJs)C! zFscSOvvCv%nsF$NPmvQB#FaB0%BP<;;Z%#xOCoV}WRk7b%MtvIM=?&b8YO5+g)^t_ z@t-{`G|SK&Md#hZnNydJ>o>LkQi5vH)tMwc316vner&{7203%;FP&?}+Et%sr0i>d zDreRJ9c?M9CH9gDzXtQ}#=EpewaapDaRy7ENZhM7T<4wm#~BPI<}f)Zsn%+SU?%iHj&_MAem4EFGpw1K5rvUFQXkI*to)I?%!rw1@SYaUPhfjL~ zum!R2vSGiZDAUXRG}K>8(2|OX5q6)WW*xwHOh}DZ#_J`MvY=PMLZEaJasBA1=w9K@ z0zsptbP*BNv?vZ5VK=l<40k8Yo7V%Z@OqQwYw++L{wEIiKXK3=M+sU|k&Q(sc3aPH zFhKJ+arM_N7~Y{LP`ZdX(XWY(Z%99ZP|G#+K9w-gMZ~?Zz0pcgKMmEgL@l@Z@vzW- zWT6d_Na?#Ky0vW|fuOBM=^`81k&CQ{cN`!PwACnGM9f|NpLJvR-Wu8lv_}7JkGQXs zPT%wBDiE|rDUHvH##UidUpn%B6)GvTEULBnm<6m{kOM*M)OYpmJ*%+pJ2i?+Za+>5 zKh)B?WWfFT%l_(D4aUXGk#)`4=SHnK?Qy|Ke0gydZfsrjS8pGJ?`-cHI+Yz<8>6Rn zvI&XXt1rUKWm7?{-KJyXQ@$MV@q9gz6I^j9(NpxaV@go#*6-c^>%qguJ&hdcezw8U%^HU5@yOR z(AVsNU$Fb1JxQuCGFSViR~6Pg&q*L?9F)c#zgIdcf%hk~s5vn*jhxmMr6pM6!{N^GM zv?o$plFp!4*}bapj~|?bzB?bi8vQs6?z~(Gl*T6}BOhvc`d%g8VunDd>x7MiUc;{J z5TLXqr5^euyOkc!8)x(oMid=Il$NB$ayM8}Z6>dHDnh2?ZVlR~d@Bo@FYgVM#;`R3crVMk5S46zr=eG%qaOuowA8m?SgLH||Ah|nG z8qYjiu}ec`U9TE)?;vWL#Yv#Z`961l(5%M<*@u{P;m3MJ^6ptK~Fo>ZL~J$xb$``DJ# zaX@=Gr6sA@nssv1`)}l$KU_K0dNb4k`gFMp`>!r3{IzWu!IH$nqh?0k;~DWAcFKLqm*d;3^%Mv?CMb>HsVKGcyPKWbN8#y zY5$>GU(m*#x|d*9;a$!eXyeQ0DaX%>YzOt=*F&?!t6GHJ6+Z z`672Uk97E0YLq}wEwMdpUoDn5O*p9h^q?~{Trq+RS$uu8U zyi(`F8K5!F01o(EUTx={*v=c!_9xvV{6#5aU2QjU(7hUgtFoz61ww;_I)6C*MdR62 z4NP?wpDfsazd8uScZ}moTs&yH4**Jw1l4MbHdJEFKg9H?$k>bbCor$3k7P=`LmTRt z$ip!~Y5c+wA*fa(w4oC9y8TTY*y$dVI6jyS{}igF1g%j@u68<@3Op#*I~N=wp+>b|xsk?4s8)l#3Osu?E~Gmc1%|5!|uu(TKJ(#VWc z;u_YKI;$PTS&h@EshL(EmdmUeQVe^NX=B$s+{f653F+=xxlk zl*aodF;<#nB(jm9T3^tHN@V>*jNad0)A573yzg|NKwLl@JHsA8!+tA)(vn08s`UwN zsD$Pp;`yz<8cnxBN{F{Vr-bUEIy)!g>`ZBV9z_VMrFxo?j^3G07|f`XT}k8_>4_rPibaUX4{ zbGR+e;grTbsb%wR?;;V51l1~y{YoXq{6lygMnf@)Pq8!B=1AEKZY!~}H<;`V88wUo$38)`lug!!D(xRX5WLQEhMeUPA9 z=4eAD=Kn+F?YbDthL7P#n&rxr_<=Ug9(x5&p-w<)+Y-8(Z%7-J4r=fT}L4^kS>s*0&)FXDu=9EFKZIfapfsKq zY8#++F1Vx|{62-#tp6I%NQs=D2p7L}6J{St;#L9LFL)YBR73}Xc#6b;0r4<3(itd? zPy3K~kHopZ2s#5$8fTn#0a}ys6Zk85s89(d?xDS3XV1fUBXxas!XiLh2?-q%REy?w zk=S%FL5MPm?vmH7m2b--?W#G zOydX6M#)q{iL)5Tn?n}?ma9+P_csmDUMW7CTW{YiQ!P3Jh(z^90owY_dhs*&>oY2$ z#0j+F_T~y4X{GMK&Tkl?HA6y&1l6K5fJpQ(3($IZDaJQV8o{W95{J-6L%ZA1es(C@ zuts7g5*v`9T66{wi5m3-v@Q0UE1x?AGAg0O0kjdn@d0$at-fy%T`xe}35kzLP%SzG zh=euT$aykQe)YwVQ3)juqm5qa>a#*Mj>$-T{X3%#Ejj~;#4Pgw?ZHqdwxw(}MkSPpLmP*(a$sT2V6>q@A_9qR zNKh?01BirW?mTU+H!~QU6d_XyCH!!Fd>r)_x?NWH0mOf}tX+I;E(>=ImZ=t<0Yu_Q zn{@qAJX`I{#*ca`p+pMC@wC)iIQC3EgD$^ifVNoTJmxa#tuV9D89*cwF_*A+qgl)7 zcM6qIA`@+ltNI%JUa9XvmS`WK)gaLy393bB0Fel{4$wAR(~OOO)rnIHC9=`RyAzqP z^JZ7H;fh2nB*r2^wP-#UiRYN9!|NTBYftj#REy?wk(jW>1Pa>DmlLCWIF(Q$7rolz zp8~xD)t$>Vwxnx+`CZcgm>9&VmU?ZNKSZMHRueE!+N^YNo6V_&65?zyb$Bsl;DCJD z_O&}7ggbT&Zxf%NG8$|xu7l0)-k`_pxZ}5>!ZNiz-u1br*X-=aqGM|b1l6KXu<_)t zCQrb2!5aB-o7s#?C~*#LgxK7GgJI5S!?Sl|?T@kpl#k>51%he~KyUx|wru;Gb)d5M z9NtP^D^m$2XiPYBw%??+sxyjL-}O#%cXHp8t*c~YSbuq~LJ6w14~fX=9Dw@j8I2(cb+pP3 zUlxaUC_%O8PAX}t-?V$?P3jAB$miGygPne9vX&vqi(@M*P4+wc2OUgNE?Ku|3j z6MmHh>OcU-PyyS7N+>~N5^I-AC_z2MQQLfkcH-(_=IIDLHVgN}^|YBGQwb%OBCQhD3eOyEYEf@*~#5g37AOgC2N zk5-_Bs+C>iKIF|Ur7W4);4k7!@HAH3>x{h2@~TkoMzk?~ zdqpL8!&IO&J}a77f;pFUWtS$mQ>a#H^u+shd1Y`dcc_Zjo9C8OX5CTWyx-T3F(bJp zD;N-NPli27#T2|)| zOLk&a)ySv|*l*C$ndxlu_M=ab@}~ zXpm{Fv{|%S(4sWHskb&!S({c#_HvxaXjzo@J(~(2`jk}KOy7=i)LbL+@eg*zRUb8y zQAyVICy=n*MDerVDcHkzMsEgl+fNm>{!PLh`qxc`gHC&)S#>W6!g6nHihxCV8z2m? z-@H8uiyYPOn5a8z$}FmEeQV1A9hFcb7>T7_&q1lr>;Dk$c@?eW8oB6Zp`>9=1xoJP z3sj5JMK%^nyQ3dyo&Oz z!wxw01iwp8>aZw|`GYjkbC(U&sagwS^pLi0tUzzY|EJeF2VoV}IV$IVFe~%1O5A7v zDuTb%2DL3ocO8P+lYqux_h5-Y(8wu`cWbkPd9zn9^yW#2<4&OUk@F6N>}dhz%^!nB zr*QCG&{`-7-*);Q%wLvw(wErcZBGeWSE5&HFNr;~+9u`BU|pOV`LF$Oriv+0`d{Mn zd?V{kO9tquU zoA@aYPS{Qcs^3vvS+o zztDz3LJ40a{+CNsf}4)DZMu88j!G!87>QQ+C9_?R)nAY*(Nni7_Pmv|ZURbb7o>qp z_$i<@?SudCKkG3JowM@~;dsf^X5TKcJt#dFiJ3z`LZ36c{t&KC<~AFG`wQ(swbZ;~ zXiZ7FGCr8^2np3LY#$v*tvA4t+Vy5KG}oK}YOg4cni<;YsOe5RwJbx%p}9+~k@^L9 zU_nbY@2Zg>8F$1c;GUz7j^|~l)wK#h)Tm{Jtr;~b0q(C?pZ2N5c!vcs!*});vM42J zNkzo^3A18KZs{WsG>cNYhL-M{}VK=CQ^6bbMty4b`I2Za@#4bvp-_@2GF^xP1v`65({I;z(Ti70kDw<@h|cId8k!XtcO5Qt&?a&1|8(6I^tVdQRCtp3LQl(8|G&id z4mkABDvE;zNnSSNU-r__y84?ilq5+LJ_YkB7HjktEHsYhS~`Ewn#S{evV-}iwRiPk zeZh`er?g0@wfk|*A{+O%T?^wd_)E2@w?&aJtZ~%3zJIU65oH)3bWG6MN0QF|CvmTZ zExGPlIc}s+gXU9if#tb3!is}>i@Oa&oALbS<+%C05}f)@>4La4s8KEv40)~;6H61+HkMa zTzS57C|lD}5^Shi8y7!>CQCl(DUG{#mU_Xy%n5Ax(-c{?VQ5=QP;c?ea(i~jTe~&a zu5z8lsaKWIhF|D?80V3przPQ8Fa4vH&)#kLPsb(#L4Bt*#u4{Xu`lkxTuy#gXjxQ? zdWi3ae@N2%_>N#sdBqrwkZP6jz6B-l?f>KTK4V=yc=SOjd#ny$HrQMss224Q&;Fc! zR_38g2eV_o=|w`n8c-G^WUL3XUBE~rQhIZt;+$=cNqFzyN@hS4lA=;?3yS4is1r-uE z76Md#{Y!6&(V98x;okS}f7zHksVr1!-Az9TPa3B-)N2DRdezUiA=u`2XDOu{2{!s6 zk?M8^8bOT+*laC`T1Xj{})GX%L~EEnw35RVYD?H zYR-y*9yed=DUD}M-d&|HI698M`|(UJjh=X3*a*WHtc1Y!FW~Il9WcGrb~x1~4Z==r zhyN<7-vx+D`J&&HIi5T0OcMyIrAH#G@g|6LSD&9h8v0FN`oj#)!w(1q)%u3_NTX7Nv3D(u^itGvcY@|K5yK;xf+dhTqGS#^=s4Be(_IqvTs(SLknKO3;$<#FLYy z`RY&g*^2L#3v1Vq)o8ht#uIy`OY+T%^W~M##&Rm5D zgOr8q2lJtqL>p9#+Qaqk7i0S#_3ioR=(dbXDB-;!3*JvU1ZC=*VNaa1uDEhy`DbO( zhmqV2eg8c5APj!c3Z|k~5B(t+Qnfiu#_QiT_rV&swn+HTC?*d(>d$QsH&Q4;?NJ)v zo3IFob9W2oK|8{$3c5fD7;0v$afT06OE)rziMz$IwK@a`+^E@^Y4z5>$)k zc|5~(fepWM#frCFy%4B`5;Px6Qe%@jd`0RyrDbJTpb|>ZtSw1<8U=9kx6PH57I(B% zi^d^7C5zn_$eaDHra1LqqorDOb{2^-SGz04zc=K!zA>RaXm%F8>fss8eRl@Ik5T!0 zszqB(?TJTHBA`?Sb&j%13gk-H5RjZr6-rR8GdO>gOxg>TCpADq{RNp;E+?kL{y{oQ zP%Szhu|4Jmai4%EF#P2&dpag4A&w7!BwTkqfqcIlfuQA58t<@JMrbFRUX!aVpUkOO zv>(%2D2k(M#ZVg~jj@hOs3)`*@Sgs+>EO>wC=AaTr4mZ~eEA6GOx+KAlAB;%_1--n z_QrWD4IF(1f@=Lj;>VD^@M3UdB)l}a+81H2JbH8~fuLGq8E2a!$w`P9>C} z_V5?v&2>=2yEJpRaT5rtMPtHWEcm-1Z%)2G?8hQ~8|**Qp|kKgxM(d>=iDI}aX1|O zu$QcRd;r>1SD#0%?md$y`_)q3d42*M7MFVsqh2#z5nJYRsT%qnu!Pn3I;S zaec5{Gv9q+Txu^+8ox}M6vQ(v7id51-=L*h)Dw{ydo`HH_IjdUqAL*Mpad;Rl58_> zg7n*pPqndT)GN9o6NwIY20DBkyjJeJWlkYsi0}fo^IfY$VEZE+)aywt_rt*q^(k3g zw39NS%m_B2?R#0ZK?#Ev^$^e5?tNQZ$}+ z#P1?U_l7l&omsCD&Hf<_aZqpZUCSDiAfmYm_jxmf(_f187v$!yY4E=89Z2bO8Gk{J zZ8OASOzs@zU4XAZP_5GV3u#m29cZ^mCER~l@xY{deCDDUg_cWy2~!$RHmc~!v#gV~ zUl(O6^!}b5&TwDy-oXB>B;hWeBn=!N#K-6}wZ=|U^i-<^`tEr<9kR+K{6%EDkL2NJ z)9hn$p9%GZ5~5cTbF8`fvMqAr)yACKpdQ+whuiLchX)(7F>;sb&A4Z73s(Q!Ss{+i zEuO&rIzJ(F{a3w6MEcvsj+Jx)WMjt`mAvP}*1t9M$758$%yX<&C#0N{sJjAr4B=yXunEA$f*_ zZ;y#Qw7~=U3hrAPebq=Q=d%u|C&ke#sBWz6hfU~J&&5qxSKIbHwPA!zC6u5sNs@&_ zW$wNOZt$9Ji~4%T=kXW}pS8tXs9{FFUFY5LpU(!?uB2oWg4QSP7 zI%~8#MxhdO?1_09Il%g!5NzWemTD`snYn%}a)FCLP#ct%q|?zMiWMHi+ApInqj6BJ zIq2c6)}LUuRRqSdW%hYkIJq_JciLVcs1~h5N$S`138YUpXFcn5WmH0m?+LG=+tcp= z@6>s)X~Q^W`jcU-l#gDa1l6K#gZCNit14&v&tq%8*SE95-~CIkd;+`or-0g+jB)gC z`3ZjIpF$hkw*J&t_&G!C>=n$qA+h3`iL!3Io%i zNqDOKWfNudlCnz7pa4b*TJC9FGc@@{~dEMhXPgic(h`=wW^I z5Z|eud?D8N(m4L*>NCMBszp7-_nm_}X)N(8v9IUR-h;!KI#Q;fIF6bQNtiPHE!Cn2cTezc+P%!|jJc_MK{>Y~fseolTh z){9X>_0X_0kJ32K2|=}vpbeD>z`cAT(RbXrSp7#&_M=ReObMa=35{>1_>_{fqutr? zn)x!-(xF!Bun*91#VnxqBq`gz0nZIxDBoS+z$rm{2Bq=LnzFT_(RF`jbFa5TwP?=} ziDwrZY5Z=OF|E{#)4p^Iy;67VxZ#c+O5-LQsEr8|T-5u_k zCEIV_F%LH4|A!7eX5YY6y+g0t^Io<+6QNw3;v(2Mh+Y}?cu{-!i^b1TcVkv5B~&+$ zQLRMuN+o`6=?WsTdHWUHikL?{@Vy2~&|P7a#yhEmpjvd?iG+87z2@hEG({;kfzwe- z30hL&JpksIHYPg2!&#GrzH5%Zfor?1g&Ix9|BvjE0&9ZQFI(dr#f(--7i}>gx5#AUw|#)D%OI&J2=VUl)C_#G(rHgC? z?Hg(P{m}p&l~97Vf02#xl^fbjiS41GS|_l64D-joM6Xd9HcPH_)6k4ewJ2R=qxjaU zwo@995D2yRH5qdOHfq-iy|Rc%u(7kA>M3hzMpo@Da>|9N2UoxWytb(E7A~Aw{ig-1 z?5i4^S=(B(9VPd2UqRZAZG}C2aq|yQ{li+=i~n!DIS&G=Zump6l9|?ZPYe|ZTCVD$ zfiCju_?%tV%{~ngyrKlPT|{i#Vro-vf=C>}at$*Mjj52}!y8sqPh8N^98UZ3KLj)T zQOl;&^uZchE~Wn^I;?mUl^E1l$P9Y)O4lSB_C<~_%!zZ#N5k=Vo&MC-n$HJg`ti1f zz1<+8W1jZ6qR8D=pNr;kT{Wp#Zae!VSaG>Fq~P@<-$zjPS`)lma1XKuB*TWA>ibb@ z_Srt-S#-^vZo)XHHvT2d%HE6)Y12)xLA5AdWWzDn!LmX`N6kaD{;J7K_@QkectyP} zBGRq3){_VH6!I>OgO*f8B(F_~zGdPe5H#CSx`?o=XlheEx2r(Va{tY{=aVyS!u2+q zc#LCo*#hXh#icNF8nX7kgw@6#Hm}xq6$qLK)fP0+MP4nb(LP$2K2*qwl%TeYh=m`% zM74fBLURhsve{Yyx7_E$8NA+~{SBO_dqW&v=Y0PSYc~CPr-51aZ(y^mtZQLrFpOpNSgMqmK{=^_|jxh%*DD`R86jT~Xiv zCCo$9qFoL+3O1<(jrQMsRmXQ}%!9=PG+QxR|2B8w(afE&9j~8- zJ%WX!!(p3R3;4Be>sEi>&0wB+lVYydbQ6f3sI_qOJ(zuXi$E7e?liJ`%nNyjkl|Dt zhK#xkuLm7Tg>_HWJ4NcKwHsU7CL+AGkVUCi{}OjoO>FiZZ>gdFQi9qmvXR`fm`%jm zQH3^UXD7fATs0&kdG=ML{K%s7-#Z5T=_A}0RmXOmpoULdINlrAE?dtZz( zHS-nfiV|v@8-5`b5pm6X+FacvYxbZd@{=B#xNj6zVgGtH-gAp}fNKvSa&=xZtlQLU z!z@~4qr$33)~oHs$Z5I%61%HSvnjW(yM~sl!*YKdJPo1WXTn*$_M5MRZI#tsFKU~I z-=AjlJyayr6~L}~G0;d^36%a5xx+Ra#aUYe7tC&nk?Ugr>@ z+Fi+(*(N6#@#jdZNjYv3G*P0R*$q{PAnqkHqyle=80=+ zT5pstB08km$3%tp6=qIaF7*(1m~M5``uYX%Cm%Hmm89aGTNAru;Lvv#ck>z2!zHI`Zl1%^9^pwWvKj>%Ox_cJC3Q z%<4Bwu(1`}z>w{zJ@o|4)^b$J1&3DM0~yUFdh{wyc>?P?>;g(lQp?Q^$H z3xpbzA;VExlFYt#k~@7a$F8<kVeNNP&VBG)yL6`)r{&UBSOI#~wqy#pY_EY{jlb|&pOLmv zIela{r&`}o>-C89@ZxD>5Q%*k$J@)l!!4Jj>2-W~SK7fYJ+DP63%`kTzK z-lbZU#(iX?A{}hoGrpu*OM##xmC}-Q*O;|8tRF99oG0g1b^HKXVjj!=Rc@XUVSQ~ z&V!#b&qckd>Z+lhQ2Jlu{DQ5~%IL8ILA7*fz(F9HB>?gb!;Z$0W_JGwf@++ z{`R@`FzX=#LABKD|7AGUhS8e`){#m5G*m)~;`k=P^^E&a-K^{%8?W}Citbsrzd%qe znk9-N|6H$1O#Y358Y-d0Z}duI{toJ8R{vvTQ^wQi*=q+01l6KhqR2+g&8bnlyARM% z2_@7zJnQ%sR-RLLA*qpXx!5Nr?!`cXpjxkxXm-#@c|Tk|3rQu8cWoS#Fw0pWsFs+o zRANmNry&D}h0KtMTIEhiO0mq9ppJP%mMHX! zXWuLl8*US#QzeGA2+fIVNOjl{aTxI$9QyLG_GYh!z)Iy$ox6$%teP%S#n8#ytMhU9rf?hrS@D1jbSHJ1) znBXoS$gpP4o~;FfYKd8NvqdA__{auq34X1TN+{6}ZK!$I4_9ZBG-H9R8)JW4&aN?8 zAgC5yYl#GvP@)&wP*;7G3s-%oQ~K*}|Eec<#dfCz)#`!7T8oF^QLrDqio1+sFqb=I zU-uITszq04l63f6p0-|QHTYm0#HfT4jj%l=uj|lhziOlJ_dIRWj}H{L`r`$HYV}30 zn!M%kxbAKw4x(4`#9XD{py2{Rwdi^dcT@FjuCshooxi!_$f$%81JH)LvWzHPS!QS} z>inN~Uu|TFas1{u_;u|BkmdBpojNhbp zJuFiRCB~pv>RL3fa4ot&Op5K98_1VpD^h}L(b*19x+MgaP=d~)*xOS|bE`d1l{#%Z za5`tu8HeV1NyEl2d+L@#=RP`fQX1d2tU8%T-@c)INeb3d>(nbs91jQGmie=k?DDRKOh*wNwex2s zzy#ZO@S~pk8)u1$R;k_Bf!%-Flu<33OGIKd)|Jb_0jyi+zB0{GG$&FTR{#%6^HE50YuNWeZCJw!HV&tz?67aKaE`DSgYMD5_liz*Vy)*Jv*$yS6gnec#df}^{{UZj z6`(bZbJW>DX20yb_Q$j03bjrNT9PF7%5YkvO2X5h8| zFk|JX=`!qB(=W|tzizHmk_WF62&yIak`=cnus*n1Wm~;o3YAb|0@`Taub49Ev3fGz z_eEHUAJ2;e)2L#Jg4G z5Ik#|5>#tA5;Bj2jg9vq(Qbl2%dYi98&a&bKu|5(D{*J$`WX4mqkjD1t}hDhKdW(% zk5Bne_P6T$1MP2kXWL^KbDtA07poVe(6XqFtypg}Oisb(4&mrk^F#RNAJV<7Iz%9Ge@IA$P-5D5(vqC61^B=OFgJ!z!(Jk2vA?5+#DLu9P}^ zVOdQtv~hm_R2J0ZqHMakzLu6nwU#3>Z}vX$I5iN7>Eos_yZd^%Wz(`UC8*YVBr?hz zg3^h0YUGvXGS>nhx%mhafuLIA{1N_j8e8fVE-Uj~Wh$Y>cC=Az;|Zvp-xzJY>N1)2 z8M{>em>Dh*RBIm+|7|@B&q7U+2zx(={rX`lryZXu5L8Q?2k$yKvQ1rj%eJN!8I@4t z2--;Wz6(Q5jnKy3R4+Da^jK|K<5-yzREuUiyidK#oek`JAH0Tqk*S0d&#;$ljn4qf zzN(GfD-&7QF*TKdZwUfHwP+rbq;g4t%x<@t9Q!R&PbHL~*$&s#69%)c9aEGxd(X&J za$oJQrGCNgBMtt_q9va?vUZbml!FWOGR?1)Sc`RaCbPKmrehb3V>sr-p!aJOTie50 zN>DADUGY2B&u6i{7dI*myByY12_F^-evODZ{|=l+$c z!7SDF%@a*! zFQKa`=l#3Oo*{iXJs*zl@u4N*H^V&dC`)wi>~4uw3MHr(-A#$#YHZqp#|4DRqsld6 zREv5d5{EF3#5I{pGmM35(Ky7@_YTCi^{KUCr>uA`Cwu%_$-C|> zkBA(}se}?sv7HS2>G9o+w$=I4X}#FV3WExFk{cwH5Kr>#(Jo%uo)`xwq^RU?;(zBlCm|7pgd-AEi`If#(*KCGx@#4k-it4pJ3*lmO3)gS zq+gv)6y0i1etKS-;)`V&&M>9BY3Tlad@|ayGhaJPtFX2WIn|;&YeXV9c#ksP#+H?d zY{0365&>x2a9S{)0)^w_zI$I*zh!rsYHi2bHSDJPi@?m#!?hQ?6qzbh2_?jnBNgoJ z<45KwWp=w2J{dKXOJfoVbwt&C)>}#M=**~u60{C+#z}GDp3I!B(2P~+4l}y%U@=B+ zI2jS&)Z5yXt?X2t-)gj6rdnzX8uq%1#Lk?TO4)L5%9~pw89f78ZGXcly_Ci$4Zfy4 zGWe?Eh`%B!LAB_vS$s2W+#MxE=gx;3uaYT2wbT)1c(Vh)$=V*j)A+eA@9uh3p<1*S zL}FsUTZ*pr0wt=$Xig=RSdKRScS`dYoCnwXR$}iq)ZkQ$){jWE!x826XRf7MG;&&R zlJsM1bKarqd#zh}%Fiy;WK@gpdlU&r?1|y$2JisP zy;Muhi3WS(37GFNi~8R+^|RDMQu`;o5O;gm=j(LC=Sjr1~wsD+_DmTa70haw?$&tr0xU>g__gZRJUF)p6dO zYSCH{iPhaql(^NNti!xCITl;WaH28Y-%Q^H!c|{sCw{kNtm2xLD^m$2=qZx8zA9IN zxwov%e&<$UR7>4cWO&;}BsRFVxg2Ndsqq!3RfCbLJ3+Ul9YtR`=`C-b4XAv8k0zjt`*1jE2aH({SEm1h43}sQR45XhP+6uw{sn4T69!-YUVaB}IxS@sbs~HHYrM|ml_?`m(c3%EV z8FcT6zU2^iP9>C}9^#$tJEP_0YwQ^R+(aO#7L5O0k< z9^%O@6}z*6zFFGDj0T*ZDjkFE+^OF~SQLEZuXCLrhyGHAckId%YTTD6VA~qbi;hC# ztXmo!h>nC~c>R3QLueEmgxCWAwmF*6-Elu?3ejl+@*r&~)>#c}&!mysR!KHZj4 z2_>kvk~Di!W1Ss-tMRK-M@A)-IE7xR-w0@o-w43B8gJIslymOLn<7OCszqx7->)52 zkEP7HARn}En)PUFL0+uuP6y8K*TcGQ_uElQuj7BoAY3ZKfUUM<94GR1oo>+$oW zObMz*W0E8f?1|Rc3-e32W>g{&YA>1l5QYs`-@IRjL`&?u1@o;1;uz7QwSa55z>565 zPc43^dlgP4l%O$T_ED1Lv}*l${m;*3Dxt(_v{&IX?mn%46usJ>u}ASgScbWd@5!lz z#z9NM6+pQ#`IUKFelE4O@C_dN-JNK(aiPgKaO|Sq*vdq<^eCLg|Nm-o49rUIMPm5eEct1m%(fr>rBI1K5?UX;4^wXoTt~tM z?@BEhu6{S;>e)MTvqK};o^M;^rgLvYi-B9A^@dRpfrMqa|B(_%_ypdOTbgWF655Pl1JQ=v zhcu`#?WsNJ zGDiaUM)5d{qcLfBs_W=UDs%7zf#C9z62Gbn_~P}o7C+%*pt>VPC0=ywW8<4XOCYG0 zT2gzf-%vT)1c@G5HI(RBKV~1>RH5Zkt&*=ELCXifVC0E%NUZ+3S^u+PXMXWZGe!xj zMeX6KD!y%$epYk%)icu+DxpLvv|+NT046Ofi8dbXny=kl3BMWEa1N&g)uJBaJ(=+N z&=F6|dVJ1XrV>g}dy;e^zp4`LHk6GhYsAiLS=~Gm$553>0jX z+WZd2-Tn^Ny$%4SB`NDndA4rl0Jh+3U4_~>fH7UqEPw^Ojsd0dDOq|gxz2`hY)O^- z3e{?fUJV}d6U_XN{6#c6_*jVz8q1HrXd)0aT1w+=;C@DX+bA1e^_a)07Og9h(5=vN z_mTJI4aH43^_LQ2MxoZc;Hxm=#D9Mi^$*GW?o8n+&j%}%=%&qv`2(&% zR)cgsrE!%psg_dvMP=@N&yi8BF=(TX?h@>>c<>itQqx^|zQ>GL=-EjiXiSvG=gw~q zz=^2=%;H=dA#xh6NI2c;qIubWpJKXaCLdS(JDxod2T`vw^@pu<3$NGWwMdK_RED|L z=+7MV3uP+Vi-g^34jprhfR=<$8lr<({rE&}Eu)n}S=1{^<8y;HKHS~(gZ9m#X)={i zVh7qwXm=W-{VU;!I=QGWOLgnRm$s~{b;25r{CElm?Wm2XGrxl@hf`4Q&igwNm8)}R^T!6rTnm_r$Es9p|m8K?3wG}^dePh<~f1= zt@Xn6G&~Kj2qMw#%22JxvLHVHGiWJ6>rJeyz-`Oo8axl?yY=rKC_%MU8wPuLipQC& za#XjkN@Am4Lf@rzMQQv>%$(nHm|aai(6b?@5=w|Rek=-LZxgC0z4ql7Mrg2339)u_ zYX-B5AF9CVf#F&zq4gu$cvx^pnegYST84$!}|4c2_ zx_S5mOkVyIY9(j?Wh2YGqQ1fkMQisgh;KscV=mu;)NkkYE_lXsrJq?aw9PgBmx3SA zfBI{fm8_l-zxbO8zm{!_^XT1tWsEW!slPC8L5$ zDEU8=;Hl4J{nrzDuy4s7DAgwsZLDZLmq%ai2SMg5u+GaT@1c5+8WzQ0NyBrd!MTRRu%EARdS^L{3Sk@kcB1KPN) zzXPEw-lC0_LGScC9|p54O}07Q!1}S(ABQUa^7MI!N+{kgCt!|s892G`2MjR5HE_%a zByznolog>la;yCAj7lgGakzxi{vd}1t5q8>OM~*f)lGT*Ay?)X`2*Uox&$khC+aCJ z5~tVr^X=L?^08s%x)vN*V|NB0ig}#xF7`aEo8u}`~ z>&Ts?d5jYAsMY*y2K4uDDbToAtx7OwGln?S=n@H3D**|UrPn~7X8souWILHT_MZ<0 z?QY1Fc#U2;_I?MF-V!J+Nt<^0^Y`-}!3JwffjEyg`fdLJ(ZxCerSbH=vwqx-|Adj7 z?PRKT28mlaKVZz){(lh>`-AwZyDh=4>3Jz%fTNR$~8 zz{3aYwV~Bo$_KElU*j{NOs73?2(Oog;|g|bINU-HH{hO$^VaHVpwXgYF$IZCp-=6SR6#c?SqeeRo7a3vxzUG zHmKG*7TC`;)Y3&|AJ~yv9yejFTQ0vqyYEP2p;ui}m$vquhE;Ruf2c>DfNm4z0 z!y+b`DFYw6X=$&1fwl1SM>OpBWuT7D!>>-l>R;-KC!78Y;@xV7Y9}Nu5QuCfUWag) zk=-09ElCgYeE4*;!E(@PBSv$^RV?>m?-YO%wSdw^bv3_7HQkrJP8v1Bs0{$4Z|w!z zGia?B5f8IIScjw@(aT=>xAFW;Omz%h1a96UxpHj;rIFVQ%7TL&n*6j zFledXHrMGOxQTiWz1o86Un%WT zrd*F<0uhaL_L8%}P5cGAh;W$|7?YniNJq64B+NUVhv{#7{Waq>h@8h?Jcxppmy)#9 zD>eHVJh_AIKc>?8_gxh-^gf0mt{1R#zW;Hcy?@N3PE*@=#nW)Gsuf~os z&7-^N)c!N$&09EMwG*V`_45s%py|qa@C>ilF8Tz)^@gI2py*&eYGVs{pO~PhHfS8w zo+OpTZ@4WiR?)#dBur0jP_4uc=xsVaPt8>`LrP>Y-rZ~q?D%6nEthIh8t++F@#l}* z*vLDFeAXtTzsq{%z|x#ma0+W-QmN1I>Ea?GCOo;m&O2r2o-r(FR^K?PMWdy)fah#i zoXI-P+AlY5ZzhyWXHiOH7JcHw7rq}RYaSXaG;*p%X`FE?PUUS!Im!if4=Z#9KxvU! zu*Q#1?|oH!yIOyNp!Gv(^%vw6ZsilFl(#6O(8$%9%-Z)e1h-rckMa7>l^?JoWDd4R zdrN=bYrK&XZ`(#7Zll)XpU=Q`(-xpKo`LYs>`t&nE^z{5L@7J5#=rnYK}AKmjxdS^b}=G~Vvafn z7r7_w?!pcXY#qBs-*xWg&U`oi-amMr^RU-vuf5lgf258?8@^w3BFOke>9=;E3CoN1_?cLiu*EI$N>39?Wm3Lwg`O$-4*dQTo|}uWh{UB`tb*Uqu}#g*3gxo7~Bew&9Rm^@UOUC;um<Oh)$N#6wJYs1d8>zyQFUaw+5DLWi?DXUiYS6)(Sue{o>^bz`z zj^Ynvgw{)Diko{)UJZV4a+zE%>LJ=n}q* zM*{OjntbY}?F#GxmnA0D{wyAP(qGzpX}&Uv#z&ChFS>=0s)WyZ3qp zY1(sksiy6EJw!DZ@{v#q>%zbe(MEL1L0`+r~fT{)PLNVYnA zlUEB4EGt!-=qI66y|8?$&)V;bZ{fVe#%%|MurIUJ?;YtkM&9I8m(TjDEG)S|K>~B4 zFHJo%N-y}PUdQ@8KG z$&0CsKDwVc?TOI7t)F<*XOh-9=9ZkZFPrZ{I*`De$Zvn!See^xnQ*71Q9=UCjx?QZ z7ko*vi|_KcS`^KJnj?WZ(Qgk7x-86X_<+}bi(zbqQm;OKcdI&plFF z;-UL;Xm>0L_A!d2j_xd88nH*6xqO6#1hxm#6y-lr-Ug;U%f@9G zX{?=zz9ly=w_d(VnqPnC1>RM#1!80%u4kf!&YA5BpYuB#*- z`7usIDJ(lnm}hn~WnP|_L1WM|m)KejOTxCG_Y6-%^Q!YLeHZPH?SV9TeGf*PW)@v! z(Sa#QU~^xi{VMQ>jo2X^MCm zelgTKZLRqXHJjJhrEwQh<(SI1`BOKJ@t5iO_LJkhz78IvXPQe&bT(C*INzcJiJUoS z_@MLm`QdqJdOs>I-Vjt`v!&)pG;MH}&!!b_6cI?%x!UB)Ef<$qW+71OaQHEPYv;54 z@t=qR#}W+AHRt?9VA+x8ID5AZhL3+9wGb$UHD`%Rn>z?iE^Sk|{V@{O1L+p@l8Ek0 zj4igFY&G|gr}*+*J0)L4w1xyqwKU%1^>zMjQJuI*v(FEjedf{Zg9J*UMQG3Y&sOD5 zPFb-@=P4SdAkpOeQC{~~cuT3uPf1eOO-~a%3PegspcK}LS}+Jt-`ABRW{Q;@(q zaok~Pu@E_#Q!fNel~4*x#kTpCP1_W8bO&YK{um8YkifQ~TNeJc)y1cp2xrGmkx&Xt z!Vx34WxY;y%-M3M>#6b`8iN;U9qd5Q^!3)h0fv_gk1Hq1 zRvw!lScvs`2+WCYdFN{+miaz6<9_EUQeHxzAMagDW%SYaGS&|k&+Qs4exQ}pje51d za*oN>VIwdnj+^+spt|-+K`}fcT0#QLuGh&%lNU}zaxQ`8MFMl8`-v@TtM%&CRz12; zVoHT2>D=)wKP2p!{D|sAzd!i3tlIo|G1Wnv%-HJPnfrW|3b$ngS(GJ?d~RzBSzAp! zaGSN&*lWiuL;w*;bKLf;ekKzUY90dXgfyLCZ8wPvZ(UbjlJ|;ISQ3^9rJne#jHmjV zR!$_)K1kCqVYaDj2%R>@GQ*)ov0t$|9*^)f{V>hW&{s}OL4vLM9D5IgYtMNW9hiay zTdHAwJDXyQCR%i$l>Th%87z^J)7fxhSE5A+N@1N?!YTS&%St1yD<{?irI4oIa2v2* zU3Xx#l$cms?Emg8U$#<+_r+qd=HWfg@gH1fd%q}QCy%{)ls}!?(YsplSTp^yT+;}3 z*X40q#_T345*y1N;rn!4?43gd(sWlXJz2b4d#G03c^yMwzDU!1Mg2yKWuJ#h!E;uM zD24g5#L%vdr2_HIq^_UFh`+C2?$M?|toJtO-h9l`f!+=47W8&XaOP)}wDTVFb&&UP zdZwethQEvSxl_sY>KGM?-6ib2Pk$KXosx&9ZzmL(r6z5fplvI$AOi`^7irqj_idrA z-Q=zXB#p_y6eO^O6oLHM+t6`&ZF%Q6qm~s|g-_}Bo}UpqT9Vpf6#xw8Q zNl*9$DhW#z`qJAp(zlN}m2@D1B}AIM@H$fz)1^|1QyvFp z3ib@P&8wDZB_E5t>HX=mQ9=Tx*m{)A=OXvdS}4Ey+o+)wwi-*E?is}Uh3%4^o*5-f zK?3VUe!Kr>K6!b9M;7ToDXa%er2pAW4D~xLn9fYrFa-&$AAL(N{G9pK$CmusFZ3JC zty1J3hc3#SejToq`(?H~zw}W#j-DsCSt7T2e_g&ZPVZOy<7de)o6qLMDe8<;8~4tX zBSKHhJ4uQqDnHFJkDPy19+zX3kofQ|MV_5@ME;Wqq-kYxzGF`QrrN1 z$&;y6NRzF8Tg3Y~H<0g>txyW<#1byYck(^M19_g>1EsL+EOC9*T5qm;aoPNhCHj_` zEf=|Wk-h=T+KsH+cq$*#xC|fvp0yPcx;~$2`{X@D(>p)CV#IaQP4OwsC3$OZlfwGZ zy8z`YYu+?3M$>$SDVQ(TkG^;^u&;c*L@;l7$JPUht&P`OS~JU1DxZJS%w_&alDpGQ z2+Rwmuuc@Sl{@4&_IhcAorXZo~`>(f~Uez|&pLrxRgXSwtK>|xlp8k7tX4LX+ zW{&ECQfLL1&^@sYuETaXI|Ukc#}4s+nkAa+R)|#e=cTJ0&Cc{Zke>Hl6V0RN#KEkgLoMvsj_T9#K9*R-ia_h5S;d$$hm>-TGwYB|?b~BBEoZP2O&;hs*cc z=)`rW=X~*QoxLL-7$q#bZXa8|ETOkYx%fUi4h8*eU2Gd0O}C1B21%xh1tphevqa1b zb?COT)yZnzw*{vDb)-k20qc>MVA@=3yy!%;(vE>Y*~%uR)3zRC)seJp=#CvjtU7FM zkXIi|B%i;uyHd-pmQvXW%$IHRik&Z{`}+k;PR{m{)FG7D?S7E#j#g;+tTsQA+QyUG zhQ4!GXtnyfQm~e?>mp;TK>Pgs`!N&c&(zK=(el$yv0sBu+M~diYB|zTsm*ZNn|cXK zAx&>o(JAGTOH-tg2kca=Ez&H}WmIeRanZ?=@79wFN|kKhkH0=`lw5<#j`}!Gn730s z^dek(G&|Y@3A6&z6wB~DxLfaAeO}D-z*1pJbnDvsF~!33O-gTFX`CiXD@9$$02)ON zX%y+St!@0Nw|}T`c<%!m|CTn_>N}R)-M2u1>7R<5ymedkAzPsowvCmz=;OBAXL^w7 z6A_2p5AW?uI*`DeIIgkhtiSYnWOYyUKtiwidn(BhDhbjQZ;w5%47eB}xs6$2X+c{( zkieYie#y}xO-Y9~a(iM1S{KWXmZo3Y7#3zB#^oWf>_}5|@L7=IK&9E1JttZhOM;fB zUnMby7}A`qyHrfcOW5Wyj*I@Mg<<7MD}hp2D(nm7@2==#$mlrBQYuVA0xd%CP26f_ z+Tvy1ZDS3w4RGe8_aIOEo0|WVVA-Ez8$9V*n?L-iy4Qi9T5!>_2g0HKL$&YYud5%n zBzd17HbQvf)}e)^58Zc&n1UA7_4y7Tkvs3sjjgSvG^?mpiF~8t zDuXmjJnJ${JK6b$7*%NnZ!_@SaCJ6#le>~WCLR#*@0Jsh`~@1xahyF}IM-)2?=B(RUs zh$`LN;5X7bYV%6j>ckTL@6|AzIc+7-x>yg)iFADQH-vipOz5=D%Rrjm|9IZOuuis~ zE@5xi^R@MGv?0wt=f@ZduCkt(U|CeCA%@&`^@N%^5%O+4f_>J;Yv+=&f$Gb4;os} zAoV_K8>#xUZ4GBf)Q8O8nih0Gc^qypVTw-JMillQdLQTZ7!%*YI=7=#UfMR>(cFI5 z-!%G$b#B)QTM82T^M5m3x$VdJ@cF@-^AtM?=OvWVJ(<_xaqiBRIq~$5k$l!$+V2`2Sd?}sm?kt6AGYyATOhJO}S3!+7dw%#QT&m>0Q^a=0 znF!m7<7yRes;0*-R$u2E%k)GfaNJnE@RuWpH2t*J&onf2h`HE6$@>DWsrvJtI)%OO z(Q^hpd-RvQD_F*0;@N}p1aW?b?+c?;qr@ijtl;CGpU7`R0&}7-TAx2CH{O}>KZz?% z>v-ug0Ho>89erWrYrCn^<~p-I^c0&E>eEYQY*5Fmjipr6hd62peLSS1b?=ENRWNLb z`IiSv_D0dpf+ch>f5wBMO*1nCO}bS1g%kO{Ls==Lt$jCPjdy4XNOsAWuxf~vR9DiT&18^ zxXvs~&07x{&VOlTwWv)BX?j=Y^g+4o{=|$9|Dy$Mgl-=sH~T_0`)}C@A>4fR4R_F+xlT`SubG_m5{zo6;yne-X;g0CS+hePzq`KcEXxv zEp%c#?Q@VoDYOE8DcyamQ1Ww_w&c33BGH9P*mv-7egX9{)JJ=Rur4OCKwYKo38RGd zK#QV2Yft>~&#)bBrUx0uQA_FhMpC}m^O3d^6`h9dXpx7|X|s6Ta}13Sq%FJcW_rzO zx1E7fdI{rc%$K8R%l}X4wauh_6DVIKFekc6{%hzCy~j5$ndpJ`!Lp-8=-t=jgDr$d z9wM(5{_DF{C$=?gEM)a}u|4!>+swe0>c%E_!)C9a36w&8^yQY*{)Wc;tUG$tfl^pM zD-qOnfn~Riwn80PLOQRVw^Ka%B3zp=aB@behW+HwwWIi|)Wb1f)>c$1Q^h}LS$rRC zDQu5l5*+1kSyeNgEHTU4iykPe4-b_}hg?@LtWGjtn>B)WARX8qY;O;_-(GrY*TiG? zwyGKuD5XE!<}Qx=v1Wi4?K@VDDRN!ROW35)hV)Kc!G&UWzwz40M$Tl-`e0{Py-Jze{R_i>v zuy(k^4iQt(qTi_IL#UmsGn_|UZRt+Sic(a_8x>a>q*>xr;UqEt*GMg0o|d6Y)oIYe z`zmSIY1>S#+s(GZaa>&R7-@66!-kJuJ5(f43N6iX`MV{HaiOVdYPX@9C;bvluYC3S zlKxYb_%Xlmqocif?^RQkS@i26FIF1(cbz9v&CfikBJIxSBz4(aNYYDUTLJRw`)@T6 zg+9_-|0Uw1>bKc>7c7eXjedbRMAS-Gy{Jyu;UHm;!?r=YkuSQrw!ycC^+sb}>)Pzb z61Pu`_?N)4V@X)z@$ZHHjRE8(Z2cH%dXIkfEW_yB9X%3QLTpX?in&XGAvt$Pucz4j zE9|@a|7}*M7(n?j!#BIRmiY=(kU-t^D>3Sy>hkn{QnwFg5!XAMyV&_E-K41b2X@e& z-u@;IdRbfkZBn(&F*G`HzS8Mc7319-SjKt5&w=vNs`u3BoS_z9)Hds*eNZ2HORYwk z8_)a152M{SwlhkxYi&-0x5{^EiWal`i-NNymXIyg!nTJp2PwUT%Il085-5dsqi?tE zY^C_Ns49M3J4HeQrS#I;d~LcxM=^k$+!z4PwK%qMmf*O`nZ2dk4GsvkBJ3?A%I0|? zfg_mqwKv9?+;U?8n39+HZwy}Y8Dct7%NjMn832jO=Tpt&Xh+}8GVl5s9tp#?)RjVA zeI)E9xT+ydC)Kn+?~=Pe$C@L}68*ca+FPPWwA5x{YY}H;oZHz_m1}ZBE%QQqSgK0@rztt8g$?%v>{A+8eupAy5kY7lnn-5UCoO>;*Py0xi7g_;F7st7;8zeOSG*s$R?~aNkK>~B)xJK`) zh?8!Qk_!B@Ma7z9zDU!0zA{Hqe8)-|_G?5OYd8k6Wyw!WUEvfq5Z;cH_ABoy*C!7sP0@7iBTtBuXJocMY~ZR1;4Qk+$}@pLu!RD0x`B zJMyPLjmnJmqhxP-{@Tr`v`8Bz7pLbRUt?%J4?j{}xfEGlXpm%-+OAIGuZ*}Vx1`%N z&Cjjn_1in%bQkB>c1w8u21I|$eV<=8y2oe3mjUL^1(M;(wI^UxF*{o2vA z`N{zKKHc6ysrm9ui;i}bFY2RjnAR;R1a+<;$6qpPNPPF5&FeRknv)Ks>5aoJ)rA&R z4=<_*N@3Yq;?3HM{DI(-LVwbM^*{o1qA1Qu2RVAjSNZB~)>bH`)9ZR%mnT~8$utc3 zgIDXVH;WVt&#S{G^~IdTclSOZOBN#IY*D`G@)YlrbWa8eltPQpH&SkwlDk%q;b+jD zB1}P|NpQTy(gQ6znzr~VuMaQ4=fA_Y2TEa`D9X9-w4B=Ev@Bnt+ilPWNU$}}nN`Sp z?w(@i-E>a|+ZIcOmgcxh-G_?T%T7?T3QUsnO4)415E1^7E@l8H|Z?Sxno_!YDD~;F9lh4sJ$9s zS#w+D2WOuzDdJ8(zvtExz)Pmpp>ZM8=*~w(;ZPihp+Mwxt zd!;q?2E7gRUJ{u5toNQ8mR?eAyOZ`{U4V9FVimRDGhcpu>|Or%Gt)Ca6iMKpO+U!T zz0GglxHg?{8L^IcyD>eJcEbI;sO?8ZY4YSM>f+LT^F0UN^9xT;&%FNSn0N0%&w1z9 z`OTOUeQ#+%7f~k$O{$`{e&#D%bX=XD8S&+qStpX-G%sP{&^lZ(a$ zdJlJw&HQosp?p2KEN?DmXU3f9&i2A+sm#2K!o(p}RA2KGx!8SYxoeBqOoyJY z%wH?nnK37h8(1n>8vWs$xUF9mHEC_S{B-O(c}|De%n2RN%Of|9m6z1FGhaBU|UGpcK+2A%R=GWfMz zwQH=!R!4t*E+2EVGwU|AtX!`DFB~Z$))*Sv|*B|o3F0q*`;dV5@l#*L2B(M#TrbyAb z0Fy&cs}7XvloprydUA1P{-D@QmWb&XXqu9H3keDAF-TM2B^?_(T6Lfl_9d2B^f17* zt*ezlsrS@+hp6V~2F7NxM9#4QlXtJ53GCrW(;nw>fT?;PD}hpXsP$auEtB18bg@Ln ztpJl(ZmE#KafdX$D|4|k-{53z^QbRI38gwD7FSwSPs{99GAxrNUT$B?KU($9>lEGD zMgnI8q-iI7Y#ASL>8{r%B2elc*{M49lxCl%XR^eZlL4lsxxF0;-}@irrLzH4RU=VP%1yQMX_!__*Vy~XR<{3tN_!G+);}Ju4G8lmyIq5nEZ0B zi&E!3ckn;T-Q_Qyn4ZZJV~7aJ?d?eDvxIGZMVihH-UXO0gidrvn(0o4P*7Qu4 z81^E-v^IAxK_YgSgRm#si$C>rdM48Ji#mq_OoKaH+Z+j;=aHuO)#L!v+}tsUQaGQp z#CNjpmR#%NYJddhME6Cb159$}J-Hga$AVT|R5Q&>?df<+OM!ws~n%2 z%eSl{j3~A_6KT3LQMn7>u+<(R^mB}a?c9xey51g5)#;gE+lBCYohp(Q$QS*6H1FuY zPB>SGtvS*xG4}(lgTMYg=J(ndJAHAN8#h4R$`UH(GuDRX_i>|_@H;?em62@>WMg_kVd;vtgmgL>1fE$ zHOJawPW1hf^)m$L{YAvIB2$@CVM)-^^rgZ-;&_*SQNmH9QPO?2<7CxcS<^GuQhP^{ zRh!a20j)s43{=8P2w6H#Xz$Bf7ipG=bO=Q#`QYt{8Gb|{ouaOwU-viF!okMeXQ1qqZw zeH?e*a8TS_q>EVSV2FhF@wiY)xESZhpYzz9$5!E&e1xM{JIWRE!Oaz-&$MH=G}iGTj|ePuCbXHx7HF8T0YB+>81DGQSMuW ztq=Z?XBIa~D0Oy2IidFPX|g->obMfxEe9;$oQH_~7OrI1`b};#leI1q zm=i^#(gO^!1FSbWaQA~!df#nCt6X4nedqP2@lav?(M~eAnAL%{!hXzgCykYa#GX!y zvYsVyCxj)WyS0A>n0!WB#~|(+^nJ~POAg8t+7+{VoQO(g%yv7s^9NrWB_z_w186&^ zx}v0nSqK|V??IMpEPUU(S6P=HBVoQsWHn6S+pj94`0dbp$?lx1^6k(Qirq$*K&jp| z3(XtnsD$*?ZME=mkoaMAf*LVojD#sjur;sQzoL-3x~^ROj8WP`vzxwa+|W5T6KR(4 zSdz-Oom5P?c+x0g3R)L)qI2gJ8-&((m#I}3M@m@Rrr$<-S7=;IS+8!+#1hiC6IL}* z>aBgJlzBPT;>qYWObm(5oZh>!JoZ%;W%mBfnPu;mFn3WaD_vHHQO%#GH&9~wS5@P7 zPLVJL3DiwH`V0r}`BxtBe)LsDY(d@MvFXE{=)TX#08?iCv%n;&%Ttk7mj zjD{sa9l944;q*oBO1ol?d+~9DvS#cqery@5XK5=HN+C^O9s1>q{C3_GWn)V^Tcftn zM`r>>Yi7uWlwonZz)Nuc*`@S|Qr0JLb+PEnl zlLV#7WTS-jK$;~w-%yk_8xt~)J!DIzm#_h~;+*!enMXI2Q|i#HeP@|IqUzd(sZDBp zS6-KnV(NiXtPaD0zTPXV956?dUxIt&pn1-UXN|gaGbk(*^>Li3+ykXVTRUY`J8P+I zB|!r9(YMu02O1jxYMm3YwwP~(WT(_K%#xq}qFeXw;hUMqGS8Tk@{|e*%!%$)Ha&)xNLdS;Ugm6Y?eo`37P z*|KA??Oy1MK=pRZSIWHMXOfrkW>#fooLgb<=2c=DDWvKB^Vp*5i|;@9{gG1{0;R%( zYbtO4-tN71xZZ-d5`EOFtsVKv^lN5VcGSlbuMW6qwaOSopL(8}ZXa7c-qKh+Ml;@f ziWCkk&nbcA`}QLrg+}d}b6)AC4tO6T>*8JwY23GQoc|Z{!p}|=zRWO6n6FOjI)tBe zR4gni;W6Wch_)2PftUrB1ZjFREG@tk(ce1zAc0bByhJ@)MoIr(REXTh>cE{4>ZA8@ zeB9LvKMo4-Op}>5M=5L@TF;%TD-YUNP`!$wQsHbjGQca?sO+3gWfl}2ery`wy$OSCKTOuk>j#EY7gNzQ8 z!Wos$4Zi#kmu~N;4fgB6V+swc1NSib7mf%3oX7NxyBc~C|IrEspad}UMB zzq0x2O?(EXATg2rUcDZFTXg6*inoj#+H}#fKob%ur9aQS=%6&S)chHhD4uM!wK3f& zrxaVf6{XP9^t)u%dPvXJgFL1nftIFs;wb+j)PgUm1@&=fTXFQ>Zd*Tg(+EEDE>+%V z`AQmwIwi*1tZSy3soWQ;--;E!cSeGTy~fk4Y}0wW29zwc`2#G7>1o zt_I~2`)Q3Y{}5dg$_SW(gsxAw?l6mv$8nn4cjPFkONA&8Bv1<5hQ_%^U(34yRC5nZ zK?2)`M&PtKajH+0)N$zu%PeY(a^ean)13HM$Y;J#klquYzqu(ce-$EykDKd(kxi7U zK{NG{9zXc9^yO*mn-<%W2k)5i#@~PhO6ku-uQ&+$7f?CQ)=P}JbGxlnD5cNGwm2-^ z9H3r8D~^_*dI_c=aq`#sa`6d{!ZwQz+uZJQ$~w2(@ke zFC0r>OD^!hcpJvyF4Hb`obwmn)l#bek3cCS?Y#9CtYsk{Q~sZ0))NQWzkKDd z(Y+;#z1YrfFv4b{sF91;EdIP@M5!O$q;&f0zmvQrAW&*VgHOCZU#+qbwh`4wA5lP{ z6dUEFIZ@K*#6|6om@oy2P&yOQ=iLDo9TRhcEiLFy=PXE|ln2Gcb)uVv2qM4aB3Za7 zwIC8Gg|SS_%%IIA>fyHoJf*Z?nZPbcozwqPsB+HJL@1#0VhrdJ?e)%SzAy7(h zr~l$``WUB?tKOtBh$%?uHnc@pE#E!=m%tPx!l(tSR-YsPc~u{SK@Y>37PRGsQo5ye zVvU7}PP2X;#@6OG0;MpD`|tQrE06Qez!W4fUix2~xA^A(k10s#ZKGTFy`@wcAKkRK zG(Ilm9FUPfDQu^I{dTFBe}ASukigcYU(T|wIMR6jI$P>PL<9-&%4qS~8t4p?;9ZlNG? zk#4{gqCL)I#zRip-9H2KLMei>+SJJQ7Q7Vx)1Nm#|4;+x)jH`b4`TOu>AyZ8&b}nJVg> ztZ40oQC2Yi-Hy(jtJO`*ym9Nc7aI#Ne7u2F)Vx6~*S4XCQO;*~N_h9{TUr_S+ifp4 zE;>JKxaPifh4}H@5*6d0t0>;86B~@Ty)Y-bv2}m2RA-uH(eVx56bqZMupnJt(T?U%jq({o}X2*a*w@E&irs^!Bp8XT$TeSIe^a z5IOcCidf?P<@lX@x3j%u!kb2>D|HHL0inH_m_8C%KaNY^9bg)md&>f&Lqo4V zm;2D^(m&fbXJQHITVb97rb4;rY8acuJ~ql+O^Kv)wOV9pdT)DwfT?Nj{Su5>Wwk4* zxKcas@!ibCFF7tVCBXDO_w*Id`^%KtDC_6h!{{^|<7FH-rphCAjGwO-+U>50@vGPx zXjCdhUw-dhf zltvHzOkW-zrecgtmufkuy708&9WSIg&MmZC`i53flE;=f5s4Qy(=v79uIn8yr0F*& zKljukNQX}gRtMG=X{tcIC@ni8PE1JR1e}*}zVhf>TIhDWgm zdUmFY755!}X#W(eu8Fc?msVL(Xk4q{%ON@{8mbQ(UTT zN@8^2NvuxTXpXBs>C&FyEQ(R@vKLVb%gz!}xsVd3V8&%{%>FizyRgbzA9cRN8?dP1CyunDWllztPE9)}-5BNYl9i`EM`j z*J!*P5;Ks%v8@v}n)U`WW~D2Y$7+eiw~8pGuOGTpYP40ye?(lRvC_yB`wWB1ZdLOV zwiO3y`nLMb_hQKx-K6EI2`bhcYm4iZbw__Ju;-3rK|TgNmFY~ksq_`6?$O&``f~$X z6MO8>wUy*Q@IS(KYJmjiL|z|7yKc}pELSDo1J@#4qmZW6`NwzF>vCUdO#M9qu4=dr zBF%9P3~}n+Nwu|%ogU0-2ALTM@(&NWS@4-!K38}~8<>{YBn)T-k z^vrQz7MO&@cQI1>n1(#wXhH&WqWeDM9L4+FrbHbfdU ztRasC`XWfvEj@obsqMaC>5}Loqtqx`&o9lh7n&cBms#TbgmTh}@*Sn9ZVh=P(Dy-_ z_EBN=rHw~?B-idPGD_W`n;fskW%DxWV2Q~Np3>(>O{JP%4S6Kc*Fu`!KC9JUy1cTQ z)M}iIj8gl__xURa%wwMy$2cMMkN7 z8_NlMPfp{-lkqZ3+!+)qZ801dyS{YgkwAYAX^ty8K2qw|GFjw~xX38Afo|+1T`R@A zoQjuOV&H;FlJm8}qVqmi9trdfk*05$ZkZ|_h;S5B-@C{tRp8HB!p;8Ayy~Bhmsuh# z(VyUHlFi9FUdIor+6&cw?s(cM}qwMMWjj|ART zLYmens=3Ft!RnE|t};rEq&r@ljD9kIHeP0lf@IwuEtA!8bzONR@a7TH^u=Cl3#x?| zxXLJ1%D1GjtZkCq>Ri0c5_71RY)E>eo_*`WBY|Ex(j4~(^~6O5ifOI~TxFD6Np~PK z{7=d5=i_CT2%_GewX&La)oQ8BUe&sGTg|P)4cQbQ^R3x}wTu(!mllY4&NiFIY>9 zaN&`_odwby_nKz7)oVjEU+;!8N*(qM;d>6QphR4Zms#TegI(g$P2pPUZZ13$xW_@7 z?q9jZi$@Mj(8~2_D5KOwn%hsesG&S09W23Jb{BixiPjru(og+~H+VMuda5x02tDA~$~bf8p8x=*dQhYRUoiRTY?smG~3x>G%n zz&#++bgowOw)zLP`GR2$Wt7@ha-*#Gt88iymYD5tr_rjWl@(ohBydNEG1K_Cr$(!qR?DlQj8cv0zQxU=JyDUMgnntUdy8OKhj|A?|k>)sB)wFH2MtLQ=$|$v* zZXsQ#bPZg=t-de(K7QED;WHq-r*>a?D-M2@uu#iR3Gc_c70fi#^J zQ7_p{zR%)!E;34Wr8{@Je^rzG5|*G)K(fLPI zIZgL>{mM7wk-(S?LvysMX|$?Iv5_t^N)4nam+rTl$lqm&M>NCfetR1EyGURR2x*SH zK(pwHP2tj+ZZ0xPW%Oz+XTGi?G$9=QI< zn&F`QbAPS8if)DAtrzwt$M@1XV%zHNwF%vCij0)c4>>YmzAO=qw^L~Lq5CVn=r4U* znt3-!;f)lQxKlV>>kyTo4lss@NZ|bvq-jJArQ1|g7oU5L1eC%$vGo}8`zUeb>V8_$ z3in0*4ukEE2j2bgYF0=o@pLio+DX5iP?b)}7Sf6Mwmqq4OhJOZ0rC6qv7%?_crAR% z7iB`lWVyi0LPAPlhK#5Bc#D93P4H7$?P{H-+FSmHh(t2ItAF`LKH+>Gnj&{^dT607 zKdEO=O%_oKPxVnB-ISfgBcFzrYf* z_1IChy>_%jj<~GNZ_eH z(&YP8X)n!n&QZVhx+&s$_P2%h!p3oH_+RLz3!Yljz1M2{_VjX!(TWcFBA}Fh25CFb zW{Dz=#%M=P)6~bwks_WPBY`<_Ts)1BOEf-u+-)SB$XUzpiE~h@^~jL%3<}StIBsq2 z?$Z29AH>Oz=ZYxxPm8(yrx!ou4>Zp4gan?%Ax%-|4MxrR_Ly|h*iAqwtP@+0eOFHiGw6HB`;-_7W0M$lY&pG0<|?PK&4`FY#X_RVztfO3yuA z!dNKgizTEtUy=h%gMzFlKNy?Ds3RM>GxjbbJ%5#=Zm;MoVI1GS_{Hs=>2B>WK}$2( zn11TuYNn9q)wLVteI-mmf;~6L>{Enx!71vc3ceDiAi{p5`oD+$GX)5rtp(%((p96eDA-Cs{dKMD!ViQXO< z*hBC;Jyi-B`CdQ*Ju;*@ZvMs_!tdo`r2J(^D=2m2aw-0yTum6zE=^{M`umf_QNKh= zD+1yLBrwv9G@YM+S|zr3j+E?{4-ru6+Hs1zZYn3lk`9(AI^~TR7WAvsxQL^IM5W(% z^WT+1LKYE7b6k{{oisBwSgNwfk0k*zDpAhw)ucVY zI|@i(Y#M2Lw~uPQmTF(Kx}$4Ctp<&LIyPE|Ll+^v&7);kekPpty^1 zEgcnIBu?>aBvC!2$;ZEn*?``Ve^rLk{|YH2MT1tc&wjWoR< zMdKr&M}4gv-JeIP5;O+mErl^8KmudaNOPQVZAr;Jri(UC znX8~wM>>i7lvGB^S)3xX#Go-wQmvo>E&O&p6$y+@BTciK61jdb# zrtcJS@oMnU3EHAFg9MbqC@@R>=3`d7Od6&A-84x-sR`|pc5H>8w(a0t1*KkOJ(n}Xv*m2+B`i^OjFVQAdWm0lJrxOz z0wc|FW5@oY`HiolZ8=m=L@7Ut!yWr=x7>_$u*Af8cWqc)V{OabdMXka1xA{7UW58; zt9!jt-yW$aqSPFUC;on9nmlk(3jK1>fBNW*{y-OPSJfg~Tk7pdU=$c>j=MbUhKJ z5-Gl$Qsi0Ygas)wOI&fApp`j1Q0;N8o{9uUfsv-K*7Y`ODMo|Ru;5?;r7)(;5+z4Y z)mlwX7cN}Br=XNxk}=my@i~bpGD~D{o2tdoeS=M@<yQRb5;R zD5YDp)~RXy?F4JhZThT41QGX)^%(+Vx=7R4FAfH4{Q~WzW?Ro2P^vbaX1wThiXT4D z+JZKH9M_)u)rMZLMCViWR3tE_i!{dtXZdPR`&EJ92Psvv+a6&KgWLP4S){Zb*Lw=p=C?J6mTBK>5)B2P@zPlt=bW~6(isq7z?Mn(N zhIR zUfSn@`J}E&V--`7VB7p;fqL2^S4nbdYcC>!Qp4y(ATYsRNV=ix=sLfp_OfXUsqo1y z3Z@{zwz*G!JFVd_!BQeOOF#mpTGEL?k=11c3M!F~Yk5-2r{JV3n#3t4Jj=+-K+$BPK*U%c1#>5tf-@23gif79MvxUcnS3*gfa>=Mhrdo2$e(AL0chP)eb@ zSo&<&-!fl4r5Pz}Ux?AvIb@KgqAunOunNFj-Scj(i$z$&7I@VD=_Kb2@*FKC_Fa`5v zcd0#Tu6jpvmhY{20ST0CTMf16_xG zqtepc>YcQ9lb#5ef&{yR?DG1Scym;U=GL{jf&@xcY9GSi9#la|v*@^4YNq&o&p0ii zzP*SkNYp9%)Vmw)SSvi#OErc3P>ZLrZdwMWAi?e+ALQ;*{r1dd2$bU8R=5qIn^glX zI@ZVhsq}j{Mr%4^gNP|e1Q&d2)=L#-A?iD|RK)Mm+M&N1i3sL<-rn+n3DD8UwtqP_f z!R|S~*DR+^pk8wBP`rQyN(Iu*2)!q+wY1>IL*=#EJ^Zz$5l;k6L4w_L`rP!;Ca6ud zD_xo^NT8H6?GujDh_binxOB6t_TpL*ZE!<-5mS&zpgT@M}}s1aJ&+@tEt#`Yo-DD{Z$Fde4(YOrOTN6i_aU0m{7UEbDS#S|oTFVnUw zrZ0@gL}}WGUscCu_97A}RhRBC-Jp4Qlx4n}KYFa@b^i~wYb$#dQ;=YHsnf?!)qZq! zR7d1%E+BzYtlxfN#Z>KN8+T!VH>(4s(1)k*=?^stP4>iS;c=b{j*pxo>25vkYANSl zXUm1|J@(!*q`ESjp6Q0^5R;-4<{6$$Z$|=iqL_XzF+C5_>&9cVo^KB2i!`0rmX24$ zf1jX@$wS~+L7L9hhzKR3!AwsDrR1tZ<(A3im9wOSC5}D2rM4XrqTQ#OBY|TDY5K+% z5q?Bu$9ghju$|`y`Sq(J%1qM166-pb(*hm_X@N$Tz_Efft(>`pfe4i1W3R}A;@-<; zNC!(Sy6U05$!w|(oyZb6x{#)*GZ8O|_(lXu)qeb4PHlTqp71JLW{H)fyK7^!i)vwG zSOP~E(sY_Z#CRg|5rI+{=ao>}Oj#+Xzs#0d!dO348(!eJnl+RqaC9L}o(vJwh%gTE zR8T6Ua3!U~qz-b{i)@)CCUl*oi7A8CoL($}qYG)$LBzY&gVnQrJQb8`H>ZYDgWGPt z|2$h}iSLt*TKs&2GCYVS-dwM#yz_hNb>|tiAkg&2$oLpdJLfLA7eCF6a~!Ei)Ax77 zrfUA39mOrJJQb8md0AB{U$Yc{`DwPy5^FsowGqXW#Z7K3fxCO8>1|meMiFt82$Wj> zsH`%s{xtr~lWdtK{%G;5c5c8M@kc$Dz}-F4q=N_(5wq)hDk$YrtdJ73W*2|{akk77 zTmSaehDFkuS4Eb<-96GYqKFtxgj~r}L8*j|&*Y8W?(sP}*)mH^Yh7QnTjnEOEy)tN zyGNSlL?SpMdJ=(B2U0cp-2*$JJn3MGH!gPC>si6lcL$ch-96IuMbccNctKAlYEX5; zJb6TRX<@{pY?&ooGj^#nMu$uDe|Rti?(UJM--9F~j)+=BpwzdCjpV-dstDN+vt^dp zwZUC2v?f{#|I8A&yGNSiHWE>o2#pAonsj`GIcPvl;dj!(5@)}ZX<1h>N(S`Fhk^vg1CXZg>E{w_i9o4K(T#ZBRy|1v zO9W@^5@X4_ho~M%U_1b6x}TU!WD$W<@lo@5z0GHm4wfk3YA5Oas_Pe)z<2=C9G5Sb z$WH`HHCnIndf$CWI#^<9>-tiD>g~Izmmq=h0HkR($R%D7fl{A0J>&H;IGXw{OPK%m zm4?%(T}{0m35*9IO}} zl!${w1ec<95F!vkIb{WXPJBr^SYo$Fq%@Ld(XN$Q0^I0vjoNikft~9bBUTnpwz}2H3bL%r(RcRZfA)S(MGAs0)ujo zRs$q39)L7``;&;-v<_Zw;mO1qzRjs2RHK#i7Ohb%F|X?+=_{?ZH+)zE;{iz1{+x(1 zw4TqVbr7X06{#e&Cl4Tp)>@WGs2?hgBcCCPR%awI9)Ps|yJS{k2oWeXE1`tYnmn1O zh6=F#1y2=aZ-kk5bw#siS%xGlNFLLyLV!ISU&TJp&5kSD_uo3DCEFUW^07Qzx3 z4?vn?OGLaPBAf`6+7Nez*F8&_JTjKp-MO5kd#_34!y$q30Hmq!65&UL3lS)_(`y5- zd&pDBvt)^9&u)pnO(JwJe9R>3i4cKUTw^G&d-~{qn&x)A)g;gC&*_v51JUJOp}r zNK?NW{HykM;T!QljT9cGiqnZwf!VwHd)}24mXL|aB4TQFmOxJrXpR$KU*uqEc7yQ@ zfu0`HWUGQEHMv;0^kU?A9;H%yHkPF~RfJ()l@yjpy}e8AxF%fk7?Z*f=;9?2b#_k?PztIpoJ%vZ9ZFZsF zx{ey8gC(*`{AMBI@(}3hAx-zM&bW)=RF9K!DLhKW1~=w?$W}E;2TSZAVl)x1zq15- zdPtLhb$gc>MAqF#r9!ErbkgKZZSF-nSYl-^aV8Ieo*vQ^r*3B_MP~#{N65M;^@&cc z^u9ZSbg;zVL`)%~YaRkUJ*4TrPe^@9A0H3GQ+SjLp;Ie;3~nPGED=tGK0dlqzd`~% zJ*4SGv2uH<7LD5115p+-fctk z6%y#_Ax#nbwNs@rv>LRfSrn!G>C|d6tx-d0ZvUCkSDbcv2=w%jruphG`UPcL)v_E? zc$9icr&g0_?R!ExSR#&y9z;AX@PBmuby!x*_y3P?J5W?q3{(&dEKDTsx%Vix)G;wJ zk9{muEWm>vTkJTtVja8iM((}$*kU7McXwg;Z*9=e`#HY8zdyV#E@wSv?Wr|uX4cFt z6X@w7ttdMtkK((|_At_(u3#v&oldRhk7}+Br1@1QHWP7@h~dv<0zEyX6=h3@{`_T) zW5&wV6%3`q=+tUP{UzEf(jgO@iFisxeG2K22^S(XB4$O&1bTW%Qw)9e$?6|TBSihdD;P?x$^XRCv{qUDAnA~awnT&y zab%E8pr44eqMVv$v!*_{t$<8+&D z5>30WU?_Dh#}m6*j@P6^CcaP0Buf59;2t~D^m1hN$wo^mxd#y_^|@g$&1{eRq(dfp z6VZZ*gTE2D$Bs1pQmo4jBavEgdhZnsr99{?&FokENry~SA;N6)%~V%N;2t~D6ooXz zS?r~r_?%i0rJgUisF~wq66uhM{Y03({rqnP?y)1SDESpX@s7q|ZR&|A^{AMlZ=-SU zOFCr2nTTgZG>(=D++#_sV;Q-7Dx8#B8_vIs7k~sBBFjHaE~2n zIx*?cU)&%I_dR|ELn#}bzAYfT+naRA#C9S+5TUP@3EX2xT2XdQ9wpwBrQS&v4yADI zBoj6wHWSg-E)%$RLYiKhYGt$LTNW)GJG7I=8jguPiH|JdjotLXJ5_0|_IHlSs?)#` zVr(0kKq=WWj9+q9os*@f`1DUn1MLz@IWFDDwol2fCs*?%9UZ3C<##4}i9-KWG|*Zu zxt7XWwtTHUzFy-uOYITo%fIxgDt5M&3CtI1nhlyb^NJTkM99EDtoT((pl*7_V?`V8 zk}bdJ)oPrEa}mxN)_1wA2_trCNw>_p3i_ujKfe04kyJEMn!Qk}{K=wL$6VtyO9qh| z-k*EaIc7v#WF06a&$X?`4&@i;EHgS3NR(z_BqpbpvCe-}P)odNepQhfqqyVw9)^qC zI1TecDcNVJyJ0Nvb1%2CJa?kxO(5ZJxLe=HJWi^ep(FdA7`|2a(X&#?FfWvneV>@t zQG95_JnGbMVUp*CQl`FR4ux364YM5E%SP}8KbEPJUdseZ$$nzTuLF6&kgaOJruQTd z5{Yi))!YbL!rszqQc(_ibmM8k>1yEVKdhJ+O3D82Ip3Ci-mQW>pvwZu6Gmc?{X3gm z=>+R@-7LpV*QVTgkt-h&7NcQaC?)&tG0lAWhFUdv!RI!~qetRy=L>9Ew|A^WhK^o+ zJ$bu>_4sDL7!C76DS7?Tas4j!ZrC7R`Ba#+!oro%vrg5R-J!H~=QXn&3l`K>1E!4O zxlYOiO3CZN(}xSGp2=&{NObbe>HX!hhxNXv*&cxl>KYA5$M!Q}(i-{FlD_u6 z0q)jg^d*biRnyF``k3)mJ&CACMAwusX~m0#yxP9Bq|mtQ++KLNi)E=SUhCZc0cSDr?_9d~PRSH<&f zF8y@uE;cA*d<2%Ey``oUZAc>u36zremio4i66P56EzwTeJ;PnDe7d_nx&9OX_Zj2- zWcL`66z!vzsvr|6CC@k(r~V=&J=u84+DS7c&SVi01@s@C7i-;aoBgVLhc=?<`Fx^S z6PZ9Mc|Lb?y_NJ5EEd2)&n=9cO4u4>;-J8ME4xs=JJ#y9bIZ)e!U@eSEA$(B5{%W@fPO(Q%Am;Hr@4A zwD2SyI3r`eGBL;Dgf;$H2%mYdh`=6~+_RLW_U8iDrey+jx$jOm7iDd=H<+`@#RQH! zBrqqMo%e1~_l2!eT`u+zXg|>U6z#T#xy+$ob-i4JTCmBvW<1{ode>mXK?Chzfl~Rc z@9!>T9k0~Tk*4#H|2py#leViDZXPhuIwOHO(Jxz9_3()foaJl2;%XAV<~y7RarU8C zffKK*NmKkpwwiea&iWPoyRo#a&idRNHFVi$*frS6c&0TIADWdA*lNaKYwX$gyU?$L z)z;vmmo^cwcAc3}v?pod$C2IBXR&xbsF;EKal}sFcIZ}*S znB91~yRm^%D|}1o9p^b}R`Nw<3l|m=DHa^*W^DSD$G{XM(Av=(LYoGPO^uft^K6X` zltK$96J9$TiUsba#5Aq3fl__rA8L<>Uf2GjzAM|rD(!uQQ&4sBOv!6t3KGAqyqc63 zma0~9I;fF>QisDet=!5i`VP_|6PHUA6_^!|?VXw!xJ+5vH3991L&zYu9fDSo#+*J|!D zYW1utl>@(BCL%S)4-V_A2Bo+QX?_iLwEmG#SU$Q2=sVK0THXH{$~w{CiZX9>O}^VP zQk{3HTE<-aYfaV-2+WCI)8$S1hksL;M@LtQ!1_U2Q636^-XLzGRd4Pk5m-M+lb4a_ zi<&oYA)a+wC4qg{n0bvYDVM~qlJB!_&N|kmMml>~R;6+*D3gt=1D$wu_HqLK4k8LJ{*=-CW2ZGQs1s9!)Kl45`m>fnttD)_*x@; zp9k;0vX(&4BIyj%dWYw>E~GD6Um{++U-AW0GJ46@0`rY)HR|#%n>;eSrC)vt5||VH z_SwRsMxO`1JYRuo60sy>nOICts_wC;>t7HgWk#7BWg977~S=wk>KtqBGao%1bUfBE6Uu z!%{~_|B>n{G{tgjEE6{0Y7&91hP0wgboN#KyI4en`ks>SgZZN8q$r05e6i+qRz>1$ zPk~aHuT0#DnWOf2FiaeA@1kQ$&$QzfC+Gb7O0U+xd1PK23-Y;@S_%JiQyBU?=wGF} zk7u)5eb<`5=|MA2==B(0DPIojhvCosaTb31%+Z?C>5BjES3PujKIh9l_|#ri`02y@ z4V+nU?&}@Bnhgqg##*N~CLNB2PpB>>+wz@<_8T~RAuSW-KkPCbHVzWJ&l!Il2iW^Q zxsKP&a_q_|$NHF6_Wp^n`kYZQVm7t&<(7_mjH9=XwTrDueo2=8!oTwwEg=55fl^3g ztfgwIryYGgbQ+qn~6&J#E4eKiT z*m1krOO8=5L7L8^dRDW#%xz_)Sw~BCh4mxrh;6o2%bFuXoLIEdz;EBv_D}nifqC_M zqg35x_(V%UJqNvki|LVle(S1xhDD046JjL-^F^AXaa*orv$Y}OlFtT-zvu*ySwxQo~zY?q`E*v4!icK<*Kq>jFMz-z2^SwQ;kG^r= z!1}?O#+)cxq*j07_BKxK|1QqJZ!b-~WZLZ4TG~iem&>tJY0C%gIHIO)J7S=A{HnQB z4wL>!G~Ki)?86pD7+S3-F#>fUjr!;w%d{Y$M+4$AcGXY{^OcEnao^N0^E>hd<@2j! zw_Rnk%iK%a@U%;vEFpK;?sGGe@`m5HUwWO&hIUuHmvz2xSCo3E8}oo~Zv5Up7b_Ad zRrC32HtY=dTij}M9a^9FoS?=#M2dZ^rWI3=n2`Sg^ZVf8pFKl|c5Zj(taT&kchxua3k*1Z`tHwNMiLyN8 zaCuhoS_(T?x4bs(+VR~M>nS$kuacT`kNfs(B@VFzyK-m;qvLkdTS)Hh_=|a;49lk; zDyAT@dGtkA;PG>NVmGq|hgJ#X)0Y(%DZ3j>1WGwfI?0M>yKXPOxFYHJF~(-N{}?DH z=h*ItDM*YPc9Rt;{MkOHS92nswd*JbHvXo*xL-uY6eREq6=g|!u-LS+C@;S3k`)P* z!WyA>oyYX%m0eG(|6MPn7ONb=Dor)CNqO~zK3QW~R5e|@-v7RR)wtel(2yP4=Be8f z$iE8i#E*CVt`_@t--;Duv3bn1aNbTT?T1Y|YRybXs4L^zMvdG!4^{K&duMW-u0R*G`W~ zARRYebr5Ave^ozwmQ^tY2`m%!s~T>G$K|p7NR{_~NT3wfA$hM(&21a~GhfriZ$|?4 z(TJM+LmkaO#y4%i?!c+cNOJ{oUY4mct!VHBNui*#t#X zWi1rSFRog{kU**M@JkkIckQy{O)7a_vL$QCmMkG#f+dGxF$D>%1x3kyZlE~Q-li^H=pqp)g*8II)wnmvHZ(4?J+QP$pg!8Ib#gPBZyd`f zpLVf6PMw%kH~A6$wpO-1w%L3An=QSs?K|;3q0L#3q_+7UX#ED8brss6FYlCaMoqWO zl?asjmu3jEa@w*hAF1R$&Wz>9-RszLRVb@s3KDHe$Boc5t?D3CM|qdBJTF=6Q>WlkZF$IaRXV2|Xqb_QNGy2u9_PB5|o*{u!SPP2svd09qp+h8h zJ6h9jrw_fek zHmcLL-~spTA8YN`mc)+J?oQuBCC^Rs$6=a3%Fz6QDM*w$W7o1A9;JoR>_hu-e@#&R zN=1sJ-JNwLP|7oPi}tzEQ0-yHY~bLXqSm1P``5a7h6GC88oyCfQwM1GcCDkYiXnR# zPxZBXLQN~CNCcFLRxEoWMZq_vjFhlo6$vaydf0lc&!DMV&S;HvlzDr`NT%KxJGFxq zQ;@(qq`21?!L|ioGkqWY5-d5=^!tOUi3v@*Mf1=+53J^R@VW1*{oU-JgicY%w81Z& zw8y>g+tX+sG5>b&W7h6})1!IG+!yqMeO72lpwze;moyjhWCr`Uq;h0<0NuYEO)uZK zVhR$AI;Lut0gvqIy)tx+vKdZa2Z|CWJQxxvm9N2Jtr+<}Q=WGq9XDxqewp&sXjrVQ ziYZ87naGN=XmRM^d23qJ4pt;kYV(03S~yvaIm5@0j&oOC4aZhv`5Hle7gCVG8c~$i zTZ3(_qB6$^ehHQwY4S2AoVR+visHuu=USW7e6efx-lQArp6>42;i48l?QGKgw-0vL zDR@aspmo9=@=NKg=*(9&->VM%MD4OF5-1fu;GyObrg)dnAZRzAuQ_~PpI0(WM*^iT zWV@>^n|9WJ(9_}MS(-YAz3w2&7A>n{3KFKi6K`htx9M(v)d0$WA=Pkljt*8NQ0m$K zG;Isbi#H|?ARXQ2#)vr^$L|@W^|xXQ5?Cfhc|I*#49j)F>RV(D`9we8DpX)1X$ zFDn02C$qPoCVS;d_6k#wFxx*O-HBb!Sa~^-zdM@zUGFO87!oMuNwZB_-SVvY^W&sr zSf4C=e8}IeP5v&XAYt|^Q^(2-9o@*kT0#ERMe?tZKq+$+j36I!_=v5fW9PVmqE|_q zT5-+zjPda+MIxX^=mmk`PQont%h&g)r&Uyz4Ui~Pjzd8SDON;SPTRXbWR zk(F#?68$Luj!tgs^;NPClxn+VhDK`x_AMsCo9>uU{!PgrU3Yn^6;qJdaAcGgm||y} zTAMm1QvUH9$BKOoT_ggfXl*ZUx)! zWz8foU!-Lsg4X9*X^c41`rP!ddR{%p?(V(jP3r{HLt;Z#pYksL%1N6ReT)@qW!A3g zAt%hMV|!7)tcnCmnSW=qTxI84m_#k|kiVxl78cF!_dD@R%JiaWe6lf>Ur>9jdsRey z_z@&}94w?_3g%1J!cOxSJDl$!5l^~(H&)XaS$y!m6;qIyH0Y82Xs1+Gzoq$A8|mi2 zBeFoXYOOFW&;QE{rLYzx( zIOZ;r>z8bG6(yW(Vm#SIgKQ$EATgijK$^c;qX7yL1!)X^uQNeiL2FJ-K>}-mMlG#5 zby{b=)2`;m&mt+#hm$7OhMu# z?E#si_FJgg9;Ke1*T?jY7L7ZX(vd(Zb05XDS9+~1q{EMPYg1>9H>w4^%h)gZm4ZYX z?fVo^PqC*N<>*NsUvu)QYd7m45h#VVKMEy>@_ zNj~)v@~M$PsS~?4FiW;rmN$d=vZn`_1(s#V<`F5F62{V z3KFKi$lFtye}>QCGS+6e(2nq#v)lZTK&hj7_OZ7YCb2V94bo9=W|U}Iq>OE7q5LYQ zAc19~-x(!)b%yL!E3#L=6Tj*Q>y4rlX#R-!xhI49{$7q>G~Eny2^DUmocW`WA3m7Z za%vBcvwhjX+~+MPYwc&7{vOBL=Q(eomkJACuzp<>&6B)l`yzogjWqpUQC^!mp#MNV z)h|wJk4l%;GLQBn*>2Jy6aUo@=IzTC6|LsymfAda@NVYaU>0kh_q+vZ^1@q=8^OdJ`fqZHPUOn6cLNAuX! z+&$y0SXW43PV^gYr9yndYi7oUw~jlTG^G7Sb~)d9%b={+EiMyJvUK|U!)$;5Aw^Tz zT>6_{z$_hNTTydX#u*C|Woh+LI^Zzd{2Q$(Q8lLQ?YDbfQu>b=jzpe`tL$!*wzJQv zX%?huj&kf_nOAa`mi{t^qtv4hh5csbNno?q{7z_NIs>|Xz3U(+mq(CW8X_e=JvAJQy2OCHkh z@5sR_Q)?>9{Jnek=JfpJe~WbVclvDkOl#ODuhJ}m8&_ElP28?c+LvZ2l&9w2Zm2Xn@xMPB%b~E^r*#u++r>CW;A=A(XS>{bu>zO zIa<4RjuMzs#$~3~!(|I=NcIYIqPGo~2iv@U{#GN_57ygM+BKTC_-s<^&*oRzp9I^s z^~o#;5-8<08PdCmQ~u~#NApW zDy@6%{o0iAd&5SFbZ}V!Z8Jj-e2$fFKGWxi_Q2d zmy3$E<@i8j?!nPK|IEGqzRT`w*{I}5%f!9Jl6;VNtUfn5kbj$e)<2}aVQESe8(c90FOHJ^2VdDOCEX*_$<)yBHLK5EIC zWjb3pb}3s!UJdOU)R<&#^)<}8ttiE;fro^&OjNCLGU>+qjY&7C?;?Rx73ajT38CZI zgtKM~K6}!QZ>V-mW$h;zI14)@KVrvkPfQ9Rdw#L~8x{~e#a`~NS&sNb7j^Tq?Dlmz zqIesMbXd}%2z!=8p2KD0+~`2tq0X7Li}U#{@?uhRUbnBJxdio*P5l4kGvF7ZZo0Mg zh3sxXrj9*tuQUIdCA2WImgaokD!hnRm;R1ha+YmOi_mgqcmVJJZQ(PvfdXLx-mg(a7XsNj>izi2OH(FbobLtwJo!!Y#960=@=1-&R$ks5n>cTbc z&or~m$Ca68&3VqIkLe;4C?)rH=h$(~U=^)R_RAgs>XV6KkMC(CJm>2{zGSK4OH6-v zP|ZtP41JY6YM;z5Z>?^`8aDzXB?6^3=Ko|#HlAy1GOXx=Q_rmtEmj)Cf`>>1N@1C3 zXM532J+V_2>m*gSC8z_xkbZUg(w{cB)CC#sfxZaZ_LH58Xr@n8hss3pK9(R`^XZwr z1f|eY%f#^$*|fOWd-}Sb(UPS`eQ1LzZmHNcRlB*uSa_?QKq;IVWFjKEqxH!4_xi_! zQIeNodU~aHJ81usCtK#&6|KlaS8d5VvmCL_KkG(FvOTtNv_#;%i?pH?`!CezX7|hy zg;MAT$wYKQkgfJlPyY&?@T^S8p+(S_AR&88Uy~b%oRvQ6J-(OaNT3vYQFQuRqMLDj zR9@WiCG+U?JU*r#J@mTR#I+7h=`tUxx?w(CA4 z{oB`Alk}VjltM34Cem*N+Tvp~dr3?3yg$?_&q~pH3H8au#Zy5xr!N0Xpwzu3XSJ6p z5$sCFSGCF#VmtYh*hn!;?P-Pe&yO?<>XV81yDfb>Su$G?36#Q`rt_#SLAKUCGrwxq z)pOb^S`QW`9Z1W>ghnAYr)HT1`q4lS)mUca+11oka&4RR|RP7dI+w`+Nkiaj&^$wlt_v)sFU(c#`xfR6|=p5d@{|LKB z9t*C7utsP;FHh%P-HvO293Cr>m_cz3IcWE^9_>s#bo^weU!!B4(#;vi{at&%=UejH zuTVKKFWhs$oM`>gb&+4blUeLHi9o6PS?}8adwz^{b~ta5iE}gZ`a8tDOu9n^?tUPF zIVsB3dWv!K%S^S|>b7t+nim>}DsCYc0EVZJgEW}Tzk4?a*Q9Pc50l_h1Of0Lt+ zSX;;Qma@&JSlr0-d;i94k2)KIZMlE0YjFn(33)f_k>!Hgul#B2$RfQt?sA#F$iH{o zS*@JsE$GS8t3%~ivUWrNuufYZ!%+%7J(-Aa6_6Ct<7kq(O2vID%Ye-m?e;cy>>PPD z?ycDVzZ2MdYJZBkn_V|)ecS9A{R*W{b}!CKHd(`Z{14IQ;P|Ax8xJPkBONG(ezdIP z^y?to@iCe0fnSAEQ4}@cL%U%MsV`6r%h({>_@BGAn1aN})ChKL@mc0hZ9`Gs(}HZd zoHBJh-r>N^-Zz<2kd}#&d4hZ{T+WP$$5umHChoKjvT1IaI*`EjN1A@Caes5$)W(?v zwmI&qVaqDYkvnv*7V^IY?gArCcaaZdw+EDTNV-n#fl_CVZenfueM+ zUbT~6{6=he@h>}kP-Rokq*;(wlr9IWsn6HtQ!AgNHz#4w8+)I;ziU*PZdBbLs7|^! zSYQegxFVyNqPOAxBXVx=e@0)077p#XY<-%pnU*yA?UAJWL}2g3)gAU2dRydTBx{g& zi|*za!?8}Vv_{UIY+=ezGLZr`vvwQMWt zzYeO*>d@8%K^IVj`lA{#T^df0u zpzUSf%n^nAyZD8uo8kZ#6|gUS{LJF^J%;1j0QX*VPrYSd{&|!3=F2(L`Ya2ygfD$< zdH78xPzqNvin4rXh~?t7CzkI-Uy;`PC{%Y#j=j+PmkFR3c_EjcO3U?+I zC2m*|*0!B)@gV|JkdXHi9S=nL$Co(e_kmgv*B`heST1>!cD(U@`%&7nR+Q*d!v9Ws zl%Hu!kU%M1i_q$BTVb|4cBl1Wwiu2nNaW46lU}@ix3^Y+IR?FM%~a>6ZPe@SA0`nf zRj%R=E%(K;mNhGn5mEc|YinSKVC`V_Xo)~6^nEG*>Tql3c%p}%cfP!0K?2t$)UO&> zw8YOpleC*kjw$F_qW?&iI{(QeuRZ_$&u$djF4>keIkYUvVSaehOVWWeC!Q|htW9s} zr3Z;84~uZi=)wkisc2ErFI5yRcc^-$Mu8X7TN^2pE&Lt0UM3stg)ehyI^ zM~~(>JL4RVG|dKdVmT?YF;5v5XT_4^4KDfC*6B)V);DyXT6tP-0|}JET`GEakn%5X zbK`SH#z}YL@a~#S@KPcCjZsuQd6cYU3KF>QM?H~ZWGGfflnGT6Q3`Ln$%J_)t_J>B1&P&Wn!@2M?AHjF?v2v)-eSMtP#55RzFyHxE19&*XCAn4-s#0nXxTq9GiKM zjc&41?WR-hdQt5nfl}Dt$XlY?ElRaJlWG^G%&4GW_uyorI-Rx~d2Gh_9&tLRAR+G# zCc1=j*HO+QZ|83|l)~F?GV%TAow(11W+q|^67nu55-5dr^&7D$S|}86;4*g89!x<3 z>rhcfoN_hlv9UZnCeDiYyzp+9JahhvXK3_fmM^9tfxZNtBH!rCPx2HsXLb)?l*0RQ zGBJYMyER28+@tLv1r>UPP(aw_v2)uF~u{a^cyISkBieW1qs;$ z$aS>0=+pDGk$Y}#>82jmn@l)SJi|AN<_K;Zr(+5dSci)8b&O4=o0ELe);M3>-^IIK z@=j`NQIy+ULiol{$g||<1bR_)?~ZEMjcT_m)hsx1P=iX*T$eO8L9fT zrXYdq5{msGd)15Vl?$~8N@2ap#3q`Z+m$WK8_dsbUAYBH}fqiS-z{Ez1`=GFnDR@6lj(}Lk#)@61U5(}~;-q_b zSXVN!i`pZE+M_YG2c{r_wVqK9gUZ1_Bqi&3Dr2r|ew|0*{V%$2@Y7x$S~kTOQ}8wz z=JbE#qx2qkUra#)Pl3palD*3Bm8So*JhzHcct1`ideVrUMe&2zhQ;Zaf&{J;>0FJ* z$3U8I$5VVFO5y!DnK(}QJCe8Go#GQQ1qrM-`YpPF(PGn!^VT=?+e9dZ^(GUhbt5a6 z5&enxx$y29#xT*@1bN3@0)n|RBe#JmNXX|nD%Ea2s@<+syC{Ws*JNTqkJD<)BfW+D z=G+FRAc1E{^m2>S1>LmP6vdi|Qh0YwCMf1rR3TsV+S65gFa-%LANf8&UmLs;?2$ z+c5_gN?ZdlSbSs|bbCu@vu{57! z3f_;yoanvRuFmwUy&*hb&%%-pByf*|;xZ`zswZ95XMN(NTXcBaO(vdGJatjGqN4QL z+|qst61aClambYa9kTD~{&CWsIK1s96Q=bkK=n1A+5=ONzC(jk2~HvK%9c)v)yvY~6>~IY zt73=i@yXF_Ee~X&>Nt9Js0Ov*4XWV-{&70$z%2f@Z z{@XVuPRA4^aDPrwO#f;)`B$}i7M5!yV6C7hg@*F$D>%Lwcc!)`M?p z1zBN4Cm&2f0_!ltQVY|AEniRd#YlU+!Da3_{kq4Nv99IjZjoF0@e+Yj=AP64#p(Bc zXwh3WttH;H_2D?~{Adie%i_rj21e;qXbe7I?8Dx+7)fI=nMPD$>haTl?s)yuZthI| zy1ORp__YV{Ysc%Cb|mC8$X`2N4nKFie&vg|-DCpyuP_A(JhfJoF`}qgSSmzBB_>-@ z3Tsy;ijnj=>hX<_CF_`i1hx~s_C|e*(HxTePhlN*&+$wcZ*$Ra3B{D+k-qecQw<6U zw26}kH(~?FSeRv5l#XpfUii;hZ8Xhlm>1rUL*0tfn|6st&@SWIK`nohGCO5y!DnRr68T1lGK9BEd=6eQ%6YM07sI_^7CZ;8 z*JDf4oR2%$fi33Ak7IQY9`^jTapsf@$CH>J7Z+$X>si@f%??G!O`=RdQ|^?buR3Q~5ss%; zCwmmi)44=VWo?5JfmxLc%atbb%OTB?|^0MlYg{^dOz)yzp3MTSaDV*z}33sL=49h zzBQ8_v`wYgYhCDG$*peh?Nj=#)~q|s6UCNK?^u5nnr%%x62R#JuS(p+qJpA2c&c0O3@W99|vvL=49w-y6C&%=~9xHOLygX z4&3a~C^k}y(z;j=SjN0*#@cV5qiwU8^^u*<})n(_lGl#1cE#Xw}cz)hR z*}*!DnQxhp-#mjf0*Z*hJWir@v7#K$(l#C%$P!CWV1I=kuvnk`!*1^F$L58YI=uHe ziQX(kB-AdUB2mJr0sH)E9&1Z|?B<;IEd1ki_Jn9fnSQCD7#Uto#HGHH2$Vv7it=GY zNi{NiH_>jvLj!FI`c!CF=)6|X$M3ba@VWI)tJvn)nnj*B)pm!@)o#u=d;8lw`FUT3 z@uwe;O9V<`k5QEBYs(AQy&gRK{BeY_($vRheR6 zqTR^oiM57&Hs+M9&o|Y+rQ&%%>XV6hrJXU}-Iu?QsKnh~zOkHWu~D1+?VN?RKW!Pa zb))97;F#3MXqCEUsveM|iJCrPv_Kt5%h3rl%bwA575hp8(6;C%h|pA zG13^sk%}XjPQ&NV)6?`yhR=~P0`o#C>@kWmdS?xOJ}4jG{OGlcC;8aNuKYVsn`3FH zeaIMtE32y9%b^e-ICGEGuh8Pi#Oc+odEU-P)p=)6NIKBkp{=Cd+HyhM=}-dgAAeHO z_MsHg^x9jcHR`jV7UHivZ&mb`a1`O_A`jq6Bp+q7AnHLTsx7Ocu6Z_uuRSu;z^_8T4ZqNQ6}X2e`Es&#>HY@> z#uuPI&l)?m`ej1=|65^xRXNAX!g*bk%BR&4i%Mb#06 zI9uYpOJ3iiAf9{pE2BYyeG-9EIBU~v5LJnXSY1VjTo+VK!8!c?qfuI+y-_SnkZGy^ z=vjeR&Qn3mJ$YQk$X=wg#QdoxR+`L?We_ocR^=|$tYXH64Gg6)Uzxb#d`CSnvVusf zSB7KC*h9XWvTq67mhyX4amS}iw67PcTN7+C0wdb+3z1fokjVM!wioThm?C%8qCIkH zb$6~|;WQVykJx8_HFy(q{>=}f8*aYK)ZTw|7OMS(iaL-+&xxX5;&L0ym#;Riv>wdS zkHYv8^t&i#V#jG~UWdQLqLxW2=7my7)31Ox$zp`{8Z3(KidQj3>)~$c_i#JC!*alq zy?lGil`q>^JNldM(HoES^*8zprG+68C?!X|=uQ7MHcsgveCu3MF{Nd#bPF4{o>iuN zF;-PkEZ++W_x>%!{apWAF$FyU^bDw9?W!T1TjUd6uDw<aAnvEB>$tQpmR624*&(Oanq!7fz5bLBk2_sayf{2aeZOTItMIiuD?cJa?{sZy z#$MJO+RM7scQK1A*o!SmA5UxN>OYzb%Y`@U*x3hE^mkC7tmDr!?!3vSjYh3%wRrrg ze_3)wS#90ka~Aw6q$!s3Q&nSMOKuIr^h;!) zy2*TRaqH9}qkn^99QzOU66`&6BiA$7R<}}S#1=+PVLVj-EccQwguP?Y8S(AKUPN1+ zHpi+wYa~Z0jHc2{c(5C351Ggy!UlSaR!i#e<6h-`@dmlm&^6lJ)qB|L?x}t^=w^9a zy5G6O5=i4C#kr(d*Ef(4aF4elfstTHQw(GiXAyTXga`Z+YDKB}2Zn1i&Zn_M(^LIq zqNi7ik$Ai>@3}5TLn)*?-z}zb`(qZjCDo5^tmoWmB)uQR-~Y3Xp%m7eOq99Q+IZM@ zG+(hu(=Y{z&#}Sw%YEOnIR{N0?JBt$w@!`aTT>P>l)^TUiLWDL>tufu!?PBQ*DwW% z)3L!8Q^(~~rjGhfo>qU_-@RO66hkR&O__+l*;<|1Wi&tIFhRo~2UeZthS zctAb9{dQ4bZAZ73J(>hc_mb)TtHTz4Tk+!6-xskUfwz}2)?HEhT2x-OSruL=kZZ3} zkFc7tin!RJ(8t~zy$ z*N{LdTaQ<4c=wZ*7H+1Fbn5AEJl)hTBNj1CL1JdRckK16yZ*Bum^xNZqPJdiT(G|T zplL{;)Qkh~*tWXQc2<3KmUNuk8^g5%p86!0Z46V8kfT_SjF0B6l?%F8k+T{SC}rw? z+Wn;c_7+penKdK%`iVo0WVSD(9KTYKSaAL!JL%$~?YL={L+uv9-8`2YueRRID90}X zrOY}U__T@kHNw;pGSHiMT2e<`@G75Z_KfYT_h>yF&id`4Ug$@6=L-}I{Oun7R_Btu zbH6}Q>Gf(W5*QIL-{IX#znHFE3K2)$LaozitZh7>rq#cllF<`?>63{_uM{=rcweC` zJgXsrQZ30cbh1CzM(j(Wa;(a^Q+@n?kk~MFE5j5d@Rl+C?$V{!>h`vy#g=uth6GAo zBn$VU?^|u?MpH-KN^Yvd>9OJgz2S-}NZ`F>T1SPCuX8ayM)dJoqalG(pU6_1I;yNR zb$oR4)I08v5j`G`V3>kL_vTaVH#@x1@@Bl~u;gZIqhFWNqKMZ&8WJegiDn$Lu8OQS zb?lrw)R?|=q;Tz2n_&tP@?GRoEX7E_+*d4UR$oH`rRLF`Xtr#z?WT?;&n_6%JMiVaj(st1^@8FSp9i| zqywc|j=!auBg(U6#;E-^NW6B~X>5v!WSD|PLAnv2TQ%EGKl(=q@9N8qTX*9% zBv4B0@k%pC^R8f1$LCXH#ZsEnBZ@6zn1aNOcJH)D`R*kRx?$>AG$~qa$aX;wZmMfY zpwyfL@3aHS&v#z>$JEixGfI3&aa5PqY-z<5Bp#f9sD%{wV4?R-9TD&7?cJ?uR_APw zBm$*O-KM4X*k|gf)2$$%*L#OnrgbYZba4!OR%?Xi&d2eRPu+q1>zub1SiZW&l22W` zTZCBQxm+DP>1IYbe&vNa%sMn@oZO#H9sa$#im5r?sdH|&pqEenF9iv_EloFzn-36s zs%mP1>W?J?rJgmSmtkmr@9k}RmhA#Ni${}ws1urx)KLdYnf=Y2gMZX8=cvSPZAJ7G z2X5TE?Sm;uMh>gl zOSEon`KTujqOJbGhABwgBw{BKWlNem3{~Y7f~tt2t}cm4pcKxJ9Hx=#dt|Ir~j)}O&!FHB!359f1IN#NY zyPlp$QNRE98Uemi;Mrrpc7%6g?`oSRFG8;rnsKS$*#uuCPzw7ooq4_JX;c`M-{49l zM|+Mo5pA%dOe#+m+)LGaCCIN|U`!cWJKBx1#Tp~-me&^rMRH6*0&N$)EiyIPc$%fV zwUKLojwwi>m7u6Fm%+xvgTdC6Nh3K*VJ*l+NTdIvIXtrQg zwT_W3WTc2FP}PtKkir{$RJ%I|iA$jqjMHNyR7}Bq@m?XtauQ(>ku@qp#S|n`>UGj4 zQs0{4V1Ct#V(rBCwz+xvw^2G0D1|+r;;*d1HvfK^`wZwIp_hSP4c#oB6vG$y8L1zM z&*g(VH@KtIfMy&sA}Nj{k|@G7Z$18IOBp`oc7FqX+&9r{*eq(r*y4c}yyrUE-h#r>={?a$CF%{x2s^sb61@NJ%s1WMt4kfNBgCe5B=ZsjbAn1Td)P82iY zLGLsC{4F7zQ*o|Ee~x}_Ggq+f{m+*|FfY`B?N4{ZU4m^d24`APv{C4npe3SHnVtl!`=!GYMMXmkZg~!}~2r)4NgE{KeiS&fK~3PKm%aK$_l}pjB!QYXR=@!mgrJ zLX%_K!Ya|M>m7A?SAZL2iMsxGO;kBtC+NDuW_*XN&^WT zgGeh%ACE*e^i+sgUgD*SV;k)i(qv0q>hsE>`9y^rdsUReGRY-x8k3cO{kJ2(+hC#< zXEK}zN1r>ycCPHBIn6a~$-L4jMue>|k8>$(MJb$X1FNlLf9~k6dHWn8qMvIIv3THV z)p7TqDoXWUyp*kbF+uAy+isDG2GmO)9(6J5QZGRQM=H{E=4Edp?tdySigmTBC{-eO zBlA7GKx;M2Zjp)T<*uqFeT;}s+pHsjmH}z{C4mnW`GQ7QjRl2VIZ9!@$#vE9d4E1J z{eT)WZLt-7Lw9|sw##F=R(ZPJ(yLDgZQFdi7BJPU-R2J_8U4LS@U07{N(5RQq$zUw zNH$~g_c6T3#P>Q%6-tg8i`UQlZydUUg@D1|jD6OrD-c|!Y1YLmbRIuh76NK<^`-wV}6 zoqdGYv9cWPD_Tz3`dk=wN^RV7zOk!uIL8#USC|v+)+UD7yt-!2QD^~hY|FM}dh&5~ zYfml~jLgk(oa5L=nxb)Yl;D0rPmMv9JvsJj?8kE7eYN|eHFRWuJ~p>dade^-j(>Ww zH{`0mt>^~*mlp4zb{+&b&TSeFX}^DQM!8WRcD68 z8Rb%Y2rLKEGT|~M#MZrDX6<6z;+T+o37dV>8o&o?U4}$+OhH2KyYEB=qs^sbYNu(v z1@??@(Yv)3vj?!Yq04@oqt=cdrhY3q#;8Aau+&SCkY~;cw;cJN%Z-c|^FlbbZQ!tR zY>m%)wxaE_-)5ZjL+=b_Y)3Avs)0QN3CxMSrQ9#o?whw5L!DZ1Y$-i@H|sWUfY!Xh zvfnIq*0>Vl;N5~E-|>P1TMY@hJ(ksXuy*$U$EchulB1O=*=UHiyh4(8)PLD;_Ue=E zKVv|iVd~-?eFe4w5^{UgZn8-|AT%bb4dIxA1nO3l*Clf50evSLUv7=y*n-#w*fw;o zmNdoq_(zCw&}9h6(TTN-wN8=C6_;yeZhcS_Uw7eHCs-76LpEp?}oCA%o-$rqa zrdWS`47*vlt9Gr?K}%@-7fZAI%e65#chdY3mb}_%;VSgxDML8Mu>75WHS^BD*V41a zK?_EzkPmlmr5@5?lTotYV2+U$1y0T0_3-XScI4eoiyUQfWYP#jOD@3cu4yhsm}2ZG zMw`+J??!LlBfzG{c5;zkW5>8hj9a9bqT3N-U`hcs+G(mG#oR%}9>)98Jous(AAP5Y zu`Ymqw+LeSPzodVX!rc{C+mj(eR%dZrwoiQ!PqFQ5&AX3FSA*VMs-Ak1aFSOXAdy@xvqnBhQegel?I{yYiG4bKBSA7^{ZS zbV$>0b6l9FX6cwkoQ-S2F;Wf*%!%#-)RHN%KXI; zDJBu(|B zb!xo@>WR+7r27UKxs0@;OxfsWOes1-Fo!+{Mmk{(HAYI)=~DKA){WOTt94=ra~z!* z4~4PZ6m$1{n11n#MSbQqMvA6F0`*a}q4lKoLe|p4WnNQB2U-TCX_qs&sqI4b%wB>~ z@EA8Q$G1=W(?u-InTzkPQkzGE`Dh>z{F_w)<`Q;@)DQ$@+vZlkdvy0U2Xw6gSiE6$ck z(=Y1GYOBZT+pRTrM02#rXgOuuUS-aGeST{Xo+DQSj-v?st30CGj>%?pzFFD06EK>i z%|Khiz4~ccyN}XB15?OnIPVj0+%3M?_*k@;M4*&xujV>VF;4#LZro@Z!7&91*(N%D zyRF|mm`&dp9L+HW3ADlVOPF^84gZr7tpBCa94+$P>>IQ>HO5)iwn?$z%s{_<61m+N zeIbv!C+#neDM-lk$0vU$qxr<6)>h@ma!f%&o}+4Kd22M7`={!>ygkPhB>J8hukrjH z*w~I{?S^b$Y=mZCrurA`EfFY%?XM_X7nWnwCNS3VV+_Y0hka@Fu-SA%S(!a-b&zyi zw5(!xz6@iZpUMPE;aH(xqn(|f4X8NSdS-eIM+<z*KW(Is?q6DJN3k>;T-cq9kQjKzGb_We&*Duuu%5Gv3}4ar@6M` ze?~3$b$VUY6O_0~SU-ETSe z;+=hDvWK?v_z6qR!+u)c)#bD`@Ai|9zw_la%2nCNCM}GTbhHo+v>%TK+fST2A?c&q zbzZKg4-3~Lu10gr3w0n(rx~j^=rN%qjA;uZ`P7l?Eom*HwHowQUU!1`x+Vu{ua2FN zzL0(u(a%AzFh8f!a#fT>pbjh_-N)&kPdyX7g6*6f#miTTVB?+@@asF+ZYdpCku8jU zY6-k>!t!8$eO7z>1bg-rvvyTww$bq5T>VVyFsU5)?O5yd4&?C_)_?Qw)I)hRcRE~; zd3Pub{6^KgA7c;(xN_!tazbm zmuN5r32YlhNm#JKn!VZxHDytxG(K=lAWfFq)xo-TNKQ3wb(BP)6n-tm8sv=<1*^Fj zwf*x-mz} zt4F^-E!dh7ONXS{^4Up}W^d*5aG^dD9YrEniuBt{w$TF3Q;jBmB3 z>1fF!(?ac>%?Rvo5v{V6>#h|kw@7{4`>cv}jx_p5?;5PH(0ZD*7;RsT^iI;Zcd(~6h=<0O*)rx)Gs;DlZ+Wl`x29F6_-Y{ zLhlX=efwayTx`0XwrKTWF+MfA4M4Pt3-fNy|e8x!XSedhZm@92|ZmHN7k+;UrW_VLp} z3)Y$#6Mr@eQA_3>s%;KkV4xq~-Ezssx&E^HHpFtYTAtL^Cnw1T-i44=c^iCHy=%1B zrc7O+B7r_3O=Wf2OJ*1wDiT;e zNYnk)U%F~vvOJV856Z?->RA3sa?_j7Q|o;{XsPcQDi@e^+Scl(=|`5{AzGo6<@F8m zvkfFrO4M=tN~rdi`vjwq$EJOlZ&Av()#TH*s4u_jsAL3cSvzIr7aE*QMk%Zt)JLly zJsW9zJ{9L%^l1i4#Rrs;+pX!$)C(cM_|d#@9_{n47Th6pzKR6aGtzXwXww!R6t6tZ zd8gT~%o8a!=tK&(G4UkFuSDiOPT2ZHqW!9Ms>9tNes1|(11$;fdM34$F^g%X5-p-t zUw#ziYreGSZQD;u!G2zX`uzFCXclrR#DX;Ke>|TfFBz1Vmv!hQJkOC9i65i?Fvivk z<^}J?3py}f8yjh(z!$D<6fKtbFWul4_c6xq?=bl`Je6+)S1hZ z-BD_%VPq7>Yikj?yfUr*+7xh40HF zBY{r_r0Fe)e${!YQw_CKHS02zn$a>Bi@(`lKJzNXA`-ionjf&)%sR!!dGVPLfn6 zc7u^Kp{soJ{zwgDpHK1v`7g(cmbB`L7NqH2vY*AcN5~s>N#kk)f$^hzfvocG3RBsk z(uri1`rA$Qlj6z!7Ua<|CH=$}i&IJ>OFj`|DK~DA{MEN7vr$B){o2)4m7qtL4Xyk@ z4Pyopm=oQ$(4&lU!10E$-Fbk9Qb<=S^fYzGy_GEfn5m=R98FywTt_=m#+^Pq_22k` zgcwV*#`zhK>onl`U26!$Qaq1@yC=PV{*%-#*^E@0&%c@1S>tXDsw8E zXhE7*&n>^J^BRm$>)jh85ZF_ZHgA+;hGpkYefQU3?OL7LEOK7!RF6uDmZK5NSe2w% zwsBWNEF$sgV17QQ|0%i7fDQuDWcgzDou^wCKA=$s(DdEc=cTo;>4j9sTRs}*g;t?% zNeY_5j8`vPs->n6)V?3~VbZ+5^6#}1EpKK-Fvqbi*6o|?jtFX@7rpxJng$OjAboyS*xT@#UP7mrJ5I+N&yT?pfCFlDTVnLct zqzu_$vpBl(5XnvG=V+lA8Ro9IrwsEcrKQhlq3tgBz%te|LC#6}q7Jd2KfStBcYLzN zcu;zTpab*8h+#fICTP!_bWaNC(bNN|x zM@g#wW);0Jnp0auexSV=)zCjN!eLy(c!fF9ZU#lsyZ^(awCym3~YeAUp0OdF`76w-$#&6i8$ z`C)5(!;Dw?N@wTm0%obdEo#j%QezxMn$Er6^ia2zJfcrn9xhmggs7wH^*-v9+eM7M zXT}PV8l$sFn5`sFWKhynDl42j|5{d=ZGld5tbNSFX3tlfQG~--i&o*Ygl_EZQN@^- zcGgJzEl40Ra*DCt=+sXO-ph;`MJB5_n!v~)#;dIzqt(M@=Nk{Y2WuDsFft%brCaPT zqi&Ym+Vnr@mNbZP*tap-Nz%dG^(=0S52{W-f`!(Oy%zgCMTSWQ)wL}?8ckxlYuHm! z3azER3FohBrylba)~bhwo};%Iwdot6pQH6}k@N5~844$CfGwpq#-iV()ZL{#@xHf-Ib)~i2KSPMseqK*L< zU)!QTxXJaukX5jDk1OWej*Vth-*lFLZ*Q*YSG%@MZIgA5e&+fp4O5W7oefFaR%VIn z_NuJWAC9LgLl<$CA(^vf&}iQ&}or?6Y`Ai z?bNq1;R1nDxRXL-(K>aMnn|&0yKJEXfl_}AjEvAW%x&G3mZF(l~SEfO6&PSPfHfkELPH)pF4%k}YQ|v#hFK zE6f5r#VY<|tQw{ufxB5WE@?Ye-n??A$E%Mbfl|2lB1yC2S|yME=liv&1Es`WnH$S; zYe!1{spfd?%BRsyrx(jzuq4n;rx>;IsZHy3$tkkPyf1MGAy!TiojDwVTGOn1X~j|LE5E zs+vBnv$1?lZz1ktL=_2_&cn6RenZr-;830zvk*TO~n)>aFj`>6aH$EQ+;qdz(6UC zk0SA=-Uc=3d27Dn+86unt(ha4jWm*}*Xx9(a>ZyJM>UdE%6}}co2$2adPijy^Fkds zo~Lgw502o=Y}Jh(FV8cS!q_DeHA6@69YKLcg<8{8OhE!;C4HfLSgYis|LlL@`Yx^% z;(95afY_0wZa8sGy4G=D1|h=SM<}J?`T1X!q?Zzo_pO2C>^|6I(>4#XQv^pB+^m9!=fhYWQ}Ee+R2asL$8GHLYc z7@{RKook#q(@4P-BycB|PGIZx_@dK8jfH`Agq=8)!d*G@&B@-{;ZFmN`A(NrToFbc zXf561@hwG}@Wx`f@-9llRcG9(#GGiS;aMlG$LUFG_ebwk%onAQrW3y>FRAsa%v9g6 z>#ku6>cjm=dNb^1gci5zqF(*zD+TX|dQCU4@#t2zfP52E@jfYP?RtN$Sn~x&{G?3= z5_l5^()1qWkPs~`YP!+()E*sEkSKBak-WES5mvcaR+}W1R$FOXzq~MpEjwtS6yAg( z633b~)*?4lHKw_i*DwW%)pQG+58WeFq2|O?nn%Uf*ZQogz<*BNWS|t@ogosHhBnqd zf6vGHgiR`@AhD6|T6;EfEoNxZ*pZ019IlqphWRw-5AW^K zF$IZFdE({HF^5>gnr2xQK7K&0ZtcvcuR3U;6y7=|60sAqYZamj^N4!oHB3RG2iu>6K zyJ?Dh@(;dg%bz-w-+iqcn1aNpFGp?Zy$QVAQ12-M9Lnfl_#1ib(jE-l(6S=flhYUS7i#B)sW9Cwu93GCgnb zEg%1jT1gr59HsERWRY02D<2Qa(t)>nzDLItByQ%3XJ#u2{N41teOVVCIkzltMy&*; z@SZA>X!#=Du-vN6+maucfZTuE`}O7r$ILaREI(+V6y7=|5_wiu;HxJ;Gb&PR#}p)* z(d}jV=oT~o`lcUD9>F`lKc?@UyvaZ*yr)VeY~3UHmj+IT^QApHrXZ0c;0;SF)YA5~ zl<7ymokRE%%Mqn^;z0wY@CGZ9xD?QsSD0DFXj;F#hABwgqnqCH#} zS}#yrPR#Hl^ENBILrNs>4-Vn&Crnpw{IN&J6eNCLdc>{=7LjfFOh2Y5t@x-cFV&R^ z8TFBQGZx+L zWwztYyI4hHt78)$SEQ1*EqRZQDM$n)>}GrStde~t(~k{)dH6}DX$R(K^pF4K3wN=K z#NLn!yvLhoYBBfn8m8dAtPRG@X2mWXkze04{TMajuyKETH!UP`lYvrr%c@AUp8c2M z`+GYrf7~V&Q;;zGe+b>WIO(dXWBY^V#{Cwwwi~g@KqFTsAwY3`L2c{rljy~MTO4l2vA4Ti8)6(YtrS6N$7%gSyYmUw`?_U*(LPYE% z;w}-GfE)DsiW1Ik(yh@W$Nn7uk1ImW#)@_riw&-&mgVs&8muTo7)Da zAYqOMZ&19F9n5~7b=MGWDaGAdiw@dHubKC{;uu#XF83LxeLHep*)n36fhkDfsFqIe z6l#^c*(>8bobgwZ<>B z_Z&_QE$<@ll}6ir%4+wc^|`w{O@gfQMB9Xe6g%V&j+s@pf##CSMh&;*+2rN zL>*uD(pTmFs;J}*iqf!5QXAj49J{x{R-tEqdC`xoa-ZOdmW?jmsXoGM`zA~O+Oh)C838VOzt=_dW(igerLr8ontJO)K{l>-cUdIEv;Fkxh6zuNA|5rE%7DH z(yVuXd1T>^w)FA2N7Xw3x&eB9Nx9 zvPV9W^Bi5LlrLZvbYKl4ElG1n+7zegQ%c&(NPB%`_9CnUk!W}~QJ7LXeMa`ZzBSl*i!i4x4BjvLctzmbOLhwScr@i()p&-9kf3ZMhBMV)}Rj^%h{yPd8JsjiObej^TgI zQoDqQ@bbm0>FCF!PKzx`ufEz^WG^rHMDNOcFF9g;< z()3bK=y%bHwHejL>khScr0Lsdbrs$^v^IbKG$>^+Mb0+zYVEyBveDiIqF{08X zA+Mq}3b9?~il$y2<|B*5)RqoBF}OXicPGX`tFW)2h4k)HgB0WD;i0_c>%BrB#Ak*` z>`EKUKTh&AcJ64dqU~5#Xd&%EZXC-;^cHsD3!ijvGo1oYO{5& zC5yzjS9Q6%a+|R{q_RL@6h&H+a_^P+x16U9pX-e|N}+`!kx;rWf8XJx(XDN1j#B8Y zNNj)bJChR&^Jl}_a%^!2r;f8F?Of@#v89V#e@wLPY^lnrAKy2nvKlt*xbfbls-|_R zDiBx)NYf}|!9w-)%&z>K!%Y>Xu=R<=_Ai}DZSRX6WqjFD z=Zfob*?L&AoTu|8@XSC0bCRSH%XjJSfveR4X>{@o2vaa?)Kb#}G?c_lszT*00$*$1C*J&_9moz52WJlTUuv@Cjh%+hA`gcIfhJi-$$Ac)OHhIqhY&>`6Q02CdY_ z93LVOSUyP8m$L?iDn;j%FwU-u_*Z>o)`3VA%Tr$UZ60l`9X&=vd(pxLyQ;_omfW!& zxMtRQ%UTW8;HD#t;24oWDJ&5>FM9X7dgLjc()-a@C@Ul`U-XeLJXw=kjn)I`ZQ00m z>WTEyvZRd?2$aIH9et;vc#3i;n~yrRbhw6X6h~*rNXOrY)_BdMR!MO;WwN@aWDYfG z=NN&&){e9!Mdfd;U5H;`JoL(@p(W@CzL!j28QZ*7{lp~gDD&0OUZlm@L|RyDW8$Im z+&8$PhT2g|^kY<)P^H25w(8)D;X*6HwuBZ+(!@$Hl{-^Q^W}Y-bCklCArgm5=jGW; zt2}JkA1X>=-|k88)O$Z0Ve_@Ol6Otl8dqPgS6<8>siD-@Qgzt;@W);=X>~{>a(A!9 z+idEVl2D?lKw#fSnpV%R{cWtDabDeAyeUU1)56TiAQC_3L|X!jb=PL(&7z?c_VXds z2h(enlDpnFTVkI=ebr6F+_hqTYYH(D+n7kim-I_6zA_`WV<{ec)N225x({H)rPr3h z^iKUWdZ*rc#ne$NN2}z7e^w@tz>-FqBHR$ai}swJJ_jJ@+ev#GgqXr6cf@Kv5^~NEsT09(sW+*i(hilf2=~H`-2g-hpe$& z;=yYR(zN!vvvu;%TL0F8b%QkZ+G~Evr(OT+M`k@^9f(As(yfwTw9Ft->i(8kOSuD$ z%1Jdl=w)kukPFn9F28o~q(2*!SDDbYfKB!6 zL^trCPP?sCl?K|jiqdu~C%rY3@DN++`!{Li%<#&#L#C z*pf}P6LC3*C(r--PrF)>SJzhUNhIok_gZfE zypFs@|B~7;HKrte+3M4u%&q%Uc{0@j(jw9Fzy!moQ&;6^|4@NIsR5FMzJE-Byt|g^ z`H+BY{NvW;YFbl2jwx!~HCAcPE;$=Xt@(U}jmwfQ7bo2`^IEu3O&oj5*l@b5hEix@ zy>0<)q2!EQF~r3w@&-=Dg{XgN}+B#>s;}MvU$Z|C zjwz^b@tSV7!TItk7i*Y0d~y~^xmep#eYHPQAW(|e>}+{aAg^NBi5#tOsh0dx)ftPs z@g{#fmVYa-N)97?u@7SJqSn5kQu6&5)9rB=iCl5Jw3+y^jYDQ2c*|sHza`0b-Thw~hx=Gf4?kdKcewo8& zPJ6>{QlF4r_t;vt%ArSp_tn#%EVgAIkz4QAp$(PQ${Q=xceMv;lN(G|F{S?7#kNm< z9reG7KG|a#8?OGzCOey@>(Ozd{^!SJef97tjwwilby>>({QM`IVke{moz+tBtEkeE zu|ls!DeS>?lTQCQq4j@~&3%?WKzZwi2Wzsp-ab#*RN~X)BM{UZ(D#i?jMeWl&= zuc0kGo_xxvbCfFIZK-UQPi~SDi8n8%=~>?&RK7Ki(vZLyj5OU4+kS@n%F)^dN`JN7KaTmQay zm)Gi%4tnbG=DPgn7q1}82eyEI)7wt*ot0GU0Ha=(aav%pineSkv*=$+G}e(W;vQlf zc=jC|o1+mC?qxlAx5$;o+6U!05-8>UDywa6oeylaUB~m2Z9Q7rGRg{5&=RzePS7Q{ zQLDG~7nU0-=koA7^_p>%LJLv1BsG4&!|@Jr?AcoLyT~<m{;mUeUJEg+~&x zF!-~6z28h(c8bzaJJM(^&5B0XHA?=>BM*0t5D2soX}TAukkx44BUIZSHc9aOW&T9g z)GwG_EEFP?0+rS4m8#8c6!$5#LMfFuQT}6eu>5*|h>l-A5x*hrb!DplS1+r!E@mZ5 zG8W0c8=@`Ay<>I!TAui=l+jaKm}R9+-xBYM1WIjoOO$`CiM9k4GRvxb-;sJm{?)8u zv{gd_Eg3^!=R5zrqdbUo(;9N?iAr&g9dhNtB7st9A$_s%a~`d#!#uXpx0CRtKP1GP zjjk9)w8@QI@dNF@2;aoPe8sygzG{K0^M;(<#i>2Vyif=FBuTGb_Zh{@x6;09AB{F? zQEWu|dz(-BaQ%BuH};|GGFye%5Zz^PQ`V*Vd0X0yNb>yK+bH8lb!R>-%tb?~%RVt| z?zUu`<7ewHL~_@SM!)?d_@{=um6Me3u6xbc%IPsW+wa59Us0Lk&`8~jbhqkLo2`>4 zkd9ZIMi|@Y4B^A+D;Ox%fuw4Nd9V-uVZRV{lfsM@<@;zC{7xCDqY)9S+?H`b_FikR<1 zvg*ODYV4e!S%U{ou2q^n{9ViQ#+@U9QmBviwl7(fH;w9PmhK)J=8JwHP3NiGS^3vV z{)+1ae+8pYd5U(%xIktUo1hn`-)39bOl^U_2IU{gUB`LK#p@SRkw7VoL^PuxG>TvF zTB8omQA5yyaToQ`I}M3eJ|wb_e*9f)8%9pd_jj_&Z24~X8uatB@)m1~TaMpfE<`e< zO~R~m-A<%0vhwQZCb-u=-Cv03n6F4Yd1B?CuO5>t#Wi4PJ4%Uu_`u-H+_e0TZWdlPw&juw98n%Uk~cxuFRO^LJ*gAx*2CzYr*u8R0}?;pB#H z4HjDYr&R-W%okgUNo3MAOC3;0*Z#2b_)fD^PzvinB#J#x*PW}ZP#*k@6zT&B%qin+ z)Yb<FNALB?$WhK(_~CRLaafP$Qv2tLN^EqI?#5c zGpwTT-MMrk9hetNp-+;O=d_zKXq>yT<8Ua)Ck{Skkftbly`BD|y3EfPt;6vtgZUy& zqrRx>h8`24`LvqmiMAtwIZ4v`d=Hd{>A84;2OTxkjx<_J&%xUHdG*PUjd$Pbam*KK z(W>?b26Agfe|59xexv@RXQ|=)A2Q3XQTmL-=TpnC&Z+MSn4nh=EM!|)Gq-M;HlAYQ znmbm$cG6ttzWD+};#BhSRL|W{+2eb00xd~T&tH)y}a!MC5!CDC>VbV8iL}k~C&dioRk>W8PzVC4oSzP@g3I?&K=6Q3AUAdqIZ$wCMennEAP-{D{B~XpbFVg5AJvqO(G-lli(|oW0RM2)T ztKZfzOaHoe+39`e$a3;;g^aNQk=lUIx&>2^@JU+e#cn-f)$)W9QFO>N!+Z3!)G-Nt zIqE=KEUPPR56MgBShb29JL{M)wlPu1^*;t1r3wUU7bd+l9_^mNd=m_IXUj-kD@I>% zy>Xa*q~GC<7qDgz_pwQ129i~~p1W$x>HnxUITa*ODlsgQjT&-_ZMPG}YPf3C^E5Kn zbgj!V<>P^9=D6c3J4RBNlO#PX-c2hS`J3l%-GO7uuf%)xCabX39OVgnOB1Q#^ki?$V@>3OM%{rBcc}(8WAY9_V^aNw+Bdv zNR+-6$Zhw&tJCIYHBc)5l$Gq&)BSArzlcLrA0??iu2X%W6qc^2fIO4{QVnOfj}uy z$EXU6yoMF=Z1Dc4l|NXuOg^$UPF~l!pWekkMc&qBE-Mw-PanNKQQlhiT7#eTn^x%8 zCMKUqZ)dK_aFm+1bgBGD**I48U&Q!Zz8=lHWvm)}_Q|tm50gf`yWFD#~Ae96Z5u`WGv2+ag6yKYNYY$P%;=X?hO+ z^z}IDmtmEKh>Lfx$F#{>vJpP zm*kL(b;;28U&8xom=RzZ$ZfZF7!m!~%jK!gCs9ug@>w98_1}}~KXKG#+3dkq`a7-f zHf`f!+wkwQ!tybF`mc`1t6F>HT$VwgC0K4Eak9{Y)P}55%15g6sJ1E0%&Q#PzGzD# zyIStj{DhK3n;pCH`cK za;%r@zUiwYF)D8!z2MIra+$ySQt1ZvnZ`Wxj(H)0{z=l2ZReP8>As#*o>{qnldCMHhmC3PGOWt5vA1g?IhG>YUU_9ceMkCgn-leU+HrrgN=axJq#r#VCG>Ob+jW{< zmCaJ0YbRm`e^YFyf|LQI1AA?w>JCcY^F!qeulwrQZzQRELT&0dFR)g)IMmrPBh&!ammVmZqKWHzgeB3)QkBA^!==#ZAt}i zT_l`ht$auSoO-ZN2OSCQMMz81^rTR3yI?hz`jpmD3j5%m@p<%0-LkRGmwd>opLIs^ zWgE8`vkGpopj0#0@60xIIvY{ZTNjBbxx4e>ZN3`U0$%AzU{phz=Cxj}`OWpkc-`lo z45hBDJi{IjILe-q4v}az)P?tPY{0V@ZLcGNu@-51eq1ceFBr{v(QeHdO4aq7$F5fT z%q*3>b&+tNT95}A?fHw@V{|0`E;o_Q_W!|lQ=CVd_UPRWOC{6+mgm2{l?QCf~A zDI_o_`pR+Z(sGRZedXJbD9vqBKZ|ddJ+@{Gr|M?{)i4E#4`UX|EnNz;bh1{GQr=!rFFOv>T$fk2&AfZfQu_QodDV!4 zx@*!;OLUW4a@(eHdc%X;E$zoXmM`8h*L}thuHdF7S+#!ITk1$G`%ywR=|#WLw89cU zP8-vxk9vFMJLYzNt7T<}4{|t33Hhchv!pfrTRvdd5m3ClR-n~SHDGvxpaTiaNs>mM z3gK&0C#uz2+|kjJaS=7;Qht)smh?>saFruJJ(KfXH2qjx{Do1wSYNHuFS#(>3;-=sH#JrM^0HpWU&q zSyrrW)$(s$r~CF}7F>J76-be&()p#j?xi!oGoT*Lau@bjxTGv_9jDjz>BN?A{34g!Zm#c6 z-sEUF+?UlGKI3?UKj*O_$|?CsbeuqE%dwaJF>Jeh*4{s!1$X0h!=9;LBl;LC@@-># zvfY=BLnC#R!m&2B-OAC%$Cyx_u)LCvD+M@r&fj`5bDA43_qc0%o>26hak;3QHe_cZ z{%qe2*<9t?`OA61AlQzC=*M4C zHMCPwU9G9I%*Z=$pKPNt8A@?*LdAGFcHKwWiAn*VUFQ3o^zF8Wzj;{_XEIE|br{Tv zB13I&t^d(-yy`1W(1ApcO^f7Dd#B4&PMBr2ZO?f1Q{^yzw3M$6rEsN4BuXy!R4W}G zuZ?n>#jrfBhJwk?E@ndNWbsISe=Ms6cp<=0dvcf~Y;Kq>T3lJPaj&u67e4$-Rjqv~tPwkJlP z68ZR7pK$u})G1bhp65wYg53StQ&#p|xUlm_caqn-s@5CTo)2Dj$UrI7hr58Z8uciz z7Wv+t?{c_h;L{8HHr79V712Y|u2<^B%O>>|o@%HAbx~aqV@O~NN1FD}-#BZoGc4-L7p@$46mX{jpQvO&jq}tto*B;RS(tG_3l)`;Hk$BlVT#Mb=$ar*hmyUIg^^7@DeO&9L-7fywD77F$ zXo*OmK3ePBJl=>Z8K#YSx{%@68Fw&nurI#8t&y3dcb|`7X6eOlTSj>j6p3d@9 zZ>D$q27ad%rwZ~&`c_q!7qx8ViVkLFYsKm6ikkA#?Ri;gYL(AU|0YK~>&krTH?2mU z?C9|{BHn%i8&i%h?JvKY`YQDrjlw<;43Mk)7hz@W#O9Yd-Ls8e^e+N+AWf&+GzVQi zzDYiERu=XFY3NkNqQ2KRFOKBd`i^GXu0OTxtr@3x?s~&E#%Gw^ zkE~kc(169I7MI_6ntqgPQdrN|Nmi0(Sp@>6Zm)=8S5|IL&2HD>mUW`avToMP%^u59 zs&wQacJE}t{fleF=^_#DTgr0HFIsnswDLmZ&wH*NI!X@s#S*lTBK7o9%2wlne&&Pd z$JDPASZc3w@(Q9wBKFiyb^O+owx0z?2!5a?NK*~g@1RVKj*+*lu=4g>tFW6(-q@Oc zn65wktu?FG>4R-XgE$?1lB8v0n<-BFrzy#0L;_n3(zHvqVwo~O`nEDDC6Z$b62qPD z+a?VQX2UYtRhd4<_Q1;OaUc558nnK>N8eaFFRj8Fk%bM8d&}upB5YacH_cMpl;lrV z9n#}ZwA7q87MG(-HINzAElM@nT}591^o?cNdz1J!dW(|n_C({;FtG+h3-)l+?)u45 zBy}S7jZHaJMP6wqKJ_}Ir>$zt#%zw_*hW#`-fI5xp3Pq^6RB<_>3ivF+LT+&xYVbH zmbbB^>`SM{hf@(zKG=u!j2WoRjhT#5j&pNQ^o&wER>-4FLZ4K2HZJE!iV9bTLR$bt7P z4a=p-IY`P?e{J!;b4dPdUtu|Uvav_w>~ri^VG0sS!M?U`Hw`(zUB|`F#r5r#Dr!#m znrcX(l#5dZHmGWfe2sb+-6wO|*Q51?jOY{g@Q5vF|619F@GsI*bL0Z1%^#`!jInY|S(`kb<-gWWHtV_lgjja1 zY=Z1aF^0bBJy7#F8aO?pK0rI_!&0Cx(L61o#GkEeT+A9F=)ioDrrGwZ`W~Ch&b8~9 za-_L!Puv1oAxp4tqffLNl`YKUVciU?Fa-(piQZkhx7aIp%@Mjg#l!|<`^(Grmz7sh zxx3tsvm_-)$iAeHEv+n9PKc5l+Dmu+oF2)Ge7#d>S6{;vB*b`S8`ILG=HNKHA4s4S z`bW>ffs5H8^^&nZX&}eC&08bMA|GEOM^de!e-wQdrzzvz1C+RkD1Ibqikv*5hMYit zpgzn=l6FjdtUu@#rCaVs3ObNLeUfw{wWGW{u#Mhly_KUB>ccXm)6t)EDdP+DQdWjp zIeLh;i#qDBXyFldZKl1f;+-qYWfE*`B}L27qE`8L%WO7)e&Z~hmf^}S(qFXcZft2V zjyva?!aluR%+`~X_F#xDPkn=>((jaSwOIH0`&dCQv+e%8J;qkP_-f_Z}sqEa;`ttvYQkK zk*0HfKW7`Aa+K3b6|itjK>|yG&Z@m=t6!c+Z#HeFv)hnwG2aPtj@JEIQ?gwoN;