From 46a64ad7258e82e2dd867e4d6963f6db3b2c50e6 Mon Sep 17 00:00:00 2001 From: "David V. Lu!!" Date: Tue, 3 Oct 2023 11:16:47 -0400 Subject: [PATCH] Convert Tutorial to ROS 2 (#13) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Initial conversion * 9 and 10 * 10 and 11 * 12 * Mimic Tag * 13 basic * Update rviz * Partial Diff Drive * Diff Drive * Apply suggestions from code review Co-authored-by: Alejandro Hernández Cordero * Add license to launch files * Use environment variable for distro * PathJoinSubstitution * Precommit Configuration * Change ``` to indent * Add setup.cfg --------- Co-authored-by: Alejandro Hernández Cordero --- .pre-commit-config.yaml | 58 ++++++ .yamllint.yaml | 31 +++ CMakeLists.txt | 14 +- README.md | 227 +++++++++++++++++++++ config/09a-minimal.yaml | 3 + config/diffdrive.yaml | 98 ++++++--- config/gripper.yaml | 32 ++- config/head.yaml | 18 +- config/joints.yaml | 10 +- config/mimic-gripper.yaml | 26 +++ doc/DrivingInterface.png | Bin 0 -> 132356 bytes doc/NoMesh.png | Bin 0 -> 75141 bytes doc/NonFunctional.png | Bin 0 -> 81216 bytes launch/09-joints.launch | 18 -- launch/09-joints.launch.py | 83 ++++++++ launch/09a-minimal.launch.py | 74 +++++++ launch/10-head.launch | 22 --- launch/10-head.launch.py | 89 +++++++++ launch/12-gripper.launch | 26 --- launch/12-gripper.launch.py | 95 +++++++++ launch/13-diffdrive.launch | 34 ---- launch/13-diffdrive.launch.py | 106 ++++++++++ launch/gazebo.launch | 30 --- launch/gazebo.launch.py | 85 ++++++++ package.xml | 29 +-- rviz/odom_urdf.rviz | 35 ++++ setup.cfg | 2 + urdf/09-publishjoints.urdf.xacro | 15 +- urdf/09a-minimal.urdf.xacro | 250 +++++++++++++++++++++++ urdf/10-firsttransmission.urdf.xacro | 32 ++- urdf/11-limittransmission.urdf.xacro | 32 ++- urdf/12-gripper.urdf.xacro | 71 ++++--- urdf/12a-mimic-gripper.urdf.xacro | 286 +++++++++++++++++++++++++++ urdf/13-diffdrive.urdf.xacro | 127 ++++++------ 34 files changed, 1728 insertions(+), 330 deletions(-) create mode 100644 .pre-commit-config.yaml create mode 100644 .yamllint.yaml create mode 100644 config/09a-minimal.yaml create mode 100644 config/mimic-gripper.yaml create mode 100644 doc/DrivingInterface.png create mode 100644 doc/NoMesh.png create mode 100644 doc/NonFunctional.png delete mode 100644 launch/09-joints.launch create mode 100644 launch/09-joints.launch.py create mode 100644 launch/09a-minimal.launch.py delete mode 100644 launch/10-head.launch create mode 100644 launch/10-head.launch.py delete mode 100644 launch/12-gripper.launch create mode 100644 launch/12-gripper.launch.py delete mode 100644 launch/13-diffdrive.launch create mode 100644 launch/13-diffdrive.launch.py delete mode 100644 launch/gazebo.launch create mode 100644 launch/gazebo.launch.py create mode 100644 rviz/odom_urdf.rviz create mode 100644 setup.cfg create mode 100644 urdf/09a-minimal.urdf.xacro create mode 100644 urdf/12a-mimic-gripper.urdf.xacro diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml new file mode 100644 index 0000000..6abe61a --- /dev/null +++ b/.pre-commit-config.yaml @@ -0,0 +1,58 @@ +repos: +- repo: https://github.com/pre-commit/pre-commit-hooks + hooks: + - id: end-of-file-fixer + - id: trailing-whitespace + - id: check-merge-conflict + - id: mixed-line-ending + - id: check-executables-have-shebangs + - id: check-shebang-scripts-are-executable + - id: detect-private-key + - id: destroyed-symlinks + - id: check-symlinks + - id: check-case-conflict + - id: check-xml + - id: check-yaml + - id: check-ast + - id: double-quote-string-fixer + - id: requirements-txt-fixer + rev: v4.4.0 +- repo: https://github.com/codespell-project/codespell + hooks: + - id: codespell + args: + - --write-changes + rev: v2.2.5 +- repo: https://github.com/adrienverge/yamllint + hooks: + - id: yamllint + args: + - --format + - parsable + - --strict + rev: v1.32.0 +- repo: https://github.com/jumanjihouse/pre-commit-hook-yamlfmt + hooks: + - id: yamlfmt + args: + - --width + - '120' + - --implicit_start + - --implicit_end + - --mapping + - '2' + - --sequence + - '2' + - --offset + - '0' + rev: 0.2.3 +- repo: https://github.com/pre-commit/mirrors-autopep8 + hooks: + - id: autopep8 + rev: v2.0.2 +- repo: https://github.com/PyCQA/flake8 + hooks: + - id: flake8 + rev: 6.1.0 +ci: + autoupdate_schedule: quarterly diff --git a/.yamllint.yaml b/.yamllint.yaml new file mode 100644 index 0000000..253582d --- /dev/null +++ b/.yamllint.yaml @@ -0,0 +1,31 @@ +yaml-files: +- '*.yaml' +- '*.yml' +rules: + anchors: enable + braces: enable + brackets: enable + colons: enable + commas: enable + comments: + level: warning + comments-indentation: + level: warning + document-end: disable + document-start: disable + empty-lines: enable + empty-values: disable + float-values: disable + hyphens: enable + indentation: disable + key-duplicates: enable + key-ordering: disable + line-length: + max: 120 + new-line-at-end-of-file: enable + new-lines: enable + octal-values: disable + quoted-strings: disable + trailing-spaces: enable + truthy: + level: warning diff --git a/CMakeLists.txt b/CMakeLists.txt index 9485a0d..05accf5 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,10 +1,8 @@ -cmake_minimum_required(VERSION 3.0.2) +cmake_minimum_required(VERSION 3.5) project(urdf_sim_tutorial) +find_package(ament_cmake REQUIRED) -find_package(catkin REQUIRED) - -catkin_package() - - -install(DIRECTORY config launch urdf - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) +install(DIRECTORY config launch rviz urdf + DESTINATION share/${PROJECT_NAME} +) +ament_package() diff --git a/README.md b/README.md index def0c55..ba4e33b 100644 --- a/README.md +++ b/README.md @@ -1,2 +1,229 @@ # urdf_sim_tutorial See the tutorials over at http://wiki.ros.org/urdf_tutorial + +Please download the URDF simulation tutorial from [github](https://github.com/ros/urdf_sim_tutorial) or using a package manager + + sudo apt install ros-$ROS_DISTRO-urdf-sim-tutorial + +## Nonfunctional Gazebo Interface +We can spawn the model we already created into Gazebo using `gazebo.launch.py` + + ros2 launch urdf_sim_tutorial gazebo.launch.py + +This launch file + + * Loads the urdf from [the macro tutorial](https://docs.ros.org/en/ros2_documentation/iron/Tutorials/Intermediate/URDF/Using-Xacro-to-Clean-Up-a-URDF-File.html) and publishes it as a topic (`/robot_description`) + * Launches an empty Gazebo world + * Runs the script to read the urdf from the topic and spawn it in Gazebo. + * By default, the Gazebo GUI will also be displayed, and look like this: + +![Nonfunctional robot in Gazebo](doc/NonFunctional.png) + +However, it doesn't do anything, and is missing lots of key information that ROS would need to use this robot. Previously we had been using [joint_state_publisher](http://wiki.ros.org/joint_state_publisher) to specify the pose of each joint. However, the robot itself should provide that information in the real world or in Gazebo. Yet without specifying that, Gazebo doesn't know to publish that information. + +To get the robot to be interactive (with you and ROS), we need to specify two things: Plugins and Transmissions. + +### Side note: Configuring Meshes +![Robot with missing meshes](doc/NoMesh.png) + +If you are following along at home with your own robot, or something else is amiss, the meshes may be missing from your model in the Gazebo GUI (i.e. the gripper meshes are not there). This may also cause Gazebo to take several seconds to start up after the splash screen appears because it is checking the internet for missing models. + +This is because your URDF package needs to explicitly tell Gazebo where to load the meshes from. We do this by modifying the `package.xml` of the package where our URDF meshes live to include a new export. + +```xml + + ament_cmake + + +``` + +[The reasoning behind the exact value of the `gazebo_model_path` attribute is a separate issue](https://github.com/ros-simulation/gazebo_ros_pkgs/issues/1500), but suffice to say, setting it to this value will work assuming + * Your mesh filenames are specified in the URDF using the `package://package_name/possible_folder/filename.ext` syntax. + * The meshes are installed (via CMake) into the proper share folder. + +## Gazebo Plugin +To get ROS 2 to interact with Gazebo, we have to dynamically link to the ROS library that will tell Gazebo what to do. Theoretically, this allows for other Robot Operating Systems to interact with Gazebo in a generic way. In practice, its just ROS. + +Specifically, Gazebo / ROS 2 interaction all happens by linking to a ROS 2 Control library, with new URDF tags. + +We specify the following in the URDF, right before the closing `` tag: + +```xml + + + gazebo_ros2_control/GazeboSystem + + + + + + + $(find urdf_sim_tutorial)/config/09a-minimal.yaml + + +``` + +Notes: + * The `` and `` tags work the same way they did in ROS 1. + * We must specify at least one joint for the minimal example to work, but we'll add more later. + +The minimal configuration file is: + +```yaml +controller_manager: + ros__parameters: + update_rate: 100 +``` + + +You can see this in [09a-minimal.urdf.xacro](urdf/09a-minimal.urdf.xacro) and by running + + ros2 launch urdf_sim_tutorial 09a-minimal.launch.py + +This starts up a `/controller_manager` node and with the `load_controller` service, but doesn't add any immediately useful interaction with the robot. For that we need to specify more information in the controller yaml. + +## Spawning Controllers +Now that we've linked ROS and Gazebo, we need to specify some bits of ROS code that we want to run within Gazebo, which we generically call controllers. Now we can look at a larger example based on [this yaml file](config/joints.yaml) that specifies our first controller. + +```yaml +controller_manager: + ros__parameters: + update_rate: 100 + use_sim_time: true + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster +``` +This controller is found in the `joint_state_broadcaster` package and publishes the state of the robot's joints into ROS directly from Gazebo. + +In [09-joints.launch.py](launch/09-joints.launch.py) we also add a `ros2_control` command via `ExecuteProcess` to start this specific controller. + +You can launch this, but its still not quite there. + + ros2 launch urdf_sim_tutorial 09-joints.launch.py + +This will run the controller and in fact publish on the `/joint_states` topic, but with nothing in them. + +```yaml +header: + stamp: + sec: 13 + nanosec: 331000000 + frame_id: '' +name: [] +position: [] +velocity: [] +effort: [] +``` + +What else do you want Gazebo!? Well, it wants to know more information about the joints. + +## ROS 2 Control Joint Definitions +For every non-fixed joint, we need to add information about the joint in the `ros2_control` tag which tells it what interfaces are supported. Let's start with the head joint. Modify the joint tag in your [URDF](urdf/10-firsttransmission.urdf.xacro#L241) to be the following: + +```xml + + + + + + +``` + * Note that the joint name here matches the joint name from the standard URDF `` tag. + * For the moment, let us focus on the `state_interface`s, in which we specify that we want to publish both position and velocity of this joint. + +You can run this URDF with our previous launch configuration. + + ros2 launch urdf_sim_tutorial 09-joints.launch.py urdf_package_path:=urdf/10-firsttransmission.urdf.xacro + +Now, the head is displayed properly in RViz because the head joint is listed in the `joint_states` messages. + +```yaml +header: + stamp: + sec: 4 + nanosec: 707000000 + frame_id: '' +name: +- head_swivel +position: +- -2.9051283156888985e-08 +velocity: +- 7.575990694887896e-06 +effort: +- .nan +``` + +We could continue adding transmissions for all the non-fixed joints (and we will) so that all the joints are properly published. But, there's more to life than just looking at robots. We want to control them. So, let's get another controller in here. + +## Joint Control +[Here's](config/head.yaml) the next controller config we're adding. + +```yaml +controller_manager: + ros__parameters: + # ... snip ... + + head_controller: + type: position_controllers/JointGroupPositionController + +head_controller: + ros__parameters: + joints: + - head_swivel + interface_name: position +``` + +In English, this is saying to add a new `JointGroupPositionController`called `head_controller`, and then, in a new parameter namespace, specify which joints are included and that we are publishing positions. We can do this because we specified `` in the joint tag. + +Now we can launch this with the added config and another `ros2 control` command as before + + ros2 launch urdf_sim_tutorial 10-head.launch.py + +Now Gazebo is subscribed to a new topic, and you can then control the position of the head by publishing a value in ROS. + + ros2 topic pub /head_controller/commands std_msgs/msg/Float64MultiArray "data: [-0.707]" + +When this command is published, the position will immediately change to the specified value. + +## Controlling Multiple Joints and Mimicking +We can change the URDF for the Gripper joints in a similar way, but in this case, we'll associate multiple joints with one controller. The updated [ROS parameters are here](config/gripper.yaml). We also must update [the URDF to include three additional joint interfaces](urdf/12-gripper.urdf.xacro). + +To launch this, + + ros2 launch urdf_sim_tutorial 12-gripper.launch.py + +We can now move the gripper with an array of three floats. Open and out: + + ros2 topic pub /gripper_controller/commands std_msgs/msg/Float64MultiArray "data: [0.0, 0.5, 0.5]" + +Closed and retracted: + + ros2 topic pub /gripper_controller/commands std_msgs/msg/Float64MultiArray "data: [-0.4, 0.0, 0.0]" + +This gripper is actually set up in a way that we ALWAYS want the left gripper joint to have the same value as the right gripper joint. We can code this into the URDF and controllers with a few steps. + + * Insert `` into the URDF definition of the `right_gripper_joint` (which is done a bit hackily in [the xacro here](urdf/12a-mimic-gripper.urdf.xacro) + * Insert `left_gripper_joint` into the `ros2_control` joint interface for `right_gripper_joint`. + * In our new [control parameters](config/mimic-gripper.urdf), we only list the two joints for the gripper controller, leaving out `right_gripper_joint`. + +We can launch this with + + roslaunch urdf_sim_tutorial 12-gripper.launch.py urdf_package_path:=urdf/12a-mimic-gripper.urdf.xacro + +and now we can control it with just two values, e.g. + + ros2 topic pub /gripper_controller/commands std_msgs/msg/Float64MultiArray "data: [0.0, 0.5]" + +## The Wheels on the Droid Go Round and Round +To drive the robot around, we first must specify more interfaces in the `ros2_control` tag of [the URDF for each of the four wheels](urdf/13-diffdrive.urdf.xacro), however, now only the velocity command interface is required. + +We could specify controllers for each of the individual wheels, but where's the fun in that? Instead we want to control all the wheels together. For that, we're going to need [a lot more ROS parameters](config/diffdrive.yaml) to make use of the `DiffDriveController` which subscribes to a standard Twist `cmd_vel` message and moves the robot accordingly. + + ros2 launch urdf_sim_tutorial 13-diffdrive.launch.py + +In addition to loading the above configuration, this also opens the !RobotSteering panel, allowing you to drive the R2D2 robot around, while also observing its actual behavior (in Gazebo) and it's visualized behavior (in RViz): + +![Gazebo with Driving Interface](doc/DrivingInterface.png) + +Congrats! Now you're simulating robots with URDF. diff --git a/config/09a-minimal.yaml b/config/09a-minimal.yaml new file mode 100644 index 0000000..412df1e --- /dev/null +++ b/config/09a-minimal.yaml @@ -0,0 +1,3 @@ +controller_manager: + ros__parameters: + update_rate: 100 diff --git a/config/diffdrive.yaml b/config/diffdrive.yaml index 18fcd98..c7f780e 100644 --- a/config/diffdrive.yaml +++ b/config/diffdrive.yaml @@ -1,30 +1,68 @@ -type: "diff_drive_controller/DiffDriveController" -publish_rate: 50 - -left_wheel: ['left_front_wheel_joint', 'left_back_wheel_joint'] -right_wheel: ['right_front_wheel_joint', 'right_back_wheel_joint'] - -wheel_separation: 0.44 - -# Odometry covariances for the encoder output of the robot. These values should -# be tuned to your robot's sample odometry data, but these values are a good place -# to start -pose_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.03] -twist_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.03] - -# Top level frame (link) of the robot description -base_frame_id: base_link - -# Velocity and acceleration limits for the robot -linear: - x: - has_velocity_limits : true - max_velocity : 0.2 # m/s - has_acceleration_limits: true - max_acceleration : 0.6 # m/s^2 -angular: - z: - has_velocity_limits : true - max_velocity : 2.0 # rad/s - has_acceleration_limits: true - max_acceleration : 6.0 # rad/s^2 +controller_manager: + ros__parameters: + update_rate: 100 + use_sim_time: true + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + + head_controller: + type: position_controllers/JointGroupPositionController + + gripper_controller: + type: position_controllers/JointGroupPositionController + + diff_drive_base_controller: + type: diff_drive_controller/DiffDriveController + +head_controller: + ros__parameters: + joints: + - head_swivel + interface_name: position + +gripper_controller: + ros__parameters: + joints: + - gripper_extension + - left_gripper_joint + interface_name: position + +diff_drive_base_controller: + ros__parameters: + + publish_rate: 50.0 + + left_wheel_names: [left_front_wheel_joint, left_back_wheel_joint] + right_wheel_names: [right_front_wheel_joint, right_back_wheel_joint] + + wheel_separation: 0.44 + wheel_radius: 0.035 + + # Odometry covariances for the encoder output of the robot. These values should + # be tuned to your robot's sample odometry data, but these values are a good place + # to start + pose_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.03] + twist_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.03] + + # Top level frame (link) of the robot description + base_frame_id: base_link + + use_stamped_vel: false + + # Velocity and acceleration limits for the robot + linear: + x: + has_velocity_limits: true + max_velocity: 0.2 # m/s + min_velocity: -0.2 # m/s + has_acceleration_limits: true + max_acceleration: 0.6 # m/s^2 + angular: + z: + has_velocity_limits: true + max_velocity: 2.0 # rad/s + min_velocity: -2.0 + has_acceleration_limits: true + max_acceleration: 6.0 # rad/s^2 + min_acceleration: -1.0 diff --git a/config/gripper.yaml b/config/gripper.yaml index 7a2802f..0931e5e 100644 --- a/config/gripper.yaml +++ b/config/gripper.yaml @@ -1,5 +1,27 @@ -type: "position_controllers/JointGroupPositionController" -joints: - - gripper_extension - - left_gripper_joint - - right_gripper_joint +controller_manager: + ros__parameters: + update_rate: 100 + use_sim_time: true + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + + head_controller: + type: position_controllers/JointGroupPositionController + + gripper_controller: + type: position_controllers/JointGroupPositionController + +head_controller: + ros__parameters: + joints: + - head_swivel + interface_name: position + +gripper_controller: + ros__parameters: + joints: + - gripper_extension + - left_gripper_joint + - right_gripper_joint + interface_name: position diff --git a/config/head.yaml b/config/head.yaml index 9b4090b..73b2db1 100644 --- a/config/head.yaml +++ b/config/head.yaml @@ -1,2 +1,16 @@ -type: "position_controllers/JointPositionController" -joint: head_swivel +controller_manager: + ros__parameters: + update_rate: 100 + use_sim_time: true + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + + head_controller: + type: position_controllers/JointGroupPositionController + +head_controller: + ros__parameters: + joints: + - head_swivel + interface_name: position diff --git a/config/joints.yaml b/config/joints.yaml index 580445c..3249f67 100644 --- a/config/joints.yaml +++ b/config/joints.yaml @@ -1,3 +1,7 @@ -# The joint state controller handles publishing transforms for any moving joints -type: "joint_state_controller/JointStateController" -publish_rate: 50 +controller_manager: + ros__parameters: + update_rate: 100 + use_sim_time: true + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster diff --git a/config/mimic-gripper.yaml b/config/mimic-gripper.yaml new file mode 100644 index 0000000..0143326 --- /dev/null +++ b/config/mimic-gripper.yaml @@ -0,0 +1,26 @@ +controller_manager: + ros__parameters: + update_rate: 100 + use_sim_time: true + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + + head_controller: + type: position_controllers/JointGroupPositionController + + gripper_controller: + type: position_controllers/JointGroupPositionController + +head_controller: + ros__parameters: + joints: + - head_swivel + interface_name: position + +gripper_controller: + ros__parameters: + joints: + - gripper_extension + - left_gripper_joint + interface_name: position diff --git a/doc/DrivingInterface.png b/doc/DrivingInterface.png new file mode 100644 index 0000000000000000000000000000000000000000..29a9470ccc544b76cad65a2da904eef2653b08c6 GIT binary patch literal 132356 zcmb@tbx>VP(>F>I5+Jy{ySrP0ySux)`ws5z?rs5sy9Ety8+Uj2efK%fd(QLT?~kwQ zR^6efV$GVFp6TxC?)B>?TtQA8{wvN`2nYyxNeK}p2neV@5D<{#&>z7)0r&o}5D=)W zUMd!FmNuqDE}jmiM5Z2=W)Kh_%hef{PGsCsRiGO*XUKE17-5tm;OZtm zK!8c9y`pX9RFd3O&4diIXUoBS^bGXSJ@kgCPwsi)WZ5ZIol{GvxxFd*Fqyi#(R=Xn z;zxgX=6W~g+Pv^q`w%Z3MmJEsIwX)sCpdZ6IJ zFVgk1n0L2E1_j-WYPWvyd+{sY0DQzyAP?LNX>I7;I$#~3+xnz^w9oCRzjZ~OznRhX zg-B#vS3^d^q-QZss;sveOB;HiE-|lnl(dm~j(nxWVmex^?1UCD;j&yaSDrxJq(pdGcWvvt0<-_s= zJ+HIs2L@k>BuFTX@|mK@VXSF*3Y;kR7J!54?{u>q(*>YeF3ZqI0ovO7W2;I=P2oa{ zV2WQ>vo!_AP|b!B+3rBs=C$Ti$DUNHEKjKH0e0y0!^dP_VJClxA@%& z(_hp*or^)09fN?;tcJNa&~O&1tKiMO^upZpY8$q9#gx%8>U^`hU?tZ)QkaBX;gMl> zzWB#>XE$}e{;R%fU24r+qtn5x~b?CvG!TC>!~FDa@!dUbzhT$8Y$ zhvT*rmVBg6#^spYF@;(lE2Nc@fBBU2=n6_D${u@b&tth%V|SGJJ{OHU&yT*siJ&;A zsBT+S+T7P6e=T3-EvDuA$a!4({EN~$(z(3p)Es(O@8ochr(lCSE|^#%COc>p0X@M2 zi5fQ2yWQubwcTXB6EE*v1MjzCe4;Fl1%Y}A*$3a34EOWCVam8oueQFsQdA?%eG1xa z)rl=l;}!PP)`gL~pK!J&hLYy~mcNT_YL~l74Myuzw5V4%bf_}ku9OE)(29lb&1&bc zg>%|8i?ZsQDUHvj7&vwUzvP-p9*oa!8h+dSi1hBUHaF%B73_79zY?srkW-4fEy=Hl z-{Xx~Y4_1tYKDIa=lfBSb7XMr?!@@+E#(*ep%d#%F;74I*K|;8Fz#ySj;}w*6ZPb2 zR~7QE$&t0<&qOa{Q%4I5Qpn!edYoXqUPT?dZ`jp#EZ7ubb_NE=M8Sh!*8Tg=l0!BE z_ui?>I+X9ZXFLJvSiYTsqRvAV&Oc2oHV4=%2nu7eM7#^glo5UXfBWw9Sw>Yyaq7m< z#?sGeFSfo$)C2eBFsMOe6j@q!?Q*M} z4j2woeo@0N6va{wc&56AKvlw zADSTqdGFpI{&ZaItzW$3MVr?OI`-=UfaNdVN+4gkwT;B*3+LnaoH@Ywk%ey!m$f7B zK`ZXurN?Usj2tOlHJ-TZx}K8r^c84RPZ}Pz{BrDM8h1 zTFGsEndV&)exsBZAvLY_BxD>uV}&LOG5f8PvMGahu;2N$3VzDH5QAVMv3b&%iR#)! z+vW{RG;ssUt$vtkMxY=et5^u_6V0sW{n$;`elwCZmVIcd6n&T>82B z`I{&PR)1dzlw%qM;&l*KIT~*_7CG9jexSw?HSSYVG@y_q&aDDUv8$M#&K?f4jA))v zi;ATzGsF=NzslenF)p7GSNI{5UcW|{9t~zTa(#CLf$73+QiDbny%?0UYPHkSmp6CdSVF{=ubC}w zsG}5tfrP_?kIiKn`6H(%Z@ADgdV3D;(_!&BB&rq|(?f+ZaxEuh=zerw48VF4yWT*>hlI49aH zKZy7b>Y=WDv$PGR-{sF~`P3Qy+?e72F)UGn7ii3tb zYw?R}l=FAkNY00!NEttMsF3GlHnn@@D)Qj3e^3R}!?=5SMPo4An#o5-t#yKWGC!82%1!JZyJl=#uO>rl}tPu)qs!1Gk3y`krCd*Yf4GAQ6x7?&vh zF2I|KkRPk*CqkgVnpA2*U#j*SgXGfE{PfWT)S0#B*KIc>07T&NJo&{rw2|X7&M3r3 zOFR&?6<83OtY8Bvq|Fo^Q$a^cMNF6$?Qd6;hiH3zb)6^|`JvFuaaqIF!eVD9znl%> zy?;7Wsl%svDO6;@YaHvRs3bYG<5-oA&Bx04?@B-WKTZ9fnF~|id%oEmhmi@#H^|D0 zQgUczH)emeLfu?4B!acT#QnujBXit;PD!j$zTV*GzW?pUIZB$@U@{G^l+opT6WpX} z-C+@eWU!rij{?kmF2=}7xKL|t14&)VntkS&JR!5VBJ8XDc+RXbhxzN*iEneQFdHG% zj2^Of1D!3lF5ewRe>kDsS!)jL+F?0r6wZ|+)=gs{3W>xQODq?PVxDi6d z&=~0^iZN4tn&Jj-D8fAh*`9PqKXeh7sG=ZVe%_1yjY*ZKjk0>i$V6P$SM@`Jh0Yi< z>jQS`=l#>T`2aD*3AhHxTAE8}l#fG-togzVB0k)r3;VNEmS-xY2Erac(aT^a^6j@p z<%Dw}50xT6R0zJui1rln@+yZuit?eU5dV0o8>R{ygDDjE`0=&LL@U`FDWq^kqs%)` z&klK-DAKax@<_@OI|@jNXN45^;RkNQ&S+<8v9`1EplYMl8WI$=L-=n=zi7Ykb~+wb z^lqw*ugX(+#zQ+Fo_(p@XNQPp)phaLe;}aP#kMADGf|?%5qzV)977oSIPd@bQ+9HF zTgxJ?5%w_@CtnkHN!tIe{8L7fY{=MK9xQO^hg+nURzLA-F9Bp&QBk#UJ;rM2eOari;k?tnMyfOF+zBa;rsCKJ!;mt zZ?&Ukv?3U{T5~wC+c6r%MiVo{q>sX$Gc_gY^km~f%&{d2ycw(lz=L-I!9U^ zXS@*!sI>|V(g2Aobza^~w=$YAF->-07Yak5$KcAbT_NpVHF4KN|6vM z46}j3 zRhGTa4n&O~WtLIXt5Q4G4b!sZ9e!^5DMz9bQK42fv4^qyK9uwIy@6!nBvCt7Ac=4^ zbhB1{bpYLMXu$9?6sTp=_DbldfK#R4a5Yr0AoF9e%c}cAuVK@Z_`=htqszlCy}Tt% z{)G(k1%wpA5JePsn0MB0=kEgL8JoM|_gW=#$e9ujPO3>t^Cn6kp?lAB?5P=%4-Yn!n5l1&ykQDojK@Q?B_fdVkF|vC2&!lIK#p`v{Xoq4N z=jo7Ft>Yk?uP|M`hw^QweZ1ql&{*iK*eh%TpTmearKMb75BU+v`s5~$7U&vDunD0H zi1R&GkUGnC)sn-v{9HB|eE@8-GD{DzdCM}F&DLM0PAqD) zNcsx6?IHJ(Wd}C+$Zz{s5Wb;h0Lk3TCVWWpGu1?puo2LOhUk7|Qhy6yqcpcqv$vP9 zm#=9W>|9m7H5;}=aSc#Nbf#4@dtj|KvV$H$U9+ahbV2|{#n}YCyz6LkoRFHSbwfpD zPE+93!W7~g0NYj@ei~ljyE)yig5VhS)xu;#1xNI)r}%vhiHBM~ha*Db1<0M+iz87{ zu6!R~Awp_|3SXIf?pWqL)Q8yeBk6-s1bh~Gge6+dMFnjT2*Q)a9k5fmd6l@W3LZ{L zs6ICATN2U}@!w5t(9RU4dE|#Vz62P!*$ArKh!PHXSRzwr-_bpap61bsvC{q$RSEH( zNSkyv;_WaQ@F}#Yn@Ed@sSpt!yD5*JbZH&>9h(T~KK`U+WcG~q2|h@zUsi&;g;3`< z!iAbu#|@$5lWeRe_4PdsQsg<2W9KGHzF3ywxM;I)2ajg;)RYFJ>+Q>Gf6je*hZ&)p z>xtu<-0Jy|`PE$CLc;n^H|uHC)MLyS?@3YzcudiAkD{bW{N_hFa1fBDKy+)T#h{?~(E`D2u5bDTHB`b27PJkt-@Mipwt z7rcaCDN}Q3q8D2D4%Ged1WrWKOv5kzeC#e{>w1^Y9A9b|vVbNh)R1r{xjED2mr*G@x68<~G?YTzWz1U3Qpk%7GFr1u zaV-6UH_P1TZfD#^z6Gq^kWWLwxLB)p736==pm@Xm_zqg__+}tLDI?A#_}i8n7T@h5 zo1>L^Z;}9ML;R?sq~%WXi>ffD-P0c;IC!h|9D{FHWo^bGNuMQ6aGOnXhNoV-b?YXL z)8L7eySVQ^n!{3wX~o$m1@+C&p_91GG$RQKd1I;{(JFKuJ`|7nhsJzoGUA1Qy1mUF zmnLbpUThmzDBliog1$Ew#@4Te?zg0bs~ULk>9Lo}BfF(7a9ko(z(U8kR%d3jIGKrZ z$C3WCKDBo$pS8VSRS9_JJL4RM2IQf$_@xi<9rE3 zrNf4&o9?X=&E||+CZyL%O8N0{Vp{%|qkDSsop02#6?n~$*MPW|6nPGUNY+zUy2zj9 zhJg4GXelhLASo>T4}1m&&9Z#s`6c?l;SK657mHRPm?1e1D`eA!p*zmepydmdp=-G^ zwfYI63MXuDQ?+2=y=qkPv~ZmqZ_+>q5E9ie$VD(HZG#eoBC!x-Uarp9ch2#N*eYZi z+J1kKZT{oJLTm~)28ZZ|x8FtZ6w*w`N1eWQ?VJ#N=vp82NCCA9iraS?FcT3WPcrrY z3SSH_<**IB5vUs;mCAX{@)$3IMG7I3AJY<;z(QCdbW&gs7 z({oFCbk~Hz|M9umKk}rho3g*t#nKx3sFE$PODfFOd96#1^=v3$B_?t{1J$@tF7 zy5c>=@I#bQg!nrO*^+2DjS8{pNWINS6CST!UG~z|MpyWbj(#ccmEcIUF=fnI3z<_a z9k3!!q~d1;88lMxVW(~H{kqwH7nalK4@4~*5H`=g`kSBV%qAzeoz2|#(^)6;3#O?i zZ}5g-1pBufn6RQmNRC{zJmQf^Ub8@8Y*t7725}5;2wA9QOe5vbJ033X%XF-t2sCjJ zN!#(LQ=%w&fZh%C07KJmWuO%opuCC&?R0f zT!^kQX<{#vc(<|R?7nRyjjWADp7p}W4EJJSe$@PYu~=dPMqOQ+yOq=UksOSDsi-QH z8+tKj68S?GzY}v#>uW2vZ~p>MC&TjM%GrH~adHav)6B<&b@e@R)qBeBkttgObYsm+`7QhILH zT=CO7s;ZU=BNBW^*hes`cGXf}mM2}s$+(l~l9#NkBN} zI}z&J+TAUAUna+S*7fMRUG;|Ev*esntl#Q8`7hkMj{SlXoT<4}tGfw0?R2HZHolFt zrtmQzYp6IGJ9p}#9}}G3RUh%73Y8cJTt1?(6l#*@qxhNsIQ)9ck`Uv;uc%cx zJ1nY0f(Bh;`lTTQVbXJE^kZQHMS0u`F1b{qC@DpHnL7h9D{gXuG`TZ#E^QyyxEA%` zpihl~R7u0(9$PMS%SRFQyu=b==k*|w(nSeLmP5oMQ;Nv_Gkbmp9WgG-GF`pB$hK0UT>x8*W?CRzCv&M86x&GpDWU9l7;UWV>4^3tk7apV%bCLN0= z+qTN^ne0f^m&P;)>==|t2F$@y;W18LLMLyQb>_4B7kG zA=|U@KN!VM=)JK2P=2%nNL9?2o3dp_1ivzi>F1@!yA1D0hOuci>I{@_=YLDH_!{*! zBl>Ays6(n&IgDlchoF=t{TFW6;NXq-O_#ZoaHK}H!ni5AF;=4x-GU9PA{Cz9`yzCT z&H%I7t2jZSefF;DDh${^$zNMLtClNLm2FlJU>uw})u;_0MW%4cv@-QL00&z$*nLbv z^1+?&L30Xu$$I$*CIx!(X;iK_!D%Ka@djb4X)-r2)FZ9-H%G>Nrs=O>rc9Sk38F&)yHqEQ=mYcjS}xf>(q@Rkyv zr1GhPf&{-*QW{3O1!;*<)@pOeLNkU9;fMNj)b~1@TzLY;pRi8JWCfsL^*d}jWxbP4{`%O(vBTGa6I||~*AXkj_dYh}ZGwYC} z3lY+k6&qhH5$}ITe5>)udFg=?=&7f}j}~*~q1S@^?@I&GiV7Odlw#%bB(+juup|Aq zRfSEPY}xdM`qMb5!A#=m_K5T2W!1deY1?fCIZJn_E{6DNox z`}a!+XQ|KGiNbGztcq~iAO7lU$q~Vt{ClW_vXL%+ZKpt%nmwBeIyLn#sK4I#+>r=@ zy*s#7MJ54ujpRW=v$!$lVH!2e8j+Qm9I99Y7C3*s{!!_DKA5Uw_Yi;y`;{*AqTSwB zFxV96ebFUNk%%m`edTcyUucBvY(btI(82uI3<&GkSov&^tHDKHaeRM`h&^r&^gCX0 zab3qK-oI%N|Jf$uB_7ywsy!?HNq2JPrElTO9WOzK5{{|oH+XVqreP-&~ zab+iIgE?&c4jmHxWB=&!0sIV>Q4h$hq&0#Y>@ur&b z<&!_AmOe!g`K*ksvY14SOf~bA-3?zB znwTv)Mnp4SrabP_aYJUKj*k|85ihy>;TL)seB}`<>;i0 z#UqTIeEBIuhDM2koC`g1O90r*A_cEyDZWBmeGrnJ&o-zql2>?fJI3h#q+#>7_*#I_ z-`#}5RN5GJ#7tO#`QC`fcU}OZO+-i+t+O|%3uLF^U4$Lr-#W8^h4~edTgbvTU)7OY zUWR5DWuS3-J#GwpN4Cipk-sB4E~%lqv5``)lGc7j zxi}1-02lgal;_JAfGArsQ)aiP7seA(|RluZhd$o$k<=qC@ZbT!~rNKsNdZ?^{o)2)J@8_do28SZ85TB>yd&OZIc{-1b$d-mV6@c;VT;7xv>Lm z)2@Ss4lnLe(D8~XtQ<6D)xPFp=0$;e8~T)Rm=#K%)KOLV#5fE5iTJRsF#(R?cpf zA+oet#kx?W%m8guS~}4U+>wwPzx#vxb)c(@6*K#^c#4k@o5#=qX=2_p z2B{B=<~Wi)6}F%V1HF+cW6~LK2vvyctG~-%XV)+XJtcy)uJ7c1ZXXt28x}|@Uwjxl zy~vQD4_(@z&iN&vJ@fBO0Yp>J$MK;Egrl8EyZ@t##z_T5qZGtsJBM6uZmYQlFk3JH zYPyLbp)E9d3*){0wusRPq3lB^oh-zMY^zKuB-il53Td!x+16|st#f$esA z%syJ2d#ft5z$1q;h-vSIaD~zOC0G4Rfk+ic23vwk&rvjr@XeO6t3PKh4@dl_Ww{bP zDus}$+Pa^*>*+15cnAqzK32Gj5X%Ugvg=}DGdgonw%3k&Eqp0eyb43HQk_T$rP0a# z%Z2^aG#R`1{@_9vk+?-&kfE|=Oqh%;6rwHjmcQCxod3}{|H~6ruHiq|grK@yz(Im_ z%Gc4siUCQs1co%8y77y2dky(=PdL35f8a9tQaS8y(0BG+<|NmRj9>;jfyO% zXbDoar|hkfZ(yq^BG<^O3ZD9{r}g>$iyZ#WrXm5v-3a8$3Y;+CJs%>-zG~F(JT09`%$Qb(ze4dxNsx@Al93**^hX35_4P zaJ@0xbuRw8G6uaCzhyjKO^pwNo@WHR2zF~93GUBajZfWupKmfJUhhEZQ9mp7v8B|O zd@l0awT`9ftsE(i({VZ+ZjVaWGybeb`F>k}J+k*}s(I6Yza3f|@l>5Vee2^CH1oTw zeV=57>7G5h6=8jK)!;5UuCspy+LD6qhc>L`={q59eK!H1KZYBKU5^(#i;ny^(6qp{xn7jqug9O$xyKXUaFI!q= zD(>{(OOlbC;3-u1_T^r8Lx*%yg`aii&^0+qGO#CWR&e$g^O9U+-$yXd8y|VrJ+?-+ zTDc0FQWk+|Xzq#k{vMM@F%Dx3y71kncCqHP zR(H%)G^R6UI^v+I1zy32R{r(UcTleTS6bS-)TOXOUz(BDnjNoyb*`s<;p@(+&m1!! zS6UVbMfv@3+*s@K!4olPVwdSaz*9dI4Dsn9==Eu%V{@F5iJ=m3aY0Cz z_I@V#y3=4BE?t}5iMC#hCL0T?rF6qQ+H>g>^vl0H5ai{-*?}<@yd0rKP+5`D3Qmh` zeU8OH+O&H3HJ6H2Jkt8k>36kb-uAj$oN?-L@p55Z!!UR4KYhdax}7>ivCW5^x^Z`f zxT%? z<5*cal{~a9u)e*#g|Dmd{Al7Hk~pX?d6~Q}ABK|?z)#K|D)8dJMy^&UMzL+=OlqDB z0@ljQP%_#U)vs)TmO58xq7s6#rEOx(S7b4_bj^t5pOdniFH=nVDtUq5Y*u?n~2r#cq zKQ|!gQ_(Xl-A{!QfC4Wc)dAdD`7V3#$udLoUA{AatSc@&UpwVhqPwqdl{a2wWm>no z5DA`ljT7~sVx1LpW*U870lpnRx9;7qY5hB;_`ysi!D?}fCrXaNNxzV$+tfNr7iuY9!G`8}@bAI_lM?9_7kvA1D}lRRH0 ztZFVsSP63Cp31!r13u-xTo-1DZ`Y63~(ec!mMuR(=PzwO@;u9CtUwBQv2;8>@?O20Y6Nr->FG{;^w<3U~^1jWp zvQfBpygIVFR$Q8YUb=3F+~XSLL5D}!6ARayq`4r}Kh5vQBj>JFYsGqh!Ul{SIqczt zl~Y$(_4HTW6vbZ2 z(C^fkDko=O^L;RY85N~G&)cn`YMK|aCgd#p@PIIWWkRJewd&zevJ>shk1h1Yn4BKa zWi1TjTNB%S*4~}Ydo{V?ozE!>jr|s$e~ycIUiN0W_*n>gtE2yH?G3o(XYlCrQal;H zqTRKiWNOSKc2k4R>-ReF*bC*(c_P<&egI=@4OGlIeAQd&TYV^~;Jv84Ykc2}jg_ej zf{O)>FFYR5uZ-mo;GbfT`j`kuACsF)XsPPw#E?gxSS3~0{QT9{l|cA@_bp(z+pgdE zbp2Y2b?t(z>5TWQxZX?bqEv-ogL7j2n@kdQHB~;I`0s*9Z}bDglhbo)q#4dM2H<08 zCdYCPLHc&&{rZ|jGiZ~yn-6s#hBz?1-WRtL%#|4%K^O7f-3I-aEn2ylxX8}Lfot~* zfWaaxzxZOE8`!s2c%Bk=ftGmnwhNVmkc9N>r0GUia~u&}?{CeZTbJeumEO<95ziQT z9@;GtLb?8t_7B(Qnb%X_?x+1)M$_RA_>nEw#otNc3bkbqNW{d^=Lm_XAW~U6IifF{UQtp^@?CyfkIliugU(gdH zZfHg+F%)5Gw;n!wq-)U=lL(X2fl$`9#$lpMjoT|zQ^wtOvb04 zd+)~ca-?XmZM#GzD_e$psLpTel*ZiQzhCBLr*P^!DU!Fltq33F9P40pl(3PL^OPK3 zE_S;gUem($%N<$x6_q*%b=2moxm6YZ%ICRSfW^eQur5o+?^ak>pe69GqXZRk1jQmC z{)y{XMR&5A_~l$`T6Py;J~bcz+IL=^(NO9#pBypO6PM_H(DLFg)t*f-Q>LgG6c#B} zWwJjoygl$P<0u+#aW1m4TD-(|adP51^`N?xPMUq9&MO3MNT~%n8*v7D<0N@*PztnW zBMF5)M(C3Kk_r6G;3j(+o18j2>;m_Hih%iHU`d0e)Ra2nCL5e6@pWY39nFvr<*&ps z7%TnMuwxu~-Efl{u(9~@!1+({(aeky@{u-IQTELF`x555{@lylWVi2hcH9ErV<;hw zMgcTOB5_iZ8I_QS&=Q<<(0nOXgu`sD&q@0bAFzc!7cRtuL{}leW@iWR>YZ7V`|<>E z85cV&XcxE}iLR{1yb$#Mb=C=JF^_#qK0x<&*UX~qTFlil%2W!%_u0n^*r9 z2|pUB4;}6xa?I2Cu;0mSFs`5Goj>uM%k=h;w+&uxa15=v zXvP%s;qfY=f8FC>k?r(x{qA&`UN?R%`jbwaDuW{EGKeyW4ycRK`5XLIC=~BnjZYjT z??EXh)&cBb9tj}>xp_0Lk*C-*$519sRmO4u8)6!)g)cO5<#h9HX1dDAG`vWC4SR_S z)Sbln$-1MQ?h7BiVE)@I2fg}evM#9$O=;GpIiv!xp+_Om}p;BFDznx=Tmi3$E z@YdRM{-0}wOXUR5XLTck)gw@)B>^hZb;PfI1s}G$?wv_50P63=+DvP6H)SY-kdf})5Z)jNJ2*^$5pR$BbF&he)!g@`l)#bXV$O^5u;kX zdw$Lo{{IE`dK!P0IJybo#9SUPpJ_*yE|^`yYkpRcINzJsww0Q*y4!R=^h{L- zzN0CZq1IAWO#Z2jA#6YBe|XS&^z;7pV!rXZ*i(1`e0e+|NKy{(IUPKBiK%9okjr!f zoXWd(zqy+orULHWtDWDv-}ePS6L=op4}mU!CX5VxbQbPJjTE4qe##^yoECI@DD8Hk z+9MQv?r+LzsDd?C3N4reZQz7gO4jslu^m1CbN!w&V4d^+{f5%P zRRN

Rs39Y>+*&?Wma-Z^xVjX>SXdfYt2p*8jLy2p#P$hcq$Tf1e>BcIg*8m<69k z~~ZCMp*xv`U8*H9`3(ue9MXB z{8wARaG~n|feQTp24Vbvfg=8|L<=ezh%q9QrS^JyzVQ)sf2OHYt1MP3mn!aS3Z38d z%rV3&SHX!E<0p`(!w}B=_oS=Cb5@N?DhfLAj3}_1mvgpWJa22R?%!IfH;n|^Gy!d#TC+;7ETI2cx(A*< zaYUqW`snCrWJEG`ta$clp<=f(*1TD(`e6eAqMuE|h}`S(|HP7BRa?u5r=RB5`A;nX z!p28-rE(RNaPWMc-QwG_KY~k(%GiRel@Q zx$w|qMB3lCVMYJeZFiF_R%%|MkC%|4m_2LW@Efx!e`?fTNs{ygCo-FOi^|6u^c$?n?)0K_`UhZ-#g)&{Fl zPj$q!&d&j-ny#*{V9sqh>~hULn^mpd=|aWqbm(31KddH>^_`uat*xzr84ji*Qm`ss z0{h*wT%|&-(%Z{xB8NXR@Nd}sFDgCHo{w9hoqCLuHPOW^&Qeg3d0j%+a z#`dlgq}ZWm8(_j%0zvH1nVU5mPQ1jg4EZ?=He+MsBNv=C+<$g!@CIhDSmE@1(hn}) zZ*t(&&7e{1u@T>-yQ^!pY7=>2ufy(eJZ^_680Ve0>YQFUz8WF~Jui00_(euLolUb< z&s&|jy`<1<|AngoK<{ra4;QPg&L<1is;a7Dg^DEcdDBy~3e+z4f0Jyo>kmHrd>d9T34nywbP`wSo zAPbx_n6{Rd8CwQcNJ&|+{$$?-76KF{Whq$X+gFb~>=_bd6*V>ICnxRYoc#Sv$;rtC zu?KAj@ME!4z5CsLj;p)7yEH@M9oCj?836$SI$hHi8C{<3e)irS6WDF5~AS6!VV zL+TCRq+`})qN!%E5OLy&4Tm;3y$o(ySvrb!UxSS<)_pOgKcu^3T5Vxsh$0KI;phqn zHWd_XKVBKzHGA`G)t8l(wY6!rnExE5S5i|`)6uC?D(8yH%*@0kB-Af;)$5S9TkilG zFnM&Y?+nG(?qPoxrDv^lqe#@0ZDPnM3C`p+s!Q8xd4GR@3e^u6QPR@Fi5vv8VDg|{ zayH-y#__M}Tu5#?u zs`ktP-mS8-Fm!oU6ZwY4HMQl zKN{F@@bL0JoC5oq#&PU4Lky$D3c*_&G-?*h$}X`4n+Fw|z+M9;td6U0d`_FCym>2C znq(OYuu*O0LjY?=W<~}L4Gn`{2Nyg0pd&Xv=b+Km{n^TyTl*#DkRzIC9i6lyn(Qp! zq%ydIAW4O$x~7H$3yzgts75;_d(>gtQjDU2AA zV`F2ftMzdG4tSibtf=84*R&l!e=?=ZO#Jx+Ji7-1HS@(yL75{a0lfwkiC`=4*6!=$ z!#7luImS5{gU?G90d^Fna@ktlovMY?DypiIWGGt{{+D#%=yb_5GBVOvU;}&$me+-* ztQyrSU0qy~Oo4m3?8uRWeTjIYqM}^(f9EyQE-Ek`!$krN)A+sb(J(M_1bm+>9G|oi zWoIk#xPSe2bX%VCIOtN^0506b(CR=dRvfP&%>7=`o|H4U%Wx}ExqIkp=5~C=tc|T+ zk%~O~<9@a+_qwh18#ss#MX*9^`yy+tkB0cE>T`-|gYvYTygXo^H5WNtgdx@1;qT_; z#1i|1x1XsGuGy%LYp5CQ8tJv0pnIhv3OH<+(W1o;_V=$hK2TZR?9&grwIeY_4DI-T zBO-{r;*)2Uk(3NadMvT@64v!)!^uuh*Nojy9^1RSyR*hMNtG%FTgZo|&Ts`Zu>UAh zDqlR&-E)>dsjjbAs+`}CuMn+P1Kab4l9H0zT6-_AXPP12I**Mm-_M^@g|>uLvQ2?c z$oF(P2hn0X3)R{yD=W@6{99jEBB+u_=bLlH3d?J232|_)pM3f(6J;nev$DWW$gexs zFwLevV$i4oh!;8d(f=ERc+UR*{?qsSQ%iAKSy}Kt)6z6zC-M}iGBPr%)T}8IkIv5t z@bPskC2j+Z?-D5G!M4a0SWr*^1Oi{r+rVkad|C>W@ayYq^3?Q<46q3Uhgu}@RTOX2 z0cWOcI55OuJ9s#GQs){G5g{cd6;xY9jww;BM3Y?6+S=OPEtqPT0-G&o-l+BR^76;* zM)l#Ut*x!AtLyHN^>4?uxJl!;^E>)Rnfj7%V`GExYw*G`&+wU>cD34;7je2w+nQZq zZ=MQ`XAa_*K(I40ssmRNw6B5vuR5#EiLQ0@&Z!O;(l*U6E%ZI;YcP6MPNUVdV(d%V zo-I@qFnu^jwhdix;oY(~j`)E$d!kT0mO#L#rKo7Yu6e_82tQoJ2&@VQ1_mZ3WN2Tj zsVdUEiP8$nsIeF93(L8qQPKtFfm0y6{xRmjE5 z*V2-DtiIP^>d0YyVgl?n?ku#!MP_DZ5@g*vDE!I5G27zFBFE%pv=~Dw_*k`z-hl^k z`IZ?4Wv5F^rkD1lctcKjjH%$Xm{prqR%dbXpjG2nLb4=Mvgncf;wOG7=*G(V<7iw? zHy4*(rC@NBg(f2*$Dg>S1}+@ZszwMctgenW1!~ZN{l0zkN@+<+J(NG# z78Deal&d^nk1-x7RSg<3r^~4G4BIUI>^*WRQ7Rw&L;?nT*NxM`7Z+@*z=6u-!O7vF zMrFfDB>`(gsNI%DPkq&zU2bNkbg@#rgo)_Tu}z>(qwu;*tRV&l#@FxnI`_d~a|8AY z^X7IVUx3a}F=f@&XD27prL)%FycmCpc@xI~ON*Ucek`Pt0oN%e{2gBE20}6`z`if=hOh?13b3KFa z=}gklhA!yZIAc*b#VR5!(^pNL3=Az%i^=S4YUs!4G8D(KHzZEmWsRQe=x5LzXQe zY<-ZzXu^JWrj(3UF}Sp?;Xq%2M?~FbV_L;bQL@EkV8#74xu#Xydl*=*3@+GSR#8)< z7;sFI+5<$*n)AaK3!&?;#qIYQ;!UV87?uJ)EpckL=HOb9K<2Jp@PE;3vV}7 z&m42jn1j}_?n^#-kDN@xi7uh)^X3#Y+acM5|cI}6uu0@VQf zrb(0R#g~HzrJzlhV*1>z!%$mO6C*;xCJP(?ra(o;r_$nlAQ#%t%)(M%Fah@F9CoW3 zDk@~VY=n4tK!V=Q zd7&C|Za1|f++X}DRm?I()J_DBBNrCHce%=}rz?(uB9*9JgRZ8!8XpU*MN)bFuMe)C z_H?c4^k>7AD^C@8rbS=4gdh`?d_Sc zR-5f}r!90Uhm@T8wiZwB?3#Ipt}=w`fqSWvrL&9f1dEL^4L8UDB3bQQ9Iw%SWGTyr za-Ug*;^HYfCoYyC2^XHvgjfhpK~ovW`0bp-`(N589$Bsfj-U7WzaB?79YM-h(sO(g z1Ui~g{0<+mi6ag1^cB*Z>1dZEBsk+gh(ZZ2ulg-fV=4tHRnd$w{CW_ZeQhRE(f9oS z(Dl}FQMFIlxQ~HI2uinfcem2r(jncsbQ*xt4N{A=bazSjBHbM;-5tI+`mOgD=MO%D zyC?3Lx#pT{=4=eQ?F0)Q&q(R&ml+$R8l4o8Q~TgW$%sB-_eYn}uZAz_kIn@^N_a7j zR&t2=_p^*z_<2)}Dg&~yeSfW4uf9;H=)K_0c;%mJ>$N$DBJ0kC*93iZH`>}8VxE%` zgpx@+J6G=G*LFQnS2vCKyIMl$gS!QpJizywV|W^$6EZmn>{=SMgvReCUMNcFHM?{# z@YnW0;BZYDyJ{TTPdMReu9UR2SV4K)&-aR#JQbVRh*v1^DGBP^k0NPaLX zn=)ZzgdLH_$=Grc)Cm|Rt=5W>y@=>uJ-k3o4tSqqS*OdC&~M6?h%Thh#^s5z9@#4~ z+rHehzPu|d;ich5IVqUk>aQ3-6gk^#ajHT=}Qy1Bm(mNkA@byZbV z%4cO}zbg^tvAMaF{`HqhYD@{qa#ZOUR#n=W!xmi04fXX-0!Nxf6FE6l0U|Gu0zgc( zbn01hTjtrzNcJ*_C!C(19=IIsbqoL^oO)kXIpk=nt8=lkmZ>*ol$Ms()p=|}IG}!q zojAuA-}3YGDMhE+(wz=>1x2I)z5qeu-X5$3yDq|HC@17in0#J{a*LAQE2jO$%3ZFica$pB~O*rreH%D_nwJzN=6XOo9Olov-(>7=B0GaG{35uOMlcTt_7Q&-~sbv1>_7WOath%c{?-ifwvOh2JC+}_`!V~!dj~%%>$T|90lamYFM?@{Pc}fBk zGN6B=!x3)own-kZw!>HrslOhp#0T>ano+JlmsfnkZC{G>g(`<#%!G;MVDE)SQnigG z!xug8Wwo>j@{V1>Ovd_>#(^nTIF&!T(0W>`t2+n&iCHrKgzFFRRT zZFK};Jbg}BJ2IE9T~rP5UtJwg`Fc@Sy!t79f@A;xxh(0X;zKkYZfs*`&{N zbaoC;I&`%@<|-KHu z=BXvhQDGwKC1YaKX8@0dFV9pFXtr%vrLD&_8AcM8K_i1(-#p@e6+K{9A(7c@r*5dm zPwEf9ytFjgi1?QF+ciKWeRBKO*Du^!fhnxDMeIV5UrIP(j)$Id=LH~2u&}UZYwU+| zj$``QT^r`jD#F6U^&8zC#ZC23UsE^>K;i6(ay*3Cu#`$|TRpv0B}YKTd8g=6#f*=S zI}&Q>>%)#4OQR=ugdzc>#T73_p`BAM@+5#lU^~{EHc<{qwIVzsqD1->Zr-M)n<_v& zI&4+NmS}TVe<&c#%IbKyB5t^W1`JHaG(J9l`7sG%tW36c5o{G&z>;BZWJJbqUFOiS z%464Bh|nf4_V|w!ZE2(G9ZCbb9}OLy_R*LiCek1bMu&;CJmkQmtEx&KCFOL(5Wc!{ z$Rj@*5D);^LBOs63JyD@bM-JZJRG>C=93XwYp1sv>IG3q@aUximX=r-% zlM>}}Y$itOffAW_<1?6|)^|!Jll#*Z@Ty7uhAth*;OY*=?sy&MIB5j^Bvx2A33#gJzlS0bb;1i~Zd>N08haEYiLDCL&t*#)jCR>(XM0FDE zloU0LSMQ;~B*EXs%bRI{3x1XjeEJkY(oED+1h+}Ko94t#P~Yb=IMU2rfs}Ghf>>Fm z7ilXgIp4-J&L5WL@eIopSA^&H#aBOLJ!GPkm9(nKDpjR?!z*n6$ z3Li?t5eZHZw(i7x1^}3h>Uppj*{9Z53H>0%w2S<(%OMYd%w+0)imD3`8x-`4;G`HJ5xq-HO)}M5 zZp8`C7_&O{?3k{Qlnpdw!0zAK*+HGELPA2?NV9?vPEJe!3CYdt-j)g=2VrwI|boAMD3gUV;_I{RS(6YzTvwyA4c)-PhNKjdM zIF88#SOP9&JAkVMjdLRhZtLLCRgXKLeXq3sb(soj*`yjffyrkbm>h^wH4 zxqQ=9LPU_1KtYKSfkD>n=w|8BxyN6#X*QJRG5dn6@Ns-j(vI!Z zHQy!dBP;326;g7Mo`Zu@k#rh*dJt<(N9{Ze5K#u>3s}mGhdx3i@}tvUE%Z~&Yfd4Z zD^7JsvX1&18Z{T4;EV#G%%sn#Z0!&iXXtp^v3t_-wnUIL{POH1FToEdP|w_4bnq^O zfivs2t1v0@xzrT1|L3FPF)v%L*^3Jv(yYeDxn&1kPN!X`x<-9_E`!mBz?uLA+*bSP z0JSv=q1hMYSJWY!1E?bdIflxgZ}YbV`S)YiHKw#&-{@QEO($yLew*t&FbQVFE< z{F8^#C!Rj0rt2=x$}vR5tkZG>(dywUao9RowphIUsnQ~d@Z^;61$AwG;!zCy1a48p z<;)N7By3o$Eo;)q{n3MZ3(1EM-+A^fwL}WOC-X;s(w3F;gN%Tvf0&<7ZVOJP|EMRe3KY=AE;^}w<`~DM9e&y5d0ZR<+EP#&$ zj=ch)MZ@<_bsu$~r^4$oOxR3@A&MTWJjDeC^r;Hhw|AFsT+^9=8>A1bfDpo68(jEO zB{H?p$5(h1zN+#klXw(?wG{3Uhv-$4hTj_HM{XV*BS1E&qi3uo3@ZW&9G)y@?Vow0| z8-}5;L0ZYj=eDDxfe;WKp%O#&efJ z5}6vFzntz++UvMuH5p(~jAH=IW(f zI%0~D&kT5GhIl0!XOQ99ovi_Zs7+U#07EUIW&|s}QJMP?RFE%~>1B|dg2K$MYms_` z+x`LuwL+E(fDf*-wl%bIeXn0R9If@f#kc*4fP@CZ`n2$7~5=SvF51-YZkg@T908s zalg_oF4S5VxWDU5TN0O8M|E;!s8CPnC0lTa#@QZ}36!N$^^ZV3m$RLk^oA2Vo`0o= z1;u$t`?pql@y%}3Pn$;rrr8mqu`fd0Rt~ckNOq*bo#mU75YZ3jfL=#Ww z(!e7}g>DzgB>V-M14yG}t=1fnlk<;s=KF1&9XYzX`v|G~^z4l3Yl+jTfd+_2-ejDK zk&$MNz9 z$u;1o!IpU9*_5Yd#c5khwe8pB`eSEleJ3=5u-lXkFMSvr#j=IAW7Tn)O3O7hA#Kjd zcbq0TT8cs=jG^183`}xtLIOw;{HghR_~A!Sj}%!Hu<{_}$Ld?-QNW!AK$qKgh5|dJ zefi++aoP#Eb389o+?)f0PTF!=^TX zWdQs=IG+P)i5i`kmlt5CuLSKt*w@g|z#Gn;H>l1br;`CbfJ`$8BvW{=nps^-jr5MZT$tQWkU1X_$X?wP=R`i zmFzabn)uzkepPILY{YnschO=oHa$J3dCJ3^W#<=Oy6vzFb+J``9*$!Ebp{ zY0dyn`A)uoFD5VFod4)$7gdHv{`z&O?hAn!&lfw@eNhy@#n{ClhirC^uYJ0;PvzcO zm~t|wln%_9(ZhhARDHSld4*atAJa76F6pV0X2$=<}Xia^kMqfI{ntk zPN%P*X$5SY7kh)*wrgQhA7(SJUE^q96bdSy_YbDiS7{4wlP zXv=oW#OH4BDD!VEfEX|^VBMnm{1TPD(V3c66dKU5w$m~ zDCAZY6l_~bx{AaP7L5pOmEicCcU5x8$Uli0~fe7 zXmqqHN(UA?;LzW_d(D7dphgF1i7X^wUO}e!7^3)$o6-L%Etma*_c)5UECNW6jRS)U z5FTIZ-p&poNIf1+e*}cPRn^SvSEWfjUT29|frdQcI(I1c@(Lyi5u7E#@YDrspY z_DAdK>1ha7VTE)eH^;@7NYP*>`9Ts^Yv-s<|E$vYJ5`z-`16&Ps%KV}wY8eKXIW}= zlbfP3y=#}p_aPgoWK~rim04tplJbxAQ99Ps+jioD@ zvdfFZCl*~AS1E;9eYffk-I%(lo5**&C9#_X1y3g+``&Ab5ehDiye@TOOdC7)kTZh@ z^%e3a=3BS@Y_#(fzm48wdkvSX4rVB(FOm20bZd6Tv(~ce$u8`0JcTeqAE!5iqtFHJ zwB4q79bv(%nV3x3TjQgf;of6eZgB>5sV>n+7-cn|NND$$bV{B#SH0_ff-26VI8@NG zOS*3aa?BQ1R#rAPx<@Sl#oS%*Gt<+1U2W##D0VcSoXO@6rSeZsO=;@uD=3cvFZkFMcDM0r5oR#rAdzhu&a0}e~oxh_;kJ{y$lT6fw!^#s0K?$ujdMmw(LfbJ(Ci*A)8 zs%sj_M^FZGQ2@yIOAhgdV>opd8fMNr- zE-u_%TuxUy0kH)><4ZzJ41>>-rJh~iB7Ay776p9Ya$Y#dT>(VAV@N^xoJ837W<+BZ z$$nWC6UYkc9aklyq}E&;0F8$86k?eK9&4f0@R7JO2y;_YQwy&2Tf9fbzoat@7aSyo zR($9gknPcPQ%|<6Z1&Bd*GOvmz*vi5J-`0Ke~4<8X^huN;})VCeiRqfZkhMTXhk5&QH%=-CWj*_qh@W=&ArY$Xj!rkIXDp z#1zw8ZNF&8f_q2ebxs8D(t@MiBq}GkQtn!L?fdMylmw;j`D2PakN!mAzgkOz-nRap zJOK06lb1cidp$4qUM)pFe9F4n8MIyBsc*k8uT$Bu)f8s7ao#;u-Y7mX(?DNz>(O#% zYMq@IAu(evI`ELsVR>Z#kb$9Hm0z_IMLncK0g)MQ~2D?}Y|2p@1$Wc5a zHipQJZ_BiIc*rQ2(TZtrWnVPwWUPg37d=pBP>Eh_s3w!$dkOD-2 z?&r~?N9;A~nZt#eWn_$ujOd7!H8l}{##z$f$kBVsdG*;GnGNcb*fl6JSllxazHl_! zocDV4#K_zJXyAxerbu1U>ybet^T;2|!hjki7M++lJwM;%d1@6T*2W^|=2mkMupu_9 z7AI5XbM2arA;fNiBPTCEJ_hJsN?mq)<(h7@3V=fFrpqarl=+=pzwBZ`%T~5*J70Dg z{#vN18Es7$hlTW-T>Z+7u&Z0g4$c7XxS*t&kCW4-pRuM;yNWIa*~HAu_p;x>_k7+B zjYNphSYUW^5`OAwd}-&)f-3+bWU$FY2?R>ge*$j0x;Pwt#eoOJ@VvPiG?>davUG99 zIyFowaV#k8Aek{m>h*PUn-dphSd}Gw6{LV&U0uC}1+fuKb&4iv!rJfkH6|>$y5$IR z4q#0K?btG!6q)L2k0%>seMev@SuRIxp%w7op`k!SVaS3DbUWYxn;ej40R>M9!n!~J z7-;AYJ@;(FaT1q_=#GhtqeQW!_P_AHU$}sN9vf2w;p#MR3$sZOkYvs2hOcgIZ?8Mm z4Vqco*+D%9ag%aFf`ju53MgL&4O`gQ+38P(41b<1pHfskL2G(>CQ^vfo|Tm)*36M{ zt`0(p14m2u7VOJWq2-xzwY7b4)5lF>T=$8`*BN>F`FxHm9nC)1fIy49ECgfm&*%ND zoSZ<6A^=acB(3-e!y|<6co-Q60o~p@p4_Hp$<*&xjwk0T|_Q$1)%;DeK_K%*@0oKNJ`O znbROOx)&kYDwb=JTP9WY>4tIIMP^#n1r_Y^={dk~+}_>-twp+0p+Sof;UMCv0}uwp zA9(~(dV?%l8_vTO_nQL&62!-_L>H$ za+15m{`Wc@&dtGrF2WPO4R+7wX5u9q;Kk`RiZKK0-JG2V_{Mw;`9yJsU6cao&X$lZWh@?v?Dk=`__aqH&fRtN`inz2BNa8sRmL6jOJrjcr?PDsDvF7gv#i_Sr zFP}2~P%+Xv3*%nUtg;$ET+IzWI~MQ*eheJ5b`3?}zP)yzJh;9+CL*NsZfGejRicYS z(jdo-jg3W|JZ_BK-=K-@o0;LuRw0d(%4SQHq5z1-EF>U@rbsYz2Rlh`W&1cf83ZNOQDujpsfG4$9rJ$yUudPXCkEEoeAP-FA1wKRgBrPrN zR5xc;1&mjo8l7%1HSkbp0sTO5F~Uc>c5%3h@X2t4nBP*`s(!0XM#WCbw4(n-z7>dn~=0O!RbuGwA5)ySuw_PL=+MZ8X{1 zI1e%=>zW+eG}5%tthfXah=(Yr#uz!pGzE305=jQ7c~Bpx0fSF-J4*Y_u% zTG50qUR`}7G3;-jMNdF3A~k=iX$6)w&^wMg34UrlNM5`#>kcPM=CaMOyaJPhi;vG2 z!QBnihChFzCq7AtivvRj;FVqv*L9FW26=dRaGO6` z7`?pWh+6M7Wz%}|=8cR@uo@i}0%&AV3!SJ8x&u;_IWLGSW@rx8vFX zbc`TMsnp(WWYSa8)}~A7Zvwz(JN0ZjPM67`!c3k87c;-l+0E_zn$FBOp-CQ;WjE)eKz`0IV{Q_~ed?7gJsZqacXx_yinZRQN2XlCtSEMZIIuR8sn; zUI64cIPQ)O^MGVQR&mQNE>_4KMoh(BCJr>*&}qBp>?|y3a8W>nV>#^%VnzuG1X3Wm zsj05+aw_}mVTen0VEYx$3XYPymX4fN}KW{zcakgf=CgcupEqnqiRoB$kOQ`ZbcFeRQn5_6zbC+tCr7;isQ6esSK`Z^s5Z%j8G-p7Zpji>H84n%$);ms!p5Egtl29KN0b1OLF(jceb+iMGS*~yko+{n zE$QBMuG3Y3d!U>^u^rFO&xf@6$guaB**tqsic_SRN#NC>>jO~lb9 z(9nn$qqW=yXdFP3po0+}c!y_`ue&?XSw~Az5hK|4Y~i7>?Ng?aYhhKb20_A zS>T?ZcQtgrSL zsN7cxC+6c56FEvWV9QHLNWe1h26Tal(Mv}Mq}ya672T^^Q#tfZOx4;&$VX8>R;2y6 zL-b=Od4OpH8ZRI}(kU|%S5Sb3ev72`H`0nX#0`8_KhG4=y?yKU{x$J-m(zhH*TB}k}IMMU&rKKfr*}8l4Cwx;1Trto`-c&_s)y><10C;j6huMpW zgap7VAdO_jhB@jgDn@`DMJPTkSn42~wtYHdQ%zZma+?Q@)Ff;Y@Z9Mf1Xuh6Gj{C+oHrIwxZfHWkS{WotusL^Fx&b(t8IL!r=64-`79PAwprV+C6 zl$T!dSv2JLhv(8&Aa@7gY=!TXEAe0R;&2EQI>@B0M}T;2eu;7Wi0Mqmq-ofN-kw zBIEMqmwl}VTNUk;6y)ThG?K3o@ra3ij|aJrkB+dp=tef3fh6)DoE{cAb@d5vxRF*h zxXtQnkmPqUT*T|{k`T4AXcYxvn@GB5gR8Bvai&Z*NWTl6Cu;}JC7NF4GGPO) zClD}dX=wor{>s1hUZb~qSlgrzc>B}q+Yhgo+A1tVK#->iGNzuM^|@C?OBPEN}3rhxo=7@w{1?5*|Q2XY{_2k2J)37pR%t6C47Tx-QZurcqp=+m|f zN*fr*jKI(VT`*i{lM*R+R7+pqmzW*g!>(VAkYLD^j5dl<$JM6Xqp~2$S@dbY(pC6Wx2S7C7wa~nRiTM(aZmoUUYn1 zt?lfIV#-q`UfX#fR;1povdD`KRB)PQ8BI+-8&ATAJ`G#URa%Z3VVc+eYC7tpw|Fc- zYr(;R?~26#XNx{4<*?xR=SN>0Jq}Ah43w$6d3Q`N=IYcL2rK~9ii>-zuOII8w-eU=7yBPN zxjqm<9Nu&eDVs`4!e2&cXL%X)c=ta=OAd!`eC|I1n&O1id;9;l#|jSp{hd-&6W+ju zfAju%Bhmc{A3Vqja)U9cm|<$fuAApj^mh24dhKikeJI|OW>${1Ys#UTI@ud8`?+bk znc|YBUGVGb*Xx$gG_p1NdKea-@G0C7>KE}nuvGrx`BFc zw~LVz1&etbq;#4sA@WGZgv1uxhb)z9iCM$aorKW0f9~SX4^66-uN9*+M{mdTKBSXB z)edVtXnNG`=_{2+o5m`eaqjny{^Z zt{etp+9A_WPW-$I;SK?RfhES)GFP zi+FSqM027oZk(}_xkd@zcMfbTYda&sgfla&7G3|_pGOLJ#l2X-!bY%kQC(j-R;Q_6 zmu_YH+oEwQ2cM__slOWa4zOl5TtYa-f{^$OGIEiIG`}-t+ ze!>XAqWsVC{ur$7|NQn~=?1{y|NhG3*Yihx@rrb8T#Juyt2+p{*67^VW(7>|W#Q%XzywB8bQwfWhJ5mfy>Cx?PwoN~P} zzHDy-=EyCJnBAu{tOQM0@1-OQKIRW=Cn{>9YKfd268ZyG|324`k3nF~cj%4tsLAa1XYsm+~%I_qvF?jKCAgw|1_ABKyx3eKp>g5 z<(xV&?a??53y$5)=6t)Y;VI0=w-v$mzt<1}OL~vM(oROd!fE}?x?gV9^Y);}pS%Y{ zBo|Y|tKs5`)l7mQFmCGN3$~x4UW6c7J?PQ!gL(l3&SvS?H?&A z92g0b?5-QDGkf!A3L?L3Z5Krd<%|C9g7l*tqkH?ClfLNehh8CDGdtfmhV9jTeNh|6 zMFiKpGC9LNn`^cb(f{rL=x`VR7N$TAe><6w z6}(brr)9RDG){?62a|s_vZgVPWkpL^_uo@Jd%s$18dnig>0v6qnU9Q=Xj*4o+^~EU ze2K6Ts}_@*45bKy{E(McL8c2Hjl%?;HPr1I0OK@0a%?3dE@PG>5j=T+Hj1P(S0ens z#xx$sQDCwNR#HscKTO##F0kr0EB|Si(UZESmVW)CenQB30JcL^tXi^xzJ6?Kj=GE` z*OKE`)Z5hg7=7QUS>`pjhPj2MOAg#3TCECFYwwof7i))P;3Dt+|HpWhW3;5`MOPUe zZxMF=TwE|dhZtpZy=`T9^Q-@B{qsa@2ai~RT*K|8hk4dE-@ShB8H*pS#X8ryKO3=L zC=zyj9U*$(zxwa-su;}KDA>NCtQ_1fishiBf~wp9saSomOV#C!Nw%7t<39-=jV%?{ zV|c`V3c2d~zP3#=Oh!!;hYQtbFLGJc{77( zX0)v31ouMuzW*D4wG_c59AjXFbzn>AN})rkUCciKo!Jnx>?V+b=N)D)L|(< zEs`j*u%#^fZy7_aQ90~&NZ>jc6l4Hsh!QU#)axueI|G5EI_iN$+4bZ&M}Vp zhwQC+oO62pR@dk>?3gZB@sevT;~ha@Bfr>cFGDICLU*N#o(6wybprD^_>g6YOG|D<1*yH!tU6H{CQ5SMQ!mWy+Q zghjLRC|#S zKdTv-YiRchj36O!KJ+)g)rbC^>60grOXJ~L zr!J?^`uX{O77Kj=d~DBo+XUOeY(n`o(9LPDI#qe`E0 zK24n~M=BzxDiQH3{}hXo&!->}XloXX@i}ot{l6A9azT8|%$#xuN&6X@V->h|_wmtQ zir6p(0VPSJ+~#*Esej~qAE!R=dTq~+00UFr^-em;b0~(-UXPH@Pa#WmyXmIBot=C& z)a>)2g}lt@=opI$o3!lj0&!|eiPWrI`}RbK7$S0JH5RkgBS$-T#>VM1XrL?UDu+VS zP8)tFFQqu0+wW$Krsv`4My@gyNF0!=?>>DNNH2`a9g;#-8QX`N`N6iTec!$544q+j zbk&kBZ}M_$Sm?$ua&fj`=UOu>KtM2Y!h41rN>%WQvLjqW;LoyRn6@NeaRHlOc7Okl z4RvnSok$I4ZNbknojW)%$V_81rLM(0;$7%6$8Jm4#bLU9T&exU6ncgZcf6Jgl#_YE zr&W+cScw1w}g*SjkkVM6Ve^4aG5cbK&|3 z;>!Ni6)v|H^1(?w{DU7xb+*|OZ?UvyOgslz&qb>@`!y`b$hwRi2e*xK&9ws$SofZ1 zkK|KktkqlF2pdn(i(}&|BpD&t`R93wCwL@H1{at3N&NzfEHwFl z-jCXVKh<`4J?y7Fn$z(I3rwrFq}JUfCZ#7=3}; zX+^4qU4V87p%MNodGJhZm^O}J0u$l$Op-Q{ufFon(sZ7gm_0`?_cHBdF?l|m0`i`r z=Ja8mQ|JDHDt`8cBFuDmv+~o|x$ANmPH#vgHFXSD_ku!iR-&T=ZP!hGBnkKjQS|r! z41Xz&`PltG*c+Y(rPYOCWDVa?#e5o4&BGiekjomk-267Z88NcCqW2uf;F~lV^w9EA zi=|U|-O=cXTI{XdJZ_Lg!3txOUSIREnC>N6B&1Ln`8bD4kBKDCKrIo@UW==rAFVzEfpVmx zr%*j(=zuVUa(T9;!(UM|QPS)kV&~BD>!c!9El*nh46SPWv}v`|dV6AAwF!e*TUApP zx`uC&i1<=O7b3*5O7l$q^n8}NK)WVto0z3uBvyu;ngSg{&korQpWJcf4Mh)s;6 z_1OOInD6(quF885q1dbEm!XAabTB)be7&@jf;5u3+m)tvR8IU$Ds(Z)zizB({&j^>(L`^bMfAn~n zz7l#hS?M3V<33qML%!h|O9N`wtIB@zroOlJNY4y!?TjO|?2pon32=>dR)=5Pz8wxe zeG8V%*ZN%y(fRIKN|$VUt~hC$aMOpx4XmJ4;O-E*u=6&XzAr3>nu<)s560{zwa0VvwW)db40j9n+ki+x%NKHD}*r z&}4uWYIeW2rO;1LCnQP6(}^B184ZsfSU$TR2r>`5Z@2qy+T}q`z-EPl1I%&z*;`SB zf1}3^IHA{!sIo-4Wbd4@mJm2gNB;ngK)H;U$yXtb4TTMbSqy3`#m1CWJi((4nsDL! z3q5!r(#y+i!e>23?Bma$0mkC}WA5X&+|j)tx!(44kF|HM%P<<_SquuR?tjO*n!3ZH zXNgf)x;4FX?X#IB_Y}j5QSoB|HpMi&Ok_8h+!{Q141?54aR6XC6-{V+giAQju=wBb zPjdo>S1zeIbvc?dh}BOAzWeHpTz@M$awj5po49csc+yJ2sLV6}foa;j;%|jNZ1?Kl zr|88um|e?^E3JOee|n{Jf8!4x1X0TL5I46v>Ygw_m-@bgzx20O7C-~-hrm~ZGb}x| z+laMl1ZBpE4IBri#kEj1N*E(UEQ8^iRQCwA-RE`{_VXh{Dzc{@(*jPLAqqG{X$pvd zXJ%Bkw~N56g|rtQp6hOUn2f<3=L*k<2xk@kkXjUtiOT#gGnKOp{UaRmFyahi*)ih9 z8^Lg1e#&@h%gLp(2}j`<(s4?qM>`#UB}Hq6vh39Q_pP8LU>dpEWW4T9cbrkfK51>W6@!a}rz#oEex zkx&Xs(lkg`cG)~`2D`@YRODF2_0szUYX9imgmHB&Q!6a8iG4y#-Z3F@6`8H={_-lP zBvem%!EPZur*zrB9d}9{Ht+|CJ$_e4>V3yzpDZcUu(`Lt9jw-zXIhyc%anVI4-HtY zJt%=>?>Z8WK&4KnrPf!(T;$b}*ODCc8oSRp(OhvqIdXqoz|A`I1$0l*Q;O*^UJk7lki>E-o`bqhR zYJ8w+QW3byPVTbodO=JY5|Q$LK<|6%D+stpsRyGnWs(cf_)_G}y2w)G)rodDq(`#> zv&&Ab%PfNFNLAg!=DD=NIh1U1Tn&wUIy(f3&JJP{h=zKq#xYdk=oNZd4aKDNdR#05 zoR$S8y?v3W5swjz#s<*&27 zWWkkJe=7Th=;{5&1Q;>;D=&l3#5=uEwssQ#G&l%&3+s z)I-xPwSjUH^Ii$AM%NzY>5iY2LoQh!Gx~vFx^#=x5jJh9cgx8=iA?~)>cm;(8h%0YvHK$Jcb0?P)u3#@JG&q;whld6%gRCI!W<4 zRMk$+$ZjI1QZ$haVMjgF=2kawecLxx>MLbm`jm(8=Fe?E2(c(ePE#Nlf|VB@ShL`Q zZ1BKP|LqtmKN}kx<;!Q{!xj?vHl@Jp2P=v(hr;fBgT1pe2T=FZ#f^Y!y+$btGJizU z>q@lYTs>^g7p@dAUVig^;R&`4V=bzs<0m2z6y7CX1qw@(*D1YMMvqqy$1u^ zDHsK%H^f;vJ=pE-?e%JQ$H4$u zS%h`DGL=GN{_A7hAtApMp*&oOB&Ku?)0LrECQXOk_4cZ1JqD2o4V^$}LEY zZL9_GzZcPImo>|DuoJ7+%jA z%q*RK2w(?{4N z64#ZUzpRnw<58r%&x#Sb^P*%jmB@+w-Hr;m$6NF@Ss+^zTQTNrH&T(*NWh52%m6 zJUehv0&>KyifeD7Dv7}W+)6Ak=-ITqyuI+_XV3Ua#iVB2AI)Oq8->2YMPbTJNu7u< zTvW?=C%6%{kvXrfTY(AAxkRR>VZQlG3b2d1g>9c;7rYLH-7F}EydR_P>Hh?Wh!2Ke zdu)90NevZKMp)_Mtnk)%QtEcwxn~_>|B^!t=McD7VC84)s?Q>%cG~mz@6xD^bsz*y zFxpZd2WPZ>@T&bCsniM9FUG3nUmN|t6GJP-$E=OmLs4u7mOg*~bjz?uIEkf-+r0k# zxNFYyuFKF1s{Nj6IGHpp!_aa!pJWQI#NR8Hexn}pUTax?xw}m8_)m_2>2l#=wRFj*5 znR#79%4U_u^);13e@UU+4@1n7zPN5ZzF^xWgZ&&Z#c>1#NaL8#X~Esz8@QtZ4>Q3; zhfQ3L7rI%Wnrqzr-he03$t`VT53%%F;LvP1Abldo)v^D`Cd2_c%Vd ze+u0dV2yTn`6?g%$bMDcymeAxA#(63?c&bi&7{BY7_R2e&OlFnuf2qpi}qQ0bvs&a zGv%`Y^o7Z$<6*DghXlet*0J(G;f{IuH!9Z4oiheEOXf2}p*B9+ze$HX8thPtn3&{` zpA&DX6zXZHe<$7!`aVL&JmU>{LF#{gLUQqaK1!vmn9Cq0D^{9DXekMwm`#=qxqLKw zonti#-@S zZ1$b`M{-p%OxYe?)@dW>&SwNZxixR1wfs7t2dK#4)_7DF6j`@HtTY3}bU>e?=(vn% zC;fg+H*0upGNo9O{G4D^~Rr9o$e+GF;1!V$Wk8gERd3o~A6-6kZ zmbd`gMKXUqYn-0Z0QK3aPI*F@-Xl4;lwf9zZEJvNzH3eFp(lQwh&1r{Q^WTPE z%_n4*%a3_7-t`KcT*T-#`Hb!r<`-TZp10JLT0aZ?+TDC@8zv!-SjL~CC~&NrCwG?F z4KKqEUj-F1g+75jFwu{|ra)j!3e2=hU+V)IRYwfZtJ^Xv@6=U!0-uL-bDwE?v_al5 zOIny()pKz;-}H#RS20r`(xw<5YF>X!Q_ zuejE8J)YvQS@e+|Uxlk)T-TUuVJChTRT&P9B=^%hEds#Jwe`p?SV< z&B@vZ+5CTjuX%y==-^5F;y8KNYQpNW{KhRTYp&7-!Bj5&jNYD+$Jfc)xevw2kZLdM zayk-T{n>s?E1ZyTS|{n|QR2o@4MwtB2&>v=0_X;jQNMwWyv(pji7zO*N7e`y(AIgVF_`VLpA&_w9*8x zIz~s%vP))(7eSn$nj$Kn!gBG91Q)M7b`sOvExAhpRhF7?)rB`Tm)$Z6z3rMvB8F0o zflEEPhH{jvIIZ;1Uo(iw{u7hDcw(xWjI=m{uyVgn&%=Q^)IzM&gvzz;V3Fd@{ytc_%{xH&u%_E`Z=Gp z{e$?=izC0LS-$V!Rmr?TRKK_Oy?>KfSx9zY`}ypyZs=zwV-!?cCO$#s_Pz}tr)_)D z^L+Q_EW!09S#kaGrDTb88fWox4!*%{3tmW7P0O`k$&S#pxhdwRX|n5_EBtM?^w{Q$ z@y6Ak$Y}eV$+zVvTZ3tLaDJ{0=>T!@RQmWZ(!$NP;@_A3AF5f+rQ%cK8}4KmuWqzG ztEYLrw)sn%8XG)*!t&VqxE7tSQxmXg{7uUt0vr%U6589P^_ugm(Y$&W13J#e^R|AH zGsPq#JH<$q>;$`uvE6fB{J zhSfZCyFR4pr;C^Szb`}!8f^EeF*N4B%3?RQsy-Fw<-l7Juj3XzIl!@w{xUf=yWKZ{ zlZr>vQmEs8)_(EPfGBdx_3mu4mkx`xW7Bo9u~j%I!W^cMcZ4+h$T+ME9T?3pG)46i+JU#BXqT{Qlg33j zxk{p%`}OL>yH`;%6qxBI+C?905(ftIo{6ew#?g;iVZ~Zz_?5c*%%9P-Nu0K~UrAH5 zLl_%pEl$)DvcA)jnhTS!9X^(-my?is{oj0@oBu}YQQ|(0+JNfcU|BaMBh)sHi_2Ck zMWns_thYO@@*2FrOTGUgv37d4_b#*Wal2dhC$TIw>i$o5qZVla#E$dLeCuPpjcTbm zve+2PNh%zZB3kV>AwFkM_rux6C^V$zFo^bVec%1OJy1^_YM^Qi7;GuctnebcOiqotRXTo4o|*t5JiZ1dN6G zlWP*es_vd)=|m3?qw9+chXhL7=u{1uuj>Mt{6sco&@)p1b2|?l2yDR7TWpgk z9FEAVL5?6#bS*^KPe;SVsOKeKSGD>x%C|ezalNfHNGrYrGPjAPg1O8v|5Tew#2hNx zC9E@kI+gqP6>+svsqB1duGnG!?3R927P~@4yZI%H6*JBSLkB>k)Or3 z7kpQ-_;!Yh^fb$5Qut)GWK2nwSfpXbWu1e>O}VAEuE#^ZeE${IfIr znc6^2KqlthNhW{ubtZG%%!1E`SBq_puaoyd|LHgxWc4=@OIhq*-*wCHFix3UgO=Z^ zE#XH|kj^s+5zxDXz~kKfcYT_>Ep`EShid-J?zYoT*zbx9RE49G`s*YNVGqB`)%}** zeInb)VDgF;GNQR74aMBm`+`MMAo}q#GoM9t9~W z=^hlM1*Ch1ZWy||hMZxjVVHWim)CRO&-Weg@vc8O_A$Vowbx$xJI~*FPS@;bH3>a2 zAql}x)f<+;zIiXdG0!z>aqYF{mANsm=;w?21H={WZ<%WkUytzKehgKz>E-8LqxpH{ zKBbfR+%(J+s@O&jq}C*)B{DtEprDcneeqm0;pRiSR-x1HW?3*V3Gv~N9l;~5@hw_? zm7qIbwzjvOBWq7Li>|2D*-Cw%yd~m;O#bI(eySV)-vJ@gGcY7?i0t~8+u>6E-Ahl} z)O*-Uo7mMQ-hcRUuZaH92TwUe@VIwI=(qIZG+W}Bf4}gY-3NiY*W$w3O;c~FcBb-K zfUO;FDn#6$c25*U%p~94*_Ntfo3LyW5L+Oop?pE8vp%PK^o%0*Yf4uWmR?o&ErhS6zgJszJG~@V3zw6GYzt54s9rxkY zi(koVmPy*4o%Tjqy&R=VRuo-bq9Q56%ZUFQK|sva9xsyn?|8h^&;F37!kZ$vqK$z* zXt`|ok<1mUu;**Lh3!;bj9nQ;AGpNL%0{(#cP_R%1Ybo1$V_g5wQC2IYvgOgW3Lye zJ)Hg)*Z?I2~@YU*QL)T9ZUS>A<-~$oh zgH~r;m;mO6Bf*|UH~6K+JHr$)LLL++xrRrrrKK5u!$R@CIN#PS?oar-* z7}(_{v+f5za(-)5u%=Q}w3ls`cs7t)(Ak#p6ry%7aXsCzBNcPvKR4BPTh34?@oo5B z*Fh;+(}nvJt3R)oo^|0$&iXeqGl@htLUxy4o*1rRt0LUx`ZdXrhIb|39ovev*I8Iv zUk@l1D9KRyBSQvZ8LkJ1k}}>I4)pYVS|xG1yPvQ7a(?Hj@mrtBUi2@Rtt2Io8XC95 zlF9PWwx=fy;~O^F9l&d2G6WI5~{fDA_qJdiFuliPP23UyVEe z9u*^)St*k~3!JsVTqdICo!q{FEq2?ALxT0Q2X9-*{qqjUlJ`UeeW{Djg@e9dCBL81 zu)Mtu@}CvME>tXv{farG;|RVrTrk`!b$s{W!po9C(lLsTQ}+D9Kr~^~^=?*OqQ``3 z!B}LCA^I(XJdPYpn5X8HyI(3U`SbbYo=)D{RmQPOJ{V~Z^pGWbfNm``Yol{VOAc%8 ziY{}c5I)*yQ{F{yjktgPW)r~}&%pRjG3@TB75MB7ZjaqeA>^8Iih0BBdgOXhCvr6; z92{DvreI+Y+4+H`sL5qOluq)M?4+3B|P=ChgEdrAL4+k^wFw)&T>4%2N3h?p#Tpr%AN*AtAwfl*mW-&=I0 z(7B3yK|(oSRy_4`dpH(d`X(R4e1ZZ}9nRLLTf>jGn<@P{*64)gbWbk!FBV_`aIA%# zK79wsXI;ht;MmIEyebQywqc^f6bT)H-u<{WU1g^oF9SelAmm(_7O=6^IUg-jzI8I| z^N~*DQ#hkE0^TY0K^b7P|4<3F00fF9ehdNhbr6hDYAp@0^BGC*n9?ZMpiJUcT+JO* zm6ZVKb5C|lr8o#X)0Y%qT%I`I(B~CqL&o33hpO`pXVSgSq6;f4(+Gc6H8qBN;Xn!= zAYk#BrEe0T{x z<*;xoCds%e=S_QmHI484-md|swqCn>0X45+8l^YMo_uL975kU+)ogHUtywM30e@yk zix9)NS7Ai3?V?v*YMI75)2VZyCoME38S9^4_=T5trvx$jGggOM&GPJ((s}T8m2srY8kfwYZ)4^ty7u(ATEB|VP zUHT^Ws_WTEfZ`-ysF0Y5`M%GbqgZoR-X+FZ)pY>1Ad{7RtMO-?{9d~Kv^vVKtgp4v z0|Cg-U5B14v%-WQ#k|>7AM}%pOkx85h@BZ&n7m5cT84D>_=*Lb0Zz%9SCK%1Iw2%Y zngFmPhir>e4`?5q8x$Y*{%~Fy2y+5)&g^W)$Zt@KdUR;3XlS>h7o=l%PY-L$O^ z5QM9XizfszXjwB$RS5(fn-6Z+)N`eeF0WnZeR#>@VE@Z4U1_5d>30V_!qUh7fD`Ye zwRvM3axL^3cs1%W6g!`t{Z!7d(bB@%Hdc+}F8XOEuwg8A80x$de&;!2d`xpAr=a~8 z9Qk3*)8kJ}Br&^QNM1%p?^L^ef{dmNjdmvTMy-CKeH=~x@=w6CPaeNrL2l1asTrGf zmr6PGmab*gARj+RZ~s8-P6z=|s=UMJd@>_p<-nLTWchO_?qz0#_iJZ04=D%2<%J5| znnvg?n~C0mqKXUI^UO2pzu2F{3pigdMJVhc$9ndjiz=1=KzXeSvqIdAF}ZWU4Q_q zq?6Xsxt^2D`hqqyEpz*^le?gGV4eu4GT#_HH@8s7t|lYA`r_c~0U!h;MU;5=Ql`kw)zqXbaR(e52HEjjs3r#e!o3eQYsFO;(83#({-ix?;vG)mug}mza*I zt5WKSJy$V}wk==!=^{f2e40}3J8VDiz)wZB;^w1WxXC`s%6*wieNy)qhy~j0oi9+! zSt0Q=AH+04bkdZlmPN#dKr5a%W-_LH*0FD%Z za_90#$rQjN!n$e((AQosR|k@SmGab|-5%zp!CgOp zYgK{!g2Hcp8F_C#=LNpBdE~v4BOq%yjI4jYN4l z_tz|mAJ)Tl@1L=lv@|r*QF66q^PKoeVSxotlCR6j zlE!Sy#+v~?y9(3H5YWxXg1m(d_WD7#%c-GsXM{arNQ^HkP<-C-Q#3G4IdpG^1m-_YLI$nPnCmi6ynW6F!+f4T}x;X*;6`Sp7`WMrOTb zG>_*Fnnai=re!3Uo@`tdzgqb9PKm z*w!a~^zw7|u+(~cyrH~^n-dN{wDP(7a>8n%Omfe(&OoB4yohatQD$6yJ9b9mu9WOL z_tBrl1SlMDA4lia)#=s}^27>W*6P{?h1lCEg-=dOAtoE2sIfn z-~EaHYGXg=E>ZB9t9<=@`to`y_~f(Upt~`t2W8~HC7|qg+&jnX-fNlx8ch)(uI&kc zD;en!g8;~M<*9#KN6ysA{-CxIaTQEj`_Ul4nhHLw(s#rTF3JpYjS&_&*Amv)jJ(ab znbpsV!K^xX@k2%NhP~d|Owkwf{wN-p9~un7)!4-;<5!SHj$UV>u7cW6blXvh8Em$B z<}QL)Yei!N3MDja^`G<=uxsMxjTqu&l^0nQU)oH0AKws|_Z^L56PVaw3Lj)=DE1v# zpY-3(O>>%a?g&;>Y+neCJ>2GZgq;MZIo2Tl?m z;KvZKdjX3#*Oz zQd0kgQjZ{+QS`(r$(5vNCtp$FQdCU@9Q<|;Gg7)vSFE_z)qwP9EpZq2EEks1a?-bk z{Xr|@sxj(xjBnC++m&?Cgn+u|Y>X8+><TGuxA zM?{M~qRe{&U4V(6MQiiMubC&6K+#0;%6dtdFY?rU4KXLOAkOm~rLNlsG+X@e2fk45paNvdkUE&H}b z1f{P0i0$LI|24stUEFn(-j2@0d6_*U7Ev-&&YH$kNiXV|ZxP?8S5_wGI&(_STHvYq zPE2&z#hL`|T+Ilyq-U-Ev;BD%y0*rYWXCsiZYdU!R%e^5-6?4R(glHhH?Jt+I0|t< zI7Ixkh4Qh_F4yuTkRPu*=+4LT@GAz37kLU{RG#zba?P+XCaklSijfA+ei$!ew?f2( z;v{ev3TBbGY57vVomYlske`fLi@2M2G&5N5!>CpnY;n0*ffn{m_D4oSe- zmeG1X4-7>O{dgC0lenJ7#xTg&A+`QI3q8*X6Ie^Dla19Roz!#!zonbO&p!7+2)v#Jf-Hn~i}*oVzNDIH^_Lk!N>j;{%OwNQ7}B zyQh~zs@~bsT+sXu=%Kd=X+1VG(Vxqe41=ox!3_+RBsKgt3A0Y#+nnqBG%&rB!>nke z^6Ms>(Pgzqr1NCFmwPwb@*&yb|!3M2Q+87bZ2D_Hgu3 zrnL6{d*YNU7#|=X^!#$xh^gf>+-9jrMQzyPcBlnn^V2bGR-%7OdVULtdqFkaVw!fGy)!w)X{_ zehtW1hV#4q>g)HCXTo^B3J!fg?Ax8KjvCasty;?75f-HkZroi94WqJK1dBIpy@UA) z6=w&BdV5?En#C^H!0@0o9vex?uR~Lb#d-w;#)(S&!{`=@3za9u%M%xYEcDH`#Lj)nf`Ckie zUPZ6UUkiT;@BICA=7SdXh`Y7H03U^XI_zt{+(CnOPtRPqs)O+HbwSVppuuf*y)<=y z_%B~%pNxjn$Ze%_Jk6?d7=A12TA*660?~0W-ov&~EWQbT3nT--D5bbEl&yW;(f{P! zg^uLsH|@<49I|*B(qpdsedQRVn|m`n?_BqixqtbTR__+hp064tw-Hff3YMzf^8 z$U#vF?1*q2J>Kw&aZ0m3RPb#2mH1B0njbp4@cjAnbIBF6H>ShxC&)>47D+=+`?_2? zpH<5{6kWZ>B3NJ4ENRYrUp6Q9aOGDqru7wtb5gY9yw^5Ne0()BL348PE1Phc!$8jd z20BdEp`JM}eGUs>I7~R575rz2drg*z{nW3xzZ7yCg4Ooo;1d$ zwz;7@3q7Jq`^e4r$h8#~NTFnF%2z!!NOPA%FzB?X?&ULhlZ-2?NX7PJlg}qxGPob7wZl5ls?bA zG4o2v#}|Gkp=x;1iQ3nc9?wDj39#qq%EAWl`_q4Wq_wBNKZy=9?}wQOjDO@66e#{F z3JMC30BIl~$NuHQn_{SkM)yTtc|~PqCjqw!D^5%|X_sV)_YY%MtFlch5y8T9Q=c!@ z9;WecaNF$Z6|qAmJbmZuMWnnf?Q*!w4AYiki_=aFizZjX1)S#kI%*Urx!35Il(pqJ zCykJZq@e~G26eYxPcE5<;2Yq&BbNb_0&cD*_YWPP(_=SSNV3*hPe&?k<0QH;nb+iE z@z3;%KDx-WuIT6HhlA_|?VEp{C$sjYu=4jiEFx^5WCuT=fK(V4Hztk=F9|?R%D2*$0A>PI^abxj;ulo_iA>@}dn9-!ei~UnH1wr+P9l zl&npCe&p`iF&uuGfnmX#J4PPdm68!b&DI!SzX|X8ZL6ATkah_>Qd4xH^#>s_2|dh ze;zfe(oBAN$<}0Qj(7XvA5l>GFw*Q#Hy3&L@#9IIE5=Nij8_j()JftrX3C;KojZMs!b6LZx>|6x;jCd|jWE-VjCjBDU z<{W9k$0W#f34hfgp*=XSCae&@LC{Y8LUEN-RBQa;q~)a@1Fk4-!S_h!T@rHdcG|^* z4zC^9=|{>mp(fXhMQY|h3!p})XI&0RWh=PhwJjdorFNX&jZD(MAyHXjGvkgad$({d zlFQ^{ti-U(Ty~&%=4mTkbfUNzE03D4|Avb5N=A)4g+~cP##K6e^B!0BA`EQ0-;d6a zxCWq!pmQM)0sE@V4q6Vng=)o|d=8kKFXqf594vlMXg5I+)H&_}3-PwwF9=&Ps zBH!as{-`gNpA`1e%!qzo90etp@d&&A>vff1hgD|r>(PT@ddTiJs%duNSg_$2&?Nv5 zt#4%;>{pGwmiHl~i4v{{iXz!+EMW=;HpuFixs?-Pd-auS_t~xu?k>3PA8A4Wqj2h3 zfd~54O0qo>qc6P7#>YqSJa?HGR!SiY$CQiZ?k;N5mC|p6i*gV*A;OB%5LWocBb&sO zG5+fJ4iMRQSCrr$r*f2U+HxCL70e z>Cz=2X~Pciu)HU3p6!?->Z%K8fy0}!F>{aSjZbY%HV-QneXNh3i~X`d;b3R>XP@nD7_?OI?^#caAJaJ;1+Q2Uw@f2~x_^J;|`K)i!%nT14FUSB0RkstP>m9(WhC+X#P5d&s)To}G}HYNC73m4d9< z%DPG~Y86lhmZg4p&&`6cvpUHo2mAheb1kBTlG77$A{KUzf(r1-j9RVKD;_7WQ&E{G zLFSJS15&=1M+2H;sWbqu6SNw|X@nc%#O-g__Z7ZxRp6Hm=LBOX*c z0`hfXJ#oxtPzkf&zE~GwaZ%?LNn2aiYJlqZhVX)|PY8r0j*XGpa>@2ROljP=E-iC| zMS(Etbs$6!#AaG@UE#>%B;1UM!O1qU0~DNXAx!qkse54HB`0TebaV~)VZv%HpgMf< z(xsfAKO_9{wfHU)dj890FJs^>U#FljzaMOJKhYv(hbqSN^E1EJ=QrBu5&QUn+q6@)Th3?mu8*VUdY?)YI3; z_VQ(wD^IZ&VDp+98!I8XEM)PvOm#3YWar!CzMz+XU<9Bn6|utijL^fB~*}-Bno0Q?R~0se zJXMlv$$TCNWlwZ5b#3!$IkwqWDyDApzF+$D&wtBzvDzG`h{k-w>Bhr-D$!W{0E4r- zg%l8oNeBaN7d#+sJTRQ;_%ZS)?)q=p4r-WqyEk4$Lse`HTNoBTNI+m5M4~_c_oif} z-`y792|uVRGOeeu?Lz5R?N!EvPJPOKIihBkW=*);Shg*viw^S>j!L{D5Me)R^$q+f zm16x;9_6068#JKdW_yrN^D`Br8d$SCDq{35D-0UvE_NQ5uPk}B1OVJaK1{Auan_0SRSiCohTNn zEY+*wDmAd?SNHRPiwjDLpbd`i4wib&p2!mOFpfPOd@L8vr?^l{|9S9cw)g~#OXOC- z`tqlI3Q_mow=)Yc)o;(gj&YiE#k2m=_V2kvSd3P*pn)57BSNpq-8uWbmnwZq_p-MPL}^&~%RyGd zOiJpm)G3xqQx6|e`Z~@>sM^mmb74R!^R+YnDCZh)1e;Hu1(F_YU=+2n*vjhqD3hyx3tBuu+|SY0k_LY!d1TDJ3L|bX~2f zKB*`|c$BgUQQb{S9xInO4ZrTgzxP_RWp(r~cDfYAVGNxsH5UKVMfYt1xXEtfS6L(U z*RNlILQna5RnDZ8lsc2P%f{X^$lmFlN9EKp1&zDcI(FJLWJ)#qV1Q}0T*ARwe?}3z zSX{-_4jPFDKnh@g*{QO%wYBqBdAQR=(n6HJiwC)chvs)N zhO9!%gOA$s*NWOR(K*b~cbO_3Mp-gMU7!J1?H|(ht0WM*R*N{3j5OPsYofRyrD~VT zlay(&9lV$ZH8s@%ws)=gyT0yK=Q97^LS)hiJRJJ)MUUK_fml(P2ER&hm#h9-X- zTWA{B)Rb)3UUR_nDL0a9yL~t=CATGNCV)M69?I$|3r}V=zxk(&rTjBd{90PFx4%Y~ zuQ?72Up(u0ZQh%)cmCOAY7|}sS1~G@=~tPQ=uB`uxJ2^hMk((ZRyfLQ){^M7=naGr zeF2|2m3Omj+_LqdUJHzeB?>yH3d-Z|Ng4MmMjVU>jOo31D%139St$yp4(I2B5*Rn; z7LB$J1ZFpDz0J;hR&=V2INB8}qB^{fiqwNTo^|p@UKtJAW?UWNi49;I%wSvJ*Zosh zps04tc&Qs1d5I07&Wa*&{>g-euWj04r}FY$9a3&S4y7@np`7zXqUikXR=no+QgYcM z1kvNUJ((9$WpnSB7Iufn(muXQB6(|W`;wD?6E>jgoyO>J^ksp_hv@06Npvuy0V1*r zLlW7}aZo8upMh>iiv|q_N#hd&!R&f<0+~DwyX}m3@j^ZabBZ}XN`$#u6YPlx$CvDs zQVotg-F*V1L^W*|I`7)uOz;`xbw2LAxNp?xNoW4ES#&|Bm{?T~H*50Ktlmf-r?l#) ztLvP^-SK!9b!MppE12hI3FWoUriR_@iI&TOB@P*EVJV-we~xKbn3Dw#KV@ixV!Gz> zxTyic>=rF|;1XxCPG!_q%?F)}!9k&g0!>0L{bjl`XO-7X%lODd!i%`Aq1HHN9^+H% zj;QP)&F!I$m%=wP4kqksp4}&<@NAr{!ilpye7ESqNe7$h8JyyEc5Sj0e|h?3Q!ZF= zxIfztx1C1gUhSvh6TkIRXsd<#LU1I)tjky2!aT{&%X|I6J*}t#cDQm%+h%yDxqQIU zAKW%@|6z1%CdmSQx#JW3@(xwSg*Rr+8H5vJTCStwLji|{a2sz{v1%Xr6s-{R`N-eS zf9I=aJM?of$JuJ{4Kta}-;(WybNii!hSY9E|CZqt0r;X>qes!UI5K?bC>fN_xKe6V zXWH*mQIu+OUwZs3CFAmH0^4{(5i?Mt4<5UmdoVSQVNVvl^(g1MfLZ;nm>r-5*jSZlD7ez((h!WXsJC(IsFHjWr| zyrRfP;=QAKT*9f)>o{13$g?J!?@YgCi_XP~&1&{eik%9Jr@Vf}$j|%aRr&Gvf^b*X zu+UK9CVbCwhCc6&;e5P=X|P|i9RmZh|DYoce>sxwPUkHu<4T8?c4BerMceakTq)F0 z@s7!)fY|@x0-&+5f%{`ze0ntBwF=*vHbj6|D{3A;p5u@%8n!lTh#+|?58R4fUh7S% zG3TTF(?a!g7(+;gq7HU4P<4B4EA0k}(2!!>K!ZsM-R%7#H7euwevJI`7iNtA{^)#? z#YBk~!K2h@bf-zZRSR()dOr(IU$MqYWjN1kjMK;@$;fATuEV{; zY429{u{!zYYB|!_?PTVgCW+vg9su+Xp0)7v5Czg8tiU~9D_f16&yMG)V4aylQj)ud zB9nw04HT}n&OO#Hz_;BNiu58P8hiDmdw)b;9ZH5y8)OOj%;%P$HY}!!A4e@;AioK7 zSm_64?&dv*AiP$J1Qg}34gp4Qdy2+)KZ?NbI_mF(1#)G!D$h=%YDAijJ_hYS(dLJ7 z)murMsvCa%RxN9qr>g8*gW?W>a`As~_yf3;?Mt?_Od|&8qxZ7Eq|F z$z?Te$rU*`Bjs$#@q>8}JE#~bXh|t4>oQ+YiE)dYGe2#9qmM`%N?yx@%(IWM-jdBH z+Nkt;q2rFy$r};5@-iG!k`1*@)>?fc$n6xaxf;-rjK=}#6p&B!IWpEF_II+D<&+$0vC#!I|?_fkh&5O93e*Djp zL*K{XhbYCxM&#ZqycxZC3Eb%$?#v8rY+7ua-pg&Ot^|)}!4|=eBcIx|tMOQ!!o9K9 z_=XSt%@2~K`-%IQsB>Q7kThTT3)tzdU)E^EF+U-V=}iO}dN zzw`~|MDd)V4dxV8>%3718AWg)>Dun4ug&nAVMhhiCg{WbESF`P0@++?#KqSO!oZY1 zjuRoHX329wa0S2Jh4vC*%W6%v4srO+2ZVD12Uz6|w~+)S4x6F9yC#`h5{SDDZn9L2 zD$uVF=&p4d2wtg8yIiI95s@?}@S!zokY~|gff?V5DismiV&d>7S-q3kJ}}7_D|0_C z`4j>*5#vmI+m>zsK~A>2vTzOVc`=Sh<*`@OiVe1(a`<-VIv2B4o!dNR4|QI&Rxozp==py4DofbcOw!p&4Q|v?F23aUAaxAuPM8IK zv_t1D>N~|bh2TX1p-KpE%JlYe&RgOELwW34zsGedE=EL}7DYQ5HVJ=d%?l5fRvB)& zduZ(AxzuuS+()mV`XQP9KW8h>4jO#5byWeTkxKDF*0v&j6O7Tm6(w)9P5)lf&&Op) zY)Zp^&oRPSQcchMtm?vw3xjE3wth}t$cz^&ayJ%p53#s^2FL_OT7~6nA7+Oq`Jorz z+3FoV9){%sET96TS@Gn<5SKaSKEMs9*rv*~7yI#q^7#cC z`xLMfPjEgMHO7`9H0ZOM#3JuFN<~#h<$$}fo7SwBX{2~S+&*q|5-tomvS8;Iw1Rd} z=o>)}^R@>qx2)97_A z-{YTqy3}JnlCb6+Sh3KFg7?=}&!rko=IoHDZjIENU@nYR$LS(8W0><(sF1&}r9+YS zJ(4K6`**!R!<}Ke5Q<$|g|V6jOE^7XP~g6qFz8Tf(5TWY?fz)0Mm_c`_pH3wm2-;f zqa$V=O5`TGZBA4i?h(RuzF7G*%tKVTTJJ2kq~u!CnBQh3VN8-hj&W2=Ck~~8RdpHbAlXvl`9yiN`f$$4?NL!NKO!F)f3TmYzs7vT9FNa;VjvXo2r106B zHCbrPP^2dw_Av|Fh30E_HS?rkVCZS6D%@&c@@FXWRV^6xBx`|i)~W5$xLSOPG)K^) z6px5oXX^Sxqx(}z+l}?gJn2R;)ysBq9&fihPAQ*xtG;-rCPvXSZ89Dvh;N>tJmX6Z2r6vvF9sY4Jh@&0eGR69$)k z*}Ch(pmYtl-AQ$}Ei0ost1f@2B5WaMvP8WGIm@=ajid``Uf0B{*30VAh_K-zFm_FA}I zaH74_h)GId7UZS_(2uz()fx{i^>yMrc@f-~pI5LI-{HJWZeiY8y6$yjE>FB&Rvm1n~AMEdvIP|91X#wEKRj^V&v)|4~ zis_eCCdG;MiBb58p@MbkXTvcX5K64iWJm9__uoW8vVFNZtnoc3l_Qc{=;+#NeD8frx*pwJN-88ncTI5z%enAF; z2m>Nxy~JdG)0M&_s|74EcfxxWc8G!^lo=SV?H-M7r^kT(FvEBd{U$f2m>H}~*uHU7 zj0Ns2Nnr-HePLWtPzvkic2p?{MSSV{b{PCJxjclw=p_ws9r%XYmk z#Zek1*|gN(%RbtmTu2)kGRj*bXCx*+Z=XeGCg_|G3J(#XGQ@da^YK}+gH&x`Q+AAk z*N$JcI*yS82OF~Of9WvIw9ZyZoC|9LA9p{{0WU?`(o#CDnoyS8{j!T#Sb5?w-la`S zG5dG~*^XL8$%@w2edNoPDPf>(O9Q1BuzATPDLAJv()=OLEHyF%J=EAz z8r3-d`tY-nGg15G(Thagup(=($qS;!X=kVQB?JAOLiwSg62VGX*pZmioM2vz~oe3Nk0!tZYB?e^w4r3!bQg;zvjYcsB}L7cm|3p9#^v6xS+zSG}|NK#U1Xt=E8 z>Af2;n;Q+W_4P0}wKxG-2hO#}X7mvh720$q3f;X|ypFpBD|}p=&U0pHxYZTGu!=zy>8H{!f*v&pz$_whe7@HH4?Fd;c&Q(_E9%709iAnL9wO;QJIb*u41%cff zB2+^TI=Mafk8J3?2kXs#+D>E#s#SHG`Ea<5wIdDj^$P;f;{d^EI@RM8uvK{guyN-% zISajn>95^_9x!)#Sm&||A3LcYG=V@jOny35r;H=JdifcHnVY!4XYXv*K~1#gqj}Gt5m&EMn!O)qEh;{X<23dyo&QO3(tl|$GFvZCCJjnF zT}NeiR*tZIjk@P@XLl*&3#Z}X!u9JM7=^2^VcrX_@;90`6uUKITPNNNmH~_Z4I1+y zZGpjz%CV^&nT9o{&j!xOdidgEwl!7~aYeev5`g#c9)kh=ls_vF96?7-Ii&39O4`>L zBDsXs{44+<8lwi!G`ThduR7dqEqb+!-_D_&hQ55)=i!e%K+ufj&M(fx?>-P@M3iPU zUi%-Z=Y6rcGK=sUa>@*`Cz6eFF{jP3$1R*h>25H2&}8nz$2^M)HX zv7SxSh(Y)_#u);Icv;KzVg0!-U;U>y%$TFnt2QQ;sJm)v@7V&`hv;bWRtN;!Qvrgi zn;%6hY#qFxC3isVZhtAcP!2UZ8&af?Pr;{E?|OAv*%>!B1O>b>Z%+$1^4%?nWDPVN@4p-ntLn?H{x#_2*udbgts&<#6pz58^!1qK+|BE>!Syo8JC}fTUnn=IQU< zzmPqvaC(~f_JWLGqxbUlQDZOS1Z8-I*N+gRwlhNZ_lU`%O;3ncnySr4X&5@%~s6E`N`bv}OzuFWQKB)cs2bY6Wis*Jp$Xei^_PL&^XOCP+Z?xnHR(=>LvnZ;zLNn^THe0lip8V?x zLr!swiz%={G4Ra+FiD%`fCq=lceTntE8ea+gB##?867kw6`e8&6DP8z{ZO31I~9YP zf|pLn3CG?Q3nCo0KfGE4)w>%z=(D}fyn6$X*w1__ z#by92H2MLL<AbH1TcR9Cxxj$X==wdh{0kyA-5I}vVG(# zKJ}{rfC-jQ(?`3`Rlz=#=I2jUSVb3;8vs^j04NcrAXp0OOHLxHFCgBXFH31*YTMW< z#+5X#qX?z$tuATEb~>L1D9BYzuJoz5Ma$E+PS^?>}(kA#b<(1V?S-=}CN7 zGFAo#Y=+-}%Po9;hav{C8>1Qqxn6cH#!($gnFO$nT}t1;uE z#zY^?oowAmI-v2KNy`-s#04kNoQ{dnVwde|!2Id2!Uz@^vc94hPser~CZ=+}WDD2Q z)9dZ|I7vAzI6Y+0ggVc$F#W3^^(Qt@6;Yr4;>Ao@!koGf((HKmi~C>GCbH)6O*f$$ zF)`}fX%MQ}H%>})F|kytDEPx$;@n$G>IX`N91sTbj7u88z ze?2(AxOGg(eU7z8*F7a6;fQ$D_vNCEi zw6wI0jJ;W7SC8sXN!%LR|A`hjt;mP01K)26aEpIaHAZE2()*eHY0H00`u|5(zuD`r zj{g7im(A}0@GuE@n*ZR3rvFg~=d}b_??C1Q;E%%L#S2(EjoSkD8)YWvzN6p#M;3g@ z6YvM-q8J4*U>Y$?505_%I&rbFkLtAn_nmL2Az!`#s4@d!jvau)e zSt7_jbr$^v+(h6F`&@u$7eMY?+H3++A56{62>3q*xEAu*-5i<+KtP?uf$r}8uLDqz zy%~MSx}1qLU^whdm6?UkoD-q{-*^4}d#LJZ!|Cs+g>`^6xUxPnq9%hf0t{L5l<7HV z4qW(sfa^stDN^^^6876a!{t-RwVQ)tAf*34pf$))ym_$7O zD5JcvyRse-5K!lexIGLcOtD1HICq|J*8g939oy!y0tqo-BJJl{pPJL0_5E=nWw#|K zD{cPoi+bZwd#Im8tlc}0a42oqK8>dQc_~k%tmDIRmv4)>)BH3Gf4evkS${hU?k~Cx zR`W7PkJ0K&UpxzG_kiwX3UvU}uvFpBiJK|;eZ*O3H;e{^-FLcf3HLS|Cf*kF z4?RwML^7Y-w{rD??PL44p0gSGACyqtsaqX*{8@5+$BF`mNc&BW;CTG79MzU*8Bxn@ zK3R(CDC3ylm5h&zb8WjJkW6^N%q&wnX=Zuelj^Tr{nC$sz=|>|peoy+0TEH=1-_S- z={sbrr%ko4;kn|~uRq|suH&E|Cpop8OsCMpvvzzS{Ly%X$x}%}T)0PN8e#AtuVL{) zB5b!9u53AIfF2~gyuFo#xzBR9((h zMnJ5+YFX*!{n+ENjcq&JP+BYO8H0PxWCb|${*D2`(r>(inv2~GgUAg>a30iG$E2om zLYM|pUv(fjwa|BIIO4fuRAcy1ub!0KT*>r7GRSaou<1#42z}yw`|m(LmPw6OcL2mF zBf`Ig&V4v_q7x2m`H+$pPWfDMSvT=+Ns8U;v9_9 zc4BYvvwjt`H8oS!MGzL9Rgxei{!BCj z{=5J?*`zJlMDIU+l`JxJ{JR0*2mkp>UwNwuY}h(}LA5&+P@z*dD-zZBjkUYJ_8^$c z=gl%KboE^GY5{Hl-iHpFKbsD!0eP)0a`ja=%?sqOw#E7Q@gJkF7E@5q-XR^d+WD+7 z;|00XpW3?g#iL7artlEMLQ~o#PW)aGLJFZM(QoU)PZYaHb5w-^Um>S2e?3>48^)XV z{|{4N9S~*LybT73B7!I&B@NPzG}1^TT}n4dE)9<$U4nFXce5Z}Qo_=(Amx%vcYO!n z_j$h`fAHV#efHev%v^KLH8agcMehrnUChbQkfx`GTIvlgpIi3cF2|DjyaJV@|%N&`xqs~JkZYu>%TGuMxH2Ng3a;wN%CU3?;H5v;S#^? zEuY%-_ZVg>oLU!x3B$+Tnv>>pivC`dSarmq+VR%T1_GzkUPj+{ z^k+YwkNI3quG`BhL|*Qu;|Qi-86aZRk@+$$UJILZh(^ci(D-g^J;Ewn_lEnf&;D}~ zP>ypVz9Pobm{cQ4Mo26TkxsPB1Sa+NT zg&F!D-hbU`$`k?KlUSKq%jU@;>U_?HMzRKjfe|8?m6%YzKHOzj-=5yyEx^Cb|96x| zoAb65;%?|xu@aqsfij_7(3{c`aRf8M$)Z^@8;6+{lhUbZ?X5yX+hOxtzK+ic-R%Te z`GLNcI=|HTu)(mWUTri~PEx*9g)>IzCI>^wLMCiu^E`b0*nM~Qpf+s|yUtislfd+i zFXF!&n#S<Q~~2R|-;{J2zdWl*e)%fge>qO|Or9m!+&+;h#d@H#Aog2T% zwXBTHemGC`_wW9r4}8%;rRtsGn;+ijaQvqxF3vNn+oe=CV3M#aMmBU=Fz0ICD9~@y z<`i$7QQ-YlyT#uiX7*%dEImwQbJ& z_T@5^-xKrWK<<};`X5~BYc=Rz*Jp<*Do)(XhDlixN;eP0i5A0FleglgwnW4!UdZ|D z6T9rGt*`m8tz*zw0ke}86Bh@^z{iGdLy;-e%q?wXWQ2u|?zh{`-cl#2kcxVFX40{C zxB3*A!D}AKq)!WpLDBl~ZZBw4Om^z(>0K|FU-JdkYd(aNI zcmhnAqsap0Qf?j6T39hPwGmebj=MIvyZ^jqI4=%<{F)BGj!NZ8@V{Ds!gdr?->G+t z1Sorg|JmqfML#J7R^{ToZtuq*wF>X-qDnptqqru~WXqU|4#NDI=Q3Xt0VaWu!N6GH z!Rz1cehQKCSM3g4(!8UoJ*76wf;)#3zQw`ZbuV>MGb;b@mkWG#TpKiI`g52SFnf{> z3d3Izc{Iz$GXvq7F_TVxQY627IFl)8DRH{Fxmi=gNnr_Zat7zo+goVl5CC!Z-eTr8 z#8WQ5)xPM`IPfIepi_|Z7W8?jfr3(e7gqg1|69H5OXQ}p)F_3MRJwJ%85GnhZlGT6 zY=MOo|Ba-pjzeO0a$1b#0L`($NPceaOT4>32V&aEMxN;XXss8!NF=92$ge`>G8+0@ zV~hz8i{^@>;ysJ!&@owj@RB~>1v7hsXUBJuVjJ5@wj=12p-MmWg{hjjXjBrxzHxj3 z22xu%5>zEu@Lwnf2JNS>9d|q=r=ZH(+xwhp?`dhd3F0F7Y(E@2&K88vU4Hb=f9tC~ z4tj?IP80sMn^b264(~!<&ty7Fl(Cn_J}wpG;J{(?XZ$n-NCrh!KRJDV^XA&>ubkTM zKX=TxU|3M6>r>w+)(S=jQy<0w`WKHa7`yFL_7oq;#QFOR3JA=5`w+y(SMrZHrBXGL zYdx6{rek6%b>5l;(c0?YgG->ro6fH@^@z9Rh%lz#*o|WYF?z%Gn{#6Z%ixj!b%JQ- z@3#t=^W7sQQANq&<*XToIm{8|4YD=F_FzNSiSGaV0?tYTHfNT*zNDKz+zq!0?f~|t z(l^!8ssq^(1>fL<6no7vy#^B}!x3)epY8lDJOs;WHk}}Z5B41bMs8%JHm0?1j(rJ| zWLY%5Yrrhks0z@XcY_lM`+;*fHgkKpmcISADru#m8T>5$*Q zzW{fWR;M1fM3(nO)l`cHbV8~cbN*``hlPcOsEwV1LWH6>rl0}WXj6S~{joje$H8Tr z?)AC=#o2*w>P}i~l^b_MHxFlLt{-=EI@+Lr!x7&AjouE&YSSMJ)BE#{kMySrNuRg# z&$`kwGBT2rzcV*S>h{?R`#@x(Z721#hj+S(l3N5a>)<0JfF217IygM+r<o+q2AK z_j4VHOkUe|o}kY-J~61l&CZS&MB#jN1Wewd-(Q&*qlF0=s#@V(tmCS(k(A-Q#55CYRc)LV+4zJN$z{vUL zvtHtTB<+&y+T`t}%rB-j^3)AD0Mz5{e_tD?i}M=+d`d9ETt*yBf1gmwz7^@jDwyE{ zrqbO-yg`L-63>i#=0y&9v~YcgKj&$SXi z{PVl3w?UM2X^l1W@f4EiDCu`;y#E?OPbINq>u-1tRRFP+l*S6+oHyFZ?Tk15d?jx` zK8RMyypjO=tVc(8NJshYHx-A>q>}lMclZPs)YPb6d?5b}Vg4E~xzu5@F)ia`x%D+R zK7Q_&;PI_$p=vGjad2c#vQWMYUsF(i)u2#?`dr5&4YUUjrU|*iD8W$^0eK9-4*e!! z1Wrz$rPVAn`GRqdepUR2+0mF}Gf5t~(b;LAQmXu!?hF3yOyLLGYIc`5{5CUNyo!*B z)ED}M?N*$G_7AL{{xShmSh2h?nS{gcUG8*$ThP9)`Dr)2A})oGUl&X}2e&{$A;i1r zLGj)F8v*@_BJ4NJ3}^KzuRl0+CzVRvC{+?Eov>V4UIxresXkks;c3&Mf0%yQZ*U|Nq6m4a2GUAQ*Ooi=}l=6~yyB z+*NU6iQm7gT9p$d>Jq3N3hcf#Ie5w+K?Nn&S9q*Q8Z-AZa&&0ewQ=K_FQM_SrH_Uw z_m4-*ceK;$UwB6r>bTZ#Tq-(4M49ZaetQnR-mmqs%-K)D|2D#C%yU_&^#^IbXOkGq z|2>W0$;ij&wpgRwP{iumTH9N+u` znW!kgT($nNV|LQTzE4AZ4MX{gNb3o{N;T0k*d_>Aas%Qq+Mgr#mR;l|{4ShUeMoUO z=uwZti_E#!Cq=Vc=eU;Vywst1x5o8vkQ)gK954Wd)pq*V#-ywCrZHi55`;_s^(n!9=A7II)O;;Y8QoUj-&6P6cbGrs zg<>!739y6}Ms*o{)|1GG0R$LI4xN}A*J;~{E)WFWE;c8M=`0`^{F$W$4Np?9yKy-{ zfBpE}ccpvhFNK?fMg<+^a-k+^h;Cde`q=kpM>10CLGZ6}rvf8Hm}n^&_xIciz#yOh zn4)G85|29R_#(#wRxNF-H#x#iUNoVelU_!8@km5%MAftM)>&UCKD~T})Eo>CJ@=|P zS`KQ6%s43tiPy>YOq2KyfcUR1H>9Q&r104Uc`kkDW;q^Bz*e`O)VOb8>0af#wwrT? ztnG-_F{f}Xy;XSol3uqh?twYx|M%#ed!ujN_6##cZBo}5q|T7DOJ%o6#6rVOQJ}1} zwE1Y(*E2;O!I?FVC+(@oqvfIkK^B&0+19r(8$`C=Y0vtP7LnpptorLpJap}573m3? z0|>^|vHw*n;#|_(B;YD%Z{i5FfU!-)(I zmU;i4f`Wg?aDGU^5ZO_5($j2oy4SN#3Kc0H32T^GlEn2y`Am3s_#@p6e;VC^DiI_( z53ial^Uln2XW;TlC#2eV^3X_&-;1<>{O5?EfoK2JAtceymUkI+|Crct8Vhvz2qn0j zZ)z%RZS?^bSXud7IdW<3JFUkq`n=bZnu~>usq0AK{8vTpkQ-aBiN-g;-f>Fmk5+f1 zyK0~5#~(Q6d(2;6VaM>S?mF;!M12UhR99CwH!t`+W69>B_r>nA)TktHvo7nTr;(;e zEPNEqn^X20BzeCiqyHf(0PZe5c6Z%2|MH2i4Qd5LcaN?2Q5F1mYxB72giqU)^W6Iv zQ<+5}GAT*1vAI)QdUFgtnMqDlk~@3@CHr zpfD%4^B5qm5Jm+9hgp+E_vrJu4Ih@h6=Yr4=Rx1*bYLS4?*PVd%$Oa6vP>0-a}nnO zHb?1+iEje7nS*C@iNoP~q_r{d1DD86QZPIkNIe_0N6Ikr2fGz4!_g~d6d zaqSr99E5r+tl#h-^-PL|O--ZqyB+v<0lu@5QT>G-hiDr!hQ-&9CO8wxUo=AvX~y}U zZdPx#Oc=@xa4`Gt!JRqU*NTIijDHpCADo_@o$;wx4OlNMuUF+_N$jkCqIBJ8@qePM ztc(~=jq#BJgQ2gOzF2{xKku!{Qb79~*K=SvOkd2E-l9l z0OYydjKTqP_(vjxlg*+7$B`7Y6Ac||a0ulCE_CI`YgZH^R(FkYI%a+F_xJaMgM(L9 zJM^uvkV-VjqJq>E8_3G;ZaHkj-xrF?hIvP$f(AaqfXi3!Et~xF`;mbOl6d}m4s_+v z_Ba+-#T8|b^?%stY?!TLX5YA!?UhzBw+*IM(7ERUxP%B&t|Mc9&(lN~u?W-k1qb@> z(aikW1IWgM3O;mEF)`fd&j|wT-Hw|aBUhpeTA0gO85v8!ym=$wTr~|G4kd=r0E~VK}AF1RjVtEpnG&Zfcgt4{>Qj%3^(Gf8=$A``$3QWJ~JsbR|;l}Ly0wW;OYTvFGN7-}x-*K4c z&!C?9ig^50v{3c2)O&GbR)Sx7orwIveq$B77t029tmr_trNvD~=8JHPSm~m)6wm$f zKB=LSkpZ((G!t9p<-S0Qs}aR>zn2H&6XNgQ7f;YoQAwBEe`s~q5iXJ)x80if$=DQs z?oHI}5q9<%>ax=W*wg?xdDOPc-q`mP06x;&STRQqm*Ye0d1UNr7N3~HM6NjZ1y}|j z?BBzAbB9&b=wtVi{XV;>Ulh}zoKb-k=wER6OLJUt1h1OVY+t%Ra7xk2pQB6tym9Yi zG2FB(39__H+P54@)J9|$biF~2WXmyPYRPuRw`X~`PXGJcDkSWim?@8ohQy9)eTT~i z)6U-M-Je}lf!^E2H@bKVjvx^=F)F$9^!Q6IVuLpV@KhbKqMP(ru#&|`E-!>c1eWN- zXg-QHGuDja19jvX>)&;?m$RTO3^iJRpP#JmR{vlZE-4m$f-}}fy6F==u5;>GuBrdB zfK&sw7Ut4Z(xB!pgoc}q+TGK$>BN_a0ZrZ3F%@&+kEG$Sq_rAtyqa}G>%+1fe%}zJRN&Ns>>y#8TazW6@u4vv|qKM4F#(6hRTeQqICs2MfOsyI|_LwS3fF zQvrJ|1_+sI)1l?%@3)IG5E= z{0sC-KBJ?&{-3wxl=C-mp>Av}nHG~?{HoOyVm@IRVqkW2HYiYe%!6&bZ-$*fdXOKY zQBGsYrCv?=L$;b@Fq}`}W$_^u4NcE>=BCO^W?KF7WBbkNM7XyB{{)lG)P@scB>gn% zoua(FbCyS#*g$xQ&+{pz0eZ48r~V|er9M!yfQ=5Gh#F<+Gy@tC=Glw>%NyxN=|+9{ z%P5bZO&(ZUlbCLg;9Y*mRW2o=PbKIes<%Es9-5hK>iZ)-ii2k#FEUN3TKg|SORc{% zva>kk{CdmHt!}>kTgl92K$0zj+teNc0Faxz-q?w@?CjP*zk>XNj@(-&kZcRFIZ&5K za`-(53fB${0rXBMe&`GTjk|YuD0II40f2Xh^Yim>8UU>@o06FNpA9nb4K@It@l-__ zGWc|Z`*cB_16c03{Iv?BN)Dbr{7y*V7iEp1xP$}(gL9ZR?~81x9geDlo&o<%--ESg z`H?pkW(0W>p?Kg#fz}0e90r@EV&A29c%=0oj8v64`54Y%Etvgi(0iG8ALZ?Xe@$4F z?As<0Qf<4y_OTtt@5#a6v;@1506ArCyd#Zio|?1F`u*#OY;MWJPs-F~7&<C?Uf&wDbtr9aKATd=}ckmb&7QLpCCqQ6*a)C*v#0qyTRc+lE#&g7$o z(pD7;xx4b-zvOHi^qEsP7Kdf+?4$wf&k;7o5}KlpUmTc}^V7ZRxDTahgHsC)89d_` zN57Wsy6h~$B=Y8M1l8ibf==~{{}H`#rO6kO@!k zH@M)1PTx>i^e&!lDx{z>4uH=XOl7JRs?x_swXtJT$`ODFNP57W^Zf^=@-$vHHa1mU zo&n5MlQOSavY{CpiA|&?x|(rqj^3G&!|Q<#mwmmQoSclD7F5U^Dh~uD1l3ry>2Y^NOpHZKbw( zCj+JBNR%_ZB>o#9{x!E_s+~esrwM=AnpM#X@sp-YZ+_1CUHHx~+;7u5p>46h&s zyil>?qRGmNRAR+BnT6SW^{)W|`VF7k9VNMWdEG8gcBVO8`+oFUZV@Cx$p+|MtKr%$ z$6wG<3Mhe<7b*SzK6h^ptCJOkpT*dKTi1)|tJY`j!9-boO&!fYFanpKed$jX4!?iz zUIEP`G1pBD-2P$4B7_UE^n#!dbN?HO{MnoD?WK-An>FN$PZw=Ued(|G7_Q4_B1?pl zQiz+8%3yZ_;A^s(DlHI;ddCFv<~Km60ow=(4Xr#as27Y*Wo=wWxB)hq4pckEl>SMfAuZ~c+MW!9z7d6@+Db;G&7Gb(7-AfQZ zUIDdyqx$apdyOol!kGWF837G7^+W0%<{7RDu>|B%SpatXec#i&FfPh5$bggZtF&H$ z89rVG8v&+iu^G;{UydW&Z{Z5W28j0vr`?5Dy!^f_uOCPA#HUYjY!LA<2uWCLTRp)# z$e}nwOW_^s7sDe7dDIVGf%P{=FsF@J64TInLbk4g!^3N@S|+^}U+T2Gm%@#<<11q% z>X5ny{9NX<%-g8CqV9WS`gkmTSIJr}`maez^_7%-KgJNl-?^zKAUnJw*3tq?B=(%V zSO`5sQGJW=Vx@+?Q{oMS?9#>6A@7~cB-?aj<>uuSn3UpOqVR{2aFNcrTlV{r)CGB- z=pH0eQ~pIv@3z&CN~ZEnb0a4?+5vcN>Egp&9}e<`F|}$sK0fW6@U z*1K6*;536F`rwWk7do<_(T8p{Ol$SbRce^4AR)(#ZpXqbTBdxc16L{bl@YHxye^6Fb2&CJY92kt!F`bxEF+k6Rr9OupPjS=D7n%H!A zy_*PDILt*n4oYc25lm^qN!Xpaf9skTZHh zJae+9gQTCIFq@}NOT4NR!uGK)-Cn0f|K=dSuB@EPlGY7ewp5r4|HKwEt#CuVyDUFA zQj5_B1gQ!dy1Ld@c;66fyN_UApCHC3OV4`&@d?2EVROaL#J$U~y%F~_f_s4H1cI8s zY?}jyyy&Af1lda4SP5G_tDAoa6Wf?54qxB1H;gcq0c%-rDST0|6MWySF`zN;W}R*s$bBu3p`>#D2Kn3o-8&-h=eON804{rCMX{V)7|SGec_27qttWbI(f ziE?;+EAbPfmR+_V0PN{4tpsJ!r(`%7)c?E{yI+^^br*!V9S_eR=G3Ag*~^cvZnjnH zOXhi*EkCp zEQ)JrL!LZfbKZ(HA*tClupfnF7AXp$58N3r*a)15btkd-QlHP>kBg?Kz#H{$1s9UYh3MgA@hPEQ>8SP zlhb+$+8rCj`|nquqzNxt+Jxzka6IkzpiH-3maBGD`Bg>BJ~1gGso;^Qo!pbqy;w$X z1j*tEyUt@%t)Ff|3Yw*uKcPhQuOdbb{a*LV511W17U z9_Gw6VTWb)wUCZ$6Ur^LCKb$J5E-~6mU;*Cs*fCo8~3iK3Cu9YKnz@Pq9Kus-CC)3 z3RiHy#PxOaa~>Bf7{S2m_3aFFmsO_h0C|~TRNOguwCxX{p|hx!8Ke0APMXe7oV&e; z0F%3C`jh_sd%|_?(|^1wTXIdQhW+Xed$d)kLdn(Upu@9&Qg0DxAvY zKi+*UO#7Qd zwbTd=FAu_PjB#+95aG~NRy^{vZ_dFUXC@2IDSz5X?5mk&hv|C;*cNv&6J(XHs=_&) z!|tbrwX~&6vvn~R(bszmxpmP{(nKtdmf5W@yAE*LZF5J2}--CN#5s zdJ{K-@cJ?51xvW-4drH-fxa=a)9Pf_<_dr1nSCE!{9!soc>b-Bj#=dW4QXbj z0@FVXcEzy@YflW4@;r7vG;)?T4RJqM4hI%#8AuG*ujfZ#ngJ6ZBo@_i<Fda&&6A`F}~JQJiX)rSZ*Ah<{t{L9%VFKfm!BY+187AdRJh zFP@#bR@+VBSMv-kUQ_P+#%`08cx`^@WS-r{#I3L!RJzyhf_oD1%<2rzq*K?$Xm9?Evbuyy?pRYT3>Z3kZ%*1MFN>0IwzJ&Sp!p2LNnDSU<+cCS0$33YJvjI99c6J%0|}^KVwMwl z@-Qbo9{CSFTZO9cOEZv(F-;zm6X~UHf9wUNhOscUJ10JLw{e_OmC(HR{8iBz*4)E! zgvG&hDv}P5BoJKXPYx12SeSIk21U&&0Y5JOY^NDFU*2pZ`6Z-cw^5UOoKosSQT~CB z?XC(+x7$VCY#)<*RHr)-n*qJ6fx$oTO1$N)xGz=wl7qZ&7922i51dfEBmh=|ryY(~#MC@&_-1mCJ+k1^ z_v^aOfkHHL#0O{Gbar!u^r~*J)Yz`rLavv@NL)(Zi0{eb+)n1`yR8IMu3ga6*%sd9 zacUb-5`oT>u3YBrNu+*5Dxip9B4{HU-|xZGH}lUg`8iL*fr=!$ zi|;S`S`;Mi-&FF4kB+Y0&?xBYt0BEfUNqOo=EP9Am1x)gyjD#A-mC>B7Ql=K-cDBPV9QeEQOXF5-3%YiZ;q6tq-D)@7#-r(R+q>DgiD!95d>e4T=8h# zH82c_c^&+19%H8RH#jLau_uOM8#+0S+Y>7evFua3_j$3=q$&)Mu*dZGJ(OI%Mn;A9 ztgqi#(?}P;dWBP@_)yZRarCnTkJ;%Ph0{ikPcQO{dH$a5*n|fOM5`HIE^jx(YZRQ zAS~Q^PF+t3L|c6tiV~_WeR1KV@-Wr&Jj{EotaGQiw`A+G8mv+&S!UA?$E^T^mZnkR4*c8E#Q;B=>Qy`@xmY4V(M* zj_IP{@%V?`=0k;(Th_1`B#*7z9H;!!guB! zF@KXhR5aJACtvfrIG;lF@bjs{+q0f^r0xQ)d$enn*(47ewtO7Xj&+oEV{?%QzKQUW z^2e;3!|F~NLF3u?)BFX-&lF(^SWPvjH^gwB-rW*sx$5-XG_SpE6R$M=)&%i39QMJj z@_W9*pyaXZ896_;>LU%@rw#7(SzOn6?LwqD0RiJfqKb{L#|&srJo0>^g?uF_XSMZX z^+t!_DSDO(zUYOYPdx{`#7c}CY}BfrHCTlC{1m8=WI%ngszb9)A>!jQA{Y}BLyY4^ z$nBAkkNz4>&@YqB2b@EK7Y;5N;fZny>1q5r`IT}BW^f7-%{T7K=ltJ|x=2c(!giT| zPQDXJc_CD1l-@#QZ&%?h3?at&&4@#{Q(?h3Zq?;kZZ=SJwLv6qIl9)<+9knvNb3`# zO`oEfk-DpI0Rp$YdYeC-!!FY<_EK||JlI`NxD~E5O^ai5n%7 z57%_>@iqB}n?AiLzliFO4xmaG5Hw<&amH=* zK7h^$vMJDeeCa{nUyzN7$$@aNa?g`X%*UL13N2RMm(%IqCXw2q5D9e|)thDZybr;7 z>u7iWJMB^Q@M(^77-Ao6sG`9BgY1GJ<+O$Cw)Iz}56^+dT!dkDTSSG^no;bV$91zd zC%wX{lM_zYx?t)EY`SHDB$leBo1O z>K|2}9dYM`{b270G8e2TGRI8?8tsl;bRqnR>FESSTHN)FgsJxM3N6CcYwYA&lY2NXp{TF1!Ny*ur=eqRx0Ws5XLNIS zm6RP>S{Yt+){FPZ0Byldcq3NcMpz_Si=d!j>zP!>rI56J=xB7e9Ef24La|6SG~Kyq zkXK5TDl1eu!y&<`GxWeZnR)h&sU45yvjfFZi&^G-C0>Na_NpV4@TSQ8IePzR(}H;> zJ||c=POde;B1*hhxG(zFv|XyXOq}id@7G(f9Jl~9CsILQKU~yBkqtV?_Z1s7b1R&%%(M&= zPfLsX2IKwK9LRK^3KbmVnj8yle<2qw&_nj~&B?Co3<~E;wR_Q{sK)v^g46^38h+t& zyX`Xep$H;q^*o(B)TaqjdPBYY^i*f$6T@v+UtiEAI#FEKlyJt1;Yppk$c`GdM^u}h zf0cz?H7)ik^k!(LJD41b;2F29U0XAOh*3GuwZw-AFYL}06pd8ZXI`6sL1^i&V*wiTiyGWWFf zCmg+`Ib|070yiwXPIx!0HC-3H*r2zT1zD-Ui6MTlp>jY*>+{%{ZpGVrofdf{y?Y-U}Rg*YdWQ)15Nes+*jvuksh;35~V)qY8} zK@bhpZwFR1G4|L8er5PXKG{Cjg`q#PLzHoTq`5U zAEhK{7lzc&a99T(hL^v>e7r>?gx2J z)-E6$Lh(_^dVnd(K&;N>Dbglhtcy(ch2mD9MS!@KP4%OPkS}m=3NuBOa`dsAy_<#7 z@cuhpmixrc0P=O5e?%|Jlydu{Xyk(F7YG`sh=h(HWujqkTf1ha)Dq|xr8e%J*z zW@{H?nuq4M?KYT-d%9$5_1yJDb2M~70>xK48vu^>4`yjzd=IJ3(6jQFj(J7|J8f8Z zZo(S11=Ug-is*l-M=!K`HE0cN>oU{ozQVp_`m)_WdH^Q5z_1)=-iw)=;&Vdh}Q#4 zrME}`@o||sk$3u@4{7WT`LhJ|c*-#R3WZGJU(@`~syG0=JA{OLcf|z-M2ki4n@89w z;xo-g>Q4PZe=%UvBF&?2x*UA4p63O+D4v8B(6=9z$dDzOt;wtt;Z_8+XsyCKuLND4 zJ?$=gT)mCm+<2*IF^-{S;P?1W1C7&vf<6nn@X_qP)Y9S}cGbs$p5+l%(F^Tm#dVnB z@a!M5QhajH$_&1|`SNueW1EOlbds+J@$8}8v_wU&Qg3fB7!7v@(d#&+`o(EO_ZraI z(s#FYj%xHn%s46l1UvT?Id|77qVf4%B74{~XDd4=w}c1Hw@F7^_{t32dkF)!kDsl7 zSR@z?tL0v+&1+(&2UPd(SXosF#(ljjj!*+ zqf_k6g|l&+j?*QqS%==3@}QNsO=Zb>Z&*&iOj|o0P!W0ONI*r@uY9eX3)QBSq5;Q_ zj`N56)n(qi049uozKo*@&+pS~ARJ(2ussnX|3badZ>`2z;-&emlApx1X}$#mc9~-W zw!w6qc~*Bz46@L;WNB5FBRolAIB4yxo#(=Y36(R0KothV^?Y< zo{!@RB{xb3C3G5b1~a(X&_lzCJw5Cn=t1K|5ewU(&ht}LKEr{oL~PlB;$iXFamV@B z@Y@E^sSI(Hc549`q;D^}CqBrGjVcWiLeVi{Go506trBt|RqdobxKQN;r`6fbh;FF| z&l2VkPhXs`DiU;EOt{!$h!V3!U-C$ahA8GRs|%U!koIi6L(eb*g4|z+AMo7*^8QR6 z=WdAxfyY()i~z~C$f{Y#l9phtK?j}m*l2{bQv$hMWQ}2E!U#eTa*@A@>>bB%<&m4_ z*L=X`s&i6DKXa|qd$u|tWqc;rY zh#0)pqg7%_80X9KfiY*dESh?uE08eIYEE*0 z;~yb5u-p6N6_s)Wc*HhLJVnt?LY(34drk@VyK`AEEDrw-r7N)$kVTu@A*XE8c~G1D z{v@qF0>^8ebmjKRR_h$ATzTu_HDTsrXRTSY4Z)9MsS`?1S`~C`?K@BqnrD%eXTtuf zlXd&$gryp+X1TH3uhos!N5lIn!k)aVN70UWGKR_wJu0Ko7C`4;Sz&r zg}R`E?K#6W4q|%XXpsIJ>zcjF&_}w{%(IGf-Fw=-LEbJ}8+TYGO7OQ&N0C}F9zOmI z0-f7jRuFSBcpPZoR|ciI9#l2$3@$+o)+y14JvQd^Mx2sm(!-xKLWn!=W=C zGrRhPmbD$<+ZQe7Brw*Gw)FvmuGFrbzo9D{;+%yBc4swfp%at$^7$c1Ro=_(?QKv} z%!`MXQN0JZCw9}(H+Wh0@_qMverF+Tbh6buXH2ct!faNRXJMICcXecv8Jg=D*RxB6 zFKT_ZjkfbqtY#b=T*!5c#GGQcJoDOl^IR2s4b*2KCeEl%T{IhEi61~_XDqoFSq4gt zaq6P0SvC+BA)xU3&{vvU3By09p%x@7x5a!nTF1nz;TL-~OEKR~gxb@41_uZ8qzghQRPtJOF-MTjX+H>TT(Q!ND*xx7TN9 zixsD`g{seK_05&zm7Vo8>M!AkpgQRjYYE2I`e9_;FyoM?iRr*cYqz2Z@h7`?YhfKs z%rRGuV{lK+L7)13tja58k{9Ald`}P)HU}S>fEBPfX_uM3e$^Vfei}J{3p=b~Q zHgpbBQs^B@9Y$hRcxDmzaYB7NY+uZbS_}^RV-B~`j;AlcwEs#{N-E+sXRq)2F-B zb*wd{3}sgb6MLBjObG(`Wa8@At{vpreC84qD;^-)SD>S0j4o{7N3 z{PEfzG7Ngt{`B?ac4C81tGP-)@^DorZ*z!S0!pGM5NYA^5Ba8Qj%`vNG1`P6hNsnf z-su3g)Y-)=)2O{vw$~zxcacWD8J8uyz7KLos1v7D<;)g9%wX=mHOUp82$&{KnUwfg z$I)-|?KI-2#YJnhZ1As}$IlMMce0cXposP%?cTHRA;tMi=Y?c?TJypbUnU|UGo#dl zAlw?0;9wWgaBCt{iPX+nKyq?PpCQw}u^-$=@$E}p;uM(J0C8tjkVPh$%r33sH|S@s zIDDz zsGMgOPU>?ra05SzQv(uw{|&L3^X{L40;)z3zCr)ZA<-XvaPwC@#YehR&My^ttkP8$ zzx4BaQU_N_HiRj)LS-kcE@DAq}mN9(rl`wMyNl<;afb99g51DL=# z4O`FX5s>aHBV|nb-j9AYqxpFHae$bZzv@7A7Xy;lv3XIdpR~xdxC~!?01o zBHKWZFzmwKU0;>s?S5T9Fl<)*OfJCPB?DfVN+u)q+LdsiK|?WIy+b-7B8~WoB_zbk z==8$b9X%x0JK-A^!j+D*|9e!+;bLbHAiN-*U2jC`L5{ zSV{bZiN!gIpqGe^FOTQbQih+e)l=3K=Um_y9kOAe1iii^iGT{745)?(DwfL9-X}y< zSWFv8lHwaqlbCj-BU|)+@M4F>PTG z6lB)f%>DWE=jWP(-IKZdrbzKa3;|I$9}vxpgaPy>qS{C_&?mqKc=;Y^#L9G?UOML3 z8lKFrl1gYZ-C6`ZCMy3jIV}xObZ}@0gZvKyA$H97ysK9dbCMbDKj`p|i9`_(@G)t6 zkM~j35vcceY)lcbrlq9~tU@*UEyTq|o!oDpR98{)`_T1^ z-Cb%MTlCQ#*@q(bD~7d&8e){FO24Kr7&}O^|2D|;!0A{9E4?#cD=-nbHHB?f*zRqL zXeO(WkUkh|yH0b{Rs|v5S*5VMm!ta z6QydVMDFV4c~(KZWWcWYo>Fg>dp3?|#$zy99BArAw!fbu0hsWeq`=QZSN^z)v<2KQ z|AjkeVc9yx12=aOq@SpB!Z#`TQ&huBP3u!B<5}j`kjx&W=%ZIqj}C|g8WLp1xg9mm z`B&to7hYT(B{L1s#}6Dt;gp4{QSG8c8UK4oUEecy9{J8&!~^W~OA}4+wbIam(~@N- zX}8!LfpB=NQa6$`QBKn9Sh-Yv4QY^Mnya$$ac{HLlOYs}^*hS`HCI#Fz$po2cKGtH zM-c@`#)?!uz=ZjgWDsa@#=VR0RZTfK^6db5`4j>uU?a$b;ea<=(}*pFw#tr?c--_u z1zhM{(R~T-IGVfkGPaoihG6?<;hu2GbC5b1pTgoGF|SM8{A37unZXk}{?7$ZYCvEl znH%`bzw89In*WC1>hPqR(W{VoTnA$={u0YtLKZJsRQ^Fsm0LrIT2`4$LIkC=-qZv$ zI#&7xWzgzfp}E1GY+?KnOswy3`q;?v^SAtGzWJSDo5P%4a*fr~aM-bgQf@>$={sa* z82Ct55HL#Gpwx>MQy#`CAKFF#9!N+7B3T8qHi-r*+$~>3vK$;m5sQVORog*>vj0tR+14FFv7@lCh5@FsiTQMZZ$k5D6|9ReT!PQ-ph?VswTLL-Ne-g66QIU;UNyvM%HDfcUUjL!+ z`xX6bnqmgyKek$No)uSdNl%{r!En5|m(g2I>E_2OSg9%K{0W`VjSnq=(4}idPv&W6 zO%le)Tw;m%2WpEv3%&>=Ej$KJlu9W;me?xnsj5K*e6U6PQuOeep_FGA=T%qg!W6E+ zxTVU4jK7sgzIaM8m%_9%lspjXI^|Nc z&D&~vKOqmR(Rj;nC!Wsm;}C=hdUT%GUgax3SOnoASpldUENH|t;Byb{VSk6kbKunG zrIg`geE#`*r)#)Zdf^g61_r70+OL{^Uo)-MmhagTeboDv361LU9jS5iU6B(5CWzzN z3sM%`s}8)pjUns^jEQ4hF^+STW-IQ9y15 z;9gz!4XBSWvRrNpHTKrjBn%0&3!fDP<9;~4;CZX!jDiyN0B}tns*DK=`C@7d3JDR@ z#JUa(%umq7^jGy;_gLKc_#}N?$V9JVAdLhvgW5v{G^}Yn{0o0jobKe?f7K1Ylzz@( zz`i{=4mSz-;ZEeY*n& zPPwnwcKkO)uF1I*K1R;=SSyL`iFE=5ViY>9;c^Q5lM08Emnp5^u{v-m|0|i_H6tTPGMUYlgjp0k`5MOTw zR7Er&iYJVD)A$EI#JuA50&-zK{$JvNYCLvpqE#YOM92Q;(7ChEnBC#`7^nO~+!P^~ zJjeutw{I`%iU;z{`>OP6g{qTaGz}kLkx<6(M$ak>7!A4jopkqob#*npyTUMk(xr`T zD#OqC>C`$%N;B*M5c7P(M(kMM%OHBn09&)+P2|KBn{xhtRDF3k)ZHKUphDS7McJd2 z?38s7p=4i@eJ8?X9b+%DWKRg$i|pC63`*Jeond6lGG;KAv3t+->v`Yn?Rx%ruA2GI zIp=%M`E2)nf9^$D+#=gfRJ{#+x6M};jGUaDU|EHqwYf+m>VChz+JA9Kl-g=swn}An)}KTlHcL?Yjk<{&WEhuD7@0*p7Do z`wnZ}Fk={KBn6o455(yza9-iT6ynj z?pWvwNVfPhe*m7@$)n3Xn4!Xv0viKi>i1^QjO!pHvkKpap*%lpgWzk-1Kxn!&*KX2 z7v)RpvQN1syPRVQmyq7w2)}avtjSmmn=F6u%e+~<{n|tYcYMckoy`6Fw}PJ;8y7t- zbbVlwOp`aXGE%4?6B+rX?hO2lfCwC6)Jgz&G#)=!??$ppM?Aj(4*;L+D*b;$1t%HH zmV5ZT&_@a~z@w2=8`NNu!Tv?_F-UE0!*+Bb%WUBG9Ma9NlQJ!hnS>H3^w;-m4%+RCq`9|CB zd|QkZkw{`~+5jqv`T2JwPD)LYh7=qDsHrLADnk=PLzO*K4%uIejT}CNE*3e{y01<~ zdgZ_^HwP@HSDAIC=Um~iF%Oe-xKG$e-<!_?(7<|h83rtwLQ!um|5eY|h)Dnn;C7|9#? z2UpvpcGTLGIGNFHxZc)Sk-=>+4^e4poBf0G4*L8ta3rRhHTRfHdhO z+#xX87^#^{Puos)6&5U*AUES0$QaKPckXPyR4Rn=s>Ips1{R_DjJ$}KMJ<2sxF(Ua zN7+DvV~fa>auVmog@-{V%%a%4OOn9e;d4J#Z`xLO%^&4dBM}|nw-n^t+q}i7!Jnb> zSva}7H%$t-jqBg$X?DH>2$neLi-8(b{ee$=kDsm$jX3Oev5Cnv|HO*x?w@21rW zAlqdNq2Tkk``4_(aP-o9v>fH$;$xyFfl1<(G93nrS@En_@&Ep@BaNRBGlS`1ECeyUSo5Czbyh?O>Kg?6McWbda3jRCXypJ`e6I zSnyir?bJX^&bR*GZH}dUPk{s#*LH{9$&nDBbE z^V_bqzQFz(^VfhIw01+)j~AC~KN-y;HT?QZ^gOSCKv$e6z+JfhPH=JnyYikINV6H% zdluIlML(;3`L1t?y5&P^Dn_Stm*U>5Ya3EIKJ@nhGOc)~D^&MiWU7_Y;nj%>-({cd z7y`ZLwmm=6~&Cd&i)AN;DR?QOSnWed*d)w-EwkekX@Dng46dVisZ7#$})3$kh zdRi>ku((bvERWxmf&(+5SHJ5kBM?xac^kCjRn^cqg!KUmY+p|gbn_?uDgnqQ*;N=! zkjf;e04hu2NV?Zt_{z!(_=o^6FZhC&=`93va<09>(<;LrYhkFYA?NfN+vfEcT+gyP zdSr)j-?EJQ71w{4=#5qrbb8mK^{{$L5?#7P6T1ejL2f305aso*OubL&uaHC)jqMnq zV56b};!2yj30_Y)AzAA)Zilk|5U#Qsmy!!iH~3>%d|yOle#?bgZKzjjUD{*}BpZeH zD?q2oxZ-i0eBJx0zyN~^Ma6{5XZ%JBtyFXcph2qM5)l@@Q3~(v?!FxH3lPzO9TN}` zAX4f)yKfaxcC*ji9ATXkk9O4Nni2Idfio+cvc!pvTgtf-b7n*sla?aFC$g%0$VP}| z=!A|n;q{1)gspzG!IhMuOiGUTU5mPHS2!Nl8YlXcH_QqFP#$QQO4E5%G2wVCzKr+9 zIvNSuM<-?#EG2z8v%6N&C$rTpVrOUPgpvWS8!*CuoeN-yN~#@*PDPyk;r90SD>8Dx zVh23pd|gTR<=CS;Eky8Kmi^@1oMmiF;w{0Tym#ng{FbG;b=i2x7_NL_KABGf02~#n96b8IJbU$Nk3?P>35UYEpNqKbh^~gin|{tZw&h)7B5s+ zVkdmfWDMAEf#CL~t!gLG(-dsT$jC^L8L})}7VlkH_+*~~Qi1>@tRzGX{L(tCbMx}< zCcJgLT+z@_gz+wW#(OmaFO;wA0Bp@rC1^jzEbXNU&cw`!_Q%!s&y=dV?YT;zeuMt6 z`2TG4ea!{^$Jfs_187PmVv*u=nd;?evl|}G3f1^8O|s_0C&NW8g7|%3@Sa}&4lKa{ zR~S6s#YKzNrOFTsgqP*RRBv$#$R??LcCG!`wRqoY^1XUqjpGD3{ELz$z{~R7PHX~t zTMvdRj}Hl5nlh<9tg`;T&d$z&lh0fW`CEPan{Z2C?LwVRs6fs;Z^@@e)AT>PMHTur z;FCIAIOB3=hWKlkQAX5M5oLW*T1IMWJS-Y7qaRB94zU3S5N*(*vm>Vw@BP zoYVS;2p^;NA))qp-K(`1^oi+!L-)(|v=)XUWLW%gwOD=nz}GYAa^49KlOnD)T$@z% zJdOdB+`z;?HC9zta=C43=P!t>%VZ>h6tNqyEZ~Ct>z#L1X@hfIWe5NyfD+bB%)!ec z>YIKeBoWL9%2#R&yP;|7dD?eq#yw*emv{Yv%h(VWmTh}>jhbx&2lJ$TXKB-;TKlr_ zsKg01;sEaPjwL~07cg}VZ*PgfP1zw79RIoc4{pP_HI#LS#S&dgl^*@!f1W2pm1}=J zMCiA^ggNh%h!4N7^ZQ0<=vxJOu6~}#6>I!sWQ)sWcxP1wJuFp`IK&bW_i|^PcmZixakF|y52tWAZ<0I z4sxfduIV#4#86<~|IW7K=2BsKgUKy;++7%Ldfo*~@t=zy5^Cn_ybHLs8A?1?jakV; z+F2|LnR;B^s#fifYo_1@GrxzdTesjKJ@IBWUDxE;w)R88k&$Q=$^SsWiNr(-r#zb; zD9mo?N;BZ`yCEy7>>A4Dv_|`S_Y$=hv2pEFK}DJ=&79yUN5;fdgj#{Ptf2IElJr1z z-B4PpkNlRcy^oQf)l`~=^$;V%$kRNjZxmqHxbp1*IIAHSY*FIzURcwePE4*}qr0tf z!R7?VugoL~@)#PFj}bmy($KOMrhe6yR$+YahG=3I;ez)YbzueRV5UaqA6L@G#;)c2 zTyJ#fVHIF&`1uK*edW3$*o5W8s5psxEB}BLAz}9Jo{H=CZ4gVy9=!y)PHW*@``n=w z5JKncwzjsa4t>nXV36nK=ReN@F3NmeLu2Dg-WT@v9Z)J#$d7O!Tg9T`qsMgZ+IRgz zy?dLw`}NXGx_RXexl?0DX&sjWb2*cEU<~r^#%LVPY!HF(2@ z2lR)FLzVwpS67vJgvo37Zg*zoXsQXv-Gz7!{sa~L8M)8cL>q%d;PoVe?(ydZLhqQ2 zi6lqb7(~wli{5n+NR&KFyay~_aID$V(h`W|@24ij^ewvL{lRYI3YPZK-C5g-f4bk- z_y=HhAcmUuCX#8pcVL9Rp|e>`f(;eaBb6qm_v5**Vz1U77HO`s-hP%<`DEKpSv)E# zO0RIl@jk}+2hN^hNYF_iIt1h{7xvf#02wRg!v~O`5>`r5GgnepRvUVMY`Val|Ciyb zonHyy`+%41*q#C)^!G>upA*xIuX@7X6b_jmQ|X@!r8U7LL4s4WJRO?a)A_jE&@@t- zC9Geo$hk14AWSLB=IFx6KGpeHQKK4X=*!>DAQbFeEO)>PgN5j^rEbx@iRE$7e+BFz zfVu)w$WjgV51}{VQnPgC`IR zf6u#3$_?2nJ7T8=sfI*D%Z+&g`Dr&d0n0>aKdg@(I2YJ>3QVrcTiSXlnjlY z|HjnyQj_*s*)wZS_R7&>BmID-xw&lPNOu<(kSVchi)NAaH>QZ|TWSNlwzV~7XCf(W z6r+FF1KwesN+xIgA5Q!6fLc1P#pF`zUpEaQMfXkt9q?xGAjpJ&n7^s8Bs>4fbLL6L zBWKmY>;B-_y<-`fo|>(vv-I~zyWxL}_YMwTDoh}iv;6OYE;=9zZN6wEW=&x1M7OoiKLI%-+w4);Ol5?_~e_yCsGjhSO0Ql9A4B^ zRzRnQFy*FUBsT6$k)9Vpvimf*frYWVY~Ab&8l`})c1kGddSPE{tS)K@z0z#{Wl@O) z5_bE4LFeHHcB-}_i0RQ~z<`&J&8yKhL-V)K2jZfSNgl2~pmCbzab+lJ6~0{C#)`=# z_L!9uSy*eydpm@xd-cpAIj@WBN$?#F!V*6$$@--C1@#`=iAC7(asCashhh)Xnnuc2ka&C6?4R9PlQXNuXfus|X%)~QC?llaNl;MCTv4&QPbz8* zO=uNf##0c787RmJIAYh%h;|JrK10b+U0lS55j5!%&;owHR`Vh6J32b{_Ypw>%*5!5d7M&82LSNdaLkEmM9qn{I;CN|!8 z)6_v2fcWY*Oa>uJDEz!A;nTewZzLf80yP=OS>wA@lGAPO{Ulc&e_z57))9559{6_A z{nSMdSN+7%piV$o&Hn_Gi=;gQkz||3{=ij_hAmH8NXJ8vo7@Z6=q>rIoHwd!zeOIM zkangibHzy?xti3g!g7rEn?Yi3AHrdvbA83d0~OEY%mx;Pg$nunmuG)ke}_shWOx&@ z%cx>MD4>rAuI_u5;ub8KAY9}`HzhCUqe-gQpHk$Gjh%Xojr;6))!4%B{>@n<{dAGsd0Qb!4eyHAXtlzX&3Fc zFFENgY~WR095jH|3*En$*0&mMz^9kC-M$dQvIHCV-yIV3Tg@4h)xF-kQdiRU;?mA< z+~M0LGjSQ0QG`*`_C}CKkAiDn2BA`@r)+oH^N{2Za~QM}H83Pb>D}~jr8%j_rna!Y zOjTYfP>^89*7;rPCof}=?8ckBo_Q@)ke`giccvlcXZ3ME_4MR;OxD59uJ`zt*zshA z?Whcva68I8BVSyIS zc7O5A0lo$&V@Pl4yj6h=nDfCG`Sv7?o%AHgk8jED{S3uH*P*al>x7*RhLbsZS;LnP zy_X7S4s#>$3H36EjRB20mk;(07qg7k4ZT`F>lCK@pF}gUHZ<`B_bb8Eo7{BWy1AX} z=ffHoQ^Zd3zqpH&86O*TZ5^`iZH~eAPSUdpvUlB1V2!6^ed;X8%{p52#s{e1FVxB2 z6{BDDX8ZkZjZ!ZzWJNjEZr>EBTPxDhw|jBnkZo^8tnp}?{A&C9MVa?CIeZUSg`{?G zR(Tg>mUU}V+py?543e9FtHQFTgOYVjZCJv1nl>B~CQ0-zr|)>Etbbp~6ZYvdiAi9| zx<*fLHMyM6VC+6R>QN}{iKw+*P^>b?VE7M4CTei>zLTK|4i`AM4V!LF8C*l;cjs!cSnZV4TlJQ zUFNIlo0Mmg-FiLbCQp$Sm4-OE#+jlsU4iM9Xsa%#ADWn)n<{&KuiP6W;y+8>^(X7Giu(I0AeIR+<_ap+nhY}FK*`xL9>pRN))pwvuz~d&ym0W_UD*+j9 z$NQ;0w#v%Ni_she>V1+h*V=}L2B1FA1A?<+by0dn{D`qBv94_SInNEaDj9H#Lph2E z6Fvyb}XF5sVgF;ZauqNT7E~VV}AJ5!%7{~y?Pk(&jQPsvBxCe=}xR~<<4&gnGM={ z9(udePL%)rj}fU1_^(7%$qc;JEu+S7*kF7onKl5Ie$#5`0{X;9Kz!x3UB>9W&W?u?X~21L|J?BVy(A4u6LzlCdKMH$kI z?>lrow(jJl^m7aN&L0XK?OWyQYdp`MJEoWabX~fsGpJ_9=-cn?&7r=@IFuODEeNN} z)_^&&w01~au-&O+p^${l@^!zBHDA7y=w7zfKZSHXutMKHZ-u4ObU_X*PMS=MC- zI!&_?O}e1;OTR4R7#I{T)}BaT zy?%ebZ^nCQA@-sV-(KvDO`C_Kea9j^O~o7MvoG`+xP7-(c&2f(-4-(%+`i_!`6A=A za&xuO#0&)85%Wt8d%u=c?WxUfD2vNK5nKLLuu@0&BOOU-m7+Dg3pZ3I=uu2u6iUZ? zO61!rv2axCD8oWYuT|FSYkV%R3RM-koZ+2gC3PJSAel)s0K;{T*b-%1501$^*_dB% zI?*Z|xwanHM&Osiw5iLS{)l(p|09E4xX_3CbRlnJ0i9F*On@z3n2O_}?Yx9t$;cZW zY4_!C_YN0cl~*`hI}Uqq|AC!2e!pyJYbjadTlD++&`!Wl9szw8A<0JnmT$YuulsdU zoF=k&mo+?De0R6R(s$-wXooy&TpIOB%1*eE#I`q3($eRJJLnl}@K#WQ^AJv-k69Q| zIJx(%3aO1(zynTmO+tUxjp#Qnf6UJ_y^OjV-LIstu~gZXwDxQMtg`B&#zgt3*Iqwm zX=fHU?T0?ep7tdk!pt_d?QM0x+faP#4`zd_HwqgY(rVqu>GG{0&w1%Z7FLjxk(6s@ z8ll%96e54)e=A5p&OtMwajSho0Oh~BHM75zl%(j)l@ozaU!UHKmE5_f?z5P2w7=Dv zzX{CT7wqX~5A9em;uH>>I;>=HmRWf#h9t}lYU{CG>*1Z+u3r{X&Vc+qm>??l7qz|H;Gy1CZDlB6|GcrupO3j$pw5ydI7d+ ztrq3nF#nA+_~qNfUA}RYKCJE!-zlb2;mz>sH4}4+2U1jGud%nZS<-rY8CkeeABD z7A$ouY^Nnhb4kXC-o#`fE$O3X6EXjt7d6b~!CpLmWl7O2g^Od6AKn}jP8VL79sP;V zrOU2fM+Kb1+cHjHclDynoh=!|SFq3WM(U;a9P!iSh z46b;2s0Nogt+Z1U4}~A^%{pwGvfIt>uFrV)tR$(ws6vXJn)m6Pp8aDrv)3J9XX?3V zkXJP0IeD($FhzE6ypj743&$Fnm_IH;r_`(0fLo&LP0APS{$$>%g3p9o?}V^OV`n~J zAKORhUjO%ZoWVNY%ONoV_~i@f@Xh2@yVf@Ck-0T=%M;1aGnPU4-B&K$D?FxzB2Av# zx^0>x47K%4UBP??cR}*Wy4k$-3}UZd;8!^C0EW&%mhXblBUlCWdze*ftAzQ^Gp+j* z>Qns=H`~|(+N994wOg%Bu(gqZAb)(s=|BHPvkb;`y?nNeN-`O23ud4qTwZj56QVxsIMYH5fnd`nwQg$C*0BWJfwgQC0H#ErKtxdW0u`n?a>(8PlV^#DW@h?4CO#?X1e`Xz= zA9bk8I9{{MOZRrL>+=LjlQ8U)xJmpV{CISq^Wd3GUMhLh;f_i0n%ujQq?!vdtgOF} zmHO3LT-dIi0rgDL>(_>jIHIP>mDIBU9LEWT|40p>E*iQ&__wmtKTiI-Z#U*T&zT}3 z?4Y}}J9RK}x|h-RcnI>bA8GP#{*F<|BNj?PfFnuHmDn42ypu&5A|+07y`C@&firUx zD;_z-oE88UggaLm+8jbQiD+;IX)>)0dz@3h(89-QfBXx!17zvWyqMGzxF7Bq?icMx zF30(pA4V|9(*35b*ts3Mu=&7GFXv}q#MFg1Klb*-OV85XPjAH)v_v|tsfQ*9E^)jC zbRi&gjbmyFA+?MFz2K-$xPDIG$YtYpJZE%G&hl4d19JBK=j@U+$v3NV06BQIECjKm z+YFZUUFR$6i>uHi8ld;0#N4Je#$}yuS~xP5FIj&V0$IjPgh?uZLin+i7>3KP)J*OY zBwI!!8ngmIngyQZ!+7WU&2GAp9|44+;&YZ^oHAwH9#D%LxG+Jln$2&p(px{$IP$%T0-x%P}7F{<~K|JxufJ0mzr+bc(0@f}o|;Oihq^;_&Ft2LtDA&)|p?kglkfC_1ob>qx5D$9$XW!@p07=$Sy#SDnq!7J^ zLm=t{vLx@mC)HvTy@YypPR>XkJ)V{gphR@8!WLtqYNm%{qE65Hh^>hxKb(UQjrV-$0$T{_MlEaxh{Nguu;Lt{5q; zPub!v2u9w|dL`;J=*@xmyx{?nQ3wUB{E8a{%d+;XEt=!iYNhEf(>=bp(GG;th+Hlv zW0VF)YWdIb%`|nU5Fp25pMrmQn@UfB_#h6@v8M}QSW|MNA|nAV4Y)XRkn~nzVc`gs zIFR)U`A*3t*gc@oBgk~$lU6uVvl4&?vmaH30nUtJu|vw$0@?&&HPS#ih1!N$e%++F zIv!;JHxi7Ty{~naj<4WBu(X-#XKhd;kf+!OPzWmaRb$0gTzN|*w?dQmh7eAG%#dbS^? zT5CM&k)}SA?sO%@HbSm_M9ed(qrSn}4psdzNxPDUor_p^A!20dJpl$yLUr6>d^(al z!}lGaTv+Zjq}8n+#j584T{j<6r+I4k`$s#sY+t3ria(x6q#kJvn|(*kv5Iu$_F> zK`30U?uvhg=q&{_$q0r5ZdCxzq^VFFXwWo4GkW(bg4|z)MVMRK5Wm?L!)9h`+PMEGby4t4Mbqb`Se{Q6Kyzb9G$(DggGw)s4-zHv9(s!WX*_15v|9>Xy(&?CZuaav#pIfjT5PLh_x+-k0p1 zSSqP>ZTR(iK);{^Fr&hiAW7JO$MjZ~-2PYpU}7d*Ua0JH@r|8l)s`=lYKVzD1-5|a zr1Jux^A>5)wSW-qN^}p`)3oMxJ9R5KB+Z2owemafwj(*+M#C?+-9@%WcsNinpv!&l z;0#1&vP8?iUtPpDvxjDW7kfqG9bKiGBX#~w@pEKqMbd%6T^3u&nc=5^@0dXvNK;8Q zQ-5>}#&95&d^yW3OVn{o52R1iW8}3QNfiKwF)=5$JMBf4VRvtUuVlA)bk5+eLscg~ zi5#&8BCcUo2iittCJnWJtJYx?1m85Jekl5iMDXXU+vgN9CcXNL0pD`%U4zInj%spp@o3T3%@=?(0a@1Rev)Ew;xzX1Eo$`rVCESTrhxh6PdEi%SmGp~` zX_P-+_ds~hfBQoDwIPIry>;rrKFFvOK|3)2tyF5Cc0gJy0&Ow@$n3QjiyTCu!BC@@ zh6`SDd-?d18UQzO1YP316et+^-e?oUY-sr?Lj*LAsR@(S}uR*^0o6IRZB;sDf((fE=!XF>&CPp`DN9KW_ecq z^V`wsu_MM5h`Bj25ig=4gFgd)DGC(V28uM(uBc>zuX51nfQ>~LF7y_dO-4y#zP+2C zoEH25N80(p!?Pv@0<2HbF&zN9AD7msZ4ldkaVF9KM#h z_V`tH>G>;)7zmx>zfa4V<@(}7RP%!ik97L=Nff}HmO^bn9BmdyVdL{Ob0R9e1+X5r zZ5!Lpe-29oR{6VY{$rN%J#*?CWiyh|LoqXJ;?cSGjutnA$3{~4EIPf;LgI*ipil+k z*qcbEPi94$(J|rho{#^mJ0|Z@8;ibrFnlqL8}a*{A|}yB$eKjXk!U5mKQ=gtfYloY z@&s{`b8qpx$TY`{D zAPSOk9bb9RH$P^QXv#bO106#)vKye4&q;#>1=U0hHM|6&cFT@KIEvg50T~A}h{adC zzI6GlmjIfSepC(cgc_=WtmhQXEDsl$$1S1Ls1Bf((@G0 z#RUD`4LA;sJd9Ijov3y)YFXF*N8Ew%wR@TPS7zXM8?z~?rijSp2M&yB^!YXQ)S=@y zlqj_LlWIjNAX$31FPD6qdy8(=`3OfN#HQVKD*oR?UIDNd*^IknF{X}c>M^SR0X-x8 zLKxoX@YW9{NMJwctouxsziqeR0yX3zDPYxPLWR%fHXu#FGJpI)^gESWRhllK^Kx?m zsA{4Y6rjmY#_5TXDlI)1M2`D53>FU7FZ<1$A25vn0eK*G@&LX-&$w-zrD@Iy>L{;P zoE}Rh!7?TbB5IBg^ZZ3O@imRsQWu%&+?W?2fvms+T;Q-YLjy>)d9(6I>7R5{{R}c^ zArB+w#e;n3AF0kTE{&i1F2u;#1}yK4mB)~5W>kNr1mqX4`5hp#!toPG5lW^dcK9sJ z2zY=}9}u|%b<>k|?NcOZQlXvS9-J1-BKJ_shXNA5SZOJM-e0MaUW(j_kH^4e2=LQ= zoP1Zt#uIF*>A+|_)wWJ=nb8TZCgX5BehfC{GJE%Q`$^3GV`KZpZ~+safyWFDgr|DU z3%uw5ofd_Y*=j@Z2{XRIqCt~G$@^LGJ{}+?ZCw*ouQoM8lfTaRCkU!Ud zkq?$fN%fl;h(I1)wc8D;K^{%6uOFGQ?Z-s?ijl#W)HF6o`(b2{ez@nYxXi3hV7X8B zdrD6tl==M#9_tf`BPO&B#TutQ4dF%g5PGJ z%*Ju}SOaE$-Jsr=&~!W!8gM$MV+5Lh?GJ~sKQ1?G>nm(v=pQMuyd%=IHzUg?>2o7~N@mK2HVdy?Q zS%IJY9;#>co@?KHd%tX_+{|a|!cOYx{1e%4OC58|f1a3~zH0L88)16N3S--w+>z~& zA;kBk4L;oeetI+{dxXKjp<05u>JsZc8Am_Xp`1O=Dc%{ZCcTtMkjA3EK*^~WdzXjH7wA2yd5?OyL|Se+<;N2P!Ydmp-qqmdc$mgiArKPGoc~6dDzqO4bXq^p4vhUL`8TYoR znvoLUnI`|uCmE+rP4zn`n3LarVroZ&87Id9Cv9yrUij&NL#Y6K!hXW(OP?A2rf)CS zQp|jNgTL+`wV=?Oh^?D!Cv!DTe#dzy3sFhw?<_OOEJFb>qWSl?E|gpClzAu0{_kA& zw$xgSClr*shjVvcq#Ifr8C7^Hm9j{9b-UuzMtZmNVUhQIyhf9y-EP$j(|<6K&EaEC zFFqgVBC9@RwC!?d=9JKMS{9nIf5_(3p&O*US_n7w{#79cXqHT@$DIV3#x2FtfC;y9 zd1Gmpz8!(1($w{PX8s0-6c)0ZivsAzRRpZb)i`W&YBp!Lpi987S8+-8`P`b_*A^0& zhkzT$`1$~c6?R)c5d(CFunZ3WBLK6b;IOVc*$RM9J2ja3S$X5xj2gD$n>JILQUZGH zP7dL4TVJ*m!zO#=(~nTYt2gcjH+mjNKKmfWpT{)HX;wE|(!p>vYXbt1?b_0&-4uZ) zOcle->EPILE0gJI1Ou$IOrK;k_3u^El6_D~!2yuXpeoYg!9y`To!2M>SNlzQWq4N8)xPEkS@y|`UH2|7`gp@Y=_*68T0D%9PUO|Z=GQNPg zS6Q~!D`h;t|FU~q-$V#9K)Eot$>3YoXA09i2F`M_5bRES-&UtvcV!HUnR?B3{BaUH z`E)y&?uYjgx$IPG{qO9G*Q5CH(2{_*(tygn!i?iS*;?zm!fd~-S4_@c=6`;be%o8} zz)UXRNov3$PhIEXGjKGz&u{fb1&t32oe1y>Ai;0yed?`=fi$ppU`z)++}Flx8V`yE zj_YUqXHsQ8_#GgHtHHn?z`;I#Ar1Zr+Pcc)UE^QQA*+Oq5K9M(uq-tKS@MQCwH~TfY=&~>Q(jb6}H3mH?jvoF~)}lF=0DPr*kt$W90r8 zY77rtGDaUpm}MYv9zHbr0gI-aeW9jhcv`1pCTH>Oa~uzy#;DEEKAlg@JWE#f z<7Bi{-&YN; zm>si;ro{vSS?(VHvs}Q#hGd%Q(lfeP7U1sa)3#3|!S=rPExwv8JmvHd?hS4Nt$~_G zAr8&P#RxNK<#CmOYBtrq0>%o z_B%8XkX~tHKV|+09EH4V*C}C5zaFJfGH}l=sZcqa zQk6E}+p`lzJgX473~;;1P3?)kin}*`(E>2!U z@72l`IKqcN$qjZJ;&cr}HQ)?A2?3e&bN_k1?3VAqQitA#DeLxU5Q71TJP!Y)`W^U{ zF9T zgb*nB<~Km)q3D2sCeU-lE|`BO$O6`7P!mnVPRZLfR{&Zi&-?>QLFg{4nX`ki_5pB< zW_>M-f{0f{W&j}1juItP0$YLG5CDP|lQEm$>XS4O>W&za4$P1vNSp&7qY~te02QMI zL)2l+!FYe^V({Kni&zNIuLclEfB+Y#gb)$0iGVDo%af7|@YV(= zw>56r{KgSuCZe1peTbbAk@mfLS^;0Tc(>q@w%&9t+2Ep{iNT1TUvfVG%Qo4xTcp~VF^eXE)rCNcH zD}Q8qwv8d!{F0TDC;GN}HoC2gN1JIhR`{oJgfO!Pvp#@-(9<8$RkT%7@|}yHVT;wF zdiDL~*$0^fwpDEN@-FI*M2J#Awuz-E{E1~LwdEmkv4&PW-xnyC)vG7mN$LV~O0UM$ z?(YS32n4t#fvgh0;F)t)3P=_O{o<#06V9VZLa^LSQ6V^H z1-}ST$pB6TgMm&o+WDXC<`!KI=n>EYX4I_Baq1GdiWtK<1Ru4~2k63*FkPSDRksMH zFRje3jX#fi!v`BL(ViJYex4VX?_hzr2G$BeLVR?uu}H4&%j=d8Yl&RCFr}Q-03fY` zBnsxShMSAp`88zi#USyg%!=UZKx;Gdl0hWoGFX})RjJ2ZQ^2c(6rT?xX%O$AjMR=N zAAOqE9Re=H{1Hv5@|m6}liBupolj3Tn0KGSsiZwINkQ99@A_=C^J=tM-N$^N>7E|7YAV5pRK$bb+z;+sFJl6Spu7po zBkEP`AFO|l4WCyWo!|+y;HL`i5)-ciSRAF$f8$+XP%sZv%|SbNBKk)&X|eE^XB_6uNzatFOkbU0SA_GmIOwV>JTTd{`4K{mFw zw!z7s%;gi5~w&3|JUnqGUFq#b%jG)7|h#=ABr%yJKpwLA? z&x$pWCepd|Zc+Mmo!gfyV?d)i>AoQoQAm)G*g4{+di4q%w!p`8JD~m{is^9wRbEwD z5^zz<4ss`MYeZ*9SON63V_ZF%Aov}}9-cG5|8G?NTOEPKZ>|WNfKeTYBhuTv$j!qJ z(aTPi>teX!sQDoU4Ql8VwaUy-~0U#6fRDlJTACmT=&CwKLL~1+uEU zj#EI0H-~;oQ_RvSy1KIWNd#oUO}6MJJe)f5v0ew#-hT{@Hq9C6_d;UFV6s+HR6iz% zUZBLB*!G*_xKDBMH8nN0wImh)mJ!Is!CG}-eHQl62NH!(GbSno}hVo?baWP*xfM*kMF24rOQ(V(3`h|E1-(X|uW)B;I>ldMM zy;dPHaYRR1=$TR>X7jWZQ#TM)vNFIBVzHyDH#qZr} z99i1=h{7hZuRasLVIPDt&}D9p~83P_&6#>J1`>vv(clg8jlAd_!D7n|12YcCqx;Es$JjX%3a+i*d+eh{Ct9~#=IWoTevp#YpWnV;On z%HQk4Dm_^}v|qkk!7c}bq}VnWBCC^d>{`2a*ofz(P%Uo;Sfj0krfWdl{4UX^%0&g!^JcN4VEd`;x5WP(H&)&0{0)gOc2uE5NMX~L8>;E&jA z&SmUR)P1qfOG8v@l%yA*o4Nk&32yMT-o2%Cs(D8X%%uA7QqxnJ8fx%&zUW*O2CoSy zZAb=`J^y(o(Bc~Ix}n<04m*YKjK;Sw`C;9FHFo;DA#87Mtk}EK+hIGWj`k&aVD$$k zvS#Vef)vCd7f4i7_%n-(1MG{MC1(@WxS)YOuWh)Eo z-->EE-6jHat@;`}er6di5cX(bQK`20xYI$E6B1aKJqY-Jm*d{QAB~R~1MKS#1QPTd za7{X=ZF3{edq~~1R9We;n`>m}xo|h$q)Xv6!H~RbyqX2u2QI#ED2OJ}bbQe8#Rt6q z5eps-Va(RC_nWb_>ePa1R0x#@IT(!Y(VDdge)P(IOQ|waJY#6W5a(BjxiQ#g{oy-& z`k-3#_D>+u^>U09A4z<-{UB~;N6mfqh~g{PGt`LomI~B*f<2oss;CAg)zuttaqeQm zREywnQ?@Zbsv22S18$vq7xs+5o{Ar6ODxT_Iw03Z@?-VOx8TgIcTXf{uMm#Qt zPh$S4g^)n9`e>Tlt<3KOZ?Hwt9{L7ca>>%es8D`tOr~(b=Xj#$YmrAA8sOl9tV3Te zt$9mIASyuAy8dct_G?yDQ{--e1lAH?x`zFy&`EG09{N)1T+FIWH@r21dZqhO{k_UB z%Q9UaY-(|h#~u)q2&Gkib@)FSiIiz>(iImiomv^M>0w1RFbG$7^X^-~pwXtOU><8< zQ8iY=V1av$0!H5No5j04I+oTSRPtnSKUpIko9qt3g1invUWfDSHN^Mc9Atf;B$iI$ z97NMlOrugCsFV()s9OY+XEP+YSTBfVZpXO5ic2CMy<7Dby_V}*qAk(pdI5ruARb0( zLtARD-WjdR8#i~=!8@&Y;LKZgXO9^*Ub+ccrqFOQ)$R7d+r-BR% z#TfK?55}i&iv?_n4cNVAe`%tBA!f%rEsR=Fuc5N{QZ9miXCl9b09?fI;IDp}3+dZj zS-L5@)#%YPV`@$XB~NA|QiQLagIIz&u+tmPe|HY;cNEAh=7z33c9Jc%2L&Bn77{B> zLuC}wPX}qzc1CTtrr>Gelqe%vn+pxIcx>-XvHkS$z*(Hyn6bg|Wk?8dM#5P-(&JCV z-+T(Jt}`xp`-1^hy;4JZP0^m^@lOmENQVyhDn8Y*sa!?-tv(3=Oj~H5l-Gv2dtq`caQ9l(7qU(NN-NF|1r^s;&o~7ny0s<$2_2YOw;raOGkG8 zbO=HMe}XO49*q9eN>u|PW#sI*ppZTO=9kth_w35(*=%%lL;e_M$NLzt*=`8S%C3up zguwjK*~&WH;Yrw>2h!^*v^ic{N)Rj~gk9D#Q->L&d>P9lS``dq4CN>a zAb&nhGkc)zJ%;QcqnN@#vC5XtrOWyii1>!xOy;(`$y^T0d<<%WY6f@`GP(gtL<&?6% zNz(VL_iTiL=Kvv2WA?|{``7ya4^?j-4^{vEkB?MZL{cbOQqdwyk?e{>NFqzJX33uH zyEc^Ug%rvzF?LzTSPDgUCI(YUmciJ@GR(~HI_`RZzQ4Kux*v@*=e*9fKcCliz0c+h zQIWXWmGdNrhl}GXvE{KhM&9>H&yS96N%=%$HX{=gYhB~`mvXzW@cHsQ+|N36*^1zy zt7>AB@J`tNs}&cD>p0k-%>y2SfkdPr`uc#qQe28D*FMg&Lr(Z>_f47J=CAI{61Zf? zbMUM;26NI_8_V`GMm*P8SJZa-V$ZSzuApqsQ1f+@C`D#O$hw~+LiV6iyl(H3j8vAo zL_xyAvr3mhac`q9T_N9c(N4_Amwy}L$}p3=2XiW*@SrjeZm!fx7G(b6*+7YdS5$cU zYOZ-8g|3-@XGR!G{Fu|x@+(J4=tX}FlgZS~D`I}ODp$ypOAltmo>dd?G0wxSd~0uy zznU&HSty(rby@55_^Fp}2b`TziTwW_vk((pPD$bJ@vZ#|*LvJ7bN}=+Tta+2tQar; zh-+IB#`E1W8i@iODU{yq z6lph`IzAZ4aP2oLq&+c4MFy0@5YFNTWRSs{V3ftSK9U+3MT|g#rR@EO-7=l}mA7e4 zQng*40cshk19A5L1Sx*2DD4oVT8CG%XHXdj5k0CK;xgY6A}J+!ZPa5A-_t=0uB$|) zOY`I-5$br=(ofbxnl^j|5WK?YIc=e@q;JaRC1?%!`EBsL%3_}?#a+AXy~~|?W-e!y z#rHqrSNq7tgJP@noJq=>xrE_~i<^v=ZvZ)HIgA|8*3G{f67*w_802ZT2w^^((Idh2 zu9W4NE>c9g+9TwbUm+XW82_nodUkfIU9S4n_$gXeht^Kit42gUqUCt~>!Fxp%OrU8 zRC&pTQ{5k&?1onY9(tHhik~OmJYF>4)NyPi{r29YOx6@rY=&K-aIFawpjM&A;Qj z;Dm8@w~W^r{_4_^$fehgwdnb(+D0dES*YhsFeO*!P#K&T^TDN4rnhVlF-M>8vws;8 z+|{Kgzh@f+L(51p>JNYs-6uAWt12BBg~!iIaDOVaIGZy5#6qox1=Ydsqzr|GN93AmC*B4_dWD0`^P=e^|&@6u=zw7R5t#*<8IK(&?_rlkTb8hA9pE^*^ zNE!WHD2YP7YJ%Sj$!*nvX5E?p#L;gAz85^N@l)+!Yw@lp4{eBeJbvhk77R@S<3GTH zik9AtBL6EZwru}qSk|T4>zskaHXf)~N{zlBwV6I!iZd&>7B`6X+J@f9wZbpY&N_32 zfVbPT4b>t62gj^S|04}QdM@p=juYO-Jd8mG$cK=&^V@c8i?_DR;N3=~oZs1NzZ$hs78|=TY6>^xmu4v& zo}R@AV$yM|l@o#rkL!zdi*gw9s6%{{DiK=KVerbNM$fIdrE8>$<2ba8)qDdZYBRJj zHygYvynh!=g18P1*$`SeVnTx4(GhUZ!Bup zRsfr&F$ZE^zC6Iz<-6+r$zXWs`}a=jMt67Y(%Fm=k70nMj@?XXm-h32|2%LEoUO;! zZ+oPM>P)twqHW-9M87FF^e3#ybrcKBb3)TU9RF4PBmTtIU~71!#-+?(`|&~rx^~Ip zl;GU3UOex5DG)p=E zY?!B+EoOqtPvGQ1cu`Il_kJwUC<@p(k zdspQ4$GriyPVOVewfVBIq+8%U8%BKbQ&kIc+Noat1j69p;P>xg1tj~PAZzQ(r29kj zC{!-ujg{XK4}2kysPC`tXlqjw&O4~RGZxB*4`y{swY7Q`1YYz%kb9e>;OcAWi1%D^ z#PlIiCZB>oWoa_X-)iN1QL^EP0?X;sr>W!t{BqCh8|3mn511825QX_nmPMv$GmNi? zpI>zkDa*yyOh#5#)^GZk_^b^o_~{*I=3t#250&l|d0)?Bw@K5E6!8SB$INyn(jI^Q z3#ssv22t2z7gvay{LOv(xVVoq<=W5QCtHcw{&lnWF8_n3 zS)DSascJ4;8%pbH?CA#;W7BF|&F-=&Iu4v$C?rxq3T>7*OmNK@Srp z&%8MFdA7@ZrTz|#Gp>`+DFXRsPb+2N68sk9o3DS)yVWnH!o_lA#W1n<@}ku&mLAA< z(B#L6Zl-)nK5<>3+wQEUHe?zDG9{UPWcaDE0%z>KeEmDY2u5}P#Ixa1cAM=0MHSLSEgL~r5#8%1+5)C7SYPt{EBHs@e^R{GlEj!_b4bqQR@HjgXsE<$ zh8+BjjwU{UZsGPsyPDd{$}iXU!Q)TL9Ds{9IY=A=O3gZUbbHzD6yUY>hVwbcX)bw!cYn)e8iPIbCNG~)12%ucC}}M zOOM=?dRegG3*#bS4iy*&n_pi2rj;x%Muvu5`p^C5e|-j_Os@XrlQQm8OM-h4=72fN z#47nS_NN5g#>Yd>9?TMg`9d%Y(YIbn8A`-cWXkF_y{pIBfTyY|Vp`KOx*Nre1P_QC zysyHk>Ty`8`kWPr@W7>v6m2j?J*6fpH@H4FKO%Ke&GZcnVA#*N4~$u%=vf=}XKEz) z-s;tJKihV!t-W1g#!lOTk`XeE{Bx(NnHk@gwJ+o@G73=|4X`;ueA`78;*8Np}%F?-a=s7HY6sNd!t{|&uRQn9m6liNr%6RCWB8+BcAoKgQHW z;*f7**LhRY4fCklvtMT+=nC$Iz481P_rk7|yG3BtSc|S*v*S@aaKj_xIv_|zH*v?$ zAI!=YLYJPgAB;0Kb8(&Q&V;EWWq+nA?Y+oHFT0+YylYyEG%?SJsyl{+J_uA7)ni{d zdV#S$8iL`Bt+_I1kEvr!@`#l7iNLtKXEm38e#Q9=IWYjQDi6SO` z#O{JAUOMytbE$pW?1v(*RNgLklJyZDxpj;6A-|6pgZVv`DX}Y%#vdh%Yld`X7ruIR zFu$Ocyg;t)#^y|NeL$m$eKEfQk605+RVQ6cDFwlji3Ff^2PtesbFSo^9(a(;xIZw7aLgj<@-PG{lyFErAlZ zP7&s|h(j>o8JkI|n0?076(}>a#XuD{S5FNudr&!4-kI?EyreNFn=Ys1%xhv*b#-;Q zlh9vm*%n12fEUCcsSZOUH0dOOL-S0XgdV#%5V6Nu~Y?*|c#EfS06H^sG>PKGO@P$B;lV~?cLk-HK}Ht(iB zE&F2HpXfoepkOWmqwy}ufn-=%0)bDD(@q89P*1CT51am3yX?k z^0a>X@UDbDop4d{)0LM08OB8&@vadOD7)q4;Q^7&YdkWW#Ryt3xGW7b$;Z+x{VHz@ z+J_FP^@-aIT9Mpc4ro@_K&P3qIUa+0)Q_TBDbGUs62ZuphgF|J+Q@QYeRd?Tu z%K@U&PvS%+C(S_XiL7_~XswWk^5N#k$m(idFfLSMk48wCU4xxZTabP8_C{ zzs*OiS+X+W=}7yxZ!j$@KR+KjcsMlf!u&t8U3<4aU_oXWOQS1D+-1b_SmGnx<^P^v z8lt%8*O9WXcvfl3V;lCGSzh@gH<@Db!^0kjvrii1f}RCkfT&tlHczLz{CO9#=hg4p zkpdl9Rpm(hxGct8QC^N9a2QJ{Ya=hGu@_!WhtF8VmBy8TX8?2Q@o;^D4H+ZULHI~wTOhLfDlldI<<(JH zQ+b2jq4_7GVJ#-Dtxj0}sS;Ifr`T-Y>Z}KXq2VB6vj`&8^ zzN7(-#K>zeRKJ&h+qQEt`aL82J5jEw*piBf!Sof_Y=eN56N#eb*kIIONoU$-I#Qx8L7^m{$6)Y7v`OrLbRTU;VF~S4tTy&y8RvzCxObio{`(!tpG> zmXRg)7uVF3GopNBCH^hvp$s&-CZUVeU08dm%2br+<}(YX`2E?+u3A6Tw$g}dG!HaHRcwu)D@u$3%* zjuJ^)rxc$dtb~6~bHc;n5;p!w!H_rKTS<~aK(axJAw@u>juQNI=R>8_ar^Pj!FoI` zk8kDo_e^ljl&~6_;2a?d>nD;ei#`??7h^E_W+fm-NUAIQz>gg{!KH}5A)R@Hgeh+6 zK~8`nJi+voox5hwP-4KSM}C1{%J_Pqo(ZH>QS!@)VNl&9qBC5;&a2^#$p*lnT9f78 zi;7lW8el-^Fm=B#UslAIb4P4HfHj4u5=7E7@<6o#QbL9@Ze&GnRm!KYUw7I02|en? zKRNvk75wI}KSOm3ykG4i;W_JN%*%hjTrQXPTS9BaS;Xq$*lE65EOAJjz7e{l;}WHR z`sXAooMFoe2xm_2ySZU_STYhG|Ml;eo*j!-!uIdob$U$mi0g+s#13NgqA&LXnQ`Lb z->2pGkZ^99`IVC~g;M$b>vK5t>deq2K|JPtvoC8I7#M_dqbn>EHNB9(y8BN)qOTyD zN|oD>SMOtRU#Mebm4g6XeU=;0DSni?%0)fm!Zx@F0$@JZ$5|JC5epFWPHelrbjt;% zavKWY*nI892&L;PQqe20`0NP_6cGIHM5QwzeHc?*nPw*8vX<(_qk%lWarvbIckU>w z@IrE-Lyy|m4^>TqSl#N3YvsO#; zF@>3{39SW0mfD=j6R>)CLg3=pp5=&$J>U8P^k`nA&j51-C_W6R5R1QtNv-z|X*Nr{M-j6@N94q?&zg`?t)~vu<%GS#St9N;ulz6axp;#qea~JemL3ibt zN4N1kF~Hc& z%&azr6M_i)K}ePIj#>)<2Xb%Xd8XnbZ;W5z$kH|;?UapaTgBIvXU?l(OtSa6f?Lf% zNS272E0u4%SXfe`E0W-Zca}Ib@czUWF+;#QUfnWraq#p!|0Q7tdtj75m8b`DiqstfwZyiQnTl* zqJ66iZ=XV$*ZhqKQQek?yW{Qs&GF|yd!m$Wjr5BQdn<(P2lX3%P9uKvP!=&XIV4|0 z6yssXS*BWGQf)J}OhS+FVh%kY*Fx2K15aTyZ;KQEpod}KMB2DG-V+hSVT#Q(MSJDu zX*@JHSw3CZtgaC9M;GkOCgg(LyckRRwLW~e$A~)zgAYTnX_<)qRgVA_cXv%aJJOvE zO6|7gtjpJ>&Y!;z0!P}@ErL>)YCx>Km7~oPo z3jT)M4RNI!H6th8Iu0OZJiSfh@#3Ka-f@v3&=$jP%%%Z(hp{*AFyU)Mu^#}>lM zQ{1|KzP_Ky-O`z>**izcDf>JzKOotN?RcGq^{uuxYO`QOF>@j^mVK;LmSO3{SgxL~%{9mfF7Cxz&>^nBCrMR{*);e@Wz7Ib}*;V(S=wG|q zKg3YJC0L|5@x2!~yi7U%al>Bs-uHb|-Q73Pgqvs_Q2DDern)s63I=?8!ngv0JUm|F z)sCYpm@e+!$^aIuu22ji1zvq}R^#24RUyI5DJMIT&9}&J0M~j0StK8!?@*-ImmYlJ zS=vnge3kFSyU>phZt1`qcz$s6IbJkczeRmI$oHXQ41sX?Spm?0HbwcqB%T)F;-W1Y z>dxBpT4CTtzN%_@e&|PNq5c`l_a|!-YHqj=M2?^D0PyV3$+2^mjQ7Js{WB0$q~nuk zogAVT@2V7RAaM*3esYK}W8|cT%bxy~2po7YgpQ{Z+v81*)JQ`}OC_E|aDqs4YDys<-6#|~JdoP;xgo38v+L9+5VvA70hoK7b{8Hfv z)1EDdn~&^A6^C8c(#^wli6fj1MYWoOp9=GoPO=O}zIN&(a>u3r3SeiS>jfA}SO7(# z+$pY;VKQ6!)Y2LFz5dVPoG_E&^#&1k*}fX5w5@jG00WJl9wmeU~wU;W!HUA z^Brn^-#C)#pxP`um>*u&TKu5f%e%F{zn^2iDp$f3JKCL@GBwjRbiUgYC3fJi;h$it z_hl)%aH>;^L-GmKQtXoYU>dGN*&*X5@A=7@@$oLDR0N^Cn+GM7RuWjnWpCvEx8*#oBcpDUO!Lh5R%ma=bw zB7`8jUzVgW!^Oe{o{UQU|AL>leE&f+JU%x6OzW<B=WH`a{^5y*h>3fUFU%5juA4}qPz@N7^O?(dyb9M%GCBrUXPhCtq z1jN&d20YPIf2=DltBd+(N+!5ST>+E4`6WbaK@fs}LbM_r`ApN{eF4+O zw=M%`QG#iZL(G0csPai&e@#1=V8ozZ_Yt==gtZd_7t&KVbxHXC*@f+=`aw9QJ4(Qz zQ|`Yj;ZMl^9;s=rql+5oR>jB%?!1j$M`qJf0Z+?(^)D{ptDxb4oMYRK z65ON!xe@aT(2{^kPn)kw>0>Xu^9!*3U>`~WK;h{+vf7>SV_ZXua!Y$4vgUf1qhyOe z|I*^QSx;KlAt6`At>(P&)}qfKZz$2_!)>I!B_{m6TU&I!HxLYh{gF`3sQ#}O1iOa4 zcY}v#vqK*K$GXD2%zxiFsrt7TX70Zvk@8tbTm@mJBs1UGOekKnp{_jmn{U<`+G#{u z%5Kkyvyd?6cjHsH5=LuyOjN>?uB;pehL6||cp9-yQhK6`^t=^3b7JB|?{K-(voB!| z)j20u_M*51HszEn9-$tBU8#F~S);(UDKe*uS1aUQ6&&Rih+mri^*f;AIFn0DF4!v+ z0pCLNHi7KfT5Nc48_M@z9uZvH+2hgP=hjgC!LlgFWs_!-j`Q^^)yRgk`|?jB)MEY? zj~*cxvbv;AUWVwO|Ly^K4EhPtz4vf1#m;P`(ue3V-5T~`R`UkxQ6_#6Eq82lY1$3kNTZYwaM*bvXo4owtF z?>>$>{UE7{>J~|Elx?~W~HTo9<3Ttbe!Qg(?6v;tK89evRqq5;-FyFnVbSfR1(}b zM6l_eDFlY!2qSA#t%P?ztn)B|M4;=I3GQ|98AeF&;HUoA=Ag7Zaq#2lg@)TWwoT(N z1AMzpYjFQpys-;xI0)AKzu@MZ|J*x7rRq*Fo4Rm{cQ}Gx;0S`nk_p zQSSWDyr8&pYl$;m-NJG>MzQUiG8UsM3Qa*u<(KoNI8?PF5u#rla8e)(QbP)zTjUvS zU3*24BZ)o*_wjo(I)F$T#r$p@W}4_aM%{rMP)Y*Z8Lj=#{)s(9>Nl_dqep5ZmA!Lt z*7u+M)s0}g&2%GjRIPoNGnh1#5zY)_!nu?MO=`-BS7_6X97ZI6`~N-a@Lh?vluHHk zRW`(iv@8_r=#rib6zz9x$*(Yu|Ll7Pu{EBf^Kr;c3(FHc4>#Au%>W@b0{aI1#yf?n z8H%tvFps|?=GQ`D@u@aQ8lbp+-EEMACo!{AJ&-%`0Wl1=fC!l1skB3C2k4bpYKooh zl08TtY|(%sr7Mco$x7|4HS;6{tjKT7HL5^I+T9if?>~rrmHt)b{55; z#$Tb%+U}S3<2;(g-DtxU9gVCYV6Jf5e4fmXGoj|d7NlNLvH{8rBFd}~lOHF?5x2!`{Zd^pWmox-wv{vXR? z-Ue@7O@O)4wO#C8$B2ruXR;{0yaJPd(w<37_)u}wiKN2swW#1L=|v?a>Dtnd6wrq8 zFviCTypu-$?DX`wVn;0R3=j9F8)8CPB8!|1}6lT_Ub z>_S1%S}$Wo%?tyUipBA*qS5pbT~!v%jsRi>cFIe!jDyPavroHr^kv6-f8`{js&)`v zlwQF!Y~i$g+Mu9@obM9B;c8-R>_;>v_>O&jS?Z$B@8F2%i0LBJLAy}2$>&uhAl$$S zMelrsgX|;vAZh|{^`~joAvK6jqE-j3_yv)bzEM(T{IzCCv;G6xHMaA%Bg*R1z|3wq*TH7})<(pLP)Y$#TaoP$=POQ_jlbPyZ zwm#_P-|Qtp?ZMS9mnny`xEe5oTsj)A)A0$CeU#kK+k-0sCi|=i*?fqcf%AVg!pkG{ z{Fi3g^%Kx&3VQ>ckD9kFh)FeJ=a|sdiz%-IY1#yGpRDQn%jMTUi|FG#UIC+RuW3_W zK~r{@E2$jg4%xIZS=!u&cFowIIk%uWSw4@zX+~1*;<9uMNuiQfIZg{DP=BC@DPNVJ z)Ss^olcTS7kQUIW?N&yx_%5BRWn@Fq(wGtT3z*lZC~a-e1t;^hbz}|-%6#kpB6e}_ zURY8XeMUy}ishb_*(Dz{_GQ2e<+-@}rRM;{%+&+y<>C_cdOKH%TwBCRg;AUWZ7zF+ z8iG&hoxf!|x*?=MOaV^H=w&vxS3&hayj$(eR>17rN?*;@4#4=guGE-c3+nyCiCxXD zhVdglro)UGZ$#!4LZVHO_b8KmIUGh^4eC1pZ+b^A^adJ5K>c8K;n07iNL)AT@S8rl16R^HeFqM_XB|qd3VZ2dyXU!XlbO48MLp!4PS~V zVSRvbK~^b4BEC}GFKC6LOITq#{UA(pm{QG2qj9Dtndc~4O*=yg6 zG_uca)#~%;SOmTsr>m|xv_!B%UzBlt87XNh-WqxnTZ@;Mm*qM}xfs8C5a*ZZ9u)a)Hd+9sHoI=j_}I?_^O;q zXgX_v>>m{@PRXfIWjdgPkymguVfUn3L2dHQ59Z&x51U8Z;!>zH+P)25OLQ!^Mk+=u z=oh|rR7IN}x-ejzYD@p3sz?b7TFy#q>2FqCFrvd43#^sV&&5>w?=xTR zA8kUF?^WOkTCqZI&W1CFHDE%SkJ1^MM4N;$XISbozS4FJ23FZ%!^)u~&B@gdBo=MiWi;oXIA}D8IW7JJ_F^@@5~kl(4XE++ufbh{@*N^_H)E zwJWcrhGFFD8O+#d(Ar>}YS2W2DK$P}qdzZbtmUiRDdePMlwlir-FV7xEJ#cxJ5 z5XXn15o-RpkJ_e|&2zfYW;ztdB3uI#w zz9MnkY^jL-A#{P)J9a#9v{BL80loM#JnSR4Hqr;qr3Djz(Y$CkX^3mGf{mbm;@x8b zUyHZ*@p#3h*=ayVN=F`pFXuQovG z^`eif5{sf{i~|>kC@xp{WVGpBUL%X?B*zjn*@cHvwIsS<`t!S|FAw<2S#jEYJlYJM zo*Ne#y-Z|H2<1>iDAu0qM*8d%Kjc>NZhcV8GuLciQ;;jK0|3=pZ|+EeP?c}=UeQ9; zX6DQrcF@f0;v&kd%yKOF1($7mEWi*(0g+T#GAVyeKpGcqdu`U&q8 zAzaT>akTH?GbF^@e-nW}l!I!!&H^S4s{QjjBz5K~Crs(DS`)CP9}P=Cbj)};z76m+ z*$XrLkbs*1=?OR7%RaKleWcg6QR1)$5@<=sirUKv19E%tY=8s`wcx*XL8v(j=(~J$ z3NBS--?JeMVaXH7IbC;Q-5ylJq2=BxGrObUC?AD;;~tQ0+MJdHyb3Swh4o4IIkzS8 z%646*!umEJSkNudeOF@FlZFfyAtc~hv@QQ^sY6&U&6zAzfv`&z+(~Hjk*>qim@2+L zycxTei=yX;b=G+~7Z(?_q3|=Xp?-dT!W5?G1F%zb?^Yng8;-Lju|TDEi4vj8(q1sL zz4?!Zf!Cw-a3(+MGLW#=VP4>$*Dmc};|X3~oLlP+Y8PGtG3&nQwp%Ob5E;(X0z5~8 zi!BD0dmdqF*NTMWEDpGp*L2;4bPeIu!A&W`O-a(qZ3_o&gT7^IpnaBf*eYc&4i*fT zW<5HLx+A8jNbf@jl9wiX8mqn@*jf*SQAI^X0#S6-l<_s2`d+V&yHEkGtj2!h;*CbOS(LdF=s|&H+h>YWy^r8%vtjB6uxlU8LcJuD$uO zeOp^r+<*xVmdYg;urw*}{5AxjXIe+piDG_8a2(%sem%h{$rJxyl887Grejo|XB+bi z_qjsQflFO{K}%iy%!HECPlDTSi~;q|@+e9To12?!Y9Jp`Oujoi8@9a_$t168TOZdq z!C`{zN6FCr{8*Xx_+b2>X@d!OG9}zbBCCKR3z8C{J z%0$%d+QW~3rt->v-41}M35&+z=J^0DDH@|LXB@>Ee-P#(qB4kb`Zo$eMDO;_USK(A z1xdxP>DdD zrOO@BzTMl~GUBD@2&F3M)pPaVrxnOOZt*2Z)>neLk4v(TgS8`=MJXv6vnMYfTS~>}DeXDp-OqRRu>A^7u)Aq#9+9p~h<@e1yJGB|zl% z?*dH${n)Ry{1eHWUEfq+ZB5Ja;Wql8uqX{i-dNgu{HAFBdRzUYAqk~+`PCnf;;obA z{mOedhr9>@0{4G?+F5?U{QZsGV*(LZj#787kA~hHvO$Seu|xFkg!eqG+BlY+%!BiA zs}{K{G3sGsBWOAWM;Rw`{V9u%VZ~u3U*JE(rbB4@5CodpKnchkAQFxub$Za{F5qbd zJXusoP`~}}w5-N`X6>&n!8o$ZT|Z*X6nzb-4#35*;PRvw0|1kpoDAlsoXb4J@yYZh zi2fU8tj}jb!2Ky%v$Hpi%)=Q5Zk%Wtbe@w9auWry`AyZlX&Ihm zucQg%qBiLv3@ENA_bWeyiiBW-9sT^^{G83|^e8Cp*b=nl*UYB<#>_2m?kr|@xajX$ zPe&v;CT9o7XQCc1^l~~9us#E$%{>3{^N%Cbps>HEgX^=hc%#~@RiJD8qKfmI)K^JR z6O9&s^6>WXo=9O{iD?q@K+fYi`||!)$0#Qx{%Z{Ze1Eko{5<1BezDcJh++vH*Fpu?hLMjsJ|Qwc{3)w4!90aBKMt96_?-4Kxm!K$g(c zt8OQ82qZ+n5?>xU3uvSh>m4AjA68XaLWQJr!u3*8OmE-bXyB~v^mNzc3IT;MTW#Qs zOY}aV6#QPQ(c|uUHs!l(@)zv$6@#|N;A^U94>zL3`kt~2@%qoz`;jnS z0Rb4YS=3?a`{3W$g{~F8LuGtIZ*+@->1ydZmPQV1p(el+qwv zQ;hDe=Y7+o$*#e96Vp>tV70rD2wm3K&p^M@e_Q~R+PVezYgDj>P@1s4{i!{iOHI}e z&_|Q4D(S1%Sl?C)3(0vIYwHpfAHRMi`r{A$xBH_sWmUNtm^Q&}cXWC-?jp=-$a_g8 z7g4Az-tQ`lvj~9*`q2Q_)YrcFYZNdFoWnIXr41D=G$Yr)gMfX-^a|bG%`9>#^YK3i`YeN@Ks+=-gSQ2Y8`M= z9#G0)an%b~c=3-dzEdJ=`Aj*tUgQGqNC0hPErliu3*kDvf>ylT%(kHTlPTU=3T}Ve zU|;So@p$NH2v=K*tR*a6rFb7G&JHI zg$E4QT>mbF)ZElacG*yR-q-mUDcb@d^5O8*y=bI79IN36dWgE=+HexAJJg1KH!(P< zvQ2(CcjXg!oJ66$;XqpXq!J)vMxSqxMHC(1C;QdMM50D`W zz2O3v`j2E@x((V16sNnc0&4gIY06<<-mv8Z|0~wN*mlBn+>t#!Jv?0o>6=2;Sw;DO zoPeoP(Mpsy5 zB;ond=7B;~lo?9SdtJ8>8Rg7OXD%@mo`Q0P+&iXDp3}4LC`KOi^Hf4sDSMZooagp$d|FBad5LJinoS3u=*zf zvT3e~PdAWa(|Ej^5b`qK@ohU0{`r1oTUg>ee0_K0z5R;uPP^w;x79tWP~Kjv4#kR8Eo z-Wywf)XO5ZNvBU{d(XTmH$RLp>7j98sDc5d9vPU1?g)myv1}`_}sQc9u}(Nx42gk@8c~vCS@p)G}{=eHZ5;)gq9FhAmuM@y@5Ei8a0jGl|a60Yhz}| zGw^q)sy+|<5^Z|*9<9lMMv)J4Ck@dl%c*iVt$G+v25nGSsb6I2{_B3UsA|H}Gwxjr z@*M?1lLOeLcKSNbY{5<2f|oIRmI)>u(q7UXh?f<~qoO`dmz-0b2ecX1WFC|{8Jlg* zpBbL;=zOCoFz$Z+Mo%k}KuIgz2V3ucm$&({k#rwHb##hTaWyiCO6{nbj8Cmy|M`$z zB2kthgFbIeofg9GS0G*%y&wz?Zuft06ZN&3Thk6KXd2~ITYFT&cHv1Vi8g8M?E7bh zPW1Ah3pe2QdBY9blNdC`m0BetFz=l_!>9t)r8N`~CMij*5EX=~LtEoZ*6+gG-%R-V**d1fo3cCbC-t>0Va_%+=*Lhhma2M9E2f7bH)zAxKt%D+fv6Ghk8k-nS@`5F zC3%gF7JW9hOa?9_%aD({&==iU{b?N|_dG|b*tv(&vYEuHRZa;z(yIM!pVl z)qP)VLQoy@SVzs4Lu!}Cn=Wi>zSz20F5+;SuGcHplJ=l|76Y^?oLDN17|u?SZ@q5I zuhDQ_#gf&Sw_YiJzfCHo0k^TvN&B5_wvnD1FqZ5R_)WPdm5#^BOADPTcNwAIr1%Eg zjYsHs030gVhzjUriUcOgw|>CBBVQbDE)ouB6MxlT#%*w6xzS~fY8Ei?D|^;|egHoU zO-+i_sA_5dNtx(x&1jF+kfWD_$P0I%Btvc1M{gZFDkaPTx{(_=r{KK8r$`;C7;?oA za1z#XKPOP9NZ7H^sIl?-^@%|lX<74zgLmXiapFA%#QRe_m@jchcGVq6DfLGsxT|RH z-TFLCoTi8M{{6>bgEG7lxTX; zWJ*vFO_V@Y4f3)^e;+g6wJk&!mFvB6tJ!ScO_Z(}M3D;oQ!#D!@%TosEMcSTD=Te2 z%HQEZvuN}JlZz|q>)-}!%}gUYaP3vP?w6FDJ$`c|U;RD#-GrVAK>M1N$Chj#{g;MuKq%T2i7TP!An6k7(WB^gU5RX;~v9~`L^2Quky1T-V=LCQ9`$uwKH#T zi?j~BW7K~Noz98OjOR{uEMCn_E8=-ebr8B4msy*s;7#3PTGQj$w~%??^KLcS;%*Xi zI_vJitIu)VM9kZ3(fGb+;+K~e-i}1y9rcvGGMAnYmI$9y-fo^Xb>gU{ zZ~wz>yBFj{_wUMo{{}iGQ^t352;Xz8CvwjHN?uj``gBVVR#+3+r37OiQ=UP#3)|Cu zM65zt_L^zgo>@3$X6epGo7f7xS?FUXlyI1m5$@%GMcQ*1CN z>G7m(=;S>;qHoGLP>V?i+#h`Z?(C))Y?qV8Y$0^3#O50m9Q^Q36$mbMW-SD6gX{3& z+a)#;|1R)lz`~yMF-%9K;j*$i^I@NHzP?86vGWEp{HQacIlq#XeNr5B`DGT{&hc!W zqin13#zXlj%U+VJglz73Vkwx5de@OD@mbO-eO;LYDAZkBIO_o!F*#3N-QAZaB*jf# zR4%dXsC(Rc>Zm1*trLcSu9qpC*T^S!j{dTBbd6FN*jxAMR9<2s>z+M6oPfjWwhUMZ zoUXgqmX+22KuP)E$xf4Rjt26ZK&0b-SX%bE-x}^?_<+D(F7@=H;XgU3besV^h5EkD zU%7kVlk2p+ex3K{9OU1c&k8`0?<`;&S_Djf_Uj0{B&o?Wc>7Vy#2PXYM0q}46q!^q!5HW*NkNp(j{5;I!Y(Lt}OqfITFP0_6pY{^@VZn%RIz19EB^WSoV+xz4 zlt_N1D!8Gue3!ms{3?X@2d7jmdk{Uu@a6iD9`~HOGGi3~>IkE|xbpW&*E^G=j3``v zfh(baid@S%qRI1h`WBO>Fs`u3ubh_H5g;n_97Nq_s$NVze5s3_6?INPaGH^kv1p9_ zZ92qQ5?Up~yN@vM*>m&Mfg`e*4Wn%4%u-yd$NSN>%G>dU z$|b|qUf59{()SV|P0Ra@%tv~0wXmF#sQDQlv_8_YF%k2pw4ioegG8ZXt9%INU*;Kb z^^*n9v8y8oLJPxjuMU#srRY?L6t6FKyKOQV!*RD47rX-R zjL%>DOqq3|f7TFHv>y2|pwSV~PgJa=3E{UhQ&&gPeofLEHXTV`U)jxQ350>3XWOg) zu+%pF@$g%omVW=bqePXn28CS*6tJ`zeJim0RRVTGD|Pt#s~@=1>G1*bnD(%q_rmVf z%8x(3yz_cN!u*U1nx8tyu_vP>;X@_GnzVr)HQmAL^6}?N>iXjYZp9Bi+scm_jJUNn zlG)7!OqiNK`@>uEaShSD)1kz)^{(wV(A)knCg_my0Co29-AgmF`g}H9g*Su); zB<#do?u!5PIH$azRV#_!oFKmvv7#^*HA0UENP^_DhDlHq6wQNA>W5dU;60$bANUWK|>|OS>E{=i>fk;{hvm zN`v;h)?s8$D(K$qh$wcEHHggF(2d59eSI(=sMXr*l4epDs+-~Hl1SmYCx4j=_l*Ia66 zrRhhjXG+jAnHRnu@AkO&2DGP>HoWGT0$%Z#u1yU0ESjiLZaw4w~45>)8Es(t(#U^2BAml{=80lpr!h&c%Au z896a)1o}ds?aKzTfz`^JMYo{&D8<#x3e&TdW%t`S3u+d=>d^MfU;{BTk4S4al(eXt z@v@FL+zq<=iW`rFFhqH?)tS?Q1t-UNTXDU7v_I9R>*d-*_i>DVEH623&kY7qyNMki z=UD@ny%b$n$^+J><3zmsU20}JOas1{A9;M8;I|%1o6rhcsU*3`NUSWiwx66uOA%O; zT&NAUG}(Ybztr-#dqZZ|R$m8_IuzYn8Q0f2-rVm(*RJTIt9$d)-Lo6gIQ@ULj|)=O zcN~!$w_7Ap7RdDZ8QD;?jo*KC11E@ltJ!V$@?QVu5I9d#q>P&R zHcGFlCA3_QTl@H43jOFZr#I?udf(Nuq;a2kYnv9-Oqt`|Lk*_6dP6?SvhVo@eOnc& zSo(Lb_C>TJspzCn?V2oMAo2Em53YSTJkG5}T}2PdyVqFqBl{fM5912GcJIL+{brr^ zM>yKjSmt`|A_4C|xJM}71v6I7x@@xCoA;;5pnnplF!|ygiMqnm=NhP$L!x#WVExB` zC2WwJomZ!^HR~&AW8G72(nM+Oye;2G8z8Rp6^iK9mr}H^vRJPRkE2~^6KKrDN^PRz zq88ukCoHYcMb5STdKoP-fikWb&^nzOSg*Y&1g2k5|2Qa0`%`5VsZhKB!$-%O)& zI5=q&6*7I~F{O4!_A50Hh7ITF)>f^=JhG@y+ZHuaAW3?t(Z0)zde6k;g~qYb{)!-a zpejrxR823E|6|0mL+nwK>Zgx=A)cPA8fa5;4eRtF5n909QIS(5E3=i+i~Q!^!Rd6?Yv)vON`=Nr8Yr^bP(th44;ik*=9%~I_8rhEd z1Fv!QmS(AJFk?9q0;kH`&YH^G6SEFn>IqAPvTsCk2LWA?3HP6Q*fLVu%Mi5SPV8cJloY~-8KP?#WQY*=MEaIE6u%aR`U zs~YiVMC6L^;9@$;7KUX#`^H6$yA|8f(#zXQ7um7o-9bw;YofHCsEu_48a354XeK>f zWY@dBm*f>`r?bmxZc-mimfnn;@l>m?cWh)v4f(fb(|#m<#FQECSxnG+ zfy>5n(yzKP1Czw({!iU`4r3J(JRuSUoL@cm!Gi}Ew3`?hveW>hczIPlmWxd}JN4_6 zdrR9&ycb>?q}-xT;G75PyK&$4yet3N#7#=|SmPGeymWtFG9jDpKN_)u6HzGH-%$IS zwirJ+WpKMPZJV^;4g_l77+0jPrPC&0n;(`&Ag$v zb7Osa9t|8fkUMg49C!GRH+4qwRO)gXZey@SbZYlIU-Q1{!XuCOb~l^cySCcOjjf%* z!3u&2&dIr9siAu-vBZ)4*8Qvb4Rt3Cu+!fRu&dT2AKJ~JjVLqk#uBs24?m33Pw(H} z@o{?UT#|@Pl>ZD_)SFtBN^6m#E!*lxR&idmYwy+_XC9`en5`3K^=mge0&R4TJZ2M( zDR?yc|B>~c0ZlH=`*0K$RHTR$sUjj4s(_Tx1O$<$(xf9uF9GR<=8+~+1f+KnkS@Ij zkSfwbFM)s{ozMxLynA!b^ZS2z^XVLOb7yyUc6R2PYi7*=@vf{E(75x4N`S8wH2yxu zni&c@?!3t!;Et;F-cYT7S@ZW;Z6TISY=1Jm{zQB)^|-&GUi9)ojL(7pLvIrtxEiB& z{V+!)_GH{T^_XC=r&}aidDxJ$v0+YF?6s4`X&Abn&PbCe8t!9?+*TYd`|8|e` z*3PaQ5Q?Hx4_6GUtDd@gwKJxR7*muCXaGGwXed10V3^uqFxN12#fmD-GaCzoMJCqZk#*_54$E?={4fPiv7uvGMT6B!*1<@W>ps z>T0m@Qww#_NxLPS~$+txP!_Wbh&Dm#hg+CUg1iMG0zC z&KPpn`O+T4&zHxRG|Q1wd-Hqi-oG&h&WD98ll2e%D6RmG;6g!yF6y9LOK-298i87J zY^ca`avMQeuX`CalQ*1p`0O94B5J1z-gwp2$3lJ-k^hQ)$Q+V;gIF(Ua}jyRGGUqj zqE04XJm}j1+CdTfsi;f-Ky)&t9&aEC_Os1HHhoL9;wO6&2R=S~@gMv@2YR52DRq}Z z438Gg$?N8w*S!xM@!zr~mZ(8*;Zz9`vZCapGFR_YnM^}M^N2V>JdjrMPc`CX)sXOe zskMWkE^o)!0B($2-t`EfD+J2B-?=aE|Ic8!ik9d}G%z>s3EORZr^~&PUkYoMX{V0% z5cM7|!plRh$3-`Hm&;~ovAg7Z1T5xsOJii6{=wUA8g9wG91iju()Tz~r<19KUrRp6 z3oPJTlBtr06fR-QU5#D|q&KTNqT!F@UXdr((9q-UVCzN?ykP^oS7+J0mOhg-w;*v) zN!Sc8V%hQRD+sWwJ;48#2{hRI#v@=Lt7vf2+P#i66Cacj_mgG?=Pm)AO0`{A$HXCpry9(W#f8hSS~V0rsl5EE6KX!we8-v{VnlEg&ABx_{)E2&nq6=%+YD|0v%q-Ejqu0IWrz(?9zb+Ww zdP_X=Gahsr^X;L^fMP9^k!Pc!LFdx)NWJz3Qm5+YGkblKg09BB#QMR~*joL>mDNH4 zU6k}qb|eA^iwRxO?J;oC*RoHZw%`qY`0lT>~FiL6zSKxK*^OCu$oyAh<*oIS5eS% zA3!YHF|F-nBxo@|FAIxjbtKk>&E)~5ajMo==Oj0hx8of7HF$w^5qYy!E5 z=_sQXs(XjP<7Uv~R|V-YQFkcIWnwLvn+o3p{_{A5jw+FTazcC#7ZSp|j9noy+B zeFk3)jFK@GfMB_|>+Bml=$pBj)p-DoB+4#wg1;br1M)%@5MeuoB5~{txEVM6zvBs{ zd6+=Q2N>$>84g5mk}fVt{>GIEwA*!pu8-NFNz9N&LXZMX6kH?$^H4cMAkbuycYr=^ zmghi26pets`O@YRr~SVn_CW)w{ofD=^7(Gx?RA9UinOaB@sgI^8prdv0^>xPrL#@p z!XpI05_%xaTPUHB3ouMSbQuI!y_2$tp7)#N zVgte`0Ke3z+VWlB1g>PT9YiNHdJdLW3uNirZXr+sJh8iJ|E)_%(0d0y(M#ZUDi#Em zSKxJw@*(5Imo5oZG}GOr1foFIGTM{Cd}l%9R2dnW&@tM^Aa-ZSi;KMDo)X(R_dN49 zlx4fTf4bK&1wJ1otG!)dMza3_CcKe%6hLn}lAl3z!mOa5uP;^2a&F$;7bayt$qj%u z!8j;pciY0k$VddjgCc&&9Up)!u5H$0Vf$wUq?b-Ch<|X_k-hcY z`wqHHXZ>GfFmdP)-0iyVX*{W=Cf$zdi3Q`CrJ%y!QHTWkHgFY4N8!;m@cZd)RdFT@ zZ6SHfaXG0ztzX~ld4VTssPMqM8O2`J&jD-c2i8X^qRB+$77VQx#zZ^dhSnZx3Z6L! z4MkQxZ%C>2nvvEqE&2M0fHj@EW1V90w=jOsqfP^J)6iyTN)J{j&wSJU&o}Bqb${ z8&z=)VqpT4R9p6odixFh3ESD5?VCK(3a$i<7bb)9B3M+vSn*_EnoKJtAFvCp#(hC_ zag+`@oNtJI4S0W7#bwO5IX(CPVY2W8TA331m&k;y8s8<(P)fedQ&Qp!S?Z1)$XN$H z5zs1jAAYHvNNR+^R8ML4NyZ(E@Ei(SRgvP_5~uxpX0@mE^Mz6-W1FX zRiMda$bdc((dN%>{OU*Y`U;CaH^Ux~t1l`7w{{8p-LlWNZuu;pGO8r=27TEiY zs}uIy=n_Y!?4o5@{fa_3Y}hcLL}%2mGEtVT>;P;0s{lPxf4^KPk(Q3 zx3!df@P@@wXt2WLH?(cP1l2ybvN68|4gt^wkqvfj6&=vII*(EfpJbjP0d)I+xd2qV zqdXF8JmH7Wi{T-YKAZ-OEMn$+Yx~oR^4<%6^vSE>X94^h{Ia$&nT(4T^Z+i2yUxIv<%RvTQpB>Hc*+168yGSt{R)GxE5ztQ#}a zwQ9w1Ut`s)v>tKXTfNNc`KBYXm@qktHFyv$O~Pj{q!d6_v$nIh2bu>~85Du*HHhCH zh7*d(<(^~UGlt+mgk@=(I1UOZ@7~}a0^6!WUy%jAIyV}FpZ_i%+`wo#9zt}LYo|3+ zarQ&%SouSV{fRiDz1P#N?vGARPR22oK43oJQ>?dh6BlyhlDs%GyDd4JKq-r>y^r_JGo6f&INqMH!Obsp@TWSKJlW z3Hv)fET4eGmp26Z5Hv+Vgk=3#OCj(xfTZ|K;)539C3866TSWWzZ?&s1rEocu+U}Q@ z>GPC)*Ig{OpYGnHJa~4p%I0-a{At@r7+yAL9?SKK+@Q+Q+;d}zk9f_&Nr`l#loRxF z0vI|XTe;;kR26X@zm$JYWnaEMxtUomYy?vfFAmJVuO$uSFg$V(^_vW$TST+FZtuj| z*Bz{~g<2D54VcGpU1hDaSm;T`lt1*_=-8~RY)AH7x^!t~$Au-B|HI+Y5m@4K9cS(M z`A?^>Pc3%7i-+*?WqCobUIG=;v%!ica4HiLxYOFB+UhyaZ{Nkm9y=mB9x=y#Q{^!P z{e<5h;rFMhAnggWLWD=XEvw`|8A-dN0L;;lm5aD--h$~)I|u0)W?`8Jtf!e2)Z*o- z34GRAmelFw(NWd4)r7J1f@4fDHLD*jV(K)K2`){-!s0m2oRC#Xd&OTE1ujg9-*4H` zGwl~BP=8Q(AEymt+>5ovqP#i5xyow-!Q@IVQgjNA|7l^EfeK4y=E--%$Nl*Eq1~4a z7tGKcn)yNG-VT_G{b|GS8L0^5YoENAr#1msXman;o`OPEWlrvKCy&2pa!VVW1&0A)GuW zACn;=$Cg6{lx6;BDuzq~!-VIpm}KDXm3*;v!4h^9cEi9A6+F~wh>JFbV{qL=EH)Z3p}{<>s5}0&APwF3lrH8KPJvx`QHQb z+UlRC!SOP)tHo@IAWQ>8AXk@iN1^z&I^&}nw-k~w_)LxDkdJA?qzlFtnwzo)bh^fv zYNKlho#`(l^&aSwockkdi3}{Pd2hy|Q~k(q<2RSCLAkRv$)6AMZJi-c8JVbDpQi%e zBi<#9S_UudjlTG`^Y;h57I*C2DopC=_y7600u^xJn(+BC(Rqm!=rh&4Vl(g=0>*+o zq#AT-->xdn1h2U6Dz0JRV#tTSugPWj0BnzOeZA+csF3^&QT0^`#mJT*I-|%=n?G=; zP`aW9tCeB8Djy@U0gQ<<-Br>7%tzK*sx<4u-DHcogi>${ND&8JMuIGyJWd$o0J?u) z;QaMILtq@^qd{v%<*cReeIz`6)$hOQa zMs<&ffquCXhB4x>#!*4A3ZV@sae>JTH>J@@eOE7Le@@1OB4n7TYUZoHQEUJJKc9`B z16_x(J@<@%t%WI^@zWO}@}*{;skYhBAQ?TI@s?QS^f{Q$98tRx!iVs890M|Nn!YNu zKyHrxkc%#r{r^P1wiMql<~Ip$15}EjD{$~Yh` z9HUpf%l|gZC&C1T61>USA{44}MO9D|2VD^2RM!@HUs+A)vr6-o?1w=1wX%5e-* z891ep_arPqt`e4}D1dM_%@m*p^Vk;y9oHPV5D4W3r{z$Q$y=Ee59>%=e`QBK7AZ!Ollqx17#F zZ~k=V^cEMRYC8}29sYrSz@!g|m*O8hzF0jMI*(OcA+HkkkQ-UTxl+&m8G43lI1-Pa zckq9LJmLeor>R&I0L{trENO}h3tMjsiW@Cmzkdl9_oJh%QYbb7JZaLZuS%WgLj|pZ(U-knf-dRFdz9+rLDC43_+y_NuF!>@+ zAcaJs3L#)mMy|t*3~bdW6old%%Jrb&Ms;oupRc7WjT}3y()rV=~+HRe_?3LzDWb1-DG-Q72SEB4YaH zkHdv31TZC3w2M~AXZ1qmS<@|f$!-km0zB_#u2pOjqZ`R!Xl;)=a5;;|cs0xQMmMNr zs;#&uKA`($;@SR&iRvK0vB)x1CgTCspBOQ&B;B86ERXoX0F)hV>XD5S$9}p0HhTmp zDy*%tDQC!v3t=M!#F0h|!~xodspu2h{aRU+o+y%oi#cH-s*nSb$sUS>Xp=ix9l)hA zE>V9_u8IWlNwGTqxc>trH7d$jzR+;?k|LM!BJvI( zG{CZ&z5pGVx>3@64;qz;V1G~?U!g8=w;$420*0R2w>h9|TtSSwbpB^rHse*|(82e| z{Yx>&GZW~60$_;1^oH}b!EJU1QTBKIiNl}~(Y@Rbii=q_1<6O~Q~|}v!23lai(hw@ ztb#t7p?!Rz-jq){83C6XW`FGb)CTjh!_B(ET`yih4lN9>&r!f%xR zisnqr%o*+^M}HYc<@;ZM|7IzgNdV}G1)U-iNjesevF;Z`=_BC+klFU*y~t+V_OYQya;1!>>9z?s)g##xJAk%Dz09vtp7+%WBKu=%u#(v{F*`C8k)W+O9 z5%1pD2zcEN2|yR55L~Qg_Oe~C)z2s@Fr`G{t<37j%%&bkbe4#0sNaBZ3VM->rL#hX zKM!>CvjXJ$e86vwd&T#bB}Ysmx6-T55_IJ&Zl2t6@qoa!#gDBrBo@+o>@n} zt4_M30JL+*1nl)E{Q^vi#Rr>M$|<)f0By*^&E zjRE?@bhqcr>I@|x$Cm~7YQ3;f917h^4r}yl#eZ1}&n>SUP_wFa`3(lAqQkn=6BJj> zDJD&FM%4k$9N3*=O!;4nRRa6V*fAwuT^7v*?}mo=#+?H5I%~mTgsgvY6P&XV0LIg< zyH=(ws-E=~B_5aY3^OV=2<_H!Er1zbTg~7UfrKMfTD4*c(vf+ox#c)q1bv*#i$Z{d zz|byd&RTmF)`IgfCqJ+vdLW)V@RrBnoZ`n4$&RN zst5s6HOw|0fFLhtsX#z^#-M`vrWAbN7F(|peSw7QL;V4|HjLB24dDvLvPyX^_{`B! z>|Kn(IT-IXXXhAGCjHa$3g{@P>5E!|EVh{qJDRSEo6N4dD(P2ASO0lf+Dhx|YU|)- zU^D~S#Kp%k@lbbZqnewP{NnUNy;+va!oau6!%yux8Q+~cb5*`(ppq>iNGJ<=jY69D zw%Pb7sNqSgy}C*v?JA^UfyicqoTvLE5PC0h0(_Xqpu}(Su4RJDOkpw&aGW`~XOHbX zhj*3~j{Q3%=7hB)QZQ}-NZ>PHr-I^KV*Y2<(CIT_0JzGk6twN3O-Gu^UVvnV&av6NEfbkQUCmmh?RwRiYv2(zZ*%Rea?{AH?B#Xn5EPe**|uu(FSkCxi0W!Cw+2E>@P)JpH8im5 zytBYdqv_8{LnX)5o)JJ{jhlkk@vomeA4SURF$>rkLPE&W1{3@xF;rGL@Bm!33}nt& z02FVgUPy4*2d|9`89tvDH;#gPl+B4rXrA?BJ{6TTGvvF%CeX0YO4I(^Q2}B1!|BIhI5-9mX z9FmP3)nUFlRIcLGC6&>@Nm+1bmWQ=2Xo*Zt0t0~_$n=E3?Y6IwT@?fjL719){ECOA zDo`47`Ag0q$kGJjTI4!Q1B594hnm2ou4Y=&=Wzyp?FI|u1U*3w@YrRyyKIFQ=w|~M zDZo7zgA06a&H|$Tco#XKn!W}((;q1L%ATD8Y003Xkm_L{NM3wKIf7j!?gt$10buIW z60KbUuTj)N;j?M{E@&20)gq4YTh&hkeqeFUFcw=44ck9~%4H6&mfZ*OML~^6aA`Ft zQ;_LX2Ac}2r%#N-F+oi`^fS*;Po?nrVTOmGWd3E#XZ>_+0kA#*%egr-MG3v@+6;{- zl-F+#0SNmUSPHt{^b2%v>;1xBg;d6DjSPVVnk8k>nYC2c5VY~>z|JG1X4#8d($ z&H}LlH1yI>yY_dcoTMy>i)Rp|Jnw)mfaF1psfV#gJRWZVHaSSFWs9~wSJZ!6Ysm@g z7jOhXrEY1(G8jkaSCIS+(2}B7hWzE?xEb?V$V;iL{qr>Jm9PehA`w z^f`bMMIRlYr4Hxir;2EgRfSD9PT;3(63|ZKm&8rUt87Xf(Km-K1&9FF4fIA5O z0OZ^9eh@?GU}`19Z>FPA*T5csEUJ zL@FbwnGpF7mZL9Am9ek(G~q);@;x`JbZ7>~sNmeYvGg=Jh;na(m(ZokHGw5oN<8DI!{WU8-fH0oqRT2PA(*D^ zH-$^wlj0|LJ4@sQ$zi;iXFF$3)itpOsC*sXxfZF!Ul1hK-sVE|>YQ(m!TC5* zWmPC19fS*g1Lkk~!kn|xsJ{pLu5o;dY5dJcu*Mq&=Sw)%2m^^_m8!1|Q3kH(&ovg8 zmxIYx&})Dg%OD+Cp;j_IRxnVOqWY7gJvah(>%sp)9BC)59uR$6Dz8Of6|xTJ0PIz~ z!azr7-v;vqulY#7>tPe>AO+HYpDw5A&P`W={bRsMQ=4y+RaDd)RjOD=DBZ#@C;0`4MS)c;r6?M;5*X(zIV8R-?I(GKQ6^W-8U?C2cz|8$VcUKOH@JRIT>ZZ)QRspBf*J0+` zX21sU){II&d>hzd4a6l}qHjeUy#v5UG!(-z(E3?F2gWrBT!MM! zIBAZu%B$d&W}Ee;cN9R@!oUQW3Zpw`z>rb|9N*!tgZfo*Sm>0Awbs#}a>yXp$C0h?vWan(5z7y??f$n4N&Tz63*lZ!_>BYTchZdk|2*OcQ9HHy4=YgqfxQ8L=eLR`t0_n6 z_mD{uTZaS{f1>1V(-A8ylhF-xx&X@pK1Bg-T7i=xvNnmyH*65V9jaG&3#G+0|5zq? z5S{Za1UMXZi3}zIs2nc}B?x{;6x6mzDGJaVfJ!&tH3N8A$F!M|lUg4ZJDO_gfxQ3> zztgK|Mk*Ia>h~Si0(FqjRrBs(n#g%kHW`EEHYZLadj1#Ki9O``0_sl)u(zayKBi`@ zfV9le$1|aftN*{8yHd^>Km-h=lxt9J%9XKnIB3ZW4YvXyd%WEqRc~ zqwnMUt5OA&)e!P9^nK$7m6QdE`+){%U_wDRnj<;3h`6pJ&>YJ*o+oHFh%SN#Y^R*$ zv+abYv<~L%Bu(;T9t2iS;q=b#%ynSp_%*M!`-!)`wlYpD5TM7{0{0uoX^`)~itf}I z!b;@KHBUbWj}82LkkF@)l$FwzgA_b$T#a$}1q8+2Dl0^JouB7Q25A+e1b`hnef>XK z)BXo!BV%|HsQmKLIRw>wS=mc7p>StF&L>8Y{`z`qoW+4drOKg_}An1U3xR3mR1hj!+Q7cpp{qSTfnLq(K){p_8;?u*!MnlEQ7R5 z+FSw#8(5`NML1p30Xhy{%yRG z_*N1regQr|!2rWQVB|wC( zo|*q%5kQo7M8oNxQd@RTKOd?dJ11Iebd6O#Pa~8SHpzN-)gfHi{Q^w?hZzv8luO!5 zflj@84;k7$)9ODw*4K{ujMjzjn`v(Y(xuJUa|CC2nhD@SXce4ys{A*F!sM%R!&RIs zwv+54`l{XOa3zo>QzH-t7IYp1CJyaj{L60c{0?XpBt@+Lo%I4>0eSpe{su~w(f9xL zoym3}Im4}(DcRl-FFNoQ1cl<}1J0r6^WwyMZFyd_|Bnmc#Y?(#3wm@o>(8^?8DAJh zYuD}0N1$dJRhEd0y_VtrmBaDLuXI2T6;mai*c zKpE$8g#xHsmg@gA>r#sU5nq^mmkh`6C;+a|eg{K_45*1RwMfVUx;pv(L3HqECf}G} z+hSOHL0;Y$oDbH|#f1$i$C$2VowvwJWitA0jTXM074ZQk)!F(@X89b@^V*bg!z)v~{9NQzG!frwT4^xT*z8>_s3*|$g z4;2L5fRFD-2!RBj#ugww=s%2R4jG|~hhQ}w^=-`A&r02M}rvvG49eG&vn zhYL&#A!@(w|2=j%b-RxG{GJSe&1u%uSNz!(V*ns57>l;CU)s8;{nLRNcR$W`**`Y9 zvTiDZF2bxVK&)4My$mBVP=PR3VMV}uQkf-v#6IFqq`66x-Yw0UcNMGn8bBb&Wd4hL zocc9RM|j+jmGca3r+Z$HIHFtO)4W-xhx1}1TkYfglRrd9=ExY+vIYVpK`E2XhXb+;#vGK#&uYPKS?^>~j?5mP&}DBE%m&TgF_ZU(0t zVJI~ZlXuQj^G9o#k_DskxNF>S+iuHG=1c?Re04r6UVFA!$7y@5tNnb01d`!&6%s1<~z{ zn=@Y>3*9FA>x)s`9y`kU#H#6i^;tEp+W|+FYa%Z?6vyh=^Lm6&eyIw^AmH8WgjO5- z&EuJRrqIJT!B}(~H_JH68z+vWmH5*?v<(`)>^6tn)F7HG0)G!l6IT5nsu+509iK{* zq#I0Dp1dcnT*D$Qgm=2>_1^uynavZgL7MKp@t$P@-}t`$c;DYWkEa$4JY<17ieC?l zvhBoAhBFEa)J?B)q@cdjZOI@Xi~q1}mmz-Oem}9)sCCIaNh~g8e{UtQV#>K4g)AA0 z)&KE`0f%u3eXnSE5~C&Q@PlViCjE1)EB5H5$ZL7PaLPXIY0=M_$cKi<$Ia`fr(W_t z&HXodyjRvG9WD9%&_dR0`Nz|z&zYsaPZBzWP`fehC#jO|%Qcej+vY+GDwc~cz}BwO z15CM>M;F!~D95Dw47GA-R2CW{d)Z{%ry7s_OLGIwB`$Dx8+f->FC^Rc(Fvb^_(o=+RET zhN~l-IK(9j+As}}#!AoBNc#{?)7U(!tS?pdv0#ukv<)Fbt$@;|92tKI9;ap-w^ zm4Wb2bM43!s{Dt&H{tt&Ql%Lun>rIYkFB?LF5^Tka-|J9f*2DL>yNgZdfoY@uI?lS zzAnjYy%Y@1H%&58gOpXB#lxt%aC|1JSCl<3)>VAJ@nmIrDRY5aP^>lMQ^hl=I zz6pU5yyCST%Tu$$;xkuNuXT;}%Y2H<5YO>EVJ|=g;k~_(B|KX=xwk1)cQ^}b0!0_1 zeRhLUK8M7q*mr*kaW@+9@#&Mui5yt6=QY48Ui1L$T-^#AU^uC&ipzu%9be08cJY`s zEHi%sF44rDS(;?bQVW=23h9&S!^BfZoQ(Uk`BWFIdtNM0++=F(o=yExn6oa~p!BoY zWY^7Vj%z*f(J@UM>0Y&uPxgCQ5b)QaII(|1BOFdxjiM#n8OocJU#s1POM1V>-_+7~ zbeRfR_uNjAmn$qiiUno4(f-7CC=)DuIKn~gbvh3yjheFWWYT@$Uw``kfFs#qer|-j z?u0?8GON4L+YK|0SXaHmdc!Q)^RzWDVC{5G9JxgyEm0;^q`7|BQ+Qv5cnh`XMF=a1 zZsQ5WmuqFe@FG-nhu?^mSXs^a8?ZNppN?Yr|g=;y2h_9V)R>ZezSIu~N4yt zzx?ymW<@pAC2GuGOgu^Ym_5|d9!7??QBC!h zn8DCyRApBBi)9u%z52s^#UlMjD-HGK-WFqTbwsyL07I|1=J+ygQNn(VN z6NTnjzi~(|Wfr-uUF=-wdBCLSGb@kX%VCj73jCa3hmQu0cw#xZt}X1QmjmY0p7%n8 z2T3M-?CJ4CL#KoL+n1h4D-%vO_q=xInVO+JHdpPl5vzKWjCE=|w84GF{BhELGxo3_ z)Ovk$7V>>f)#`zNhrF~lCxQCOiaIimUmvnQrbzI$vhLhdh; zZRkBT+mBoE-k%~LF-!GaJBSr4);v9|30(1Vq~(g|cUmuSU1jDr+tx~P$Iq!IoSYyg zYE18SiJW}Bsx>4uahl9Uy!95JKb~G(m`jE@IMu53d!gs;AgAw$lT8%W_| zH>J zEqh(WIEn)26Slm7vEdD?ZppmELQ;jzY5pr)i>VKi$2~PxB>vUrl5^%gWUPP5r`%_S z*2Q0tpIp^Sb;T}6(U5-0C3dl`S?H;)TrKjac)qP=xU)Y%)18=%_y6;Op@Cq?upqJ7 z!jhzp$1yzUg75Z8Og7~oY?p?@@yy?O^wF;=My#8g(}m&gI|tmPUGe(#5^g_U8Ga!n zACZpS5kJiIDqZNgLe6w=M27Y+pe>`RBQ>`ceJYs~ZrVCitzBH>)9&Ru;k};HJm7VSWU^70nXvh( z(Nv5VvUB&MWc-E>Pxy}D*eQy5*-?eXQ($R1wZX{6YZiM_KF^y6OwTtqZ%q3tyFR1X zY-Fc2$w6VD%zj6M_1~y%zJ=+C&*FZcwep%-6PNn;x^^Y&rRkhI}cMBZ};eA4@-imjhkaU)a5qJ>)IS~8E~ zn4<3wGJD(4rqoj}q}~YM3R+Ma9$LcjX|!jIDb5yH_7>vcr;H-BpvMgK<;cgwVte=nePl%e zOzq}cccvPTub<=uX?BoJz^8Ht+$hGcnxAg3d)?XZl2oCLczn|9vz19Z?;`Z0`PG!R^O0`q0rto9 zx{M<#!meV2#Fm!NVV7aAdHg|RVCq3X$CUHY%ED~^VC`(+n{%I`NZPHj%dE8d&$G-| z@Y=;56s=zrd?%ro1TRDx3QZFI}vGqk6l?xWgIW*64RNy zvawn`{QfO+(Q<7`;@!QIt)~qwzZP+#&L#0zCz$B8)rF(973VsXS{|us@u+^I<5T|q zXePOUL&Z6+nT;sc*j>@tdL)9QU?NY;oV^Y1S81n==@(-EpIob$Cf?dVp10hJtFHSJC1|WP zMHSA380#zVFVj?whD*Bd8cWUR580w{fnt4|e|~m^*cDo?<3#(5_qX2%;fLkY>UP^c z2??15OaD`~m6(`x@5;A(%K=0sZa2+dsJDI0Q@rrxuam~hk6raWRP{{<`RehJiR{?1 z{r#La+y2k&A4*%=!wSuQMrWARZql%pI z=vO-ndHrFuNODy!f5Y%F;h2`#*!}izmE@zoU2@NzA1mgB+i^;F%&+i&m>b9uqjbQV zu!t=Y0;g)}UIjh7thfKi-|%Rs*oz<_=(CQ@T-X++j7XvPIM~gRP~-hF^zm7O_uM}O zEjYuqg`@IU>k=OhCeLBHe*s{uF+)1?Tk_qpt6J4#2S2a=eCg_}-+W3G*jrJlx@X87 z*J)QHD^#s#hV65~f3SVXv&m`6y>;aH$Nz$Jt-jpzwv&u>FR%8gg`_=IW##Utj^so8 zRAEBFny$*$*3|6sAMVS|*9;RGZyfRj%-^`JqjVW-D57V`)w6GE9REu%ASj4t_HTht z(`>PQaTjXseL@(w>`chl`)bPismuup*K%Yd^2;l-O8c8tdn|QV`wubti1j1M!CFtP zn{_U0Ga=W>xhF5QmJW}PlZAiUR_rP(D({G)lkl;1+6~NeW8OUEGfGb0RZAr2jl&%TS!4+H2BvaVmItkDaEePwXkJpzBH0&?m>!#@lSc z5tXNYmHll`BUcMT8!K~~Luyq`*RO`q3p<);A9H+HAfIy!!K^Zd}`R-i0Dw*MK-*gb=%`7S4D3wqP{{X_3VH&pL4r z^;|jcUNCGnVXlmL<^J{B$&U5bYLb@^67>U3`1IcLV^C8>*`L+14+Z5WvF2AN+27r+ zqv&}QENfc3?&PI>ktLXBrPRDQeOr=w+!h&BAA|3j1h=*$Cgy}^u3c(#3$L0-tIw)c zu3sQMLW<^&WZP+r(mkX164#jd5EdV(8<7__cgmeI>t?_^Hc?)XT;4X}#G5`x^T}r* zCq0pe;8we+{#PviVQ$`p+3k`sGPAEI>He~%)=Ska;U@<#- z{E)C>o_f?Z((vy1Sk>S#_S5X;(4ZpQ@%81SeHO2isX{$|ou#c4@08D(kvFZk-;D@# zW|n^KHoIkv=%^)XRJqj)(Bkk5PhU!>qt`}8GTn^CnB(XQkjJZi&EkC_f<>V+z8h+15*hq{bYchv?c0&`-EqRm5&^#?JDS5ZO z67fv-<(GGBTMfNxSnstm;^gH*SH`hg8-Q-iyq~jquPx%m~xRUoWJY2tCq*kxe>apr2q`v&f z&x9+rW53k98#k}3%GQ-Ob(?25$8+hvFV(2JC`c2=Q(1WZa(m7&j^;+4{W~6{w!};c58m7_q7)K%);MW80zoJ61w{oRG*q>7I*!c_&HYNle*}-!|<+U&xqtW0nZx=%rSZZwAx%_?M-Ha9a zxaUyuJ1d=@hEmVFGYt}M@Fb3}GgD4;Aqw-tVfRu;VpxnRl<)q|Q|vui9BV{R`~6*7 zwBDqN=MTuFp?Q=m;D8J5Xxh!`8EqLdybD)x@u(PIHTd}rG}jzM7`*&g%5pfU<%226 ziXj(M*=yK0_t~G_Xv+}gKW<9({NuSowN4OfINA+Y@g`XNARQvuXuNlIeKs0|dg{Fm z8=l0)jJSC_MQ#}!`jyQXxS2g4;)t{A$ z3JUa(jBiogwM<)2LQWIn{-HNP3pK$g1d z!aZ@bim~VKwP;*B(su7COk+fggWj}8Mg99>WNleQjAF}d9)IQ*wLV7}X$Ed=u8^j@y+Ah`d%}sBH=?K^QYOb#D?c>}}v!_98R)yMX ze*7e6A5xN8k~`ya6YG!<0*iApR$keEdi}=wZst(DL7m3bGKpT1o1A|t&Hc3c_(j#V~)!#Tc)mOhhx?#b6ZM$feJ>UO{@)8_~mj^~#aUa@Co z1pqrTiVES%9k%KnXNL=OGry0blm7nprg&`6;@$OkBcVUnN^Z{IQ7~0> z)*Cic^ui&mK1O;iGYEB#C5AI2_C#p)05^7v))T(UD7=uUnFsCX>OF#by zw)o|gFfTIiyzaFpoL<`ph=zl?UZ3Sbmg6~wPfCfYWW&zo81L&Uv?5_!n|)Ua``w>T zQuj+$C5N2mh=0aQwIbnS6D@7uJPo?9e%<^T=8jgZhr{ahA;6taZf#$2MNQ}Cb!KkY?iEk5x@P}#$ou)A2C z`m-M*2m390UwP>jzKf3b-H{zg=y3gE&BDU8!$IdTye!9(`uy#7QcjcYOqt(T+ii^N zTw-c!wqOok>edUl%sQQ@$PU>s_DC&+2zJQz8_(8qxo_92k2f&uC2D5e<#r*|2*+B| z__4lCqa?~r>Bqe>YU=*)U+js-RqZ6d%+VhYn|_CR?ex~-F4*OIR_=fADYC!HPcP|j zYaN-;vrMQT%z5P&YC7|=ZaU}P=G9NY*Ltlzm(`^%J&7x)Uie<%NX*f;t}`Z)NWa_r zR!Oki;QccLx@DG5br*3LwCyeBp115GiNXH!9~A0yQ3WpdIXVXQ?s6zB$qMtbyj%^P zRHjBg@-NQHSa~y+p)Y6jasICBq=YVE^;cX@hk1;2)VWsdi^?}^CNdq5XbipPRyY3Y zOB$|!YgrxqT3j+fy+o;_yX5a+sP2>Er5CO^%^`!^!XuY{T*vpC+3be8a7C%m z&R{JnxK8|Tcd|zX_Z73U=`B|^Dy;UAroS?EL;7Q?c!eZPuyfb%0m_gHVSXmsT=>I#m7a_YN}8ShdSX_O z;%6Cm!^&%aM~B4AZ|9b|ouXQVl1on914}hVY8Kj#+5W$-t~?&9evOZGsZ>IdZ4@Q@ zzQ*uoNwOtnCs+1mWQno2%Q_*HcC=Kv_O=%5?57qj*X_L+ z&6PqpqBOOi>~ah}(f)UevHrMG>~nxEgq~hg?bZWn&7h>x-nfL3y-2--E?P{({&?-_ z$g|#${za!Dp$+dkN#ueU9=sSWJ_Uu#vucs)$Jjr%)Q(f=$6Q}30)G_G*+!H;kt@uf zK~^_Ps*BG#&q1q_&VJ+{QiDybe0MPB35(hot=yF649W~`Z%=xDPb`kDVeL)-P#=Mv!8sI2k2z$u57hz+E5eUWB%mgu+IZ}Wy>nb#iM6c0r>e5iYW7H(cIT^zGd z3EYc&u-g?g=PW2TzsR+g8dz9tujDNpjo?H$%6EJ3@%i}NjOk$SJRi=n6mmUYGiNO) zP#9Yp>YzK$Vb{D8nV88pQQ)}rhL?MYcKME=V2u``FfZr6JTjxSUP(6nev$)|{5Mh8 zCtj#Yo9R%Vy*6#3Tz26X9LaiLnVkFqHvCuN4!nZlSfN*~tv~ID;T-x4+QLrpGx11M zW|X*zOHZPNg05T#ItuFQ5&+$b|AsK{o1fP~Mt<^$PXX7}|HX^QvVLUmTr^O2|1Xov z^XZ*$4H0;JKpt|Ke<4ZX$9+zVh!lDZf6jxGJ^k~R`8B?~lm!tP8FB+tPegy%PFMUJ z9VSqm2#;aq`UD1JciRmY{db-d8Hyynj}9y;qH527bDNvVaugDRkG|f`t;6LYK znFOQ6?Q03xcb`0(MNQv(n$PtC*Leq8TeU}KdO;o@P_OUl_B7oy$XOR9tLbmVx&GZa z5{yFc)|ZP`+K6$?CyiDqPr^G;O?IYtl_am%l%`vn#>%Y1JEb}2<@-A#PfFCy{$*4E zkq(k9d8pf9oDNw|>nguNe@B%?M0bIAI!9QSSjR4#?AjH!58;%))G?lDB9e69#CxG@ zy+%5h{1~9~@4$#N)!V5iiBl5-@TdDiy1+%2b<4w*+rmMtL*|6;B0cS{bE7HNx6Ra5 zeYEQ1czSx;E7ArqZpbdVYrSh}E(Ls&;JYr~i}x`Hi$0?JWc#43=^Y=M$1D^~!Ztkk zCqUbY(51%rwS1>PSV4&5+|gO-TR$6SJ(ePJiNs14$^x-YR|tQg+_1OVKnWeC?1U)Z z&Y8yJmG?IWf~0cZdF^wdgC{(3in~-I2~niIru5)x>p4np!ynTHBwU<1RP7o$t<}r1 zJ;}_-4tmM#T1bc}B>=WB?HAxQmS8}werEbH4~v_S%V+ul7LC!p?Z4l|C~VIwKw$ef z4(e<}0bwejwXuNfnT6(wb0eSpaX-?$gJD+~* z76y~r0U6P)_gH8~KVS3lk=o!~6cdwX0!Ps@tNQHR5Q5Oc)12@g%kAu|bVDtFXUkSD zAg7vdD4g5Yw%KT%^|AA)-Fn4=5ym-O`^iIg=7cKsi*W)59_4lA z%gY7`%fgwP7L`yEV^hsWk)Wv_x}ef#)n6e^(ZJ>Tz0AzJt(`m`jQ-bD^VZ~}BccL} zfYKLHf_0pPDqjP6k831TFVJElyS11kwpsZ!Rqo1)wt+3byeL`iquWgGBLZ zoW()i;o^HFoKig{01wN`A~#6 zZOd7eQ&(SY-P-%Wu&AX9G_hs{_1_HG5)+`Zavt4km1SdR_o;^R#x}u#(xO2GpjIV= z5JugJpA1lf3%m$<&KI^FkXEV@D4-KHuBNY6OKnX9@G7e8T?zXBRxX-qjPnfen;_WO z-E$8PhHya}V%BSCpIkpv`XZ0AhA&1l55gHe+9zJIup~V09h7Z3trg5J-AwX40wPZNVi(7ai z$IQ%pPp4%1Q$A|GwDGd4`md5L5J+*4jg2kZT;#&ZjEoGbbx?_LF5Z{kd9}4D!AvOr z9^b_3_Py?s>h`j_`O;|I^zwC}vFZ>@OP)7VNhDGpEr>5Rlh3f==|F)b+6l2dheC#^ zTzw!l=iBYzMR+z%W7@9wZ+pu*YdJ%2kmQ&c@BfCQ&Uq_5N3c5 zMqmHf*S~XY>;rPP){;c_bc?l@MPN&fU97E7JU!=ce2wvRNHYOU*JLFIhG(IUV>Tkx zxEaoeVC`0s)%RwxZpxR@Wo0X0Sstl9Z3fE#ReD`+DTaoIN&r!Gp2$(uGsyVv=mEN8 z5|tp_yF#8{o#Vie2yR6u6z5{vZREe6!F*Z8DZ|-*Rl6Mq4N{{w>lc0NNBoIzHIt>| z4Z7yNm3QaL4GY$r0U||6&IT2jk%@^(6uo7ws!EM2*I>83F`)mrnF3gF5(Ab#t@29b8?DIwpr3f`ctAI9qF)6}0#+ zni?CQdaY7pF7ob<97mK#PB{NlAt@;-4v1exPR{L%>b=58yVuyPr~m#QpOl>3H5$Bn69{P z1*jmGV?Np*2psf!?Fw!+qI6fzy`#`ZYQf=OQR5uvX@{vnm|yjOzdSGK$1}i9kAr}t z#(Ddn(-W{0sV9Ed4gU7=raw%xBRnIi9zJRx;lo>?!wHbRpe8W?pB>;p@(5!E1jGLU zq8=dYn!MP2nD0k;_D~T2)oKLLOFqIgPO~HtnpJ>^>=<){-@L>V0p_-2d@x7khBws# zgapT!99Fc@PFig}8YBIe$E!dfg}&Xv$Cv-iNjOp%7#sVML~@40pS$0f9zsUHUe zx7g=#tBIL^jER-3T-3OHl;Wq9&~F-3NgxyZ^z-apgHYp16(qKo0( zgu+Ie;dSXJ+lJpN)~9V#ig)g4xJ}Kx&L~t-YvGs1;J}@{ZkDyF%%NweqBg6e2W3rq_N<3>}{tQu-9?i?7P17SRVb7pER^2vMm*G|eL*Pal| zTCk+sYH0k-;KB@qBImO|(`X%5G`l`3AXDW#nyo^7E}6T5J&BCc%R}%~weos^#bN8hrY)i?R?giNCHX!*3io`NR>LM{>F z2_11*y8&iG9sBD`bj9p2fKekCU*oILZc|p0o}I6PUwa^cz_ue;d?6yS?Z#e30hU_4 z9{QTDzfDEd2X$#ZoSUyvscn6`W5<)0noUYMl zKu(CIKgL!*wf&;uBS(#bulbJ2g>53avEuRC*#bnU#Q;emLX9;y@F-H>vXA3)9GGz-J69i>*7cw>$vUe`l;DwEyjFp9t zjg60mjZ8$2OhR1wq*TQS0f7ubT3kfgJ#A;s&71f%egAGE%{R(9$`g{p*qtzIW8KT8 z&k}%3MvnAYx=YSA&f2rA$@cnv>wrnasHPsmBad(-47#X%Gy6t3_PL;8Ag30N8 zbX2y|`gt$|IRT!uDtmoqbTH{RCDTTBvw`H~b8px&r)r_5NlLCX)iVQg^APR@M|M*9 zL2y@>dcd4*CksQ!zgt%yd;jAW{V!2bu06d9`i5UpQ^RL=J1i>=3$$y7F@m9!yRIa+ z#S5_+86x`4gMSvumh2yoaKO9>#Q)uN6EUF8mX%A+HTGUVHa5)jjPFE_j*db?LtE4v zy=yGWr`*qyg%N2GZ+(vEOrQSUVz{XkD)7SFd-U9PjHk*>@I5>{)-yA1DCd8^3JOAo z)%j5TyV;q`=Y=onhYYWnsN4D+Gq!cKy{dol_e@VU5WoQrbvo(@D{s1m*oBx}8)vBg zJ(ywz0~4i`nuHj@LS&29W z4em%ppBw+bPc6R6kW0`KbhQxn?_e@WajilAJ%|E5&ZLo$?EZJQyuJr7qxWH#X1a^- z>pa=-kLYSO9U;%Z|5yF@0QrL%KR5|97R_NoTE0fQdHOzX=>1!1iI$7^=kH2mL)n_T zT*bNZ&?6XQ^uZutGE`!t)2xf+U#Lwcg0Rjo@@(I^2rz()Ir3h&BI;!o{5VP*WYp4Z zhQK#voW`S;-hc7C*~tqHJ$&$IZlqVO>6Q#DFV0SgrNQ-Qz~}pm^%0a`lL>n+_TKdF zpTE~!=zqf^>prO=t1HIL|;}R5X zI5|0Syqjoj?^en~#X`vw)WI~Qxqo~o=#J63A3V)$E0~-wb7tO&8B)|uH6SFe=0h!6 zr=-4#&?gdgv!{32#J^>+i;7+4CCxn9OuSzoZpD_4B;(uW1$TM!sXWT4aLVm~SCNt=Lc`wobcA#{GVI|uNK@vy_dyn= zLf;4YWpw5x$KCbz!jGz=jO!-24Z_wIVONiK+im9MUG5y#Y4d#`#_$@P?ZB9?y;w16 z>G!W#{G8UFDgGelNz+wKC|J2VC5TYYsx%_l_$IhPMnjIJkexUU9Xz_-7Zy>$$53O~ zw6HMF&WVY6=0AeKV&C40V}s$i6SIFXCh6+*W9FT9efXOZ){L7&|C`0NjL^=$b?n`K zL3|QgQ$6-z_zh0u*@44D1k;bh!A;Oa()pIsaRl5t5kGJU{L<~Bhg6>Z7LId26>M5> zp;`!f&L?Su!ZaP76L;sZ?g4Fa8y&$)ms5s!3b0C^Pue`1wpTr+PnT1=I)*YkV-l~@^ zlaP2Hkgy;UUH5Ze^u#r&$3c!tpJ+>KPlS8#PrVhb5}3a|9Xza(P@T@a;}*Is&)V_Y zd%+i0OleRdl7M6jZ-rdEi4o~NURWXZbqz>JXSQF=5aoKZv+Op=^^9Y==7>^nSxL*g zLf}|X=)5;e8NMm4TeAeUKI@zL{rrAToOtvGcoQ#SHR~qNYO=W|nQ}z#2Z18aG>YGx zSno5LcE8aRIJ@6wY3b$4-GCYQsna4vc!hS5D9^@x_Ir^_NDKLKU#eWKjBmSJ=5N}K zo)w);&nNAr$SwY~yu8+iDJnNx<)n*hE2c)9=2?ub`45;>t+~+ksXcBzk9<7>#Kh!A ztAeKfeCY4~7P_R>?LvrC@^DklHh1H@;u+@X`yqT&rwo?_)%g3wl9kl+6P{-mw7b5# zhIzvU1$}1kPVJ(<$|3wL%!hrlyCH47${EDLSxFyvRzXy|N22urYPzq_^F_3NCTDfl zR5} zY&K>W--GEH`9u6D*{b=9pizfMP==vLR4>i?_xnyBBcmoGASaZgD6)6n@?W#w4=Q&F z|NQAZy3pOESW{BCX@tihim>Y*?fORbF8zYXm)a|2HawGqugu<9AN_7RAioNWVfhP} zW+XS$!g5x%zd!vas#-(zI;+;0Fq}fNqTwNTvs#jNe~31d`CZ==f6uFV(S%x+RygYd z#VwjH`-}mrMwQUKI36VVo;^r*xpjWDRETPXQdt$jP*#9!`ZIbdKyLQ%jNfBI$IbCP za;AD|`UT~Ky{WzjuQL`TB=93PtdC+DC(9B_+HCdDh}UX-hyzfEs;!=MiqQn|r`9{4 zHr}VO#;b%E&(qFpT5~R)#G@0XL~sJd)Pl~SE|4C7|*bl9QG;2HOq z4p@34>~l+bchxUpUFRT}KVF#Cyp&g%m6|c{i!4Wb7>--+-Om>myZh!#(G?9}P|)L( z^AXZAoW#o}AX zA?TsZVmpAM1Yi?~dj0{YI!H+LHsj%xhlB zU>YH-i=x%I1rJhbze}{ci%Bw_{(cU~HERDkm-~b9dbfjqX6^oNzq{wcLM+}(cv^}c z$9M3T5EpoS)15)TNvSt`r^F#`6SKvT_Tk+0c;b=t6u9`XU zzkyKyK$gDw5!v#pnU~=!f=vA&YmOvj|F5CmKacv1j^}HbMP~-|4$2cXLn6HT7KVjG z4{*uE`$z6NCNhMMVcN59HsT-LC(JHa<+`0oykltnR3x;T!?-yUTREP*U0sfIzeRmt z3nTL(oGA6Uq$Co=#y?LJ>6?~&KE35`s6f0V6+kQu=i^^5ER4gkE%+{ULW66Pqc8a0 zZQbx=;OMqck0iwPVB^js37QqY*+oTEJRpb8}%>D0CbaToFW*3*xu>RlwtuF<*u? z9KOFgKf|r`Wrt?eAuQ!hU-j(NyFDE}n2eRo#no-JBN_ra0mLska}EnT_o}I}Z6d?k zG}lo@ZD{5ql~C#DU8ddf;z}Mqk(cR0{`d4HgVTo0rA9`Awi-qZ*D?Ez&0vp>8cSr^ z5>s0k;yEaKj4}Ap>0NKo*O&!+Te=jhY#Au%Te{zC@iN2LVFIq%Rt39JCvx?>d#M_k zneq`+a;I?G%YI5`2R{AJf{ELAXCy^*T~xdsk3OmD-bACgR||wgy!Q~b6TiNRXOvP9 zqhr1~QxkBgcZ(&zT*dghYv6aT8pd5rv9+jslZC^*tf5!`-0IZt*ii{7g39)4ncKr@ z#qIJslav|>KSR4}&V_cOP*?Pw^OrLmuM4PHbQxqS`=D|E;7R_wi!&H$E(M1AaP=v? z*m1WT<#MOE7nOZ@v+?G%vi{XHisofq9=m`FyrPcp1p+l+ta`5@2in68bbN^kfi-+6m_yL;g} zed+L5IR4Wj@9FQVSmaK>UwbZgGUgp4`CAmfw1z>?aBY#faj-}gM-PrUdtG(imG2R= zAbe#6_aX~3;ckl45Jxs+fCA^#&ykV>v^IMGBPZ%LB51UyyB@wc4KFqmu z3;4(wxwd_b+H}I+c=wK_GSREZN-jbR{X+WBDT3K-;Q#@{S?vh zMSZ%0-&Wsq~Vb? z@hyc9PAwP=qFPhB(*rjyWgTQq7yI44;hjG%i9P=8WHsLK&`!(#+@UeKMYFZ$=?X87 zfA;V-a@piXPCr9$*}=PH>1h>6iBMUb-{oN(5h?P|b-cqs@8dH$hTGGpSn0`jl4B2| z5~8CM>V8f8=~qyXBC$=m-@QE=E+8t%=;nN$YuYJqX zL=48)*<@Q5npbJ7c#JItSH!dfsXrB*JbueRZDdQNmd5Q#CAWdn3@Zo?MrRCC+(Fw5 z!uXnXo4)R}Yv9WbI`;TA^010d{DKlO5+e2dd~8~JWR$O-eC8!To@}grNu#QcbudCI z&^q53W1)<(Za>yj9|Iv2;+pkjq^pc}x*N>+&ijyvU!Jksdu5Ni{IXjyBNcMW(W-iY z)p#4{R)2;%qCkw05N-#B(Zvy37OvWFI*2xxQm&o6^+`XUuZ@gQgTJ{YEHnPcD*?5Y z;d!Dm;&~^((G>Sf+a%<<+qhTmR;Y@L?4ho%M;BUrog`csIG#`{{62evz{iEmw|c%e zt@+egeM`14p&(`ZFwl3IRfa0x*G>_1B$EW7=oJAA+vCvhSi@$rM0d0Wp=ifJPRF1GTK(hjquyW4{;hvQOxPO&x*41B(cfEIf* zr?GT5$K4)=SRdEVhz7H7u{)=-X8S)%_1fybu8VZDW2Ct(Rv0ogF7=S1X($%xS#kP?*HJJycT}ZnjxvbTz7=R@6?DT^k8DFE(FV{6jlcHqhBPSGvl4_{Zyq zBb9o3+XTbpv@AdUfdt{l^oRmw^U3b+<46W`owj8LLL2^Gb3$|mIlkVg5#yTV_GHxz zK>@vO3-ODSk(=vc-S1|z6_MHb?sq6$X_vjehc?x2&)C`OcwJXH*7+T~T}5u2Wtskx zpRQ4DMakt4Sfs!KbnMtX0LZ~JWEmx=;g}aBXUp9N%j9a9&P5t#4wtd)bvux zj!UQ_OW3i-o%*(u)?klmSXCdbFrVIXC`r10-Kk07jB9`0IWN)UK}$sQ{2|n$#gZlV zNw8P|0cM0GobZ=l&_29V#>|s4(*SE|#Om|0_J~XA(Y(T8lj_)UXRu#eONTE5!NhUP zlY%rjUp01lxX<9%gQ{p76RUN0fu)+*{_g&r8wXw}%p=?YAG>I=)D9kdy8`7Iq54Do zusoO&CBNqUY>eU5S@FGb&JMTV+BXM5QtkBUyu6SXLwO!>DOkjUJgJ4Cyv7W%wN5R* z+x0uH_Jl*>U{6+m-?N01!zWtYU)*P@giS)iI^`WQu(FF^VBxeh8$Mte)PBOk^yM}K zmdw5n)z_WC`N%ujvKdFaiLWPWV9qOMcsbTR5kHkWdBG#N2| zk2gZNC`k*FlTK>@`H~VBS$_Hgev;^~JjVIn?{`AfcNx@_pkKu{LD>w?P*N={Ej>^5 zoM;hYb&<2NZ(OVJ?v~8l4fS~Qwzqk8Mp~O0Om#mE!=|PZdcMwZzprn=w_6LZSN3Y8 zN2L*TaXG=?WC+{O@@RGB91%2sNRy7DyOeG9g3#`jX(fyYg&vv58b}4OX);A?4Pj5>U48$4#%|J`W+o9REY8g6!12}(G=Zk zpO&eX2e$y0^NCD? zsbR(V2+Pj{)&CNf^$BWBLoT}9zzl;BISl)+gDv3=su}rV%jxY6-ad#oFbmp#gE%C+ zkcgRWaNQ1q68)<1$^^9j0#1c+BhGD#^%V(#z+P4(H>G=hCIp*GWwN=OV-tq zBQ6gNxn_F`*N|z0ys5dWP>HfIdrJJja zSf%^loBn7nNNr4G&Q>(UHYq!^TFcRn`_jcY1_Ti+IM`pKRA0yWg>Nf(@s8niyl4v9 z7$@HOjh0qNYM31t6ol|0zX-N|Dn?{O7?6#mT|V`T*EtL?BY*X(ZlRZ-5xR4?w1?Wj zrgwbQ1G{iqQ{AiC$2sW~fPTO7?fXf^X2W@7Vn=MyyfZ!6yXNMwP&mO>a*h&@nS$|k zeOaCh+@F^V6#;oqoo{x%w0493w=Vz-_nE{4?BnAn=xOn%2!1 zoC&eNZx;I*?{ktaWi;I(?9rat|K<;%7k<>aA=77jCUi-`?R(`abk#@}z5BaUcBX6B zj{ck5`T3-e=@QINP|lW@xfV0k_v%WnUWU8G_5(3BCgr{}UPCCv*3IFENz&vG!fGe~ zuSdad_MRQ#+Ts5dVzT`^DAnp7-&;GYDt&Hz8pCz2=T0iyj=CFEg(^k|JGsxEMT&T3 zhTmDIMj}jzE+?EHPBG$;VyXzW;x!&}*sL|J@ZZh$r`t6Ic?r7`ei+9_oU>6T5%$T@ ztoJ8^?`Ixc&+@yEEcm2o1=s!b*fWcduVOWli*_!7(dvC~xaptuK2@2mJY;k)FnBn} zI2ynEt?hvhzhAdP>_R`W9h^naJrB`|=Z&A6U=Fd^NaNDX&MZ`+iFm2dt|^fFwpgx> zM-G{9`;|vUfR4(i<9hn$7D?Z(yZUR}B9A+>8mI;K%bmQuO{zlpX3@v+s`xVN&DSH4Au)2Np-Kc^0{`On6dxF3`U#}Ws7Tp#5S zd0$?1nei$QWFY!jPbv3D`RJ6pQr;efK8rfh?H_OM-4S3d!WPf|n&_5rI8H6YTXT01 zFkP%^J-eL!l+a`lqu zY_{o`G@8_)zllzbAdceDJX*kj*ofq#29>347CoRb0DHZoJ@Df`qK z@61}6H~ZS@Sk!{5sp&L zLY{Q_8(-nw-CYa}j6S#WziQ4jeqx*Y^=mXJ3yU01VlU_Rahmc+D|}=|M#k*yZ2JYD z^QA*~(>k5R!0~a_cQP_`jEvOu^yniTtQba(sg;Wsf(?yHxzb8XI93xy)O2*A6%`z_ zw%oYkd>8*6*sg7vSI=Ab&z1D_6l`q3c|ixTV_-`llGAED3C}0SKp!$wvzDM`TFIK2 zKUe3bq^kN>Pj3NOT_Pb-Q5{S6i^rE8B;`}qpq(k7&ey)UxF}F%yTmi$Sv%|O>KdDz z+?_gqk}H!U&qD;7p9Amn|32ILTPrL2rrTY+(8$R4?bCrC0h$+!TwGj7^XH9ff_8(@ z{qy5LVow~-=iCO}lyC#0qOe}Se*LqcfC@a}$FnonXE-=h6&5(Q5U&iaYL+xBK^=KM zK0ftQ!$+xHHYrD5!9hVho+qyw8XA!NMJQsr;`5eV>%g$nu(HM!6fm4#{I|^+<8fTK za2r)r#H6UGXzD#3_xd}FfIz{)*~1?{e&FNdli_0+LS|rfyvI!B+E!ZbGLw$N`BEf}=0Py70{<=ebMCM$NSrCssB zz(6pX!=s}dg}Nzr&$G5S9iN7ZZ)|KV1`*mO9eF(=;%Oerl62r9;vvGa=9;PS8i)#N zlF!2_o{+Jypu0ZXO&zcJzn39)n-!6iM9K9S`i!FV13}F+a%R`m-91U4r77P_}bUccmH%g(Aj3P=tRb)6kJQTRzDKF=XzFc;!k&=^3-#67R^V)AnL?Ln4 zZ%ide|56qCt6ZI-t*z|~2%722?MX1XGgUT5;O}!hymH$)KG6G?l9Fm(vX}J|y0XS) z^5KHXKKiuxcP&7ki<7S=H^}dDdUkfFj?T^GOIv%2qgpN=9w|-D>G*jiUEL@H{PN*r zSApnGF$IMuIXO86>ZQxEd1m;?ph>Q*qSAk{`y?*??q~Id`*@K~=MpsdXK{Y&!L0I} zLnpD4uL2Lz`e7$&r)6cC=c%Qkp`q^a%kcJAr$IsPUDwb)Bq)o0jkdc02}m;C;zZE0 z4+;wU`SYi~y}kWgm|6Lh)Vp^SjEs>N7w+0jcrj7|QdFX3*x$0U{1Xyz`S|%!gQ4tf z3i)I2bahFlrg*8Ss0=GLSt6WB$)ez{r>CdywX`HXJP1C$(SJM5s=}2Td2{34)6=tV z0!I%Vvoz_BrLKTL^i-+iO?x)n)~vw=rl+R~_6sT4dtt{hv9WAxD-_}FM?rJz65{JU zFVwVK0GQ{V5YElc_6?--Z*FcTwBbiBWOS&eHY~t%z7)~5_Oq$UuZNnowzk&vW^3dUz(7h$3KMTLr(9f)OroN)azO9e zkBSQCaWU=ic2R9@fzZ%UcORiNd0G}W1;|Wfzo}7wN+r*Z>+k%0X1X>(=Z!z{uESZq zBv`?}z`(6^M8Yr}%u)woP!74PtE+YId2|&+Lkiy}zj@J`OMp(LQ`SZg3OiQ_&@HpF zvH+IC3QE)C;>08*9?>dfq{TSWPfbmMS$+sEW|1OJ5mR~>1T_#KdBT(!4&V?O1%=n= zilef!GLb_ex)b_UO;^J4sH>|A@0u9jXC4-Aa(RT0%dFcMMa(=jJ?$yIn-mohfpK(v z-1%@f*%UI<-Q8_4^g}{iQW7Ur+}z44D>v6vH{o0x>OW8#Jq z2iEWJ%{yeCYA_^}h7-EhrGp6Y@VK-(`-K(kzq4bFjEsy=LXulvevGMs+sz@jyu5rL zGXM;%OD5jGYFk_+1AtahQPC%JSvWbVj)so@>-X=JVYkU8`}gYVkH3MkWt?z%>k9&p z=GHTFu+s)I*U{*64S+K(F-oRbk|a794)^sIT8NN4J|$dyOI`Y^UwUu|y@4k3rruqC z49sjfu_F_I5PQPtbK2We#uJJ4I?l2$n3$Myyb;9s_&hjoqqJXCs52<5sg2Cd39hK+ zfY}6r%;O*fY^-2b48-vE&lV~8L7xopLHz|Y8X6s)2SRna$%kIGfQ*;d zL=(>*tiV}0Eb%xt1NCZ+1?wa#>^`Cmcuo$bx>XN`c10))aLB;;Q@1hFwZ zJPbxVyP&{&zL69+JTNVd2uu^eW-x8`t6ed?sZDdXwA|e1pJ&p?EUBM`{`vFgji29L zL_fcvVEXs(Tjphf;Ab8Phj0_C{^5)dmrr7fc zZ1SV+xL&IdUPnYkXxQe2gdiyK%@Yt2wE=8%*;XAM8JQ|K8;pOb&&wU&&bET51*2-N zY%5-@%`e-WJ?FSiWhyJ@{?Xm!$uEP5;_j&@$WFM+AdWmF!F^bD>c4Z*kDiv2_o&LO z2zJ%~)D>>}{ZX|muALu>8lTL?eqQfElaN#BL?yTp1G2iSD^H=Dr6)$^Q|1;H-+%o0 z92SOVX=PZIf4O6CV_#RhQ{=554L-QZdiCY-K$sM3JM|s2uU|h z*g~AfRMcW(k1Rv@UXBJqmnM)PD|gAc(xRddx5o=tnm-|qT&2Bb4$=t&_%D;uae3h_ z1mgWZFv`oFc92@v96xAjg%85A^7GO2$M}}YD`s}7sHs_5Sl+m~oyV_RfHZ0Hy|rqc z`2b?*^XG?vAm%A#X24tJ;yPChPPfLgb90}e1>SRKg zUEe?ebuh)(Xcv|4PXgemsj0#9_R-NH_H81~90XyKbXZ1fM%eJ?F(uwF$)+YJMoLQm zf`Wolqa<_!5)vAaZl~K5plAxM?e{6ScXY(2q`dR+;FXq^j`Pi&v&}0h`BGL^#=9^N zs!1G}1nrt5PPZbkIu3jYpj0{Eojs2%V0piO{W7|)0D-Nkr3G>fP#d%n4p3~!u^)d) zOOthT;|6gJ*fBxVA0~Dq`G>PodfW{$?QL!1MjWSUHRO|Io`-L_jIrKVZNKWzg0ZNQ zmg;WUZ5f!pZV&D9=Hp+rvb9~Wfn}^z&Dc`X(}(x<$rd%7X#!{mC1epW?=%6A*!lT+ z88pjW!ZU)PmRgr>T^xJ$Le-+`Wwd*2HWG}(fVOUN=6Cn?v~tMt@lDe)(}S6@D!?Os zW35dDN=N|I03eUKt>ur>(obL`u;^3-7Sp&b5JE*Eld% zl9HX_uPz8r+pd9@UcVy2{aYB=-=SV;d3+5oWfeHsEGOE(V`6_D-r^AnQ z0InMmR1N6ES9&$agT)r8kW<29ja&F^UTiVUxH`=l?NONNTIm2H0qLl z(x*=kdV23EWp+`K?anDcsI}h2xR{tvBb%#(e(>XXSTY!GL&N1qdPexjy$Ot2H8sgg zOH0RRvVfhkPiHxRItI}5C7^F+X0#|zNYYN@s=C=Qj9P^}Pu#eOu;P-FrM0vOp-||_ z`MKUO-2J9DqsMLc)RViVCOa=LIuN4t6a$&=_3Iz?_1@#}a3Y@A<$-W4ao$t}H03d} zzmw|_s85X=g{nKQ{2Ce>FacT{JG;!$%T;sO$4z`9qSa!*TY9%S7d&wHjg3MXo?CR! zo;@?SvoixU5b$QllZ_9cb_W^QuS9ZZ@D8M1hbOV|Iw^^gkIJ|SQ*~aIj6hjFK9$fk zMPn@`XN&DIw|yyXAGx9Koj{g82WJ;4_P=PCc+MzKJ77dTx$t%_)F__&Boe89TphPq zM@0T}^s78fQD4hJ~vv&!S2xqUc2VvpyDNVA_bbky)_M=Ognvd8(hd-CC| zK~cmEyM#uu`V@>m zx`3c7r`!!T#4Uo+N7ie}^MnaV<8yG+1P(!{-@XmavQ)PIEgu>l z^|I634LjcM?>;CzV>rkdKg!0H>R*SqCA~@;fBdQA_U5wY9YZ*GiG>SR_Yf9^*sXK? z?qV{f%}=|Q)t&io>ZH2O z$jSL4u@}H`Cie2#`8nYHK&`~b$M%uh5d*2_so;LTtoO@&PRm-OaiPtH#e7#xe3bpj4di)vbf>J ztuCEOGjo=Z4-KC8;55&cNXg&RF3r=oyVve>)OmSDm({W_`y!XCg+o%!Qb>kyw= zQBgR=;xIN1H(JB%O9LjNxV3Am;8Pwedo5^s`xRq;=yv}41%3a;;g=+(H?5!PhxHdD zWT@N6+Tn?=BTvhort7v{aZZ#?-Qf>rVl3*`hvuURDmUFQ)bWW;{_w#UG<#_8hNWd! zAKO+XR)6Hp?!PBdFt6O_(t+SNsWMo?8FaE^+}EQcpf{p0xlT6v;=vPa+w9d}YUYpq z2?$!7><3tx$fOi@SYew*d=GK+2(Rst9*KOSDjf^@`;}=F5)K%*6yTO@0U*_8)nT~ zU6ES2IJ}LiW|p3zJl^7g*Lbrz9|IYlqa9wXL?65Pox8#6i6=LmV^dRQY;BolAa;38 zO_{%czrLR=k0UA|kH+Ocr>3NsTUr9~5JqTQZLo8APZKw~CIOwe`TP(A`mLcbGD|Wl z?Yym`uI@UGUj+zHQ0t&#V&%Fxt`)G|4Vzq+vMjIyk1R4WvZAuG)M2HAAUP3`S60@; zdPo?5x;)^zAJx26-%>mU)fN@$A*kXLV}&WW;g5ja0_)w^93umR@X!k8A5*{RK&kQZ zxn1#G(|y%dSMkNKKZVn1+m9oJNRQ3H+n#?*lw9A{^(-DyTVFeJj%CSyqfbD0j;7-Y zA3oZnPGsSf{DYF;zrz5#i;ay1KEO8!B+&%)91;?OfO`Sfxq}qESNLO=?ZD4cRAl?U ztHe5m=nQ4KS7kXlCOhoTb#qiSG*LbfpxnV3$bch8DH$cZ?Iz60`E@K`ZROB?V|RD$ z&v!9rXJ=UtJ}2_$XgcYT#w$zxRi3pev&{72!(bq-f$^i%c)W56%Opj2 zSXo{MT1wr%@*~U~yZrGSv5q*~O2{#O#krXCTja)~m+$1;?Z<*7vL{o`A8Uq$hPP}K z=UU;HP{$?WNq+OBrKaVR^qj47dFH4$c=cJ^8`C7BKsWBw0FCC1o}fs&``m1EYD0i= z3Qx)Tt5dV6r~IO&#RsKQ~( z<~dun?ct+*Lr?5w)K$%!m=@q)kxo!DO|I0&h0tOXADJ(C>i17O z3>O!do!OeW-5H3U^PeIhH^+;?;oV60WSrBoB3o2Org!^H+;jD;tV=zF zR|{kVcps;#W+e@uCuBSqynpgEm|_vFQVSQp_?jpuAsMx3#+ zv9^8F(9DdCkr5?HwAoH6AdtX~u;(Efu~eXX2GoXrsk)ScLLLy9)G`V8s@u_#4fvbD z$S4OC6_Cwe8gmf9>L)0P zV2DeBTF&r;U(zWURrP=Ph~82pf2ICTG%fvIQ?Nw%kBy&}G=HWPl+1CGEtpDYQhy7R7OI7bi^NoCBI!gN*R$vwfmbz>6 zV8qRDDaxRxSqJ1qtJV}UD&_>;6c-rQ0+i+RjxKN_cN$H+evdBlI_Zlkk zZpl*>mh%*ExA_^GAs@z#Dn0i1{PpKL^yuC4r5_gbW0O(>DjVWE$PwMV1xTzI^5<`u zR2%t37{(uyKpwz0l?W}07tMXRQmdN2R*!s5EjAd-v|0l#GngT&)XE>qmVSDND<(2&8I2c?)<> zB*rnK;argkpC4oy87kZzevWd_SiGHH085;QMn=S(oY)Bn2=Kgt5F}@1br8L*e*cPN z*HJ#})amY`Q`j(t#?J40#=^p4DU>$jzQ6$q&(6cs6-CU?s4QPGJhun}^s3Vj}buBulTGn6SNJelj}PwI61U$mcif&qHJI2^EgR-Q1N_zX^)m0vBblu^b!}}~ z4GjVn6&0oF7Ed2aEelD>>k7BNtkaKaZuCu8^w{A|EB$R%jqf88cJXh0@EcV2L;<{jNd)PI0KPdW zqogzv|GEFZNx;WP6YtKO_#cC;)6)s`0snxu(0H$_xw*OKCrfANlK=#dJNT_p1I?gm zr6wH%gYkV|psK3OY%qgva9=Uvi4CpO4=%XjrZ=W2C;Z&1?9_r8CD#J9cyy2J{)~^m z{qW%_CnqP2p%mEn;=l=zlamALUcue=WFRA1pLDC4RiH9%y_{J;G^BpW#MD&2I?g~} zU%!Cr8z5qb%k97~tJh@)z=|U(mpRD2OE$D}c;BpyytPT8N#(XP1>S>E(+Du&XKd?i zQe?P1fEm2Avx6GVs96yL`Uj|;1mMm5qS`RfLIJMJ&*I{|ni`L{z4*FPKy(0SPNQUr zvCrUR_>`E{42w+cNLP8bp_P#AG4`8)foabhHM6)>{x?L#M4R|E&up&hHc_WS6~bDE zr(H}xzCsC=E?q4CPV4@i8o%M|FapJi>$!*sT6dA9rS20tE%%RAThNO1-`@_WA!U{3 ztfjQkf5wIoEe^#|yetkBe0eFqv(U(=VKHUt*5Z1H9!_5Ureh@hRT$AO?-x>vfLETl zg@aizAFtr5$sPWKpI2ihI8^#uejGwg+gnV>Y@6SLexfJbYL4G7sZ@IHRvEX^y7|<5 zLnju#?UxsomBk{WV9EaWwRCaeR1m&Bq0S@%J(YW{sH!@yzW)^nB9Z82)HS#1?nQQvKYZnNHd&^aUfn)70L1+&OR)$H@KR5(SpVVkK^k7w^56ViY5Xe zEM-E#?Plg}jufW=f$bzJrgtK-$hK3akb#`$Xnwa1=LahHMu0dx9$C4@fP7r^NrZc$O45bEkJr@=k znVv6^#7Rd-x4O0#lawT7WVE9Gq`w=B2^SBKd%W()&z~Vbeoz1gAg7`-mi=%Hc!mHm zfm((U%a;E76*`iqfJiB*nUb0c)HDMK5WrD@k$8CNEiNJ902=GvOneC8c+4b(7=;kX zdA-XAPw>Og;bn+7|b&bR6A2gEW%(0$n%n0UYl z4~SD6;Q)nY>0k*8Yxr83pC29&5a5J$v}w-+_&@q@>)?=(h>g8H)4>cuV7tYFe7Cb> zW^OonM#yCingt%Bn;(wn7)Itz3}iKh&TuW;5C zjATbWbsL@-6LYt~>P@Ut9Orw}71HjciW2i?7u9my#%wo%Dvda2^eobvCuZC+s*-6b zYCR%BN6A6piVH~SR-o>$z5Iu4O18unQ#Q6+|W0tC;jb!`{%F?-A0Z0UaOESfs5O zf*t=8-zW@b!Aa}{x-WwcQ%IE8?*`{n1#2QR-J105X}ye!w|rEXx5kI3&B{BYaGHwh zPp7{gnf!Kih|O2}`udKpQEshJiI*0Swnl1)-KaBamq3fMn|)a7rHhQ^Y2!Xsoivx* zv*wzO2akS;JVOw9MwY4Y^_|=S3U)s->Y_i&LNF{wKJRIGdl@DQk_TY0EId5!2E5(I z&py3D_@(^ryh)AM&ySKaMC*aWF>Tb!mu}-SKf;>Vvzj!31T*V~`sw9hW@PU_1-)q= zqTg+X47kuN$!Hcfw$H#Yp0wryf4~BXg2F;TVs*)hf|baeDbfyqE%Z*05*Zkayt=Irf10%2Q^cK{4s8X6kx$4F=$EaoEKY*gAe zN}hP{cvFMvA|L)1Uv2B|mX2`1ry??FcmxVTTUjs=xp)o=#^14_&O=@UYWiV`pcyFeVwg)D;8K^FDkO z+fBvAEoaB%)>yMEC}kC>XT&K=^3+Vnk9W*!VZKqqbA zt0GmKo_27w4{)peLL^GBa6rxPzd58)@75kBI~qM_M`B<=tILA>iC?30CY`HKRyOPI zfIMLk>!2T+7b35qzuMs=J3~86jbZfr(akn1F<}{o+wHjH-kbIN1f-g6YJ)QeEtOsuE%;wB_7~fSaBnP( z(%dyQ^A6@n!-_)=LKtpv?=E*_1gvYLQzwKwqP4j`%8@@sHxz!&cObXF(!WgCVe93< z0r|wfq_!-oesR+jQ{#fJR^$^Po%q7~2;6{ zc!MQ2zjwiZU;s6^IfFE{FTi&faET^{hd(!6*EK=SGJS%8pJ+b7<#T(*nI>;0-){4Z zh=jz@*H`z@y+tiv@pARDDvUdM)NTdnT6|K{PN3fcW#2WVRK21miCzJXrx|ixti!@> zFncZfEHn7;7-$1*^F7I>WE<9Ude?el=tRfLhu_&`z@A3Fefk)w=QURE=`|t2ucQ}^ zer+#mmfspW-mU&zHT$g%Zc@PK>N#*7!8(hnuya`&e`h|O6Q)luG@~Xs9KI81 zTC@J;D_OGa^5rqC%a{$HkPsS4$o)&C>c8y8B=?&&7aSBUl)cu+zwZkFgAP z#AoS#3`5f{k-S)k+>tic93Vxvt!Ex?=JpAAKl@aP=U$y)mb^*qefq1!GOT`gqgSe{-*$F9SaMt6jBpV0$X}`hsy-dI z_HIWRp;zygq*t%IpY|Mrz;kDH15eDEqmkEM1%0S$hZW=^-3CqjwBEH=y}MIABLFpb zmzj6T5HAz*;Z2T4_?4A*gXarMN=kiv@Wia%+*Gjr$m&{?P8w0NYAWVtDkTJ-s0Bqu>)ybaOJ4$uil#bqR8!e7{6SAtyUrDpD;2Y| zvok3*wU-{ofQ#PI*~!Yu`6$Ss1Of>LUEA1k5v;>@6p^miHVNtjmiU|LIG3-?UX;86 z!y&KxT@m2rJKt#hpbzyC;uH=di>gnS6^X03C2Wbs(<{jk;iKmYi zJxH41r^T!s9Px46>*v=kW!CaE*ie?F?@5t3MB6gbkgtlojqjs*V!70-4I@c2~E-ok~X{)Q#Qs7FogbhYv z+z{+uC@697-Wl@$qQj3i^YLk^T<406j0DRv_G1+5+JS(8K;Og!ZRAVs@?n%*Q7hlj zvA1Y*z`Za4X-Pv?$2Wf+K%LyZ7c+#xT<>o@0ZaTC#h}GrSX_LeO!U==fTx%QK5P(d zm^h^oMW6ieG3{Y>m${RTSXq|dOPqCm0Ac8`qQcXGQxZ1}4_u|$<0n4A!EV3j*Z|B2 z`G=LA-R8)QTLe%MSHKCGao;h{=z^M%kiaP>_9Vjmi@$pL(9fSQs3Zd7a3t;~YVqeO zZ5vPu5Z}#v-t7+3)s{#vnEC}tu!WueSi&FZ+B@5<9~bXc3pfSy^P%3N34yopz+Mmn z0jDW>8$U*~g%}Ys*o}ME|J|=|3v^yT>9{*pR$*jgVPT2twrIKl|uc}+yi3no*Ydbq@ zu4MAI1#@z8@=HnvdG#8@e~qQ25Xc^h4Y~=6ipnsjanG!m6AOuo_JK}stRJDQG)<0` zkf2#~ym#+R$Ko%GQedD2Fqh$Cg@bQPoSoGHaa34SgYy`+Hc=pIfM_fu{1I*Z4BT(4 zfN6|e(c|mX-9*~!argIsW@%{&=znS8KJAgRgF`{D1ena=ZNbN|W6yw;l$3a1pE86< zUboSM$OBlxZFiUmyb4Nc>TQs=h<-P*nk3p6oo}V!&FOG}JOy$Gho3x?n4O34$Hmxc zB;wfOVUp7ij-it|W!RyBl24}ih>s%qA+xOPg=pXdB@UHn(BSq^ZYan`@aODSO^uDa zITc5TheWKpSm9DvcW2|^j}Y_5ZKLkq*7fnx(z`}yF?_wp{r6CV6N^KS-Jf9^5KSTA z3`~T$oj0>JwJj}}2v?VZ|Ga=#V`EU_!A({C{q)bi$9D`IMjP{;4~?JaSC*Hx{5AC} zr5lO8b0v$^8yjY@kQ?VSe>4pacG6>4qJZmh3vT+9dRA6Q%9QE6UvUTO2< z*rQjE`XDGQJay})^KLd%QT(yg3awbwxA|HZ+1d!Rd(6{uFRvlWG z;4|cTSVb3+jLN%rBD#Q7o#g2`66WN5e|F!}*ciUJXaLsU+}T<6Otwx6gQ&~F;fVGV zfNsDiJ25>S`s0TUc%oE~<+ZLZ1RGmh#2iz70~3>hsVU91Bi6*hP_PJA6&~yDK3cU( z@Emo5dZRE$Pqwo%09*lNHxjhtm{Hex1^UbI%lPf)aye=@QQ(_OePbSDPWnnkWfORJ ziDIv4FhV$K!G=BhdPxQNzrsl-z_kGLrGwNO(whi!_a(^%vW++ zpWeGZFet3puT3W7;5Va4l47M>pA0enCxAe77$@_LpLsvr2|axZ=JN6$2tz|d7ddui zXf@pbrn<6hPfXxaK9z6EjPC-Qyh$;A4er$}M)m!>QTX6?MDL%V-k)K!_Tl4up%S=3 z;pQ8EeJAH7f`Ca6Y{O&G#C|yB_;yzBNa&;LO3NGcv$L~BEZ$&k=J37oJPOS%143<)_wD@Z#|LCR-9q6%1EE1larl^OVJki)|Hhw5PbA0iVKcSAxCb& z7Vi7*-KMMH#PYHsad5V32|y|n04)JEAN(G;x*%nOyRRBCw;Ho+-nxMR1tsVuGT!k>XKD>*apDz_-R@lHtF&BLM z_HAuj8w<-z;7K@9`**H(HJKO?cDWu1EP1GTey5ngYpxVvoVy1eniKHHl2^tZeq<-! zj{(bc?fI$Cl8YYS4OmWoyt?!jy#h?)<_YhPw!%lqZ-E820<48y_f6oL6=Lj_VwGVV zGR)^zaXFVdS{{tvDlPLqzrEKtFz5yugagB9GqCvdt-rrmiH}|tl(JpKt3?e|!h^}@!+ zCji+m+HD!qg)h^3d3n{f)R|2AVsvI`uLYcq3h*(46mvPos#7&&HC0=1J!|9TMFI*X z$!R&uv&6cVmT16`K02WFaf*L`0mbKfLpKrmoBKx$gliW!wPMZ3S^?0YckXyJ4_H+2 zhF&;?bphdba%u_*L1L;4h03pBXV<|(gaQI#Oy5UhSBr!@$rf=4vugS zVgJqBuYg^mT^GoF^*sBp9t0z=8@xNn_%lk%(wn%O`v(XTyr7_9zbcO^QJ%leRC(7` z2-kw(QySd2!wW?cSI*MS4UclrxVgTNaO*@cJtISBblbg!@NgZ#$xRR86EGe_D-yrw z^BD1_N=iyPaQGT<-u!JUb15^#n@?Z4Ls z(8%$vzo1Ag^rI>raXi%TZA87ReullK&`?8bE9^Mkl&ANs-44YWEK(VMZF**QcJHrW z%mCEKfNxA*D|xf%%YHGtHaGHx^~aANoB%4`C#drrfmhEjAix*9rw8U)fnzh|TtkVK zxI&4JCU>vy%a@SH(gq;=+gCyrl6j&&AtxtpafykxbX4b3ej^`qJb<}xU}8f3;soq# z*oW%w_1zNGTooxBg3!0@qmkZ`x+$4Z|;76 zaYaRRpor4r11m(ZBdT`sYiDOUCPHS1fZUhdncCnb(15Rh^hN*`$kD~+H~yr0Tzx%H zd%#~T9=#fi>Yk6^!(ZM~Maq6GU{}6l%`f5RO z@#-tKd*IRns1KwaUat5x@8qj2*$D*n3Rr$fq8}u1r zpz#SI89etsdTgR&b8>Ubh38g4&jPCW$)lztC@A>S)RdY^%-1RlZNk?g!k+-sD5TU4 zpv5n6C#1c!j=X@I7l43ed5gciwq{Z{)(fi2>gp;3MK-X};rJUk!r@@f`T9lgBJ z$@sN2d>{zUa0;(KE8W|JiIX5ySoEq(v(~@q6xoO%a4p~HhJv~%>V1p=zU8qkK!D;$ z(~`%750p3-XwCqLfPNrdMIQ|b5m3)S2LV$%J96fKmq>L6` zR)%R(Ljraapb%=j_1yl?9Ydp(UOpC4P|o!3_yE|cmnfOGTR6OksX_kVw+5QX$pUPn z5GXi1t>Wf}-UTqI|NHVg1z6xG+K`#Ne|LMuKds}ETSZ<9VN7~3#2;9p)~{ivGJ?k7bdr3Ga1tTTPlc}ObK8>(h2_t}r%r0uO$;qg73rW)>%G6dM9kR>hWrZ~-1--*GIFW^o3wcR zg^vm5yLazMPREVe^~RpjfX0nIqhe=%O6hsZ&;y5Kc29%fV?cvtvNna=7o77rMfit$ zuR`vrBWoF?)tP zX|=1&on5@}>R}c|J9Sa}>wU__&mRG*AHp|0`1J&{V%j%DgbklH*HLPMXcWMET(~h2 z4nMF)8A%@hV(@BISdsz~T^4b3&mRB!p5EO@%$yPQpNi%}46qJQq|;cwjnxyms-r#o zB#UKwD92cz1-3e)Pw{f9H`$i|Gbgpb(aBEu?>nJ3^^0AcuP%fVw!6;!-gfr6QC8|Y zjCtvQeWr#t3?#S3d(M$BiJC?{%P%dqH)dE) z^UlWCE1$eb9Rc3NNsy!)e(5?DSK`Mp**8LSJTU%MB(?b}!)PV0J9tnVFieVXZ!HSb z`(XE)F*{&1#EkTL8yhB(gXnnZ-t_^hV*Sxs^f0ZX%M{kKHZ#NR*ODDt6!lE|H$4jq z#ZJN>b&UlJ&S}GreS^3cA?ltkWu%51uq95x8SFp%sKgAX>CmVpIX`?RN zoFz$v4EcKn7Kujns%*6hO}?f8&|#aoyW<0LkEGmrlvOAGdHC6oarS7$z`#Ix6^UDt zR0#b2O9FsIM8}Z@|J|O7=2a=sX(*=x)uL9P)yzQmqUkSy>h)hSF_x>m^Eg=5g8ERB z)E1cUtEXVIEdDCN7L!jJsa z+M)Tgjn>j68-_d7_5N(=9R>kY%i5*yREvaLlC|il%ei4TahV6jc=m#@4Z1^vrTMC2 zVwQG{X)5TwW+hCoxqOWCm8x~7{s)bRO0E|FTYgXsz9d5USXp#-(v@?|@#+;7k3)1FXHe|wlrU` zdSw|*=+Y1)SHy!q{QwUq)XiD4=KgRHOzK%QK>GfYMEGO&!l?7Os)va^YRbx>K{C3h z2wl{Tw4b5idkOgr^AC<%6fwNe;rL{4WOG9Th|$mBI=p(%-)W%FF#_ExC`kzHG0XP4 z6EFJ}!?5c8 z{wz*%({2g5##3K&$6yHYL%)!t$I9Ri`nv4&jqrtPp~9JN^OBeuv|Wf&m0x$0x;=t| zdL_cviF&i)iHexzhyBKlol)Vt##=H*j6#elR>|cf{AbVy~eGZQ#Pf zLh03SU2?iuSk?OtKK5{{s@kgAA{n|NLvbuj!+O6GvLsEH=o+0#<*B)aeZ1X#5;T%# z1kJ$@fmf)igN&RjUa0VaXSJuSn$b+EPZRORa`c{`BzcPZf48u=C#0Ld*=TTAkVRVX zxyE;ak6CGYV1|^UD#i1@r#e=yS3G%y8D)o_+O8#_6#VflHUTr=OxQ?GH;`TmhkXpMsjFAF(szZ_ zbS(8$w9|R_%~5To@O_+5gkr2FrC6jz@iL_rvBVqWCeqkP`i1bXOXeq8@Sb9#mCv!^ zgtQa6@W?s+DrS(A93|!3{sg>pG*pQIp;qK(Fg+8ah@NFpI`u-duYF$pq0-u*>DTS7 zZ$1@6O%8~&u^erwbK%Cow}>MW-(RaWAv@P+gp{{9Wx#PVO)7`se(jej*& z4DHTe*FMi(FV(EX4Yy)*@){WYo-DB5B;V82!6bXG#LeW)H<69b&d+)33RL!#clX;MOOIjEbv9z;PreFMlTY{6iHMeBq7# zKq(nxF(8ToZYbZQb1&=nTY{C$oqF|?v?3-q{teNfcM&&NUZyHQ5hMQsXyFCNBkk{9TRy+;KV+$+gKh$r*(Yf?QdX_$3*QYT{08#$<{+r97; zOs`bDCe41;&teN;(AL;xO%}`9?|P0tz5;SuEbf2DdPl9eg>*P=Ldm1?l$eUU$@5k%RTM2^kgT)7$&wxEVy=bh4t!e zlu`ZOCKid%>=?2-9hX#K1Ft?X!+?yy!ceKpBA9?Yeg*{3#Ut6Jr_oB#gdJQxZ$^Af zgkiYT%ZIIS4>J0mD5=t6d=vlc1vsTK$u&506%iKZOzLbCwQi?aTvmZ04jo%oOzV!qHk#Dxu zzPQ?GxA0iMCc+aL85vY%#Gqsrm&W{tEnO$;YASq^i6bwP5#x*z>tRu&bZY&Jsa9Vs1b4mmqHYX#7%9RJvdn@2@1C?_zkZMy>Qm$@(*L1rXy}j>WZau%%VMX3yCja>pK-U?7AmT{0hMRdvammG6f#jw<56sm7Q8dI<>LL zGM{?%fh~+D88Hq$)Jwdt@)8@^?@pM9yZ_YD67L~?#-qCw?}|Iag}gD{N_BeqFYR}; zf1d0?B1CW(LH==x%vnX>MME9JOWt5lYhAk1U6AD-&=azSf`$_or4|$R?4v6JIAO-T zPQU95D`~_KKNa4%UV@Tr$hXK`pN1{#9~EXZ(g#nUJTbSjl4-ItXyLI}CNouuhU`-_ z0{eU{XsA`rY`Do59Mi;BhywlrV+0`NECEM1dlw!Cj!A%l11g8}UZ`kOmsM7U-|bi| zi@bkl`+ns}C1hT3Cbo7KNzugesUN}6w zYSf7`OmhQKA12Q^*>8FIlb~HVb;W)~Jmlm8MVHzy^e-;X21>UFL2Jiyr1%l7s#*tI zol0JJ;Ewcr^o_)>#cPre2hNdBwm3$Hb=EWE5mLA^o*K-Z2v%o=h+Q`I!F$(`7K@ku zhX+x^`3=K{HCRV}j1LxN3{F@~_d?Wwby-|l*2Ei81Y5dz!sd$jwC-Nd+q)U*s8}2u`>FZGw&E-2&c5kuf7dl#?<+0V z>*B>k>>M^WSA#6hlaqfvVOM03#M)RyC_&-KAa1m4ZS%)k9&B|FGC)S$Xs&R| z9Qw)0Ndt4z@O7&OXLHv*F?;YvH+cy9Z~dQb;fY7zx9qzTeG0NxId-QDo{<7XoK7@zg{6=7ER}BpeABD(4mr z@*#Dmcc~ZXHyW?z=5C#S_)1;371J?xBTUGmhHBL$>#ejWeRA^GjM-0H>qjJ2JI|8d zu-QyHzQ*0Uot)T^8m5*?{wZr4`K(O{4@)$;05|y+b=ImP>ru%md))|{0v}60 zynu0FVlh5*9f_VQHx8mDL+QI!3bJxy%m3U>?s`%WWtHxV8hl0X7%fGrbNVBtso^WW zuU7f~ECtBykUXj3rP$3(4PL=2gls9+o!--Fxc*5U01I(M3OZFZN71;d zj9bB&9P`5=%UZq9T*7XUUR6l5Hg@-+kK>_arr)loKAI$MgnZdP(s!@rW-0|>!LuMy z*w>AeTCUbOeLebkLJGpYyCI}NHz%Fvw&_FIERUw-AJ5s1w{3vgd#^yRJ#MJjcY?Wf z>E-7~sg^5RcDj@nk*Lc9_5&MPyuJPgk{+7QayR2Jyd+Wok$y*;; z#zNBmFQSOohW&`;36lh6pNJsF;DjV8I0EeSb=lU-Kp<8UVQRnVXSST>h43gL^Spe= zSDmXea%!H=Y{a#7DIKK=6oINOavkDgoi=x!n6&bxw2=y;PWDwz)qO>wQ!g;KBbYG4 z;`p;UgOhvf&|oD}dSM=-(;QUCIDb;!%qUtbqb0U*+hHUAnz14}JWyy~KyG{jzpo6w$J z?n^8uk`hWy?L8JzjMQ$YQ5vlzDOugIg#rH&Do>HkDL%^k+ppiex4_zYN40q#ae#Wc!k{>AQYKf>F2w7}69YXmEFJ5Fc=s*-rq;RmJ zm)HKS8m7-z`UgAMN&Va5q?Cu~OPI$d)?ld`Wwpn2oHKVA;7G1dXS%$!%7&dz*7fAKxsZ+fGmX=UA8V&Zg_MyiRFFwLeJY^KQBEBQr!5Gu<5-pzv7yP zF_qNn#Nv0e+_xi;Q2fJuUs*2ko!MztDjD8U`nj2iv%Ra44`*Ze-1@vppxb&kNmT~- zylVUJ3UQClT6&8%wymw`7SW48W*f&(&HVgG#h#5G3$mJ}XoTI}>Kp6#nO80?353e* zU?=HgwcZ)9vXOrEr(S($x*?d#9XV4?XHlo$s25x+J=4d|iJg+h)PMR~acYiZ>nhA$ zBl^yejR;=6v#iVVkDpr3@%3{(Hx|a`GAw}%sV}-$9qf?{no9~Qey7h(IDU?!&_rs4 zSHV(w^^5LSZ=|Yy+jWbpU;qkJKl;-xAx7^6ssmjiUw`^nc9=+Uc6a|cDIEPMH;f?1 zariD);+FYD3ESvv{nh>jl+w0sLElK8bFAl=y_7=%)&vJsX0+J; z(pKY%gpN(b~N!hkJh4 zy?fW4tQ<@4$zND_b`1?d(3fFYs(@6()2Tgq3ORf@ zQUq~x`VZ9xk?DoNYoypnss0(7x8aC$Z(pr^><)rsQbj(&&gjbw#HoO|)DaM8^us3j zuZ{1HVaP_h#C0iRtew8`hn(5|Ytv%Enb83r4bA3?5pE3+_rvD zi0qN5j(#|AaB?lz-w{Z(u16J1i1xtZ(7U>3eaLvUdYgAVdxxLnuI2XTnNrhCi^kk~ zF-}ZwgoUfoZmoAOx4;FXUR-es-MStQKo1^#{7$TplMYzX7gh=H)1QcaXcrDI7<<0Z zA{Y`$q3>NE@iJLYFe13kmR#Vu@5IthaBmNd+Z|eBo+Gr!dqT{INH3ywVrL@>`y=fi z3xv(vOuMe##DJiaZ+cfpE(zV3f!XPD-Z^hM{cd`0#|Zt^NO@HPa3nHO5T2H}h!2vm z;2p;iJhRl};+w&&8H{+<7daa4!}_eh8@U#qu(i}UvVYQQX08==oql}&`$-O&qz3^? z0jb#O>%TF^PVuhs9^g5y16qM|eYEyaa9 zUQYipVv~XmUBheoF zr|w6Wd~`xuylll!k|RDqg;9ZjrQ@dK(s z-Uem#2oEI|_Aa9a(|un?M;Z!kiK;VCU4o~Ih=wH_%U#2d2!O%Nzfx8mD6sQ!U2OCY zzZt&Bm94O8`zYMfTc)^(2>eFHEXr@{&eB%b2<5w{v2&nGRWdmVh@?LfiDPv}jbn4& zUiQ8&#Du%7bX^8`lXZM$b98dvhB6YQ$%}eN(V3zJ;m8ka=m)yu5ELCQWL*Yk4-V7) zTJC;uLkps2Y$wV1W872x88s&&XP<&PWcwJk!@JFE&F}X)_Ql1&;Kc`J*8|7RWoZ=@ zoWu(P$srwAJ|M^_l+Qn6RtXGAie2LF^npI(NeOZJJ1?PuCcL+Zn2y0`t%;#J~n zYXeZuA|AM3Q|8EY-ji~4ei(d#DoS8ezSgUV$!# zIP8i1G|gA&?Q6m{&0?5egWPGdg(}#0VG53&!fMaB;p7wyTTEo+YPrW(+q=X~%Vs$2)d-UBoQDW(XFThbrHd+p zsG=k5XKgq&b^U3Nr@p_sXp@XX#c12KLXa&vO1Ek7Ws7pU#Z41>3+KNuxA(>98>(NJrxrk228(XmUGAiv>D*EutLijn^|Uq2$)c% z{A^V^nypf0F zUzz3k(fWY8J#vl7ce>P#O{$#!dpw4bUA%ai?&YjaCo5OdYE@zcoXvY?#FJZ-1F<2m z!d?XIyn)R-X;u{X2iS(Do2!{y>nUlV;C@fnHzqk-iGizKB2k}q1PP)kJQ+o%q=sZb9AjwXDTpDfc7^g_Hd?JWpVxEvZ`^%BdD zO@%rQyWft%a6e$-B1(JG0_K%vX)r5?ix`q6|LD3eneNK_W($H|nh(@)BZVb=7+3uc zUlG`LkzJ!bbem^1eV0WA-E17Ms!ST*u_;{l$`)dV$>!2{3|Q6{<3;`1d}Sk|p~=9) zYMWn#{NxpMyk_&QT*Qw#b)tDvLmhBKE%iuvKLjKN-B$#EMOLQ@^%C?Q$r<$^- zo5!r3;MrKC%QhZ@vL&Oi5%?zzL0QYwJNrqf6q(3U8_Zk`D`=EQl}L7-fEZNegC-ZE zTljB$Oq%aY8&2-frk~^W?4naibd{aLJ#&9}#UI9)`v%+|%^vYjDDNmDqw+Do7FBJ8nD-e#R-TQzLgTGsT0h{Ss0$_%mzpY8 z5Q852DO%V9Dt_yLjMLvL!YZBS{`4Z9tzSaM-m3X4mc!BWztipwV#tGyUOUqGRG<}L z!Hpi@1E*J(RJ_Yo+Vda(n#xg{nbvi1zLi+VvgrQ?R;!fZ2wER+sD{_TEulv;X>Zo7XlDE*MSdu9Fp+7L1J^rXfmg-gG_Ru)w??oO+Fu|oEyXV~_A z6snsaISa9Vl5J8j?U5pyJcOg}Pe)9h2(?*AJYDn2lZ!-4LE}4~hn(E*v`stkS3%|} zQ90Fg?LHX#tH&3r7T!z9ZQ;_w#66QeJghf%donXPHe*G6EZ6QHi0TQ>MBgsS-s|S< zNRwyh^Wo@$;atsV$Tz)Ja-c;!={UDcFzd`l8H$;a%4LwECO68^VCftp9VL)`H)>Sw zNiXH~<<%z`H!a^t0~FUGfsIVXPUG_7qDVC`?NzcwXscnpol7YA_io>>wSVE3`^9%~ zsPAOaI8dGL4s0bV`ff^l#e*&bcp(qFF2`1kT8E7^7+Pl|rVpBv&ES__sj8;?I7L~2 zb1u`c3=4%7c(8)K7(3-8F!{MP6;Z#%GH>p^yZqB_Q5R(X0rC&Q=&EJnA1q+*RDYD0 zZ8}!0Pc@3?7=3y zi9VEv#)qX}^^96<}RA*mwQ~y@*rl3)+(kq{$nNcBH3R9X?Y&3Gd zT~Kjc(0L-*OYi?6Xxti?7TVD^H8ow^OSM@^pXvh@4L+g&(xgxqwu40~xv$F%fzQ~l zfHVxo)K`@Od&I zl9L;-IB(m;ZhaQ+CEnt-5J`^z`}4x#4L4h|9>;e!SKwg40*^I0wOC(LHpH8xn%Uttke?>BN15Sz~so0g}Dg!HbXg{j1%pcG11%OE#_{R zaOr1JSPv6ntZ`|?1Yc+=TWTN+qtWaDBVl1OSu@PqNr>5b7R!LndMlj=qBnXZ1O~%N zI82zR)NpMinLi`!@EQ%nYnZefmEn;DjX}9nx=#Sw`arnJ;=WzjO#^#B3hK$+x$2NCV$R&Ud16U{&?K$8@@O|3Z{ErR zprwc$lG#bE+@98*Xe4wjR_vM&hX_C_BUx*O!nk* zGmxqAtYaa&Iv7OneUWWFA}J-U@J3*61iXCQ8K}f5G4ObPjd4Wqe9S3il^7XUafiw|#(%rUnLHyWEi|ca?DdIY#v|*!yGtPXYsi|OGjq&|Og;##+tfOD5(+FmzX3KXI)R>A- zbyfJPSI(t6-_>1zvW$sm@yrEdWT!8Gz9}Bw2d2scR3d0#c>d&@ADD0G^n{oW^z8p$ zRjALh2es!ZnwxC8u^sSWdhUQ~%=TJ35zS%iTJe}12OmDn72nm!iOotZlJmsmJkC@y zkuBk{7gtaa5#eAF?=6o12EtXSZo|Js0}n6Zx+b5n-f4#qfBuBLc|)P7zv1K(&d~le zFgbYjXIOar=8j;HSqQpRiO*bD^x6p?Zy52(;2ujpx z2#c%Ku|&y=ghT3`?;EP9Qac?~!#W|+hMpg!fU~t`vnIgra9LiITSKDBq`im26wNG$ z#P*vEo(d9}K!j%VK5OD31g}f6mwMNRoD^y)<3qJz+&#A8v;qc1ChF^>N8_JS z%3HUl8)QxXYJ@f&N^ARmAHA;a@C&)D_CuF=z1sg{4z1}TRAFi_xAaZw&Lq-N7A<1S zl;VnCnff+ENGU_yf&%c26+gl1w~Tx4kp}qIS-29@bGO(k(+;jFyYSB>Fc$_S-PrGJ z{7nn(?)zUwzor)fC$L>y2&KDFvl6#hKV#X}c=4ook&Gvec?GpSEm_}}ME3R%1e-@p z@puKDd3Dfk2i8w{6!`F8oZ(%&Ar;=j@L0hSkXY$*zvnA(lL@K{F6<=TsZ}QSX`XPcps`P!1f_?$ znH6DCJ+I=n{@;*W&5=Y7cGxc|$ z9ZwOmZ+V&p780Kt3c$9|y`K^Kmo}rQdSx8@xj+UlACLqFZzdb+!=k*&?#QHUMbU(X zC%RDH&=HQIL!Sxt+*Hsx9;$9{AH`XGdV~4kejpVll>;dTi3%7+ik+R3?vrT4*R1Mm5!PwWj=JnK!&90(u8{a4yU?cBnEkO+iSyKB zzUc_diK-6ixA^p>Dj%e4&cYl`#CTj;6zl9)rM{Hrs)~>HhW}ie^A^WlEAqz2YnM(0@baR2-!09 zwZSAcO?Z2Vu~uY1xAna5=%X{s%#At)P+9WiX5dlz5?C%r^bsXuwT6P9ENLj&M0*R@ z@2EvX-uEhq5Y>H09rKFoVJoD66YUQ5x_zPEV((F(%pp(01VlIdI_7*(T=4<$4?UQbZ1NWg$M|3 zYYIXJlWh3wK8{LkxHVm42d<==@_L;=dH9`@^CIdQ+t%-*euyOr)dLkoHjp|5*qZh6 zlfE-FSoFzRG)C~gmGr}9(VqED)}~%+_aO^=#e%49ifgyJolV|Ps>R(k?YkD+Ow_hg zKNBft`5fQVN2>u-)eh(EU1FH(#GecO->F3?FXCxW|AHx4j?fr}XJjdDpv)ckXcxO3Y=!SFD)!wd|**U?t*+xnNk=b5%d z;oY#}$@OE0WPn>Ka|?C|_By9pqxKAqzp1-F#UxfMEhCkjp|h}KNpI;%h_iBblD=;E z@u-)o8*oq+{otu&(3BjyD^@bf_uh44+uax*b>KZ8?o3lnxn11XX;w;VBbA5rzTMoK6jhP+ZZCBqwR6ysHUFR5R6iCkFf<`1Efa zNbnmQL)l`S{4=B>z#NMr?tQsKtWABtIC_Q>;J55s(fSAv6luKg9;BSIt`@< zr;fcDC4;gJCp$Y0zRt;SUdb;GLW6HA=h8;BN#qA70%A(}f!?yaqs}KWNbeNwEAJHA zXc404jUCkIL-G1n+j;4>{&{Y^L zPW62eVO{yT4+9sL`z+k1rcWp2D#T7q`*(6JgFR-EEcg2c28`WOr`jLxEnk3uHI8*R zjxgr@vEY9GaQ|QD&3Fd-*eeBP(DNXddp zU;abPB7*`si!kC;-3b;ux#v_Rx-03-ZfEg`=kaP2H|;CU7M8K2Eb?XO1HOvtVtrK} zu(Gs{My0w4yR9h1BIQ-To^*Cj{6^JcTCyGPLd7L~nV%SW=H_`|02Yiq3MTYENF4O~ zAIQzuv`swxev1&)pL@H=uiO`dAE)jLRi{9j-;z>}BuPKUQzbx?n6RdNP2C>X9YyV; zxPc#LjyGbong8C(*(YDlLPkh^sjD()7A{xT&er&=DfJ4a2xGzhE5G%IE*b;(H;mcV zssBONdq%_AMs34`AW)d-Ed+*~Ql3zHoVNtoiwocIxbn+x{;gZ zHUFu_ReeK#0s0*O>Lq*NSQrI;`Oo&3U+V6!QXr6IhBvX~LLC)LV=N|*ST~h>5Esr% z&4YIXkEEA~f$CfJNTNpMLvMv8f~k^8(OF5Zu4^z?(-6@Xs+`{T~TzA z@}U1^Arlvtu1JgPnZmh5Zqtgl?3z^ts?7FkGu&1eJ23N$G>e7uclM(@`3dGUwm{FW zN5-BvkRhL!AOq@6IlqLl-gV%jfWOunHznm_tYuT@IjVN30c-N5E6qQ1I!Xk$^OR z-;*4d{u0c(N!{E9eK0U-3UEqfe69%xu;f}1@TYRTsw252=mpu1F|*>~&Vvrg-Wq$~!ye4*?8vO06TraWE&TD=m|f&o|DD*U3I{hvO^G0qRC2~=f*WUf%o zu9puo7z~~CyuO1K7#;Y`%#LWC$Ihq!PsHv(?zrM%%$S{L; zl@cpSg-Kp?q_T1cu_k@bh5O}-0%Z^8boT!)?E!0?LIr>Ql*21L#@CF6@BJDNMU!PO z6)p-X8KVFvcNE8yaIt4Q*uNhkts}Hcsn$<*Y%JUJ=N|bU<69xJO0VC@4Q0zEx)!OI zA^V0MUA3<;*2Ja``_y6ujD|DGK+cunU2(42>?m#=;R~SBmelcXnPW~znp>X#G7-dY z>MlA|4$NoXUi7Uo-FAOra$GX&JFk=Y-}`U&L9`N?(qlU$3)|IccYi%Zpd$q(0S$V$ zz-Yq57W>zCX{37w4j!3j;Xymc5iVZM;iD7MEtuQ2T0 zzThDAo)!eJL^Ua+Itz6ut5ANsO_nqqnvD$TTC+)FY5rL5p;Zg zVZCb&S|Sg%Vd_?*Nt`J*0Wa)bwhhs|Y&)ab1^bobWxAS4WQ*-Zzhk`6q*w{k()u;9 zA$*#UK(Txic)TMs6ffPnds$4x1&W7MlIOe;+g1DiIHq9d+gQ{ACTHs7?qg%C=2^z% z-o`_TI_h27OitfZ@1~J1kA&Llx}`UZ-W;Qs6w(a7d?vz6`_?M-OzheZo<_5EXAWOj z{}KSrNDzIvP(38PZfGDX!6hoe9{Mmp-y-t%MIy~Q7x^4KyqYOmK#Sm?m~Q5iuJ>z(w!nG$g! z5*9w$DRd(gFWwQ;-7YO-vA%L2U$_Z=978NQJs_kjV-~jEHaZyHMQi(%Xkf+V5Zt)8 zZb1z@IzG5Mr*>X(a6P=z_jf28L>qCM>>i6jA#1AuA479)Q<%2E7;@vlgPp1zHCXM` zA9#RME+h9Y%LeU()+uv`vQQ>f8!H=#V_?(x`ninS7#i)bVNWo}F0BkEz~fk$0T;-rid*C=tcd4b3u6c^U6s7bd#Z=fi& z=W1f>19Isy^HZ%Q1=y*!LL3?|_MZ`=1`%P9P$>EX9KsGoc_Sb#Jy2uVOLyP7fJCiz zH|f5Q@OC8BquSj7IuBmXN5m@DxW}^7amDyBK|1Meq*qSvAuk{91ZC>S^JPYA$=q-x z7#oMVO$99&X)esK^3gu`#TAYxpnv&7&GVuYTp%SLscb=sEPu5$Fzib$A{tW*=C*~e zWpJ_y+qoi~cb;PqZg_;bfke_k;Y|mjr^C)W1&BS#3$8_%vEh-^KVt7w-sp*Hb$`Rw zrifQv*)^O>u@O;AuEr2v0}TC5L&F-(nvYeMHOeZdZ6~3ZM>FLuN5CvM#14+(=hGf= z8Y!a`yJn+Cw3L5*TE#YgMN&-~uo^mZ)A8?Etu)%jqSoYL$fC#9v31U~ghwuHqIT;G zF9|lOTRR*uxDN0p0^`6lkas+ipxlIgKTG%ff;V18@DlF@7V-us$Egwa@~}kKy^QGihtq@T6h1 zR>?@7p6F+K!}xp=Euf`4_+x(}_$22UY=jpSx-`}7$hV1_Yp?zF*PI$wL+UB8h?yDo zT2Ct08qDq;KBLbgHBXU>B}T2z|Erw6-SfS!kzAvp$)h5gWcBgo=&mTKc@7wXkYfJi z+Kln)N`pp)X9F}74L{c}(;#PF6jW3ogUdweYmn6)xSFS%)GXT?#gu(lHh@cf2|kA= zI}KhD-_#H{%@8@a4VzxAlJ-%JE=3FvO!oY9$CN`lfAC?Q7mwYu{C7nn$n1ODt?D|< zN0tT%;Zj5h!NGLD3-|O3mJV2CPREWL9K1?eC#@d8>@on0=A}H@1lQk$4%o} z3IqnJq2?LQrLTYkfsdUERVfU1lZpp=v%#MeB|Q@ekTScNG*4{b4fj|;p4X?PGy=ky?Ev544yJy|mSL%f-hPGB zUgfM?t+x%W zJ`0-CnMma%kZ3f)q?f$K^8wHn%AnjAE6}pO=>aq*O*MKtCc-&pF+;`fK0GNuY=)Vn zz3<>r@QDKiBiYiP{Eh0`UsnSU))tp^0_z%w&a2X}Te2rEA34+DjU&TH#*S+zC=Z?? zcB*B$H{)Suv;c!p7eMC)GPSiWrE`%3=wLJh6HD%ox-V)hhu9m4B z&JK}s$X*c0kMX61BxbXrg$mN@Cx8inigR+Zp8#sf;ST7!GmpSW#=&YzR1VD&N$HGs z%0t6zhjH~v{F2bmM|NQ$Gyc*>s7+Uaw2!U2Wvvxx>@wD1=D(}b;iMMo=CW7=!IuQi z9tI7NNSkj@*MfrlFOG4d0wx@&?dhUZooe}y7<8v2)XF|If~FI|RTo(WFJ{Sq895I+ zG5C@ol$4BqY6Q>(dOTa-W@T%Yg#N(S$$3e#e$)SM*_x-tbxx%I!VfDt*pLwqDgv2%+C=^F2E}li3^#yKgq;uTdm`*%7TT__dwUj|TPs%v5 z3Q8ny9`6qz@8rX|U5!Dnd$nf%YMfyH?rfv-+Uo!*Cbv5Jz~8o_kTNvhcBg}!3YS-X z(~SGU5flQxz4IE*&IR{@okD*=#1#Cy^e$r2Ms0Z3%txVZJ{ysZbu*N7r!LxKHn^`%I6Yj9|2w&g@M@LHwc7%- zQBavYXGv<>Z2-ktn;U!kb3$e#IVIBzYq<(dOPmQHa}!g{Paa&sX2IaIKPI=gAlOyA zjy8vvJ04G9;{yg~kG-!FrU4zGP#AWq#b25}o*;oyGUVGgI+V$%DT4z<2OHy02pfnM zQ!#MqOiUut;QW*jYrH#dok8$sJe7~$98si4U})haopZfxoX!~-1n1|=t2Q#ludhW{ z`3@SXXIr*Ci77SCddXY5oX+FX($%j)>-vaq{dz3C=f-09~`fT<;M&KXAGyT+yH zEW%i!{(ZD@SLa3!qWtYU=KgvESZf+99mA`eid42g{P0)Fr zZcArmAyTy>&&9D-*GM$v!)tuhTB#tn_+ERNI4;_SZ8N?y7g*6PbC?7OJX8d!jj3H+ zgX!`FW8$=|Yw1zj+h~6hgo!^I`w`)Rs;{5jb^x~i*e+!G$#);ReAAPg7nh8+nF<(E zxe%x*2xom`mq$4*ZL%S*p&5LYy|T*_9-c<|^Y1oKOk%gcH}&dOqRxWH?&vnD&mq?* zMMftaZ~)oi>O;T>lmEso0R1rx>+JerMgkT_<|0DWs6kqv8JJa&S)E%=IM$i_|JKMm z{B{kzurXv7lO8h1eI9Y7D@lXjO*doH8=c8|6HVIGt6zQBN}o!MJk~HBHl>g6{x~%0 zs&F+K{eX{*^Fb^(mMry$O-#&$-hTKG(OjjWJQ z*@%;!u3QK{=^sYj$>+{CfkQJ%H}sWyib=?_gCvVEk?z44*Q*B##G=hLSHmt&ZDeZp3Gjx9ns;oyvE9Uy;?( z*t<5?mtcOlV-|K&OJA_AHW1xapq@~B@ai|M>rbQd_<`uy<-S$Vt|OOhcY`d*_@)PP zaCxxVcx^=tiLS42Mqk{GFmiYPVCwhP$t*KdL)jeeo+i)`kbrT zy%dh%RcEK0HbWFa!ldUjl+{Nks(g>Qbbg`)9aaTptLRs-6^rE!M7ilxQNe07l~K4V zk?%@0hE3a@Sr9SxKhf#>g2B?B+D!V9n(Fp#B|gOORzYIhn6ROL_nOXU!+lSj31dSu zE1m6bt{aq`yD6i)Lm3_DT$77Fl#?FrLh216z6=$d!qu}nm`L;_9HPqM)-Zs4Q+Wgq zQ!GPE&dhG3@Y@}fQf}t-Zdg2iasMrIsmCOns!@r+kPgHA(-HgLX(bGhT=6UV{@e4osL@anDloQg-yP=l%X`vFrkR5c7h+8!yPjf zdBHBuIKO}Oae=hjoD|wSR&019to8}Dmjx#{BHs397cyxujf;Z0Zg8#3u2 zzEC&*5iw&3@yyP|ZbMKzbdHVTMV(nJWS3PJ>C3Y5Ga(A|6Q3A-bv3Af7NNUo3yR8-rkc+5M)G#_-EOX?yV> zZ5v|QSzSZeEp$Lm+mPCjdqe!V1A1n5@akVODy6fT435j98lBoF@E|sEsZw8ew$-wx zsDx;#(LQM9&;`2OOP+U;M6!5I3+Z{*z*{+-#Ks4#wYIyxXZ z-kDCw_S9h)4P^F|@`nh=q-Tp)S#0}|{H*4RIPuQrqEh<46y4P~z`q(ZDRkuX{2!sF zvqgL@GW!prXZr2WpZ`IEZ0Y#Hn7_6W zbkJH&n+m?BByfADQ(?jPDla|1Eu>yPJP#svWfq5|R#~AS_T!H8GuRYgti>B%!^XIu zSAR?q1<`@g~4TrT3Rly zz8Pg3-V{~qH?|^6@o9VYZyiJ0e9eH4wdmV+9+wgH|JDL*uN|O#>(yH@Sa%2v-UyiT zx^pQWIWjWokFR(Fp+{>$Q3afFW$ttiPl--3Kr_Nif)5{(hAq>sWCdU*T{8l+%Bv~_ z7Xbk*Cyo6y3*-nvAz<9eZOHCQK-SLab|1a~y4^{Q%H-D7srYrsv-xcL zE$zNH%r(M{SNfHHt-f-zvFg4Sg?QjG2h!h{N$mPs1r$^&nfvk$h9-$&pgoijy>kSx z$1DQcXY0Mk_qFAX{q~i0;h9-kU9-)87ldc3<29=z606i7Bv zzaJQL(?x93?6J^+Z`kBjB`_DuHB@ef8niW%yfZkKIyyNaKvL8EDA!c0sT%54GR2ru zxo^i{5CEM46WxdH^Dig9E7mXraWu2!uZMNt^@wa`j-Hgs({bB zy``lMY&n3#2nSO&mDkl?_+TB*MOE5&c7NM4SU@_eG6U_zPpmu{;DO?71v*VIr05$; zfH3ffjaX{}kHgQjQ$~~=(#Zg-lNN3uE(|e<|Fn0gWJ{%a>oro*Bh!glkA>2z#0;}6 z=k$BIr<4t`wgz^2_S7yjFn)JRhh|LVkyImA`lBS)5}mb!+VC*m3rdah>83YbE@7w4 zWr!HNlt{P`n(+10AWmgjsAGb2zQxlY-FbMTyx$e1rlgerSQRbNWr*!3>*|fGZT`TW zqMx9(r>IRu8)3#^3|)HIwY^ynSsS0eHdZ6hS5F1e$W*{!{<}b-l^lh_uDsCEq%>z!Q>@IcG}TUwW-4kL*ixJFAFY=QHlI6xL!0<{@GbJ zUtA`@2ob5&8}9U9Nil`}jenu_fjYu$YGlZrGN^kyTM;(1X(DajQ!#!I*~F~ZV1%!( zMD+n_jYYZoH2!UX&aw?(Mei-Tn${>k#ndf%Ou_&nX%@$Vd`FxUKvWzrXivq^f|}!a zOKJ7g+Y?8(-_*;G5~*Plf-49dHvBf=Zmh0BVcmf${ps#$mBRK9wL<(Do0v;x<{6~yQs<>ZBDE5 zy%Wj+WwrwWp+eLxg(oM4u94^cTwhB@&$%nv1Vd;!LbiDolyh^cLzNi7;AnggWndj0 zRT2pJ-((&Q(e-h)%i{aOE35OP^hw*6c^*FZpN5pBO*RIsE7NM?jKlJj2DrDpoOlSR z@h1%*5^WmZ1CHcyD3j#sfMYanYVMskm0BF#S-b@=k}?DtEpBnyUO9y3AJ|!m-9OsMmzH2>Y&66jL1lbO7D`>kVWdKIkeL^-NoTthRh3jKo!2K-!v` zf?{K1dH7FW$mynXoNXT(wyP=4`~vVTpOH1&nTu0D1s#orIv`F72a~|FH{BlN>2CV~ zC^JJphs=G=U*O$I9uhf|B$7 z6KizBJ41>`#E8J_pb}*xS=A(l?T+o93I`G|;-zSIx=R|pHg~J1^99D;|GLK!bxY1$ zvn~X1fv@=vQ{fJw;}Ta$s)r|=T7)jYLGQ=0m3AnuhXPFzo*J40P(*e{gzTP;Or4dq zj?u;4?n!hN_gKk5uHc#taV9-Xwmgc~`o|U0f_9ZNJlV)O3TR+DicbFn3lu zc#;Lv@n&!|@k{@svI!ygHL;x$B+ii8kH8x(C8cOf@rs9to3Pz~b$$9!?aXwf2Dtc_M>AiDVe~uwZy;)TK7<(og{KyJ5 zgfJ0lX-Ompv2V0}llmQl@iDr_-re1I!>OKS5KUlzW8qFa=J!UoF~L=XG(rt_>~TDf ziw7am3k_uD1FVIh+IH4E!Ed!GfnHQ2p?7$=F6=(#YL1^GPQh zTL^W|*`m&d3qCgqi8Y9K^rmO)Nmg?$1!2x5m5xzs7@)Ca*w}ctcvoIYDcjlArAotc zs((x;q2A@rk69OCqI?E`JN#B|22exiQUvbxv(Pal%eD@7K&X54bH_`y0CPmVn7D9D z@F&Ero^SU8A^G=pG0R!TiRz18cXxF=)RES@9@G^6{>b2kr1z5*Nc!~1$rLhcQh z7FAoiT%!0~eUm*uzd93j;}xhdsvmCLu`NnDRR`u|zV71RYWYWI9C$;(omD8WG(jO= zRYyZ;b?dQhaNUuMi;u^V7hd%E^*V*e0C)|%tA)7Vf}xb~ zGG{tl^ir#~BUcRW_%b($?ORhtn>7P(WBQlZMW0_6<#7?c|DeoKEs`g=;pqEg)*SH! z?u?@M=tjkic3w|Spn|Y`v$$GsUls>P%pyFW3F1}LXw17=k`AnOM|Y{O$M^gpGQx8B>axjYk90VpFFGcsGj~aU1v~; zFFUz9l|XjqutQ|!&4y}{lrL#DHQq+>hrX`@3kNl1>FyJ@9M8(c&HW}BA?t-x4I0YM z5S)fD-RmzOz6O(tj%cy6=|3v3s$*(Q=h3*-u0XNxcg>L>aD@qWP3tK2QB!z&c!lcOfV+M9P8P8$D+(G&_ zv;esbrQE2808-F}T3n_mn300xYgOPr%nTeE8p_j$7QFp<{V+p={pk|-S+LxTua7mx z#7GE#JELNI=^KO0pKEK&<`T9|HcT*g@}0F0Mo%n{hBEf&G0J#VZu?dPnh5(H!~*}o zzENDP0xhQnW#~5=8s@vR&Ch4)W7zD@KHYfNZUBnmP6_#8V|bqr1YI{wQq7;g_BskwyVJQZg)XEPe4l(t(0c2+X;Xq796y5jgQmI+ z;W+QYFaY8BYDqX3Yy>|DSW$a1;`xAy?A%;J(1fk%HB9SMzc#6!EWJv(A0VUIDNUfbv5BVFf z4=R95>DJj!mQtrh&lTR<9YY`kv8MD)S=(@QVw=Y9aS~qi(Q-Tq`(wfBhTfN078o)f zaFPm;|F44_95DuMtQu>INlsg%fEj_=3T7*F4AuRH^ca|(qwBlPDZ&-kI6r^ZUF&(Y zN@Sh_I~_lFd<=lScwQ79cD3~6n_!MO=Q>IkR*FQ;#j02^&6oHwBpu6WX!m5pLbsFJ zvc??lj_c@iLQo6f|NcMlZw>jc*92wot&Y?`On%E$PLqrgs5trT*6?qy|9MtMbA2qY zLi*^a_e}5E(YPi9BNS^BZ-0752e4$;j_b)h5mc=m!Tw zpr;b|tw4oPyV<+n&hRQI;uXnZquvv>E_-TgOn9Z))uSfY~CUeA-kWd-aiL| zg>SuK_VUVu!M+=;B9Q)L!>(`d;<}^2q}pML3P(a!{Bn`mVd+#)>8f|KVH-H&XY8MY zi2qq~@c&}i>*LJn>N%&*k~*eXwIw1DmkU!Bi#M0YvE1F(Wgvz-9}m6ZrKO95pcDNQ zawU(R+{j{0E}+>HV9A8ETwk8KMdmLJ;r)^>=&#=b80+H8e*sV6%oe?J}5bdIg_ z+bU$Okv7Yaxey)EPFqOrGYQ5wym?AH{fjVD*wguP^2BL>whi;=H^1rlfq_^I-05hQ ziUj0o`A+YuK6I*5EcUQypxJ=7M1V?2&JokPYyZ#|j57}3HLo+rbrrrkkEPI77ev05 z>%&o!y$5vntl}P*xrWBoUlG+QIh)0^dVpzY-5P0*fHS40Juec{K5RQvvfT)*+>weY z&Pj@{@xJE~-+PioGQ2||(oaiH+_3ms);4YbP`-OXg=0W>ba5cHcW?bLQYgUUK{8Fn zyvH{}W2KrejMj8^PhYy!yzv>THONL|wTV4A8QFhrqE5pl=BMy)`glNv_Z{eLp29HY zNa|hryBD@bz}+!R^mzW9#Suq7xBw*h#tV%vW=6a1Ni@`rl{mh#QHNk+n50?S#-)$v zSA8oMwg)W|=Mtk9yXftp6&b?Fw|WxYhS*VC@tAIN)XA6tU|w1h_3s{pflEs}1mmVu z$r3_Yd9dI#ATAyYRXCBAoF+1hsk@xv&|h?~h0QR|0$$~l&BPW$%xsqd$U5)6A*c@8 zlkUMxT&uDBBbeaN?>}PF_f_zPbv2h}?9!Yr`dQiwr8%__F7$`I2&L%XK$L&v!vx@u zZWR%fACK5qRbCZyDiS}NdizYssdi07l}4UzZCy$kop(KZNyo8iIHiMq1}wI&2_B?( zUx%SKMe%2qL~P@rF|U}A=LYT$L@p>Y*YED;HwG>qVAFqs@OMl;h}j*c8>pM1 zVOLY-bMhY;!lVN6$Nvte_wk$78HRo{4zCKP8qz22m+E@*I>Do=Zp=E&vYSX-9JmG$ zLs*T#Dm|rqt-Zh(7hM}l)&MRBl4wQV)9vXQ1eBkCXU;QVr|=tr{tst%m^! zg6j>pT1auC=VAaIB>KF<5eJ@`0^clU^11{|e^*oI%?c!)dtQ6#0R)V@P2W0RT)@q4 zlBM%Do(%D31f@M9>@oWPmj-B$ly@VW8TPdJ@kL6xW}2f4dj-HrWscEoiB+lA(TuL$ zWDR}=d5A7j0i`|%5&D^sJZUUzyRfQjMCALWYfiFy>Bj$UhRn>nN_Kpozw8Mk>+zN z3C_82p?J!3EG`jgH+g-8@-SnmlobG1 zqJV4A(oz`MbQ7;cC8_*)v%^(|iCByGSfXd03{`-d*oxXNn4j_DqtXN?GC4LnkxwPr(t0yW=8fjFj5QJ~MHTMtT&*N0MX#`7Hi2>Cia{LAoB-Ory*M8KNji9$Ip>8~$1@YhoSHJ?+lgq&|G?CbID1vync`e)nnATVE2Zn^YX#t**O`o)t(F4+4IfJQxF zAY%%qt~uFEWOE}+OS#epNg5~~{+kMi6!Nk2QPe+?o1L(&y%6|4XW-npgT_{_3ZOus z8qA+1Q#p-v6(u2JgyqJAS^t%{zcUq-o=_+xIIh<$nLcLB-$~7wO{2KVaZZ*|E}*F_F}h)rA1Ovp+H&+YDhjsfWL)+*As2(pt^S$R3#}q^pEC3|j0DFOQM?2YFRZMOg z7AFz^d|xVQiz9#7=Hu*~1b)V*e#b~?=W%ksh*eZ94Fp77g?h3Rz&DhF>G>tBMY~fNQF(?2S-j;C<;7Av&G>{<#S}%W* z1G|6aa=N#WgQ++Iz*2CJe!=q7hp}8#L<)`sueyljHgoRU0fP+>b{Q;mw^n;GyH!h} zwoCB$bNv)Wf)vC_wgTW76@zc?78x^uqh`c*plCd1ORKWp;lKk-Wu;dcDDC>bKxD{v zFm!7%BAy{1Xftj!%=-Ddei6KeeH~rPQqoRo zD!k9Osn4Hg@X*eC)tim&HCq*tSng;cP()5nMngk`Q%(XLrQuO`{cJ2yMG*+H4~1PW za!X>D!-*un+?`QEdz9a>KyR&d^cOxDfVGPQd*Ujli+%fEX#PQx)d5;1I;vbk@e%ER zChm7dYCJZ^_|13*;qaMX%NcGl49laa&w1zyWoi7DPt1#NbQWg)UlqgS^De&`KnhS9 z&B`WURz;jusP>id6)7AF6ykJ~;_)8^$0RW&E-YkY1)VPV{7$Z<=V9y=6cpXx7~O&| z1Oj3v>qBNP4JCj37-eHu!>rj%V-UOrkgU@yHih&82Oek-f7Ik(w&iE*50qItp`Jjk zk#={GZ(_lUP=h7az>qrzny%oeF=Rb;cB#3jMqcc+=F7SF=fX2&mX(cdGanGK`p5B4 z>8;iL7rCzXdEhM!x_E@L!Gsw7K9Z7y8~wh0Yl_|uhQMTq*tUF{zZl5cHTu0pmN2!& z-sA$ap<*F{UmyI^Pt#5d`E#Wm^(>AvV3lRTQC1?NJ&q`yU^Dg*;d{lV(Q-)Ca&!FT zYsd9rmSj}x#ppFZ*^k}DmAPxtCNCjlp8Hbn^Hwb}tv6GwLw`|wz9v`fSt%!LzsMJg zZxRKTq90L;w;l#AnD`xX>rOrZR;d25;tp_Y{BkBXuTcP&ekQ@tn%a$!fZ+4!+J2FM z|2=-R~+jlw2p; zUR|rpD8e3xS-1Te9S80g5Qtp%l=c0G?nssZz`{6hPCT8vAq}}ad!tz6P&CPCB;*mS zkjAA)0$*sKY@niInIp6|Up)$pthnySr~O+iacXkI8?gGbR_|n@+G`KJwzn{CwFk}( zAd!a0fseEvmW(V+leYxVT^}pc{&ki)J`-3xd(l`G@LTB&Dam+sZL)~oot2-w^L0#h z&*W;kc(3i$Htr$8XIozL)oGii+hC+<>D~R0+Wih4lqRQaIe~68$Q4p5$DDTb+?lZ7 zTBvl%3k3+acMHA%FjB}Hg?6@{RyflJ2_52HqD^k@Ctg>WwD;}T#q%`8>JAdn*)O%LMo-jc2%_wEi0 z*kEF8gqmMiT@zkzTX9rcdVzlS;9A0RIvD2sDCXpJL$>8KSMOi9>)!Y>zMQFtZ~kqY za+OQG+2-^BrCl?&UOO6he8rKc>pIrFB)wd(CI_Q8c{i(3PMgDyOQXh8;U8s>fdp4f zX(=d3ANp`FRqOtukIOICC~M0MHD7H2PXTEGNxzwqinDr14?k^074JH5r{5|`Ho%q^ zyJKP3#%AYdFMa-J-x7>iHw7Zl>+`loo3%M4F2ZH+B(ATO-{%;{`uWgyh7uj1nLEeH zcY|!jv<&p*Uoha>D${QI$Xt*IGRsv-lhcaw>QGUM$%d^3`Vfk(1W?|L+P!Q0edl;* zCgkWf-lPk~%EWygN4c=ko6wo5%gEN~xj;Mm9}Uc-0cUG_l#PU@I+jABnLSfK@J|2D zp~Kn(Zv^&DG(Kd*aSBhwnu5dsHgZkkxWc0J{U2~@r0rL65>{F4@-LeN5?Z)ZdhF7N znIoNcI)$T-5SVlPrlTDy+2f5PE}2u><5i7CFMKTmmacq4g4Ao$gr-QF@itQrTJT?~ z)nb~@%=Dd`Oo>aq*DVo$O)e58ruVtJNa_Nvc}@qcIP*jY(p!WRF`H0{e}yJJKHKnp zgSjS>9eyB%rh3P~+0^WLN%6X=A1U0BpKx3R@KC6fZAQSaK&h&woqc?a7?<1Y(ThF{Nn>lsCb5^;X$DY@B zbXiWRWE*+NU61d!TnpTQdIxRn&o2e$(`4m>du5MVuNVJm_c{o^Q5_q45 z*{H1)FVW0VC%E1T*D*kloRS0PcW5%78z3AWod0O~0KFf6v)|fD*(qIRrPw`2HfK>x zMYdQSDgFpN+jSCnBEDZtQ`WbA{os17LMAp|Q!X@nu0HPFLV!3Ag?70FzJYTke+3!u zf8N5?T;H8{A8P527kOV*eFQKoZbOA}kx$hhL28^TloW3-Ig`n+yZZ1e%3Qb2A+`EO z9&>>34=oc@H^6{Hej_Rcrg4DseCu!20nIk!%@XnV>h^On3iyIB#%=@MGQl_V14&@S@z3EYu^MUvRLKb* z?00&1WCe5gcCTD0DZ4?X#pCd4Bwrs-kkrBBmdi=bw7CF#(FkhOZdk_8!dcK~murI$ znys$Np=7Wr`rAqaNaNhgpOI)ykfhf3&EVsDhti7UjL$v zepBI%@3sUd6LaL1cjSy-Q(Yq$2rD^?3%p-iSbiS%2nZ^IU?PU;@U_I|&rB{!WduyV znZ#E$;STlQ+~81XYb~4FJtvl~JlMuK(;U+wzN!OWzd=8{&Pt3N{_WlSR(n0@v`Vg-iS)*xFZZlHPFx+)-Qvbo zd4(QiyG?SToViThK!-qEe1~O8$>LTOg;Y6Sw zDp|j?=a|nl)S^4{wxaiL@S>v5i$7GZpyQ$o6v_jr0_%txAZu&-0>o${>&9Mw74-Z^ z-7wb#{;}62@Ch+0ice;`~_w1+hr}vbT$rTHIe0V`2ml>04WhKS3Z6_v@A(?uK zlaYZ`iE%N$f@ZWq_wdgq!F^AYxfl-9c{1A8@7LLzME?7m$K+^yey z1vID7Xg>pqibo{<#l!^8 zvT(K6%FVUt<;JI2mbXjKMzRdr-X)TlkEUHe4Okhc{w|z+T4-`5m7oJ!>dExF!W^EW zeO>$7yD)^Rdt>Hr5BP$5sGE)lY-BEyFH$XGbmLxYE8uitoHnJ6%@0HLjg>y*R(mNo zHsp|p@AR5=@L8{i-7zgf_)Bdn%jB2vQ_euuUb!1hmW5FA;{9kVl<6T&z`dKb-a$c^ zGSOQK2cE^JD^tnIR*f4 zZF=Dechv6i5vjCx+H;mKJ;aQRrf3?kQaN1+-K36*8JB};mQPLnGX)Fry74>tj$+2| z5&*%&8Gn@Z-2ly2XUdAp>)m;|Rv#kxYmQ$ZDT@q>_cjBsnJ%w+#M3HPMF$YR@PsXS z0-t^QgupfI=~Zh3E)!@|cOP}L;|cJ)X0=WJCHjhCCHPA8qhhAbuW`+%Iu0CoN$PhI zYL{M7EL6iy=-)zQF+Yp$9QxRFG2pAVq!Vu-anSQ|!e`%+LZ8DDs1cdX5dx)`m;^A% zNqF9v$hV$4_+7O&1y{p)`W&XBpZnJ3{Z4O>k7Zf-6L+tz?I`UAbTgMkjA*pZtJ6|q za?iRLtXLp7kq$Rd#{1jBy<8deje*8_bBL5T12m+Z<-PB@?;ChPpfQ)O`dl=qy*&D0 z!UDrhcvA@UF?f`gvSkk6esV`&jEj_%#`rWR08*##%OoyzCXB-h4k3DHnZuSzgDZJ9)4zHJRhmx)Nea)* zJ32aWA3l7TaTC}*YAcp$w6Azan<}bTXrGpYxiuy-264TD1qH>MprbmpTYRH0pUBne zlzrgk<;{EhQ-sB&yV0&ZvC5G4zU+V1Zv52gKxrGXK$EHO%%DK))`=K24|2_RofddW zXD_I+D0g)b*p?I?0EKAfl?ItvPyPE=F;5fd#xPVJ7&dp>j1pqn!GEZfK*l0#?|b%N z;|Uhf)2{N|HD-ZFMP0I0Y~DQ&6AD+v@jc$!z@BVH0=m$@VQu)S8oVg(gQLX;<5`%l z$s7+vcV6Go>coBV*_r0JNZM7-$)B-8)wEe}eABD*qv65G$Vgp3K)hApoZe~sIw7m` zP1}Iy7to1rf-^o{cv2=cJg$!FAySA0+4~XOJ2Cz9U2&xYT5N7dph=b0?DKR2%MItv z{YZlMBxEajo8o(a#1jQ)fh^ekGW-D^PblBqTMUC4bH4mC9FR8^ynm;kG~j~+qTx4e>+8E4v|~93 z)GNZvU4ck=H2I+X)5us+0EMF*4Z9UBF-OH3)e?&gxQcZX2&W4IXku(>Bj0ZyePLyzFUt+0u|4-p;S}ba=#l-Vw2GB`^psl z0c9uOm_JZAWne^TSWL+Vgr!NjTLumPJ!C!m>A%Vn4;8#E;y$|IB)en=av4qCX)4g&dFCW?jBM`>T=Wfy4MOf%gYVC>ne{9l<==1;Xgq>QEZ;b8+R zr>ySZ!Y-YfVJtvmV%^rWL&TdxW1@gRQ8ucChoqiLm84GTs~elS;PeCc9-9Py(8w4m z9X9p@30!G^aW%|F`+vr2G3_hjy4`H6^!)?F@x4Ef7DUbZgZ^%w6l0|hg zII>p;80R#0`hO;v0@SX%JT1TV!)_l^4I1tp7IOOc$LV4eQGwSyx;5QiEFvdOQ!ianJ26dDt4!lDTqQEpwW{4*RtP^tMxsm?V&e4veJr!G}ex@S6*`0zq?al7diNdqtfu%y6~c#_mFrx;aITiIAv z0%x5~fAKbLvbDAjBucciZhzBsOA&(cc-$|276t}|I!vShl`7)xp0Akl+v=;8l*YhJ zji%zNy0fD(ivbdyd=yV`fXYyO4YK-r!vsz#HCh4#Hnx)jTHPov8Q`~d10n%Fx7*?E zfZ?g=UHX8=Hj;Xw6)OAg8#@Anf*q$6UJ45D1>gh^jioqJMto>+K>(@Y!MezW)TqT6 zU_}%oABh|P?_M!@{kf50bi1#d^F2T3mOU>7w%i0Q}_h zqOvws`VYE)miH;3Q#3TeAL5Mm*l!nzVx|{3-%0JC8OWd^e7%qED`(nd_-E#$M|YK# zl$uw7r3_k=yj^U-LkE^}S#bF{t%-8jRIMgV`1Tdf`XA_-`jPHsKk$&tajMM!A7yVD z7G=B{_KT&4D|1g7ZuvPhCE zvB(Ppl~uE?mLESnu8l(d3bqD(p;JR-!&pdU)m)-^71_k4$@>N+CJ`s0jDt`B%t3G+ zzV2ZA_lkus9r|k#>-}{>n`(dWU1`>zeNGsV;qeHir|WdUTMBMsVx1e6Dd4X`pTqS0 z^`^c_Gw|(lE(!o&-|rqA|Cw&*D!DnjIwmIAtuW+bqB;fe zI6pbCRCg%T2-)J>_X z)%9p({KKBqadZI}oJ}YN;JFM5U__0uvI&2VhH#H_EVdEe{LBmFUxNk+4LkOlv%6ak zkyS`=jC|cq`At$(AZk9Hn#b3c23vaJkSzI@ejDoxkc!Z8kK_vu*1n@!>SBZopRjon zWcXrH>fucyfRH3Z$e>$&J5N996jw(OZj{{y>ZA20upN>g$ZU$}$!<2`*(7(A1ci|^ zoH$}X2%4N>dJ;xNN%;WO4F(4rh0P@tep_C}08EQdhc+d$MIUTIH{2pDaNIR$%Klv; zoybRzj~IS!3(TRv-b)PY+(RrTxNLqPb9O?KLF_j%lkcl*V-D{~%I;;RqA47yTMQZHVWOxTHw^ft{K}j>&Th8T2Cjcp|3Im!L!HT^}iwCn_ ztZM#eZ~-NHm%+ieK<@N@2C-AflyNnkm7;zY&JU0)4PeF0O5J_(4xs)}K@l-laTaC4 zynK?c9)->ZME8|Yt-2JiA5VZ0>tyY$N^cKdUZ03W8P!f&B{pcU!2f=oN27%eg)}s| zW4s7`2FhVe!i{?9(3LI(8@sT-LXXk#;O2o$cS7kzWB@PX4KLjpZ$FVtj zr$lV&;=(WB6t5pfi?rZ8GmL9_Av;IguKW8E^`I3e9FqE#fdbUqHAOf%=RF2)d}239 z7v6euLJSa$Sl6#V)H~mT$?;Ddf#mqcr22s_@B339bs!96%m6e8hJy-?-6`7HpaSPu z`g{Kl7aKUvF^`S$i5wY0QZWQ@oWR4Z-Mjj4jaeaWx}hMsl`xRNAh4)j1F>lbisYI2 z+j*8BfX9d34Bh1_^g5RMu$0e13_&Ur53o1#nY2!uE;c7X^ozg815L11|54lX*}Zf) zIsYQi!YQlarx|ab8+m&RuJ-ntMFzj)N{f z3_Ujei5iK{i z1wN9*z-TYFd>=9^7Z0l)U0m8Kc$Wm&A~}hR`TwBlWfkk)*pm6a2^bsxDfi~Dv?3=?`OGT@{=E$b=>O0qRcodX}pglNZZtXkGlvjKd7Ckjts!O04*FaueLG% z6CnH-{EMMCC#wZJV>nOLJwuL=IVjrk@ zFI#R@mzI|Hdxxo$eRTQwAwM73mU(oy1s4#Y;)w8Y;E|NIeFm9U;E#Co0mXVwUi+~9 zpX@1jyjW}tR+W?(&U0nw?KpY=3hg3>iu@1I{W%vT8vDEKo{a<;XD_L1YaTi@#3CE(&#;;sGE~>b1<+s!PJ3Nyl;J_ zP@rNqfQ6P`R~}SujNW`JKSWL7w50qJ;4{F+%FsVp+fjo z4~{11!j#^P(}fDx-W+?;rprGy*(ZhOKI+78W;5C%#~jkUJ;1hu07=VTJzx*Tiz7F| zeHejpl-E}3!_KjsM4XyqC9YhLDSDWQ2fyJLfUqIm0L{%&)S~sgM6|gNGov`v{FJ~p z@2a|q$M^45+?0JNavoAO_A3^Bri;96yQ47gO@?3bSp9;^7DT{MpdA#Ox2Y|}jykI9 z1P~%ypYPY$Kp#)}?*ZpB+GAH{b0)RhdKz!{Eby`S}?G z79eOKfiH$uzPa-(-=W5=fYa~}Rltpq%x!Y)jIX93*n8=JuQ+5x534+YQzPoAx}Tl%8g6*5|4#G!Et&dd0=XY7KrcGsZy zPy98KWx>;H3NNsz51HS2DVgY^2HuvQZOK5v)HH7NBbU^DHSiPluCABQ5@GEP610eb-qq-_|I7Px)aa^pJ&;H52O)F0u z%jA>)L0=Ah$@i8?LRZ2dgDiAKfv*5VMgYBj z>he1ri`tn*e`i4Xw*$c_@G>Q!?spNSjqtK1pDIvTsR;1C|1KQe9zacvbpb#eeE30r zzH6mbtns6!thdgQF8{3sFetEN)H=V1aNRV5g8mhKa37IGoJ}}l3q*GC@TvyFqPi`- z4D!_G?*s}PhSO1Nl{6QDHrV|9P&KAj^t1265!+}M#X}C;c9>Sm-$vsDX=}nTL*Dc1 zy@YdoiRvn2A}J@HVm;7ML`$9V*RaloO?P=@us?QC3xxD=haB|GaB-q!APq zJ%Vm^uoJ!&$kkM@IuT@se+dqrf4@6Qir!Mjef~gQDIIK@;!-+U)@uN{&(HV<9Rd;k z1=fVm7LJ&?UcXBoxN1jT9kgRC?t1_=-`XlEr2|U$x^r(ezevlsibMowfVgSAEZw8I zQ5g3!1_0;Op$u)PzUwWyh)O*6$l3z8cL6@~&#JIKb11K%Wr&vrVW^S}zMF|nVHI|H zj~(tJTraP{eUAd=M`=6fJ2TqqDwcLt!z?ZZBL$v*v)gXFVLxBoysd}eYQ-Vg1LgZyzIKb{O~wkpgn z3*^`?zwc}dYx`{({aWJZyVCKnXhKl)IUWW{>r&IH?lr3g@4@Wa~O%R6M(5a7MyT2swJN%Oi598UnG{xA=65}wP4|wT)61xuy%R;z;pij>Z=xC<>67?oeS%MJxr$9fhzGS%}64$_Gm*Q zNiW|tm50#dHuzQ*(qV|5SE$6tY!$31xqTtpGO6|ypC(1>2PQ-<-nml#mpLY36wR2HAO8$VmnXDdU5YkW!r%)H%&>3<%Rqo5fdHR@RGk zZqCJQMUsNukL-^^a)EG;huwhC880-1+3URha;9&@3fZLCg}*>AI8?1`fQM9!wTobg z2EX0+qK}l6lmI*MXbD-$Bww%UL&r8pv0Z3`6yUyDzH?td%ANSS7Dtogh z#h_dyEJxI85z`+P<}EDCpBLm3=7{?~gmz}Ow%bA4{tH0x`Iu;5HR>(U8la&5Pwm6wn;!xU0%F@!(WrQ~&u5?Z! ziEo}&=vRi?gBG|pU6~eL2;C=l9bNR2f10H9WaHW5*e!(Un<@Rce0N`WvFpV>ewgZJ z>kkUBD#b4YJeZFlkPZ$Lb%v?_aD#lo6oQx`o1Q(Uf|eLKJLV+IeZ zYyoD^@^{xEL34}{&13=`2tpQxW9EQG8DaW-)=H|B>2Gd0-yH-)P_Gg6)Osx!2XZ1& z$3hO4^P|{AU+<;Q;EzsmOXkEV9Y&SBxGCuUDu3Bm)slG~;mB-DaQkZK&T)xP!~#3y zM6`~D<(oPL;s|G-%no=;e|L#ar-LOvm^4HJ|K9DedLl?^kbRhn8R}@#8GFJAy37Ju z1RUmxUK|XQu@k)`&xiC(ceVAh`%W_gS5+0cd zga@8DbJc28X2gcg@emw=BGse@p%~OKZVw;3MeUu_M;)~f&OP#Sk=ZoM7~`RqNqc7( zpuOhXS^Vcg!2$?mv({!HA+kp;QRNPDz#@(jzw6%(*A=&z<~I zJn*;xO}XZ6ErFnl63|Rie+45Lgd`@{7hG#cW@d_i{`_ggCi@B;wk<~{3p=4dI6W+I zdb!luma>lqp71kDp?Q2A_@Apzn~7>n>YI||?9?pZN9;HDPZnKk)pc|VBE1)B);Bg{ zX{YPG5FK)fA|G|$?SHn`8lCj6fiRKo!Ue%5)0*&X%QV9~ik@dtScG)6#u7t$*SEIx zYPU8vm^Y&2sxiw^tjpPUH`MOW+nziH>&2v=%y@VQDQY^&G-Wn~Le)NT%-SQ42TwXC zvMiroTvnCfIlbSLu47?CulS*a&Ss(*$n0<>CAKqSF7X9obam@1!d*$AyiAG8NU$h7 z4&!3WBuAufi*8yEo?Z6?Ansjnmt`0So}5MCA(uM2M zW;)(Qh+a;>>v?#g@Xud8aMHNI*vIIxZZHjD*I&?qOBbF#9<4I z-hK#FJ!>VtEMs^V-4wM=%iNN^aj^mud>5S2X%cw0%CI}gACF&>)76gc zbgT8)*ABEPBP%K@l9H2qQ43yz6hNS=EI-~si0;~kBV&S*qIh8G2D_1~5Qz2Q0FO{= zkwm4WN0;k7e0Sq(h*ajAbS2R>9Eyzd#Ye7kj8kT@uM7ay+h+B>(hp0tIfVs4zlbM-bEeH0wk~rR2EFNy&k}4`Hva+?E9?8{hVo_?~ z2}35B7JXGD6!m>*$1LqZHg`ibkZLkxa+7vZiW<+w*?Dtip5UI-Z)!?7iN{wMe5o#F zNq{NQ9!D(!_~NHeer$trawimPH$=ZsO=3)lvu4^JrCKI=r5F=r{oFYw^upWAE-qG} zh+N6@2YkY00O;lGBlj$}MfcsOU_|^Upb0T0DlyBu?;+#8(<}b*bKC+S$33*Q0>MN^ zib#<|7qHso|HCWqu)xp|Fw`S~Wzy^=J7$#7BDiqai0ujXM~iQM;Hr=Ok`lHfqfP9& zCqG=#>YS7pDB$)9-CMXFFn66VfW%Q)5`h1Bf^;FsyPuk^=`A86A|&;bwg8rHUD#!j z&iR@xQ;qp24v77}yC4VP5ZrempK<z>UaV8zTbW_=;sKiIm8#ZyEiwXI|s!l%gt@IKV5GhzN9O9ag)MinpHxwRaH(;CaqGzL_wUT^)wBN8Z`<@v$_ zhy{AQ>XFQ%nbCOA_Y5Mc$SRf)Vu6#U@+F(GyF9d>Xxu#Tn?4og98ZKjPTIq3i<_qV z(5?XI2BGN4DhqY7-EGh!P|VaH;{em{VKC{12d zNY6S9k66*X3RJV5B;&kRr!b+xR^|@1Nh<#GV1ZQ_HLWh&pJ$t4x$_$q`f0 zL;ENsLy(Pd{-*y$BJmyv+XtzhBEc4&#Si{CPfIv5ZP9bHhQocdk@D&OgU!QtAxiaV zlZhyQXcx`gM+?3iW(Iox^DsuT9?p&K9D`8M($=oOqluQrfYdAoM7G-uO_gOu7S0x( z&09AJe-uBoz44v=rRy8;B_vkhV-Nt{^VseNL<`TUn{fBZOUWOYrN&>dFahu!u{JZ4 zYHn_}vanDBceIod=FqZ#vN*i9GMnpOAqa@St}T!NgN3>xXK;|DfHht|32Plcx#=#; zN2b9?)@R*uc;XGz`_pX8Cti4^nDZ=-_}0wD$U?o0~UmvK~?qj^?I-HozZSr)5L*L`yJ6{HTJg zEIOdvjM$`#mz%O5mjofv7(f;^6IF*ez_;m0Df~i#_>qM;8JqHIII6(%tyr zQ!@z##mta}F8=Ksh`(a#QKx5T=!40Sc@`VmzM!qIuYX2D<8%yj5A!y>#R`Fp^S(@` zM5tsdMQKRCt(hkCoC{H6_zn-y|X60_FC= zKBcYOSXkU#T$S6_j~_p_MtpieISOva3oA8&Km^OQda9mV+bZY@Mu1nLT_k^@FsV%7 zC%n9D&|U60JiD+aoD}s%pR8oAz}JWxc{x8d7gtveFqeS)pQkjAz;7}{yNyMzEjsuZ z0BJxrwP+trxR}g~nP+u6d@IMT%c|Z)2I+K{gW`r!1%LWy&$!sx(_t`J{v9O9ruD?* zLQJ3P^vEmv#J_n~z_a|wPMHBP1w`o)laF?wY|>2x{!L59ZXP|cNwYcE%ro-i!#>WP z)vi>%Xf==hMb_ufZHTLHK(d%Q0cvGT>{gFwPjn9x%MY)(114byhAj10J3cn15!#jL z+Ax0PmiqSX+kSA(bor%T@f^>d4G7**W9#Fr_wSGmeoX0!)wzpCF%TuKe+Clm?-bF3 z?UDT39v4aPnQ^u_^faw;DoZ8Lh)t|B_n@OzJ#Najx;OhVp5{zukLhU`s$NKNJUC;_fA;*VXa`1qG_o(w~x&k{0=3k3v3r z3meEJgNpn-U^ds{9zp!q%Yl2!RQp-3uGJSPL&aGTqIJ9Ug2B+`FY*)%8J`X9kSyd zVhv}U4@T4O5GqVf1W^)3t9jIgM4eSbBmk2jDlG5VdIokFa(&^E(6*&&au)ef%mA z255~>ie{CxE`AtI^9ukN&dlgDZ8+n_s^eXSPkDyGrmU>2)Kpc$UPhPOZLO>ZK{YT; z3~E+AZ8dCrYJDbz#Rf^+%R1%+K*q^{#q!raS}w2wx`I4q17TZW$O)dM8hYfQrm!irnuXBa2Mh) zHu={w(%BvN7Dg?4&2iXh{`?_qcz>!%PP$2np^|6b2{BhX++^EOSXgM`>kGbcFTa5S zJ#8cVn6^z$qp2)=*Zd(^v>kPH zM~XC-kzf4A@ZB|rT9Ec&om_5KXxjSQ-cI1blOf*dWHH-hE6hp+QX*;KgPA!P(B;&C zpK0ss>y_2j3?*Z=JnA1zwKlS4#))hzT2Ub(AwpMEK;MkEeP*`oMiVa&U@7nqvDaXk zL2m6uEsF7>WBh$Yj4a30GODX96cm%H&bcmJSy@}V;X`@bPenp( zg;0cMCSw@QQjmNg1RA!sTa$OYrfc0s`uo#@f^N$MBCE9o8nP+fOukFUm}nXN@@%{) zWuJn&EUnAlL0AH%2BwdV6Phx+v?~aUwY>*lyMjq&0s$Qy98`(+Q-MIrQAAGDP=p{w zi}G9~AS%Z3+qHIS|73J|L4H;r=_u*r2)iRG>{{XebwdyVFtR9el5fR!x#RyALu&O!t1CbQqu%$xFVYD_ zMF1zuEzG|5C9oMD#9I_062rs8ar@49C$eSj$)qnXF3@vnO>TcMUAveuW9Qv}!hnxv zMbW^$6K`vJqS`70Dnt|$<5V_)?sb9+)Y0x%-?z+$=s+wRwqXCB1B^zo&OqbPVT(M` zr=mTQuh7~_bY_v6$?(|m%QHjXF7`zYqv~E@d7={;<#^gAZNTtvD+%@>F6Fki@NsEr zNzcd6Gxc)<>?eT3*M{sJCD875?do~KI!#T&i!8Xh1c4^Q1r-56Ah>LL$1Mcefr%dYj&jQd1X}MP zNC}u1HJq-`p)AM$t87+E=rtv?7(p~I_;c7aQ!D2kHZAWF!{jTDO&zqX2k9RaF%T z3scMd4Tus~7Lgrq*MEXwMfDDfJ%Rt3J3{JkyLKl(GczFSt0YtWmd?!O>%DVBURAmG}IC94I9ENKZrhq|6# z>>j-4oUMS@n528?W&$DnB|uSKAfQ`noO-@U4@@RNk>E$S=9GG-t55l>XCo76iR<4U zI@JE}M;H44@Mo9aCXmDHUz7oG&`F4il{vmVKgv*h9@(B*T+BK$Hb!{haSc1sPpJ{j z+s@I&%7ElB{<#O*AfSIBIx({yc>$_*&}s|)13{Pn+n>lVG%8lR+3tWJ*$yf!7x@$b zUZ)0r9|FZvGR8c#D704p?&7&m;Z9&HkJ9P*ZR}5njR)}?r@w0A{g!H2-|c|+W3SUt zo^;fRJix_Wo2;_7_PhLzC6YTiIq7nIvX|Ic$JTv&lMn^3s;ldHZ=J#q%QWEt#Ufdv zPk+4HWG(Yez#2VnG9+bqU~@C@=cxfjm&1kmG*h^vE@2eqx!g^N(z_6e4*_Esj%3my z5*g!R%J8=$-8dUwmu0wdgz)$0Mi*>sOO=-uPy!A9BAku~Xw89{Ae$9he}~{#c_Bb& z6Gj)$MGALLz!rSRZ|{LEoX2&8EvUOMm9suYXD^iI!cQ}6&Zo4hyu#{fN5TfM0?kpb zAaZL1)|aaCc9z+4wh4@uH6+c&FT7gH(H-?0Eox#;bTPCJ!jLXrKUr|$2(4$JgYl!o zhs0G_!xM9=f0wr#X5IdVHXN%I-8S&iI&NO_e!8q8uUfFag()8xcI80xlBeJkVw-Ww z`<15GI)d+=jFm&B!G*DtwrtWKFPYkL2()Tc(Br|V{+EH@%~bNA7RrUHtkwjJ7d~w) zO+-?D#~`X|KbSxMmf*C4@-%kWIx9;^9CfXl7FcEwzIy!tiymLQY%$+bMf%rWa?3qv z`OLDtA9H@ld*6s2iMS}mpEvac28N2Y$DV~%Z(X?6gj+I7N}W1ek1PEOTXA{O9qnM{ zq4C%_HVIdqyY3W`$Do$GXv@9AN#!%r;PFK2bZ)Yviqwc2Oxlhi9n z$*D7P)=(i(ItGDFGvN(dFX@vwRC=w5sjz6c>4{+&QZ%&}=I zFXFCaaMmm`$a^~j)3=_(<+l&z$n0xx1-oN&Ki09`$aPJT!vHHzy3V4ccM+Re!Sirh zEt2z+s{-G{UZ+#~)Dz+9lb(`QMJZ+~8<7a0P9zsp&X#t@MreGI^5QUCM&d9g!I#DF z&mM5&vHX!Xy4MJ+KX|1lP%0B*Z$#pKSWpxDR)col!gN*`b4gwZ5nvw1Vf%LMOFNWe4FP9pwI`>%_MFGb$wSAu#L&*D7AEzKsRlNZBAxwwv7^DEL&{AXjg$xT++l zzHIol2P^TsPiC8kDWQ!kt0V z?C;UJj0pQ+S6*DiCi&RQJrJ*27jV!x#I|<+{T@0&A>>s<*G>8WHS3qt&A>1FT*1=$ zZ}c-U2Q4YpgtKw&l)4;LfbvMC%WD6w0%o1>h|Lo_rwMp0749^$K&DoPd`sG;6vdW0 zd$lOR5g$X>IQi?_NcxY35@P6y8@}BHVpGipdehROccw8bJ=mnU_A6t%qZ-Qh%_j`# z1oJ)#F^Sr&cxv$xMaSvwxtU|lgeRwVYunzU)AVfl6Xuo@xtDStQxcWLm z@$yHkAL+{{gNq%d6!I)gmbLift;T$Cy6&O;$19Nx(}B2&iUcoy`%&7sk=3WcBhG^V z#xzwdka+%4G7c+X>(U|TW!YXA^)3i|F$^5Hrw|#5S86_1D*MehlghM5Jl2EH`^wEI zaIOEqXl6(B$;ZFXX(!NS?tW%H)b!25@m~*!ig|q$sb~onM7@QDXG)msj(72*pB^24kD)6&U9#HhXq{qLkG8m+c zFnylbK0MYyHngeR+0e924Dd*3TNG*~o|w4*D{mV<@6_IH5|`D#GD25Ey)~D;W88JR zKggqE`&)`M33iEM?u|I>4_D~1Px~ySEZfMG6X2j^pPd~{zL|Ss%;{QfU^h#oDY$Q4 z);isadh{rjLg^}84ofjbdEt*xudRzYeMZPYR1e%qV0z?v;&&-O*=RRPOPgXjTw4k{ zb7^kklA(cpA*&Mh@5^aD@dy`lXO)3~>3rkh_luTet%)fk>5J7AGc`F%Jqa)SbC;98 zKY}f`Jab-H3ON_l46)Oku&IZA(I%qQ97d(f(LX4di5vc{?7b@#5%J0SugOr*Np+#^ zj$Pp!OXpFQq0XUo=)SC#Msodk1O?3M)FSNu*+SBGZSg0$B7w6W2X0z;t>67$NWSmZ zh-XVet}-hERwmn24+3hF z^7!-272zFUO;OH;aVmTHjBj&ll5{T*%MEACRn?KWuVZXjB4$RKmo$?34L5uZxE5CI z^V0V}k_`IU*u+^|YVe9Hw|=|1C&*39`QVIMlDjcVDeaA1!bMBJ&wZm`i+snopg3-ueOA8oDaS3=Pv7%tQv0qPH2~})lOkK&ZDSGX~=)l z>|Q6#RWMLr7^s7zt?TNXMs-G72BK`Nv+JJaYgRFzRj;P+dcY3Xe;nZA?m%}7A_)fi zyAApi`>uj~Hv^kbyH0}#Jb20^osF@TYxiy7(KL#!QKU8mdKdINr~e$vk!sxPU}xHQd!?`N>4 z+Nk;z8BiorS$pWy+{_H+bdWcV__S zSF(zAkz)2^O=njLpPfTXBmN8BpmQvR)u}H~a+|{F?oi9!0WZ%j1(lfe-)lP~pA<_j z&v6iq#dadWUD2AoLgp^;m8c{PR=P}15~Q1sTRU|D*8O6sLqR9~X_mwMLuA%)Owi0_ zLeK}c)r*{I689}s4Pn<-@aUL>{x7%Jju|AA+YB5HxvihmPcw04Dc4E3BdiV{STd2t z4~^zp@KK{?)1~}Q`$vj`veUxXBw3z)7ZA2)sJQgk_Lhk-@Y8goAHuST)qYuY;JnsK zS@V45G<72)I&RTwAaA8FuOMCFMyhnsV@(sQ*8vq2A!aq9koRey6yL?3H0A|4UK<)SEKU9#mdIs+J?Q*G{^Fyv#O$Q>*6B1G(#a7 z#w|!Jw`6OhQpEY)zQyx=cZTMFSzICl#iq?A z$XYvVF2l|P-rTL%kudnENqumOD+*r0l|I0)lTSM8WjCd&LNUTaIap@=Nj;T9FYYx1 zqd1H}b#Sk9VNx8Kd+LLO`jG%27_;E_+DumR`r)FWmLJ)Tl${#X99f-#aTrA`*d{tG z`{j*$d2MX+tUcCw6$&n_j09T4<;n#|zx6-$*_K}&bLF3HY8_Vc=8algdqCCP?4}0Z z4g>DWUMOTuURP3m@wCK}na4+`q=B8bU|*|#$EMcmf|U_jcv9w7<6tcjT{Zbz^H@$K z11jT~aPViTaj>Xk?(mF6#?1DULaIn+Cf0|&ab|4!`|EvMzP&=id>reMYh78!R>e3S zJ1(6vMGS(wO1yUWEeu^gfBT@f;=JpelXMfx-)S0nIy+!}O!$3S-{*I0X6Rvk;TTq; zBgtXy^u}9nPc>Bs@v6s&gEmnWSglmV*7Q11AHSk#5!#9(IT|vdk=9JzPBvFWu$a#8 zCIYgpkITLFx0bR>t!y31>J$7qj`5s0lfEf*T>Uh6t}IXvP(_jRk`HG+&>i_1Xni{R za)V~~8BWE8unWsfarq+|Evbm}hTh9v7P`l9U17O030dEgm)&ua?DA87X|2ngHQxOt zU)F31@i+L&S)`X2BF%|@t{m(d{CySZcU*BANV;E+F@0)%wJ$O%a{k^gTk#4(%=qh0{_`vJCpApNV8$ zanQ;nP+a(3={BA(mDS;n=B;gxyhk;rr=B$F(U~&2Z?_*dUhPG$UtXQC9pw4FEH-T~ z$)voD^F5(&kVc4{;Rb#Kn&~fLIJzh!#3AM`9l7|8vGvZ-l^-7U2UAomB6V2^XmQ6h z@Yebo(z{%Q}eiZT6M~%zii+9uqP{cS)X(`G`9O!R5EhzU7rIPf0+mFVSNEs z+4n_TjbA5DHI9t=CH2CEpJ|Xfed}3-UM6p*h9b^zWQl}Nih@=4R>NljMc(ogPEx!t?G%99e+ADqE$k^+i1zsKJVPn<0a`@+U+VToxdwRdGG__$=8j? zqD4{V>XPs4`Zf$z9|*lY?472Z_Y-k=DxoX&J5524uSl-fX}!@)H9!u2zLn!Lw@Hw! z^_O}2^Yqyby-P&FmSWBzT(=!~xgQsI&3x@gqQ*8n$VhqZV^CAG(ah0t#_m&O zAq}HcJ8hJGT6( z9r4>%KKt3MmmG~8e9DDfz-9Y`zJ0<$m9=X5I&AGrx1Qte;*F}ZTpPtAt3m?)!S&tP z^qkq$Np88Y^k6cBipiS$c@1rJ%pAp+m#CUdbLW%Sw)gi#myd`NjJpz(29ps|ro_US z51iNC72Ce*b;!UMR^_!Avurw-II@x{cx}x;ovG3D6nzq>I(cBwpIz~upK&5vvG3fc zUdXcZ&v5>UeI(4h4)5Vt@7%e+uadWH<8)dZFD3ce1tSDbr=$PT&1-LFUSI$ae=7df+2pa!)VL&QZ2t!Pm(1;4qQ< ze9UuX>ollX2gS1TdO+l^><>);M~0sZD4lFYJXEkMbFpIa`1dycbY|`;G!)n!M-)+b zK9^XuJb9(JEy%FbQ92LA@nv>adt}AK7;S;soaJQ_;(a+C!37H1%%ra=>K)O`)WTJi z4GdmZuQOF;WGb}pJLlFT)O(lH+6r}jgL1yG5FXqVah&TUER?C=CoHk1#T#6l^cDWT zB>G99kE`G(kw(w%T7Rc;KJM%Y?~F&9#j-;_(({%@dm_jk{9W{Jn=XD#pH#{5Cv>KP zw^3l;)l5GxX=f~6wOvhQG^dodb71fMW41Xb%;?NuB=vab1QCMaq(QNETKh^5=`1sQ z_VaNPG3n@^ej0fje!`5*x9-}UPK=h&R~p7S4I95dv<1;u{(ha5s4ZZiBxhX|KGAyq zjdI1KHZ<6yfyPxazd8an)=JWfjG$Q5$yW+A4c(EJTl1(L38X=p%B>D~Hv;HalY>1%uLm zN6UF`2h+aH%L;VB6()OoWkv|ET61u2t5wK0?BEjG8{x@cFewq3V)o=BPN*s`J#!Qgkx-OunhQ70)ROe?6 zm7ov8CHLr-I+UNML>YT7?!I<({7YOu%=Yp?$*zGnpMLD>wG}@da{c~B&%}b2U4HEB z7K0_yNedxqICPu@W6@cA1CLpx-NGV2 z@yU(_&w`%KOODKmamFg%+orHS^AlkmxoFeQiW-q}@n+8#F0TnwuXfZ$gbUNtsUmud zHf?4)z7cc0>6FQeQ#m!50GH54t906CYfOOq%P2vi0y@C z4vk{zOXp>2;Q};+FxS|rTyhvv_(Zi_tyq;vKkVitS_V+Adj{RggJ|My5^i$gyzN$x z>Ez@gS62r4L0nB7BTGBH<*#bol)uU#FdtvU#EZ0tRWGP z$!ZM@{+1Mwzd~y+^fJ3&qEYPeO;7v3T0XzmO_Ni<4v@z3dlzikd`|66FqY%Mb~!Kr zG7*NB2{rNlq5=EY%4fUhNv>+?_OdBKr#UN4To|aC**iSB8qL^&j|Daj^kg2VV@gJ7 zyO@7j8LXPVaB}Y>=fudzeT@?x9FwnCzlW^PSR&|j`_UMtiYtCO>96am7KW#TMd7E* zRaRH{eND4B!91^4r+pl;c=<*hflK7FUSqGmbrfq5^O$^~_e@T}{WAPMCa+d=#K^42 z=(Hupk*0!;jGRoO6-Gl<)y$uff|(r)+9!#bdbg)~kFJ8KCY)-{_Pml_7d85Ezy+|N zqjm)w10ySnokE^+JJU%+pi{KYssBI&Ws zb{iwd&p4X&8r%u)xMzKllq?e8L(+B*?m6o2jVsaMS*%SgqAFW)Y-cg-C6?%^ zttMVK{ULMJ%V5yXcV*~wkzRjLi1g`Kd!uHbH#$AUuL6zT@J}{Vh{93{Z7s| zYAzS9R75U*8hdUW({pnSe81X$QxX1tbC);%O=qkv#lnS&UE{Y_xMChDgbB3y4fgj( ziKUljXS?xpt_-8TIDIK`dx1xF4BD8on-j!h6OZNk%p6sMXD(&vL$u% z9i@n7S`~M9?Rvs<9Y?QGN-{n?+uvXJp4?x#$vw%v=lA*M_w2cPta~$4sBO!?T_^S2uf<87 ziPc4Hl((PByC?%8irDCLoL#0unNz7cHWRuOzcku*2(Iu{NiEnEjPy{JST%bVIR?KG zH#i`-(s%ulo$gpxqiKZ4enN!N+v!TkM4wnrowKL61EsmcC!z=p)(~;}=|R`Y}D>G^x?ZluC8baaWXYlDpSt zii|T&_*je*Od~fWK(B7a(@p@d_5pt$No){$v;M>Vi{h*+9v+p((!ReqyC!C=8Z)a)}W2_;iS#tyfY$~l?fxG@1X9M z{NS#-zb0N#;%VLVjZRlPzHsWJPhf(DzEkIXdKy?>{Qk(m1V2kChU(>pxaMt48=mhF zvrlkQwQ03OCU?Whs|X3K@p1R7Uvh4OxQ2?l!il$q6BS)m@y#!$8l?ixz7Q47{7lig zHydRQ7o?1Kl;=ILDRUF-{f%w$VnZg2-v`l;u|LiQf3VH3NxX8>En-#+c5 z#Oli~V-mVI5iQ`tvLxsE< zfmEb(ezZ=f-5Xu%{99(=?8~fnx25SkYiz#lI>`NG_Nj5>fzi(oZ*5iGgpOXrMKlRp z-!|h7^s{9CZdeTeW~Y!Y`i8iU#+?25g@^31zM9(;_pV}fjBb0{>fCaV4dc~XV3(@u zMbWVD`m**bL;)*f;Nm02eX~rItteUhFP+(Z6DiFCL`}4_LiSHXt+xw{HorUS&xGy9 zRh(OOad~e(`2GZxJnKTA{QAq7>;gJ!W9piP?^42$HJAwVw`zD^7%Bup?QULC&Ih?R zi4uKzwF#h3db@^nH=-MA18Sv%#Pp$~}Qv-xr|;jz%5F0~jx z5#Q)b_Oj{=;!?aMt}&99DAsylPz(y$_grlxe`xvyeR9FYpUn`J*Uy!TA( zDf=360!kWd?)3u!6L2jw%Ha4i^G2TUR``+bReGDW-s+?bDpReB9WUP`idx~EKF#eE zZB;ILIcpV0md}KZw+3si-ZNB;QPPCwQu7r$zai{89a)lUxv3hGRaP{7l;;Cea`-Fr zv(U1VHOEip^}xg+D$x!aQj36Fle*Pca0xj{8H`s)qFKe>hDZCKk)t zsWr?!5sa!0DEjjD!`5$3`Q~xDGRn|;pk7n!A!0-3=cqi;-Dir4MIIrP1=V6Bsm9Vs z0n#QmpsU8d|6v|>yCgL?{>~S98!i)@4gENV)`n!c1-o(K1#|b))5brV8Ox`w69{Dm zv?tBr*Il*+!qQ)Gu$?KDO$d6?o55*m$G+WwFlIt03EgN8Z4-wnw^!`8yh7z_{EqCi!SzirrH=bemFa&-@wgvu|nsBKzg&U9ltUS#i1KPA7kZ| z0^##x{l{Q|H)pDbmOX|aw@on2-CQm6NcN+dDdKtz&(6yUML3Q-p@iMXCbq4{;}b3> z7X=YUh-Ju@>zL4*LU=c%emPJwwazweagjOp)SxPu)&Z+%oD2I;pqsHyR$ zsEszGw4o$HY$_BV?^L!&*#@>l{l804&%hW@ z@;>3hZo}5=ApOR z>t$Gd-eHC~j^*)q_bDQiw*t}RvIr<{OFM?UCM6EXP^~sM7^{`}-n>cJhzdzz+-8?E z6LN8zdg#ymgu3=r~4qmY_Tl_mk$duF(JehSc7|2t)BDi;7&sGeD8roe!ZhW$2e zIBeCIKGc5(ch{JEh;Ju82XK8qzuvb1S`k5Q(nvQ-Et-Sm|b}7KMum9#PiN zuv>b3$n0G2qpLLbkw|SI+uKoaK;uG)M569Th0A~Nx{4yaJs=WEwBKnyMd|6H00u6> zVij`NO0va6*4L^V6}*B*w`qS8;KdQYGx zl@)vFWfHLdW(E^rx4=TE0*y)sXFzpzb2BVVo3VEH4OVI(V}HAmL6SXU1_hk64<1MU zHqK&@{^#K3#lg4Lo@%({G(-nr)6=uFNgW+p_SxcEYlA~WZqCj!G&Y-y29{O50K{m2 zD>>++&*+Bu_`pB{2aU0pQlYK20-46$J}dllk}Sw9RK<%jv8LM#1gBV^Am}PBqo4n% zWrjvGx6!7+6&i%0Wbjuwo(gJzA{sttV{1!U+s=0Y<2MT+!VhBq?4n-;|NU@XZSBd0 zs>J@+5T?u0)WSmkPZ8mooLR6)z8t??Ik47v81V>a{KnMYd!T~u1AgL33ODFX)HDrfx#e*X8}e`)eRQmy}qfTiz& YAjwb%-Rf&+_Qz|WYjUeX=fRVI0B-sqSpWb4 literal 0 HcmV?d00001 diff --git a/doc/NonFunctional.png b/doc/NonFunctional.png new file mode 100644 index 0000000000000000000000000000000000000000..3c3370303144017893002a9f5fe640efc2e6b5c1 GIT binary patch literal 81216 zcmbTdWmuJ6*EI|xAdPgVfJk>YN`r{fozmT~5tJ_J25FH7>28qN0!r7WyF0(d_1xF} zKJTCR$9EnF2e9|K*SXf3bB;OYm}`f=RhGd(B|(LQgTs)Mm3{{Yhv)zY_k{5o5_koz z2%8f8dg?4G_x>5Ue4d$xfd5%sUTeBYIhh%`SlZiBy|=VAgM0tcm5P&{O5W85{Nm)I z;$Ro#

D*q>@mgdM*9_wDN-q92^y#oV3JykM!MncNbmvjE9GfjDnOH?(KQ2+7~)b zbt@Ew{M7UQ*s<7DK3%N-`OFn!nwo~wzi0UdSYkyG10!1BZ!_z)}8bF||arIN#V0ol)RJJ@MGxFPAGLsL?W`)bL_&D~F4x7aHq zdP`kZwQg89%YlwY^WO`{vw*ns;6ly7pbyLMk~Z^h+*$hdYa^oG!?xvR94;bMSjDX8 z_Qivexj8{AgzYl|!qd<2isR{9X4udFy*$-8(GiOOzKI_X9VA!s^(A+ob7b)UL>b-_ zz~OiQWZb;&q+PFBwEyeCJxPl$qTZ9EFY?9Z~IHOaFVB`*(D}MoQj*sdvHs6^(r>unbo#kfAx!_B z18370NqT~D^x;$f|1<0=I@r9R?f*R!y0l}RfA{5i%=7@~IKn?0m7;DghS7I^Ja)q7 z{7vaE`s2WyP18RIUOoP$5#R0zxhP*;N$|&8NOi|hh%4n1p?Mr9=Hwlg?&BX|06+5C zOy3}}1J?W>4M`GRaz5I;bc5w<`*o$XP&37|XCs$>wpig{ZMq|(H-{RGEam(gzG&-& zN5gCo$V@K>-r)&b*8K}dM+&&cM(@jCbrc=X@q73vGUxdJNJ=~|s~~c^CW}(+mag^W zCWEYKCufoJ1^;S(OKrs7Y}B|}%J!l9<82EzBZLc2;>p>vY8}xLZ_~g3SVuFsA()>R zadE#m3@nGl;WDVeD34XV8XH4W9yePNt2&AN;S4RaoHQU=lD7>ws%D~6fbZ9lMpR7q z{K_f#WCSv=<;6=sot=+c=g)uk#cKTwYg%x{nlzJvEuNSx+}H~pWmJ+|54VIL`0UxP zrs|Phj~{sK1|qz74Gd9cF}z#9@qqS{=_1+V&85!oUT$r8T{Tb7pZS zD?Gq*bzE&=xY|RzDcU?-k!LiVXK_EtBwc@=o2~^GW;$_o28GDlxNyUX`1&?qAW#yw znxq~>{jT~{j-duO^gK1LJ}~RWC*NwzGShbjd|;FhZF134`1SwTlVxbX<<`s|tKfOh zvbSjWqOM5vPa@=~@0w%lrAxgDTIlY%H6~m3g~JC_tc>vP--A;>vmM?Yh)J1Yqgx24 z5EGl4nSMXLJv~S5TP&*8S-n5J8lNC#4tbjPXutG4sJk3SfWP+gI&wXL1siy!e^xRh+j+)e zKk6%d-0y36&3`>xezIoaT~T1Sl#8XOB)P%la}bF1r1r_eNe%SyTtIzB|Jq&j{-kRc za^yNQxgh?|Lp$zft5gFAe_A+GzxIth<9al+gf6e#3+5T0ySluY7An$1U-{bv*AhEz#Q zb9Jzv7JF>R_^q+c^G@8|`5kWY`0n1!L$9_@`aY7A)f8Ein;QNWzB7$06KPv-g8qfM z6CCcVG$+*@A>H3G@N<|NrzYH9k7FI}s8(10tQ#X)j)Ws*;!Q)Wh;4MDLu?c5_V0LO zr5#XWRlfXXvHOsDJ?O8TrvFg!r0VhJbGHi(wFPWbJ%86Q_4t3{oRy~^I1E2kk-}R%_}IT_>b2yGj8Q+VQ3>Lk%`U>%%{k8 z3G5Tk=H7Wfq#cMj$1iL?v1_o$?I|Ovz1@bAon%2uP_id%Zx1(wEHQd2&pX;y%5?h< zeY3Ht+Z{}+VTopW(N;v}p^P-s{3ejX!r(=f_NVL>>7LX)&VSmt>~VodGz83_?IW{! zJg7zAI|&AHEVoczZZ;ew7wpxt`Q1FX+Swk+jO$4fyCH_VU)x#CDJY97_qj3fTrD<8 z|Ksu(LF3T`1%Wa30oH_q977VAVpk^j)*37#5a)VMchg)!X?Ha=eOwz)()x{pGaKEu zkdp7JxTriQ8(Cr_nfjmqSW~P@k;cB^wX)R`Sk=TB5@(Z=v##GEcR$(p-d|rxD_<+v zA;dtgx8S^C^s^LNlVCS?Vw9~h98BpGZt|b@P9}7(!+jy%b)G?nmP}Npi^}=I_Yv$l zb(mki5^+%37ep*#$o>bvUaGbosMiH*%tF?SKG$>;f* zCeXaIW3aS7LwR!XP#H{N)BS=T*WF8JD%OQ3>$1=K;{&w(uv9|_#n{ljXPFmibI09b zUhJNfQqKzE0lxJHc5oC1rFtb8MbxEWv4~Br8{fQh;&WBYTv8A%)ppNm;Mp1qr><)! zbbk;3gg@DPQtT+Q=_KWrzW&kA`Y*M_&MzphmKCuiAE#f2{zj42dXkMwbTz+lGThxT zKT|j35&AQCR+r>YUY9_Q8rTQUC^o54h){`vVj;8{d0yB|vA=Czx zExuh3*Fyrj-Y4>jC7Kd3T?*FTg!3Z4=*g-tMp6bl&6r-w)gV9wcStNL$+{;eWenPt zB_|~9>JRR2=Od@3i9Z=J*pAAh?&)#Y{v01A?M`^t{@1-Ft8Gyj>!RV6=RXO$;FD?* z>OUFrF)Kcg(UK$Ncy!7Cxl;0N8hy$hSNPA>ziZlXDfPI(|G7-*r{4ShucR(ig#5p5 zX3qbghCsOd|3>>GYpF zz`K7Z)6=&&{ySDkzW~u-B8wUp;=i8&%aCQk`|p6#=8TB{#P+{4dGfy(ED!&G%^B{W zVEWIaQm^4A4=XN5unz0^Rt+>>s!?OLa?bm+Gz@jzsV8xZ0Kum!`ZipnrXCXAfxC*bLSUGD*Hw7ljt^ zviXO%wR81qA1b#VO|?N~`%m3$HF& zid=U60xkUX*Ky^QuD!j2q8&k2+fVF`l$A*)d}|7^kThl6V6;A_QbH>Ci+%h=`ie5V0>r=T z%M&}^o|sksmwP*H(Niv^>XR@HGExekU@~1@_(Ve47P}@}4_`1qQ(|Xi^}UcUZ1wvB zcBM;vdC0tA?!t}v=?ftmc&X^Ff8MG>wuS#zVRB9`4Bxqz<-Yv;`rF-$zpeGEd(THS zDd3n*=db7>5C-wDKOXLd4SZ`uW!HX;#MYhg@fE6Gv@I^j6smBtJ3;sPB!#+$$8H{C zkS8o+ma5o)YYqFeL?3O2e>hDu9A4;_!m`O>r%mCn%XsU@WmewWe*fEtw}h3NfibLO zf>Zx$kIiHI?MD9;d5X2iO-o%>6?+_ib@-1K=<#fy!CE}@skbQK{hqI`M!b?$I<5~( z^KovlX9;s~9b}!_u3wI3X1%cK{u$fD{-m&TiA6f~)g^l3zN!5r(nOh#4HztVM4Daw%X zA{tlcd)5SQljr&NFheO;)~O zpvWyu?9$0vc88MXh#00doN-GK`e0=ZgqRHoiMH!$tbNTS`urJQa3`vAC57Q?Wx?Fs z9OYjOTVTI}BdpLY(d@!6Dv;|(H`3>>Ram<~cb}x#BDG zFmzGp{+j!gG&3JD{48=zYaIPKYRV^xq2r6=fnfFDO?!-x>yIM$^$jI$EE_bq=%csC z(U%?Jk;%#EZgsDjn-K}a%e7?QL9K5m6Gvft#6$2T=k~DCJMz=Zy*#}$-UZ)>#ZjF* z0g7^T!|si0hs=b#wp-Cz9Yx_lKF5by%5UGU@gWbZDwkRJ9|`8JS@%6QGydF;M|;j& z8+Vtl+dmxH50qacMEli6wARzjUF}~SJLbkgA2z6cYS9VGm|t9OL$B_4Y@g=Lq5rw2 z{?j`u_7L@J!48Qzl(~6NuX*oaKX;!?%%ttW2aO%&-l?{2qSG~PqKes#Z`M0#k@3y1 zR}%z5FYnG+XMzkSDw!>9uKNq?`>L}T9(D`_1d@AGn-+VdDA9hOvpozCn5?1e3PlIt zp{*%VM(QCck>Ef!(>_lhcZ6d$fBtTV1>-|1?lXC#8rr&;1{XO|KO6=$XqSyP0C#spJ z&ap4}A@pY!B$VI`G(f#bM*^c|Ye->q{?3__|<$7&o zH^r?=>+#L_hxiW|^{8!KpREaSt4*xG6g!lf+Cq}EY#}R&hFx4fXJ{%;obm13btUw* z%P6f!gM>j{Vo~EMjX}k{`W`?07YInUw`mp;CS#?|-{568#=SRSM?f3ZZVaCo_sjUs z`%?D?3lHyw@%viz#gFIjG~6OqO6lLb#MC-H=bJp(NSKVqhWmBnta*3k%G_Uh=v5@w z+dHdCJk#qAIcDw)g8Ol4X3Viz?~HNc=Ny7ixG}5W5Zz^#o4dyP>S7-)`iqqTZ*f~i zY5+RZO)*VFP{4cp`8Q|7?o|*oVIlqf?rzE6ZJt#uvQ-A}k@@i{bq9pHkpsiQBuEEZ zjl{RuZ5b}j)2qKFzivc6tjT%M=bQi0;}lzHEV)~aM_MllAK=N{?<;EJ}^m|l;58ti|8ff-x662 zrj_0p_)Nx14kyoeu~BiEtDu>FnB;@Dr9mz9+W(g-v9 zOFkK=e!^{Vd3C}a_$jyVJ9R?&qPNgarbuTvS8Zm{blAc`9prkX`hdOV&lAIjOYciz zTPFk-d@^CD2snq+x5Of&1}hyxWpq1dVsG7F*E0X>71PT&UQ3C`VvCS~nCiS?IFVrq z)|u0Z)YtoD$oo^lm-|o(l7{ID&1}{f{?E^l>#4Q%@BD68*Z8!_lBM*xpTg@PO=}U% z=$Ga>*Tzp1_ilxCh9kl%@mkg>78)y)1wuJAgME@YkjUL;wGh9M~t`Iee3BBh-IQ`W7j> z%`P3M7%FcGpIa?-6z8XTLW64Z?#~2LBgrO8p#>Xf3<4e_4&&`{aZ=4Z;lo%DUxePw z+tnZyMb;T+@^^ON9!3S8IJP!s%>@RcH=i>j6U_hWyi%^E=(m9R2r)dke8~)HRZ(nC z!2eU7641aJF=0AUrj&0y2tV^HZCdQoaiaXN!dpf-@MP|ktegl_9eVX7dd=Q4C-Sw2 zF?zeQy0YLO`xWU$Pl9&A;06I+?Ye|9K^)Cgmw1ZYQ70zn>e6Nhhk}Xmilri!+rDyx zLhnC6BjY2RAF@9bK2#apip+6E5vS;piMXJiWL&KZW|xV@Dp3E2_Hl9~{YI$EN>pPI z@XUOBAc;;Z-4~U0WbgNbSgphA+S@YRqb4o1t=NA%Zez>enuMsAAE$B)XZu^j-)K6% zBmv%+A{O{%5_8uVM@Qb({O7ACJ`W$!5L92!U5&cOxh24h z4x#D0Wr~ISQ4E`YNT$V{Mm1|qsI3^I$)>Oh2RcH)n($eqL8ZG3kwxld;}b(S=Z}8) z7mE$?SNoV@@+I;2=jFS6cB=>qXpZhl6))HE*vPj-F1Jpz6HVf47kYxOoE>Xe%$0l? zAH2UIj~|##X6lR97~v1}DWZ-eG5T%4*kGg*(P5W;h7gX}F6=AZUN3&`o$0MChV_|P zPX%sWT&Pev{hO}~T3|;Ydep5*)Wsoxpyc|YF)8dH&F`_g=pU-jqo`joOYM>ffycI4 zeXsX5Qo!yYu0_(GUeQDS>}7K z)?b_-?}oNI_d1f_=x=nl*qfaxi8{^qc~muL;r4PwJXEKq1)+wPLtyb3LL~rg{OTlTr>GlxIBHQ z24g}^k92h#5lyx>Jx}1N;n%miij7)>=Z#c`BXeFPNsi6IEEYbL8R0PVg0 z-~LDB1Wd+!;tz6tLDGU~+|*UECP!hSh-=2~LRE&27zCN}?rR5SUE;W?DFZ84OlynZ z+DDB%1l-TxSB2Nv93mTjCvRD2Z@))w%JNM~6KhC`_U-;fsn3`@e?Y~s^8{v7k)T#1 zx~x9mL2icBhb;0UP`P47*7^&psrgvb1qy|C%cr)M2WKDF1Gd{ULmqMjg7l*lydjK= zo6)x4?mXCnp=`V-;6YYCJ`Ts9^Emk2JjmI-K)Fw(mf$(j z#iYLq#V4&l@Q)rPybwm-zGlx=>#zNAlB8Gj6u#P-tvq4A3&CAi<)Mu7t)L;NW^I~O zV%tWPwG^434Rk7Oq@M*H{|0l^dyi)>ajK_yQGnAayVP*rt#)#*SIBOd#^aWcEYrn4 z20PO4j<%`nhW+BMOR7F|dSIXoZlsf&3>KWMx9fF|Z+E|%;j`)s$(+#-PN_^4TGW?@ zMjceHoOVKi{T7|{PepvzFI4Xix%BAlVYX@MWcCy^t*i9=`eymNm8I#a0|<)$fgu`2 zg-^3xnHKl`zb@vxz3qfL{j>JFyf0N-?^;;*J$L@jJ;Vq(5+k_qkgcVRX%tem*L-ch z_x16*o6+B~qzU!Gzd5s8P#yoa)RP{T5s z*FI;hMrAAiFt`=)j{1pHxx*VcGkrDAHm>d_RHt7Z1;YpB@ZNPgn)t&D1`mOdeeF?=<_tu0G!p z>aQEp`duy55jEe~EjabvG_X!6x6jI-O~_0)Ho09&dYSWi*HWyKqis|_)R=UYuNe{x zU7S@xl<;-j-Ib?9Po?@U9KLUm@LuYh%pR#mQc1Ej*OtcD4W~gvTaf!sAsH{LE!f&F z*DowR`^`N5E=Dxhil{Op2VE z(#*-p2?-5N*~$(XdO6Nrsa*sv!Z%FmzN6dp_Pb9NW+qj#!)kBxQ4(8};Ttv(X~WlKS*5fPV2iI&RF z)^HEE5(z1(R;!NyBO{}!sp*naLxtx1CAR-O!=BY&9Ikv)K~ImIhlhuoj}MoUQY`<3 z8yMJJ|5PH#f8K7RcGfO!tV6fVZFfq-(vq>IrG-l*UW=NZ9x1rXzi)-OVc5LdsBTuk z^Y{e<0s^4lwWXxGl!@n&wc(?QF{$mv`2!1HsrUxR~1-@j8aFd%=b zt>ul4i_@w$$6!se4wB&)O1Bo#Q=XZf)%yAIx%EUz%AqqdGO~crCA)}-$mJbGGW++J zLYPwn*mr6Hft2)gvJbcaks13VJeNZmHg|Vlu&}T!k5g!%1!iYc2i6f{lanj?`H4Z= zD4XU*$GcJ-<>cf_bn2qMe}Ad1t?j^1_JV=IdERw$`1H4V0@viY%c){$yuUwuRdqE3 z*+Oc8oUgA)et!Ox4R47$lUtMTJD4>)QC@j@bY>>SuV243>m8`4r>AizSiH0KVGj)5D@P8; zt8%vxzwSbof5Vd^oPecs=j@G3Dv)bUCBY<$ii&W(qAXL%1YJJ<(y4qwPk-Er#-_L> zY#uhg^+H6%w;8FZxbSl6G=ST}$l zttK}XCiRkU-@bjy%X>kF*_XGGJ86DCX6+2o=G!QAr3Ed78nErOkc`a!q>j-3w3+sH zIAUUATrcJN8IM2zo(0g-A`UWAlv~^TXjhlEzi;=rH#x7vSv|dijNZO|D{f|H)~(`4 zba2~+gM$k~1`!#H;#*m*+mJ8r0tH#DuUnHp| zv#~|9qJe9trloCdZc-7UzcI~JFHQ&uc;e)IA}cT7YgJ=Nw6P$L?&p4X?xv=url6(8 zD4NAavy%KWZTO9m5jF5IF3yMPPOBPD`vu{dnHkn%0{Ix6`;v47}TYn$8Dh;Plf$V+9lO~ z2FTj0RW1;2CFJN)m(1#M42@ULCo4zlAAWPQ-@zjK*S?pR+jp{X2nq?&LQc1QcHM*` zBO{Z@mQo7_Zm&)N;&g1eIIZ@_Fk(5f5TK!;go2pC-8sU>$45kmj;}cxRZnZy+6Z7a zW&HT@Ljlzhi;SN=n{w;03i-1H2zRX(uQLIuxuW$W4|b)vg@pyntP7ij^z?|yos7!2 zcJxzwZZ^ELvf?{#O)>#9$;m_|>N^77HXCbes`~mPp|}h*V|H|Wd`Yjv2|)0JA>O{^ zK3+6r51HNT-ExVIiRl1-QmCAfQ&6xTyT0Yt)Ns8WnOA^mFnw;khyc40$@Cy#jWF4t zYp|KWeg*I$i92eb|JSdaiVBApzoWRD=9TsJDV*1b02l_neJO2i&Gh&0U#_a=jpZW` zurT7#&`=Pj)vh}emMQj^?Y%uupZJH=(Nt+N(<1YM-O7F&QdLz|4N)Vs- zmszhdzQK9J>2y=o%Gw$wkp4c`qHb2J#tI*REp1((BsF>$h%+!Nf^fufZct-(v4@0( z0gHa^?v@6Kz`1qM3j8G|HI=srfj`J-$*oDN&W_ygvWt?Q=V1VtZYWEPviPq&2)-t_ zy|B$wJyt^N$uc@oQOMAqmX;PsvTs#YL8jb_@D*hyK=btU1a?|+;0JbF|D7#0&g%#K z1_HT9TyzJq4%`ML3SVE}=V|Wd=JcOGfBsop8=H}#Bqi0=zhV4SoJ!o?oevlvWF>%c zMP+4~e=J;R0Ey59=?~2B;%2(iq%VHtKoX!dA|fI`SyarSpzbJEgwMrr3RiGc6eb9+ z0+!XN@NilY5fEvw0y>uJp)V_D_h=I?z>L*|<)1%?r~lc)#m@feua#L>5QeF_d6o0V z2nu4mlN~`g-7>OHAzgdT3)bbJ$Of0)h0cZE@Y^X;4m|zp(5qHon`u26)7*^deyW01 zf`wM6Po-_XDREps+s}6s=IU9yYZpgq;U-7slnz$6zl+>L6W=x4kLWHdu@Iq0HGI_r zw}R{#Q7v(@KHmfw^JNgpetqyxX`2a0D)#L~UjQ0=%T9Gp{0$d^bIM zyVjgk-@W6sh1tG;k2f$d5C;({e;Q7y6d*Vl*qqz;LUG~1i0 z0WPentu3#oH(#G+T{k;j??`KDY5(Or>>Do;dM5r{)V)P2{Ub-vtPJqIIak_tMWsY< z!UH~=Bpi8ixwVxtb_GBjFeO!9G z97=H@{rZSf0-oUF>Kc=g5eeN0zw~ztjj%*eXoy2II8``3rlfHkRwgwl4(+cE)Gf(#-6 zx#ed75>8>^Mr=UpK#*^cQH60&SoIT3ki$P{==DsL>d>mEm=X~rvg*jYDPtB`jx8*_ z(XwRB$jG4m-~)Grg0i~4j)RW0wZC6bR2dT#>L(3Tz3K(FCev6mlLub+4G)Q}N z)YL{Z+77z=Ap37^Z2{bGW7K)2$xMLWMWhzPOHp7Mb&Z_;_UqgJ?lq@s(}6J*#QI{5 za(cjqOqpR@!Ltkz_rmE{4bOt>0eN87Z%)3uxrp{|HG;Hd!3I*>yT#l=y4c?@nzaN3 z5qM8*W~Q=<39a|}E;SMQ*y5rJ;5Pu|{!C0n2`@atEKCwu4}jY;=n$NI*+@xEm3MMF zMx+D<1sVbKx1yrZ?Ck6l^@6Fr^AL6J5r7r>3Q5Zj{F|Gbh7b35YOUkE`awn!SCN>0 zP^8Zi0DUZNZOuM@3~6m`Rk#+RXenbj*7B~-RB~WVNlBrF?MVZwEiW(sl8Gs;YT{{b z*X-ja0l3T>8+&&PdH6|wivK*tQoR@-0HCt+h`@#1?95DWjTkX2W^x2D*!}fnn-f&z z!mvhrYj1C@VIz~4kuemI{j!#GZIJo+0in06Bkf|ZzgkaIvA0lukWeJf+Oo{X-pnq> zdbc7nwPpUSJ%pZCD6;+%PKz<0n+KDj{*9tAMR-;e>%rEyNr~k-9Qk$g*rnR#1MB?r zOVwZ7-oXg^*22z7Y&2{GQZDfrPxOCWGw~RG^MYvL~3?9O`S@%B@ITZ zbe^n&sL~%*+U1mBpSr60`Cv6+@-1`0E1(MuPF6KjWz@eUI(B<^HFL6CM7aQ~=vk}2 z{qcIWpcmFDvr`0)TD7EOiWw>ucyxWh%com%obFg0JZcjihKI9eoowBZC_^L?>HeR@4xB+{6smv4J%B459@$8>n$6HE9?S;Jm4R?~4~Z^+sw z^I`h0bbpNE=r4Rcs9Y~Deopz-Q)IV;6;pR?_K*>+ff+i17k#gB%`jlrQ-fIsCGDK< z_|}Q*F(fNg+*2~%Tk4r&f5NQLdM)~*$eFdOzBD&C$B_4LZhi!eeB^j-kQhX9cDDbo zU-BU9e=jahtJSv$zRsVa+^m0)j9ph=jy2BB$jWLC%@lb)T{#4(q>vEur_@w6G65ft zRT-}#tU}9oUb`=cSy)bo4R_!Q#|M6VDDM4ICnY6CCgc`zdwUyl-pzyl832W`i3zk3 zYE^@SkI#d%iuhULiGMqOWu;LnJ#QLD@n1oDaWYVOf<%2?U|WQJKT-i$mBjw08MjiL zA^R80pf`694i46-)FbF33{?V;w7?5d4IxtnjPgMyHND`t$Tm3{7@0=dCMm;#XO-dzt6*nn*&Z_gfX zJeFFuwY72|bP5UzqIOOWoEly-GlNnOE4+sjhxy|4G$Q>~z1yBPsKf;vm%HhF-O`mA z!U@^vnV78eHmm_d=w>w~M1hHp!ah^y`uTxak^S%hxGBhjYR5w9$;tdxQ6nJnp`f5> zmZ}5ZML&ORnghsuJtoPU?V5+k4aCyb>$0ME@!Ly`f)At!x$oB(Y@J*I4z`qs8uG@T^uvb_F>!HS zGd0$XOiU|Nl_r39RXeV{iH(gdxK)e_4Fg<)n%X}xF;NbmB~YgmfqRj7aO;Ld20TZ<=P;o;Dnu|*xx!mm6K_Q z%k%=}A$eMpc^y=*s57`N7`zSUCA{0;D4L@%CFwy057e4nI)knENq7mGioEs^Yu%q# z^mwp0svs|w3G>eR@C=k9d)(#IBk4M8Hkz~W5#8Myd6P>`@N+t=aWK`MymO_LNc${q z@oY}K!e0d1qU?)3^qXp7x;oks9@1zXRaHDODBd2%U{74Ep*JXgqt?7IBksHLf%%tg zm%byaSQlZLLL|oT=C+KlFryAvd!zi~MBnljaUH6}TYT&K>uYRZzc~f#-|Y#pO6o3r z$hG@0E4(p&A$1P97nc=fjOs@YPyW*h^c5S?ixEZ*d;=;{0?=s%MC*-ypvYAi` zDzU)VuZe;rbgY?zvB(7vqAWEuCI$T7m#Q;?bcc?CsqCpT<*;UZ$*o3opFP{=Cx(H6 z0a$63*V%T+(4bviTzb0Cf?7{*PELP+KitCi67)bxbaeEkldHokANwC_Jm3+mNoYxf zf#X|bC>U&bntCWK_-~LKT3UQ_e>kz>t?Fs_x7kcr#hg)M(#X^)5|PgZ>Aie9G(4Q) z@ChwqyOQ(;5qf%NAL&8pC?Pre(_30XvDC7|imIyEvNG0p@7{shI0u}PL_{O_8WZC` zxMtiDfcUefMpa!s=&x1J&RLZOG?T+5E9A)T8)=XPsLO_jhiS{R2iIr>1Uy%(fubVw z?i~&&P#+bFcZ)Xw#6abMS2wGqqJo8tN%jrQv~xTK(_efk-~bJj+Ar~F*w~^$=rb1W zQj(E18+s5gpbQQUuKX!dQ@a-(85%NO`;|cG6JeQpyQSh6)~|_*ipoml6y&!u;{F>m z2&;gAfWYbU5RvtsLn5xUnS7pC0#+KLD;E|PCaa{>vboZEH`GVV%bS>!Lvy}2>n>-q zv$sdykeoQa)xB}@{Mpk(58>UphDYL5*0kS<5}1jLkBciMFOO<#YfCuit|TwNoN8SL zA5^EN?*R)$vGoJW6L1V}7?+s7*H(TEHXjJs`}=#XNi>gCR%3#k;+D9#Zck9`KG%wd z4E*XG*BZ`@bF|Ur3Fh{uJ%gY*qBs)yesIBruYHe-igWnE)&zPK1q+*dwqm9;m!G;pyK?NZTGpja6^&Bicdt%)StX$w=|o#2-GX8+1%u~7UW8~#YoBTX|t1&xV zg*crzt*lB2rz1}iYL3Q`dZ+m=srqGURxWh^+fUl3KYzC}MV08B3@FS1jTB8iO)7)? zPX>eqPT>byA&0by8p80NlsIzCUYM8J_tH``ppMwg{M^bR+yl600_+T!F;3f}%InvN zZCAtgH0l_uE`p%|gnwhY85=LlYVs2Uq^1?iF*A$X!KgD{`;b>y=v?(9j8=xGZrqJN zY0y=D_6sQJ&UdG|oI2_Op9;~vq$4YcxIpG3GYw)}e>5!>HlVE*6X^v$jG(fkh_>h? z+(AXFdk^YJ$oRf2R+c^i2?|FcAY7>6%^`1A-B7eH>cJFS{E-rL(YV#svG|h)Ujwxkh-U9Ud~iJ7Y#2!+ zX$!q2_#&oIV2ShW=_YW->Clky@Z9=(4^zF~-rgvoc2~g+P}<_62KGatecZz_W@$>u zZ-FAy@7-r!9ceuuIQgOeu1E2w1>g;24cI!au4nOO<6Jrl=?Zz;$e@6Lxd=kFDaN@4 zT(|LLqAAF?TI{Q*0j3zjIs;9-9D-lV$l#KalExr3!d_K@@+Y!ElNSAfHBd6!`FsqM zQuw_G6OBfW^M|>h3pv1bSudML$HxJcK(MRxUabWp1c)v`LE}hNUg7~w)2LFje`qML zxjEhQWL?$3Km{lkAbP-x!B=K{GQIa381HNWl{XtNP@)aQVr#oS_GHo@9~*mfzX+H{ zdb)7I-9!&4u;ps@92;~&PK^8dwLJ)f)MG0@iC#Feh*t@o^-@S^(@azj#qCwI-TF{y zK}!{ifedA&KaZ&ee^GfP4P(cMp*ONGJ<%vi_w1d^Pq)bJU?FK8YeLg*T>IdCM|>;I zBM;+mb>{Vv?Q6ZKW8845Rw)bhJrc}KiQhH$l?;rIMSflQQjTb3O;VXVfb9&sc z{+UfC)i}53T7t%-f(>wU1(In*1j(LrL$>m>c;4^IgSZd_chqK#+`;C7GE;&*cgIp3cb!WnDk$W#z>^VJ9LJAnjyF2Q;-%q@Dau z$O33qN=o_J*+$xZ>>tL)#ztn0Fasrbr>lcO&j2uJ(Rbu_sq{eZczg-y!0IKM9Q5di zH+KLXWL~r@DJq(d`a>&iUf#~**&!mlxtWrG7`=^>&V=1vw>*C?P})y#;)Y{;>794Z50`yn#;NoN9(_WOQd5dWCNh|1BpS+ zYd8k%Ajj;erKRNtx?e3;;5W89{CT=yo`o>_+O?u&kuk-I9f77;vD36G86I>YCMIxnFtrV<11 z?3ncx_eNNn-wAv&690Ze#MYuMv6vi)xpV?wed5b+S=O-A0Q=!Va=yR3)~kOz!JVkz zmU=juIjyJk;pQCybhv$Cla{MXPUf}99eq6q)t@1M79jy1dNl5%3uJ-nC~xWSX~#+T zNkOMRVPOiIz9*6d8m+$)GkCg0!p!D?yr3d>$L)8*=f|~=+O;=Z7oBe9%?MlrkfuO1 zLj8BHE06q^g(bhL%1KhJqB0ZaZt3kko9CC@b@wT!;P5>mktjJJ&~Zsg!HWl!YM!L) zZcTtJv&uw~HRO4^y0{otYW9-(W-T;hn#gqT*08 zoaezp3+;zEiz?vTgoIq6F92kiDWHme*>Gok6I{D8txD=!;ZndV$#Z>U-F#=sh71~v zM;;^B`X6m=^Yik)Y;SKn*J=WKl%1RVxwrQXD4zP}2t}(IaCSfM@dwe@j{B^`Ge3`E z(sOe=Pv#;9l8B7*K{1L1*^t8LhXRVqIe|ioWf$lurXOzb=5m_+3A40pX%g! zXQl!e;0tURbk3n-jv*uGcKxz1dKaZy+;0boQJ->z(){W$d!KLJ5tklPS{Fu}-_?>( zIkknxjxqahS3=B5&|C!VHyY45`;3eg)wJEcMuKTeKOQf_?9pgt@x#v)G?{`i z$w6~(e0thb-2<&_C%2;FFcx7BAc%qj8fYVU2xmI)e-D<-j$z7++W+jus$3X1H8mAd zqxO=8MZ_Y6c;Jwem-jpXW_#Ib3nO1UIYY%n`t0K7Ha0s;T8Y-I)OQS32hy8~7i;vr z=(9Eknc#X0q=t=~g|O)8tg_e1oB(M6%6?5xR|KlIY~Z>F8*Ad%uk7#ifDkJwCx`Ob zg8@OP>u<$QWD2x{61}GLWxRX*hvNDOs)N*s4XD}mQICX$IlUa&H}b}I%yd-E-6m|yhbE} zn(9D@A*1s@@5c3Hz*z=# z3=Zj6Thnsf8a1Qd+x%zX7}ZZZ#PgLJ7tG|T*c_;ai9oTyINE^o`RIaBh@}b@-HiN4 zhp*I%*G$oGn+$20?59569m>u4Q16bSNT0obJMDFE$T&5vOgN}n(HydX>#J!(eyX7{ z&Z{%>$*DUgF=l|Y$&uc_71K+o31tLo0=p%U*SSU^Is#n=?4!SAgt8e(UsjC!9A zxlLtytCO$cu|3)B*3!g5^lr4yW&GhN2nQf;32nSiEszAQ0?=>S*bNq9XJ;R)rSW;? zU9a>BGzabKqKR|+R4)JErOC`(AhA$_=^L6aVyRE}(4@fF2|$LYQ}PYE@70O!ECV$I)>$kD#Tb9Y>XkA;)l z6~AcsrvH8PBU}soCQ_D4g1mI@&E6X^d;3Mm!oi9IX!kCGMq$XC+|7f7zL^i_4%>N*2{Qf0xUHv#P_I!p>c6>u~VslYn$z6yTmIOAtm{@d2heSjxiz$ZgOy4jRnhTnvHne)il|(>sN6g$9otd%H zq~=N*OrTzXT&*RA^cVxcYL}t(jVEw)cXRu_xM-k$H1R6_Z9C$-dl9l;uhF!r-ZJ>q z*?-RhOjK?Ly?$n7F&KSRV4l89xva`MNVY|`;qrXLQ7WSASDPKVrd*1f^xdX?8_w8hL`BBBW$Xx3c2V~n3u82Pe26rx* zL%P^aq0g3SylIDkX))nA0>Po|zTJ309uRV8hpf;>c<##fj5s!5<1y`sm)UiAl8g#* zgw_gTkx4#*wTtTeUZLwGZp*AM@9v_vJ=`4}UHCm*cy1Jzm-mU?c8M)jLq)s535V?I zSr)>XF?++NlMs7gdm(6`&k~ERA>*1y6xYW$sv|MJ+_WKIJ@x@&q}z}!1sc|p$IZc zO2QBP%o7KET6RKdFK_3{Q6ASq+`tQ*Q0WfU zC*I!PTV_Cytf;Fiv~&Tz(7v%T9PmGA4ufM5pFxl8l>O9{GZY4cF%Oc`w^rMnZ*5tA zn4rDtu1!rPQB+aMt*OBem43p-#RYt+KP|?0V}$(Ac~B^zozYnNxLj^$!XVCxyGd5o5lNZf=QZPAMCn!##G-0;ockpGWsS zM-6m1Ss#w@Zrk7AKMgl;SpJ$%MGy|VI@yq=k9$0QQ>s(vQn%&QFh*0V*=)AseY*L) z6__IzW~%Be1)U(g-~+>1EPF zZGBFPhS(XXzw8~fw%2|%^SOizhhkQIH=7L)`V@Y(2zyAe$nw0*dLVf?*A-Sl6^gz$ zxFx-*zeN<)8ksldtdFwDDwpELV!ubqx=WiIQEV4`Kom_$y82P_qT>9j&4>j`rUMo0 znm7^W5*O#k7H4(}${%(p2q72iJ?8W4KIU^89O!wnbmx4zVtjYkF#X9fbr8tb$%vP-k}Z9RYf;2|L)wL6ljYiLx~o|hGRw&?qu zj>>F7qbWpwVdH^=0_;E|E5j2J5-NTr#7Gh;j=jxubKpc442~(miL(>Et=awcE6j!< zZg8y=Fe0GphXDTQbF)|1h>Aum!I{zxgHZz^UR6h@Sa#PqBD87Q&xxYm>HRx+t}T0%;I2pD z>F<|~qGP?YzJvH(pKNdcpq}m2hj8=obgVg1Q$!bX9f9Lqm5q(5jw7OCVtrk~SmRk| z=4oKkz_@eujtH2+2;h$7l#~I+5m4}g7+ShM+gakrY-(x(ua4GWIE5I9vP-C2R(2bk zcge~qujV9cwMPJ+j@~AjKLmyDEXa`cG1}3RM4F@2=R-#20hYe}-0~@2zb|&c)Jxik z?yZJKFgR)iM2o?&x(H3?pwdznMP=oJLR&k##1GASy1Fm0bOTKCk|SSr=TA9xIQgfSG33l1Au%1vXteh_5kOjLC_V8 z-|AaU{eM(_WmFVk*X>YJ(%s!H3P^W~gmibelyrA0DF_0hbf=0ea^T`=c!yj{6SspS$75sB(Z~(@E;gvZ zSPafp?ieGGYRpQ7+1c4Enw#||KMsL0Ccrs3;a5H6Z|~}g3rJn?#{nZ3@Ysdn4FIjR z;nNvCct+wodM;kxa8Q11+<&{cxOo0CD6BA}dpN<5fi{$DHa3XI_2Jf~IE|=5Q^nOR zMRJ^vCALZLU;VHJOJx5y)CFA<%0^qa#;_MS@M38&za}DqbHv!$8O!5vF>qo>k~*;+ z3N`V9|1t%99=%{TOxO91aH{7ZpP(S{xxn+qDa?p5G5q@V%k%!4tM#hoC|#qwwiky@ z%&L9P9moIS1dHBKl_npPgr4gDW#e}<(AmBq8Y@V{1`vx{K>QZRrjE|2`RFIrky@WY2I2aCCmMofICZN=+Mu&>SmQf-B zx+Q=1{`2_KQY=t_;e*BY4-Smo-0+Hvi??@o#cgeEe-lE-#<0A+y%S|=DUo11*DBU} zQUShu-c9X>_I#tpy1FpHvVx1a29n#^*=-o*+<`lA90YECdcJn#@rciB34#+W%#8{* z;FAEdBcz}R2b?>2WrJ29?JAo==m8_IyrFQqv2HANqU`s|O0GT9ob#Nq1NUEszhBw$ z=%yQPIPbvb5q)@z4&dZ()Nk1EVp{2YGv(_bx?e-1Ie_gb?hlgdm;ho}m zMYWVjo#yH`si^P6;n-7ISWv6$%Frh!>Qz8MP-6}az4yQ3Zp8(b>#8^DEt*HhFTsaTnxnE2xSxVX63eSZELlu(@9+<7nShF`>XKyS%pA0OAdq($ajy5^_Bl8BJ@6Z} z`RTukrU;@$;)c339zWh4tzTag<|rcp!V)karAR0E4Wy+h@8~D4@Z_`TM*jXCcf*XK zPJd@pg=;cm_^z96Dy0l;PIs5~g5H;Z2edKa1^pjM@9yrddpP_8 zfm!if?k#cb?%ymE38K5(TVT8%@38~DyTLou+R_+D1*cx1s7ENTM`8bk%3e?6-b5yx zjq$i{I?IO+I7Yjhe$^Fg84^j0x z0A-~#a+yeFM~vtE%WvP^WhN#j9w)LeiPz1S8tk@naIjf+s2(334FD?)3Kjr7I@X*v zmilUIYk~7QWN=g5($Z1|eo>M-&{HrDz#$-WgXgvHxOQ&3Qi1JTqt?r@i?I>Urx5K?kcOQf}ZgvOzK0qTC={c?jYl`I#Wf4 zM`3xQxf(_nR?100Yw|Pz{3JMBzgTHI%?1KWV{MC-u2AogpeKC759c4iAv7^EqNMqt$pN6c=fmwAdIkn=a{dp6xLG3p z1~sT>&`wxlk_-UY(z58ui3h@@4)^zsOnnt++$&b-@EqIj4x6HI90Lb^Et5;8wOB25 zChnhscQ61!tZloh3#NcB`rg_~4nmLiLXNBM<>lq;l|^D_IPDTd7|JWmD{!=dBs4iS zC59RDQXn`w8Wltv+$nJ*8yggm&mjq8;nF5kFG3{8-NoSA>7Za z#X$SWk1f5cCt!|VmfJCQ(F0x#)4~*NlHiDCY{}?zPCh-YDl!)&kI&un242WT2VTF2 zJ;PtWkb?ri@d6AeiT}-@;iN+uUFCRfB)lHn&5ZxUjEiHCb&l_cG?SJ>5I%!v_7pAW zWlLe?184T6n3G?*UguLHJtIml7Q*;GJPeVc9*`}-Gr2f96AWe+7xh%4(dfR&HQyg1 z2;V+pfI4aI>dwi}FAxL)r)^lvtt~zg0dCq1wfAN^`uf8H8#8~9f{ch@coSu}|G<|3 zhp0ux@83~{g-k&D-=0@WHQCFrD0kO#WKQlJ8hQzk`uG;on?VP#@1~{_)yMa{Q!F48 zn@0-E1JrEJL`#bVtD&Lcv^UKLwxR#;hatOB2Bj<`Gc$M^8XD_p#5_!l#xFQaV0%Yr zW>O!UYiiU~Pw+*5^W_p|45#4NMh`46lk@ZQk6((I=&@_g$;kasWdhY>@H!tYHnJ2^ z*S;5%-|WK5il#5w(!xU5#)et%&Cr_D4^*9h;(xjMh+|V)f_RA_qVQ#=Q5#G3sTC=SfzW&pl0p zEy(axg8(vsgt>NhgBdIROoaRmV8(NEa|3ovsf!U)@X|e97-uJ782|~A)6znwtE(HP z^%@s?e^2_c+`!ny28ElhOi~z_Z~<468#TGvX(QEIQrD7Ci;J>0@P$E3Te}1BG-Dtj zN!VdQoInbarNx$|g*G(s$uQzd(_#agf;cTUC~_vvbQ9(CD**lhZg;>hfjV{z&lg?{ z6iD6k^Isj5O2K6ic|3_vOG^_qG&Gc+_IpOe04`QEHfr;9*m-ymfTV~74@+mrJ94I_ zqtiJyrZNx?9O_rkIdjd45G=#bf~p}SlN{`t+mYV&lT5!6fNhFU8gOacE45x4`rYL3 zZgyjM>rkA6{0xrE=)wZ^E7&G@A7?S1JK*j<^N;k-+ z1MDUO0t>P~KZ7s>^S!7D1hqX4S@IUvZ$s4Zw$~k z$cv!h3yV%UJ3G_T(h>#N{uu*JPrneu9M5A@EyM*6fDQrOF&@hNM-JR6;Gxv6&mom! zvaqyNXnjwY`RyAOesrOZ^uc{-MBjSR{JVVBpH(Ka;H2N&G?sa1g8I(R-o8+Wo;Vf? z{9j*Zw2`t$!k--O+TO73`Jaf7DWK3?l8Ir$=U`-Qoh*5*7<+jU0}AtcBKy%b-_|AV zVcu++!6Aq;N*we-J?>;bGCkbzw%sU>&CCH%esl9_Y5IjcpMXGDe}4p(eGfR_>b$Yy znDF}qH}-~9B6-!--1|pI1a2fq;v7MgM*jXQxV~=y0faCQbd1lXspgl!Rrj|KoBY)9n(`@02<{o;X?WqcsH0Hnw! zw+RKNxm8e|UJn{RelFuF`^6~Fim#xV__P{~A=^y%-}j_M%7s$Gq*5Y*sv}vl9f6%i z_Gw#2r1Sn>5D1h$!r4D#76Ie>`t@sIIU)mrkFK2gnFsyvLj^^)oel{Wye*yK7BEHL z9!XMzx>5Vo{{Q@0;2)d<8-WU#@QV%}+A~T}w*T|nVD$u(!2g8Uz+7my-Krs$Y0r6l0M<-S2W#ASsAL1=i;anT3|Fa{E!aCivdY##7v~slA<~UT{3rQGn z1EXV&n389$k|;A|X~!r2R37#0eW*IrgPOEHaM&*}b|{oH>i+dDcW;9Wy=u7@D4!{o zb!F{Eg)~}^+hb*W$TuFZ(k!*q?t}-Htdwta-P3rxw z`d7>g-a}M)K~wH$EgyOirE(nyI1h51^#QiF;*N%7*Ifi!NfGt`^I1Z;(kr1y>1l)H zi=}2n$`0Lkg30m&QMAy9p)(&Z|LP;qp#(41pO*E`fH*{j6@{i=B#n|CZ-@*%+>VqG z$`=t@qIZ{RLdC&fwH|cgkB=JWNx|LS2b&>t--27&U|T&`X2*&W*=pCufE^iQ8@l9x z*r#tH6?yfMI5^IN0T(kEKTG0DC5J!O$lB1 z76V)Qx)&RH_rmuLfNLX);|dY<{>4yI-q{zotn>K!OvG+-WE;`w%pd&kQxcNit;NPj z#9!J=F#R$&mk3_FcDoj%B52h1N4XtWe5{G~Tik_uO;jC}0GRwpF!2ZSCq%lmXF)#l za~dI25%%;jaiona7V8Ol$5rw$5JOWv5)R;-tA$c;~4rM z3D$LoFGA=wf>?hgNcCto;t zSm{mTZKD);q|I-lPzj^TSy*|XL7}WXCL?=l%u-x|k9LNI6{yWk%MlOd+9!gS<3W<( za}R|yBIx~CHO%br8uTW-J4P(f*X=r#LqhIASE?o;okdRS8@Oe@Z{c;?>uNe~o$J!> z44jXnigBNJI`u;H<8K2?jw#ur5;HUlxHJ_`8Fthtyn)Jv1H3J3Yg#WT&EJ0WyG*tW z79Lh|7pWLV;nRZQBs@#wDr-Bx$^e!NY4fLy;nt3QtAR8&ToPvzlQqp^`}Ug~vdQUI z<+EyL6t?LXP;p~<6Pg+6oE^!_$AoAMoT0gUR-S!gj<70UT*yuE>={C`H9LG4b4ZnA*b`}`# zXfjC$@MLS(5>@vwr!g#-S-sZ%uG!>JZ9=~?r@Fwe6{**=uu(RcFYE`oFc=JNr9pz) znE1gEK(NK^M*O1>ZeXhscusaR6r2CN4G%cZ2*2Kl?O1pQUYL?EEU-;ur5&{L30aVv zH*w9PrE;zz)3~2dBdef0E`6VgeEiDA#dt*1vzfjRTh^snT^wxQc%-+6c1u4UFho!P4|^OnayvgJasC>zaR9Ote+kv<^UlGm@Gxt~u)WyC^<+^= zV0$4iWk9Jb`dU>mDLR^1MT3aN#Il7pA(!`# zf8|_!&+MRhAgeTlPdmp`x6ExTTAi+EU^~cR-~7j-2e_0W7gW#r7+ey}Mu&ScbQ$SH zl1hdZb$rw4K%Kyu^%IEbZwUIx*^W31WL&CccB`1NA0LhmHg_?&s&9RO`5&E>Ps!$B zCp@D@=qSzkt4ayIZdrDN{cG$#g~Qogtxaji%Qp#3msO?_-!OW%B%PZBJpATyi#rLE zH(3~Hm6%=$Kq6`1fQ6lG zHR=w%K7~zKC)^x{?067w2~zZHcZ&+E0@}&zKT*-p4IHNfcW-GbL1*1@>kytKGvlaG zZBQfC9`*F;wFZ4sn;a$d%u?#3O09*7P9L@yFVhi#^&SeywZfJs{f&+LOzV+q=% zS#(r=VE3{IZn0L{SGQLMo*Dcbtjwo9!x3qbGabs%0~UhpVp4%1qi41ayxj|v5JHyL zw`?A3IX+zvEb5DIGAN5vT)d9I!c<38*^JuEBq*@fR4ErsS!(zUB}4TJr+>p#Scvh| zZev*nLdiecglE}e?d03*vMr3p^mIm9@3nKDG7d4b?JY4&^g;6PvawVLaARNqR$E9NjF93xO*k5P2gWmK9`|kIlUCiZf4z z!H$Onu#g7EOGTC3I{OGiI9&h|{!}kOoa|F_Aj=obPNB}IQ%f3OAoy-)*!eZhpxtfq z!pO&j@Y`_h@hk#uE&MEf<7{z2=H8=PX0oikH% zyX_A~g}zlf>FDP1x{X&m$Kg&4V%$NU)&pOXo1?s#*Um(CCiB_`~Ook-2Sf2^9G7WasM@9&kQ!r+>#N#P!E7ztpz= z_jA#OH3j+(xA79`f$^>MW)F^a5yD)>en+r%Q)$Z3swzB+CGS-jsOcOnXah z`UMW{kF%`|X)75y!8u{eKJ(VI;u`%z1oQ+lfhM6dL9uNKxk}F3$|UmgWaxq|!tBjw zs#HaQU90|<+mUmrHJAGIABfP;%Ev2Oiy8Bj6Vl;hxa{Sdp6{C2z-S_6(y&J`-heMf5MbMUv7yyxt87XNF=`-rO!kw>b=)*{fZ?qQP35q0zM5vcKW6AUK5#Jk zXo`B*!3Phi>xGG_L!SL~3tx`@YQ<^xDYI(aVTTojIl}RQ~kb?^JhM0Sa#n{KFG}qV~gG4ldT|+zp zVQAg3&`ee&Z@gzop7By$7FUhsxXM~1t~A-#A~~vAv@XIGPtxE`YqjXlYq%typN-O` z6$e<}t2#N9x|Lksm7H(#5+Rzd`)o=BZ0ZQ9aIT{rxr9)GK*qM={<; zH+6YC7K9I|4UqWbWfnm}EwQdz_Ve>gmUs|UM6BBP6_V(5) zr%cY*pJG)`czIwf$mlS$sk!J#}KaAP!(mfv6tbvnF7$d$)2iaF_>Eux(milQ!0?$+jdu9vN?#Xf%I<~ux1 zm$`kawVi2qUR-$ax^*8g?5_hBY(P2zSqUh%V5-QifRMOj>rVbEGal*$GdeTYi(zII z;&eq@>2suzWTQRGRQ18S!6N4=><N1(9too{EGszb3^3tob5ntCj|A)ASdz;FBAPr#WM#fgWQFYyG&tm{{G3cE zdt_BlUIL*ObD(CVCxZcnE<=w7xe#@^=hsAPN2+X9>jewE6QC<|@$kHeTL)8jK7Xje zdm2Vzk!wrMD=kF>y#z!PpsbIJivwS0f{OaJs%FziKM>lZ<@Iu}_HBXL>cc9#8a3wRxYA(@g?fqHlDDHQ$FIhUlr!_e6cZ0Mv{pVsrqg-5 zI@e|(G;{Qw`E=}SSNGKy79saGt4^ zEYgKeKX}f*^l1CAM%RCM-wn4-YEP@vZ6NwcnDXB81gFgo3>*L&K2TYMC=--*CFSk+ zC}X(=;=T+F+6hLLJ8utPCih|~J1kN8C3;Rt8iG@-_kihu(TH{a4J!B*p48y=Rcvl7 zs_FVQY~lKw67nk}n_D5;)aBJxL70pMRQP&l&t|`yrBXokH+OVslR9bS{l#yecfgbv zA0!zC%$g=5%_~y`v4E~MNS`wiLB7>%FFJO44Ke#L)+T2&YGvkR`97kC7=fn3n%|n1 z`8o6-c+%f>g6S7)PG+PF@7f9ah`wuO#EMs@bV7%^A^4W=%^5wpf&C#{H!qzvycFve z4nVib>L+2c4?8DAlCaZRi~K{YabVQRcrKf=Rz-4Dm2_mI%Zd{4UOeH$!vF>l ztO__SpBAub@ZjdShD-**tL$j~=}GS>n```wU=ia+_d)h`)tnumdw1*<=%JB@&49WG zecR_x<9B=~3dD8q$}X^abER?3`hN7S%lYHS`tjL-?SV@6VOcbLZ_5Rh>hEK`zv9kK#aBg>}plmUi)h?K1V? zTK$(0m1%soNsi9(_vGJz>5pCpPChTh2M3aCPr|@bZM#G9^lN6q=QU30md${zO|Jy` ztc87AxalocG-TWz`G7IfqwWjP-s*6zlueTZ**k}8M!PK7V_eUwBYYJm1| za6L9tXl)?zkp@lJscm3n-4H%iDq)5~1sm- zn%c(Na|ucgdcU)b6~?cQrlxQ}l9XB|Hsw-{8Gh5ECL8{*+MZg47bg#X&c&c0-^7qT zC*H&_@@twd)v~C&7}|?S-=oo8ZrwvIxW*nSY|pd2d`_)K=(oXob^hW0v}bo15Hmmo z1d}a@I_+ESbZbpYvAHzk#LptDGx8^ZvJ0f_%DTE2lvi9I*vHhAn$Hy5iWo20&HYnN z7iM|neih?EnEs`1;2aHMI$G;ZO|mEW$#AvNY7S{P54+eA+_Gy9ZT*`kb>je#AV$t+78iP?xQL{6Da?*CY9K)G+3ycC|O|zf+@R6kpbVUZ}s)v4ouK zzn0sTdBXkS_F&n`5iRB{ru$MgiAyZ(nau538&Pc`+>$Cx2x9V*;f|pLOxommTA!RcB37kM>MxnT7ydX&s)% zkIx7O`Ez{%Zt$OI`aNQ}T_T%-HUaFdGGJl?WCPdn%zUv3%PjV^Nj-S+6bA|4&R|?JPnBT1)fo zyTD#)F-HgKzZD?J$2G6@T>o>k`lq942sJ1G=pixj@hm#iTW2u+xNe(2wGmo^vWatM zEUE{xP|M_bO6Nwgy+wr|$9HbR&a3?>$x%2A!k~seF;#Am8UjaC;XR95i2_MxK-W&? zdY4d?b$u%N_5)?a5Pz|OhbOeGo4HjNReX+3p|LWr)e>H)4z79mrIuL+a^CkZRTqp& zR2lO5pebU4zzJkFhhBIw*|s;936!>qKYRnJ4&X#BM1Y}k=Y}!5bH0Bm;!H5R6^7sn z&e`9X!$Zq(^;1?E9KPi3XrD=@EbS}uUQqwvcEo(62=KsgD4_tl;e^&}HGa@=Lr6~k z7ux}5)345^jRTK058tz15!%YkZuT>EdU`tM3C76BN6@xa9>)u2GZ&-j1>d*7u7W?H zae6KgV}ly>Jxkw?wT7g)G-WV;Xrhna`@NC<;00c8^LDM9QT8V2R*e*V|BJhrB5h#2 z=Z{)zfUTqGm6J$FG(yQY!iAcqJ$66OV&c7c3X``5>lQ&Db6WFIOBpg&A+`}YnK+6q zd4v()jQzMFfwt|l7{Zb(Hy+o6(Z1bovJ1^Pi+-t7_xRMl*a8 z%ql^2+r`-YHG1rJa_*B}wf`jk@NDteakaQW@Cx8Y^zyOj;ToF3n6-4iZ1p61ei)8HFkw9mg47MA8CeR1qCNpSoZ zHtNC9u3MbL+xS^)K3oTmIxRy(j)6K{xRXZFuc1tTe+)7-7qInfl;kXg_@Uh3%1~p0 zA>J@X`YQ%dGF5>P(2;WXHLI8cmw6UZ4S=IO&X$0^g1wIGZchFT+qFtmSxFAe<5FV> z3mi-HI2sC!^?N;0TJ5M>XQwykMrJ=K$k^PDf7{9Sh$G!zRq(e(1UogFuYdx3s{yIc zSXRsK0!-p0pZ93%R^fC&Q@KL{^B1e(Da0w{;k8d(zaJ;K(Nxh4uKiNb%T-T8sEU4q z+`jskJj>ay?JWC5f3D(?J*W2&U?1)(Yr!rSe;eXlaPkcyrjm!V7|}5w_-rUM+*r2U zbdf7wE?B+(dLjaW5AGmU4SjrA#AHsc+A^{e617*$6dHUzlRe-jFNpUW%K z@KImVl#))Oum2J@eraMWRO*goQQ-yvB8!Ow%*oZ z4zN-jYr5^4t*RxF!M{EdQ!E{X?)f0@McX1ts#bX0jLq%_cER7lb|Ua(i*#Ew)(0~p zgDFA2s^&px$iLHZB|vdvtV_jf_FiyNXP#lZKc&E4 zs~Wzw4wxob>8Z=aRU2SiY%5hQ5ZIE+QQ_I{eh=e5`|{EvW;t6@NrJ7J9g$Bs?Bf%= z#uh<^FMTWK!szQuxcd$1H-eYAoeWJ{es97{tJQA39q$POp&iUQqHRrj6sC|=v(Oa{&4YAp+n!))ZLY)~EkbvM{ZiHWE?wm_=P%hPQ zEp@rCZ4NO9ev37G_~WuoIn0I-vfnRg0XMFnmYAip$69Zx0pCOQ_2~dV`*`%esinj@ zOR)eaj~kh9X|2;K7Cibi*V8RpoM}+!Cq6Z|cdOG@h{U!nPII1;@doQBU)=PZ3~J&P zjhoBSYT02bSDC2E(T%pe%80ut9tdd&R#u;UJm9l>ezv|asK?1n=$}8*>+tQ&ao-QW zz9EDh^Z7o!ZPjZGXm1>Q^*VIVx76yGKcV^9*whbSAsh<{k{KJ^;A~1rhDJUM(4Mb? z=j{Ri-(gBuO-z#x4V{+?`-#^1I3~i(+6ix9->w<#XZKzz&_(_B+Gic2?<7J%ZaPx_ zOog2GA%YtP+hcRU-2VFy&dlUHc;x0#Yb&ev)m0<@y_6ia26c%_1Z{4l)^R(7Qlj4$ z-_rokB&tCFYdXkIe#R8E;cfD(3h@F^)W_oB6{X4W(AC$U9>ruQNR{gIR-4(j?JC!u z4vBbzdY>;Y)+} z9<2YZ1f0$Lg->+`@gzrZqWenL@ zU+3GAE14qB7qM4d`@HCLMrUV_sW6f`>qhkCMB3+Q>E4^*%XIrjNIY0Qw=*l)_a&Hb zwFFRBkueVjp4mu9_JUm#wI7i%6QaVX+QY&sF^(T8R#nSXc@U}aIpdDF*8zg<8AnogADK?g5gW!+V%3K*pm@IY$Vn5wHt2c zUk69n(hX%P+Tx#^T`=Q$ohfoKG{V1K)n93dn)z%J*%EMZ8*U&FA}?m!%lp06QFexk zOwk(tAHEZfuIEiIzK7#dCx-v4mn(<#JiK)k*=v!^l-PXjIULCC;az!{`yze;V;vTD ze{WZAD^ZYc>MA{w;8*)1M+0mz%GPua1m6ccxW=A$xE;e9vhN$|Gp#E zTgdQS7{=n`3o+bylfiV>F!uIU!0syb9j55)LSWpUV!;*<)-VgZ zOF?02Als%4<*yx%@UP2Ut^)DLr-RydQZVg^PoZQK{(>Qiaq5Cga?D>5Aqjk4V}Tej zb^3AdUtVgin_Qp@8loEbok9Li?E~`&Jkk>EY5KuI4hJHJJQQVY3hq?;YX||=*39QF6p25 zKbAcLqflg4R#tPTeP!sVNo1+bJZLL@M1u!5c5<;TZH2xv3EM<*7-cjEgv>n^aBEIqJ3>(Z`utyKmb zhP_a8_M7{3J&HhW6}->`Q>XKKa&FairANu%{c7o5CK~9P%YefjK&<0`%`=O+d`d-2 z(?4(f+sW4i=^*yaF&{jws=HHNfh2rN_&T4cXqLDE&m`|OjOE#J^xviXMvTX8#(5GO z;{{~qv@JEihpCH#Y6d4CpR!_6?Owm|@7CE)Q)mSr=T!tQc&}GJ=s3HvQJ1ji1$*&QNa=6%%A9y6&I4cea)WgWG;n4nXsd!_QZl%>^}EvZx&S-84e zAStTJ1*%WA_P(?h2ATC=t{SXkjvsX@6Y|C(&9gb2l=QV)177q`uPTQrv$cN<8u<&# z>gu7OEg$%08RwT>z(@;j^3ly(bn^)vL?LmG?<=ih?8Pa=O1?jut%jkmJO7BuiBuMm ziRXWxo)*IZYT-(!4A!iFaQh>%#_z+`b?=EZ{>!z2!25l1^1`z!A#%Zh!Mkt;F0QHz z(v^}db5^DwCP*ygUL#an2N9)MrbkOshCXEF21C?@c*;`(u~#pWYFH>;v4U0$BqY$n zgR4(HVUUdO6cC{g23FZfZ~Yh$oy1`gt1-CzGqKo?Pmnx+IQ>2)^q+T>7-^?`@k^w) z{}?4pFe`jTFz>3Ibw7xvm9kNf9dg8O2F0O7uF}MzKmVo51fVi#hytkhT!L*+#>H2v zEPFI#>yJ3|Vx;5ex#5z9gTJ0uDVKQI7AzS)&@!MBT%m<`B|5)19(;u*j~U{6i6Xl7 zSzfHLoyCvO9oSOC-_d`O(}zZ>HBUj^iWxp?3{-j96Lhb@g!*d&3I#N9RWvmfTYa-} z;*0qNe|h(y&4JrP^y%fa=ImR9@3wKtV=U)YSeE0hon<0Hl$6Qx`9c{xzfFZ=YFrYQ zi)D|DaUvyE!gg`~b^m|ln)+!_VGGPK8c+9wB|-_Z)|V}$EY$7Nav1R@zSOt9NoE68 z?p``N%EJh+*l;s1tP1d*nwtacSMn9bHUv}XxCdAIks|iNmxbQb-}e2kxUrMz9ZBxf zUL_^8mWsX`*7b&O*O-XH$B3_PNAQ$7+qkyQfdt7hd|e0XyEIfFP5-7e7CxOgkkdC4f#=szmiBXCx++5RrC?f zRFHfmjs3C%cf^wZNl%=_<~DlqSoP%fKeYbG6m&WBL9A)%(vcEAII)<9wz-4Ll1Fjg z*5p7PTezJI8NqC=?vFs*Z>1alN>idJoB_95)h0UvzDSd8iJ;p)!ae}9iH~M-QkR5_ zZFUj$Te`;a@|~Xb3sUcs%)MsV<|gz=nRrODq0t_5=a~;b)$=*OAmCCV-$v2VgByjc_Lxr#^|eSsS=9Ngo;Mx55rw;egUYHxgRUAd{$p3 zCZVabxj9hzY?bF#(6KLH9xrV6RtZ*MR~>LGJHMDHqw3Aov` zTQoTO-IG;p!;M0cgSCCUk?qrT+G~-WyAQr?XOl|SE};K_A|d)}`TY*SGeq&UrAdO? zjB-zf^AlhS2y{bv%PX*zmpib-t3B^&qarKG7aK%S7*rz+NR0>DkPT~&Pj}qo4AxG* z5Ym@lt^W(&t3X8#@rg#-FE>4zBhCCE(QwnjnMoS2MjfWSx?N>OoI9(pBi(mEwFqW; zcbxe~UJtGN9FX`pb485hkiT5s4(;m*jF)jD=j-IRgfsE>yt#f`rW9*@{|M0&#|;dY z@;URuV<_RGJL~VHX}Etw-q*(^>`HbOwpf8GC)ou<`YjBVNMpn5w4q&C4(jwsH(m6T z)AdLq<|j2$iGO%Y9_M?4woc7RxtJ@Z)#U_KJ?60Ji8q<{q>xMI*RF9n{++15Vr8gF zyVvfyS#NhjOljAg8ff$#mj@QR_ zR|wDQH0r72>1UWtY|!;fG8==0@79H{?(FD?XVP*<@Bdq8+TdzTd| zg?61TS0A$9OL*Q02+qAv@wP?k9KZj^+otk*1vo9itf#2vH-C%>a8Hgkur*xr>Ss0S z^pf&>V!IuG!(jh&$&pDbt?{FIEcro+pQD&rn&by(rt1lr!|0pzaLN0rm8O2H2*%Ta z#?DuQj`@%E@=qME*;ZCuvTOf-vHkk_DCuu~Q&Y4oZEnFgpUKHdLTKR>{ECRnc$=e~=KgC6wDDqWqJz3_O z2l)Z2foP)+_C``D=7;}?P5h_2^=o+$H8^0W78as`g?cW?+=ej;xp?D9?|`t~9X zPY2So$sm`yfVK$%+gu?!^CCz~56fFvS8kHdxb9jHf#k)Tx$5!tyxHj&8uXegFw7qo zr%XO7M?T1~E=MtWz;M%L2kswCQbYgLesL7Y2fk8c4-d_;(?(9}yUX))H4l>fUaLgS z`IM=@GA=y0$;Y1y2)D_i3?s$MC(&UP!*W< z=+@%0oK4FQHIM^sR$$D#)WlP-FQ{PxB$V&8ASwfG)JBZ2VIJ?)Jd$n~!33 zKJG}ahW4Zz3mFu)s13l~fszpA+_;ZFX`xQc^k+PD>wy49% z6E*ouF*jLRrL835M|Jmu>@)|^JN^(FZ&ET`!v6c@OqmZ0ug5@4fj@fvUoXI&^eEH5 zk>B1+1ePi+cxO=I)&r@z!&&c^KHfYcLg_ldg(_BZ?vHd~Ht12@X{Da|C7VX)B7{`^ z5$8^KQL|ej8bM6i++NhT@YNX0p?qkIPfzFe;*U7c=?l4uj+8To{!}&8rV(_!uvoIe zb0)Is*28ulj>k_V=ob`$nVWePx88mx2pWAnvqk{D8`J-%6DdcNU&t`qWQ(dwqJR}R zB9zw`25*zbv<%xf^{fubq>n-=P+y=n9F{d*ua(-Ai1^$3^F;kR6T}Gb zf{9xn=M4e4C{b2#fGS(k?-WgpV5H081t37fzQK%~O=d^1YKh2$w%!LIg8{|s2Zc`H zzAyr%Z)8`|M}=+HwO9&r`2KC*cfWj4Sdi=Y{MqPd7{&kEHtMm7>D+V1l{B<6 zIT>R0I!cyS)ybeU6W8kmz8S~0XN!4S1Q=RVG^^Awe}0^v5-oiIO_oEuANKtLi+ek! zexgaYoI}@?dcg$Q@iTi3VDW)f_M`3M-bK6dI^{7FtqB$UgZHeKcF&=9Re|l+x^ZSU zY6Pyw8+b7*%2Y`4WTz;rJET!cyYi^;KaI5g75bFSICNbjFbBfb7AF&Q@=BFHmOa|< z_I-NhnZw)IRmfx5@#zmV$8!cY&+BSnK}Ou!*QHT5mHRGJ!> z#GJmQarmHa{AGvA;++^vQLAUjR5Y|y=s#>7v{ngIlE;GOk`B+N#~l@VBsW_7Li&1$ z*ja_WE}LCN_y_M@XqXO>`e1N{JNL4hkqs(7K*KeTMTL}SWSNR{>;I= zsY(MA0s%tCjc#BSh+@QW;Yg2RWc^928z;G3EGFE6uk0Z-X}V(cFUT%L_(!filf7<< zGlD{xvzJRy1Y~tKJUEX}P^2-oHS0yQb_5(GbH-s+Mx-=o27#9Se%8Px<2>NJ+{v~! znnf{x;+S7h;-7R+$+j3c-ojiI2^XZ`6ca!`?EYdo)IA^ne!e}B#gcL+TA00eZw`5&n(;5Uq>!PIu{aqs%7Ym&GI1ns@3Y3}U zlBVR#OswA7rx>Gje#D>ehY$$6l`1qd8ww#w4oR}29@ z8l`wB(L{8ou%|RwD7A_k44Uq2PM^x{F86+niF1f@;6{bc#=T>mPiczRmTs?gCbi>X zSe!!JCM1#xrwJ+zru1xpffSxe?2}%%!yO~;TRj?1SUI|_5BE}`zjrjsZ9zMXW$QMQ zkoZVrXK8!f$H%wiFso{uNlHe8i5Fm0hT2B*jRvj&ogF$dqUl71Z)xv#+z>dsjOD{1 z_5%VR)g*wFTT)^7L7FbI$}0h-&a6Ixf-Z1M~`1G_C;aiW5! z=|jweVyA<{Nip%{`AFHX=(U21ZR)>I z{S~!_;iSenov8g;8#tBVeL_17pICjHaHoe%sLvYH|I}WjvB~tc~aW{oc1sYh%#8If^5D(x|4N#lHCSonGSsW=V)n4#D>z zJJlb4br$}@^&tU+h#DuZ7Kn*zD3Mz5iCWk<94D}zS^A?0l2`T4uRozK9gy!|>yBxV zb*!!3n3E(5`CM(`*tuRBJ8knXQ;_y_49Z-)v(Q?9kvPDR|k0P<%IJfX6(nbXBBHqJ?a2_(jLJqHR+WoqL58E}sKmdPAnT zfyH;5)xB+Re_v8bDSquBWl&hG9I?#c$$%~*)bL*@Nvt%Qz6{lAi*mx99S>u1onQgh zN{#1Fo%|K;DfABch`Yd)5`$Xt^3NAZsN6SmHXYbtlnNF+9LzyhRi&@pz9Ll25qweU zK|%b!DLW+!Iz`XUU+kMr&c*?7s>>^|1dSP^_+X)>qq4>}dOOo|z`WJPsV=-O4^$+A94O1%>1 z8d-r$uTw*|XZVB}Ks&fZl+ghJrqon*{@m-8cP+8wP_yRE| zFMJ0u(G5&$1HE;hxmpsgRpbNffjoc}s=|B<8+u1>%dzsBE`dzk9O&|FQer$T*K;;& zQAiCC3cbD}N2Ge)k;)3PcJu4E4YoRCywh<^@no_+PR`A71m$&@Sdfe#vE5@Vf_~Ut z8y9|yK2BurRDlVOSTO!bXx~h?vyVHi*AtNto%x<#M*ICH#D>oyr*lUo?W0O>KHt;$ z+{oyVT1614S8y`1$;ZC*tA9RVG+4u!SCit0iE#+_IS|k{;l&^$XHtW$Y_yBaweL9p z2#Yy>*Ye|4V?ajt-~UC|S%yXVMQeX(7?fr}KpN>15Trv|k&y0G zYG7!jyFpMwX+e=1Kw<_4aA>5Fh9QS;Bo)N>@&8`ud^=yf_~bnE%-(CSwf4R4-&&0Ie=e*z}0Qz%~ zky+hI;7=tA0XfbD5f-m4QPg6=VHA2pr34sLlA_Z$x>rnB{%@cMsA_)1RF;Mu11_3@ z3t|tiji4X&i+9=_Z8X)`x3P;I z+`tX@DYV^EQlbDvqvdS}B&Q!=tUC&m&W5m351E8HXg=8Qi4?!iWi949u(Dy^i2dFm0)$Y(apKDO?5xXDl063{EB&Rc^u8*1AP5PtGMvHccaLUJ8Wq6 z*%X?rZ_1_`CJ9(=aMMrf1SY_o2oLSNA&KBSMR%Bi?(fAN$}+(kZ_=*xJJk45F*3NWU5) z!w0+m?xtOx83LEati=3wJ-9YrJ!7D4p;)z?sNnY)r=R(m)Ds$$)fPh*0#%bS6U3)Q zFTPBrn|!pN-MQ8NBI9(B~yL`qNnCJ)_3MFg-(p5 z+urm8ER{rH;6D9fCT$71Ly^aE8#lWwlp>7e^J z{hy7WB)g1Ay1KfY841MBhP{+=J$~^3uWwH8?c;L8b;BR>#fzg^$Zly|cpHJ_-`ya3 zis|F+(Hc*IubC?qEwH^mws|3^M5q6n1r9cDw9xOzQunt8a^MU}^}kkn z{7%)}?485jCSTrz%U=~X)Bk>N1cLv<)9`Ib?(=TL-5^q)(IyE#M&nVR*n(tpIjiQF zdEK?Bh1uCx^X)E=G*%?Y_~+P6B9ud@S<{V4*Misx6Po60R{#)XdzsRB1{+#&|9+&6$r4R|#fo{AuG zO-M{kMG#T}6W5Z@mFH;jTyFdC@yl%@(0?b0tFk1 z*D_=Jdl7=L)Go>TfM%~`Dc1qLxPlYSWIsgFeEO4Z2lC3At-5>2eV;rO0f%Inh-Wn! zR48G#N8T#z50#7_dLe`wp$;#G&*No3Q)FjCuWnLp8mCcEy4Re}-@Vx`Gdyky?~Y+v zAg!sbWl?UCkzpKD5RK@#PgPqsHH03xV5A)zy_bv3SRXEXkBN^ zYLK;u?AJyq@%&3pa(*PQA9|$J%Imf)PdV%i44Z2V-M@EFbAgAV2U|hh>JVpRc}8Ph zU(ugCINFo}|Ko(F!iAUkQnVS$3%D_1#~LG&(yqsrzb2X%n!HQ4zud4F$R`d*b1-k> zzN-OO=#sn^^;~kLZxf9*f7TaJe+AxSV=lN5#pEE9_R0!vrwehVgnu7~kRuo( zO+x}7|mi=X)@sj(!)ZAIR4$2+j zVVWh#@)erC#(M%%qUbjKGOzH3<%NI|4nYx!Cj9bLHkkOupNeBV({IvCulN2enPk_U zc5_J0*T<8OT6Sycs7YD|O zLkbG%=ZnK=1`4t7gYB=1^|zn#!E5%yX?kwe6=JA62rOEz9<0R>tEJ_4zwZOj2JBF+ zwL})&M~%HjrINB>lpx^XIp6J#EG&{uh)stxM{ME!Y>!~P`W)lVh+_i|Zw%e3&pmI& zp#aNSfNSC|_bThUDFd_Mb#RcyJEeeXGMY#^#h;2_fp&AhGdFIgC(z6QM6qc=)2$l| zoB6H6S7u0H)yw7sX^d~}bsnY(tZp(@m|HYsOtsz7)pX|^^ZxX#XZ z^_Ov&=8Ek%F*3-8+U9x-ixJkVW^T``71jsBa5nlgmCw zzMv$33SrrVdi6A$vw14$qIM_`=aG$*EhR(vCqov(cJT;H6(x+xsN(K&S{L3ui?9tj z%u_c%FA0{e)X`L%(#wb4kCkjgNJx_gRcGL`o(*SS{H<3Uhv@u=qIM9s#YA(P1{_$f z+WO8{6M9&Z8YwD&_j5HNYRxgyi)>zh5V_j!%Rw}Q4Cb21dy4q*a_aL783ZpEt}**A zaL-_XK9{nh47eAkIIyako*mdU+;fTxr@7bDUM%2b^^KGkbSCb^P3O5kB%d7p62@=& z{l4-2_dX27_>^xz+n@%4hmTo{c;2wG%`PO>GWV@ztVTYw>{z6|d;L0yG7BOa_UFNc z!f()sd>h_`!P}fXGql+foJD&2Xi0T<7U#@YTNTHj)CF8FAVPBox1W7>BI*rOS9)0} zzIt*PscD~C{~@PZh1X+cVi+AajI;$#_ne;IUGalvxvZuAS>#EbDvo7C>AiO-N*p&@ zrsQj#x}#6IO|L(Wzxw{`6Q&ke34Y7cwC;P9#Wr~_C6_DmY0rK3ji^dk{~6(?FiP?r zQlF5WQv^7g#(s8AR$+x>v-(MAm-8qNh8F}!T^ZB*2rNkCf-Z}f>3YyF!)W4~h9+t~ zJZRn;XV6ybP53Bgc>dL`QJMk0@H`$B3{5t^bs|Jv9QJiYkz;qd_^+-~5T0_j^*DRE zW}=W4?D|&5$mbt+wwvxV+h|HU*J@p##0GMmdgqB9 zpOZ$IDfYq@pzc~zyC$>q+XzM*?biBsh3sV#$7pStHuBC)3-TrCiX5ffU;@B#%5A|9=cSI7O^^c~Vs-wcA$*TzK512#3i0{S z#@Br>!u!t!ZfZ)h-O-9;l|VIH`i1TO7;Il}E8UR&&CKUI8(L#sLiddaaKXcl?*?hC zB^dN#a%4vox5#I}UonM?W<}+wK(zZSjI*90I34H7A4R~z4?Ltl17(uW=zJQC7r)=T zYOm5in&0Q9CA``xac27q0vA5&z$;@`5dvgru8$QHip;HghUf72A6>g-b3{`p2{zX& zZXB8dJ4SZpt;-kxx>_JSP~lE;=T7g%OtcQcEm2LaHAY3g?6WO9?Tu8v+HEyX9|Bt} zgSZDXU0l2QDZy%@*)c=&jCCyVM`RuR_gbT0e0aIn{hfc>731V+y7VZ8-NQG)1bx?L ztH6?&)5B(|v)Rn#eV4M|9gZOXH7v>-d2vho zu;eRacxkJ(-@;R_0I~?y9;4+FPNP;DM$@O3#<8DWyrCaI8WK)AGgGu|@bWw|7MVDUPX-y4a+`uvIHQ@0SaM--XFkT2zS6)6D#eQG(zUsIXw#`h}D2)LS zPIOF-xqv^>)m1=#kV-{I@c0qud{HJ@WG|AS#akvy%c8-lV|tKY)zZ6|7dmn9j0S6Cg0k9L5qhQcOe1M zI|GExFu-OJc6$?eDWk;@X~={N8kE8pw&P0HTRCtW`smK@J_s6sj)wcIF7X?~ZQR_3 z8qWh~BeaRxo{Vk3!V|WmMX>6q@q{)$(6MY-(+NecTHo5Y@be0gZIF+vSU7J5InZN8kpL^#0aM7jU?Jqy~YM#bm37thR9Sg`q z*ASN!m1B0FV=AnlJB_=!dl0I2#(_fbumA;J}mjHdYEz%yb*hJ~2LX(h$rcTB*!Fb&luO%tv!EaODVGv#v{(1RV?Sxa!UE+uyj%&S5N6;UL&g#t zM6krWL8R}`c7SNDoux3=VyA?%g*1WOV4QxPzlaEyF1iOEFC~6-|1`<|lcB6Jv0oc! z#?Yr*ID|YbuzcJ=VJChA~a+>OTQ&;le7I}O^k6sR(=Er3gIb4t3m?L-GJ zdVQ>X>&QPvoH;h&15W&mrglK_m@0wKT!2uD1L^ecW5 zDmbcIRg7Mceqk0}W#G)6o{cNS7CosbcxYN6HBD51>_~@DBq|YWH32@YZr&+nZYI8(&^YpjDWUy=QXLw4h~AjqzE2G!STB zv*x%VkC<%rV)p`+0f05Mj5R zvo?-#;(i~t@P1tA4pBgm3*MA-4VALWH7wxhA*4nZ%~g8ewgJ$`1FMl)(_;o1qaz5J zP7ryX4W0KZGwpYI9^5RLsah0$jdbe0Xw(tY0dk%KkD1=}c*^b6 z57(IsYEk)U<8$V3H||rdHere36kx;TAmFO+l3+F*WT4}S8hCAjdgH*3UePGwuC8JPJ)K-)uabJr8JLVbS>cJcK+EYRjT3hBi$8=$^mJ;7@orf)Q2FlFjh5wRiATEF z(GLasZFo8Hr|8$3Bd96qc&x{Uc7m`ic}=1^H9r3ZABowg&i|tYU{q?P1P@cd4vs$} zfq1Ad+$wPVa5QT&v5dgN0UKY&$+W!}L(cmJ6e$xY`X;ZV%7a_YFGfV-Jq~M0Sq-BJ zDiN9JzN`hlv{Nrkj!8PQk^a=dvY5ib&D?GO8oV5IMD_v{VOe%uK7mTlZ%_7Duux%} zjgyND8q4VqRyHGtc>=@;bBn|ci{?z^%VBmLa%ky)WzkbTZpnw+AGxZZJk~Ron#fOV z*}ybl4mIm}x%OkbY!^0MXg%_!-G|AnPg*Qkh7PpaB!#UjQqaTfPANW%^Q)Z79Xj2# z3V_Al`9Z0+xH86(3HO951rl)Z#2k8A$^c|@yP8$qr&6+GanL{r|7&8DI?Ft^#I{UP?c0JDq>5Hyb((SWQaO;?IpO9Gjtr#U4z>Kpt1dn_z)r)n*m%s5!Xk_3U8YXSYVUDPUvB0p~;LoNI zg9mR{o1VM$F5n7*A)=18k;^{~?L%)v^} z&8e|BT2PP{1r7w%20Cgg4a4eh|GVB?A4c+)Yq12;nNF{qktE2_uV^*G6Dm>#72+nw$IvNn1_2 ztE`lro44_?LHtBels!#za%9$(;7CZaFIo!XE6hb4c563x07a+2OW{$B6?iQTn3D8LFmB?+lRhB96IGox<{h>f5_OG#2D zeM1LQz2pad9iMQnrlB_FX6h|j-Mb%B+f-yIGmX>NXIV=*Gp$}FMZJH_kNDtAsn0*m z19757fNZoy#j(N444PbX4O6LjmD@4;fh|6c=}vlDMPExYcw)?+Sl9&Jx_|0)Z!|@m z`z%Ytw#*u&4IDsSJhLR+kJG)lzxL6Y6 zdEiQ++>~gN_>m@TfL5NPRKL|qVCd?7uhx*7QZ_CGMlHG60M+ArJ`->P9Wvd@VTG=) z_o{N?8gkWSTL~+?vD4DSQf)s1H-CMapNi7QtulynuTG%ITFi`7s2 zj8}xz{t)Rohx^5>p&B3DT1vA-=UL1ls*rZx6<0j8+?$_gYvjjlaLQfl%^4N*>-<9` z#pI{7li#`bm=vUAiJ0Xg!%H~|HEkVXwC|_o2&vahw+FZyS0+^#z&)Kq+%C!Htc_#D zKto2Kve@d(<=mGK|i4b|3f09Ra!kzyr77_^m?hOeNfU z99iNA%l_m?H$m~;(+PXKPNR{7M^DZLT-5kij`3k?v>ZKADf zVYMxQUhD4ad5Frl`ivilGvm~znTm{x37H=@noNI}#Rhp_>$?w4Bv0_?|4WHJV;(~F zG;zeRuJw3`^ad@aNMld4r+15x3p(P`qfNBM=skBH;A_jKG#|gO>!((&*ucE&A(qTdN}IRZkX$J zQ28luY*(CU#yMRK!9y1}2Db06oMb;_$i|BHFw(1<716gqyJJC9=ZV|wNt^ImXFz7|#MkQ%PAEN|M_ ze805-Bv(uBe8U|QGM;-%WqoV`1c|8Xh{vN@v9Y~M5r}s2r)asL3jr&DEu2 zFaMR?a?luN4`9w-Q^@qOpfzr#mr(D+FZI)iovnx9|7dE)(7P}61(NB&)lrt1$bO1UXK3AFhN?Sz@*zPKzNLZ5Pm z1+0`FIUBN191D?0e{{*=^~ItSLgF>3z814`uJ1&1MK^rn&jzweInlHvza;ab+$`iX z?v0%$1KT<$y%9%OsIhi(=4 zPYsiriW+qXDLuB0^kJs)M{LdEw)V1Jyx==FOSxai9Fg7o+#oUMF&&HxUxkeomHO^0 zo%-b>`bWwOz0$j6X;>S7!aYV?{3slicS@i?M5)-T2-`E?UvI3fyU#MyV1bWFR#o0c zMoFEaVf)KdQE%RBQ;ygU1nX zu>k+;r^={@&3P{>0PDiEbY)EaBQVFZc?|{=Zt*e|NDfFaO8NKA#ozk%PaH&d+F2D* zQO?NT{qo#LxltJy^7*&BvRz)P3sREm$S)j*IU(c$uj>jva7^c;x~w;5Fcl17q`xs# z&vo9NfF>+>g=N_jJ!ag`|^{om=!1e@rvBw5j9%w($jp-yS1W=`EI|u)5lM&HY(DzYb{xFO8 zXY)G1-tYbgDkbEb&m1`vX{XM8aGHJ@T9++o(FG%deaAc+6AKdk*(dx6*%PpG^P~45rHz3P~8> zA;YO(#AX5tcpX+sZbzSb$#vhO_Z~c>_RO#2U12Zm8K~yZkvkS4J8DZrNgC+--S0GU zATVCCdh*&LhKWoG=gs*Mx>zMdV>$TlR!xpnEFLY&;>Oo(FIn~gW15N zpo=>xH*BSc%f|CB2=`K6vgJr5_Ix4Wbg^>Q?Q7yC;Q8En#X~5Mj3Su$s{)Ruc=yx9 zq9ti#N;VvSE#+E;QkjWe=T#Lu#D%uVL?GD**Quk48AjU6$kbaU*5a&LX(05vnE4}= z*H{ou9Ia*(+PcKk`(fdQK4z%(&ZP;Ac>QVy{$k-@PH4R5Bgjq0SZ7`~wLC%s zg%~CE1)gi{rsX4D+o9zMr0Y=qr&ro$F2tPjSR@l3j=#(wk`Pg7&^hAiBMJZ{LV(1E~#JJTjO$)G2g#y4hfan zUXnz=*|bkJ5s_zxa>)Y(Nw$S@E@(%2ZdN*5X+BKs`HU1Hj;paCi%NCgD{-?^>EuIG z)Gxb&d_3bD>*{&4Hi&z5t&6LhwHCcE-@LSGFVwWM-PHE{z29IKwbPy@PYQ*wfmTk% z3ydHa)O2I+=S^w@=?4CinR8KD75L|0HE~uP+F%9j@^7k}-8h6+VvcGT1u# z-4p1LQ=%BZMM;LS5g|6s0st4q&I~@5ai5)m-b6fJ)fxoI=~-)k1t%eMglND%6IA+< zUV$y?8u(}@O3uPjW16$=igS6Vt?Iyn&(2w7FR;%X#;1AKK9nVl)_MH`?{^zk%A180 zEPmbG&=NFA_4?@F?0E27l^CY;7&gPR$-FE%+=&GL<5o>W##hV*24at~6rN$TV@3_~j%d`aDxb#fB z1p03^)_onQNgPTk_vyhlujOB!G!s;DO-B?nKbiE!JTuP|$H)-PzJ92S?)^a{B>2pJ zcctv4nVP8f`ll?^ktx(tSz{5l`*GN*{*B|k&~GdmoPl4D@3C2Ze3v_I(yBV+%ae#} zXgJtHLc(_0mj$yZuP_Vtpn>7gct|r8g4wDgI5h!SkvV>!eq;^B6MQG*YSS~?J?g>P zgi0Md!sJ5d{paOJ59Ve5$W}TIPgH!b=ZZ$g{n~6380;xy1dw5MMTN86_X_za2a_&o zd`WnpsSscWy3Iiu_>x}=wh5zZ!UzeM5qgy}78;DjAr(wJvNaD2tKsJ$8Ell7~6 zdEYHN9a_VWM^vQR&HM5%p=`x?zXzUKSTgmL$1%q-w5K*dAtOHH5LmTZk4Rmg^c6_X z?>*^bi9DJYFcM?9S%u>38z9?0;=X2X&Pzq3Mg07^MQSc=m&xvZ?IHDDm%ONr0(Z1PDZsNS=#( zAa^!|EA;JK?I%MeLB(tuo=_0M-2_(;>~JRulY&S@U)ryt&sid;ORh-q{3V*mbD9UE zZG`9BFedpMii?<=u_=Kc393V-hnmP8=ho|%)RI2()s=F}=wL%L`x#_)hC=FmKP4w5ZL*RdJZ=5Asc*R8@NNNvN%yO7IHRbNPp%E zl$98|{DAuC2C+}zq$w(1JK8pzRt-oGA@6Pz-B*DHX{fd!M^l7W&!pKCle%COY2Lx@ zA7atOrbw-yZU>3w3BK7>{wafc7_R(iaZypdN5#JXca`I6%_j)iRO6b|qU07(?k52B zB%Ga2h90{{q!$eF8LOuY%K-#YubYqh~Q zn3dTQ>Wb~_Fdh#-Xw4N_LfWls|V63n{YInR^wRA&5TbjZKwAzp;{wI zex5|Hy5MB>cDz|z`X12Jf71d~nEYg&R@7;H9XC0A^N)c#8z}-q>{8N+D zAJ6){Oe`tHp40uKk&cb&o*>czXjwP*&rbk5_zez00JgMj)G{-XkFhN$z}!nF|?GB=+2xXEOq9+Tp*KNtB6?>a;9Z? zumS*?Aj02nyh`Lp2nj;2$?Q!EJ3cMA@|d@!P}qG3@ZI&OF@0hp_*~{-RPaj`N%s&D z(#Brc%e?1G2yfo43R-Nc{m4D5(FtFJDnZq-u&|R$02KpR0Wa2jC0y3>`)xvWqAgMC zU4ct;a{;2jm;LetBf%g%WdFP>>5bW|obc;OgXcKmmF#euxwJk78L~e=$d4~3)dH1_ zz&18VZ2Okho!ox7a3tFd5Km{OO0QoNbcS7R^g`JS+vgv!BG8rcsR|m>RUrAyt?PBs@E%07{ zd~M)@!I_?$2K89#%l)f4EV|F_&+2Mcd{(G#Hyar>a?dA~3CquYx91{Vp=P|Yi3Vvb zo%80)pTf0?%NhSGj2a+7wMOXIGX@mR%=84W(esAdWqRJ8AIkRB&Xj>Zmprczzyt+Q zbRb0!507Wd#byBIrs-zH;h}jbaXB}QpG=xgfBm_%9Yz;(U{Tdu%m@@0Gtao;1@HTa zYDQ*SnU#s1Ax_5dE8A7EBPB`q>keehbm?2tq(ZFsz#$Av!tB z?%D=}ew}kY4g1L^|Ni;v?Iug-Y*{FcJ*cS6^UoCB$+!zKDy^Wqu1zJL5G2tSyFh2% zr|v&B-;T!?jfsL=cqmE&A^{}9ku7Zmn(@JbHpfq&m^b{Pc*C^5DTTbhaonI2%Co=` zTY%~16*4y%UUu~LZ454v#x{6Ja%X+@3(1fO}&} zsj)|J`CEsW?NS8g6%+o%7#=kCOnbnV4#64?S+ao9wYVhEPOa}4MVU?l3%6%G#_6$d zREJF+xmq`Uzf-+xu}JPPd-h=S&t@9OgnMP3@POAbqIb?C0-N$vChS~5J&S6#G|(R3 z77D06ogMvcl&wVvt+7JAGcNpEBmPh>QZ533weDUceT7B*HicCWGptg^)4L z%SEc7Jsg7d>4;w~=Y7cMC9kyizo=p)06FZ=oqEsQVW)K2d<;8gI_WbBvZnQCBI?k* ze|u*SXIj2vQ7bX6oVWBVT33V^4Sy4!Iyofq^hho$u0TF%apG-Gt3(Qlx0jnjnITF_ z#9URtr^UvB>qp|H&qT)S4kW?L+FE*N{9de0TWW$8#CI4UH$w26c5y}Sj2PgB9;1xY z(*8#}@grY3J{Z;5!S2xgjOVZ=4(9gA3`r}liuSc`B><6R;49APMFf*7#(mCI5FMZJ z4mkQm`;_dcDK3K4hIoI-aG$uNF)-rH`tfcq-c>Xn;OoxG#i{4XOm2x#zTMG$B6p z2g5Y|yvF{LWgi;v$^Qx&Zq9N70f9}PLqYa<+s06vl6meZFaga<+!}(yr}563nDO!9 zKFy*0@5iz}o-}nk{3ck@4-`K*_rZmYyAhM+8rq`q0q^yJLaT1BA`<=<82FgV(E0T4 z%fg*(ctwS-AuXT);+f9)Z5PbY&wCQE)q9#b*g{y9M2}m|&ol>A6SJDFxIK#po$kOE z`c;^#ex}?|{INP6P^=p!A++%ER8;yIqV)ya5;p{A4y36JB>;q)7CrDw3u zN>D}NZ_!=7hTctRAh(Z8wNH~ytD=f%eUy^9!kkPfS^Hr?>C(SMVLz&1uvkL4jhO8q zb}o|<93y)$P~H7(@U7{O-3Av7E@=|w8kzDWZKM$B?CcEWDfzl%#8TTODs{g1-~OjC zHtVQ%mAw@k&1!h4(_?9xg^r+YyKCT^o9`bO`iO39z1w3z#Irb?M^V>qY@t# zggA*8z*C#ss zY*y%C95Zr%=wst*<3)6|lp}zmqGyJVl%zoIg)%lTulE?@-i&VX^Vu2g_;8={3+4b* z&#r#T)v%U;>OE;d2lg|dj@l~tq-R$~!%dV_Err5wSeYWNGWuPgtWm^)6YdFv=h5pQ zd|~rEm|mf77qh>a{Kf!Nc~i?e;sLE_C8L(Y#eM>7;ZwHUY>MrBz3EY+rJse^JN|I7 zl}43MWokVRaVh zv#~W|C!1ZFY821c;Ce_}_|^K3gC5e|sMr1RycRk$QgnaT8((Fd0#{yfxXN~CS_bLq zOHfs=Ma;HP@1;ssCN=KxNRVx*I0H#w-^6TlP_dEo?`C~M99$*A&V3%&NfNVlPna00lMzM%5LrI? zjQ4{Z+any^_Qb_ax;%>iUoFQ2QJL_)-)un^qa19vrO zK2ZV;+16~GJ-qcn^klY^!^AwTJXVvN?cZsWlN$p%_z6pqbd<^>Ve9??^s#|{gJuQ= zIEGbIe>|joPa3$c?A4h9i+ScISyFy=N$aBVBXJgBUqT0;aslV4XgV5G@16UrX_Opq zG}|g0I6xJ>yDh=U`>Eq{=7X-v8VAUO&%UJf{E{@_@l5S_yjFdaAvpbqy5B;I{z7b} zjbDr(6blTF`Q8UEGyhXU*&RBwQt-5AbCUcDW(MwK#rk>M8wq>+qts~GN@}$=eBUk1 zhf3yG@@ojWnS2KNQT}R zjh`k;|6o`On**_b94Ku{1C1*bw#*rNrj>w#Dii$^2I17SI4^eY56~)9^=i-Od&TtZ zfBo5d2MZx)TbJMQVQ7J?WNoaaQ9uFZKh&&L5!3i zkRkzgC0ADQ%`I?X^sv$Pk8k3HthunAue`h8uNY-E&_av_bA3X#=e09QNmTn>r+Y~; zkWaHoj12%KRS|!71INE|N_Bq?(yhwg_lT`@k&?`!UeT3%JB!MDxDy_4BeJ=BxYWkj zVMCFWlmyVh;d}mr8(siF99W(Jf%_loS(aHH;NPvUbNcPi>IrO86XOHe2e!e7ksUVU z&Tid2+kj9RZ+7Tx%D0VI$Py*H;P;qFlBJ}lZkA`Cp+~UASF^3$_+1L^zhk-~l@dw- z+=Z}}-Z?n@Z}k{UT>(X)RheE)j~QjX%^;FMSp&sUz(Ykz3<%>?!6hQ*T9bksKO~Y` zWc>EgBl$A0n=6<`Ms!b)s(_G?^33@MRm*1+6l8If2~PkRcoRu2NJKW+`V8P7_h2wg zG^$EM*2SCRFJrGDV1eZMm1DoMwi%#ovukUW| zWxO8Oh?ph=BQAkA$`GEsg!l4zrQ<&FatPxx3W?9m9#2=CJ1sYq3Tp96pyT;h#i8B` z{pO2-kw(AqQ^yp|&(4Bs4bfx1Z9Mxeyt@q6m*?kzISSC-qE%h|^oa}87KC8eGuETo z2VTE?VGWP6b_TxX45C2{JPGg_<9qCY)?C0=zJHOk8O&N3Ul9;&5aSo|fPvS3(pXUe zU<<+5^(HQYI^kR|gc7 zA-%3gKwtqCVWZ7)2rxk!T6Dh&uUUJxYV*big%$Y}J37k3zzV;L$hDXM(hFNzxcJ3s z5CJu-JtcRl5hW>&m!_O^W2ap;F%}X}C$gkLu|`$S1eP%00m3=Bx!D4aWYI3009DZW zR^u;vjgx*AC_y0T0I7@l6U)^}f^d}o5tP!GOS2P=MrScuVO#aDg5?2OwCwq$0n&37 z*T~qouDu<)pw9LgSXTA{0Z5ZE!Avb%XXk(OOaEdf<8NSJ02=~85z^1B;CmMcde9q@ z$1IMZ2iL0ZZ^8<`J0y0x0|!CZC^?58+w?y4QOZ1lMLAL0&Avi+TK={=Co5h{Z1C&5 zgWd?wog4muoqXP^ppamq2gm+@cb0pi!|n_n8!F>_EYEG%z3OF6(%TJhur;k znWE4mfju`q#<>~#dn>@4uxoO4_%|W!7I4{gNhmAIoeuh!(x%FRWlJH+xMX9@z_L#N zmqU`ur~2!Y8l`FDU7pT1hfpFYg+y#zgOd&PjECx}d2@ix0-|JjX?#~bam8zDU!WB`>*4SXkH!EQbDPyNrvQP z;$~xlpbJ~Mi-VikNW7Ue4QqvuO7~hms7RNokX+hbu1?H`Y;!Wx|GK<7Q23VEQ1-0) z;rgTbtHrf}n6$dk-+JAznY&epZgFSe7zH-66oqIkCCO`B!mZ`}k^t=wfUd1N$#PY! z;3i$)$HlhJ2-qa0MpZw{Qx?ejq@4k!3;Jle_1zv_o}mmM9;F=!?m2PdI9oNvk5$2q`YD5jMCnOU>86GvvNo*ld1Y1n$Y_^sPt!9_**rovzW&=;jVB}=@)zg!z#}+1?l!w-bz+gg;<`R8G3>B=Wb2{KQNOkq%2Qsj(0n5lEjdHD5kfNHb0v5Ya4V z*8P3|7ZP@zpm*mYdX?XeRo?raNAMm&t53-Ntgr&K^G%e;jil6$dCS)8>9N0)!Yg5a zPVmr^f8&;~W`ynZ@K{xA|B5Ljv%LPPlzbOI-8#Q#1JNG!E%@Z2Q6SSc{XoJav{7+5 zH%WEWe`N{~_(A(IjNy__W|Y7|&25q(3Gx_uGmSpFqzkLcYw`OC=Xv*F(^QrAMMmZI zckV)foKD;007Uycgp}Zz0cpX(^BsIx6U}C)gEEpf z<~t9@%pm)Yg&ZoLTzE-&bDYiRSI`)B`j~_tVVXh!=&O|?)E1V?jtZ#|p>b9PT zl7<~$fPDhF3xY59u1>max8EBIz<-Y`cu`qj1#!gRT!%&c^?B^NOmw!m7l6Z9IcPG9 z_nJMyB9w~7T65JPO|91dhN8tvA?=-PWLF&fn=>YOm=CS{{p{Rt35aFO?y~k;>N@I| zBFrt(#XzQV-VF0%~ zokLwjMkWbJ1iJ0=b76D4BG&$Ib?9Clh>#*ae0HaV%G8ONav_CRv_hk=FW1Jodnq$O zaxCf?ipa{vTgdIkw@`qh!jf2}{P?&3@ldf4t7O8r+x+D&>rsu_>&zM~i+nv%Twx%C z`qFI}%uv7r8L4pn@>`ns9CO}{a2QV5(Krs%^_szK*zKsO_u1*yTCvb}<<@cB-?g+8 z+kv!n;lJ#mzXnUBPRpsUD*5T$u8XcOpd({gsY~^5&0KhrSF4Vt%z^ajQGGC;0A`j8 z=H7Jqd#`T^S}QTS=Dl#qWPydH|rhH6Q)%ddgK;TWdZcvo8i3EevsZIxsoE+ z;8LKaMtUCIfS?!?k%6>YBGrrbjKG@AuVK23xmk(3zwtnw&nL3-yM-6BRl!z zU!UV1%HQ1aJ3s7MvSRVNzWAt(yS}7;vM_PuOn-sTsW=}~7PcdK(g1Us0sTgC z+EoAfOH@t#uaCGr;Qp_Ow8v4hBf>)F@c_a1THg7&Z&i(ld{Y3>76*L+(qtO&0;WN^ zN&+ImPXq4X@G`Nmzz6Nm*5OrDuu~;U1`7hlEa{b#s*9Zar_Q91E)>T0;&KLhv$>!1Ed{&;JF6H7!l?J8 zi%hDwtd@I-JQ&NG_oTu^Q`HOiyT%jLMOYT_?wMKy9ohSYhmvlSwEq3AdNWq1PAPLE z#VjWg|Nkg^?{F%^KYsinBnKIV2w7PfWs?z7w#;(uvOCA#TehT>vZrnGkT4wN2Hz;ola9`99Av+5hk z$B~S)KlO=o8;*36*SL402VGWraTEgzGi2T~UGlFCi#GCQ+-*;)3ugQELSl|_76Iy+ zqpWt8P6wOd^-QKDCCKVM`#KST9H2Jz$MeEp8;d2M7T-K>-YHE7HLERY{ zOkawNS*RkJD8jGxa93@usC)@Bbeb!-2{w!<+iN>u)d3Oc?U)SvbqX}qU9Ua2oha$X zaM{E5{a$;wKf=O)4Z}9Xq8>e(X~*iN-4!{ScQ}$_Q4`9vUzN-ErznqcX{20mC0>Ao zQMabC`KpmE!oQIBdg~(6b)q?4Mm7e?HqKyv-he=~WIx-4Gg;^1G$9^!jVPF>{mn(qMaH`LpTqmCin1Vf0vwLDGet$b ze=!&{a61^?HCpS&2l}yqFWq5aF#o-fyVJ1`fuwTuC_^=b(N)hU%MhZRdb*iB#KY&7 zLpdjh9}l#CaExz^-kK5(XOs{O;XBPVZnYGU;kfDlnz+dC+}uDY)$cfZ*6!4; zJFKl`n<;us#Hgd z=Jnrx!G0%h+9ze_2UnyHtnkx39Lc;I{&XHlOQi%-t%W#nN;=@oc)v-+)4uB_ z67xewN12-at~h%@mw_euF~79*RmJyjI~Tu#Q=Fc~Vcq@Lo`eLi-ZWBL`~8~8Dq4qE zHX86=HmUu}-A!JXT0CJx6Fgxyjgdt0K;lTltX0r=0CQiwdPZ{37!0|PtYDNQH#zM# zH}F0z-tIzCYd{(*bA6gmjk;OHX+jc{+p+PG0WzblNF-NETyTZo3=PFn!C>)SaxacrTn~jN599>!SJSJ%}Zb z=##w`XdU-XlH5t@KW{YzxuxFdusmY>4LTHSByY`yHg=9+Z?_HQOqBC0YuX zTdr_{iOr_ZIuY2c{lqAL8O<`EK8OR2L#<)_h}W8awPfRL<>~OT3n5ByvLZJ^8t*^&CaL~6sBF+xIOa;5HCs)m_KCCB-7}6^LwEq zdf{6*WgGJg0Re%8#Ke}LKYv!bMBX%b*U3E`e-Yh96hHI>@&D!oDiXgp=rJqkIT59^ zmY#eqvTf6VtTo|Pxg9hCFbc9-nZ8Pfi*C)rtp9Xt-dU~(upe^Yn(j|(@x0&JqaKrZ z*DL2cdcKUy!nBLNv9~(?b2w={mTV8Q8EIenZmRDjHSUY+ihuW49*-=u?9o^A!*+J^ zNQ;SugQJwFz2qPJ@Js2Z^eju9$$v@y9M?hxTC}7d7*zG8)GAhs2I)?)V*#4h)=jrQ z8lvC`kL*1e9i3}L_{uxq)HL$53S$mqiA18lmy}0pfMLYNLaGyvuU!CU))5S&wpq`@ z0l`XSTZCVdhSRJlg!H@>V;@lMZoHWc(`EJpv&f#0&Qsg zu4UI7L!#Q@gkZQ+17ZVrK@BgS&$xYbG{JV=w&Bu9=K*Hn(fLl#obyu!R@%TX-3x7Y z*btqNiO2sUA`@?q?QAg%dKu~fOX4RDc#FyYAi6Xd&aFrRfHPpwz|bimbJ0LJfm8RT zun@TQza6X10`AVG;tS*d24hEmm4eA04+Lq0dzM@K`zeM;M(zp;;ivV40+|K}zX3JN zoYuo~la%G73UW2`8S#i<;ppv~qyqZQuiT%d^IWE{&E{mE?010sam>ca5VeuTIS19A zd@nTUknr1MKft{3N*knyhZqkb(kGKL$#vTYzaN zr56ucTr>yc^;Oi=TDJD(o_sL7ANYv_ugDHv<4ISDUr}mJnDklu!xM*A>5pWxk0n87yG@<@n$&aC zyRvJchx0076!Y))bgSpIxJV!T9w3(;r*_KV=S~)Pc=#bu$Kf8+EYSmOdML!_7;`<| zP+z|V02|;7KuI+?=u%J>M6)ZatId6xkKQR|f32%~?SB7_y{N&Y`i*1jYmUMEli{*v z^>Z_WVrr8$uE7IeroBjZB!ld^BNDW#5WGC#+;3SzCgg&-UJ<1pj|?ag_B5TQb{9eh zI1pw%(^%QzRah>dSCco82vE9HY&~8XcB!lvOqT#>hQ95xc*1cFz^-%qc1mRV+C-p4 z5x{%^LRMghqb@4YIz=C9UT8cPjo<6=}J5-|#6(;N(vE#WL2l9<^7vg>E~Z4IuF)Bvm4?zj5<@ zZVZjDZ$eAq<@8JOWU_?Sp=8$IetbwOGT;Wqvw-uH&brp7N;VGuC8vSPbI5jm^^daqpEm=c1p}KH8;lxg)%^_LC+ewT@;wMr0_%=pf0i*h~Qrv zX4KAxkEGHb@y5Tp)A@aQ7vQ)cIsw0J4YUHDZMJ3Z6Eic7Yzn46KJ)-9h%*OhP24p* z&Ta~kuN1CPBe$A#O-I}*A8$y137YsVrwBEHT+sTspC%nPmk>mD8Dw>S8SVmf7Jh`9)??=| z@uT$hV^&;~vd0NPae+jEpsL&*Dmjj8wTkqp_CL+lp*ym)errJ**sE-$2(|!%j2CtY+`_W9$FlM}wXYLg& zUF|)6npyxw)AqxK+O55a?kLl7QL{#JkHtIfAW#Px>}3VOX#kom&@fG02#J zkH7TQ!E;srlL9bX)1J5i|m&OUOm88dnFy`yto$*zym;ffNLYfs=@j48XULC z2wysECz3l52FO4GGU>nFVp*?%KLN79c^+yFU9(cGHJOeMOA=t_V!{{^OY;4NpwjQi zXGP?}1CRGEB(Wd!!D*=G3G4UdSZ?2BDk+wraspShzKJdVveI4HJ+o8Uu(>EE+3{$3 zW>d~_-7?0zGuLp@TaPyWII}6rf|Hpb8J!_S%j<%Ix8~JPlfQg$Uw7f?eec>)#djC| z=yeMsKQG9WT8*Vb4l7!Z;igo!Nl%`>E;5iEzbw%_97QLc{go?(02Effb!EOrG{ia{ z*SeN0x6%29i2m88)@v{hgcx7HKc8@pN=ByzAqJrP%NIn|kJD5WB@gKR)nWz;+U%Qp zK?c?>|2ApHbV7=Y1x|=a7@@Tkvtv3%;*+M{x-|Rux$F2iA-FtD@VhXSS#mc3{Q<{? zq%juRI+Qv-;q~8(Vs4T+j@5mIooztYvykICL+>2Fs!d}P$G>}}_6T>k~R z=Q$@i?kt&q3y;$IhO4emn9tW0A(tnj>i}!n>A`0HvbAG!;Wp>80da4~$<=pphFdm) zq$f?vc_kCon$66&5yNz+ZK+9m))rIl=^ckqQ$ zU5zk51T-FY{c1(t2K|-a3=4kLAY8uOEC*>@9UX|{3>kahP`2((*bTDh9H26g61o1- zZsH}!hW^DKhkd4@xAU*~T&Wd&jU6=ae3BJ1tPXmaZMZ_d7% z?1un)${Z*>1Y9;w4(3Bp0MO+ zH?C?ZU8fRQD%2F+xeeHqOa~zTh0p?-{#Eb*P3dvN^g;qq3YXc$oJyRYr>uX)p_^2r zYLB+?)`li9ly6C!6ix3E-7bv$Kv>}N-&%mf7Qm15La)^*+nLHQXU|h{xM0C4RZTWfhKssLu=5bXBHw9Z zGkwfNZ3gqV!E7oE&@U(cPAM|s-BA-*z)K+eQfYjtmjMKA37nQ194tL{M8RnYHf=@Q zHw-zlXaUs3)%G(5=8rb$?_a5DSaiz<T7EB zLsQ>+K99}i#;CU6H&oy&XKeXx(vX_;KQ?@|ZVFGw)32c9| zvPYygH!Id82$$)b3r)t?@Dy7T2t2Z~!=UhEk-?Ux(%0T!3pl$tr=0yha_Wt{FuGbp3f~wSV#q3rK*uF9Bd`|~F7ChMweEeqjj0cZ%O(q|` zTWY!qm)!t8!L}w}NYbsxspfRA-OjXEwh1N&9bhBY%Y?zeY_1frWeF~Y;Xij^GI}|9 zc|oePs&T#{0u)6>7p-@pajhRD)~{VPS|K$!E_RGW{$2Ji}f&5r^d(A?UNP>4rPu1@>hV@Z$!&^#skJ zA+k(0j`S@crXpktdisRdGvE`_C5*Wq3WoQ)U%Z2!?-2(Uo{OgiRaMy1Jr{96@u0VB zro+6e&I!42$%s!fPd*^jO*E_6qJl0yYezN+TaDOXgJq!H0iv|Kz{3Y`*aM`*geBlP zkj8=Z{frNKOpH|>Bq&b!!Rz?{eUgHN-7`=Uh{@J6sK&miDr%-jS-7~#%seZ0EiCKO>W3BlGJEdsw*N83HH4y*=>Y7@x5C%sy`bu8 z{x|E->z+H_@o#loxjdUW)*@Ddb;(?U?O`TK_S}CE9gR}czj!Hd{lS{vifgRWgK8%n z;PrFblga)Hi@f|fEZD+`^#fPj_kYwbXDN)!wWUHnOV~KK+(N%v_`ZAG;Ag@A%9@zp zo%sOrH;}rc_;!+=*KHqD?kOtvPR;S9qS!<@bFBeeaD0}MZG0?83D2`9$?soq7HL0I zdXancdgq%((QMKFws1DF{#A^#m)H2z#DbJV{O>5r9!(uGIF;1Tv zf_e+XEpY)02D zRLW=OOL?!~4l^EXl}iK~n4BkT)nLSo_-VBBwcndRqsu@KNGjF8)f~ICe$XgdG#|Uf z`x53(ezA;l&vj6t7uYhlZ84L0`kmf?nCavaH2AYf>8-Yd={-g9qnzvrC2e{8H1s-Ys19$u8wt`)Q#q|j;5*x3 za2ok6F61AVk0Q-@HwjC7nAz7=teOyse0YH8X@FB6D2cF5J6?3Gmb{D_5(QK?9wBuh zX?6enW)d!Uu(4Ra4;t zgB3l}o4eAMX}m+QZSigb2$GQ#tR>C3F{xD@V#*&2GiJ`hhup&@s$8ba?H=0K#wabj z|6Ofa$8JPZYIzyBv_N%nobl3l)LW|UR8MXWig5XuO1y1?{gxNqyUqXGdU<%@L`rWi zteB+HYoopU59P3 zNIXIXD??C~*em#cHB0j*dS&1t3)w90D5We>Q*EA{m84r6XsVey`B;|rR|>4Gw&a4@ z%aZ|dQ{^Zo(N}$H@~Clm{cEbP@&{4Mcs&W7zyv6x}ARh zZ!7Sc5s@185IbP$V>8BE#I5O?I99l8Wa4rc(wuko0Z(s={?2qR7tU1J?65SK4xgx; zVXbF?25J}kK_Zs?Ap4vE;b8*AgSwYee^#8&5sbP9mFI=hOO4{-&FX~9e*$9svUERb z(a~d~<%LuH^0nHds@ro)Ng~%IKB=Q5z;moUSTV_BYP-2UnR}o(p7uO=H9MR5q5=&Q4{clZ zRhN*;ZXb5)G%F#hyRVD~X(u&fdOxlV>`8KZKIpfYz4av2e{<5% z!Z-0JTi!zfZBM0U`teVv?&p`Lu>x|e9yo!n)JiKV^K2HgZ;9&105bOqc3T_NE|9Oh zkk}j14E6UMWgm>?q8hK}W6OHLU6uQd)y2h%j>zH15*vou(#vq;&PNqtM<@S+NmvZ| zV-rKW}#UP3YhccUWJ%C+caMJ|(A-T%iPfAnnyW%bMDvZdfiZycG^ z$>u^QX(ju}`gHXXI>3G9K|V}Wfcovhd{06lzP!rqF(b7PS8V#!hK^odLExC!xe_6l zd3zKont5mgrKT{qz`8XLy;H3X4scxvx9{z17n#yr&vm?FJ;(NU%=2nT>8U9rjPL9E z+J;YoM3w4=q7E|Cdybe?a;{PGslnWx8Ov4PYncX0$x6&i|25LU9UnZYOfx?V{Mw6t z0p}fn1LJ1yc!zW^6C)5CdbKbn_Fi}N_(ua?)QymAzHFiYE72a$`zp9nLi=-Tu^Mu` zMNl=zp-*^_sVUkO_5i4z?xYtR#(hd)1{+(BWPm(#A6nJFXNY!EtzK$qi3gu6Q{8O~ zONUs=DBJztWcSi<gyGq-c5hEQikupE2?uGEhhl9Y zRcn2HU1i}D6S#%3eC?eXAjZ^#c3-Mvoz-@l?#VdAZ7475cT2xTZ0uYqTW{Oq9cN>1Z%P#@uoth;OQP9 zcPe7r%8Gzr3Oq&bmr^rS>{sKVWKPBF)#D**f6Kd36F#nM#XRwyc$HQ)Y9uzcPY`ng zjq2PcZbPzgOtp-Y=q31a%){;^s|_!SwBswGVA~cO4<{GJuv_O~9ym)inyI!nz}AF6 z>!GsX%DYC^%R6;*5Zx{rYfD3*RZSlz1#hC8q4~M5Kp6J)h zfDfTgjxn9HPl$QS_=yy!P~mZ{-%yU@W^}VL*sZ#rdOH`iUkalo{zjDGwn9wra)T|%aLLfU+b`pC>+O@*u{>s^F_?CILGupQ1d05iACA9C|1|RYguVT7My9m{1 zIpHD8#5*Sbkon!{NLsNjs>#f1`Zp=?3W>K-p2yB~QDrz#Lz^HNDirE(!IZUk6)eGL z{^wcMUNX}IRA?m_oeR8xbo0po9v9fOj6KXbI^_u52KJzMj5|vpY69ry^gcoxiOA!= zdq6u!Kl~0=Jwf#vVfMm&D5GYnR-|IV4Z+}st&chR-cmh+$V=dR6`1lic`=H%*%A1d z&SSm&9^FqJ*Q`D$8KQh2PRZJiF8_43PwHGGMB)hI13rJ#EQp@o&<$-e6B#98;^A`8 zyCcfpG%7ukqo2leY%WN5yfe-qAI2Ke(vAw^4mo!WRtj7 zgg|G~2U|~0f%n(X2Qql+0G?r3oGR+4B-3U|*K(O~VEd?2=|w601oc&CVy^1<83Kv*~J)g?bq;&58 zw1X{0QMoNQj`Kb2t2@PZu16`LB*zEC^W=Hvf zqm1k2bQ-{exT8Xl9t-q|GyZax9xKJpCcc0RVP42vs+9DB9LLYWl^dVu*ltQ=a^QZ* z6eE<$jC}e22p$Tm3j{CHbHMN(nbvfA?5Bz2J)ZJv4nqT*uyJLTUZtLCHtb7G`+oWygf%ve>*(I6M2=lzgNQNFanb0PH1S2)x(1e-S zE~@R(9Y6cd138N?gOiVXEB2#}KEv&|YOf%1+;4z=E?NX8jb6)ekV%F)58uZ8@+GV> zBL7{(cj9pm7pnYYGZpA`Zn%2oN+29ElJ|$Df39$(jTa9>D`>z3-_)8lALb#;FbjXj zaP2?&e)5&z2^o&4!3T~T`gH&Q6@LF^u&e&G(oxFvvismw`k%*JETaftImQ-CVCA?9`dTrj3WU9G7&2{>NldpI2@oq}sME*!FreYK7B}yiT{FSBB zW?U|AexLz6P`_|lkXUO`!gtwUcuajN&@jqks|OUlDA>cA)WO!K;~wu!05df`Z4|4- z2K=0xz`^kVrUoOOt!eGl*v$!y zhXEVfVI=`!oui+NrGd@qvKendVG?R%1YVCT-m55D^l4~vpc=#~M0mJF1h10hsK6PE z_f$c=CDVc3=slZ!xv#mEla$alFE0m<_F5U}4^BGXu@|j7e9ZfR7di+nJIc}Ec!_S@ z#Ccs2KQcHlkoj2bQ=i}68uE<@CwJ)VA$Ai-xd}$#p|cxWzh!6Ogf=*$)yFU0))bwM zx3@q<;!HarDE0>3Qu-yL(K1bInCsnRL7SMGMBp&)S9`6Q**MJ$y9(WAse4j3`vq=) zMg(C4hV)FaOYmCK=4u($dKW@Wnp3LiC!wk)JdJQK>Be{|`0;9l5-hDG?K0-ga}nA$ z`pKI8E#TFCX!tPvEjFA-=L))MxH{Txdh)sP)h29o;C#)^50Nb%bn2+KpukK{Rd3DD zi-9(B^sOes-Z<{JSawHx^KRp$S72x-br;Y*6~%PP$455m2uMZ(I2zl9Ab8a;8BOqU zumcuG-%CaVmd*gSIjO$bZTf3Ws>-6H!&Ruu-0g$%#H$IQx0ZN&I9>O4T3+a3FhY~I z@X=$>H7e*L&YQ7vrk7>mkE)dj)Q7wl(Pgn*>Lx--|8bH7c=hZqBQN;ZnaXR<Gn2>vFG=(E^1?5>x?UI_bwf5oyKv~N-W!K;80o5w8Ib9*aka~uQE%~|L( zv1pteYftg2!km8RB33H7OTB{NHvJZLaN8`(+5miQmu_LtaB&8L4QRmS%t|9^QfTx> z^X8e@s|ls$b6-Lvw}aZU_$9+-=MwoTT>n$7muo+?MwZoG`*bF1B*)>34Nm#{k>i(1 zKc;6UsQ;)e;!bhDdtB~CIc|fRbw&S4W#z` zc$6~OI{K4w%Lx@sus5(_ywfE~8s8=2ZIj{mn|nS9V`2z3_hyBG%@60Mj4+Ixs(2={kar zwBZM@IqyKezl(nTxY$UbcE+o+r{}@6Lk7xZM)qEO@P+9}gY>N)_3W@0pnVMthZov-AdsVw zOuhQ||R>~ebK zqWDKO!FJ1zH4x61iNsm)2890_sVhCdZ16n<<^)B_q#-OzqG6bC*R`ts-9|GI9NLGP z$0vuoNsYWbJk|~lPn4CF_4V~_7A?>}i;yMJ)ad7J|BqD~e&t#Kw^v(q`~{r=qYp9c zYEmaT(T<=c@%%ltVTgQ%m7ADvI)LBa(8;We<|5Yb3Jd3yl$3P&HTs@Q~;72c? zg#TA#i9e0g+1V#)wX$(v*UcAklQu09s4_RbSEYj`iIp;QFaEec*6nnb)2OAC0An_o z!BY%_q~IHR7Y5V6aH6N8t{dGo)yZsyhsvV{U+)Ht{PrE*TLqoVyWnd2ZjTIAt4IY0 z^+oY@579X2Omm&tYR=w$SK(GO4<-|+9H23JiLi?5O}eYyhLl{5LqIneQ((oG<5*uD z8@-z8iasr;{-DGr37XA*F7GDc6#2Zdnt@oW9EG#C*U5)^Ttm&#@M;I=)8OUVmIM^=VB$jI#%ERQyF+Ds{|Vt zSf7Pl!`K%#`i=PD%8<{XlZ-C=O90NAdGmXU{Bd^%My=~vw z=$o&tnXg@N;H)5ebJ`&9?JU)%c0RJX;lbl6Tn#L8aIEljouvDb>BnT;x;BqF*)*P$ zrqrwg?ULEH=aKb!F_I31gRP}sYNYvMl@Mp+1^gqV2<2?ep&p<`;M19_%GOzJTfd*(e&UUwcsKCq`#BfqvVD2_zIdPchk@oM>u#?|>8#3ysw(ug0jyLQLH;C3;Og zD`gK+j_QlFA$^1S2C{JXhoHmo(8;Mf*|FMS$`oxB2xkw3A3Uq5!Efbfy_*t=1|A7S z|Hj%Ny`&(x5(EZtour=?(v^&Os4gwrEpFOO%>-MTb_))+P3fxGtkI#TEW*^=#QQrz zHTce0P<4d@@S4}7G@h>#Ae=f?ukW}i3qK#t4-D`OSp(}HJZbCkSCgH>t+@`=ku&-7 zhYvnaNYd}Qr4_Q?9u1%!l8Chpt;C#Pu2BSB0uC+G1K<-5{L;Z?7ud>ez?{9o$=u-r zQ7{lGAb|Ie=>RdSy5iUtPYz;EWX~Be3ve|+!DY3G^7lT;V%`T| zK?7`VUtgcF9r-Lt23h=~jDQBpU#;aGE>v@KplU_9TM8} z&VXo~ya8G%-K-?fvHF)Fueff-#f5vC`5(Yq<@D zQ+?Si$a_)%BD@TqSs#@}T?LT>x8J)SxCZIU8YqZw{xt-BB^jvNh8?{O=mt@W5b^Wf zz#CTaj@6TcM|gprO%q(I%b=wpy+TwIf(jhnWXb1SV96PUQN2_v_c2)12yl?fqHuzB zA~0r~)2|IHyy%p(--C+7i5e29u2n3hR%;4(MAb?V>}%7Tja9f8tw?;QgWC#<^ypK+_A{60dIT;xjj0f2R*jMR}_Y(VN(Zf+yAk@6^ zwm(Kbol~tC4COfG!<&rk%OPm6i`3y`dz&u^MNJx$VQCp+bqrO)O5k#-G`)OnoBf;( z#eWd+XuxqISkoZZwg7z98k9-@3Ma5x0^Z{{K@lju(6Rca$W@&3Yc8<7%V6Cm#>uc` z0O%=!RYUGN;EA_mtoJRT70019s*Q&dAG<+p4w=jVu#eE1DdK+N83cxLzt~R>+7L@$4J13=c5Hk6-|ozaIH8w$mJ3A%DS1kUupjnp9O+ zSAGwsG70kYgHe^kONBOd|H#_QJjmmWg?MFJ{|hCAI%1I$T&S*{6dCj5_tMtbxu2EQ zW583ibab{OOCX1|p^chN{<-M+YX(RHq}nQov`p`b;J88i-&z1FNL)F0%DyaDeNz!` zX|?_$E&8{kSoVOmr2Dps6SJGQcb)kJ4C<1flC{KgrQr2}sx$dC9;oRvMR?GA@YZ4p z2WcU!3J;?CsG_h_=HPSsXJoIRu`X*=$1kM1_Vgy?%)Uk?j-_cj+hp`#`}ebw-MzyK zRxoI@d0tmtR#D=M%h@y%BwN_97T|BBb=!2b_1Ye%Im0<0L$qB;RTt26$1~NMI(U$_ zmhu$tK=t&uXE;#0Ip9ff++HTIFoPb^Be>h3#%i;3wOx&pD0pyUVgj@9RlwOXbU@FL&07a>Ho9j$+$K88(L^rs4?^YFlFJUZD7{?llcr^^zh}KFh$6+EDNM7Vy z9GT@vd1laAH<2S%Y}{A`JgUdzPiH%=k?78dwxYGsl3Ev^LTxT!y_2qsil;G;soSp$ zgS{&$xl3~ODmM)=SBjd5bM5*=dszCjJovUSb_e02xehGv2yx6P#i;qxd#IoqWl$$a zjQlL-cUIS(CS44U+g0wjNZ?k)+Ok2;k4to_GsE@vmr=3ZY#543B|1tJW^i+Sd^|4t zMo5MMZ!S0}&b(|4v|v{-f$y=2&2eH|qZ-FLiM_h6VYW016O4-+tbkc$+&;5axk&h( zoh%i*CP;{keCV1$SrDN5hqo)=8}PC#uC1>RtgPgfj(q`TkZVV@{b>5CW)qEpfq@#Q zWwj|k5lAq?N!$&@Lq&^;q1YF=sw@bH06SGX5B2(h)#?6W{bkr!yM?iKtt5w|{O0VR zV!aIO_evdA|I1m(Pc;{od%3TdmzI74i&s@sLlRVbkvOINi^DJSBSxI2-`v z6^o)H4ZY%E_)i{}0(BMP~6?g$F}Dipc^*G7j7@(7^ac5o^*s&b;16U=#MJZ$&0_X)RL-|9%b42r_-aP>RUZHE9 z6J`Pni+?SyXLR)ml)Qp?HoWwAqqq0%olX#aX>rAZ{HIdxKrI0($9h<(83q|GG`z_~ zn%ZHdJ9VgQpbDMOl7Ga^1Noz8gJ&z>?=JUp^NV~VF%MX8n7{INcBjO;XolARq3Oai;t?5XU>odCEet%s>tmD z6AdO#HzAqMDy&{j-CiC8d06fXCAhV2ZLr+NmB9n0CxX-kXl5rNAyFKEO4wPqC zVI3IlP|4O*Vb?z1(WG_-i8%B&8hfb=#zT0KB0CpL=Xa{Wn81sL(t$?Q0omoKQj%>gosb+f7egIdek zs=8j>i)b@DKJx;(1pr9qSlgJIJ^+oFBnNMxbOC3tDQw2PDZWlB3J#E8O}$Ba0{;{+ z_mPK**A%%4J4|n=286Ln1)t`mgkT7f7N2MB6J4VkvhYagYRodY>fTjao;S?X}_n3H$Y|*dDX-jD(oD+#~WN z`-WEa@fBot)Ejv5Wt7@6iG%6@s2yOg!iTOFXroMwx5gNE$M+bp28m@8fCkvtH-hdd zu-CTE&e{PoGJsD)Ou^n(cnx@Gl7q*QAQ8TRe}LJTabW;+l>mM2ck}({I~J4MNkUsC z7@PsTtjz++tcy`&`$v-+?LtxDfNdpK3dERjV}TnN>Pd4UD_hJDpL6<6`}JX-6fq|Y zbtYuVQ&zAx#sa|3@LR_Zt_;BIGpi7F6U zL?~pw7v}xC5&a|zf~GZ;x2*oBC0&mGu6B{d^P{AIizxA}O&5inDp+j~EZ-4GNlRm| z0^x~vAqb}$KCpI{Cf*|h5i+#mj(+$Z2wcnDSCxU6Uh(A6Y`7W14eZPNaDLi__ zrU+0}ePiQXqYO1yA$%sJ3m~MEX_->-fU|g^`~4y?Dk!Az5>)=m30H(R>SyVlk2%$B zy@+dAYuS;X-2?QL+j=|j!{QAy_{GJ!I!lGw6*u1)1Wt|z%No!Qw~#tsCLj>@iw2%n z4IB$c&uw@*d?0|F@hsC2z>r_43*!Z>Az}jYZ zH(QevjL@h=u!DjHVqh%)vCa$0>tOl*#Z_`}FGpAD%OEd`(=_8)oeXR%^SiJt_PIid zU-UFI8h(C_{i}kJDxefb(%QwH`@;Sd>8EY_%1tP3^bQx9-TDUJ{g{pY_61`KD2KOi-CAO%fAthYsYQRxVJ7&AmW~-{>+S)d8&m zG2mxEX6^qlP5{X)jApzn%s^E50b>T(4R|k0^H!sb%XfA9m$Y~>9iWP+04&Iaf3$L2 z7wc=5Yj7XGr2Ek@D@goG2_Lfhq;fmcS-gIkbJAO?I5jnu2M3wGJ>2kYg%lz1@%8ZV zaQWA-Uk}~dFO)XrZ{aY3av+vT=l0%!ao*8SSFZoipu-A%KCtPVQqXWD0ClXuq^h!I z2&KURDqTRr-S%VUKW#N?F!+myA==IREgg~2R{yr9cww>5flrPj4rH_x`)`GU0V78* z>B6y(;g#T+`mC8>&Q@0_jDRcK!>uQhCr0v3k(q{3ZO(@S>THTz9cDFaL@QHT)y*bv zgXIC47PJ5J91!R0YIdmQi?fGpbV%VqQDq}!B4mWx#4o4j3Jqg408nLpoIIiUwzig= zlJb34r<2qBEb4*Pt{JD&=zPF(ATt4=Tu8s$_TMg!vNT?B!u&lpJSggVbcYZ>zlK|E zpmkzW2N?T`psOf!eOnukKok6U;kbJ~k+C`S^d<0Y1Y>Q_QJ=L-n!xDC-aAIbc5GM? zq!-WbseA{(9RDTIs^Jov5oeyS%{4S+H^G6?=G`Nza8g@rNKmsolw|)`^^jb?R0SOA zYsVoO)WvpJ082J!WYCcU#5QDqLO6n6 zK6k(xNOIsLt)SUO5&#+kLx7AYPq2Ut@53~N6F?E5sF)uwocGp-5HVj?o%Mled{oIv zNzy9=ER;G-J(h9=&v91M)hQ*&f5~3=x>$6p(bK;cU02v1v}UbbWr%}sWJ0ta5tVNS|w;Jd4y z9!+GMYC*_ExAtsf_! ztN~E^Omy2{GjT&LY`K(9wE<=mUkWm*HR0!I<^RyR=Z#8bRnd%MTfTT9->>j?Tu58|BuK?KMmf>;upPQ=4iJ=O2R)>;kSi(S93>r_Vo*{zme z(9^#X0L?@EfZwL)?^`70jJ<#EQV)v*7T?OzQ8QOPZJOAD?#7b%D|lzAHgCMp{ri(& z8yly%R2Lhz2;Eb#GO$%Du`2OzVd>eE(FRIg&sOlxEcp^!z$cbR3sfQYc50>}z4sQD zmO^4;)nZW+;^GCdv9Uh*)vvwnZt3)EnUo`_)1 zpBW;SEg-1o8n~wB^jFV`%Ed(>sA!7uJst6@&+s$;n&C$W{(=2TH^o|_i=U><|381q zZchKZ4T7R7YHA8Te!Ou#vdz^_se>rARorzWf#CAxq$8IEpqnm!#EIt+y8z7T`t?ij zbRB^1|Nc!MvRx^pzvFcKzt=(0Sflpu=l|nRq6)7|z=t3JwX$hFpS8JulzwrwQ+otj zlmXjd(@p%}C09>p_f~!CrjsJ~{r7hmtQd^WrBsNch_xkjvx8M((@bsX7eEq z_r3PftEc-jGbj6ezB`d?TU#@K#EcJr>gksvWIh8W3g(}v8PNSIy@SP~l-M3-K2bB< z4;#sq-uAR(n7(w@`e94?EG}C%qZi$^ z&0~~y*0Nr|<9_u3wiVDmzqiHb>v_66Zo?~GPt{8U^dKbo3=7BIcCG{bfL6V@qjkN$ z1l(~I+%dPeCGG2hy+f+8?%y4~bGWZMTy|n%;{6k7o>e0iM!_`eM8FL*^Lwk(M(*`) z{UyQs{^#y#9C+e|E#4Mjt7(3tHVSe`|BTpkRSiL={hI+x!))_qMSQrHuQe z%Q)SaGG<*G0JsmaXbiG;VZ}s|V zrkyu%K1=hJ+nO}i<2G8H_B7ta(3X8L_DG)?a9}Gl-}@V7buwrzDbx>Nbb+@n#|uQv z)MtKdD<_KJaNSN&OB4Temdce>wZ1%38&&zfUtq*#(^n=}>ii3-UFr?$3R=JPj|Zii z>mDB^LkJYwUFKIaX{Q&Xbo7liyzuV{R z2EAi)>_~&3Ra&=rr03y_jUTR0J+haUuNfOWvEeEH z-WTaP_tbe|0VL+plYOm=uZeV@_RY15pZ#^9=f~{wTJ7ve12_8R)8-+3Hb-@%iA~Yr z4V?-f4XHzoeM_qH(nOsnOnYslR)2mgMs-Y<1m+ts7mXdfr}%8kMV#Ev-NW!?RDa-f zzj)2p;@FLm=6<#wFGFm}p+p=}xYyBdPlG1v^mE$;_vr5xt8uJ z@pP@CEm7Bd1P|XO_-Div`#j;h`Nfgo`J&+IFyrb#OHIGE@>rZC{`LMoz4JOF1~=n2 z{h!l5%6=z(?=jAgNl8}+m5bNDZ;1Tm(6O2c*77jybP}jJ-+ni&^uDAscX?jKdDBR@ zwWDWE-cPY}Ki6e}a|XbM413>mxLK&DidzRLRnbnQ2Mc zR~^o0E!L_x!+xxkX#X<*U{LqjmT_9ICV4>rHVe1$^!a*A+1BSZSFfmNA8+`0o@V?i zp%i!fse$e*&yhaWZjR(zd3uh~FyHUtvsoP$no`58kFLUKwUw@JP4^24d{NfA%r)sg zdb+zlrSL=3)aAj|EoqJWAN9oe=a1YqbjLK$-^C<`g}kuP6LhlEAF+G%_s`)g9psw? z{j|n>^&EjU3BjW9+-R+mw4 zdMkjS?sCg>aVG~Ewhp!O4|Tb8`@6LCt6mh-R53OCt0Y}XEVR;&2BGRS5j5=!(aVB< z3yElpN6u>})+7WYdsau4MaBYqC)rxGU&QRkM5C()kMqwClH5L!lw%GUS0oCkrTp|i z+nx8tL3&a5hXp%%kJHni>Dt?C=0?-5aTZ(eoJmeKFlfwl<_gt$G_n+DOQfv~D?NVx zh;;q8y!N}tGYZ>eD+34B)I$2MCwN54H9pVP0{TqHE}dHN<{y4M_Wb&_;L}*9)j;Ep zTIqy`vux;ON7zZCrm|Cw+j^yio`~yDi4>7S^s2mf?(-KEwtTf z_EGh-;r#Q*gMRXEYnSb6nQcvcT;PPOi-eEreR2(}gD_HqbK||V({_~32hjeeR)?WH zN^0D86WWe!%sbER3a~ot-dfr6J#-U3%U(|QT@&%u%r`#uIGz6Tytd{4GOVG zw;@{)P$?=19Je3@1e7Wz34(z17FuW)kS4tcLPQ0W-U3SRy+c4+5D}0j1`dlfTP{>uaH*$bi|*X zEG5K^*@WjvjyG67{)sQ+PNY^MACB1`VSO-}$#C~$iM9{XUH4KoQH5*eP8L5?oDEtn zNz>PsM(TbL1d%jg z4&9B?X5s)AmOm@pNRoY#nu?~VHV*a6`iWL8j;W8VGW$_~m@183P1JnG@*F>2%CU-6 z3{^X8cVpHKwR0Ir|0%4`wd!~LQ(xG(L=E#KZlBw%PDuRfq?TtN-yTZk1YO~4#FyP11sz!Wa8@wK=ysCxC`X$N(LH! zoG-u+&eOhCt2GJ!zJ{VhStvgyLRUntNy7b)3I(M+krDA=AjQv) zaJHYkSRdX`EKWAx#*f+TzBI7AhM|^nWd809XxmuDSSMUoB$p{D72PWRwy{i9E<=N9 zB_6Bn#GtvR(ybr6*RD@YVTY71{h@;XAXBmMz3s~66{u~CpI6z>fvR#;l!9LfTyNDN zld=gbiLZUfj~s71SOHIZf{!yPm9+*Ncu-an0N_IkAy0<=)*^jQdQX8(_#L}-RpTkM z9LT%E5h7$bm~6iWhOH;UbV{mbe$QrDWbwysG6JDMs;C_NcmC1D>!fJfJ9KZw+{ z6WlcG&ySAZ3roX(t&$VaT|xuc-;;DF+MvaDMUC~hiJP6&^e&5B^if&~x6$SzqM(aB ziMBRm)8e{FdgK;J?&~@-t+qdW0H-%-rMf9Aw;N#XYW>R({w;HLm6_a$=b#C z9g^EoLK{|eRNPPi-ibBP+b48a$KGM$2KtzfW&tbe^Fd5|mC%nN`hs{X^SR`rx_Fg? zS=foCp62~LANlg5X+c6^`@1;hGP4hZ#c9YCAtu?oCdrP=sJ5meVJ#hA6>34)A@1}n zbwk15$#w%w>5$A(Eb0zZU&whmND$9xJvKVZFI0j#Thcny8pLJVPP*lQ!&3;12VNbO zJM?=gcZf5*+Z0AdHu4e@M4gwBRv8#FN3A&815y1l_H`+FxRp~$Wu`R8$Don}glz#y z=&*>&lWCOt@;D-RcVLnfXMNpj1GiSr+UDh|b_*lGEfbT`di2g?xJ1F=1}xHlqu0rQ z@lzh<*3I&!k`N-Te7n~Ucc2&HcVLbGKH}i+)ReUAL~ixgHrG7ZCjK5cGOJ!W!>a-k zI&PBru2A)4DTl}8x>ZypQoGoZcZqi{v_rNiKk5CM1alNL@z&i9yYBASN|ykx+pjCz z?s?|sjkxV4-woBvr7y%ZfDY9=WlWP{>}#9iqia*&Ult_QoiVptj|j=IVk6ebN;M-#+A3zGmWzD%;t4`!qm@`^NVjqeqREfNJYo z)}B`^3GHF%Bm=-RwzXg1Q*;mK7A}*m4^nl~TYwbHxvjlh?T8WgaqI4zK-!o%AHA1{ zb1Z((tAu5pX+%UPI-cLCY0=+7TbyIHN#Jf%=n@ckCzV?^(r>NYR0%ZE0>`}jTu>rd z#0`XLN8KP|+V(lx*D22!@%IFpIqQz2fPq`LO4(ljc?Em=1k{EjUEgIM4GLW?iDs!p z_^F8)8o1uQW3`;D!%_jJ3OQeR$c)9Cj{St%O@yz3HXc^op!f7Bc`v*&;J1(r;t*Vp<$suT-Q{} z)9vn;W5UZ~=LD>Zt4wyMDThn#Ixk`e00EoVfna|~AtteEu`M|eUFZo`J{3O&FBU^x;6G|?y(`6 zQ{8i|>zL1T&DfZQ?F+WOdG}0g)^R0e8a!8urwP*I=j=qw0;#Mp+A6}_K7+1EBZMSF zCSKDI1lO*jrKjtjWTOjL{dZFESOT3I8OKi%qzCwz-kU+Q&#pzwEc{eHCr4iph!NoZabmBL5WU zgm%I8@hA5yzlWESXBce!J-S?{a!N{Z^4P95#Tir@s#q5O&KI`*BV7(j<+QbSp?0_u z=O6IDEg}uH;4K<%jD6pAB5nGPx@;}5&4$uTes|x@4&8rc7kaaL*;8NK4fh)e;ql8J zwn`HgZz%|wtlcoL5hcfOU>ir*imysjHl`1djYZ$XSz%jyrCe|ESgl-P$R7_KQpd#x z5*=K&=0acx9?&$#VjwhdVdpq)Jr%bz~441j0qfUJ!J*cIQC77Gb98tR@D|5-*(^8B(TH4G!-zW_h(xRtMeiOoN zqI2|0c*|>XTB3^FG%@%jj$gT=yZ9J7yTt>$TY-7qBc|U~+OibPR1oFA-wNow+g7El z0Gc3W0G7U{=Cto5e-l1=C@8T-e^awdtell9eW8r*yQ3TNifh}y2EuLR$rzNYnK{_p zJAJeTYbrX(LUJ7{ebckS_Fjx9I{6~M61{@mofus3aW zr00o{t}PIbh%(&xQF`9YJFd=UYDPRx{xs z>Jfg9ggdwj5x8G|RZ1Ym|KKd#P5ze5OfA~S zJguqT^Mdp0i!do2R?4sJ(I%T_uD7x4!@isi)=E_`bjm{?VFtYU`3M#dgC+1?#iJm} z^3`Hr-s#_>p$4on2@qajb)otfml30Nm9`2WZDG@m^$R-W9EGitnrB50%L42Bokg(& zs}K}hRTj3>I>8|;)OZPg+G-m{Q0ltf%65~nYI-Z8NAg|KLG}veuLGc^!9vz`ZT#HO@ckTvygPbnhT#{B><-`7vUl!+_M0 z&oS8UzN$B!dyb(MJC*RqIRyb}ccT*1Sg^NCKqB?79>p~5*{2YDGG!utPsUQ`znnTqLw!O= zEHJ@ytQ9wk$lVXI1!yN1laU_D%HI| zj@uB#@I~c-o6x~x0T=I9Aqf$P0H}fp%KE-Z`*s$=(1(W*K*DMd9? z!+8XX{al@Y4Fo>E&7Es+flmU&HO=dFWF|;-Fz?r{9K2NDHntg>C@W!CZu4|3Pn7z~ z!sfF1wM;(e?e^sQQxjs?{-dEIZ+%To|KBs-+@Q<}oae0Ze?10#=QPO^>V@?jpIrEu zK<_>);=iJ5&_XA{XZ77Tr&4;~v%~R4x1&5o>wh20#8kp$yUHZgXV$ecP>nwy>MW@D zlNQ(N)L=I(ze2o$)n-msYiYSws%H)L*PRcOK!<%=u*8%i4GBjWDMCu6T4t$*ysdt` zuWDD`s|B@bDJphcW@cXxi5I{;@_I1T8Tn^;0Z+Psi=tI(s>$b*ceOT?d|e25E*Qn4 z#_UH~)Zibfb#dHgM3|&L!_-l#so)oGcH7V-yXzY2f(s=Mw_S`RPS*KR4lN?^DY^6hp2$Wu&mt*7=R zY>Usd|K8ZJ_o`1 z0?#>=N<+3X14(%)&nggP046=#zmQgJ0<&wGqdm$M)(2c0-+64b@Ku+xAP8R{5M()5 zj00($F|oVMf8YPXYK~HwrEJyXRw1$u0VvVdXfq73W)bCCH&fNHYDgWr>cG^)5+!UU z7s|msCM6SWO$<9UGMu1`x^@bYFY0Z~M3nkFIH+oVHL0H|RK45cZOe57`_;>cz`=tu ze^$V=CW!I+ScdE^Ds(E(EAB0l1ywE7VQZMi&URjoFoWbj*4YPCF+j)#hd0C;P+xo(M zBkqNtJT!T@!-uI{;fBZHOVh?V3*_b@FY6oZv^X~_lQu1Z{)Ul*{&??b>tyK6f-MM~ z=jCa6x-w7gfuZ?V0FPPIE0%*cdLJ(cFegqhwA5e`zp$2ZSqU^Nr~M>uNRCQ^Vq@5kwI4%Z!=)ws@w+U zbNA!N&jvmB^#6?b^KwM0+3xOxJ1V5q9Qbk>BO=fVPkdF`Le3^!?|m8SV7CZ7CPm2N{4uDq1*C4?wY#h&|%E{cLqp zpeqLSNvsmWF7|PG2x%tC%vC37HRY{5%}`dH`Z=sOH>OMkLnJTZ>SLtV9Y)*I%o`E} zF;gF3egz%I&!Id02S>$LQ6AcT^)VEx%xf5FT?-cItzVpTPanSBI->iLCzM%QA8^Tw zkrLL|&hMXeYDaKzBO7&uQ>@$DU)^fk+0a$8dq2@{0X7kHDkql5z{o|k3*j5#UkwuC zg3W|V9`uYAI_NB`^TiM>TZ@ug^PU>AiRQh0s(z12P#8IE#k z{hWN*3U{Dzcp0V8 zT&OAeg0r*FSMK<84kRtyv*%42^8P#C&K8#T7WbUXJatVtA)-%3A$n`yXu==VOZ^HbS29NbdwH0o22!m}-lf_(Rj)4_q}`B9Uk1(c)X2qT5DXRFk5AW;?L z0t~)7q(_)jMigj0)AC=$j>EP?3<$%t1JXp4x0ctWP57r2t-Z5wV~w-k#p701J$#&Q z<^lQy^G9dl@hMl_Y{kVDBeXQRm+X9fAxa4Wb!X>Zv{pR@RlYzs0aGgj=46+)#iukR z`oEf}1%g{E$w}qeJ=WSR7uTkIr3i129Ac`6V?ie`^rLctrSB~3;+LeG8&i*VTF43X z&2*BCeV9IiDA-y2#%yBdb+EqOdlS0g9S``RcT93}%N(}rB(8;p+?MT!c2B4F-8QC|=S7h^ZGps`gIoTmU{MQb2IcTOli#;<2>Y{L?NH)qa!#@CWiMJtiDjr6>nwHQOdri-bTc z2T~_=ttA~%-Wm83^~D;zI{#;N-tCsAP-5G2o)oBlX;bnyu;M4s2^7PSNr9S02E{T> zL_5g8K0$TG%vjt=^NCA&QAx=Uiug-d z$8Sv~-?2*5+ZYkjct=!eufslS7B!X!Buy~t#GM*gRaw1BMtt)HNT-#o>#$x8%g)APYKEIO`9c$cTH z21(A4q#uczwd^ip1T)j6F>a=s+gt8_qG5zK&C+Ml{m*5UWb@yYYE=7+!*p+#Sbk0% zCEmJOZ<}_d12fgZGpRFI^E+`>pD#Ws?MnW=2x-*M_WtT&H5&#^vwQf8$25@RZe_xg zk{ccg9d<+ux=p}`hJp3{K}YfDxt8`OlPAY=@TuPxlxp@xjah_{>sr-)(ECw&JM0p?C^-*HTxG-`b z#JIqIlTq3IWx%3ZK_7q;Tx)Nj%Hg15K{Y)iP9yGHpW{H+to}>~+c7dael+gs@C>d5 zZKtcQ(C4R^l``9IeH^01E$SuT?j2m3(MCb?3yd9-rDP>bL-n&a2+nuB$`AUM6@IRk zgg8l7`h{vP4BQiL4F1605`bgEhCD`e`@79nYhlv`F>&uI+wQs!*fm;*qYbv~Ka``= zp3`O9T1Z1n-)>m1owc527Sb*6)mYZ6RdEx(p8^*>l^3-c4bc zoTNQfU?%sb{;Jq@IhYgR_i#^KeNyY&%rhxKFZFbGmd`t>1(r93Sms+oeXw6WHD#qQ zOT1S_E#B+JRW#Sgk0fZM4o*Xsp!Y^W{HC%`OhcS%&-|FyQFL|a>*Lm`IjLIduW?zN zzd#0uLHbbB(7SH_c?Wd?BOHX!TZ_-{^UeWXJ>}&DZ6On0E`iy)nvxZM2GWEO((u4p z9lN7PxpS7H-7gxd8U}(RoNlAu59-KAsi0w~gBG`3&m)>LHt3^$l$NF}$j`XNM?QE1 ziW{Gmq({GqMOs2W`&4v~Xlx>#d-iVk3&6KNaQ^gN?EtALw61jC*+!jQ`(UcVV*$#X z+=;;HM%{ds#+Dk@kQX216NBcwQ-zl_(ai=guv ze!WS2t8$8{vNdue#kR(c7<} z-UiAZ?~%CF3fIBaUhHXo5PRJR*HT%F?wsOPko24`o~X%#wokyk38-@zS?Y;)op^VEy4PG4 z1v07tJ^nhq|2{{uBT3INMTwG$tzW5(3=jmBn?|vE()(fZIOYbXKDrBAF707!j-9_B zup}V8JQQY}lzCN7KL7KDnWHD!%EXEK8arU{C&2h1AVo(^{zFH*ewg_rGa6g-jF~%h zBd-dgw{*4VK*&qD__o~6fFl1o(R_4?dATV$`c2KoxKyO9g+sw7uOpmKnJHY(;76*N zw0yN&S69)%@b8S=pLavLKKQ0a#)rvO(fW_0-P57$f~G@C2(7~X#GIhEw~aiLcKphy zz$G8$;g$ZE`V;mAdnLGf)Z8@}Q&S>fHsl)AY*MNJt_z^VVD|XM=uWx} z{D5|BuWc8sE`>n!E@cXCkP(MQwYA1WUyi%591~?rHL+^Boz?cC`};qoR@EqnC_%!~ zWVEx#c7+}NBw-r?QqDshPlp#XruO z@^~4=+8m{=+jx57m%Q%(3XmZjKDd;NiwcsGps14bIa1ko?co)|C-16%i{Iv9Xn7{! z{KcFX&szY)$T$m}U9z@aVEwO)r%pMp_$gV;zGW_UycU^dusyY(_jYtcts`9kp4axB zStsVORuacW|6(3&W_l-2){rRDjDqipzVMZT@^L zclAx>GxZHh8#mKAL4%CmR6Ei+;CV{lnFn7V*0STS{nZ=f8KbvH3<9o>NpHL=dT6#z z=5p@T`r6s4fwzcM)_SH?_I22Q5V$fUp?~?jJhh~M$+(v+8fO^RfPXhJt_uv4#=qM9 zWyZ(R+K+4?lWu1C9Wt5qLGE_pYtd-* zmPcQFib3fz8Kw($GM4e$JL>qn;H4dSG0$iC+czFt`P@;4yaQP;_xEt8aDW@^L$bQ< zuI|RDA6o$ocgN)IYpTod-@g}at71Ip7&@8j)(ozX(TuVg@F0W1|Eu2%HZ9ZDtqk-s zHa697^;9!{csRDCv@}MN7|_nm62bNE;oy|m-$%XNxDux+2LwvAOxupZVsb{Or>4qe zoWA{YSZ~Z#1-NNLU!P_+2;QbA@y}e!K%VHM5?41jT{}fUI&aN)(g4oyu>zm?(Z z3^UQ|k-J9z5`r9z677F!$*-U;{e6mgN(@|@F+P;hOGSA(UQmwVNq6f}-K#+6+umAc5iO$gtx8WE(KvAlu-l1d{Q@ z^hpA8*299~AFb58{Qy0?q?v%I;HdINp{`uo1kB>LI z;acYV|3IUsntA?Rey9HbYqj|+ql5@~#&?w4Hiz*A_fLC~#3;S$SL=BFzx|Jk!{ - - - - - - - - - - - - - diff --git a/launch/09-joints.launch.py b/launch/09-joints.launch.py new file mode 100644 index 0000000..412bba8 --- /dev/null +++ b/launch/09-joints.launch.py @@ -0,0 +1,83 @@ +# Software License Agreement (BSD License 2.0) +# +# Copyright (c) 2023, Metro Robots +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of Metro Robots nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.substitutions import LaunchConfiguration, PathJoinSubstitution +from launch_ros.actions import Node +from launch.actions import ExecuteProcess +from launch_ros.substitutions import FindPackageShare + + +def generate_launch_description(): + package_arg = DeclareLaunchArgument('urdf_package', + description='The package where the robot description is located', + default_value='urdf_sim_tutorial') + model_arg = DeclareLaunchArgument('urdf_package_path', + description='The path to the robot description relative to the package root', + default_value='urdf/09-publishjoints.urdf.xacro') + + rvizconfig_arg = DeclareLaunchArgument( + name='rvizconfig', + default_value=PathJoinSubstitution([FindPackageShare('urdf_tutorial'), 'rviz', 'urdf.rviz']), + ) + + gazebo_launch = IncludeLaunchDescription( + PathJoinSubstitution([FindPackageShare('urdf_sim_tutorial'), 'launch', 'gazebo.launch.py']), + launch_arguments={ + 'urdf_package': LaunchConfiguration('urdf_package'), + 'urdf_package_path': LaunchConfiguration('urdf_package_path') + }.items(), + ) + + rviz_node = Node( + package='rviz2', + executable='rviz2', + output='screen', + arguments=['-d', LaunchConfiguration('rvizconfig')], + ) + + load_joint_state_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'start', + 'joint_state_broadcaster'], + output='screen' + ) + + return LaunchDescription([ + package_arg, + model_arg, + rvizconfig_arg, + gazebo_launch, + rviz_node, + load_joint_state_controller, + ]) diff --git a/launch/09a-minimal.launch.py b/launch/09a-minimal.launch.py new file mode 100644 index 0000000..db14c10 --- /dev/null +++ b/launch/09a-minimal.launch.py @@ -0,0 +1,74 @@ +# Software License Agreement (BSD License 2.0) +# +# Copyright (c) 2023, Metro Robots +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of Metro Robots nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.substitutions import LaunchConfiguration, PathJoinSubstitution +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare + + +def generate_launch_description(): + package_arg = DeclareLaunchArgument('urdf_package', + description='The package where the robot description is located', + default_value='urdf_sim_tutorial') + model_arg = DeclareLaunchArgument('urdf_package_path', + description='The path to the robot description relative to the package root', + default_value='urdf/09a-minimal.urdf.xacro') + + rvizconfig_arg = DeclareLaunchArgument( + name='rvizconfig', + default_value=PathJoinSubstitution([FindPackageShare('urdf_tutorial'), 'rviz', 'urdf.rviz']), + ) + + gazebo_launch = IncludeLaunchDescription( + PathJoinSubstitution([FindPackageShare('urdf_sim_tutorial'), 'launch', 'gazebo.launch.py']), + launch_arguments={ + 'urdf_package': LaunchConfiguration('urdf_package'), + 'urdf_package_path': LaunchConfiguration('urdf_package_path') + }.items(), + ) + + rviz_node = Node( + package='rviz2', + executable='rviz2', + output='screen', + arguments=['-d', LaunchConfiguration('rvizconfig')], + ) + return LaunchDescription([ + package_arg, + model_arg, + rvizconfig_arg, + gazebo_launch, + rviz_node, + ]) diff --git a/launch/10-head.launch b/launch/10-head.launch deleted file mode 100644 index 2d2540a..0000000 --- a/launch/10-head.launch +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/launch/10-head.launch.py b/launch/10-head.launch.py new file mode 100644 index 0000000..cf62e83 --- /dev/null +++ b/launch/10-head.launch.py @@ -0,0 +1,89 @@ +# Software License Agreement (BSD License 2.0) +# +# Copyright (c) 2023, Metro Robots +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of Metro Robots nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node +from launch.actions import ExecuteProcess +from launch_ros.substitutions import FindPackageShare, PathJoinSubstitution + + +def generate_launch_description(): + package_arg = DeclareLaunchArgument('urdf_package', + description='The package where the robot description is located', + default_value='urdf_sim_tutorial') + model_arg = DeclareLaunchArgument('urdf_package_path', + description='The path to the robot description relative to the package root', + default_value='urdf/10-firsttransmission.urdf.xacro') + + rvizconfig_arg = DeclareLaunchArgument( + name='rvizconfig', + default_value=PathJoinSubstitution([FindPackageShare('urdf_tutorial'), 'rviz', 'urdf.rviz']), + ) + + gazebo_launch = IncludeLaunchDescription( + PathJoinSubstitution([FindPackageShare('urdf_sim_tutorial'), 'launch', 'gazebo.launch.py']), + launch_arguments={ + 'urdf_package': LaunchConfiguration('urdf_package'), + 'urdf_package_path': LaunchConfiguration('urdf_package_path') + }.items(), + ) + + rviz_node = Node( + package='rviz2', + executable='rviz2', + output='screen', + arguments=['-d', LaunchConfiguration('rvizconfig')], + ) + + load_joint_state_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'start', + 'joint_state_broadcaster'], + output='screen' + ) + load_head_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'start', + 'head_controller'], + output='screen' + ) + + return LaunchDescription([ + package_arg, + model_arg, + rvizconfig_arg, + gazebo_launch, + rviz_node, + load_joint_state_controller, + load_head_controller, + ]) diff --git a/launch/12-gripper.launch b/launch/12-gripper.launch deleted file mode 100644 index bc0abbd..0000000 --- a/launch/12-gripper.launch +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - - - - - - - - diff --git a/launch/12-gripper.launch.py b/launch/12-gripper.launch.py new file mode 100644 index 0000000..7c8859a --- /dev/null +++ b/launch/12-gripper.launch.py @@ -0,0 +1,95 @@ +# Software License Agreement (BSD License 2.0) +# +# Copyright (c) 2023, Metro Robots +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of Metro Robots nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.substitutions import LaunchConfiguration, PathJoinSubstitution +from launch_ros.actions import Node +from launch.actions import ExecuteProcess +from launch_ros.substitutions import FindPackageShare + + +def generate_launch_description(): + package_arg = DeclareLaunchArgument('urdf_package', + description='The package where the robot description is located', + default_value='urdf_sim_tutorial') + model_arg = DeclareLaunchArgument('urdf_package_path', + description='The path to the robot description relative to the package root', + default_value='urdf/12-gripper.urdf.xacro') + + rvizconfig_arg = DeclareLaunchArgument( + name='rvizconfig', + default_value=PathJoinSubstitution([FindPackageShare('urdf_tutorial'), 'rviz', 'urdf.rviz']), + ) + + gazebo_launch = IncludeLaunchDescription( + PathJoinSubstitution([FindPackageShare('urdf_sim_tutorial'), 'launch', 'gazebo.launch.py']), + launch_arguments={ + 'urdf_package': LaunchConfiguration('urdf_package'), + 'urdf_package_path': LaunchConfiguration('urdf_package_path') + }.items(), + ) + + rviz_node = Node( + package='rviz2', + executable='rviz2', + output='screen', + arguments=['-d', LaunchConfiguration('rvizconfig')], + ) + + load_joint_state_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'start', + 'joint_state_broadcaster'], + output='screen' + ) + load_head_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'start', + 'head_controller'], + output='screen' + ) + load_gripper_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'start', + 'gripper_controller'], + output='screen' + ) + + return LaunchDescription([ + package_arg, + model_arg, + rvizconfig_arg, + gazebo_launch, + rviz_node, + load_joint_state_controller, + load_head_controller, + load_gripper_controller, + ]) diff --git a/launch/13-diffdrive.launch b/launch/13-diffdrive.launch deleted file mode 100644 index 4a83521..0000000 --- a/launch/13-diffdrive.launch +++ /dev/null @@ -1,34 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - diff --git a/launch/13-diffdrive.launch.py b/launch/13-diffdrive.launch.py new file mode 100644 index 0000000..f075c0e --- /dev/null +++ b/launch/13-diffdrive.launch.py @@ -0,0 +1,106 @@ +# Software License Agreement (BSD License 2.0) +# +# Copyright (c) 2023, Metro Robots +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of Metro Robots nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.substitutions import LaunchConfiguration, PathJoinSubstitution +from launch_ros.actions import Node +from launch.actions import ExecuteProcess +from launch_ros.substitutions import FindPackageShare + + +def generate_launch_description(): + package_arg = DeclareLaunchArgument('urdf_package', + description='The package where the robot description is located', + default_value='urdf_sim_tutorial') + model_arg = DeclareLaunchArgument('urdf_package_path', + description='The path to the robot description relative to the package root', + default_value='urdf/13-diffdrive.urdf.xacro') + + rvizconfig_arg = DeclareLaunchArgument( + name='rvizconfig', + default_value=PathJoinSubstitution([FindPackageShare('urdf_sim_tutorial'), 'rviz', 'odom_urdf.rviz']), + ) + + gazebo_launch = IncludeLaunchDescription( + PathJoinSubstitution([FindPackageShare('urdf_sim_tutorial'), 'launch', 'gazebo.launch.py']), + launch_arguments={ + 'urdf_package': LaunchConfiguration('urdf_package'), + 'urdf_package_path': LaunchConfiguration('urdf_package_path') + }.items(), + ) + + rviz_node = Node( + package='rviz2', + executable='rviz2', + output='screen', + arguments=['-d', LaunchConfiguration('rvizconfig')], + ) + + load_joint_state_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'start', + 'joint_state_broadcaster'], + output='screen' + ) + load_head_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'start', + 'head_controller'], + output='screen' + ) + load_gripper_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'start', + 'gripper_controller'], + output='screen' + ) + + load_dd_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'start', + 'diff_drive_base_controller'], + output='screen' + ) + rqt_robot_steering_node = Node( + package='rqt_robot_steering', + executable='rqt_robot_steering', + ) + return LaunchDescription([ + package_arg, + model_arg, + rvizconfig_arg, + gazebo_launch, + rviz_node, + load_joint_state_controller, + load_head_controller, + load_gripper_controller, + load_dd_controller, + rqt_robot_steering_node + ]) diff --git a/launch/gazebo.launch b/launch/gazebo.launch deleted file mode 100644 index 6278ba3..0000000 --- a/launch/gazebo.launch +++ /dev/null @@ -1,30 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/launch/gazebo.launch.py b/launch/gazebo.launch.py new file mode 100644 index 0000000..539246f --- /dev/null +++ b/launch/gazebo.launch.py @@ -0,0 +1,85 @@ +# Software License Agreement (BSD License 2.0) +# +# Copyright (c) 2023, Metro Robots +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of Metro Robots nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.substitutions import LaunchConfiguration, PathJoinSubstitution +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare + + +def generate_launch_description(): + # these are the arguments you can pass this launch file, for example paused:=true + gui_arg = DeclareLaunchArgument( + name='gui', + default_value='true', + ) + package_arg = DeclareLaunchArgument('urdf_package', + description='The package where the robot description is located', + default_value='urdf_tutorial') + model_arg = DeclareLaunchArgument('urdf_package_path', + description='The path to the robot description relative to the package root', + default_value='urdf/08-macroed.urdf.xacro') + + empty_world_launch = IncludeLaunchDescription( + PathJoinSubstitution([FindPackageShare('gazebo_ros'), 'launch', 'gazebo.launch.py']), + launch_arguments={ + 'gui': LaunchConfiguration('gui'), + 'pause': 'true', + }.items(), + ) + + description_launch_py = IncludeLaunchDescription( + PathJoinSubstitution([FindPackageShare('urdf_launch'), 'launch', 'description.launch.py']), + launch_arguments={ + 'urdf_package': LaunchConfiguration('urdf_package'), + 'urdf_package_path': LaunchConfiguration('urdf_package_path')}.items() + ) + + # push robot_description to factory and spawn robot in gazebo + urdf_spawner_node = Node( + package='gazebo_ros', + executable='spawn_entity.py', + name='urdf_spawner', + arguments=['-topic', '/robot_description', '-entity', 'robot', '-z', '0.5', '-unpause'], + output='screen', + ) + + return LaunchDescription([ + gui_arg, + package_arg, + model_arg, + empty_world_launch, + description_launch_py, + urdf_spawner_node, + ]) diff --git a/package.xml b/package.xml index 298e14a..42793b2 100644 --- a/package.xml +++ b/package.xml @@ -1,5 +1,5 @@ - + urdf_sim_tutorial 0.5.1 The urdf_sim_tutorial package @@ -10,17 +10,20 @@ BSD - catkin - controller_manager - diff_drive_controller - gazebo_ros - gazebo_ros_control - joint_state_controller - position_controllers - robot_state_publisher - rqt_robot_steering - rviz - urdf_tutorial - xacro + ament_cmake + controller_manager + diff_drive_controller + gazebo_ros + gazebo_ros_control + joint_state_controller + position_controllers + robot_state_publisher + rqt_robot_steering + rviz2 + urdf_tutorial + xacro + + ament_cmake + diff --git a/rviz/odom_urdf.rviz b/rviz/odom_urdf.rviz new file mode 100644 index 0000000..7bd01d8 --- /dev/null +++ b/rviz/odom_urdf.rviz @@ -0,0 +1,35 @@ +Panels: + - Class: rviz_common/Displays + Name: Displays + - Class: rviz_common/Views + Name: Views +Visualization Manager: + Displays: + - Class: rviz_default_plugins/Grid + Name: Grid + Value: true + - Alpha: 0.8 + Class: rviz_default_plugins/RobotModel + Description Topic: + Value: /robot_description + Name: RobotModel + Value: true + - Class: rviz_default_plugins/TF + Name: TF + Value: true + Global Options: + Fixed Frame: odom + Tools: + - Class: rviz_default_plugins/MoveCamera + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 1.7 + Name: Current View + Pitch: 0.33 + Value: Orbit (rviz) + Yaw: 5.5 +Window Geometry: + Height: 800 + Width: 1200 diff --git a/setup.cfg b/setup.cfg new file mode 100644 index 0000000..3e8bd8f --- /dev/null +++ b/setup.cfg @@ -0,0 +1,2 @@ +[flake8] +max_line_length=120 diff --git a/urdf/09-publishjoints.urdf.xacro b/urdf/09-publishjoints.urdf.xacro index 13e1f7a..98cf16b 100644 --- a/urdf/09-publishjoints.urdf.xacro +++ b/urdf/09-publishjoints.urdf.xacro @@ -7,7 +7,6 @@ - @@ -24,7 +23,7 @@ - + @@ -235,10 +234,16 @@ - + + + gazebo_ros2_control/GazeboSystem + + + + - - / + + $(find urdf_sim_tutorial)/config/joints.yaml diff --git a/urdf/09a-minimal.urdf.xacro b/urdf/09a-minimal.urdf.xacro new file mode 100644 index 0000000..35c6c65 --- /dev/null +++ b/urdf/09a-minimal.urdf.xacro @@ -0,0 +1,250 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + gazebo_ros2_control/GazeboSystem + + + + + + + $(find urdf_sim_tutorial)/config/09a-minimal.yaml + + + + diff --git a/urdf/10-firsttransmission.urdf.xacro b/urdf/10-firsttransmission.urdf.xacro index 3a4c225..d933a63 100644 --- a/urdf/10-firsttransmission.urdf.xacro +++ b/urdf/10-firsttransmission.urdf.xacro @@ -7,7 +7,6 @@ - @@ -24,7 +23,7 @@ - + @@ -213,18 +212,6 @@ - - - transmission_interface/SimpleTransmission - - 1 - - - PositionJointInterface - - - @@ -247,10 +234,21 @@ - + + + gazebo_ros2_control/GazeboSystem + + + + + + + + + - - / + + $(find urdf_sim_tutorial)/config/head.yaml diff --git a/urdf/11-limittransmission.urdf.xacro b/urdf/11-limittransmission.urdf.xacro index dcd8118..753f6f4 100644 --- a/urdf/11-limittransmission.urdf.xacro +++ b/urdf/11-limittransmission.urdf.xacro @@ -7,7 +7,6 @@ - @@ -24,7 +23,7 @@ - + @@ -214,18 +213,6 @@ - - - transmission_interface/SimpleTransmission - - 1 - - - PositionJointInterface - - - @@ -248,10 +235,21 @@ - + + + gazebo_ros2_control/GazeboSystem + + + + + + + + + - - / + + $(find urdf_sim_tutorial)/config/head.yaml diff --git a/urdf/12-gripper.urdf.xacro b/urdf/12-gripper.urdf.xacro index 869fec0..b0bf341 100644 --- a/urdf/12-gripper.urdf.xacro +++ b/urdf/12-gripper.urdf.xacro @@ -1,5 +1,5 @@ - + @@ -7,7 +7,6 @@ - @@ -24,7 +23,7 @@ - + @@ -145,16 +144,6 @@ - - transmission_interface/SimpleTransmission - - 1 - - - PositionJointInterface - - - @@ -180,15 +169,6 @@ - - transmission_interface/SimpleTransmission - - 1 - - - PositionJointInterface - - @@ -238,18 +218,6 @@ - - - transmission_interface/SimpleTransmission - - 1 - - - PositionJointInterface - - - @@ -272,10 +240,39 @@ - + + + gazebo_ros2_control/GazeboSystem + + + + + + + + + + + + + + + + + + + + + + + + + + + - - / + + $(find urdf_sim_tutorial)/config/gripper.yaml diff --git a/urdf/12a-mimic-gripper.urdf.xacro b/urdf/12a-mimic-gripper.urdf.xacro new file mode 100644 index 0000000..12b6d28 --- /dev/null +++ b/urdf/12a-mimic-gripper.urdf.xacro @@ -0,0 +1,286 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + gazebo_ros2_control/GazeboSystem + + + + + + + + + + + + + + + + + + + + + + + + + left_gripper_joint + 1 + + + + + + $(find urdf_sim_tutorial)/config/mimic-gripper.yaml + + + + diff --git a/urdf/13-diffdrive.urdf.xacro b/urdf/13-diffdrive.urdf.xacro index 9d1f8ef..91dc1c1 100644 --- a/urdf/13-diffdrive.urdf.xacro +++ b/urdf/13-diffdrive.urdf.xacro @@ -1,5 +1,5 @@ - + @@ -7,7 +7,6 @@ - @@ -24,7 +23,7 @@ - + @@ -67,29 +66,6 @@ - - - - - - - - Gazebo/Grey - - - - - transmission_interface/SimpleTransmission - - 1 - - - VelocityJointInterface - - - @@ -167,18 +143,9 @@ - - transmission_interface/SimpleTransmission - - 1 - - - PositionJointInterface - - - - + + @@ -202,15 +169,6 @@ - - transmission_interface/SimpleTransmission - - 1 - - - PositionJointInterface - - @@ -233,8 +191,12 @@ - - + + + + + + @@ -260,18 +222,6 @@ - - - transmission_interface/SimpleTransmission - - 1 - - - PositionJointInterface - - - @@ -294,10 +244,61 @@ - + + + gazebo_ros2_control/GazeboSystem + + + + + + + + + + + + + + + + + + + + + + + + + left_gripper_joint + 1 + + + + + + + + + + + + + + + + + + + + + + + - - / + + $(find urdf_sim_tutorial)/config/diffdrive.yaml